From 77cae9ffc34508fb01df9b2eee98a30e2531b86d Mon Sep 17 00:00:00 2001 From: sambas Date: Thu, 28 Mar 2013 18:20:50 +0200 Subject: [PATCH 01/35] MagBaro Extension board module OSD update OSD output module for FC Sonar update Flight mode fixes + poi --- flight/Modules/Altitude/altitude.c | 64 +- flight/Modules/Altitude/revolution/altitude.c | 52 +- flight/Modules/Extensions/MagBaro/magbaro.c | 40 +- .../Modules/ManualControl/inc/manualcontrol.h | 15 +- flight/Modules/Osd/OsdHk/OsdHk.c | 315 ++++++ flight/Modules/Osd/OsdHk/inc/OsdHk.h | 41 + flight/Modules/Osd/osdgen/inc/osdgen.h | 1 + flight/Modules/Osd/osdgen/osdgen.c | 45 +- flight/PiOS/Boards/STM32103CB_CC_Rev1.h | 4 + flight/PiOS/Boards/STM32F4xx_OSD.h | 26 +- flight/PiOS/Boards/STM32F4xx_RevoMini.h | 2 + flight/PiOS/Boards/STM32F4xx_Revolution.h | 9 +- flight/PiOS/Common/pios_hcsr04.c | 322 +++--- flight/PiOS/Common/pios_video.c | 463 ++++++--- flight/PiOS/STM32F10x/pios_tim.c | 2 +- .../STM32F4xx/Source/osd/system_stm32f4xx.c | 919 +++++++++--------- flight/PiOS/inc/pios_hcsr04.h | 1 - flight/PiOS/inc/pios_hcsr04_priv.h | 55 ++ flight/PiOS/inc/pios_video.h | 19 +- flight/Project/gdb/osd | 4 + .../targets/CopterControl/System/pios_board.c | 41 + flight/targets/OSD/System/inc/pios_config.h | 2 +- flight/targets/OSD/System/pios_board.c | 46 +- flight/targets/RevoMini/Makefile | 3 +- flight/targets/RevoMini/System/pios_board.c | 14 +- flight/targets/Revolution/System/pios_board.c | 21 + .../coptercontrol/board_hw_defs.c | 120 +++ .../targets/board_hw_defs/osd/board_hw_defs.c | 195 +++- .../board_hw_defs/revolution/board_hw_defs.c | 156 ++- .../board_hw_defs/revomini/board_hw_defs.c | 85 ++ make/boards/osd/board-info.mk | 4 +- shared/uavobjectdefinition/flightstatus.xml | 2 +- shared/uavobjectdefinition/hwsettings.xml | 14 +- .../manualcontrolsettings.xml | 2 +- shared/uavobjectdefinition/osdsettings.xml | 3 + shared/uavobjectdefinition/taskinfo.xml | 6 + 36 files changed, 2230 insertions(+), 883 deletions(-) create mode 100644 flight/Modules/Osd/OsdHk/OsdHk.c create mode 100644 flight/Modules/Osd/OsdHk/inc/OsdHk.h create mode 100644 flight/PiOS/inc/pios_hcsr04_priv.h create mode 100644 flight/Project/gdb/osd diff --git a/flight/Modules/Altitude/altitude.c b/flight/Modules/Altitude/altitude.c index 4e11848e7..21295c717 100644 --- a/flight/Modules/Altitude/altitude.c +++ b/flight/Modules/Altitude/altitude.c @@ -39,7 +39,9 @@ #include "openpilot.h" #include "hwsettings.h" #include "altitude.h" +#if defined(PIOS_INCLUDE_BMP085) #include "baroaltitude.h" // object that will be updated by the module +#endif #if defined(PIOS_INCLUDE_HCSR04) #include "sonaraltitude.h" // object that will be updated by the module #endif @@ -55,12 +57,15 @@ static xTaskHandle taskHandle; // down sampling variables +#if defined(PIOS_INCLUDE_BMP085) #define alt_ds_size 4 static int32_t alt_ds_temp = 0; static int32_t alt_ds_pres = 0; static int alt_ds_count = 0; +#endif static bool altitudeEnabled; +static uint8_t hwsettings_rcvrport;; // Private functions static void altitudeTask(void *parameters); @@ -73,9 +78,11 @@ int32_t AltitudeStart() { if (altitudeEnabled) { +#if defined(PIOS_INCLUDE_BMP085) BaroAltitudeInitialize(); +#endif #if defined(PIOS_INCLUDE_HCSR04) - SonarAltitudeInitialze(); + SonarAltitudeInitialize(); #endif // Start main task @@ -105,11 +112,13 @@ int32_t AltitudeInitialize() } #endif +#if defined(PIOS_INCLUDE_BMP085) // init down-sampling data alt_ds_temp = 0; alt_ds_pres = 0; alt_ds_count = 0; - +#endif + HwSettingsCC_RcvrPortGet(&hwsettings_rcvrport); return 0; } MODULE_INITCALL(AltitudeInitialize, AltitudeStart) @@ -118,46 +127,52 @@ MODULE_INITCALL(AltitudeInitialize, AltitudeStart) */ static void altitudeTask(void *parameters) { - BaroAltitudeData data; portTickType lastSysTime; #if defined(PIOS_INCLUDE_HCSR04) SonarAltitudeData sonardata; int32_t value=0,timeout=5; float coeff=0.25,height_out=0,height_in=0; - PIOS_HCSR04_Init(); - PIOS_HCSR04_Trigger(); + if(hwsettings_rcvrport==HWSETTINGS_CC_RCVRPORT_DISABLED) { + PIOS_HCSR04_Trigger(); + } #endif +#if defined(PIOS_INCLUDE_BMP085) + BaroAltitudeData data; PIOS_BMP085_Init(); +#endif // Main task loop lastSysTime = xTaskGetTickCount(); while (1) { #if defined(PIOS_INCLUDE_HCSR04) - // Compute the current altitude (all pressures in kPa) - if(PIOS_HCSR04_Completed()) - { - value = PIOS_HCSR04_Get(); - if((value>100) && (value < 15000)) //from 3.4cm to 5.1m + // Compute the current altitude + if(hwsettings_rcvrport==HWSETTINGS_CC_RCVRPORT_DISABLED) { + if(PIOS_HCSR04_Completed()) { - height_in = value*0.00034; - height_out = (height_out * (1 - coeff)) + (height_in * coeff); - sonardata.Altitude = height_out; // m/us + value = PIOS_HCSR04_Get(); + if((value>100) && (value < 15000)) //from 3.4cm to 5.1m + { + height_in = value*0.00034f/2.0f; + height_out = (height_out * (1 - coeff)) + (height_in * coeff); + sonardata.Altitude = height_out; // m/us + } + + // Update the AltitudeActual UAVObject + SonarAltitudeSet(&sonardata); + timeout=5; + PIOS_HCSR04_Trigger(); + } + if(!(timeout--)) + { + //retrigger + timeout=5; + PIOS_HCSR04_Trigger(); } - - // Update the AltitudeActual UAVObject - SonarAltitudeSet(&sonardata); - timeout=5; - PIOS_HCSR04_Trigger(); - } - if(timeout--) - { - //retrigger - timeout=5; - PIOS_HCSR04_Trigger(); } #endif +#if defined(PIOS_INCLUDE_BMP085) // Update the temperature data PIOS_BMP085_StartADC(TemperatureConv); #ifdef PIOS_BMP085_HAS_GPIOS @@ -196,6 +211,7 @@ static void altitudeTask(void *parameters) // Update the AltitudeActual UAVObject BaroAltitudeSet(&data); } +#endif // Delay until it is time to read the next sample vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD / portTICK_RATE_MS); diff --git a/flight/Modules/Altitude/revolution/altitude.c b/flight/Modules/Altitude/revolution/altitude.c index 54b241408..bd59e5baa 100644 --- a/flight/Modules/Altitude/revolution/altitude.c +++ b/flight/Modules/Altitude/revolution/altitude.c @@ -61,10 +61,6 @@ static void altitudeTask(void *parameters); */ int32_t AltitudeStart() { -#if defined(PIOS_INCLUDE_HCSR04) - SonarAltitudeInitialze(); -#endif - // Start main task xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle); @@ -79,7 +75,9 @@ int32_t AltitudeStart() int32_t AltitudeInitialize() { BaroAltitudeInitialize(); - +#if defined(PIOS_INCLUDE_HCSR04) + SonarAltitudeInitialize(); +#endif return 0; } MODULE_INITCALL(AltitudeInitialize, AltitudeStart) @@ -92,9 +90,8 @@ static void altitudeTask(void *parameters) #if defined(PIOS_INCLUDE_HCSR04) SonarAltitudeData sonardata; - int32_t value=0,timeout=5; + int32_t value=0,timeout=10,sample_rate=0; float coeff=0.25,height_out=0,height_in=0; - PIOS_HCSR04_Init(); PIOS_HCSR04_Trigger(); #endif @@ -111,27 +108,32 @@ static void altitudeTask(void *parameters) while (1) { #if defined(PIOS_INCLUDE_HCSR04) - // Compute the current altitude (all pressures in kPa) - if(PIOS_HCSR04_Completed()) + // Compute the current altitude + // depends on baro samplerate + if(!(sample_rate--)) { - value = PIOS_HCSR04_Get(); - if((value>100) && (value < 15000)) //from 3.4cm to 5.1m + if(PIOS_HCSR04_Completed()) { - height_in = value*0.00034; - height_out = (height_out * (1 - coeff)) + (height_in * coeff); - sonardata.Altitude = height_out; // m/us + value = PIOS_HCSR04_Get(); + if((value>100) && (value < 15000)) //from 3.4cm to 5.1m + { + height_in = value*0.00034f/2.0f; + height_out = (height_out * (1 - coeff)) + (height_in * coeff); + sonardata.Altitude = height_out; // m/us + } + + // Update the SonarAltitude UAVObject + SonarAltitudeSet(&sonardata); + timeout=10; + PIOS_HCSR04_Trigger(); } - - // Update the AltitudeActual UAVObject - SonarAltitudeSet(&sonardata); - timeout=5; - PIOS_HCSR04_Trigger(); - } - if(timeout--) - { - //retrigger - timeout=5; - PIOS_HCSR04_Trigger(); + if(!(timeout--)) + { + //retrigger + timeout=10; + PIOS_HCSR04_Trigger(); + } + sample_rate=25; } #endif float temp, press; diff --git a/flight/Modules/Extensions/MagBaro/magbaro.c b/flight/Modules/Extensions/MagBaro/magbaro.c index ab02a902f..99df558fe 100644 --- a/flight/Modules/Extensions/MagBaro/magbaro.c +++ b/flight/Modules/Extensions/MagBaro/magbaro.c @@ -43,9 +43,9 @@ #include "magnetometer.h" // Private constants -#define STACK_SIZE_BYTES 620 +#define STACK_SIZE_BYTES 600 #define TASK_PRIORITY (tskIDLE_PRIORITY+1) -#define UPDATE_PERIOD 50 +#define UPDATE_PERIOD 100 // Private types @@ -53,14 +53,20 @@ static xTaskHandle taskHandle; // down sampling variables +static bool magbaroEnabled; + +#if defined(PIOS_INCLUDE_BMP085) #define alt_ds_size 4 static int32_t alt_ds_temp = 0; static int32_t alt_ds_pres = 0; static int alt_ds_count = 0; +#endif + +#if defined(PIOS_INCLUDE_HMC5883) int32_t mag_test; -static bool magbaroEnabled; static float mag_bias[3] = {0,0,0}; static float mag_scale[3] = {1,1,1}; +#endif // Private functions static void magbaroTask(void *parameters); @@ -75,7 +81,7 @@ int32_t MagBaroStart() if (magbaroEnabled) { // Start main task xTaskCreate(magbaroTask, (signed char *)"MagBaro", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); - //TaskMonitorAdd(TASKINFO_RUNNING_MAGBARO, taskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_MAGBARO, taskHandle); return 0; } return -1; @@ -102,13 +108,18 @@ int32_t MagBaroInitialize() if(magbaroEnabled) { +#if defined(PIOS_INCLUDE_HMC5883) MagnetometerInitialize(); +#endif + +#if defined(PIOS_INCLUDE_BMP085) BaroAltitudeInitialize(); // init down-sampling data alt_ds_temp = 0; alt_ds_pres = 0; alt_ds_count = 0; +#endif } return 0; } @@ -116,7 +127,7 @@ MODULE_INITCALL(MagBaroInitialize, MagBaroStart) /** * Module thread, should not return. */ - +#if defined(PIOS_INCLUDE_HMC5883) static const struct pios_hmc5883_cfg pios_hmc5883_cfg = { #ifdef PIOS_HMC5883_HAS_GPIOS .exti_cfg = 0, @@ -127,27 +138,25 @@ static const struct pios_hmc5883_cfg pios_hmc5883_cfg = { .Mode = PIOS_HMC5883_MODE_CONTINUOUS, }; +#endif static void magbaroTask(void *parameters) { - BaroAltitudeData data; portTickType lastSysTime; #if defined(PIOS_INCLUDE_BMP085) + BaroAltitudeData data; PIOS_BMP085_Init(); #endif -#if defined(PIOS_INCLUDE_HMC5883) - PIOS_HMC5883_Init(&pios_hmc5883_cfg); -#endif #if defined(PIOS_INCLUDE_HMC5883) - //mag_test = PIOS_HMC5883_Test(); -#else - mag_test = 0; + MagnetometerData mag; + PIOS_HMC5883_Init(&pios_hmc5883_cfg); + uint32_t mag_update_time = PIOS_DELAY_GetRaw(); #endif + // Main task loop lastSysTime = xTaskGetTickCount(); - uint32_t mag_update_time = PIOS_DELAY_GetRaw(); while (1) { #if defined(PIOS_INCLUDE_BMP085) @@ -160,7 +169,7 @@ static void magbaroTask(void *parameters) #endif PIOS_BMP085_ReadADC(); alt_ds_temp += PIOS_BMP085_GetTemperature(); - + // Update the pressure data PIOS_BMP085_StartADC(PressureConv); #ifdef PIOS_BMP085_HAS_GPIOS @@ -170,7 +179,7 @@ static void magbaroTask(void *parameters) #endif PIOS_BMP085_ReadADC(); alt_ds_pres += PIOS_BMP085_GetPressure(); - + if (++alt_ds_count >= alt_ds_size) { alt_ds_count = 0; @@ -192,7 +201,6 @@ static void magbaroTask(void *parameters) #endif #if defined(PIOS_INCLUDE_HMC5883) - MagnetometerData mag; if (PIOS_HMC5883_NewDataAvailable() || PIOS_DELAY_DiffuS(mag_update_time) > 100000) { int16_t values[3]; PIOS_HMC5883_ReadMag(values); diff --git a/flight/Modules/ManualControl/inc/manualcontrol.h b/flight/Modules/ManualControl/inc/manualcontrol.h index 4977fad2d..7b841a035 100644 --- a/flight/Modules/ManualControl/inc/manualcontrol.h +++ b/flight/Modules/ManualControl/inc/manualcontrol.h @@ -42,9 +42,12 @@ typedef enum {FLIGHTMODE_UNDEFINED = 0, FLIGHTMODE_MANUAL = 1, FLIGHTMODE_STABIL (x == FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) ? FLIGHTMODE_GUIDANCE : \ - (x == FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE) ? FLIGHTMODE_GUIDANCE : \ (x == FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) ? FLIGHTMODE_GUIDANCE : \ - (x == FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE) ? FLIGHTMODE_TUNING : FLIGHTMODE_UNDEFINED \ + (x == FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE) ? FLIGHTMODE_GUIDANCE : \ + (x == FLIGHTSTATUS_FLIGHTMODE_LAND) ? FLIGHTMODE_GUIDANCE : \ + (x == FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE) ? FLIGHTMODE_TUNING : \ + (x == FLIGHTSTATUS_FLIGHTMODE_POI) ? FLIGHTMODE_GUIDANCE : \ + FLIGHTMODE_UNDEFINED \ ) int32_t ManualControlInitialize(); @@ -105,8 +108,14 @@ int32_t ManualControlInitialize(); ( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED1) && \ ( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED2) && \ ( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) && \ +( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ALTITUDEHOLD == (int) FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD) && \ ( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL == (int) FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) && \ -( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD == (int) FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) \ +( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD == (int) FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) && \ +( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_PATHPLANNER == (int) FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER) && \ +( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_RETURNTOBASE == (int) FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE) && \ +( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_LAND == (int) FLIGHTSTATUS_FLIGHTMODE_LAND) && \ +( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_AUTOTUNE == (int) FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE) && \ +( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POI == (int) FLIGHTSTATUS_FLIGHTMODE_POI) \ ) #define assumptions_channelcount ( \ diff --git a/flight/Modules/Osd/OsdHk/OsdHk.c b/flight/Modules/Osd/OsdHk/OsdHk.c new file mode 100644 index 000000000..e81268d68 --- /dev/null +++ b/flight/Modules/Osd/OsdHk/OsdHk.c @@ -0,0 +1,315 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup HKOSDModule HK OSD Module + * @brief On screen display support + * @{ + * + * @file OsdHk.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Interfacing with HobbyKing OSD module + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" + +#if FLIGHTBATTERYSTATE_SUPPORTED +#include "flightbatterystate.h" +#endif + +#if POSITIONACTUAL_SUPPORTED +#include "positionactual.h" +#endif + +#include "systemalarms.h" +#include "attitudeactual.h" +#include "hwsettings.h" + +static bool osdhkEnabled; + + +enum osd_hk_sync { + OSD_HK_SYNC_A = 0xCB, + OSD_HK_SYNC_B = 0x34, +}; + +enum osd_hk_pkt_type { + OSD_HK_PKT_TYPE_MISC = 0, + OSD_HK_PKT_TYPE_NAV = 1, + OSD_HK_PKT_TYPE_MAINT = 2, + OSD_HK_PKT_TYPE_ATT = 3, +}; + +enum osd_hk_control_mode { + OSD_HK_CONTROL_MODE_MANUAL = 0, + OSD_HK_CONTROL_MODE_STABILIZED = 1, + OSD_HK_CONTROL_MODE_AUTO = 2, +}; + +struct osd_hk_blob_misc { + uint8_t type; /* Always OSD_HK_PKT_TYPE_MISC */ + int16_t roll; + int16_t pitch; + //uint16_t home; /* Big Endian */ + enum osd_hk_control_mode control_mode; + uint8_t low_battery; + uint16_t current; /* Big Endian */ +} __attribute__((packed)); + +struct osd_hk_blob_att { + uint8_t type; /* Always OSD_HK_PKT_TYPE_ATT */ + int16_t roll; + int16_t pitch; + int16_t yaw; + int16_t speed; /* Big Endian */ +} __attribute__((packed)); + +struct osd_hk_blob_nav { + uint8_t type; /* Always OSD_HK_PKT_TYPE_NAV */ + uint32_t gps_lat; /* Big Endian */ + uint32_t gps_lon; /* Big Endian */ +} __attribute__((packed)); + +struct osd_hk_blob_maint { + uint8_t type; /* Always OSD_HK_PKT_TYPE_MAINT */ + uint8_t gps_speed; + uint16_t gps_alt; /* Big Endian */ + uint16_t gps_dis; /* Big Endian */ + uint8_t status; + uint8_t config; + uint8_t emerg; +} __attribute__((packed)); + +union osd_hk_pkt_blobs +{ + struct osd_hk_blob_misc misc; + struct osd_hk_blob_nav nav; + struct osd_hk_blob_maint maint; + struct osd_hk_blob_att att; +} __attribute__((packed)); + +struct osd_hk_msg { + enum osd_hk_sync sync; + enum osd_hk_pkt_type t; + union osd_hk_pkt_blobs v; +} __attribute__((packed)); + +#if 0 +#if sizeof(struct osd_hk_msg) != 11 +#error struct osd_hk_msg is the wrong size, something is wrong with the definition +#endif +#endif + +static struct osd_hk_msg osd_hk_msg_buf; + +static volatile bool newPositionActualData = false; +static volatile bool newBattData = false; +static volatile bool newAttitudeData = false; +static volatile bool newAlarmData = false; + +static uint32_t osd_hk_com_id; +static uint8_t osd_hk_msg_dropped; + +static void send_update(UAVObjEvent * ev) +{ + static enum osd_hk_sync sync = OSD_HK_SYNC_A; + + struct osd_hk_msg * msg = &osd_hk_msg_buf; + union osd_hk_pkt_blobs * blob = &(osd_hk_msg_buf.v); + + /* Make sure we have a COM port bound */ + if (!osd_hk_com_id) { + return; + } + + /* + * Set up the message + * + * NOTE: Only packet type 0 (MISC) is supported so far + */ + msg->sync = sync; + msg->t = OSD_HK_PKT_TYPE_ATT; + + if (newAttitudeData) { + float roll; + AttitudeActualRollGet(&roll); + //blob->misc.roll = (int16_t) roll; + blob->att.roll = (int16_t) roll; + + float pitch; + AttitudeActualPitchGet(&pitch); + //blob->misc.pitch = (int16_t) pitch; + blob->att.pitch = (int16_t) pitch; + + float yaw; + AttitudeActualYawGet(&yaw); + blob->att.yaw = (int16_t) yaw; + } + + /* Field not supported yet */ + //blob->misc.control_mode = 0; + + /*if (newAlarmData) { + SystemAlarmsData alarms; + SystemAlarmsGet(&alarms); + + switch (alarms.Alarm[SYSTEMALARMS_ALARM_BATTERY]) { + case SYSTEMALARMS_ALARM_UNINITIALISED: + case SYSTEMALARMS_ALARM_OK: + blob->misc.low_battery = 0; + break; + case SYSTEMALARMS_ALARM_WARNING: + case SYSTEMALARMS_ALARM_ERROR: + case SYSTEMALARMS_ALARM_CRITICAL: + default: + blob->misc.low_battery = 1; + break; + } + + newAlarmData = false; + }*/ + +#if FLIGHTBATTERYSUPPORTED + if (newBattData) { + float consumed_energy; + FlightBatteryStateConsumedEnergyGet(&consumed_energy); + + uint16_t current = (uint16_t)(consumed_energy * 10); + + /* convert to big endian */ + blob->misc.current = ( + (current & 0xFF00 >> 8) | + (current & 0x00FF << 8)); + + newBattData = false; + } +#else + //blob->misc.current = 0; +#endif + +#if POSITIONACTUAL_SUPPORTED + if (newPositionActualData) { + PositionActualData position; + PositionActualGet(&position); + + /* compute 3D distance */ + float d = sqrt( + pow(position.North,2) + + pow(position.East,2) + + pow(position.Down,2)); + /* convert from cm to dm (10ths of m) */ + uint16_t home = (uint16_t)(d / 10); + + /* convert to big endian */ + blob->misc.home = ( + (home & 0xFF00 >> 8) | + (home & 0x00FF << 8)); + + newPositionActualData = false; + } +#else + //blob->misc.home = 0; +#endif + + if (!PIOS_COM_SendBufferNonBlocking(osd_hk_com_id, (uint8_t *)&osd_hk_msg_buf, sizeof(osd_hk_msg_buf))) { + /* Sent a packet, flip to the opposite sync */ + if (sync == OSD_HK_SYNC_A) { + sync = OSD_HK_SYNC_B; + } else { + sync = OSD_HK_SYNC_A; + } + } else { + /* Failed to send this update */ + osd_hk_msg_dropped++; + } +} + +#if FLIGHTBATTERYSTATE_SUPPORTED +static void FlightBatteryStateUpdatedCb(UAVObjEvent * ev) +{ + newBattData = true; +} +#endif + +#if POSITIONACTUAL_SUPPORTED +static void PositionActualUpdatedCb(UAVObjEvent * ev) +{ + newPositionActualData = true; +} +#endif + +static void AttitudeActualUpdatedCb(UAVObjEvent * ev) +{ + newAttitudeData = true; +} + +static void SystemAlarmsUpdatedCb(UAVObjEvent * ev) +{ + newAlarmData = true; +} + +static UAVObjEvent ev; + +static int32_t OsdHkStart(void) +{ + if (osdhkEnabled) { + // Start main task + AttitudeActualConnectCallback(AttitudeActualUpdatedCb); + + SystemAlarmsConnectCallback(SystemAlarmsUpdatedCb); + +#if FLIGHTBATTERYSTATE_SUPPORTED + FlightBatteryStateConnectCallback(FlightBatteryStateUpdatedCb); +#endif + +#if POSITIONACTUAL_SUPPORTED + PositionActualConnectCallback(PositionActualUpdatedCb); +#endif + + /* Start a periodic timer to kick sending of an update */ + EventPeriodicCallbackCreate(&ev, send_update, 25 / portTICK_RATE_MS); + return 0; + } + return -1; +} + +static int32_t OsdHkInitialize(void) +{ + osd_hk_com_id = PIOS_COM_OSDHK; +#ifdef MODULE_OsdHk_BUILTIN + osdhkEnabled = 1; +#else + HwSettingsInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + HwSettingsOptionalModulesGet(optionalModules); + if (optionalModules[HWSETTINGS_OPTIONALMODULES_OSDHK] == HWSETTINGS_OPTIONALMODULES_ENABLED) { + osdhkEnabled = 1; + } else { + osdhkEnabled = 0; + } +#endif + return 0; +} +MODULE_INITCALL(OsdHkInitialize, OsdHkStart) + +/** + * @} + * @} + */ diff --git a/flight/Modules/Osd/OsdHk/inc/OsdHk.h b/flight/Modules/Osd/OsdHk/inc/OsdHk.h new file mode 100644 index 000000000..ab0b16608 --- /dev/null +++ b/flight/Modules/Osd/OsdHk/inc/OsdHk.h @@ -0,0 +1,41 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup HKOSDModule HK OSD Module + * @brief On screen display support + * @{ + * + * @file OsdHk.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Interfacing with HobbyKing OSD module + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef OSDHK_H +#define OSDHK_H + +int32_t OsdHkInitialize(void); + +#endif /* OSDHK_H */ + +/** + * @} + * @} + */ diff --git a/flight/Modules/Osd/osdgen/inc/osdgen.h b/flight/Modules/Osd/osdgen/inc/osdgen.h index ba81a5b17..d2f3aef23 100644 --- a/flight/Modules/Osd/osdgen/inc/osdgen.h +++ b/flight/Modules/Osd/osdgen/inc/osdgen.h @@ -9,6 +9,7 @@ #define OSDGEN_H_ #include "openpilot.h" +#include "pios.h" int32_t osdgenInitialize(void); diff --git a/flight/Modules/Osd/osdgen/osdgen.c b/flight/Modules/Osd/osdgen/osdgen.c index 7ec0a8f6c..b2e64e795 100644 --- a/flight/Modules/Osd/osdgen/osdgen.c +++ b/flight/Modules/Osd/osdgen/osdgen.c @@ -173,7 +173,7 @@ void drawCircle(uint16_t x0, uint16_t y0, uint16_t radius) { write_pixel_lm(x0, y0 - radius,1,1); write_pixel_lm(x0 + radius, y0,1,1); write_pixel_lm(x0 - radius, y0,1,1); - + while(x < y) { // ddF_x == 2 * x + 1; @@ -851,11 +851,11 @@ void write_line(uint8_t *buff, unsigned int x0, unsigned int y0, unsigned int x1 { if(steep) { - write_pixel(buff, y, x, mode); + write_pixel(buff, y, x, mode); } else { - write_pixel(buff, x, y, mode); + write_pixel(buff, x, y, mode); } error -= deltay; if(error < 0) @@ -2198,6 +2198,9 @@ void updateGraphics() { HomeLocationGet(&home); BaroAltitudeData baro; BaroAltitudeGet(&baro); + + PIOS_Servo_Set(0,OsdSettings.White); + PIOS_Servo_Set(1,OsdSettings.Black); switch (OsdSettings.Screen) { case 0: // Dave simple @@ -2229,7 +2232,7 @@ void updateGraphics() { else calcHomeArrow((int16_t)(gpsData.Heading)); } - break; + break; case 1: { /*drawBox(2,2,GRAPHICS_WIDTH_REAL-4,GRAPHICS_HEIGHT_REAL-4); @@ -2262,7 +2265,7 @@ void updateGraphics() { calcHomeArrow((int16_t)(gpsData.Heading)); /* Draw Attitude Indicator */ - if(OsdSettings.Attitude == OSDSETTINGS_ATTITUDE_ENABLED) + if(OsdSettings.Attitude == OSDSETTINGS_ATTITUDE_ENABLED) { drawAttitude(APPLY_HDEADBAND(OsdSettings.AttitudeSetup[OSDSETTINGS_ATTITUDESETUP_X]),APPLY_VDEADBAND(OsdSettings.AttitudeSetup[OSDSETTINGS_ATTITUDESETUP_Y]),attitude.Pitch,attitude.Roll,96); } @@ -2294,11 +2297,11 @@ void updateGraphics() { /* Print ADC voltage */ //sprintf(temp,"Rssi:%4dV",(int)(PIOS_ADC_PinGet(4)*3000/4096)); //write_string(temp, (GRAPHICS_WIDTH_REAL - 2),15, 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); - sprintf(temp,"Rssi:%4.2fV",(PIOS_ADC_PinGet(4)*3.0f/4096.0f)); + sprintf(temp,"Rssi:%4.2fV",(PIOS_ADC_PinGet(5)*3.0f/4096.0f)); write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(15), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); /* Print CPU temperature */ - sprintf(temp,"Temp:%4.2fC",(PIOS_ADC_PinGet(6)*0.29296875f-264)); + sprintf(temp,"Temp:%4.2fC",(PIOS_ADC_PinGet(3)*0.29296875f-264)); write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(25), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); /* Print ADC voltage FLIGHT*/ @@ -2306,7 +2309,7 @@ void updateGraphics() { write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(35), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); /* Print ADC voltage VIDEO*/ - sprintf(temp,"VidV:%4.2fV",(PIOS_ADC_PinGet(3)*3.0f*6.1f/4096.0f)); + sprintf(temp,"VidV:%4.2fV",(PIOS_ADC_PinGet(4)*3.0f*6.1f/4096.0f)); write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(45), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); /* Print ADC voltage RSSI */ @@ -2371,7 +2374,7 @@ void updateGraphics() { draw_artificial_horizon(-attitude.Roll,attitude.Pitch,APPLY_HDEADBAND(x),APPLY_VDEADBAND(y),size); hud_draw_vertical_scale((int)gpsData.Groundspeed, 20, +1, APPLY_HDEADBAND(GRAPHICS_RIGHT-(x-1)), APPLY_VDEADBAND(y+(size/2)), size, 5, 10, 4, 7, 10, 100, HUD_VSCALE_FLAG_NO_NEGATIVE); - if(1) + if(OsdSettings.AltitudeSource == OSDSETTINGS_ALTITUDESOURCE_BARO) { hud_draw_vertical_scale((int)baro.Altitude, 50, -1, APPLY_HDEADBAND((x+size+1)), APPLY_VDEADBAND(y+(size/2)), size, 10, 20, 4, 7, 10, 500, 0); @@ -2389,10 +2392,21 @@ void updateGraphics() { lamas(); } break; - default: - write_vline_lm( APPLY_HDEADBAND(GRAPHICS_RIGHT/2),APPLY_VDEADBAND(0),APPLY_VDEADBAND(GRAPHICS_BOTTOM),1,1); - write_hline_lm( APPLY_HDEADBAND(0),APPLY_HDEADBAND(GRAPHICS_RIGHT),APPLY_VDEADBAND(GRAPHICS_BOTTOM/2),1,1); + case 4: + case 5: + case 6: + { + int image=OsdSettings.Screen-4; + struct splashEntry splash_info; + splash_info = splash[image]; + + copyimage(APPLY_HDEADBAND(GRAPHICS_RIGHT/2-(splash_info.width)/2), APPLY_VDEADBAND(GRAPHICS_BOTTOM/2-(splash_info.height)/2),image); + } break; + default: + write_vline_lm( APPLY_HDEADBAND(GRAPHICS_RIGHT/2),APPLY_VDEADBAND(0),APPLY_VDEADBAND(GRAPHICS_BOTTOM),1,1); + write_hline_lm( APPLY_HDEADBAND(0),APPLY_HDEADBAND(GRAPHICS_RIGHT),APPLY_VDEADBAND(GRAPHICS_BOTTOM/2),1,1); + break; } // Must mask out last half-word because SPI keeps clocking it out otherwise @@ -2420,7 +2434,7 @@ int32_t osdgenStart(void) // Start gps task vSemaphoreCreateBinary( osdSemaphore); xTaskCreate(osdgenTask, (signed char *)"OSDGEN", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &osdgenTaskHandle); - //TaskMonitorAdd(TASKINFO_RUNNING_GPS, osdgenTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_OSDGEN, osdgenTaskHandle); return 0; } @@ -2460,6 +2474,11 @@ static void osdgenTask(void *parameters) //portTickType lastSysTime; // Loop forever //lastSysTime = xTaskGetTickCount(); + OsdSettingsData OsdSettings; + OsdSettingsGet (&OsdSettings); + + PIOS_Servo_Set(0,OsdSettings.White); + PIOS_Servo_Set(1,OsdSettings.Black); // intro for(int i=0; i<63; i++) diff --git a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h index f5ba3b067..caa3683e4 100644 --- a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h @@ -156,6 +156,10 @@ extern uint32_t pios_com_debug_id; #define PIOS_COM_DEBUG (pios_com_debug_id) #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ +extern uint32_t pios_com_hkosd_id; +#define PIOS_COM_OSDHK (pios_com_hkosd_id) + + //------------------------- // ADC // PIOS_ADC_PinGet(0) = Gyro Z diff --git a/flight/PiOS/Boards/STM32F4xx_OSD.h b/flight/PiOS/Boards/STM32F4xx_OSD.h index 5628571a0..2126acb8d 100644 --- a/flight/PiOS/Boards/STM32F4xx_OSD.h +++ b/flight/PiOS/Boards/STM32F4xx_OSD.h @@ -76,7 +76,7 @@ TIM4 | STOPWATCH | //#define PIOS_PERIPHERAL_CLOCK //#define PIOS_PERIPHERAL_CLOCK -#define PIOS_SYSCLK 108000000 +#define PIOS_SYSCLK 168000000 // Peripherals that belongs to APB1 are: // DAC |PWR |CAN1,2 // I2C1,2,3 |UART4,5 |USART3,2 @@ -106,12 +106,6 @@ TIM4 | STOPWATCH | #define TELEM_QUEUE_SIZE 20 #define PIOS_TELEM_STACK_SIZE 624 -// ***************************************************************** -// System Settings - -#define PIOS_MASTER_CLOCK 108000000ul -#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) - // ***************************************************************** // Interrupt Priorities @@ -207,12 +201,13 @@ extern uint32_t pios_com_telem_usb_id; //------------------------- // ADC -// PIOS_ADC_PinGet(0) = External voltage -// PIOS_ADC_PinGet(1) = AUX1 (PX2IO external pressure port) -// PIOS_ADC_PinGet(2) = AUX2 (Current sensor, if available) -// PIOS_ADC_PinGet(3) = AUX3 -// PIOS_ADC_PinGet(4) = VREF -// PIOS_ADC_PinGet(5) = Temperature sensor +// PIOS_ADC_PinGet(0) = Current +// PIOS_ADC_PinGet(1) = Voltage +// PIOS_ADC_PinGet(2) = Flight +// PIOS_ADC_PinGet(3) = Temperature sensor +// PIOS_ADC_PinGet(4) = Video +// PIOS_ADC_PinGet(5) = RSSI +// PIOS_ADC_PinGet(6) = VREF //------------------------- #define PIOS_DMA_PIN_CONFIG \ @@ -220,10 +215,10 @@ extern uint32_t pios_com_telem_usb_id; {GPIOC, GPIO_Pin_0, ADC_Channel_10}, \ {GPIOC, GPIO_Pin_1, ADC_Channel_11}, \ {GPIOC, GPIO_Pin_2, ADC_Channel_12}, \ +{NULL, 0, ADC_Channel_TempSensor}, /* Temperature sensor */\ {GPIOC, GPIO_Pin_3, ADC_Channel_13}, \ {GPIOA, GPIO_Pin_7, ADC_Channel_7}, \ -{NULL, 0, ADC_Channel_Vrefint}, /* Voltage reference */\ -{NULL, 0, ADC_Channel_TempSensor} /* Temperature sensor */\ +{NULL, 0, ADC_Channel_Vrefint} /* Voltage reference */\ } /* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */ @@ -232,6 +227,7 @@ extern uint32_t pios_com_telem_usb_id; #define PIOS_ADC_NUM_CHANNELS 7 #define PIOS_ADC_MAX_OVERSAMPLING 10 #define PIOS_ADC_USE_ADC2 0 +#define PIOS_ADC_USE_TEMP_SENSOR 1 // ***************************************************************** // USB diff --git a/flight/PiOS/Boards/STM32F4xx_RevoMini.h b/flight/PiOS/Boards/STM32F4xx_RevoMini.h index 0f8fb38d3..6398f4a71 100644 --- a/flight/PiOS/Boards/STM32F4xx_RevoMini.h +++ b/flight/PiOS/Boards/STM32F4xx_RevoMini.h @@ -124,11 +124,13 @@ extern uint32_t pios_com_gps_id; extern uint32_t pios_com_telem_usb_id; extern uint32_t pios_com_bridge_id; extern uint32_t pios_com_vcp_id; +extern uint32_t pios_com_hkosd_id; #define PIOS_COM_GPS (pios_com_gps_id) #define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) #define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) #define PIOS_COM_BRIDGE (pios_com_bridge_id) #define PIOS_COM_VCP (pios_com_vcp_id) +#define PIOS_COM_OSDHK (pios_com_hkosd_id) #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) extern uint32_t pios_com_debug_id; diff --git a/flight/PiOS/Boards/STM32F4xx_Revolution.h b/flight/PiOS/Boards/STM32F4xx_Revolution.h index 98b306f76..32f8ab451 100644 --- a/flight/PiOS/Boards/STM32F4xx_Revolution.h +++ b/flight/PiOS/Boards/STM32F4xx_Revolution.h @@ -95,6 +95,7 @@ TIM8 | | | | #define PIOS_WDG_ATTITUDE 0x0004 #define PIOS_WDG_MANUAL 0x0008 #define PIOS_WDG_SENSORS 0x0010 +#define PIOS_WDG_AUTOTUNE 0x0020 //------------------------ // PIOS_I2C @@ -126,6 +127,7 @@ extern uint32_t pios_com_aux_id; extern uint32_t pios_com_telem_usb_id; extern uint32_t pios_com_bridge_id; extern uint32_t pios_com_vcp_id; +extern uint32_t pios_com_hkosd_id; #define PIOS_COM_AUX (pios_com_aux_id) #define PIOS_COM_GPS (pios_com_gps_id) #define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) @@ -133,6 +135,7 @@ extern uint32_t pios_com_vcp_id; #define PIOS_COM_BRIDGE (pios_com_bridge_id) #define PIOS_COM_VCP (pios_com_vcp_id) #define PIOS_COM_DEBUG PIOS_COM_AUX +#define PIOS_COM_OSDHK (pios_com_hkosd_id) //------------------------ // TELEMETRY @@ -236,8 +239,9 @@ extern uint32_t pios_com_vcp_id; // ADC // PIOS_ADC_PinGet(0) = Current sensor // PIOS_ADC_PinGet(1) = Voltage sensor -// PIOS_ADC_PinGet(4) = VREF -// PIOS_ADC_PinGet(5) = Temperature sensor +// PIOS_ADC_PinGet(2) = VREF +// PIOS_ADC_PinGet(3) = Temperature sensor +// PIOS_ADC_PinGet(4) = Board Power //------------------------- #define PIOS_DMA_PIN_CONFIG \ { \ @@ -255,6 +259,7 @@ extern uint32_t pios_com_vcp_id; #define PIOS_ADC_MAX_OVERSAMPLING 2 #define PIOS_ADC_USE_ADC2 0 #define PIOS_ADC_VOLTAGE_SCALE 3.30/4096.0 +#define PIOS_ADC_USE_TEMP_SENSOR 1 //------------------------- // USB diff --git a/flight/PiOS/Common/pios_hcsr04.c b/flight/PiOS/Common/pios_hcsr04.c index 02177fac0..925c5a175 100644 --- a/flight/PiOS/Common/pios_hcsr04.c +++ b/flight/PiOS/Common/pios_hcsr04.c @@ -29,6 +29,7 @@ */ #include "pios.h" +#include "pios_hcsr04_priv.h" #ifdef PIOS_INCLUDE_HCSR04 @@ -37,173 +38,260 @@ #endif /* Local Variables */ +/* 100 ms timeout without updates on channels */ +const static uint32_t PWM_SUPERVISOR_TIMEOUT = 100000; -static TIM_ICInitTypeDef TIM_ICInitStructure; -static uint8_t CaptureState; -static uint16_t RiseValue; -static uint16_t FallValue; -static uint32_t CaptureValue; -static uint32_t CapCounter; +struct pios_hcsr04_dev * hcsr04_dev_loc; + +enum pios_hcsr04_dev_magic { + PIOS_HCSR04_DEV_MAGIC = 0xab3029AA, +}; + +struct pios_hcsr04_dev { + enum pios_hcsr04_dev_magic magic; + const struct pios_hcsr04_cfg * cfg; + + uint8_t CaptureState[PIOS_PWM_NUM_INPUTS]; + uint16_t RiseValue[PIOS_PWM_NUM_INPUTS]; + uint16_t FallValue[PIOS_PWM_NUM_INPUTS]; + uint32_t CaptureValue[PIOS_PWM_NUM_INPUTS]; + uint32_t CapCounter[PIOS_PWM_NUM_INPUTS]; + uint32_t us_since_update[PIOS_PWM_NUM_INPUTS]; +}; + +static bool PIOS_HCSR04_validate(struct pios_hcsr04_dev * hcsr04_dev) +{ + return (hcsr04_dev->magic == PIOS_HCSR04_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_hcsr04_dev * PIOS_PWM_alloc(void) +{ + struct pios_hcsr04_dev * hcsr04_dev; + + hcsr04_dev = (struct pios_hcsr04_dev *)pvPortMalloc(sizeof(*hcsr04_dev)); + if (!hcsr04_dev) return(NULL); + + hcsr04_dev->magic = PIOS_HCSR04_DEV_MAGIC; + return(hcsr04_dev); +} +#else +static struct pios_hcsr04_dev pios_hcsr04_devs[PIOS_PWM_MAX_DEVS]; +static uint8_t pios_hcsr04_num_devs; +static struct pios_hcsr04_dev * PIOS_PWM_alloc(void) +{ + struct pios_hcsr04_dev * hcsr04_dev; + + if (pios_pwm_num_devs >= PIOS_PWM_MAX_DEVS) { + return (NULL); + } + + hcsr04_dev = &pios_hcsr04_devs[pios_hcsr04_num_devs++]; + hcsr04_dev->magic = PIOS_HCSR04_DEV_MAGIC; + + return (hcsr04_dev); +} +#endif + +static void PIOS_HCSR04_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +static void PIOS_HCSR04_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +const static struct pios_tim_callbacks tim_callbacks = { + .overflow = PIOS_HCSR04_tim_overflow_cb, + .edge = PIOS_HCSR04_tim_edge_cb, +}; -#define PIOS_HCSR04_TRIG_GPIO_PORT GPIOD -#define PIOS_HCSR04_TRIG_PIN GPIO_Pin_2 /** -* Initialise the HC-SR04 sensor +* Initialises all the pins */ -void PIOS_HCSR04_Init(void) +int32_t PIOS_HCSR04_Init(uint32_t * pwm_id, const struct pios_hcsr04_cfg * cfg) { - /* Init triggerpin */ - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; - GPIO_InitStructure.GPIO_Pin = PIOS_HCSR04_TRIG_PIN; - GPIO_Init(PIOS_HCSR04_TRIG_GPIO_PORT, &GPIO_InitStructure); - PIOS_HCSR04_TRIG_GPIO_PORT->BSRR = PIOS_HCSR04_TRIG_PIN; + PIOS_DEBUG_Assert(pwm_id); + PIOS_DEBUG_Assert(cfg); - /* Flush counter variables */ - CaptureState = 0; - RiseValue = 0; - FallValue = 0; - CaptureValue = 0; + struct pios_hcsr04_dev * hcsr04_dev; - /* Setup RCC */ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); + hcsr04_dev = (struct pios_hcsr04_dev *) PIOS_PWM_alloc(); + if (!hcsr04_dev) goto out_fail; - /* Enable timer interrupts */ - NVIC_InitTypeDef NVIC_InitStructure; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn; - NVIC_Init(&NVIC_InitStructure); + /* Bind the configuration to the device instance */ + hcsr04_dev->cfg = cfg; + hcsr04_dev_loc = hcsr04_dev; - /* Partial pin remap for TIM3 (PB5) */ - GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE); + for (uint8_t i = 0; i < PIOS_PWM_NUM_INPUTS; i++) { + /* Flush counter variables */ + hcsr04_dev->CaptureState[i] = 0; + hcsr04_dev->RiseValue[i] = 0; + hcsr04_dev->FallValue[i] = 0; + hcsr04_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + } - /* Configure input pins */ - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5; - GPIO_Init(GPIOB, &GPIO_InitStructure); + uint32_t tim_id; + if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, &tim_callbacks, (uint32_t)hcsr04_dev)) { + return -1; + } - /* Configure timer for input capture */ - TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; - TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; - TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; - TIM_ICInitStructure.TIM_ICFilter = 0x0; - TIM_ICInitStructure.TIM_Channel = TIM_Channel_2; - TIM_ICInit(TIM3, &TIM_ICInitStructure); + /* Configure the channels to be in capture/compare mode */ + for (uint8_t i = 0; i < cfg->num_channels; i++) { + const struct pios_tim_channel * chan = &cfg->channels[i]; - /* Configure timer clocks */ - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); - TIM_TimeBaseStructure.TIM_Period = 0xFFFF; - TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 500000) - 1; - TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_InternalClockConfig(TIM3); - TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure); + /* Configure timer for input capture */ + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); - /* Enable the Capture Compare Interrupt Request */ - //TIM_ITConfig(PIOS_PWM_CH8_TIM_PORT, PIOS_PWM_CH8_CCR, ENABLE); - TIM_ITConfig(TIM3, TIM_IT_CC2, DISABLE); + /* Enable the Capture Compare Interrupt Request */ + switch (chan->timer_chan) { + case TIM_Channel_1: + TIM_ITConfig(chan->timer, TIM_IT_CC1, ENABLE); + break; + case TIM_Channel_2: + TIM_ITConfig(chan->timer, TIM_IT_CC2, ENABLE); + break; + case TIM_Channel_3: + TIM_ITConfig(chan->timer, TIM_IT_CC3, ENABLE); + break; + case TIM_Channel_4: + TIM_ITConfig(chan->timer, TIM_IT_CC4, ENABLE); + break; + } - /* Enable timers */ - TIM_Cmd(TIM3, ENABLE); + // Need the update event for that timer to detect timeouts + TIM_ITConfig(chan->timer, TIM_IT_Update, ENABLE); - /* Setup local variable which stays in this scope */ - /* Doing this here and using a local variable saves doing it in the ISR */ - TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; - TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; - TIM_ICInitStructure.TIM_ICFilter = 0x0; + } + +#ifndef STM32F4XX + /* Enable the peripheral clock for the GPIO */ + switch ((uint32_t)hcsr04_dev->cfg->trigger.gpio) { + case (uint32_t) GPIOA: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); + break; + case (uint32_t) GPIOB: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + break; + case (uint32_t) GPIOC: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); + break; + default: + PIOS_Assert(0); + break; + } +#endif + GPIO_Init(hcsr04_dev->cfg->trigger.gpio, &hcsr04_dev->cfg->trigger.init); + + *pwm_id = (uint32_t) hcsr04_dev; + + return (0); + +out_fail: + return (-1); +} + +void PIOS_HCSR04_Trigger(void) +{ + GPIO_SetBits(hcsr04_dev_loc->cfg->trigger.gpio,hcsr04_dev_loc->cfg->trigger.init.GPIO_Pin); + PIOS_DELAY_WaituS(15); + GPIO_ResetBits(hcsr04_dev_loc->cfg->trigger.gpio,hcsr04_dev_loc->cfg->trigger.init.GPIO_Pin); } /** -* Get the value of an sonar timer -* \output >0 timer value +* Get the value of an input channel +* \param[in] Channel Number of the channel desired +* \output -1 Channel not available +* \output >0 Channel value */ int32_t PIOS_HCSR04_Get(void) { - return CaptureValue; + return hcsr04_dev_loc->CaptureValue[0]; } -/** -* Get the value of an sonar timer -* \output >0 timer value -*/ int32_t PIOS_HCSR04_Completed(void) { - return CapCounter; -} -/** -* Trigger sonar sensor -*/ -void PIOS_HCSR04_Trigger(void) -{ - CapCounter=0; - PIOS_HCSR04_TRIG_GPIO_PORT->BSRR = PIOS_HCSR04_TRIG_PIN; - PIOS_DELAY_WaituS(15); - PIOS_HCSR04_TRIG_GPIO_PORT->BRR = PIOS_HCSR04_TRIG_PIN; - TIM_ITConfig(TIM3, TIM_IT_CC2, ENABLE); + return hcsr04_dev_loc->CapCounter[0]; } - -/** -* Handle TIM3 global interrupt request -*/ -//void PIOS_PWM_irq_handler(TIM_TypeDef * timer) -void TIM3_IRQHandler(void) +static void PIOS_HCSR04_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) { - /* Zero value always will be changed but this prevents compiler warning */ - int32_t i = 0; + struct pios_hcsr04_dev * hcsr04_dev = (struct pios_hcsr04_dev *)context; - /* Do this as it's more efficient */ - if (TIM_GetITStatus(TIM3, TIM_IT_CC2) == SET) { - i = 7; - if (CaptureState == 0) { - RiseValue = TIM_GetCapture2(TIM3); - } else { - FallValue = TIM_GetCapture2(TIM3); - } + if (!PIOS_HCSR04_validate(hcsr04_dev)) { + /* Invalid device specified */ + return; } - /* Clear TIM3 Capture compare interrupt pending bit */ - TIM_ClearITPendingBit(TIM3, TIM_IT_CC2); + if (channel >= hcsr04_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + hcsr04_dev->us_since_update[channel] += count; + if(hcsr04_dev->us_since_update[channel] >= PWM_SUPERVISOR_TIMEOUT) { + hcsr04_dev->CaptureState[channel] = 0; + hcsr04_dev->RiseValue[channel] = 0; + hcsr04_dev->FallValue[channel] = 0; + hcsr04_dev->CaptureValue[channel] = PIOS_RCVR_TIMEOUT; + hcsr04_dev->us_since_update[channel] = 0; + } + + return; +} + +static void PIOS_HCSR04_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +{ + /* Recover our device context */ + struct pios_hcsr04_dev * hcsr04_dev = (struct pios_hcsr04_dev *)context; + + if (!PIOS_HCSR04_validate(hcsr04_dev)) { + /* Invalid device specified */ + return; + } + + if (chan_idx >= hcsr04_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + + const struct pios_tim_channel * chan = &hcsr04_dev->cfg->channels[chan_idx]; + + if (hcsr04_dev->CaptureState[chan_idx] == 0) { + hcsr04_dev->RiseValue[chan_idx] = count; + hcsr04_dev->us_since_update[chan_idx] = 0; + } else { + hcsr04_dev->FallValue[chan_idx] = count; + } + + // flip state machine and capture value here /* Simple rise or fall state machine */ - if (CaptureState == 0) { + TIM_ICInitTypeDef TIM_ICInitStructure = hcsr04_dev->cfg->tim_ic_init; + if (hcsr04_dev->CaptureState[chan_idx] == 0) { /* Switch states */ - CaptureState = 1; + hcsr04_dev->CaptureState[chan_idx] = 1; /* Switch polarity of input capture */ TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; - TIM_ICInitStructure.TIM_Channel = TIM_Channel_2; - TIM_ICInit(TIM3, &TIM_ICInitStructure); - + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); } else { /* Capture computation */ - if (FallValue > RiseValue) { - CaptureValue = (FallValue - RiseValue); + if (hcsr04_dev->FallValue[chan_idx] > hcsr04_dev->RiseValue[chan_idx]) { + hcsr04_dev->CaptureValue[chan_idx] = (hcsr04_dev->FallValue[chan_idx] - hcsr04_dev->RiseValue[chan_idx]); } else { - CaptureValue = ((0xFFFF - RiseValue) + FallValue); + hcsr04_dev->CaptureValue[chan_idx] = ((chan->timer->ARR - hcsr04_dev->RiseValue[chan_idx]) + hcsr04_dev->FallValue[chan_idx]); } /* Switch states */ - CaptureState = 0; + hcsr04_dev->CaptureState[chan_idx] = 0; /* Increase supervisor counter */ - CapCounter++; - TIM_ITConfig(TIM3, TIM_IT_CC2, DISABLE); + hcsr04_dev->CapCounter[chan_idx]++; /* Switch polarity of input capture */ TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; - TIM_ICInitStructure.TIM_Channel = TIM_Channel_2; - TIM_ICInit(TIM3, &TIM_ICInitStructure); - + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); } + } #endif /* PIOS_INCLUDE_HCSR04 */ diff --git a/flight/PiOS/Common/pios_video.c b/flight/PiOS/Common/pios_video.c index 5d7452f9d..eaf4d6cb7 100644 --- a/flight/PiOS/Common/pios_video.c +++ b/flight/PiOS/Common/pios_video.c @@ -33,10 +33,18 @@ #ifdef PIOS_INCLUDE_VIDEO -extern xSemaphoreHandle osdSemaphore; +// Private methods +static void configure_hsync_timers(); +static void stop_hsync_timers(); +static void reset_hsync_timers(); +static void prepare_line(uint32_t line_num); +static void flush_spi(); +// Private variables +extern xSemaphoreHandle osdSemaphore; static const struct pios_video_cfg * dev_cfg; + // Define the buffers. // For 256x192 pixel mode: // buffer0_level/buffer0_mask becomes buffer_level; and @@ -69,6 +77,7 @@ volatile uint16_t gActiveLine = 0; volatile uint16_t gActivePixmapLine = 0; volatile uint16_t line=0; volatile uint16_t Vsync_update=0; +volatile uint16_t Hsync_update=0; static int16_t m_osdLines=0; /** @@ -78,67 +87,51 @@ static int16_t m_osdLines=0; */ void swap_buffers() { - // While we could use XOR swap this is more reliable and - // dependable and it's only called a few times per second. - // Many compliers should optimise these to EXCH instructions. - uint8_t *tmp; - SWAP_BUFFS(tmp, disp_buffer_mask, draw_buffer_mask); - SWAP_BUFFS(tmp, disp_buffer_level, draw_buffer_level); + // While we could use XOR swap this is more reliable and + // dependable and it's only called a few times per second. + // Many compliers should optimise these to EXCH instructions. + uint8_t *tmp; + SWAP_BUFFS(tmp, disp_buffer_mask, draw_buffer_mask); + SWAP_BUFFS(tmp, disp_buffer_level, draw_buffer_level); } -bool PIOS_Hsync_ISR() { - - if(dev_cfg->hsync->pin.gpio->IDR & dev_cfg->hsync->pin.init.GPIO_Pin) { - //rising - if(gLineType == LINE_TYPE_GRAPHICS) - { - // Activate new line - DMA_Cmd(dev_cfg->level.dma.tx.channel, ENABLE); - DMA_Cmd(dev_cfg->mask.dma.tx.channel, ENABLE); - } - } else { - //falling - gLineType = LINE_TYPE_UNKNOWN; // Default case - gActiveLine++; - - if ((gActiveLine >= GRAPHICS_LINE) && (gActiveLine < (GRAPHICS_LINE + GRAPHICS_HEIGHT))) { - gLineType = LINE_TYPE_GRAPHICS; - gActivePixmapLine = (gActiveLine - GRAPHICS_LINE); - line = gActivePixmapLine*GRAPHICS_WIDTH; - } - - if(gLineType == LINE_TYPE_GRAPHICS) - { - // Load new line - DMA_Cmd(dev_cfg->mask.dma.tx.channel, DISABLE); - DMA_Cmd(dev_cfg->level.dma.tx.channel, DISABLE); - DMA_MemoryTargetConfig(dev_cfg->level.dma.tx.channel,(uint32_t)&disp_buffer_level[line],DMA_Memory_0); - DMA_MemoryTargetConfig(dev_cfg->mask.dma.tx.channel,(uint32_t)&disp_buffer_mask[line],DMA_Memory_0); - DMA_SetCurrDataCounter(dev_cfg->level.dma.tx.channel,BUFFER_LINE_LENGTH); - DMA_SetCurrDataCounter(dev_cfg->mask.dma.tx.channel,BUFFER_LINE_LENGTH); - } +bool PIOS_Hsync_ISR() +{ + // On tenth line prepare data which will start clocking out on GRAPHICS_LINE+1 + if(Hsync_update==GRAPHICS_LINE) + { + prepare_line(0); + gActiveLine = 1; } - - return false; + Hsync_update++; } bool PIOS_Vsync_ISR() { static portBASE_TYPE xHigherPriorityTaskWoken; - //PIOS_LED_Toggle(LED3); - - //if(gActiveLine > 200) + xHigherPriorityTaskWoken = pdFALSE; m_osdLines = gActiveLine; + + stop_hsync_timers(); + + // Wait for previous word to clock out of each + TIM_Cmd(dev_cfg->pixel_timer.timer, ENABLE); + flush_spi(); + TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); + + gActiveLine = 0; + Hsync_update = 0; + Vsync_update++; + if(Vsync_update>=2) { - gActiveLine = 0; - Vsync_update++; - if(Vsync_update>=2) - { - swap_buffers(); - Vsync_update=0; - xHigherPriorityTaskWoken = xSemaphoreGiveFromISR(osdSemaphore, &xHigherPriorityTaskWoken); - } + // load second image buffer + swap_buffers(); + Vsync_update=0; + + // trigger redraw every second field + xHigherPriorityTaskWoken = xSemaphoreGiveFromISR(osdSemaphore, &xHigherPriorityTaskWoken); } + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); //portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); return xHigherPriorityTaskWoken == pdTRUE; @@ -148,134 +141,342 @@ uint16_t PIOS_Video_GetOSDLines(void) { return m_osdLines; } -void PIOS_Video_Init(const struct pios_video_cfg * cfg){ +/** + * Stops the pixel clock and ensures it ignores the rising edge. To be used after a + * vsync until the first line is to be displayed + */ +static void stop_hsync_timers() +{ + // This removes the slave mode configuration + TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); + TIM_InternalClockConfig(dev_cfg->pixel_timer.timer); +} +const struct pios_tim_callbacks px_callback = { + .overflow = NULL, + .edge = NULL, +}; + +#ifdef PAL +const uint32_t period = 10; +const uint32_t dc = (10 / 2); +#else +const uint32_t period = 11; +const uint32_t dc = (11 / 2); +#endif +/** + * Reset the timer and configure for next call. Keeps them synced. Ideally this won't even be needed + * since I don't think the slave mode gets lost, and this can simply be disable timer + */ +uint32_t failcount = 0; +static void reset_hsync_timers() +{ + // Stop both timers + TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); + + uint32_t tim_id; + const struct pios_tim_channel *channels = &dev_cfg->hsync_capture; + + //BUG: This is nuts this line is needed. It simply results in allocating + //all the memory but somehow leaving it out breaks the timer functionality. + // I do not see how these can be related + if (failcount == 0) { + if(PIOS_TIM_InitChannels(&tim_id, channels, 1, &px_callback, 0) < 0) + failcount++; + } + + dev_cfg->pixel_timer.timer->CNT = 0xFFFF - 100; //dc; + + // Listen to Channel1 (HSYNC) + switch(dev_cfg->hsync_capture.timer_chan) { + case TIM_Channel_1: + TIM_SelectInputTrigger(dev_cfg->pixel_timer.timer, TIM_TS_TI1FP1); + break; + case TIM_Channel_2: + TIM_SelectInputTrigger(dev_cfg->pixel_timer.timer, TIM_TS_TI2FP2); + break; + default: + PIOS_Assert(0); + } + TIM_SelectSlaveMode(dev_cfg->pixel_timer.timer, TIM_SlaveMode_Trigger); +} + + +static void configure_hsync_timers() +{ + // Stop both timers + TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); + + // This is overkill but used for consistency. No interrupts used for pixel clock + // but this function calls the GPIO_Remap + uint32_t tim_id; + const struct pios_tim_channel *channels; + + // Init the channel to output the pixel clock + channels = &dev_cfg->pixel_timer; + PIOS_TIM_InitChannels(&tim_id, channels, 1, &px_callback, 0); + + // Init the channel to capture the pulse + channels = &dev_cfg->hsync_capture; + PIOS_TIM_InitChannels(&tim_id, channels, 1, &px_callback, 0); + + // Configure the input capture channel + TIM_ICInitTypeDef TIM_ICInitStructure; + switch(dev_cfg->hsync_capture.timer_chan) { + case TIM_Channel_1: + TIM_ICInitStructure.TIM_Channel = TIM_Channel_1; + break; + case TIM_Channel_2: + TIM_ICInitStructure.TIM_Channel = TIM_Channel_2; + break; + default: + PIOS_Assert(0); + } + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; + //TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStructure.TIM_ICFilter = 0; + TIM_ICInit(dev_cfg->pixel_timer.timer, &TIM_ICInitStructure); + + // Set up the channel to output the pixel clock + switch(dev_cfg->pixel_timer.timer_chan) { + case TIM_Channel_1: + TIM_OC1Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); + TIM_OC1PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); + TIM_SetCompare1(dev_cfg->pixel_timer.timer, dc); + break; + case TIM_Channel_2: + TIM_OC2Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); + TIM_OC2PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); + TIM_SetCompare2(dev_cfg->pixel_timer.timer, dc); + break; + case TIM_Channel_3: + TIM_OC3Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); + TIM_OC3PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); + TIM_SetCompare3(dev_cfg->pixel_timer.timer, dc); + break; + case TIM_Channel_4: + TIM_OC4Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); + TIM_OC4PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); + TIM_SetCompare4(dev_cfg->pixel_timer.timer, dc); + break; + } + TIM_ARRPreloadConfig(dev_cfg->pixel_timer.timer, ENABLE); + TIM_CtrlPWMOutputs(dev_cfg->pixel_timer.timer, ENABLE); + + // This shouldn't be needed as it should come from the config struture. Something + // is clobbering that + TIM_PrescalerConfig(dev_cfg->pixel_timer.timer, 0, TIM_PSCReloadMode_Immediate); + TIM_SetAutoreload(dev_cfg->pixel_timer.timer, period); +} + +DMA_TypeDef * main_dma; +DMA_TypeDef * mask_dma; +DMA_Stream_TypeDef * main_stream; +DMA_Stream_TypeDef * mask_stream; +void PIOS_Video_Init(const struct pios_video_cfg * cfg) +{ dev_cfg = cfg; // store config before enabling interrupt - if (cfg->mask.remap) { - GPIO_PinAFConfig(cfg->mask.sclk.gpio, - __builtin_ctz(cfg->mask.sclk.init.GPIO_Pin), - cfg->mask.remap); - GPIO_PinAFConfig(cfg->mask.mosi.gpio, - __builtin_ctz(cfg->mask.mosi.init.GPIO_Pin), - cfg->mask.remap); - } - if (cfg->level.remap) - { - GPIO_PinAFConfig(cfg->level.sclk.gpio, - __builtin_ctz(cfg->level.sclk.init.GPIO_Pin), - cfg->level.remap); - GPIO_PinAFConfig(cfg->level.miso.gpio, - __builtin_ctz(cfg->level.miso.init.GPIO_Pin), - cfg->level.remap); - } + configure_hsync_timers(); - /* SPI3 MASTER MASKBUFFER */ + /* needed for HW hack */ + const GPIO_InitTypeDef initStruct = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN , + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }; + GPIO_Init(GPIOC, &initStruct); + + /* SPI3 - MASKBUFFER */ GPIO_Init(cfg->mask.sclk.gpio, (GPIO_InitTypeDef*)&(cfg->mask.sclk.init)); - GPIO_Init(cfg->mask.mosi.gpio, (GPIO_InitTypeDef*)&(cfg->mask.mosi.init)); + GPIO_Init(cfg->mask.miso.gpio, (GPIO_InitTypeDef*)&(cfg->mask.miso.init)); /* SPI1 SLAVE FRAMEBUFFER */ GPIO_Init(cfg->level.sclk.gpio, (GPIO_InitTypeDef*)&(cfg->level.sclk.init)); GPIO_Init(cfg->level.miso.gpio, (GPIO_InitTypeDef*)&(cfg->level.miso.init)); + if (cfg->mask.remap) { + GPIO_PinAFConfig(cfg->mask.sclk.gpio, + __builtin_ctz(cfg->mask.sclk.init.GPIO_Pin), + cfg->mask.remap); + GPIO_PinAFConfig(cfg->mask.miso.gpio, + __builtin_ctz(cfg->mask.miso.init.GPIO_Pin), + cfg->mask.remap); + } + if (cfg->level.remap) + { + GPIO_PinAFConfig(cfg->level.sclk.gpio, + __builtin_ctz(cfg->level.sclk.init.GPIO_Pin), + cfg->level.remap); + GPIO_PinAFConfig(cfg->level.miso.gpio, + __builtin_ctz(cfg->level.miso.init.GPIO_Pin), + cfg->level.remap); + } + /* Initialize the SPI block */ SPI_Init(cfg->level.regs, (SPI_InitTypeDef*)&(cfg->level.init)); SPI_Init(cfg->mask.regs, (SPI_InitTypeDef*)&(cfg->mask.init)); - + /* Enable SPI */ SPI_Cmd(cfg->level.regs, ENABLE); SPI_Cmd(cfg->mask.regs, ENABLE); - /* Configure DMA for SPI Tx MASTER */ + /* Configure DMA for SPI Tx SLAVE Maskbuffer */ DMA_Cmd(cfg->mask.dma.tx.channel, DISABLE); DMA_Init(cfg->mask.dma.tx.channel, (DMA_InitTypeDef*)&(cfg->mask.dma.tx.init)); - /* Configure DMA for SPI Tx SLAVE */ + /* Configure DMA for SPI Tx SLAVE Framebuffer*/ DMA_Cmd(cfg->level.dma.tx.channel, DISABLE); DMA_Init(cfg->level.dma.tx.channel, (DMA_InitTypeDef*)&(cfg->level.dma.tx.init)); - /* Trigger interrupt when for half conversions too to indicate double buffer */ - DMA_ITConfig(cfg->mask.dma.tx.channel, DMA_IT_TC, ENABLE); - /*DMA_ClearFlag(cfg->mask.dma.tx.channel,DMA_FLAG_TCIF5); - DMA_ClearITPendingBit(cfg->mask.dma.tx.channel, DMA_IT_TCIF5); - - DMA_ClearFlag(cfg->level.dma.tx.channel,DMA_FLAG_TCIF5); - DMA_ClearITPendingBit(cfg->level.dma.tx.channel, DMA_IT_TCIF5); -*/ - - /* Configure DMA interrupt */ - NVIC_Init(&cfg->level.dma.irq.init); - NVIC_Init(&cfg->mask.dma.irq.init); - - /* Enable SPI interrupts to DMA */ - SPI_I2S_DMACmd(cfg->level.regs, SPI_I2S_DMAReq_Tx, ENABLE); - SPI_I2S_DMACmd(cfg->mask.regs, SPI_I2S_DMAReq_Tx, ENABLE); - - /* Configure the Video Line interrupt */ - PIOS_EXTI_Init(cfg->hsync); - PIOS_EXTI_Init(cfg->vsync); - + DMA_ITConfig(cfg->level.dma.tx.channel, DMA_IT_TC, ENABLE); + /* Configure and clear buffers */ draw_buffer_level = buffer0_level; draw_buffer_mask = buffer0_mask; disp_buffer_level = buffer1_level; disp_buffer_mask = buffer1_mask; + memset(disp_buffer_mask, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); + memset(disp_buffer_level, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); + memset(draw_buffer_mask, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); + memset(draw_buffer_level, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); + + /* Configure DMA interrupt */ + + NVIC_Init(&cfg->level.dma.irq.init); + + /* Enable SPI interrupts to DMA */ + SPI_I2S_DMACmd(cfg->mask.regs, SPI_I2S_DMAReq_Tx, ENABLE); + SPI_I2S_DMACmd(cfg->level.regs, SPI_I2S_DMAReq_Tx, ENABLE); + + mask_dma = DMA1; + main_dma = DMA2; + main_stream = cfg->level.dma.tx.channel; + mask_stream = cfg->mask.dma.tx.channel; + /* Configure the Video Line interrupt */ + PIOS_EXTI_Init(cfg->hsync); + PIOS_EXTI_Init(cfg->vsync); + + //set levels to zero + PIOS_Servo_Set(0,0); + PIOS_Servo_Set(1,0); } - /** - * @brief Interrupt for half and full buffer transfer - * - * This interrupt handler swaps between the two halfs of the double buffer to make - * sure the ahrs uses the most recent data. Only swaps data when AHRS is idle, but - * really this is a pretense of a sanity check since the DMA engine is consantly - * running in the background. Keep an eye on the ekf_too_slow variable to make sure - * it's keeping up. + * Prepare the system to watch for a HSYNC pulse to trigger the pixel + * clock and clock out the next line */ +static void prepare_line(uint32_t line_num) +{ + if(line_numpixel_timer.timer->CNT = dc; + + DMA_ClearFlag(dev_cfg->mask.dma.tx.channel, DMA_FLAG_TCIF7 | DMA_FLAG_HTIF7 | DMA_FLAG_FEIF7 | DMA_FLAG_TEIF7); + DMA_ClearFlag(dev_cfg->level.dma.tx.channel, DMA_FLAG_FEIF5 | DMA_FLAG_TEIF5); + + // Load new line + DMA_MemoryTargetConfig(dev_cfg->level.dma.tx.channel,(uint32_t)&disp_buffer_level[buf_offset],DMA_Memory_0); + DMA_MemoryTargetConfig(dev_cfg->mask.dma.tx.channel,(uint32_t)&disp_buffer_mask[buf_offset],DMA_Memory_0); + + // Enable DMA, Slave first + DMA_SetCurrDataCounter(dev_cfg->level.dma.tx.channel, BUFFER_LINE_LENGTH); + DMA_SetCurrDataCounter(dev_cfg->mask.dma.tx.channel, BUFFER_LINE_LENGTH); + + SPI_Cmd(dev_cfg->level.regs, ENABLE); + SPI_Cmd(dev_cfg->mask.regs, ENABLE); + + /* Enable SPI interrupts to DMA */ + SPI_I2S_DMACmd(dev_cfg->mask.regs, SPI_I2S_DMAReq_Tx, ENABLE); + SPI_I2S_DMACmd(dev_cfg->level.regs, SPI_I2S_DMAReq_Tx, ENABLE); + + DMA_Cmd(dev_cfg->level.dma.tx.channel, ENABLE); + DMA_Cmd(dev_cfg->mask.dma.tx.channel, ENABLE); + } + reset_hsync_timers(); +} void PIOS_VIDEO_DMA_Handler(void); void DMA1_Stream7_IRQHandler(void) __attribute__ ((alias("PIOS_VIDEO_DMA_Handler"))); void DMA2_Stream5_IRQHandler(void) __attribute__ ((alias("PIOS_VIDEO_DMA_Handler"))); +/** + * Check both SPI for the stop sequence before disabling them + */ +static void flush_spi() +{ + bool level_empty = false; + bool mask_empty = false; + bool level_stopped = false; + bool mask_stopped = false; + + // Can't flush if clock not running + while((dev_cfg->pixel_timer.timer->CR1 & 0x0001) && ( !level_stopped | !mask_stopped )) { + level_empty |= SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_TXE) == SET; + mask_empty |= SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_TXE) == SET; + + if (level_empty && !level_stopped) { // && SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_BSY) == RESET) { + SPI_Cmd(dev_cfg->level.regs, DISABLE); + level_stopped = true; + } + + if (mask_empty && !mask_stopped) { // && SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_BSY) == RESET) { + SPI_Cmd(dev_cfg->mask.regs, DISABLE); + mask_stopped = true; + } + } + /* + uint32_t i = 0; + while(SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_TXE) == RESET && i < 30000) i++; + while(SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_TXE) == RESET && i < 30000) i++; + while(SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_BSY) == SET && i < 30000) i++; + while(SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_BSY) == SET && i < 30000) i++;*/ + SPI_Cmd(dev_cfg->mask.regs, DISABLE); + SPI_Cmd(dev_cfg->level.regs, DISABLE); +} + +/** + * @brief Interrupt for half and full buffer transfer + */ void PIOS_VIDEO_DMA_Handler(void) { - if (DMA_GetFlagStatus(DMA1_Stream7,DMA_FLAG_TCIF7)) { // transfer completed load next line - DMA_ClearFlag(DMA1_Stream7,DMA_FLAG_TCIF7); - //PIOS_LED_Off(LED2); - /*if(gLineType == LINE_TYPE_GRAPHICS) + // Handle flags from stream channel + if (DMA_GetFlagStatus(dev_cfg->level.dma.tx.channel,DMA_FLAG_TCIF5)) { // whole double buffer filled + DMA_ClearFlag(dev_cfg->level.dma.tx.channel,DMA_FLAG_TCIF5); + if(gActiveLine < GRAPHICS_HEIGHT) { - // Load new line + flush_spi(); + stop_hsync_timers(); + + dev_cfg->pixel_timer.timer->CNT = dc; + + prepare_line(gActiveLine); + } + else if(gActiveLine >= GRAPHICS_HEIGHT) + { + //last line completed + flush_spi(); + stop_hsync_timers(); + + // STOP DMA, master first DMA_Cmd(dev_cfg->mask.dma.tx.channel, DISABLE); DMA_Cmd(dev_cfg->level.dma.tx.channel, DISABLE); - DMA_MemoryTargetConfig(dev_cfg->level.dma.tx.channel,(uint32_t)&disp_buffer_level[line],DMA_Memory_0); - DMA_MemoryTargetConfig(dev_cfg->mask.dma.tx.channel,(uint32_t)&disp_buffer_mask[line],DMA_Memory_0); - //DMA_ClearFlag(dev_cfg->mask.dma.tx.channel,DMA_FLAG_TCIF5); // <-- TODO: HARDCODED - //DMA_ClearFlag(dev_cfg->level.dma.tx.channel,DMA_FLAG_TCIF5); // <-- TODO: HARDCODED - DMA_SetCurrDataCounter(dev_cfg->level.dma.tx.channel,BUFFER_LINE_LENGTH); - DMA_SetCurrDataCounter(dev_cfg->mask.dma.tx.channel,BUFFER_LINE_LENGTH); - }*/ - //PIOS_LED_Toggle(LED2); + } + gActiveLine++; } - else if (DMA_GetFlagStatus(DMA1_Stream7,DMA_FLAG_HTIF7)) { - DMA_ClearFlag(DMA1_Stream7,DMA_FLAG_HTIF7); + else if (DMA_GetFlagStatus(dev_cfg->level.dma.tx.channel,DMA_FLAG_HTIF5)) { + DMA_ClearFlag(dev_cfg->level.dma.tx.channel,DMA_FLAG_HTIF5); } else { - } - - if (DMA_GetFlagStatus(DMA2_Stream5,DMA_FLAG_TCIF5)) { // whole double buffer filled - DMA_ClearFlag(DMA2_Stream5,DMA_FLAG_TCIF5); - //PIOS_LED_Toggle(LED3); - } - else if (DMA_GetFlagStatus(DMA2_Stream5,DMA_FLAG_HTIF5)) { - DMA_ClearFlag(DMA2_Stream5,DMA_FLAG_HTIF5); - } - else { - - } - } #endif /* PIOS_INCLUDE_VIDEO */ diff --git a/flight/PiOS/STM32F10x/pios_tim.c b/flight/PiOS/STM32F10x/pios_tim.c index d160c2c51..28a187341 100644 --- a/flight/PiOS/STM32F10x/pios_tim.c +++ b/flight/PiOS/STM32F10x/pios_tim.c @@ -134,7 +134,7 @@ int32_t PIOS_TIM_InitChannels(uint32_t * tim_id, const struct pios_tim_channel * RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); break; case (uint32_t) GPIOC: - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); break; default: PIOS_Assert(0); diff --git a/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/osd/system_stm32f4xx.c b/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/osd/system_stm32f4xx.c index 9c743591c..17d935034 100644 --- a/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/osd/system_stm32f4xx.c +++ b/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/osd/system_stm32f4xx.c @@ -1,552 +1,553 @@ /** - ****************************************************************************** - * @file system_stm32f4xx.c - * @author MCD Application Team - * @version V1.0.1 - * @date 24-January-2012 - * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. - * This file contains the system clock configuration for STM32F4xx devices, - * and is generated by the clock configuration tool - * stm32f4xx_Clock_Configuration_V1.0.1.xls - * - * 1. This file provides two functions and one global variable to be called from - * user application: - * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier - * and Divider factors, AHB/APBx prescalers and Flash settings), - * depending on the configuration made in the clock xls tool. - * This function is called at startup just after reset and - * before branch to main program. This call is made inside - * the "startup_stm32f4xx.s" file. - * - * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used - * by the user application to setup the SysTick - * timer or configure other parameters. - * - * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must - * be called whenever the core clock is changed - * during program execution. - * - * 2. After each device reset the HSI (16 MHz) is used as system clock source. - * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to - * configure the system clock before to branch to main program. - * - * 3. If the system clock source selected by user fails to startup, the SystemInit() - * function will do nothing and HSI still used as system clock source. User can - * add some code to deal with this issue inside the SetSysClock() function. - * - * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define - * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or - * through PLL, and you are using different crystal you have to adapt the HSE - * value to your own configuration. - * - * 5. This file configures the system clock as follows: - *============================================================================= - *============================================================================= - * Supported STM32F4xx device revision | Rev A - *----------------------------------------------------------------------------- - * System Clock source | PLL (HSE) - *----------------------------------------------------------------------------- - * SYSCLK(Hz) | 108000000 - *----------------------------------------------------------------------------- - * HCLK(Hz) | 108000000 - *----------------------------------------------------------------------------- - * AHB Prescaler | 1 - *----------------------------------------------------------------------------- - * APB1 Prescaler | 4 - *----------------------------------------------------------------------------- - * APB2 Prescaler | 2 - *----------------------------------------------------------------------------- - * HSE Frequency(Hz) | 8000000 - *----------------------------------------------------------------------------- - * PLL_M | 4 - *----------------------------------------------------------------------------- - * PLL_N | 216 - *----------------------------------------------------------------------------- - * PLL_P | 4 - *----------------------------------------------------------------------------- - * PLL_Q | 9 - *----------------------------------------------------------------------------- - * PLLI2S_N | NA - *----------------------------------------------------------------------------- - * PLLI2S_R | NA - *----------------------------------------------------------------------------- - * I2S input clock | NA - *----------------------------------------------------------------------------- - * VDD(V) | 3.3 - *----------------------------------------------------------------------------- - * Main regulator output voltage | Scale2 mode - *----------------------------------------------------------------------------- - * Flash Latency(WS) | 3 - *----------------------------------------------------------------------------- - * Prefetch Buffer | OFF - *----------------------------------------------------------------------------- - * Instruction cache | ON - *----------------------------------------------------------------------------- - * Data cache | ON - *----------------------------------------------------------------------------- - * Require 48MHz for USB OTG FS, | Disabled - * SDIO and RNG clock | - *----------------------------------------------------------------------------- - *============================================================================= - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ + ****************************************************************************** + * @file system_stm32f4xx.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. + * This file contains the system clock configuration for STM32F4xx devices, + * and is generated by the clock configuration tool + * stm32f4xx_Clock_Configuration_V1.0.0.xls + * + * 1. This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier + * and Divider factors, AHB/APBx prescalers and Flash settings), + * depending on the configuration made in the clock xls tool. + * This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32f4xx.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * 2. After each device reset the HSI (16 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to + * configure the system clock before to branch to main program. + * + * 3. If the system clock source selected by user fails to startup, the SystemInit() + * function will do nothing and HSI still used as system clock source. User can + * add some code to deal with this issue inside the SetSysClock() function. + * + * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define + * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or + * through PLL, and you are using different crystal you have to adapt the HSE + * value to your own configuration. + * + * 5. This file configures the system clock as follows: + *============================================================================= + *============================================================================= + * Supported STM32F4xx device revision | Rev A + *----------------------------------------------------------------------------- + * System Clock source | PLL (HSE) + *----------------------------------------------------------------------------- + * SYSCLK(Hz) | 168000000 + *----------------------------------------------------------------------------- + * HCLK(Hz) | 168000000 + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 4 + *----------------------------------------------------------------------------- + * APB2 Prescaler | 2 + *----------------------------------------------------------------------------- + * HSE Frequency(Hz) | 8000000 + *----------------------------------------------------------------------------- + * PLL_M | 10 + *----------------------------------------------------------------------------- + * PLL_N | 420 + *----------------------------------------------------------------------------- + * PLL_P | 2 + *----------------------------------------------------------------------------- + * PLL_Q | 7 + *----------------------------------------------------------------------------- + * PLLI2S_N | NA + *----------------------------------------------------------------------------- + * PLLI2S_R | NA + *----------------------------------------------------------------------------- + * I2S input clock | NA + *----------------------------------------------------------------------------- + * VDD(V) | 3.3 + *----------------------------------------------------------------------------- + * Main regulator output voltage | Scale1 mode + *----------------------------------------------------------------------------- + * Flash Latency(WS) | 5 + *----------------------------------------------------------------------------- + * Prefetch Buffer | OFF + *----------------------------------------------------------------------------- + * Instruction cache | ON + *----------------------------------------------------------------------------- + * Data cache | ON + *----------------------------------------------------------------------------- + * Require 48MHz for USB OTG FS, | Enabled + * SDIO and RNG clock | + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ /** @addtogroup CMSIS - * @{ - */ + * @{ + */ /** @addtogroup stm32f4xx_system - * @{ - */ - + * @{ + */ + /** @addtogroup STM32F4xx_System_Private_Includes - * @{ - */ + * @{ + */ #include "stm32f4xx.h" /** - * @} - */ + * @} + */ /** @addtogroup STM32F4xx_System_Private_TypesDefinitions - * @{ - */ + * @{ + */ /** - * @} - */ + * @} + */ /** @addtogroup STM32F4xx_System_Private_Defines - * @{ - */ + * @{ + */ /************************* Miscellaneous Configuration ************************/ /*!< Uncomment the following line if you need to use external SRAM mounted - on STM324xG_EVAL board as data memory */ + on STM324xG_EVAL board as data memory */ /* #define DATA_IN_ExtSRAM */ /*!< Uncomment the following line if you need to relocate your vector Table in - Internal SRAM. */ + Internal SRAM. */ /* #define VECT_TAB_SRAM */ #define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field. - This value must be a multiple of 0x200. */ +This value must be a multiple of 0x200. */ /******************************************************************************/ /************************* PLL Parameters *************************************/ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */ -#define PLL_M 4 -#define PLL_N 216 +#define PLL_M 10 +#define PLL_N 420 /* SYSCLK = PLL_VCO / PLL_P */ -#define PLL_P 4 +#define PLL_P 2 /* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */ -#define PLL_Q 9 +#define PLL_Q 7 /******************************************************************************/ /** - * @} - */ + * @} + */ /** @addtogroup STM32F4xx_System_Private_Macros - * @{ - */ + * @{ + */ /** - * @} - */ + * @} + */ /** @addtogroup STM32F4xx_System_Private_Variables - * @{ - */ + * @{ + */ - uint32_t SystemCoreClock = 108000000; +uint32_t SystemCoreClock = 168000000; - __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; +__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; /** - * @} - */ + * @} + */ /** @addtogroup STM32F4xx_System_Private_FunctionPrototypes - * @{ - */ + * @{ + */ static void SetSysClock(void); #ifdef DATA_IN_ExtSRAM - static void SystemInit_ExtMemCtl(void); +static void SystemInit_ExtMemCtl(void); #endif /* DATA_IN_ExtSRAM */ /** - * @} - */ + * @} + */ /** @addtogroup STM32F4xx_System_Private_Functions - * @{ - */ + * @{ + */ /** - * @brief Setup the microcontroller system - * Initialize the Embedded Flash Interface, the PLL and update the - * SystemFrequency variable. - * @param None - * @retval None - */ + * @brief Setup the microcontroller system + * Initialize the Embedded Flash Interface, the PLL and update the + * SystemFrequency variable. + * @param None + * @retval None + */ void SystemInit(void) { - /* FPU settings ------------------------------------------------------------*/ - #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + /* FPU settings ------------------------------------------------------------*/ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ - #endif - /* Reset the RCC clock configuration to the default reset state ------------*/ - /* Set HSION bit */ - RCC->CR |= (uint32_t)0x00000001; - - /* Reset CFGR register */ - RCC->CFGR = 0x00000000; - - /* Reset HSEON, CSSON and PLLON bits */ - RCC->CR &= (uint32_t)0xFEF6FFFF; - - /* Reset PLLCFGR register */ - RCC->PLLCFGR = 0x24003010; - - /* Reset HSEBYP bit */ - RCC->CR &= (uint32_t)0xFFFBFFFF; - - /* Disable all interrupts */ - RCC->CIR = 0x00000000; - +#endif + + /* Reset the RCC clock configuration to the default reset state ------------*/ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset CFGR register */ + RCC->CFGR = 0x00000000; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset PLLCFGR register */ + RCC->PLLCFGR = 0x24003010; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Disable all interrupts */ + RCC->CIR = 0x00000000; + #ifdef DATA_IN_ExtSRAM - SystemInit_ExtMemCtl(); + SystemInit_ExtMemCtl(); #endif /* DATA_IN_ExtSRAM */ - - /* Configure the System clock source, PLL Multiplier and Divider factors, + + /* Configure the System clock source, PLL Multiplier and Divider factors, AHB/APBx prescalers and Flash settings ----------------------------------*/ - SetSysClock(); - - /* Configure the Vector Table location add offset address ------------------*/ + SetSysClock(); + + /* Configure the Vector Table location add offset address ------------------*/ #ifdef VECT_TAB_SRAM - SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ #else - SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ #endif } /** - * @brief Update SystemCoreClock variable according to Clock Register Values. - * The SystemCoreClock variable contains the core clock (HCLK), it can - * be used by the user application to setup the SysTick timer or configure - * other parameters. - * - * @note Each time the core clock (HCLK) changes, this function must be called - * to update SystemCoreClock variable value. Otherwise, any configuration - * based on this variable will be incorrect. - * - * @note - The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined - * constant and the selected clock source: - * - * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) - * - * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) - * - * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) - * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * - * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * - * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value - * 25 MHz), user has to ensure that HSE_VALUE is same as the real - * frequency of the crystal used. Otherwise, this function may - * have wrong result. - * - * - The result of this function could be not correct when using fractional - * value for HSE crystal. - * - * @param None - * @retval None - */ + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock (HCLK), it can + * be used by the user application to setup the SysTick timer or configure + * other parameters. + * + * @note Each time the core clock (HCLK) changes, this function must be called + * to update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value + * 25 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @param None + * @retval None + */ void SystemCoreClockUpdate(void) { - uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; - - /* Get SYSCLK source -------------------------------------------------------*/ - tmp = RCC->CFGR & RCC_CFGR_SWS; - - switch (tmp) - { - case 0x00: /* HSI used as system clock source */ - SystemCoreClock = HSI_VALUE; - break; - case 0x04: /* HSE used as system clock source */ - SystemCoreClock = HSE_VALUE; - break; - case 0x08: /* PLL used as system clock source */ - - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N - SYSCLK = PLL_VCO / PLL_P - */ - pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22; - pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - - if (pllsource != 0) - { - /* HSE used as PLL clock source */ - pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); - } - else - { - /* HSI used as PLL clock source */ - pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); - } - - pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; - SystemCoreClock = pllvco/pllp; - break; - default: - SystemCoreClock = HSI_VALUE; - break; - } - /* Compute HCLK frequency --------------------------------------------------*/ - /* Get HCLK prescaler */ - tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; - /* HCLK frequency */ - SystemCoreClock >>= tmp; + uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* HSI used as system clock source */ + SystemCoreClock = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock source */ + SystemCoreClock = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock source */ + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N + SYSCLK = PLL_VCO / PLL_P + */ + pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22; + pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; + + if (pllsource != 0) + { + /* HSE used as PLL clock source */ + pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + } + else + { + /* HSI used as PLL clock source */ + pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + } + + pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; + SystemCoreClock = pllvco/pllp; + break; + default: + SystemCoreClock = HSI_VALUE; + break; + } + /* Compute HCLK frequency --------------------------------------------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK frequency */ + SystemCoreClock >>= tmp; } /** - * @brief Configures the System clock source, PLL Multiplier and Divider factors, - * AHB/APBx prescalers and Flash settings - * @Note This function should be called only once the RCC clock configuration - * is reset to the default reset state (done in SystemInit() function). - * @param None - * @retval None - */ + * @brief Configures the System clock source, PLL Multiplier and Divider factors, + * AHB/APBx prescalers and Flash settings + * @Note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). + * @param None + * @retval None + */ static void SetSysClock(void) { -/******************************************************************************/ -/* PLL (clocked by HSE) used as System clock source */ -/******************************************************************************/ - __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - /* Enable HSE */ - RCC->CR |= ((uint32_t)RCC_CR_HSEON); - - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC->CR & RCC_CR_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); - - if ((RCC->CR & RCC_CR_HSERDY) != RESET) - { - HSEStatus = (uint32_t)0x01; - } - else - { - HSEStatus = (uint32_t)0x00; - } - - if (HSEStatus == (uint32_t)0x01) - { - /* Select regulator voltage output Scale 2 mode, System frequency up to 144 MHz */ - RCC->APB1ENR |= RCC_APB1ENR_PWREN; - PWR->CR &= (uint32_t)~(PWR_CR_VOS); - - /* HCLK = SYSCLK / 1*/ - RCC->CFGR |= RCC_CFGR_HPRE_DIV1; - - /* PCLK2 = HCLK / 2*/ - RCC->CFGR |= RCC_CFGR_PPRE2_DIV2; - - /* PCLK1 = HCLK / 4*/ - RCC->CFGR |= RCC_CFGR_PPRE1_DIV4; - - /* Configure the main PLL */ - RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | - (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24); - - /* Enable the main PLL */ - RCC->CR |= RCC_CR_PLLON; - - /* Wait till the main PLL is ready */ - while((RCC->CR & RCC_CR_PLLRDY) == 0) - { - } - - /* Configure Flash prefetch, Instruction cache, Data cache and wait state */ - FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_3WS; - - /* Select the main PLL as system clock source */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); - RCC->CFGR |= RCC_CFGR_SW_PLL; - - /* Wait till the main PLL is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL); - { - } - } - else - { /* If HSE fails to start-up, the application will have wrong clock - configuration. User can add here some code to deal with this error */ - } - + /******************************************************************************/ + /* PLL (clocked by HSE) used as System clock source */ + /******************************************************************************/ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Select regulator voltage output Scale 1 mode, System frequency up to 168 MHz */ + RCC->APB1ENR |= RCC_APB1ENR_PWREN; + PWR->CR |= PWR_CR_VOS; + + /* HCLK = SYSCLK / 1*/ + RCC->CFGR |= RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK / 2*/ + RCC->CFGR |= RCC_CFGR_PPRE2_DIV2; + + /* PCLK1 = HCLK / 4*/ + RCC->CFGR |= RCC_CFGR_PPRE1_DIV4; + + /* Configure the main PLL */ + RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | + (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24); + + /* Enable the main PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till the main PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Configure Flash prefetch, Instruction cache, Data cache and wait state */ + FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS; + + /* Select the main PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= RCC_CFGR_SW_PLL; + + /* Wait till the main PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL); + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + } + } /** - * @brief Setup the external memory controller. Called in startup_stm32f4xx.s - * before jump to __main - * @param None - * @retval None - */ + * @brief Setup the external memory controller. Called in startup_stm32f4xx.s + * before jump to __main + * @param None + * @retval None + */ #ifdef DATA_IN_ExtSRAM /** - * @brief Setup the external memory controller. - * Called in startup_stm32f4xx.s before jump to main. - * This function configures the external SRAM mounted on STM324xG_EVAL board - * This SRAM will be used as program data memory (including heap and stack). - * @param None - * @retval None - */ + * @brief Setup the external memory controller. + * Called in startup_stm32f4xx.s before jump to main. + * This function configures the external SRAM mounted on STM324xG_EVAL board + * This SRAM will be used as program data memory (including heap and stack). + * @param None + * @retval None + */ void SystemInit_ExtMemCtl(void) { -/*-- GPIOs Configuration -----------------------------------------------------*/ -/* - +-------------------+--------------------+------------------+------------------+ - + SRAM pins assignment + - +-------------------+--------------------+------------------+------------------+ - | PD0 <-> FSMC_D2 | PE0 <-> FSMC_NBL0 | PF0 <-> FSMC_A0 | PG0 <-> FSMC_A10 | - | PD1 <-> FSMC_D3 | PE1 <-> FSMC_NBL1 | PF1 <-> FSMC_A1 | PG1 <-> FSMC_A11 | - | PD4 <-> FSMC_NOE | PE3 <-> FSMC_A19 | PF2 <-> FSMC_A2 | PG2 <-> FSMC_A12 | - | PD5 <-> FSMC_NWE | PE4 <-> FSMC_A20 | PF3 <-> FSMC_A3 | PG3 <-> FSMC_A13 | - | PD8 <-> FSMC_D13 | PE7 <-> FSMC_D4 | PF4 <-> FSMC_A4 | PG4 <-> FSMC_A14 | - | PD9 <-> FSMC_D14 | PE8 <-> FSMC_D5 | PF5 <-> FSMC_A5 | PG5 <-> FSMC_A15 | - | PD10 <-> FSMC_D15 | PE9 <-> FSMC_D6 | PF12 <-> FSMC_A6 | PG9 <-> FSMC_NE2 | - | PD11 <-> FSMC_A16 | PE10 <-> FSMC_D7 | PF13 <-> FSMC_A7 |------------------+ - | PD12 <-> FSMC_A17 | PE11 <-> FSMC_D8 | PF14 <-> FSMC_A8 | - | PD13 <-> FSMC_A18 | PE12 <-> FSMC_D9 | PF15 <-> FSMC_A9 | - | PD14 <-> FSMC_D0 | PE13 <-> FSMC_D10 |------------------+ - | PD15 <-> FSMC_D1 | PE14 <-> FSMC_D11 | - | | PE15 <-> FSMC_D12 | - +-------------------+--------------------+ -*/ - /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */ - RCC->AHB1ENR = 0x00000078; - - /* Connect PDx pins to FSMC Alternate function */ - GPIOD->AFR[0] = 0x00cc00cc; - GPIOD->AFR[1] = 0xcc0ccccc; - /* Configure PDx pins in Alternate function mode */ - GPIOD->MODER = 0xaaaa0a0a; - /* Configure PDx pins speed to 100 MHz */ - GPIOD->OSPEEDR = 0xffff0f0f; - /* Configure PDx pins Output type to push-pull */ - GPIOD->OTYPER = 0x00000000; - /* No pull-up, pull-down for PDx pins */ - GPIOD->PUPDR = 0x00000000; - - /* Connect PEx pins to FSMC Alternate function */ - GPIOE->AFR[0] = 0xc00cc0cc; - GPIOE->AFR[1] = 0xcccccccc; - /* Configure PEx pins in Alternate function mode */ - GPIOE->MODER = 0xaaaa828a; - /* Configure PEx pins speed to 100 MHz */ - GPIOE->OSPEEDR = 0xffffc3cf; - /* Configure PEx pins Output type to push-pull */ - GPIOE->OTYPER = 0x00000000; - /* No pull-up, pull-down for PEx pins */ - GPIOE->PUPDR = 0x00000000; - - /* Connect PFx pins to FSMC Alternate function */ - GPIOF->AFR[0] = 0x00cccccc; - GPIOF->AFR[1] = 0xcccc0000; - /* Configure PFx pins in Alternate function mode */ - GPIOF->MODER = 0xaa000aaa; - /* Configure PFx pins speed to 100 MHz */ - GPIOF->OSPEEDR = 0xff000fff; - /* Configure PFx pins Output type to push-pull */ - GPIOF->OTYPER = 0x00000000; - /* No pull-up, pull-down for PFx pins */ - GPIOF->PUPDR = 0x00000000; - - /* Connect PGx pins to FSMC Alternate function */ - GPIOG->AFR[0] = 0x00cccccc; - GPIOG->AFR[1] = 0x000000c0; - /* Configure PGx pins in Alternate function mode */ - GPIOG->MODER = 0x00080aaa; - /* Configure PGx pins speed to 100 MHz */ - GPIOG->OSPEEDR = 0x000c0fff; - /* Configure PGx pins Output type to push-pull */ - GPIOG->OTYPER = 0x00000000; - /* No pull-up, pull-down for PGx pins */ - GPIOG->PUPDR = 0x00000000; - -/*-- FSMC Configuration ------------------------------------------------------*/ - /* Enable the FSMC interface clock */ - RCC->AHB3ENR = 0x00000001; - - /* Configure and enable Bank1_SRAM2 */ - FSMC_Bank1->BTCR[2] = 0x00001015; - FSMC_Bank1->BTCR[3] = 0x00010603; - FSMC_Bank1E->BWTR[2] = 0x0fffffff; - /* - Bank1_SRAM2 is configured as follow: - - p.FSMC_AddressSetupTime = 3; - p.FSMC_AddressHoldTime = 0; - p.FSMC_DataSetupTime = 6; - p.FSMC_BusTurnAroundDuration = 1; - p.FSMC_CLKDivision = 0; - p.FSMC_DataLatency = 0; - p.FSMC_AccessMode = FSMC_AccessMode_A; - - FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2; - FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable; - FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_PSRAM; - FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b; - FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; - FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; - FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; - FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable; - FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; - FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable; - FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable; - FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; - FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable; - FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p; - FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p; -*/ + /*-- GPIOs Configuration -----------------------------------------------------*/ + /* + +-------------------+--------------------+------------------+------------------+ + + SRAM pins assignment + + +-------------------+--------------------+------------------+------------------+ + | PD0 <-> FSMC_D2 | PE0 <-> FSMC_NBL0 | PF0 <-> FSMC_A0 | PG0 <-> FSMC_A10 | + | PD1 <-> FSMC_D3 | PE1 <-> FSMC_NBL1 | PF1 <-> FSMC_A1 | PG1 <-> FSMC_A11 | + | PD4 <-> FSMC_NOE | PE3 <-> FSMC_A19 | PF2 <-> FSMC_A2 | PG2 <-> FSMC_A12 | + | PD5 <-> FSMC_NWE | PE4 <-> FSMC_A20 | PF3 <-> FSMC_A3 | PG3 <-> FSMC_A13 | + | PD8 <-> FSMC_D13 | PE7 <-> FSMC_D4 | PF4 <-> FSMC_A4 | PG4 <-> FSMC_A14 | + | PD9 <-> FSMC_D14 | PE8 <-> FSMC_D5 | PF5 <-> FSMC_A5 | PG5 <-> FSMC_A15 | + | PD10 <-> FSMC_D15 | PE9 <-> FSMC_D6 | PF12 <-> FSMC_A6 | PG9 <-> FSMC_NE2 | + | PD11 <-> FSMC_A16 | PE10 <-> FSMC_D7 | PF13 <-> FSMC_A7 |------------------+ + | PD12 <-> FSMC_A17 | PE11 <-> FSMC_D8 | PF14 <-> FSMC_A8 | + | PD13 <-> FSMC_A18 | PE12 <-> FSMC_D9 | PF15 <-> FSMC_A9 | + | PD14 <-> FSMC_D0 | PE13 <-> FSMC_D10 |------------------+ + | PD15 <-> FSMC_D1 | PE14 <-> FSMC_D11 | + | | PE15 <-> FSMC_D12 | + +-------------------+--------------------+ + */ + /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */ + RCC->AHB1ENR = 0x00000078; + + /* Connect PDx pins to FSMC Alternate function */ + GPIOD->AFR[0] = 0x00cc00cc; + GPIOD->AFR[1] = 0xcc0ccccc; + /* Configure PDx pins in Alternate function mode */ + GPIOD->MODER = 0xaaaa0a0a; + /* Configure PDx pins speed to 100 MHz */ + GPIOD->OSPEEDR = 0xffff0f0f; + /* Configure PDx pins Output type to push-pull */ + GPIOD->OTYPER = 0x00000000; + /* No pull-up, pull-down for PDx pins */ + GPIOD->PUPDR = 0x00000000; + + /* Connect PEx pins to FSMC Alternate function */ + GPIOE->AFR[0] = 0xc00cc0cc; + GPIOE->AFR[1] = 0xcccccccc; + /* Configure PEx pins in Alternate function mode */ + GPIOE->MODER = 0xaaaa828a; + /* Configure PEx pins speed to 100 MHz */ + GPIOE->OSPEEDR = 0xffffc3cf; + /* Configure PEx pins Output type to push-pull */ + GPIOE->OTYPER = 0x00000000; + /* No pull-up, pull-down for PEx pins */ + GPIOE->PUPDR = 0x00000000; + + /* Connect PFx pins to FSMC Alternate function */ + GPIOF->AFR[0] = 0x00cccccc; + GPIOF->AFR[1] = 0xcccc0000; + /* Configure PFx pins in Alternate function mode */ + GPIOF->MODER = 0xaa000aaa; + /* Configure PFx pins speed to 100 MHz */ + GPIOF->OSPEEDR = 0xff000fff; + /* Configure PFx pins Output type to push-pull */ + GPIOF->OTYPER = 0x00000000; + /* No pull-up, pull-down for PFx pins */ + GPIOF->PUPDR = 0x00000000; + + /* Connect PGx pins to FSMC Alternate function */ + GPIOG->AFR[0] = 0x00cccccc; + GPIOG->AFR[1] = 0x000000c0; + /* Configure PGx pins in Alternate function mode */ + GPIOG->MODER = 0x00080aaa; + /* Configure PGx pins speed to 100 MHz */ + GPIOG->OSPEEDR = 0x000c0fff; + /* Configure PGx pins Output type to push-pull */ + GPIOG->OTYPER = 0x00000000; + /* No pull-up, pull-down for PGx pins */ + GPIOG->PUPDR = 0x00000000; + + /*-- FSMC Configuration ------------------------------------------------------*/ + /* Enable the FSMC interface clock */ + RCC->AHB3ENR = 0x00000001; + + /* Configure and enable Bank1_SRAM2 */ + FSMC_Bank1->BTCR[2] = 0x00001015; + FSMC_Bank1->BTCR[3] = 0x00010603; + FSMC_Bank1E->BWTR[2] = 0x0fffffff; + /* + Bank1_SRAM2 is configured as follow: + + p.FSMC_AddressSetupTime = 3; + p.FSMC_AddressHoldTime = 0; + p.FSMC_DataSetupTime = 6; + p.FSMC_BusTurnAroundDuration = 1; + p.FSMC_CLKDivision = 0; + p.FSMC_DataLatency = 0; + p.FSMC_AccessMode = FSMC_AccessMode_A; + + FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2; + FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable; + FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_PSRAM; + FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b; + FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; + FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; + FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable; + FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable; + FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p; + FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p; + */ + } #endif /* DATA_IN_ExtSRAM */ /** - * @} - */ + * @} + */ /** - * @} - */ - + * @} + */ + /** - * @} - */ + * @} + */ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ - diff --git a/flight/PiOS/inc/pios_hcsr04.h b/flight/PiOS/inc/pios_hcsr04.h index d2574a826..fe735e336 100644 --- a/flight/PiOS/inc/pios_hcsr04.h +++ b/flight/PiOS/inc/pios_hcsr04.h @@ -32,7 +32,6 @@ #define PIOS_HCSR04_H /* Public Functions */ -extern void PIOS_HCSR04_Init(void); extern int32_t PIOS_HCSR04_Get(void); extern int32_t PIOS_HCSR04_Completed(void); extern void PIOS_HCSR04_Trigger(void); diff --git a/flight/PiOS/inc/pios_hcsr04_priv.h b/flight/PiOS/inc/pios_hcsr04_priv.h new file mode 100644 index 000000000..c53bdddf1 --- /dev/null +++ b/flight/PiOS/inc/pios_hcsr04_priv.h @@ -0,0 +1,55 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_SERVO Servo Functions + * @brief PIOS interface to read and write from servo PWM ports + * @{ + * + * @file pios_servo_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Servo private structures. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_HCSR04_PRIV_H +#define PIOS_HCSR04_PRIV_H + +#include +#include + +#include + +struct pios_hcsr04_cfg { + TIM_ICInitTypeDef tim_ic_init; + const struct pios_tim_channel * channels; + uint8_t num_channels; + struct stm32_gpio trigger; +}; + +extern const struct pios_rcvr_driver pios_pwm_rcvr_driver; + +extern int32_t PIOS_HCSR04_Init(uint32_t * pwm_id, const struct pios_hcsr04_cfg * cfg); + +#endif /* PIOS_HCSR04_PRIV_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_video.h b/flight/PiOS/inc/pios_video.h index 4be4a2f7d..abdba4f6c 100644 --- a/flight/PiOS/inc/pios_video.h +++ b/flight/PiOS/inc/pios_video.h @@ -42,12 +42,10 @@ struct pios_video_cfg { const struct pios_exti_cfg * hsync; const struct pios_exti_cfg * vsync; - /*struct stm32_exti hsync; - struct stm32_exti vsync; - struct stm32_gpio hsync_io; - struct stm32_gpio vsync_io; - struct stm32_irq hsync_irq; - struct stm32_irq vsync_irq;*/ + struct pios_tim_channel pixel_timer; + struct pios_tim_channel hsync_capture; + + TIM_OCInitTypeDef tim_oc_init; }; // Time vars @@ -65,20 +63,21 @@ extern bool PIOS_Hsync_ISR(); extern bool PIOS_Vsync_ISR(); // First OSD line -#define GRAPHICS_LINE 32 +#define GRAPHICS_LINE 25 //top/left deadband -#define GRAPHICS_HDEADBAND 32 +#define GRAPHICS_HDEADBAND 80 #define GRAPHICS_VDEADBAND 0 #define PAL // Real OSD size #ifdef PAL - #define GRAPHICS_WIDTH_REAL (336+GRAPHICS_HDEADBAND) +//#define GRAPHICS_WIDTH_REAL (352+GRAPHICS_HDEADBAND) +#define GRAPHICS_WIDTH_REAL 416 #define GRAPHICS_HEIGHT_REAL (270+GRAPHICS_VDEADBAND) #else - #define GRAPHICS_WIDTH_REAL (320+GRAPHICS_HDEADBAND) + #define GRAPHICS_WIDTH_REAL (312+GRAPHICS_HDEADBAND) #define GRAPHICS_HEIGHT_REAL (225+GRAPHICS_VDEADBAND) #endif diff --git a/flight/Project/gdb/osd b/flight/Project/gdb/osd new file mode 100644 index 000000000..291b0570a --- /dev/null +++ b/flight/Project/gdb/osd @@ -0,0 +1,4 @@ +define connect + target remote localhost:3333 + file ./build/fw_osd/fw_osd.elf +end diff --git a/flight/targets/CopterControl/System/pios_board.c b/flight/targets/CopterControl/System/pios_board.c index 2656bfab1..64c3d855d 100644 --- a/flight/targets/CopterControl/System/pios_board.c +++ b/flight/targets/CopterControl/System/pios_board.c @@ -59,6 +59,8 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; #define PIOS_COM_BRIDGE_RX_BUF_LEN 65 #define PIOS_COM_BRIDGE_TX_BUF_LEN 12 +#define PIOS_COM_HKOSD_TX_BUF_LEN 22 + #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) #define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 uint32_t pios_com_debug_id; @@ -69,6 +71,7 @@ uint32_t pios_com_telem_usb_id; uint32_t pios_com_vcp_id; uint32_t pios_com_gps_id; uint32_t pios_com_bridge_id; +uint32_t pios_com_hkosd_id; uint32_t pios_usb_rctx_id; @@ -526,6 +529,22 @@ void PIOS_Board_Init(void) { } } break; + case HWSETTINGS_CC_MAINPORT_OSDHK: + { + uint32_t pios_usart_hkosd_id; + if (PIOS_USART_Init(&pios_usart_hkosd_id, &pios_usart_hkosd_main_cfg)) { + PIOS_Assert(0); + } + + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_HKOSD_TX_BUF_LEN); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_hkosd_id, &pios_usart_com_driver, pios_usart_hkosd_id, + NULL, 0, + tx_buffer, PIOS_COM_HKOSD_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } + break; } /* Configure the flexi port */ @@ -675,6 +694,22 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_I2C */ break; + case HWSETTINGS_CC_FLEXIPORT_OSDHK: + { + uint32_t pios_usart_hkosd_id; + if (PIOS_USART_Init(&pios_usart_hkosd_id, &pios_usart_hkosd_flexi_cfg)) { + PIOS_Assert(0); + } + + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_HKOSD_TX_BUF_LEN); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_hkosd_id, &pios_usart_com_driver, pios_usart_hkosd_id, + NULL, 0, + tx_buffer, PIOS_COM_HKOSD_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } + break; } /* Configure the rcvr port */ @@ -683,6 +718,12 @@ void PIOS_Board_Init(void) { switch (hwsettings_rcvrport) { case HWSETTINGS_CC_RCVRPORT_DISABLED: +#if defined(PIOS_INCLUDE_HCSR04) + { + uint32_t pios_hcsr04_id; + PIOS_HCSR04_Init(&pios_hcsr04_id, &pios_hcsr04_cfg); + } +#endif break; case HWSETTINGS_CC_RCVRPORT_PWM: #if defined(PIOS_INCLUDE_PWM) diff --git a/flight/targets/OSD/System/inc/pios_config.h b/flight/targets/OSD/System/inc/pios_config.h index 92fc3ee9b..cda229055 100644 --- a/flight/targets/OSD/System/inc/pios_config.h +++ b/flight/targets/OSD/System/inc/pios_config.h @@ -98,7 +98,7 @@ /* PIOS common peripherals */ #define PIOS_INCLUDE_LED #define PIOS_INCLUDE_IAP -/* #define PIOS_INCLUDE_SERVO */ +#define PIOS_INCLUDE_SERVO /* #define PIOS_INCLUDE_I2C_ESC */ /* #define PIOS_INCLUDE_OVERO */ /* #define PIOS_OVERO_SPI */ diff --git a/flight/targets/OSD/System/pios_board.c b/flight/targets/OSD/System/pios_board.c index eef8e6756..84595f320 100644 --- a/flight/targets/OSD/System/pios_board.c +++ b/flight/targets/OSD/System/pios_board.c @@ -85,8 +85,8 @@ void PIOS_ADC_DMC_irq_handler(void) static void Clock(uint32_t spektrum_id); -#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 -#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 +#define PIOS_COM_TELEM_RF_RX_BUF_LEN 128 +#define PIOS_COM_TELEM_RF_TX_BUF_LEN 128 #define PIOS_COM_AUX_RX_BUF_LEN 512 #define PIOS_COM_AUX_TX_BUF_LEN 512 @@ -104,7 +104,42 @@ uint32_t pios_com_gps_id; uint32_t pios_com_telem_usb_id; uint32_t pios_com_telem_rf_id; +/** + * TIM3 is triggered by the HSYNC signal into its ETR line and will divide the + * APB1_CLOCK to generate a pixel clock that is used by the SPI CLK lines. + * TIM4 will be synced to it and will divide by that times the pixel width to + * fire an IRQ when the last pixel of the line has been output. Then the timer will + * be rearmed and wait for the next HSYNC signal. + * The critical timing detail is that the task be _DISABLED_ at the end of the line + * before an extra pixel is clocked out + * or we will need to configure the DMA task per line + */ +#include "pios_tim_priv.h" +#define NTSC_PX_CLOCK 6797088 +#define PAL_PX_CLOCK 6750130 +#define PX_PERIOD ((PIOS_PERIPHERAL_APB1_CLOCK / NTSC_PX_CLOCK) + 1) +#define LINE_PERIOD PX_PERIOD * GRAPHICS_WIDTH +static const TIM_TimeBaseInitTypeDef tim_4_time_base = { + .TIM_Prescaler = 0, //PIOS_PERIPHERAL_APB1_CLOCK, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = LINE_PERIOD - 1, + .TIM_RepetitionCounter = 0x0000, +}; + +const static struct pios_tim_clock_cfg pios_tim4_cfg = { + .timer = TIM4, + .time_base_init = &tim_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + } +}; void PIOS_Board_Init(void) { @@ -119,9 +154,11 @@ void PIOS_Board_Init(void) { PIOS_Assert(0); } +#if defined(PIOS_INCLUDE_SDCARD) /* Enable and mount the SDCard */ PIOS_SDCARD_Init(pios_spi_sdcard_id); PIOS_SDCARD_MountFS(0); +#endif #endif /* PIOS_INCLUDE_SPI */ /* Initialize UAVObject libraries */ @@ -148,6 +185,7 @@ void PIOS_Board_Init(void) { AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); } + #if defined(PIOS_INCLUDE_RTC) /* Initialize the real-time clock and its associated tick */ PIOS_RTC_Init(&pios_rtc_main_cfg); @@ -403,6 +441,10 @@ void PIOS_Board_Init(void) { #endif #if defined(PIOS_INCLUDE_VIDEO) + PIOS_TIM_InitClock(&tim_8_cfg); + PIOS_Servo_Init(&pios_servo_cfg); + // Start the pixel and line clock counter + //PIOS_TIM_InitClock(&pios_tim4_cfg); PIOS_Video_Init(&pios_video_cfg); #endif } diff --git a/flight/targets/RevoMini/Makefile b/flight/targets/RevoMini/Makefile index f432a535a..e19310de3 100644 --- a/flight/targets/RevoMini/Makefile +++ b/flight/targets/RevoMini/Makefile @@ -44,8 +44,9 @@ MODULES += FirmwareIAP MODULES += Radio MODULES += PathPlanner MODULES += FixedWingPathFollower +MODULES += Osd/OsdHk MODULES += Telemetry -#MODULES += VtolPathFollower ## OP-700: VtolPathFollower disabled because its currently unsafe - remove this line once Sambas code has been merged +MODULES += VtolPathFollower ## OP-700: VtolPathFollower disabled because its currently unsafe - remove this line once Sambas code has been merged OPTMODULES = diff --git a/flight/targets/RevoMini/System/pios_board.c b/flight/targets/RevoMini/System/pios_board.c index be334adad..80c6b3bd6 100644 --- a/flight/targets/RevoMini/System/pios_board.c +++ b/flight/targets/RevoMini/System/pios_board.c @@ -209,6 +209,9 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; #define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512 #define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512 +#define PIOS_COM_HKOSD_RX_BUF_LEN 22 +#define PIOS_COM_HKOSD_TX_BUF_LEN 22 + #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) #define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 uint32_t pios_com_debug_id; @@ -219,6 +222,7 @@ uint32_t pios_com_telem_usb_id = 0; uint32_t pios_com_telem_rf_id = 0; uint32_t pios_com_bridge_id = 0; uint32_t pios_com_overo_id = 0; +uint32_t pios_com_hkosd_id = 0; #if defined(PIOS_INCLUDE_RFM22B) uint32_t pios_rfm22b_id = 0; #endif @@ -549,7 +553,9 @@ void PIOS_Board_Init(void) { case HWSETTINGS_RM_MAINPORT_COMBRIDGE: PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); break; - + case HWSETTINGS_RM_MAINPORT_OSDHK: + PIOS_Board_configure_com(&pios_usart_hkosd_main_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id); + break; } /* hwsettings_rm_mainport */ if (hwsettings_mainport != HWSETTINGS_RM_MAINPORT_SBUS) { @@ -612,7 +618,11 @@ void PIOS_Board_Init(void) { case HWSETTINGS_RM_FLEXIPORT_COMBRIDGE: PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); break; - } /* hwsettings_rv_flexiport */ + case HWSETTINGS_RM_FLEXIPORT_OSDHK: + PIOS_Board_configure_com(&pios_usart_hkosd_flexi_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id); + break; + } /* hwsettings_rm_flexiport */ + /* Initalize the RFM22B radio COM device. */ #if defined(PIOS_INCLUDE_RFM22B) diff --git a/flight/targets/Revolution/System/pios_board.c b/flight/targets/Revolution/System/pios_board.c index 317919ef6..dc002cafd 100644 --- a/flight/targets/Revolution/System/pios_board.c +++ b/flight/targets/Revolution/System/pios_board.c @@ -292,12 +292,17 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; #define PIOS_COM_AUX_RX_BUF_LEN 512 #define PIOS_COM_AUX_TX_BUF_LEN 512 +#define PIOS_COM_HKOSD_RX_BUF_LEN 22 +#define PIOS_COM_HKOSD_TX_BUF_LEN 22 + + uint32_t pios_com_aux_id = 0; uint32_t pios_com_gps_id = 0; uint32_t pios_com_telem_usb_id = 0; uint32_t pios_com_telem_rf_id = 0; uint32_t pios_com_bridge_id = 0; uint32_t pios_com_overo_id = 0; +uint32_t pios_com_hkosd_id = 0; /* * Setup a com port based on the passed cfg, driver and buffer sizes. tx size of -1 make the port rx only @@ -617,6 +622,10 @@ void PIOS_Board_Init(void) { case HWSETTINGS_RV_AUXPORT_COMBRIDGE: PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); break; + case HWSETTINGS_RV_AUXPORT_OSDHK: + PIOS_Board_configure_com(&pios_usart_hkosd_aux_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id); + break; + } /* hwsettings_rv_auxport */ /* Configure AUXSbusPort */ //TODO: ensure that the serial invertion pin is setted correctly @@ -679,6 +688,9 @@ void PIOS_Board_Init(void) { case HWSETTINGS_RV_AUXSBUSPORT_COMBRIDGE: PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); break; + case HWSETTINGS_RV_AUXSBUSPORT_OSDHK: + PIOS_Board_configure_com(&pios_usart_hkosd_auxsbus_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id); + break; } /* hwsettings_rv_auxport */ /* Configure FlexiPort */ @@ -797,6 +809,15 @@ void PIOS_Board_Init(void) { #endif +#if defined(PIOS_INCLUDE_HCSR04) + { + PIOS_TIM_InitClock(&tim_8_cfg); + uint32_t pios_hcsr04_id; + PIOS_HCSR04_Init(&pios_hcsr04_id, &pios_hcsr04_cfg); + } +#endif + + #if defined(PIOS_INCLUDE_GCSRCVR) GCSReceiverInitialize(); uint32_t pios_gcsrcvr_id; diff --git a/flight/targets/board_hw_defs/coptercontrol/board_hw_defs.c b/flight/targets/board_hw_defs/coptercontrol/board_hw_defs.c index 19408858c..1706a2c7a 100644 --- a/flight/targets/board_hw_defs/coptercontrol/board_hw_defs.c +++ b/flight/targets/board_hw_defs/coptercontrol/board_hw_defs.c @@ -1083,6 +1083,82 @@ static const struct pios_sbus_cfg pios_sbus_cfg = { #endif /* PIOS_INCLUDE_SBUS */ +/* + * HK OSD + */ +static const struct pios_usart_cfg pios_usart_hkosd_main_cfg = { + .regs = USART1, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART1_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, +}; + +static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = { + .regs = USART3, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, +}; + + #endif /* PIOS_INCLUDE_USART */ #if defined(PIOS_INCLUDE_COM) @@ -1224,6 +1300,50 @@ const struct pios_pwm_cfg pios_pwm_with_ppm_cfg = { #endif + + +/* + * SONAR Inputs + */ +#if defined(PIOS_INCLUDE_HCSR04) +#include + +static const struct pios_tim_channel pios_tim_hcsr04_port_all_channels[] = { +{ + .timer = TIM3, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap_TIM3, +}, +}; + +const struct pios_hcsr04_cfg pios_hcsr04_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + }, + .channels = pios_tim_hcsr04_port_all_channels, + .num_channels = NELEMENTS(pios_tim_hcsr04_port_all_channels), + .trigger = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_Out_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, +}; +#endif + #if defined(PIOS_INCLUDE_I2C) #include diff --git a/flight/targets/board_hw_defs/osd/board_hw_defs.c b/flight/targets/board_hw_defs/osd/board_hw_defs.c index 9f32b5613..44434c392 100644 --- a/flight/targets/board_hw_defs/osd/board_hw_defs.c +++ b/flight/targets/board_hw_defs/osd/board_hw_defs.c @@ -35,9 +35,9 @@ static const struct pios_led pios_leds[] = { [PIOS_LED_HEARTBEAT] = { .pin = { - .gpio = GPIOC, + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_5, + .GPIO_Pin = GPIO_Pin_0, .GPIO_Speed = GPIO_Speed_50MHz, .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, @@ -49,7 +49,7 @@ static const struct pios_led pios_leds[] = { .pin = { .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_4, + .GPIO_Pin = GPIO_Pin_5, .GPIO_Speed = GPIO_Speed_50MHz, .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, @@ -202,6 +202,7 @@ void PIOS_SPI_sdcard_irq_handler(void) #include #if defined(PIOS_INCLUDE_GPS) + /* * GPS USART */ @@ -246,7 +247,6 @@ static const struct pios_usart_cfg pios_usart_gps_cfg = { }, }, }; - #endif /* PIOS_INCLUDE_GPS */ #ifdef PIOS_INCLUDE_COM_AUX @@ -521,14 +521,91 @@ const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = { #if defined(PIOS_INCLUDE_VIDEO) +static const TIM_TimeBaseInitTypeDef tim_8_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / 50000) - 1), + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_8_cfg = { + .timer = TIM8, + .time_base_init = &tim_8_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM8_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +/** + * Pios servo configuration structures + */ +#include +static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { + { + .timer = TIM8, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource8, + }, + .remap = GPIO_AF_TIM8, + }, + { + .timer = TIM8, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource9, + }, + .remap = GPIO_AF_TIM8, + }, +}; + +const struct pios_servo_cfg pios_servo_cfg = { + .tim_oc_init = { + .TIM_OCMode = TIM_OCMode_PWM1, + .TIM_OutputState = TIM_OutputState_Enable, + .TIM_OutputNState = TIM_OutputNState_Disable, + .TIM_Pulse = 0, + .TIM_OCPolarity = TIM_OCPolarity_High, + .TIM_OCNPolarity = TIM_OCPolarity_High, + .TIM_OCIdleState = TIM_OCIdleState_Reset, + .TIM_OCNIdleState = TIM_OCNIdleState_Reset, + }, + .channels = pios_tim_servoport_all_pins, + .num_channels = NELEMENTS(pios_tim_servoport_all_pins), +}; + + + #include static const struct pios_exti_cfg pios_exti_hsync_cfg __exti_config = { .vector = PIOS_Hsync_ISR, - .line = EXTI_Line2, + .line = EXTI_Line7, .pin = { - .gpio = GPIOD, + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_2, + .GPIO_Pin = GPIO_Pin_7, .GPIO_Speed = GPIO_Speed_100MHz, .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, @@ -537,28 +614,30 @@ static const struct pios_exti_cfg pios_exti_hsync_cfg __exti_config = { }, .irq = { .init = { - .NVIC_IRQChannel = EXTI2_IRQn, - .NVIC_IRQChannelPreemptionPriority = 0, + .NVIC_IRQChannel = EXTI9_5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, }, }, .exti = { .init = { - .EXTI_Line = EXTI_Line2, // matches above GPIO pin + .EXTI_Line = EXTI_Line7, // matches above GPIO pin .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising_Falling, + //.EXTI_Trigger = EXTI_Trigger_Rising_Falling, + .EXTI_Trigger = EXTI_Trigger_Falling, + //.EXTI_Trigger = EXTI_Trigger_Rising, .EXTI_LineCmd = ENABLE, }, }, }; static const struct pios_exti_cfg pios_exti_vsync_cfg __exti_config = { .vector = PIOS_Vsync_ISR, - .line = EXTI_Line11, + .line = EXTI_Line5, .pin = { - .gpio = GPIOC, + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_11, + .GPIO_Pin = GPIO_Pin_5, .GPIO_Speed = GPIO_Speed_100MHz, .GPIO_Mode = GPIO_Mode_IN, .GPIO_OType = GPIO_OType_OD, @@ -567,7 +646,7 @@ static const struct pios_exti_cfg pios_exti_vsync_cfg __exti_config = { }, .irq = { .init = { - .NVIC_IRQChannel = EXTI15_10_IRQn, + .NVIC_IRQChannel = EXTI9_5_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, @@ -575,7 +654,7 @@ static const struct pios_exti_cfg pios_exti_vsync_cfg __exti_config = { }, .exti = { .init = { - .EXTI_Line = EXTI_Line11, // matches above GPIO pin + .EXTI_Line = EXTI_Line5, // matches above GPIO pin .EXTI_Mode = EXTI_Mode_Interrupt, .EXTI_Trigger = EXTI_Trigger_Falling, .EXTI_LineCmd = ENABLE, @@ -589,7 +668,7 @@ static const struct pios_video_cfg pios_video_cfg = { .regs = SPI3, .remap = GPIO_AF_SPI3, .init = { - .SPI_Mode = SPI_Mode_Master, + .SPI_Mode = SPI_Mode_Slave, .SPI_Direction = SPI_Direction_1Line_Tx, .SPI_DataSize = SPI_DataSize_8b, .SPI_NSS = SPI_NSS_Soft, @@ -597,7 +676,7 @@ static const struct pios_video_cfg pios_video_cfg = { .SPI_CRCPolynomial = 7, .SPI_CPOL = SPI_CPOL_Low, .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, }, .use_crc = false, .dma = { @@ -606,12 +685,11 @@ static const struct pios_video_cfg pios_video_cfg = { .flags = (DMA_IT_TCIF7), .init = { .NVIC_IRQChannel = DMA1_Stream7_IRQn, - .NVIC_IRQChannelPreemptionPriority = 0, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, }, }, - .rx = {}, .tx = { .channel = DMA1_Stream7, @@ -626,9 +704,9 @@ static const struct pios_video_cfg pios_video_cfg = { .DMA_MemoryDataSize = DMA_MemoryDataSize_Word, .DMA_Mode = DMA_Mode_Normal, .DMA_Priority = DMA_Priority_VeryHigh, - .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOMode = DMA_FIFOMode_Enable, .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_MemoryBurst = DMA_MemoryBurst_INC4, .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, }, }, @@ -653,16 +731,7 @@ static const struct pios_video_cfg pios_video_cfg = { .GPIO_PuPd = GPIO_PuPd_NOPULL }, }, - .mosi = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, + .mosi = {}, .slave_count = 1, }, .level = { @@ -685,12 +754,11 @@ static const struct pios_video_cfg pios_video_cfg = { .flags = (DMA_IT_TCIF5), .init = { .NVIC_IRQChannel = DMA2_Stream5_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelPreemptionPriority = 0, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, }, }, - .rx = {}, .tx = { .channel = DMA2_Stream5, @@ -705,9 +773,9 @@ static const struct pios_video_cfg pios_video_cfg = { .DMA_MemoryDataSize = DMA_MemoryDataSize_Word, .DMA_Mode = DMA_Mode_Normal, .DMA_Priority = DMA_Priority_VeryHigh, - .DMA_FIFOMode = DMA_FIFOMode_Disable, + .DMA_FIFOMode = DMA_FIFOMode_Enable, .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_MemoryBurst = DMA_MemoryBurst_INC4, .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, }, }, @@ -732,23 +800,56 @@ static const struct pios_video_cfg pios_video_cfg = { .GPIO_PuPd = GPIO_PuPd_UP }, }, - .mosi = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, + .mosi = {}, .slave_count = 1, }, - ///////////////// .hsync = &pios_exti_hsync_cfg, .vsync = &pios_exti_vsync_cfg, + + .pixel_timer = { + .timer = TIM4, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource6, + }, + .remap = GPIO_AF_TIM4, + }, + .hsync_capture = { + .timer = TIM4, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource7, + }, + .remap = GPIO_AF_TIM4, + }, + .tim_oc_init = { + .TIM_OCMode = TIM_OCMode_PWM1, + .TIM_OutputState = TIM_OutputState_Enable, + .TIM_OutputNState = TIM_OutputNState_Disable, + .TIM_Pulse = 1, + .TIM_OCPolarity = TIM_OCPolarity_High, + .TIM_OCNPolarity = TIM_OCPolarity_High, + .TIM_OCIdleState = TIM_OCIdleState_Reset, + .TIM_OCNIdleState = TIM_OCNIdleState_Reset, + }, }; #endif diff --git a/flight/targets/board_hw_defs/revolution/board_hw_defs.c b/flight/targets/board_hw_defs/revolution/board_hw_defs.c index 75128549f..42042f054 100644 --- a/flight/targets/board_hw_defs/revolution/board_hw_defs.c +++ b/flight/targets/board_hw_defs/revolution/board_hw_defs.c @@ -1020,7 +1020,7 @@ static const struct pios_dsm_cfg pios_dsm_flexi_cfg = { static const struct pios_usart_cfg pios_usart_sbus_auxsbus_cfg = { .regs = UART4, - .remap = GPIO_AF_UART4, + .remap = GPIO_AF_UART4, .init = { .USART_BaudRate = 100000, .USART_WordLength = USART_WordLength_8b, @@ -1078,6 +1078,91 @@ static const struct pios_sbus_cfg pios_sbus_cfg = { #endif /* PIOS_INCLUDE_SBUS */ +/* + * HK OSD + */ +static const struct pios_usart_cfg pios_usart_hkosd_auxsbus_cfg = { + .regs = UART4, + .remap = GPIO_AF_UART4, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = UART4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +static const struct pios_usart_cfg pios_usart_hkosd_aux_cfg = { + .regs = USART6, + .remap = GPIO_AF_USART6, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART6_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + #if defined(PIOS_INCLUDE_COM) #include @@ -1363,7 +1448,15 @@ static const TIM_TimeBaseInitTypeDef tim_1_time_base = { .TIM_RepetitionCounter = 0x0000, }; -// Set up timers that only have inputs on APB2 +static const TIM_TimeBaseInitTypeDef tim_8_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = 0xFFFF, + .TIM_RepetitionCounter = 0x0000, +}; + +// Set up timers that only have inputs on APB1 static const TIM_TimeBaseInitTypeDef tim_4_time_base = { .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, .TIM_ClockDivision = TIM_CKD_DIV1, @@ -1415,6 +1508,19 @@ static const struct pios_tim_clock_cfg tim_5_cfg = { }, }; +static const struct pios_tim_clock_cfg tim_8_cfg = { + .timer = TIM8, + .time_base_init = &tim_8_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM8_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + static const struct pios_tim_clock_cfg tim_9_cfg = { .timer = TIM9, .time_base_init = &tim_9_10_11_time_base, @@ -1841,6 +1947,52 @@ static const struct pios_ppm_cfg pios_ppm_cfg = { #include "pios_rcvr_priv.h" #endif /* PIOS_INCLUDE_RCVR */ +/* + * SONAR Inputs + */ +#if defined(PIOS_INCLUDE_HCSR04) +#include + +static const struct pios_tim_channel pios_tim_hcsr04_port_all_channels[] = { +{ + .timer = TIM8, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_PuPd = GPIO_PuPd_DOWN + }, + .pin_source = GPIO_PinSource8, + }, + .remap = GPIO_AF_TIM8, +}, +}; + +const struct pios_hcsr04_cfg pios_hcsr04_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + }, + .channels = pios_tim_hcsr04_port_all_channels, + .num_channels = NELEMENTS(pios_tim_hcsr04_port_all_channels), + .trigger = { + .gpio = GPIOD, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, +}; +#endif + #if defined(PIOS_INCLUDE_USB) #include "pios_usb_priv.h" diff --git a/flight/targets/board_hw_defs/revomini/board_hw_defs.c b/flight/targets/board_hw_defs/revomini/board_hw_defs.c index a19e904e2..2e098d86a 100644 --- a/flight/targets/board_hw_defs/revomini/board_hw_defs.c +++ b/flight/targets/board_hw_defs/revomini/board_hw_defs.c @@ -865,6 +865,91 @@ static const struct pios_dsm_cfg pios_dsm_flexi_cfg = { #endif /* PIOS_INCLUDE_DSM */ +/* + * HK OSD + */ +static const struct pios_usart_cfg pios_usart_hkosd_main_cfg = { + .regs = USART1, + .remap = GPIO_AF_USART1, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART1_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = { + .regs = USART3, + .remap = GPIO_AF_USART3, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + #if defined(PIOS_INCLUDE_COM) #include diff --git a/make/boards/osd/board-info.mk b/make/boards/osd/board-info.mk index d82d30319..d93151488 100644 --- a/make/boards/osd/board-info.mk +++ b/make/boards/osd/board-info.mk @@ -20,9 +20,9 @@ BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region # Leave the remaining 16KB and 64KB sectors for other uses FW_BANK_BASE := 0x08020000 # Start of firmware flash -FW_BANK_SIZE := 0x00040000 # Should include FW_DESC_SIZE +FW_BANK_SIZE := 0x00060000 # Should include FW_DESC_SIZE FW_DESC_SIZE := 0x00000064 OSCILLATOR_FREQ := 8000000 -SYSCLK_FREQ := 108000000 \ No newline at end of file +SYSCLK_FREQ := 168000000 diff --git a/shared/uavobjectdefinition/flightstatus.xml b/shared/uavobjectdefinition/flightstatus.xml index 5687feee6..765e15d66 100644 --- a/shared/uavobjectdefinition/flightstatus.xml +++ b/shared/uavobjectdefinition/flightstatus.xml @@ -4,7 +4,7 @@ - + diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 761252f96..61c24d4f1 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -2,19 +2,19 @@ Selection of optional hardware configurations. - - + + - - + + - - + + @@ -24,7 +24,7 @@ - + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index ccb7cb54e..c6a70d5af 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -26,7 +26,7 @@ - + diff --git a/shared/uavobjectdefinition/osdsettings.xml b/shared/uavobjectdefinition/osdsettings.xml index cb3f73b74..0f3151fc3 100644 --- a/shared/uavobjectdefinition/osdsettings.xml +++ b/shared/uavobjectdefinition/osdsettings.xml @@ -14,6 +14,9 @@ + + + diff --git a/shared/uavobjectdefinition/taskinfo.xml b/shared/uavobjectdefinition/taskinfo.xml index 756143693..08181701b 100644 --- a/shared/uavobjectdefinition/taskinfo.xml +++ b/shared/uavobjectdefinition/taskinfo.xml @@ -27,6 +27,8 @@ ModemStat Autotune EventDispatcher + MagBaro + OSDGen @@ -55,6 +57,8 @@ ModemStat Autotune EventDispatcher + MagBaro + OSDGen @@ -87,6 +91,8 @@ ModemStat Autotune EventDispatcher + MagBaro + OSDGen From 5ded8c6dfc678e9f32e666a5bb0560b42cb76635 Mon Sep 17 00:00:00 2001 From: sambas Date: Thu, 28 Mar 2013 18:29:26 +0200 Subject: [PATCH 02/35] VTOL path fixes Flight mode fixes POI mode AutoLand Tests Simple stabilization Shortest way yaw fix GCS map and pathplanner fixes --- flight/Libraries/CoordinateConversions.c | 6 +- flight/Libraries/paths.c | 29 +++- flight/Modules/ManualControl/manualcontrol.c | 53 +++++- flight/Modules/PathPlanner/pathplanner.c | 15 +- .../Modules/Stabilization/inc/relay_tuning.h | 2 +- flight/Modules/Stabilization/relay_tuning.c | 9 +- flight/Modules/Stabilization/stabilization.c | 15 +- .../VtolPathFollower/vtolpathfollower.c | 157 ++++++++++++++++-- flight/targets/RevoMini/UAVObjects.inc | 2 + flight/targets/Revolution/UAVObjects.inc | 2 + .../opmapcontrol/src/mapwidget/gpsitem.cpp | 14 +- .../src/mapwidget/opmapwidget.cpp | 2 + .../opmap/opmap_edit_waypoint_dialog.cpp | 23 +++ .../src/plugins/opmap/opmapgadgetwidget.cpp | 8 +- .../src/plugins/opmap/widgetdelegates.cpp | 2 + .../src/plugins/opmap/widgetdelegates.h | 5 +- .../src/plugins/uavobjects/uavobjects.pro | 4 + .../uavobjectdefinition/poilearnsettings.xml | 10 ++ shared/uavobjectdefinition/poilocation.xml | 12 ++ 19 files changed, 315 insertions(+), 55 deletions(-) create mode 100644 shared/uavobjectdefinition/poilearnsettings.xml create mode 100644 shared/uavobjectdefinition/poilocation.xml diff --git a/flight/Libraries/CoordinateConversions.c b/flight/Libraries/CoordinateConversions.c index fc5032e4e..5347b6edb 100644 --- a/flight/Libraries/CoordinateConversions.c +++ b/flight/Libraries/CoordinateConversions.c @@ -148,9 +148,9 @@ void RPY2Quaternion(const float rpy[3], float q[4]) float phi, theta, psi; float cphi, sphi, ctheta, stheta, cpsi, spsi; - phi = DEG2RAD * rpy[0] / 2; - theta = DEG2RAD * rpy[1] / 2; - psi = DEG2RAD * rpy[2] / 2; + phi = DEG2RAD * rpy[0] / 2.0f; + theta = DEG2RAD * rpy[1] / 2.0f; + psi = DEG2RAD * rpy[2] / 2.0f; cphi = cosf(phi); sphi = sinf(phi); ctheta = cosf(theta); diff --git a/flight/Libraries/paths.c b/flight/Libraries/paths.c index 353ae9b10..d9b7fc389 100644 --- a/flight/Libraries/paths.c +++ b/flight/Libraries/paths.c @@ -176,6 +176,8 @@ static void path_circle(float * start_point, float * end_point, float * cur_poin float radius_north, radius_east, diff_north, diff_east; float radius,cradius; float normal[2]; + float progress; + float a_diff, a_radius; // Radius radius_north = end_point[0] - start_point[0]; @@ -185,8 +187,8 @@ static void path_circle(float * start_point, float * end_point, float * cur_poin diff_north = cur_point[0] - end_point[0]; diff_east = cur_point[1] - end_point[1]; - radius = sqrtf( radius_north * radius_north + radius_east * radius_east ); - cradius = sqrtf( diff_north * diff_north + diff_east * diff_east ); + radius = sqrtf( powf(radius_north,2) + powf(radius_east,2) ); + cradius = sqrtf( powf(diff_north,2) + powf(diff_east,2) ); if (cradius < 1e-6) { // cradius is zero, just fly somewhere and make sure correction is still a normal @@ -209,7 +211,28 @@ static void path_circle(float * start_point, float * end_point, float * cur_poin normal[1] = -diff_north / cradius; } - status->fractional_progress = (clockwise?1:-1) * atan2f( diff_north, diff_east) - atan2f( radius_north, radius_east); + + // normalize progress to 0..1 + a_diff = atan2f( diff_north, diff_east); + a_radius = atan2f( radius_north, radius_east); + + if(a_diff<0) + a_diff+=2*M_PI; + if(a_radius<0) + a_radius+=2*M_PI; + + progress = (a_diff - a_radius + M_PI) / (2 * M_PI); + + if(progress<0) + progress+=1.0; + else if(progress>=1) + progress-=1.0; + + if(clockwise) + { + progress=1-progress; + } + status->fractional_progress = progress; // error is current radius minus wanted radius - positive if too close status->error = radius - cradius; diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 4a4481566..44ca51a06 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -93,6 +93,7 @@ static float inputFiltered[MANUALCONTROLSETTINGS_RESPONSETIME_NUMELEM]; // Private functions static void updateActuatorDesired(ManualControlCommandData * cmd); static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualControlSettingsData * settings); +static void updateLandDesired(ManualControlCommandData * cmd, bool changed); static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed); static void updatePathDesired(ManualControlCommandData * cmd, bool changed, bool home); static void processFlightMode(ManualControlSettingsData * settings, float flightMode); @@ -455,11 +456,18 @@ static void manualControlTask(void *parameters) altitudeHoldDesired(&cmd, lastFlightMode != flightStatus.FlightMode); break; case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: + case FLIGHTSTATUS_FLIGHTMODE_POI: updatePathDesired(&cmd, lastFlightMode != flightStatus.FlightMode, false); break; case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE: updatePathDesired(&cmd, lastFlightMode != flightStatus.FlightMode, true); break; + case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER: + // No need to call anything. This just avoids errors. + break; + case FLIGHTSTATUS_FLIGHTMODE_LAND: + updateLandDesired(&cmd, lastFlightMode != flightStatus.FlightMode); + break; default: AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); } @@ -728,12 +736,12 @@ static void updatePathDesired(ManualControlCommandData * cmd, bool changed,bool PathDesiredData pathDesired; PathDesiredGet(&pathDesired); - pathDesired.Start[PATHDESIRED_END_NORTH] = positionActual.North; - pathDesired.Start[PATHDESIRED_END_EAST] = positionActual.East; - pathDesired.Start[PATHDESIRED_END_DOWN] = positionActual.Down - 10; + pathDesired.Start[PATHDESIRED_START_NORTH] = positionActual.North; + pathDesired.Start[PATHDESIRED_START_EAST] = positionActual.East; + pathDesired.Start[PATHDESIRED_START_DOWN] = positionActual.Down; pathDesired.End[PATHDESIRED_END_NORTH] = positionActual.North; pathDesired.End[PATHDESIRED_END_EAST] = positionActual.East; - pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down - 10; + pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down; pathDesired.StartingVelocity=1; pathDesired.EndingVelocity=0; pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT; @@ -751,6 +759,38 @@ static void updatePathDesired(ManualControlCommandData * cmd, bool changed,bool } } + +static void updateLandDesired(ManualControlCommandData * cmd, bool changed) +{ + static portTickType lastSysTime; + portTickType thisSysTime; + float dT; + + thisSysTime = xTaskGetTickCount(); + dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f; + lastSysTime = thisSysTime; + + PositionActualData positionActual; + PositionActualGet(&positionActual); + + PathDesiredData pathDesired; + PathDesiredGet(&pathDesired); + if(changed) { + // After not being in this mode for a while init at current height + pathDesired.Start[PATHDESIRED_START_NORTH] = positionActual.North; + pathDesired.Start[PATHDESIRED_START_EAST] = positionActual.East; + pathDesired.Start[PATHDESIRED_START_DOWN] = positionActual.Down; + pathDesired.End[PATHDESIRED_END_NORTH] = positionActual.North; + pathDesired.End[PATHDESIRED_END_EAST] = positionActual.East; + pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down; + pathDesired.StartingVelocity=1; + pathDesired.EndingVelocity=0; + pathDesired.Mode = PATHDESIRED_MODE_FLYENDPOINT; + } + pathDesired.End[PATHDESIRED_END_DOWN] = positionActual.Down+5; + PathDesiredSet(&pathDesired); +} + /** * @brief Update the altitude desired to current altitude when * enabled and enable altitude mode for stabilization @@ -804,6 +844,11 @@ static void updatePathDesired(ManualControlCommandData * cmd, bool changed, bool AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); } +static void updateLandDesired(ManualControlCommandData * cmd, bool changed) +{ + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); +} + static void altitudeHoldDesired(ManualControlCommandData * cmd, bool changed) { AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_ERROR); diff --git a/flight/Modules/PathPlanner/pathplanner.c b/flight/Modules/PathPlanner/pathplanner.c index de2fe9184..f6ddbcd44 100644 --- a/flight/Modules/PathPlanner/pathplanner.c +++ b/flight/Modules/PathPlanner/pathplanner.c @@ -238,20 +238,25 @@ void updatePathDesired(UAVObjEvent * ev) { pathDesired.UID = waypointActive.Index; if(waypointActive.Index == 0) { + PositionActualData positionActual; + PositionActualGet(&positionActual); // First waypoint has itself as start point (used to be home position but that proved dangerous when looping) - pathDesired.Start[PATHDESIRED_START_NORTH] = waypoint.Position[WAYPOINT_POSITION_NORTH]; + /*pathDesired.Start[PATHDESIRED_START_NORTH] = waypoint.Position[WAYPOINT_POSITION_NORTH]; pathDesired.Start[PATHDESIRED_START_EAST] = waypoint.Position[WAYPOINT_POSITION_EAST]; - pathDesired.Start[PATHDESIRED_START_DOWN] = waypoint.Position[WAYPOINT_POSITION_DOWN]; + pathDesired.Start[PATHDESIRED_START_DOWN] = waypoint.Position[WAYPOINT_POSITION_DOWN];*/ + pathDesired.Start[PATHDESIRED_START_NORTH] = positionActual.North; + pathDesired.Start[PATHDESIRED_START_EAST] = positionActual.East; + pathDesired.Start[PATHDESIRED_START_DOWN] = positionActual.Down; pathDesired.StartingVelocity = pathDesired.EndingVelocity; } else { // Get previous waypoint as start point WaypointData waypointPrev; WaypointInstGet(waypointActive.Index - 1, &waypointPrev); - pathDesired.Start[PATHDESIRED_END_NORTH] = waypointPrev.Position[WAYPOINT_POSITION_NORTH]; - pathDesired.Start[PATHDESIRED_END_EAST] = waypointPrev.Position[WAYPOINT_POSITION_EAST]; - pathDesired.Start[PATHDESIRED_END_DOWN] = waypointPrev.Position[WAYPOINT_POSITION_DOWN]; + pathDesired.Start[PATHDESIRED_START_NORTH] = waypointPrev.Position[WAYPOINT_POSITION_NORTH]; + pathDesired.Start[PATHDESIRED_START_EAST] = waypointPrev.Position[WAYPOINT_POSITION_EAST]; + pathDesired.Start[PATHDESIRED_START_DOWN] = waypointPrev.Position[WAYPOINT_POSITION_DOWN]; pathDesired.StartingVelocity = waypointPrev.Velocity; } PathDesiredSet(&pathDesired); diff --git a/flight/Modules/Stabilization/inc/relay_tuning.h b/flight/Modules/Stabilization/inc/relay_tuning.h index 9044986c5..2fd69cafa 100644 --- a/flight/Modules/Stabilization/inc/relay_tuning.h +++ b/flight/Modules/Stabilization/inc/relay_tuning.h @@ -36,4 +36,4 @@ int stabilization_relay_rate(float err, float *output, int axis, bool reinit); -#endif \ No newline at end of file +#endif diff --git a/flight/Modules/Stabilization/relay_tuning.c b/flight/Modules/Stabilization/relay_tuning.c index 5d53aa7d3..02081f427 100644 --- a/flight/Modules/Stabilization/relay_tuning.c +++ b/flight/Modules/Stabilization/relay_tuning.c @@ -32,15 +32,11 @@ */ #include "openpilot.h" +#include "stabilization.h" #include "relaytuning.h" #include "relaytuningsettings.h" #include "sin_lookup.h" -//! Private variables -static const int SIN_RESOLUTION = 180; - -#define MAX_AXES 3 - /** * Apply a step function for the stabilization controller and monitor the * result @@ -108,7 +104,7 @@ int stabilization_relay_rate(float error, float *output, int axis, bool reinit) if(phase >= 360) phase = 0; accum_sin += sin_lookup_deg(phase) * error; - accum_cos += sin_lookup_deg(phase + 90) * error; + accum_cos += cos_lookup_deg(phase) * error; accumulated ++; // Make sure we've had enough time since last transition then check for a change in the output @@ -148,4 +144,3 @@ int stabilization_relay_rate(float error, float *output, int axis, bool reinit) return 0; } - diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index 52ccc8f29..6d24eaa9a 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -53,6 +53,9 @@ #include "relay_tuning.h" #include "virtualflybar.h" +// Includes for various stabilization algorithms +#include "relay_tuning.h" + // Private constants #define MAX_QUEUE_SIZE 1 @@ -123,7 +126,6 @@ int32_t StabilizationInitialize() #ifdef DIAG_RATEDESIRED RateDesiredInitialize(); #endif - // Code required for relay tuning sin_lookup_initalize(); RelayTuningSettingsInitialize(); @@ -211,7 +213,12 @@ static void stabilizationTask(void* parameters) float local_error[3] = {stabDesired.Roll - attitudeActual.Roll, stabDesired.Pitch - attitudeActual.Pitch, stabDesired.Yaw - attitudeActual.Yaw}; - local_error[2] = fmodf(local_error[2] + 180, 360) - 180; + // find shortest way + float modulo = fmodf(local_error[2] + 180.0f, 360.0f); + if(modulo<0) + local_error[2] = modulo + 180.0f; + else + local_error[2] = modulo - 180.0f; #endif float gyro_filtered[3]; @@ -277,6 +284,7 @@ static void stabilizationTask(void* parameters) stabilization_virtual_flybar(gyro_filtered[i], rateDesiredAxis[i], &actuatorDesiredAxis[i], dT, reinit, i, &settings); break; + case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING: { if (reinit) @@ -292,6 +300,7 @@ static void stabilizationTask(void* parameters) break; } + case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK: if (reinit) pids[PID_RATE_ROLL + i].iAccumulator = 0; @@ -307,7 +316,7 @@ static void stabilizationTask(void* parameters) rateDesiredAxis[i] = pid_apply(&pids[PID_ROLL + i], axis_lock_accum[i], dT); } - rateDesiredAxis[i] = bound(rateDesiredAxis[i], settings.MaximumRate[i]); + rateDesiredAxis[i] = bound(rateDesiredAxis[i], settings.ManualRate[i]); actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i], gyro_filtered[i], dT); actuatorDesiredAxis[i] = bound(actuatorDesiredAxis[i],1.0f); diff --git a/flight/Modules/VtolPathFollower/vtolpathfollower.c b/flight/Modules/VtolPathFollower/vtolpathfollower.c index 3781f492f..7a6182640 100644 --- a/flight/Modules/VtolPathFollower/vtolpathfollower.c +++ b/flight/Modules/VtolPathFollower/vtolpathfollower.c @@ -70,30 +70,40 @@ #include "velocityactual.h" #include "CoordinateConversions.h" +#include "cameradesired.h" +#include "poilearnsettings.h" +#include "poilocation.h" +#include "accessorydesired.h" + + // Private constants #define MAX_QUEUE_SIZE 4 #define STACK_SIZE_BYTES 1548 #define TASK_PRIORITY (tskIDLE_PRIORITY+2) #define F_PI 3.14159265358979323846f #define DEG2RAD (F_PI/180.0f) +#define RAD2DEG(rad) ((rad)*(180.0f/F_PI)) // Private types // Private variables static xTaskHandle pathfollowerTaskHandle; static PathDesiredData pathDesired; +static PathStatusData pathStatus; static VtolPathFollowerSettingsData vtolpathfollowerSettings; // Private functions static void vtolPathFollowerTask(void *parameters); static void SettingsUpdatedCb(UAVObjEvent * ev); static void updateNedAccel(); +static void updatePOIBearing(); static void updatePathVelocity(); static void updateEndpointVelocity(); static void updateFixedAttitude(float* attitude); -static void updateVtolDesiredAttitude(); +static void updateVtolDesiredAttitude(bool yaw_attitude); static float bound(float val, float min, float max); static bool vtolpathfollower_enabled; +static void accessoryUpdated(UAVObjEvent* ev); /** * Initialise the module, called on startup @@ -126,6 +136,10 @@ int32_t VtolPathFollowerInitialize() PathDesiredInitialize(); PathStatusInitialize(); VelocityDesiredInitialize(); + CameraDesiredInitialize(); + AccessoryDesiredInitialize(); + PoiLearnSettingsInitialize(); + PoiLocationInitialize(); vtolpathfollower_enabled = true; } else { vtolpathfollower_enabled = false; @@ -152,12 +166,12 @@ static void vtolPathFollowerTask(void *parameters) { SystemSettingsData systemSettings; FlightStatusData flightStatus; - PathStatusData pathStatus; portTickType lastUpdateTime; VtolPathFollowerSettingsConnectCallback(SettingsUpdatedCb); PathDesiredConnectCallback(SettingsUpdatedCb); + AccessoryDesiredConnectCallback(accessoryUpdated); VtolPathFollowerSettingsGet(&vtolpathfollowerSettings); PathDesiredGet(&pathDesired); @@ -200,11 +214,12 @@ static void vtolPathFollowerTask(void *parameters) // Check the combinations of flightmode and pathdesired mode switch(flightStatus.FlightMode) { + case FLIGHTSTATUS_FLIGHTMODE_LAND: case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: case FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE: if (pathDesired.Mode == PATHDESIRED_MODE_FLYENDPOINT) { updateEndpointVelocity(); - updateVtolDesiredAttitude(); + updateVtolDesiredAttitude(false); AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_OK); } else { AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_ERROR); @@ -216,15 +231,11 @@ static void vtolPathFollowerTask(void *parameters) switch(pathDesired.Mode) { // TODO: Make updateVtolDesiredAttitude and velocity report success and update PATHSTATUS_STATUS accordingly case PATHDESIRED_MODE_FLYENDPOINT: - updateEndpointVelocity(); - updateVtolDesiredAttitude(); - AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_OK); - break; case PATHDESIRED_MODE_FLYVECTOR: case PATHDESIRED_MODE_FLYCIRCLERIGHT: case PATHDESIRED_MODE_FLYCIRCLELEFT: updatePathVelocity(); - updateVtolDesiredAttitude(); + updateVtolDesiredAttitude(false); AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_OK); break; case PATHDESIRED_MODE_FIXEDATTITUDE: @@ -239,6 +250,16 @@ static void vtolPathFollowerTask(void *parameters) AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_ERROR); break; } + PathStatusSet(&pathStatus); + break; + case FLIGHTSTATUS_FLIGHTMODE_POI: + if (pathDesired.Mode == PATHDESIRED_MODE_FLYENDPOINT) { + updateEndpointVelocity(); + updateVtolDesiredAttitude(true); + updatePOIBearing(); + } else { + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE,SYSTEMALARMS_ALARM_ERROR); + } break; default: // Be cleaner and get rid of global variables @@ -262,6 +283,54 @@ static void vtolPathFollowerTask(void *parameters) } } +/** + * Compute bearing and elevation between current position and POI + */ +static void updatePOIBearing() +{ + PositionActualData positionActual; + PositionActualGet(&positionActual); + CameraDesiredData cameraDesired; + CameraDesiredGet(&cameraDesired); + StabilizationDesiredData stabDesired; + StabilizationDesiredGet(&stabDesired); + PoiLocationData poi; + PoiLocationGet(&poi); + //use poi here + //HomeLocationData poi; + //HomeLocationGet (&poi); + + float dLoc[3]; + float yaw=0; + float elevation=0; + + dLoc[0]=positionActual.North-poi.North; + dLoc[1]=positionActual.East-poi.East; + dLoc[2]=positionActual.Down-poi.Down; + + if(dLoc[1]<0) + yaw=RAD2DEG(atan2f(dLoc[1],dLoc[0]))+180; + else + yaw=RAD2DEG(atan2f(dLoc[1],dLoc[0]))-180; + + // distance + float distance = sqrtf(powf(dLoc[0],2)+powf(dLoc[1],2)); + + //not above + if(distance!=0) { + //You can feed this into camerastabilization + elevation=RAD2DEG(atan2f(dLoc[2],distance)); + } + stabDesired.Yaw=yaw; + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + cameraDesired.Yaw=yaw; + cameraDesired.PitchOrServo2=elevation; + + CameraDesiredSet(&cameraDesired); + StabilizationDesiredSet(&stabDesired); +} + + /** * Compute desired velocity from the current position and path * @@ -280,11 +349,31 @@ static void updatePathVelocity() struct path_status progress; path_progress(pathDesired.Start, pathDesired.End, cur, &progress, pathDesired.Mode); - - float groundspeed = pathDesired.StartingVelocity + - (pathDesired.EndingVelocity - pathDesired.StartingVelocity) * bound ( progress.fractional_progress,0,1); - if(progress.fractional_progress > 1) - groundspeed = 0; + + float groundspeed; + switch (pathDesired.Mode) { + case PATHDESIRED_MODE_FLYCIRCLERIGHT: + case PATHDESIRED_MODE_DRIVECIRCLERIGHT: + case PATHDESIRED_MODE_FLYCIRCLELEFT: + case PATHDESIRED_MODE_DRIVECIRCLELEFT: + groundspeed = pathDesired.EndingVelocity; + break; + case PATHDESIRED_MODE_FLYENDPOINT: + case PATHDESIRED_MODE_DRIVEENDPOINT: + groundspeed = pathDesired.EndingVelocity - pathDesired.EndingVelocity * + bound(progress.fractional_progress,0,1); + if(progress.fractional_progress > 1) + groundspeed = 0; + break; + case PATHDESIRED_MODE_FLYVECTOR: + case PATHDESIRED_MODE_DRIVEVECTOR: + default: + groundspeed = pathDesired.StartingVelocity + (pathDesired.EndingVelocity - pathDesired.StartingVelocity) * + bound(progress.fractional_progress,0,1); + if(progress.fractional_progress > 1) + groundspeed = 0; + break; + } VelocityDesiredData velocityDesired; velocityDesired.North = progress.path_direction[0] * groundspeed; @@ -314,6 +403,10 @@ static void updatePathVelocity() -vtolpathfollowerSettings.VerticalVelMax, vtolpathfollowerSettings.VerticalVelMax); + // update pathstatus + pathStatus.error = progress.error; + pathStatus.fractional_progress = progress.fractional_progress; + VelocityDesiredSet(&velocityDesired); } @@ -332,7 +425,7 @@ void updateEndpointVelocity() PositionActualGet(&positionActual); VelocityDesiredGet(&velocityDesired); - + float northError; float eastError; float downError; @@ -435,7 +528,7 @@ static void updateFixedAttitude(float* attitude) * NED frame as the feedback term and then compares the * @ref VelocityActual against the @ref VelocityDesired */ -static void updateVtolDesiredAttitude() +static void updateVtolDesiredAttitude(bool yaw_attitude) { float dT = vtolpathfollowerSettings.UpdatePeriod / 1000.0f; @@ -501,7 +594,6 @@ static void updateVtolDesiredAttitude() // Testing code - refactor into manual control command ManualControlCommandData manualControlData; ManualControlCommandGet(&manualControlData); - stabDesired.Yaw = stabSettings.MaximumRate[STABILIZATIONSETTINGS_MAXIMUMRATE_YAW] * manualControlData.Yaw; // Compute desired north command northError = velocityDesired.North - northVel; @@ -554,8 +646,12 @@ static void updateVtolDesiredAttitude() stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; - stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK; - + if(yaw_attitude) { + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + } else { + stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK; + stabDesired.Yaw = stabSettings.MaximumRate[STABILIZATIONSETTINGS_MAXIMUMRATE_YAW] * manualControlData.Yaw; + } StabilizationDesiredSet(&stabDesired); } @@ -618,3 +714,28 @@ static void SettingsUpdatedCb(UAVObjEvent * ev) PathDesiredGet(&pathDesired); } +static void accessoryUpdated(UAVObjEvent* ev) +{ + if (ev->obj != AccessoryDesiredHandle()) + return; + + PositionActualData positionActual; + PositionActualGet(&positionActual); + AccessoryDesiredData accessory; + PoiLearnSettingsData poiLearn; + PoiLearnSettingsGet(&poiLearn); + PoiLocationData poi; + PoiLocationGet(&poi); + if (poiLearn.Input != POILEARNSETTINGS_INPUT_NONE) { + if (AccessoryDesiredInstGet(poiLearn.Input - POILEARNSETTINGS_INPUT_ACCESSORY0, &accessory) == 0) { + if(accessory.AccessoryVal<-0.5f) + { + poi.North=positionActual.North; + poi.East=positionActual.East; + poi.Down=positionActual.Down; + PoiLocationSet(&poi); + } + } + } +} + diff --git a/flight/targets/RevoMini/UAVObjects.inc b/flight/targets/RevoMini/UAVObjects.inc index 56f708ebe..f750288c0 100644 --- a/flight/targets/RevoMini/UAVObjects.inc +++ b/flight/targets/RevoMini/UAVObjects.inc @@ -89,6 +89,8 @@ UAVOBJSRCFILENAMES += altitudeholdsettings UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRCFILENAMES += waypoint UAVOBJSRCFILENAMES += waypointactive +UAVOBJSRCFILENAMES += poilocation +UAVOBJSRCFILENAMES += poilearnsettings UAVOBJSRCFILENAMES += mpu6000settings UAVOBJSRCFILENAMES += txpidsettings diff --git a/flight/targets/Revolution/UAVObjects.inc b/flight/targets/Revolution/UAVObjects.inc index 1d7b592f8..f025cd9ea 100644 --- a/flight/targets/Revolution/UAVObjects.inc +++ b/flight/targets/Revolution/UAVObjects.inc @@ -94,6 +94,8 @@ UAVOBJSRCFILENAMES += altitudeholdsettings UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRCFILENAMES += waypoint UAVOBJSRCFILENAMES += waypointactive +UAVOBJSRCFILENAMES += poilocation +UAVOBJSRCFILENAMES += poilearnsettings UAVOBJSRCFILENAMES += mpu6000settings UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp index 07d75da2a..358ba5ed7 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/gpsitem.cpp @@ -28,7 +28,7 @@ #include "gpsitem.h" namespace mapcontrol { - GPSItem::GPSItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(5),traildistance(50),autosetreached(true) + GPSItem::GPSItem(MapGraphicItem* map,OPMapWidget* parent,QString uavPic):map(map),mapwidget(parent),showtrail(true),showtrailline(true),trailtime(1),traildistance(2),autosetreached(true) ,autosetdistance(100) { pic.load(uavPic); @@ -42,8 +42,10 @@ namespace mapcontrol trailLine=new QGraphicsItemGroup(this); trailLine->setParentItem(map); this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); + setCacheMode(QGraphicsItem::ItemCoordinateCache); mapfollowtype=UAVMapFollowType::None; - trailtype=UAVTrailType::ByDistance; + //trailtype=UAVTrailType::ByDistance; + trailtype=UAVTrailType::ByTimeElapsed; timer.start(); connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); @@ -74,12 +76,12 @@ namespace mapcontrol { if(timer.elapsed()>trailtime*1000) { - TrailItem * ob=new TrailItem(position,altitude,Qt::green,map); + TrailItem * ob=new TrailItem(position,altitude,Qt::red,map); trail->addToGroup(ob); connect(this,SIGNAL(setChildPosition()),ob,SLOT(setPosSLOT())); if(!lasttrailline.IsEmpty()) { - TrailLineItem * obj=new TrailLineItem(lasttrailline,position,Qt::red,map); + TrailLineItem * obj=new TrailLineItem(lasttrailline,position,Qt::green,map); trailLine->addToGroup(obj); connect(this,SIGNAL(setChildLine()),obj,SLOT(setLineSlot())); } @@ -92,12 +94,12 @@ namespace mapcontrol { if(qAbs(internals::PureProjection::DistanceBetweenLatLng(lastcoord,position)*1000)>traildistance) { - TrailItem * ob=new TrailItem(position,altitude,Qt::green,map); + TrailItem * ob=new TrailItem(position,altitude,Qt::red,map); trail->addToGroup(ob); connect(this,SIGNAL(setChildPosition()),ob,SLOT(setPosSLOT())); if(!lasttrailline.IsEmpty()) { - TrailLineItem * obj=new TrailLineItem(lasttrailline,position,Qt::red,map); + TrailLineItem * obj=new TrailLineItem(lasttrailline,position,Qt::green,map); trailLine->addToGroup(obj); connect(this,SIGNAL(setChildLine()),obj,SLOT(setLineSlot())); } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp index bdc60225d..ea477adde 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/opmapwidget.cpp @@ -80,6 +80,7 @@ namespace mapcontrol if(GPS!=0) { + GPS->DeleteTrail(); delete GPS; GPS=0; } @@ -93,6 +94,7 @@ namespace mapcontrol { GPS=new GPSItem(map,this); GPS->setParentItem(map); + GPS->setOpacity(overlayOpacity); setOverlayOpacity(overlayOpacity); } } diff --git a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp index 2aef32311..57dbaa550 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmap_edit_waypoint_dialog.cpp @@ -200,6 +200,17 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Relative Distance(0=complete,1=just starting)"); break; + case MapDataDelegate::ENDCONDITION_BELOWERROR: + ui->condParam1->setVisible(true); + ui->condParam2->setVisible(false); + ui->condParam3->setVisible(false); + ui->condParam4->setVisible(false); + ui->dsb_condParam1->setVisible(true); + ui->dsb_condParam2->setVisible(false); + ui->dsb_condParam3->setVisible(false); + ui->dsb_condParam4->setVisible(false); + ui->condParam1->setText("error margin (in m)"); + break; case MapDataDelegate::ENDCONDITION_ABOVEALTITUDE: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); @@ -211,6 +222,18 @@ void opmap_edit_waypoint_dialog::setupConditionWidgets() ui->dsb_condParam4->setVisible(false); ui->condParam1->setText("Altitude in meters (negative)"); break; + case MapDataDelegate::ENDCONDITION_ABOVESPEED: + ui->condParam1->setVisible(true); + ui->condParam2->setVisible(true); + ui->condParam3->setVisible(false); + ui->condParam4->setVisible(false); + ui->dsb_condParam1->setVisible(true); + ui->dsb_condParam2->setVisible(true); + ui->dsb_condParam3->setVisible(false); + ui->dsb_condParam4->setVisible(false); + ui->condParam1->setText("Speed in meters/second"); + ui->condParam2->setText("flag: 0=groundspeed 1=airspeed"); + break; case MapDataDelegate::ENDCONDITION_POINTINGTOWARDSNEXT: ui->condParam1->setVisible(true); ui->condParam2->setVisible(false); diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 0d9639e38..223343ec4 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -24,6 +24,7 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#define USE_PATHPLANNER #include "opmapgadgetwidget.h" #include "ui_opmap_widget.h" @@ -546,8 +547,8 @@ void OPMapGadgetWidget::closeEvent(QCloseEvent *event) */ void OPMapGadgetWidget::updatePosition() { - double uav_latitude, uav_longitude, uav_altitude, uav_yaw; - double gps_latitude, gps_longitude, gps_altitude, gps_heading; + double uav_latitude, uav_longitude, uav_altitude, uav_yaw; + double gps_latitude, gps_longitude, gps_altitude, gps_heading; internals::PointLatLng uav_pos; internals::PointLatLng gps_pos; @@ -581,7 +582,7 @@ void OPMapGadgetWidget::updatePosition() gps_longitude = gpsPositionData.Longitude; gps_altitude = gpsPositionData.Altitude; - gps_pos = internals::PointLatLng(gps_latitude, gps_longitude); + gps_pos = internals::PointLatLng(gps_latitude*1e-7, gps_longitude*1e-7); //********************** // get the current position and heading estimates @@ -643,6 +644,7 @@ void OPMapGadgetWidget::updatePosition() { m_map->GPS->SetUAVPos(gps_pos, gps_altitude); // set the maps GPS position m_map->GPS->SetUAVHeading(gps_heading); // set the maps GPS heading + m_map->GPS->update(); } m_map->UAV->updateTextOverlay(); m_map->UAV->update(); diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp index 7bd385842..fd44550a6 100644 --- a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.cpp @@ -121,7 +121,9 @@ void MapDataDelegate::loadComboBox(QComboBox *combo, flightDataModel::pathPlanDa combo->addItem("Timeout",ENDCONDITION_TIMEOUT); combo->addItem("Distance to tgt",ENDCONDITION_DISTANCETOTARGET); combo->addItem("Leg remaining",ENDCONDITION_LEGREMAINING); + combo->addItem("Below Error",ENDCONDITION_BELOWERROR); combo->addItem("Above Altitude",ENDCONDITION_ABOVEALTITUDE); + combo->addItem("Above Speed",ENDCONDITION_ABOVESPEED); combo->addItem("Pointing towards next",ENDCONDITION_POINTINGTOWARDSNEXT); combo->addItem("Python script",ENDCONDITION_PYTHONSCRIPT); combo->addItem("Immediate",ENDCONDITION_IMMEDIATE); diff --git a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h index ae29bc975..53aac4887 100644 --- a/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h +++ b/ground/openpilotgcs/src/plugins/opmap/widgetdelegates.h @@ -41,8 +41,9 @@ class MapDataDelegate : public QItemDelegate MODE_DRIVEENDPOINT=4, MODE_DRIVEVECTOR=5, MODE_DRIVECIRCLELEFT=6, MODE_DRIVECIRCLERIGHT=7, MODE_FIXEDATTITUDE=8, MODE_SETACCESSORY=9, MODE_DISARMALARM=10 } ModeOptions; typedef enum { ENDCONDITION_NONE=0, ENDCONDITION_TIMEOUT=1, ENDCONDITION_DISTANCETOTARGET=2, - ENDCONDITION_LEGREMAINING=3, ENDCONDITION_ABOVEALTITUDE=4, ENDCONDITION_POINTINGTOWARDSNEXT=5, - ENDCONDITION_PYTHONSCRIPT=6, ENDCONDITION_IMMEDIATE=7 } EndConditionOptions; + ENDCONDITION_LEGREMAINING=3, ENDCONDITION_BELOWERROR=4, ENDCONDITION_ABOVEALTITUDE=5, + ENDCONDITION_ABOVESPEED=6, ENDCONDITION_POINTINGTOWARDSNEXT=7, ENDCONDITION_PYTHONSCRIPT=8, + ENDCONDITION_IMMEDIATE=9 } EndConditionOptions; typedef enum { COMMAND_ONCONDITIONNEXTWAYPOINT=0, COMMAND_ONNOTCONDITIONNEXTWAYPOINT=1, COMMAND_ONCONDITIONJUMPWAYPOINT=2, COMMAND_ONNOTCONDITIONJUMPWAYPOINT=3, COMMAND_IFCONDITIONJUMPWAYPOINTELSENEXTWAYPOINT=4 } CommandOptions; diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index 5b61364fc..42536c390 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -95,6 +95,8 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/txpidsettings.h \ $$UAVOBJECT_SYNTHETICS/cameradesired.h \ $$UAVOBJECT_SYNTHETICS/faultsettings.h \ + $$UAVOBJECT_SYNTHETICS/poilearnsettings.h \ + $$UAVOBJECT_SYNTHETICS/poilocation.h \ $$UAVOBJECT_SYNTHETICS/oplinksettings.h \ $$UAVOBJECT_SYNTHETICS/oplinkstatus.h \ $$UAVOBJECT_SYNTHETICS/osdsettings.h \ @@ -175,6 +177,8 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/txpidsettings.cpp \ $$UAVOBJECT_SYNTHETICS/cameradesired.cpp \ $$UAVOBJECT_SYNTHETICS/faultsettings.cpp \ + $$UAVOBJECT_SYNTHETICS/poilearnsettings.cpp \ + $$UAVOBJECT_SYNTHETICS/poilocation.cpp \ $$UAVOBJECT_SYNTHETICS/oplinksettings.cpp \ $$UAVOBJECT_SYNTHETICS/oplinkstatus.cpp \ $$UAVOBJECT_SYNTHETICS/osdsettings.cpp \ diff --git a/shared/uavobjectdefinition/poilearnsettings.xml b/shared/uavobjectdefinition/poilearnsettings.xml new file mode 100644 index 000000000..281d064e3 --- /dev/null +++ b/shared/uavobjectdefinition/poilearnsettings.xml @@ -0,0 +1,10 @@ + + + Settings for the @ref Point of Interest feature + + + + + + + diff --git a/shared/uavobjectdefinition/poilocation.xml b/shared/uavobjectdefinition/poilocation.xml new file mode 100644 index 000000000..70022a86a --- /dev/null +++ b/shared/uavobjectdefinition/poilocation.xml @@ -0,0 +1,12 @@ + + + Contains the current Point of interest relative to @ref HomeLocation + + + + + + + + + From c60a750d963841819332037302fcfe4a5ff8eeb7 Mon Sep 17 00:00:00 2001 From: sambas Date: Thu, 28 Mar 2013 18:30:14 +0200 Subject: [PATCH 03/35] AeroSimRC plugin fixes and updates --- .../aerosimrc/src/resources/cc_plugin.ini | 2 +- .../src/plugins/hitl/aerosimrcsimulator.cpp | 60 +++++++++++++++---- .../src/plugins/hitl/hitloptionspage.ui | 2 +- 3 files changed, 50 insertions(+), 14 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_plugin.ini b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_plugin.ini index 8b4174f60..555ee0aa7 100644 --- a/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_plugin.ini +++ b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_plugin.ini @@ -25,7 +25,7 @@ cc_channel_6 = Ch13-FPV-Tilt ;cc_channel_10= ; Control TX or RX (before or after mixes) -send_to = RX +send_to = TX [Output] diff --git a/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp b/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp index aedf3e909..2e1c55659 100644 --- a/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp @@ -71,13 +71,48 @@ void AeroSimRCSimulator::transmitUpdate() channels[i] = out; } + ActuatorDesired::DataFields actData; + FlightStatus::DataFields flightStatusData = flightStatus->getData(); + ManualControlCommand::DataFields manCtrlData = manCtrlCommand->getData(); + float roll = -1; + float pitch = -1; + float yaw = -1; + float throttle = -1; + + if(flightStatusData.FlightMode == FlightStatus::FLIGHTMODE_MANUAL) + { + // Read joystick input + if(flightStatusData.Armed == FlightStatus::ARMED_ARMED) + { + // Note: Pitch sign is reversed in FG ? + roll = manCtrlData.Roll; + pitch = -manCtrlData.Pitch; + yaw = manCtrlData.Yaw; + throttle = manCtrlData.Throttle; + } + } + else + { + // Read ActuatorDesired from autopilot + actData = actDesired->getData(); + + roll = actData.Roll; + pitch = -actData.Pitch; + yaw = actData.Yaw; + throttle = (actData.Throttle*2.0)-1.0; + } + channels[0]=roll; + channels[1]=pitch; + if(throttle<-1) + throttle=-1; + channels[2]=throttle; + channels[3]=yaw; + // read flight status - FlightStatus::DataFields flightData; - flightData = flightStatus->getData(); quint8 armed; quint8 mode; - armed = flightData.Armed; - mode = flightData.FlightMode; + armed = flightStatusData.Armed; + mode = flightStatusData.FlightMode; QByteArray data; // 50 - current size of values, 4(quint32) + 10*4(float) + 2(quint8) + 4(quint32) @@ -132,8 +167,9 @@ void AeroSimRCSimulator::processUpdate(const QByteArray &data) posX, posY, posZ, // world velX, velY, velZ, // world angX, angY, angZ, // model - accX, accY, accZ, // model - lat, lon, agl, // world + accX, accY, accZ; // model + qreal lat, lon; + float agl, // world yaw, pitch, roll, // model volt, curr, rx, ry, rz, fx, fy, fz, ux, uy, uz, // matrix @@ -209,13 +245,13 @@ void AeroSimRCSimulator::processUpdate(const QByteArray &data) out.groundspeed = qSqrt(velX * velX + velY * velY); /**********************************************************************************************/ - out.dstN = posY * 100; - out.dstE = posX * 100; - out.dstD = posZ * -100; + out.dstN = posY * 1; + out.dstE = posX * 1; + out.dstD = posZ * -1; - out.velDown = velY * 100; - out.velEast = velX * 100; - out.velDown = velZ * 100; //WHY ISN'T THIS `-velZ`??? + out.velNorth = velY * 1; + out.velEast = velX * 1; + out.velDown = velZ * -1; updateUAVOs(out); diff --git a/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.ui b/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.ui index 4b8d6e6e5..543feff6a 100644 --- a/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.ui +++ b/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.ui @@ -809,7 +809,7 @@ - false + true BaroAltitude From 1823135573cf2af61ab09fe70b8aff9b5bb0d7f4 Mon Sep 17 00:00:00 2001 From: sambas Date: Thu, 28 Mar 2013 18:32:25 +0200 Subject: [PATCH 04/35] Android Map widget tests gitignore eclipse .metadata --- .gitignore | 1 + androidgcs/res/layout/mycustommapview.xml | 38 ++++ androidgcs/res/menu/map_menu.xml | 9 + androidgcs/res/values/strings.xml | 3 + .../org/openpilot/androidgcs/Controller.java | 4 +- .../openpilot/androidgcs/MyCustomMapView.java | 121 +++++++++++ .../org/openpilot/androidgcs/UAVLocation.java | 189 +++++++++++++++++- 7 files changed, 354 insertions(+), 11 deletions(-) create mode 100644 androidgcs/res/layout/mycustommapview.xml create mode 100644 androidgcs/res/menu/map_menu.xml create mode 100644 androidgcs/src/org/openpilot/androidgcs/MyCustomMapView.java diff --git a/.gitignore b/.gitignore index 06eca8f32..5e5455b43 100644 --- a/.gitignore +++ b/.gitignore @@ -52,3 +52,4 @@ openpilotgcs-build-desktop /androidgcs/gen/ /.cproject /.project +/.metadata diff --git a/androidgcs/res/layout/mycustommapview.xml b/androidgcs/res/layout/mycustommapview.xml new file mode 100644 index 000000000..0bfdf9842 --- /dev/null +++ b/androidgcs/res/layout/mycustommapview.xml @@ -0,0 +1,38 @@ + + + + + + + + + diff --git a/androidgcs/res/menu/map_menu.xml b/androidgcs/res/menu/map_menu.xml new file mode 100644 index 000000000..77de36c5b --- /dev/null +++ b/androidgcs/res/menu/map_menu.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/androidgcs/res/values/strings.xml b/androidgcs/res/values/strings.xml index 37e54515a..fc6237377 100644 --- a/androidgcs/res/values/strings.xml +++ b/androidgcs/res/values/strings.xml @@ -32,6 +32,9 @@ Alarms TxRate: RxRate: + Latitude: + Longitude: + Altitude: Tester 3DView Tuning diff --git a/androidgcs/src/org/openpilot/androidgcs/Controller.java b/androidgcs/src/org/openpilot/androidgcs/Controller.java index 32b9e2655..a4bad8ee7 100644 --- a/androidgcs/src/org/openpilot/androidgcs/Controller.java +++ b/androidgcs/src/org/openpilot/androidgcs/Controller.java @@ -66,12 +66,14 @@ public class Controller extends ObjectManagerActivity { private boolean leftJoystickHeld, rightJoystickHeld; Timer sendTimer = new Timer(); - + TextView manualView; + /** Called when the activity is first created. */ @Override public void onCreate(Bundle savedInstanceState) { super.onCreate(savedInstanceState); setContentView(R.layout.controller); + manualView = (TextView) findViewById(R.id.manualControlValues); } Observer settingsUpdated = new Observer() { diff --git a/androidgcs/src/org/openpilot/androidgcs/MyCustomMapView.java b/androidgcs/src/org/openpilot/androidgcs/MyCustomMapView.java new file mode 100644 index 000000000..8ba53d168 --- /dev/null +++ b/androidgcs/src/org/openpilot/androidgcs/MyCustomMapView.java @@ -0,0 +1,121 @@ +package org.openpilot.androidgcs; + +import java.util.Timer; +import java.util.TimerTask; + +import com.google.android.maps.GeoPoint; +import com.google.android.maps.MapView; + +import android.content.Context; +import android.util.AttributeSet; +import android.view.MotionEvent; + +public class MyCustomMapView extends MapView { + + // Define the interface we will interact with from our Map +public interface OnLongpressListener { + public void onLongpress(MapView view, GeoPoint longpressLocation); +} + +/** + * Time in ms before the OnLongpressListener is triggered. + */ +static final int LONGPRESS_THRESHOLD = 500; + +/** + * Keep a record of the center of the map, to know if the map + * has been panned. + */ +private GeoPoint lastMapCenter; + +private Timer longpressTimer = new Timer(); +private MyCustomMapView.OnLongpressListener longpressListener; + + +public MyCustomMapView(Context context, String apiKey) { + super(context, apiKey); +} + +public MyCustomMapView(Context context, AttributeSet attrs) { + super(context, attrs); +} + +public MyCustomMapView(Context context, AttributeSet attrs, int defStyle) { + super(context, attrs, defStyle); +} + +public void setOnLongpressListener(MyCustomMapView.OnLongpressListener listener) { + longpressListener = listener; +} + +/** + * This method is called every time user touches the map, + * drags a finger on the map, or removes finger from the map. + */ +@Override +public boolean onTouchEvent(MotionEvent event) { + handleLongpress(event); + + return super.onTouchEvent(event); +} + +/** + * This method takes MotionEvents and decides whether or not + * a longpress has been detected. This is the meat of the + * OnLongpressListener. + * + * The Timer class executes a TimerTask after a given time, + * and we start the timer when a finger touches the screen. + * + * We then listen for map movements or the finger being + * removed from the screen. If any of these events occur + * before the TimerTask is executed, it gets cancelled. Else + * the listener is fired. + * + * @param event + */ +private void handleLongpress(final MotionEvent event) { + + if (event.getAction() == MotionEvent.ACTION_DOWN) { + // Finger has touched screen. + longpressTimer = new Timer(); + longpressTimer.schedule(new TimerTask() { + @Override + public void run() { + GeoPoint longpressLocation = getProjection().fromPixels((int)event.getX(), + (int)event.getY()); + + /* + * Fire the listener. We pass the map location + * of the longpress as well, in case it is needed + * by the caller. + */ + longpressListener.onLongpress(MyCustomMapView.this, longpressLocation); + } + + }, LONGPRESS_THRESHOLD); + + lastMapCenter = getMapCenter(); + } + + if (event.getAction() == MotionEvent.ACTION_MOVE) { + + if (!getMapCenter().equals(lastMapCenter)) { + // User is panning the map, this is no longpress + longpressTimer.cancel(); + } + + lastMapCenter = getMapCenter(); + } + + if (event.getAction() == MotionEvent.ACTION_UP) { + // User has removed finger from map. + longpressTimer.cancel(); + } + + if (event.getPointerCount() > 1) { + // This is a multitouch event, probably zooming. + longpressTimer.cancel(); + } +} +} diff --git a/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java b/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java index 6ee1bdbcd..cddad46f7 100644 --- a/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java +++ b/androidgcs/src/org/openpilot/androidgcs/UAVLocation.java @@ -49,13 +49,22 @@ import android.graphics.BitmapFactory; import android.graphics.Canvas; import android.graphics.Paint; import android.graphics.Point; +import android.location.Location; +import android.location.LocationListener; +import android.location.LocationManager; import android.os.Bundle; import android.os.Handler; import android.os.IBinder; import android.util.Log; +import android.view.ContextMenu; +import android.view.ContextMenu.ContextMenuInfo; import android.view.Menu; import android.view.MenuInflater; import android.view.MenuItem; +import android.view.KeyEvent; +import android.view.View; +import android.widget.TextView; +import android.widget.Toast; import com.google.android.maps.GeoPoint; import com.google.android.maps.MapActivity; @@ -72,9 +81,11 @@ public class UAVLocation extends MapActivity // private static boolean WARN = LOGLEVEL > 1; private static boolean DEBUG = LOGLEVEL > 0; - private MapView mapView; + //private MapView mapView; + private MyCustomMapView mapView; private MapController mapController; - + private GeoPoint mContextMenuGeoPoint = null; + UAVObjectManager objMngr; boolean mBound = false; boolean mConnected = false; @@ -84,23 +95,37 @@ public class UAVLocation extends MapActivity GeoPoint homeLocation; GeoPoint uavLocation; + boolean towerEnabled; + boolean gpsEnabled; + + LocationManager gpsLocationManager; + LocationManager towerLocationManager; + MyLocationListener gpsLocationListener; + MyLocationListener towerLocationListener; + private TextView myLongitude, myLatitude, myAltitude; + @Override public void onCreate(Bundle icicle) { - super.onCreate(icicle); - setContentView(R.layout.map_layout); - mapView = (MapView)findViewById(R.id.map_view); + super.onCreate(icicle); + setContentView(R.layout.mycustommapview); + mapView = (MyCustomMapView)findViewById(R.id.mapview); mapController = mapView.getController(); + registerForContextMenu(mapView); mapView.displayZoomControls(true); Double lat = 37.422006*1E6; Double lng = -122.084095*1E6; homeLocation = new GeoPoint(lat.intValue(), lng.intValue()); uavLocation = homeLocation; - mapController.setCenter(homeLocation); - mapController.setZoom(18); + //mapController.setCenter(homeLocation); + mapController.setZoom(16); List overlays = mapView.getOverlays(); UAVOverlay myOverlay = new UAVOverlay(); overlays.add(myOverlay); + + myLongitude = (TextView)findViewById(R.id.longitude); + myLatitude = (TextView)findViewById(R.id.latitude); + myAltitude = (TextView)findViewById(R.id.altitude); MyLocationOverlay myLocationOverlay = new MyLocationOverlay(this, mapView); myLocationOverlay.enableMyLocation(); @@ -108,15 +133,159 @@ public class UAVLocation extends MapActivity overlays.add(myLocationOverlay); mapView.postInvalidate(); + gpsLocationListener = new MyLocationListener(); + towerLocationListener = new MyLocationListener(); + gpsLocationManager = (LocationManager) getSystemService(Context.LOCATION_SERVICE); + towerLocationManager = (LocationManager) getSystemService(Context.LOCATION_SERVICE); + CheckTowerAndGpsStatus(); + if(gpsEnabled) + { + gpsLocationManager.requestLocationUpdates( LocationManager.GPS_PROVIDER, 0, 0, gpsLocationListener); + + //Get the current location in start-up + Location last = gpsLocationManager.getLastKnownLocation(LocationManager.GPS_PROVIDER); + if(last != null) + { + GeoPoint initGeoPoint = new GeoPoint( + (int)(last.getLatitude()*1000000), + (int)(last.getLongitude()*1000000)); + CenterLocation(initGeoPoint,(last.getAltitude())); + } + } + mapView.setOnLongpressListener(new MyCustomMapView.OnLongpressListener() { + public void onLongpress(final MapView view, final GeoPoint longpressLocation) { + mContextMenuGeoPoint = longpressLocation; + runOnUiThread(new Runnable() { + public void run() { + // Insert your longpress action here + //Toast.makeText(mapView.getContext(), "You pressed here: Lat:", Toast.LENGTH_LONG).show(); + openContextMenu(view); + } + }); + } + }); + } + + private void CenterLocation(GeoPoint centerGeoPoint, double Altitude) + { + mapController.animateTo(centerGeoPoint); + + + myLongitude.setText("Longitude: "+ + String.valueOf((float)centerGeoPoint.getLongitudeE6()/1000000) + ); + myLatitude.setText("Latitude: "+ + String.valueOf((float)centerGeoPoint.getLatitudeE6()/1000000) + ); + myAltitude.setText("Altitude: "+ + String.valueOf(Altitude) + ); + }; + + private void CheckTowerAndGpsStatus() { + towerEnabled = towerLocationManager + .isProviderEnabled(LocationManager.NETWORK_PROVIDER); + gpsEnabled = gpsLocationManager + .isProviderEnabled(LocationManager.GPS_PROVIDER); } - - //@Override - @Override + + @Override protected boolean isRouteDisplayed() { // IMPORTANT: This method must return true if your Activity // is displaying driving directions. Otherwise return false. return false; } + + @Override + public void onCreateContextMenu(ContextMenu menu, View v, + ContextMenuInfo menuInfo) { + super.onCreateContextMenu(menu, v, menuInfo); + + MenuInflater inflater = getMenuInflater(); + inflater.inflate(R.menu.map_menu, menu); + } + + @Override + public boolean onContextItemSelected(MenuItem item) { + int lat = mContextMenuGeoPoint.getLatitudeE6(); + int lon = mContextMenuGeoPoint.getLongitudeE6(); + switch (item.getItemId()) { + case R.id.poi1: + + return true; + case R.id.poi2: + Toast.makeText(mapView.getContext(), "You pressed here: Lat:" + lat/1000000.0 + " Lon:" + lon/1000000.0, Toast.LENGTH_LONG).show(); + return true; + case R.id.view1: + mapView.setSatellite(true); + mapView.invalidate(); + return true; + case R.id.view2: + mapView.setSatellite(false); + mapView.invalidate(); + return true; + default: + return super.onContextItemSelected(item); + } + } + + + /* Class My Location Listener */ + + public class MyLocationListener implements LocationListener + { + @Override + public void onLocationChanged(Location loc) + { + GeoPoint myGeoPoint = new GeoPoint( + (int)(loc.getLatitude()*1000000), + (int)(loc.getLongitude()*1000000)); + + CenterLocation(myGeoPoint,loc.getAltitude()); + } + @Override + public void onProviderDisabled(String provider) + { + Toast.makeText( getApplicationContext(), + "Gps Disabled", + Toast.LENGTH_SHORT ).show(); + } + @Override + public void onProviderEnabled(String provider) + { + Toast.makeText( getApplicationContext(), + "Gps Enabled", + Toast.LENGTH_SHORT).show(); + } + + @Override + public void onStatusChanged(String provider, int status, Bundle extras) + { + } + }/* End of Class MyLocationListener */ + + public boolean onKeyDown(int keyCode, KeyEvent event) { + switch (keyCode) { + case KeyEvent.KEYCODE_DPAD_UP: + mapController.zoomIn(); + break; + case KeyEvent.KEYCODE_DPAD_DOWN: + mapController.zoomOut(); + break; + case KeyEvent.KEYCODE_DPAD_LEFT: + mapController.setZoom(17); + mapView.setSatellite(true); + mapView.invalidate(); + break; + case KeyEvent.KEYCODE_DPAD_RIGHT: + mapController.setZoom(17); + mapView.setSatellite(false); + mapView.invalidate(); + break; + + } + return super.onKeyDown(keyCode, event); + } public class UAVOverlay extends Overlay { Bitmap homeSymbol = BitmapFactory.decodeResource(getResources(), R.drawable.ic_home); From 4f7e37651cfe69cb7a45ac7fde023cb637dd35d7 Mon Sep 17 00:00:00 2001 From: sambas Date: Thu, 28 Mar 2013 18:34:31 +0200 Subject: [PATCH 05/35] F4 CPU temp fix(revo), I think rm still not working --- flight/Modules/System/systemmod.c | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 8d6e88508..875582cf5 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -441,12 +441,19 @@ static void updateStats() } //else: TickCount has wrapped, do not calc now lastTickCount = now; idleCounterClear = 1; - + #if defined(PIOS_INCLUDE_ADC) && defined(PIOS_ADC_USE_TEMP_SENSOR) +#if defined(STM32F4XX) + float temp_voltage = 3.3 * PIOS_ADC_PinGet(3) / ((1 << 12) - 1); + const float STM32_TEMP_V25 = 0.76; /* V */ + const float STM32_TEMP_AVG_SLOPE = 2.5; /* mV/C */ + stats.CPUTemp = (temp_voltage-STM32_TEMP_V25) * 1000 / STM32_TEMP_AVG_SLOPE + 25; +#else float temp_voltage = 3.3 * PIOS_ADC_PinGet(0) / ((1 << 12) - 1); const float STM32_TEMP_V25 = 1.43; /* V */ const float STM32_TEMP_AVG_SLOPE = 4.3; /* mV/C */ stats.CPUTemp = (temp_voltage-STM32_TEMP_V25) * 1000 / STM32_TEMP_AVG_SLOPE + 25; +#endif #endif SystemStatsSet(&stats); } From 25576002579dc8f32636f4a5dc6bec8da9f9b773 Mon Sep 17 00:00:00 2001 From: sambas Date: Thu, 28 Mar 2013 18:35:42 +0200 Subject: [PATCH 06/35] uavobjects thing that fixes sdcard settings save on osd. Can be reverted when fix found. --- flight/Modules/Sensors/simulated/sensors.c | 8 +-- flight/targets/UAVObjects/uavobjectmanager.c | 51 ++++++++++--------- flight/targets/UAVObjects/uavobjecttemplate.c | 2 +- 3 files changed, 33 insertions(+), 28 deletions(-) diff --git a/flight/Modules/Sensors/simulated/sensors.c b/flight/Modules/Sensors/simulated/sensors.c index fef692598..0e21d7f91 100644 --- a/flight/Modules/Sensors/simulated/sensors.c +++ b/flight/Modules/Sensors/simulated/sensors.c @@ -332,7 +332,7 @@ static void simulateModelQuadcopter() static float baro_offset = 0.0f; float Rbe[3][3]; - const float ACTUATOR_ALPHA = 0.8; + const float ACTUATOR_ALPHA = 0.99; const float MAX_THRUST = GRAV * 2; const float K_FRICTION = 1; const float GPS_PERIOD = 0.1; @@ -372,9 +372,9 @@ static void simulateModelQuadcopter() RateDesiredData rateDesired; RateDesiredGet(&rateDesired); - rpy[0] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Roll * (1 - ACTUATOR_ALPHA) + rpy[0] * ACTUATOR_ALPHA; - rpy[1] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Pitch * (1 - ACTUATOR_ALPHA) + rpy[1] * ACTUATOR_ALPHA; - rpy[2] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * rateDesired.Yaw * (1 - ACTUATOR_ALPHA) + rpy[2] * ACTUATOR_ALPHA; + rpy[0] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * actuatorDesired.Roll * 250 * (1 - ACTUATOR_ALPHA) + rpy[0] * ACTUATOR_ALPHA; + rpy[1] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * actuatorDesired.Pitch * 250 * (1 - ACTUATOR_ALPHA) + rpy[1] * ACTUATOR_ALPHA; + rpy[2] = (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) * actuatorDesired.Yaw * 250 *(1 - ACTUATOR_ALPHA) + rpy[2] * ACTUATOR_ALPHA; GyrosData gyrosData; // Skip get as we set all the fields gyrosData.x = rpy[0] + rand_gauss(); diff --git a/flight/targets/UAVObjects/uavobjectmanager.c b/flight/targets/UAVObjects/uavobjectmanager.c index 1f07e0c9c..aa550faa0 100644 --- a/flight/targets/UAVObjects/uavobjectmanager.c +++ b/flight/targets/UAVObjects/uavobjectmanager.c @@ -41,17 +41,6 @@ // Macros #define SET_BITS(var, shift, value, mask) var = (var & ~(mask << shift)) | (value << shift); -/* Table of UAVO handles registered at compile time */ -extern struct UAVOData * __start__uavo_handles[] __attribute__((weak)); -extern struct UAVOData * __stop__uavo_handles[] __attribute__((weak)); - -#define UAVO_LIST_ITERATE(_item) \ -for (struct UAVOData ** _uavo_slot = __start__uavo_handles; \ - _uavo_slot && _uavo_slot < __stop__uavo_handles; \ - _uavo_slot++) { \ - struct UAVOData * _item = *_uavo_slot; \ - if (_item == NULL) continue; - /** * List of event queues and the eventmask associated with the queue. */ @@ -109,6 +98,7 @@ struct UAVOData { * inside the payload for this UAVO. */ struct UAVOMeta metaObj; + struct UAVOData * next; uint16_t instance_size; } __attribute__((packed)); @@ -174,6 +164,7 @@ static void customSPrintf(uint8_t * buffer, uint8_t * format, ...); #endif // Private variables +static struct UAVOData * uavo_list; static xSemaphoreHandle mutex; static const UAVObjMetadata defMetadata = { .flags = (ACCESS_READWRITE << UAVOBJ_ACCESS_SHIFT | @@ -197,12 +188,9 @@ static UAVObjStats stats; int32_t UAVObjInitialize() { // Initialize variables + uavo_list = NULL; memset(&stats, 0, sizeof(UAVObjStats)); - // Initialize the uavo handle table - memset(__start__uavo_handles, 0, - (uintptr_t)__stop__uavo_handles - (uintptr_t)__start__uavo_handles); - // Create mutex mutex = xSemaphoreCreateRecursiveMutex(); if (mutex == NULL) @@ -350,6 +338,9 @@ UAVObjHandle UAVObjRegister(uint32_t id, /* Initialize the embedded meta UAVO */ UAVObjInitMetaData (&uavo_data->metaObj); + /* Add the newly created object to the global list of objects */ + LL_APPEND(uavo_list, uavo_data); + /* Initialize object fields and metadata to default values */ if (initCb) initCb((UAVObjHandle) uavo_data, 0); @@ -383,7 +374,8 @@ UAVObjHandle UAVObjGetByID(uint32_t id) xSemaphoreTakeRecursive(mutex, portMAX_DELAY); // Look for object - UAVO_LIST_ITERATE(tmp_obj) + struct UAVOData * tmp_obj; + LL_FOREACH(uavo_list, tmp_obj) { if (tmp_obj->id == id) { found_obj = (UAVObjHandle *)tmp_obj; goto unlock_exit; @@ -1027,13 +1019,15 @@ int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId) */ int32_t UAVObjSaveSettings() { + struct UAVOData *obj; + // Get lock xSemaphoreTakeRecursive(mutex, portMAX_DELAY); int32_t rc = -1; // Save all settings objects - UAVO_LIST_ITERATE(obj) + LL_FOREACH(uavo_list, obj) { // Check if this is a settings object if (UAVObjIsSettings(obj)) { // Save object @@ -1057,13 +1051,15 @@ unlock_exit: */ int32_t UAVObjLoadSettings() { + struct UAVOData *obj; + // Get lock xSemaphoreTakeRecursive(mutex, portMAX_DELAY); int32_t rc = -1; // Load all settings objects - UAVO_LIST_ITERATE(obj) + LL_FOREACH(uavo_list, obj) { // Check if this is a settings object if (UAVObjIsSettings(obj)) { // Load object @@ -1087,13 +1083,15 @@ unlock_exit: */ int32_t UAVObjDeleteSettings() { + struct UAVOData *obj; + // Get lock xSemaphoreTakeRecursive(mutex, portMAX_DELAY); int32_t rc = -1; // Save all settings objects - UAVO_LIST_ITERATE(obj) + LL_FOREACH(uavo_list, obj) { // Check if this is a settings object if (UAVObjIsSettings(obj)) { // Save object @@ -1117,13 +1115,15 @@ unlock_exit: */ int32_t UAVObjSaveMetaobjects() { + struct UAVOData *obj; + // Get lock xSemaphoreTakeRecursive(mutex, portMAX_DELAY); int32_t rc = -1; // Save all settings objects - UAVO_LIST_ITERATE(obj) + LL_FOREACH(uavo_list, obj) { // Save object if (UAVObjSave( (UAVObjHandle) MetaObjectPtr(obj), 0) == -1) { @@ -1144,13 +1144,15 @@ unlock_exit: */ int32_t UAVObjLoadMetaobjects() { + struct UAVOData *obj; + // Get lock xSemaphoreTakeRecursive(mutex, portMAX_DELAY); int32_t rc = -1; // Load all settings objects - UAVO_LIST_ITERATE(obj) + LL_FOREACH(uavo_list, obj) { // Load object if (UAVObjLoad((UAVObjHandle) MetaObjectPtr(obj), 0) == -1) { @@ -1171,13 +1173,15 @@ unlock_exit: */ int32_t UAVObjDeleteMetaobjects() { + struct UAVOData *obj; + // Get lock xSemaphoreTakeRecursive(mutex, portMAX_DELAY); int32_t rc = -1; // Load all settings objects - UAVO_LIST_ITERATE(obj) + LL_FOREACH(uavo_list, obj) { // Load object if (UAVObjDelete((UAVObjHandle) MetaObjectPtr(obj), 0) == -1) { @@ -1783,7 +1787,8 @@ void UAVObjIterate(void (*iterator) (UAVObjHandle obj)) xSemaphoreTakeRecursive(mutex, portMAX_DELAY); // Iterate through the list and invoke iterator for each object - UAVO_LIST_ITERATE(obj) + struct UAVOData *obj; + LL_FOREACH(uavo_list, obj) { (*iterator) ((UAVObjHandle) obj); (*iterator) ((UAVObjHandle) &obj->metaObj); } diff --git a/flight/targets/UAVObjects/uavobjecttemplate.c b/flight/targets/UAVObjects/uavobjecttemplate.c index d2e0e8f34..f8db8a024 100644 --- a/flight/targets/UAVObjects/uavobjecttemplate.c +++ b/flight/targets/UAVObjects/uavobjecttemplate.c @@ -40,7 +40,7 @@ #include "$(NAMELC).h" // Private variables -static UAVObjHandle handle __attribute__((section("_uavo_handles"))); +static UAVObjHandle handle = NULL; /** * Initialize object. From e43e5c502850385d0e8bb225b4bf041734e1680f Mon Sep 17 00:00:00 2001 From: sambas Date: Sat, 30 Mar 2013 14:57:43 +0200 Subject: [PATCH 07/35] Add missing flightmodes into sanitycheck, pathfollower needs to be running before sanitycheck runs --- flight/Libraries/sanitycheck.c | 40 ++++++++++++++++++++++++++++++-- flight/targets/RevoMini/Makefile | 2 +- 2 files changed, 39 insertions(+), 3 deletions(-) diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index ab5cab3bf..864eedd8b 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -114,7 +114,7 @@ int32_t configuration_check() if (coptercontrol) status = SYSTEMALARMS_ALARM_ERROR; else { - // Revo supports altitude hold + // Revo supports VelocityControl if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) status = SYSTEMALARMS_ALARM_ERROR; } @@ -123,7 +123,43 @@ int32_t configuration_check() if (coptercontrol) status = SYSTEMALARMS_ALARM_ERROR; else { - // Revo supports altitude hold + // Revo supports Position Hold + if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) + status = SYSTEMALARMS_ALARM_ERROR; + } + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_LAND: + if (coptercontrol) + status = SYSTEMALARMS_ALARM_ERROR; + else { + // Revo supports AutoLand Mode + if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) + status = SYSTEMALARMS_ALARM_ERROR; + } + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POI: + if (coptercontrol) + status = SYSTEMALARMS_ALARM_ERROR; + else { + // Revo supports POI Mode + if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) + status = SYSTEMALARMS_ALARM_ERROR; + } + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_PATHPLANNER: + if (coptercontrol) + status = SYSTEMALARMS_ALARM_ERROR; + else { + // Revo supports PathPlanner + if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) + status = SYSTEMALARMS_ALARM_ERROR; + } + break; + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_RETURNTOBASE: + if (coptercontrol) + status = SYSTEMALARMS_ALARM_ERROR; + else { + // Revo supports ReturnToBase if (!TaskMonitorQueryRunning(TASKINFO_RUNNING_PATHFOLLOWER)) status = SYSTEMALARMS_ALARM_ERROR; } diff --git a/flight/targets/RevoMini/Makefile b/flight/targets/RevoMini/Makefile index e19310de3..0e6c487cf 100644 --- a/flight/targets/RevoMini/Makefile +++ b/flight/targets/RevoMini/Makefile @@ -34,6 +34,7 @@ MODULES += Altitude/revolution MODULES += Airspeed/revolution MODULES += AltitudeHold MODULES += Stabilization +MODULES += VtolPathFollower MODULES += ManualControl MODULES += Actuator MODULES += GPS @@ -46,7 +47,6 @@ MODULES += PathPlanner MODULES += FixedWingPathFollower MODULES += Osd/OsdHk MODULES += Telemetry -MODULES += VtolPathFollower ## OP-700: VtolPathFollower disabled because its currently unsafe - remove this line once Sambas code has been merged OPTMODULES = From 8698bcfb8448e8101b227819656e6666199638c2 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sat, 30 Mar 2013 15:20:05 +0100 Subject: [PATCH 08/35] Moved OSD settings from SDCard to mcu internal flash memory --- flight/targets/OSD/System/inc/pios_config.h | 6 ++-- flight/targets/OSD/System/pios_board.c | 10 +++++++ flight/targets/UAVObjects/uavobjectmanager.c | 30 +++++++++++-------- .../targets/board_hw_defs/osd/board_hw_defs.c | 24 +++++++++++++++ make/boards/osd/board-info.mk | 23 +++++++++++++- make/boot-defs.mk | 3 -- make/common-defs.mk | 10 +++++++ 7 files changed, 87 insertions(+), 19 deletions(-) diff --git a/flight/targets/OSD/System/inc/pios_config.h b/flight/targets/OSD/System/inc/pios_config.h index cda229055..391c59861 100644 --- a/flight/targets/OSD/System/inc/pios_config.h +++ b/flight/targets/OSD/System/inc/pios_config.h @@ -103,9 +103,11 @@ /* #define PIOS_INCLUDE_OVERO */ /* #define PIOS_OVERO_SPI */ #define PIOS_INCLUDE_SDCARD +/* #define PIOS_USE_SETTINGS_ON_SDCARD */ #define LOG_FILENAME "startup.log" -/* #define PIOS_INCLUDE_FLASH */ -/* #define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS */ +#define PIOS_INCLUDE_FLASH +#define PIOS_INCLUDE_FLASH_INTERNAL +#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS /* #define FLASH_FREERTOS */ /* #define PIOS_INCLUDE_FLASH_EEPROM */ diff --git a/flight/targets/OSD/System/pios_board.c b/flight/targets/OSD/System/pios_board.c index 84595f320..f85f6faf2 100644 --- a/flight/targets/OSD/System/pios_board.c +++ b/flight/targets/OSD/System/pios_board.c @@ -161,6 +161,16 @@ void PIOS_Board_Init(void) { #endif #endif /* PIOS_INCLUDE_SPI */ +#ifdef PIOS_INCLUDE_FLASH_SECTOR_SETTINGS +uintptr_t flash_id; +uintptr_t fs_id; +PIOS_Flash_Internal_Init(&flash_id, &flash_internal_cfg); +PIOS_FLASHFS_Logfs_Init(&fs_id, &flashfs_internal_cfg, &pios_internal_flash_driver, flash_id); +#elif !defined(PIOS_USE_SETTINGS_ON_SDCARD) +#error No setting storage specified. (define PIOS_USE_SETTINGS_ON_SDCARD or INCLUDE_FLASH_SECTOR_SETTINGS) +#endif + + /* Initialize UAVObject libraries */ EventDispatcherInitialize(); UAVObjInitialize(); diff --git a/flight/targets/UAVObjects/uavobjectmanager.c b/flight/targets/UAVObjects/uavobjectmanager.c index aa550faa0..6e6edc38a 100644 --- a/flight/targets/UAVObjects/uavobjectmanager.c +++ b/flight/targets/UAVObjects/uavobjectmanager.c @@ -158,7 +158,11 @@ static int32_t connectObj(UAVObjHandle obj_handle, xQueueHandle queue, static int32_t disconnectObj(UAVObjHandle obj_handle, xQueueHandle queue, UAVObjEventCallback cb); -#if defined(PIOS_INCLUDE_SDCARD) +#if defined(PIOS_USE_SETTINGS_ON_SDCARD) && defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) +#error Both PIOS_USE_SETTINGS_ON_SDCARD and PIOS_INCLUDE_FLASH_SECTOR_SETTINGS. Only one settings storage allowed. +#endif + +#if defined(PIOS_USE_SETTINGS_ON_SDCARD) static void objectFilename(UAVObjHandle obj_handle, uint8_t * filename); static void customSPrintf(uint8_t * buffer, uint8_t * format, ...); #endif @@ -668,7 +672,7 @@ unlock_exit: return rc; } -#if defined(PIOS_INCLUDE_SDCARD) +#if defined(PIOS_USE_SETTINGS_ON_SDCARD) /** * Save the data of the specified object instance to the file system (SD card). * The object will be appended and the file will not be closed. @@ -743,7 +747,7 @@ int32_t UAVObjSaveToFile(UAVObjHandle obj_handle, uint16_t instId, xSemaphoreGiveRecursive(mutex); return 0; } -#endif /* PIOS_INCLUDE_SDCARD */ +#endif /* PIOS_USE_SETTINGS_ON_SDCARD */ /** * Save the data of the specified object to the file system (SD card). @@ -779,7 +783,7 @@ int32_t UAVObjSave(UAVObjHandle obj_handle, uint16_t instId) return -1; } #endif -#if defined(PIOS_INCLUDE_SDCARD) +#if defined(PIOS_USE_SETTINGS_ON_SDCARD) FILEINFO file; uint8_t filename[14]; @@ -807,11 +811,11 @@ int32_t UAVObjSave(UAVObjHandle obj_handle, uint16_t instId) // Done, close file and unlock PIOS_FCLOSE(file); xSemaphoreGiveRecursive(mutex); -#endif /* PIOS_INCLUDE_SDCARD */ +#endif /* PIOS_USE_SETTINGS_ON_SDCARD */ return 0; } -#if defined(PIOS_INCLUDE_SDCARD) +#if defined(PIOS_USE_SETTINGS_ON_SDCARD) /** * Load an object from the file system (SD card). * @param[in] file File to read from @@ -899,7 +903,7 @@ UAVObjHandle UAVObjLoadFromFile(FILEINFO * file) xSemaphoreGiveRecursive(mutex); return obj_handle; } -#endif /* PIOS_INCLUDE_SDCARD */ +#endif /* PIOS_USE_SETTINGS_ON_SDCARD */ /** * Load an object from the file system (SD card). @@ -939,7 +943,7 @@ int32_t UAVObjLoad(UAVObjHandle obj_handle, uint16_t instId) #endif -#if defined(PIOS_INCLUDE_SDCARD) +#if defined(PIOS_USE_SETTINGS_ON_SDCARD) FILEINFO file; UAVObjHandle loadedObj; uint8_t filename[14]; @@ -975,7 +979,7 @@ int32_t UAVObjLoad(UAVObjHandle obj_handle, uint16_t instId) // Done, close file and unlock PIOS_FCLOSE(file); xSemaphoreGiveRecursive(mutex); -#endif /* PIOS_INCLUDE_SDCARD */ +#endif /* PIOS_USE_SETTINGS_ON_SDCARD */ return 0; } @@ -991,7 +995,7 @@ int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId) #if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) PIOS_FLASHFS_ObjDelete(0, UAVObjGetID(obj_handle), instId); #endif -#if defined(PIOS_INCLUDE_SDCARD) +#if defined(PIOS_USE_SETTINGS_ON_SDCARD) uint8_t filename[14]; // Check for file system availability @@ -1009,7 +1013,7 @@ int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId) // Done xSemaphoreGiveRecursive(mutex); -#endif /* PIOS_INCLUDE_SDCARD */ +#endif /* PIOS_USE_SETTINGS_ON_SDCARD */ return 0; } @@ -1995,7 +1999,7 @@ static int32_t disconnectObj(UAVObjHandle obj_handle, xQueueHandle queue, return -1; } -#if defined(PIOS_INCLUDE_SDCARD) +#if defined(PIOS_USE_SETTINGS_ON_SDCARD) /** * Wrapper for the sprintf function */ @@ -2013,4 +2017,4 @@ static void objectFilename(UAVObjHandle obj_handle, uint8_t * filename) { customSPrintf(filename, (uint8_t *) "%X.obj", UAVObjGetID(obj_handle)); } -#endif /* PIOS_INCLUDE_SDCARD */ +#endif /* PIOS_USE_SETTINGS_ON_SDCARD */ diff --git a/flight/targets/board_hw_defs/osd/board_hw_defs.c b/flight/targets/board_hw_defs/osd/board_hw_defs.c index 44434c392..7eaa327de 100644 --- a/flight/targets/board_hw_defs/osd/board_hw_defs.c +++ b/flight/targets/board_hw_defs/osd/board_hw_defs.c @@ -71,6 +71,30 @@ const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revisio #endif /* PIOS_INCLUDE_LED */ + +#if defined(PIOS_INCLUDE_FLASH) +#include "pios_flashfs_logfs_priv.h" +#include "pios_flash_internal_priv.h" + +static const struct pios_flash_internal_cfg flash_internal_cfg = { +}; + +static const struct flashfs_logfs_cfg flashfs_internal_cfg = { +.fs_magic = 0x99abcfef, +.total_fs_size = EE_BANK_SIZE, /* 32K bytes (2x16KB sectors) */ +.arena_size = 0x00004000, /* 64 * slot size = 16K bytes = 1 sector */ +.slot_size = 0x00000100, /* 256 bytes */ + +.start_offset = EE_BANK_BASE, /* start after the bootloader */ +.sector_size = 0x00004000, /* 16K bytes */ +.page_size = 0x00004000, /* 16K bytes */ +}; + +#include "pios_flash.h" + +#endif /* PIOS_INCLUDE_FLASH */ + + #if defined(PIOS_INCLUDE_SPI) #include diff --git a/make/boards/osd/board-info.mk b/make/boards/osd/board-info.mk index d93151488..b33eb53d9 100644 --- a/make/boards/osd/board-info.mk +++ b/make/boards/osd/board-info.mk @@ -13,15 +13,36 @@ OPENOCD_JTAG_CONFIG := stlink-v2.cfg OPENOCD_CONFIG := stm32f4xx.stlink.cfg #OPENOCD_CONFIG := stm32f4xx.cfg +# Flash memory map for OSD: +# Sector start size use +# 0 0x0800 0000 16k BL +# 1 0x0800 4000 16k BL +# 2 0x0800 8000 16k EE +# 3 0x0800 C000 16k EE +# 4 0x0801 0000 64k Unused +# 5 0x0802 0000 128k FW +# 6 0x0804 0000 128k FW +# 7 0x0806 0000 128k FW +# 8 0x0808 0000 128k Unused +# .. .. +# 11 0x080E 0000 128k Unused + # Note: These must match the values in link_$(BOARD)_memory.ld BL_BANK_BASE := 0x08000000 # Start of bootloader flash BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region -# Leave the remaining 16KB and 64KB sectors for other uses + +# Leave the remaining 16KB for settings storage + +EE_BANK_BASE := 0x08008000 # EEPROM storage area +EE_BANK_SIZE := 0x00008000 # Size of EEPROM storage area + +# Leave the reamaining 64KB sectors for other uses FW_BANK_BASE := 0x08020000 # Start of firmware flash FW_BANK_SIZE := 0x00060000 # Should include FW_DESC_SIZE + FW_DESC_SIZE := 0x00000064 OSCILLATOR_FREQ := 8000000 diff --git a/make/boot-defs.mk b/make/boot-defs.mk index 5c0bbf32e..44d8c27a8 100644 --- a/make/boot-defs.mk +++ b/make/boot-defs.mk @@ -112,9 +112,6 @@ BLONLY_CDEFS += -DBOARD_TYPE=$(BOARD_TYPE) BLONLY_CDEFS += -DBOARD_REVISION=$(BOARD_REVISION) BLONLY_CDEFS += -DHW_TYPE=$(HW_TYPE) BLONLY_CDEFS += -DBOOTLOADER_VERSION=$(BOOTLOADER_VERSION) -BLONLY_CDEFS += -DFW_BANK_BASE=$(FW_BANK_BASE) -BLONLY_CDEFS += -DFW_BANK_SIZE=$(FW_BANK_SIZE) -BLONLY_CDEFS += -DFW_DESC_SIZE=$(FW_DESC_SIZE) # Compiler flags CDEFS += $(BLONLY_CDEFS) diff --git a/make/common-defs.mk b/make/common-defs.mk index 60be74a6f..7bea9bf1a 100644 --- a/make/common-defs.mk +++ b/make/common-defs.mk @@ -95,6 +95,15 @@ endif #ADEFS = -DUSE_IRQ_ASM_WRAPPER ADEFS = -D__ASSEMBLY__ +# Provide board-specific defines +CDEFS += -DFW_BANK_BASE=$(FW_BANK_BASE) +CDEFS += -DFW_BANK_SIZE=$(FW_BANK_SIZE) +CDEFS += -DFW_DESC_SIZE=$(FW_DESC_SIZE) + +CDEFS += -DEE_BANK_BASE=$(EE_BANK_BASE) +CDEFS += -DEE_BANK_SIZE=$(EE_BANK_SIZE) + + # Compiler flag to set the C Standard level. # c89 - "ANSI" C # gnu89 - c89 plus GCC extensions @@ -122,6 +131,7 @@ CFLAGS += -Wall CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) + # FIXME: STM32F4xx library raises strict aliasing and const qualifier warnings ifneq ($(MCU),cortex-m4) CFLAGS += -Werror From 4240cc96707df31aa758dff28668c75919b97c23 Mon Sep 17 00:00:00 2001 From: sambas Date: Tue, 2 Apr 2013 19:09:40 +0300 Subject: [PATCH 09/35] Flight battery to AerosimRC, needs option flag, currently linked to baroaltitude option --- .../plugins/hitl/aerosimrc/src/udpconnect.cpp | 2 +- .../src/plugins/hitl/aerosimrcsimulator.cpp | 11 +++++++--- .../src/plugins/hitl/simulator.cpp | 20 +++++++++++++++++++ .../openpilotgcs/src/plugins/hitl/simulator.h | 7 +++++++ 4 files changed, 36 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udpconnect.cpp b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udpconnect.cpp index 0448a705a..44151b661 100644 --- a/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udpconnect.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udpconnect.cpp @@ -87,7 +87,7 @@ void UdpSender::sendDatagram(const simToPlugin *stp) // attitude out << stp->heading << stp->pitch << stp->roll; // electric - out << stp->voltage << stp->current; + out << stp->voltage << stp->current << stp->consumedCharge; // matrix out << stp->axisXx << stp->axisXy << stp->axisXz; out << stp->axisYx << stp->axisYy << stp->axisYz; diff --git a/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp b/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp index 2e1c55659..374a27386 100644 --- a/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp @@ -143,7 +143,7 @@ void AeroSimRCSimulator::transmitUpdate() void AeroSimRCSimulator::processUpdate(const QByteArray &data) { // check size - if (data.size() > 188) { + if (data.size() > 192) { qDebug() << "!!! big datagram: " << data.size(); return; } @@ -171,7 +171,7 @@ void AeroSimRCSimulator::processUpdate(const QByteArray &data) qreal lat, lon; float agl, // world yaw, pitch, roll, // model - volt, curr, + volt, curr, cons, rx, ry, rz, fx, fy, fz, ux, uy, uz, // matrix ch[AEROSIM_RCCHANNEL_NUMELEM]; @@ -184,7 +184,7 @@ void AeroSimRCSimulator::processUpdate(const QByteArray &data) stream >> accX >> accY >> accZ; stream >> lat >> lon >> agl; stream >> yaw >> pitch >> roll; - stream >> volt >> curr; + stream >> volt >> curr >> cons; stream >> rx >> ry >> rz >> fx >> fy >> fz >> ux >> uy >> uz; stream >> ch[0] >> ch[1] >> ch[2] >> ch[3] >> ch[4] >> ch[5] >> ch[6] >> ch[7]; stream >> udpCounterASrecv; @@ -253,6 +253,11 @@ void AeroSimRCSimulator::processUpdate(const QByteArray &data) out.velEast = velX * 1; out.velDown = velZ * -1; + out.voltage = volt; + out.current = curr; + out.consumption = cons*1000.0; + + updateUAVOs(out); diff --git a/ground/openpilotgcs/src/plugins/hitl/simulator.cpp b/ground/openpilotgcs/src/plugins/hitl/simulator.cpp index 1a0967ca8..5975ec837 100644 --- a/ground/openpilotgcs/src/plugins/hitl/simulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/simulator.cpp @@ -69,6 +69,7 @@ Simulator::Simulator(const SimulatorSettings& params) : gcsRcvrTime = currentTime; attRawTime = currentTime; baroAltTime = currentTime; + battTime = currentTime; airspeedActualTime=currentTime; //Define standard atmospheric constants @@ -153,6 +154,7 @@ void Simulator::onStart() velActual = VelocityActual::GetInstance(objManager); posActual = PositionActual::GetInstance(objManager); baroAlt = BaroAltitude::GetInstance(objManager); + flightBatt = FlightBatteryState::GetInstance(objManager); airspeedActual = AirspeedActual::GetInstance(objManager); attActual = AttitudeActual::GetInstance(objManager); attSettings = AttitudeSettings::GetInstance(objManager); @@ -284,7 +286,10 @@ void Simulator::setupObjects() setupOutputObject(airspeedActual, settings.airspeedActualRate); if(settings.baroAltitudeEnabled) + { setupOutputObject(baroAlt, settings.baroAltRate); + setupOutputObject(flightBatt, settings.baroAltRate); + } } @@ -726,6 +731,21 @@ void Simulator::updateUAVOs(Output2Hardware out){ } } + /*******************************/ + // Update FlightBatteryState object + if (settings.baroAltitudeEnabled){ + if (battTime.msecsTo(currentTime) >= settings.baroAltRate) { + FlightBatteryState::DataFields batteryData; + memset(&batteryData, 0, sizeof(FlightBatteryState::DataFields)); + batteryData.Voltage = out.voltage; + batteryData.Current = out.current; + batteryData.ConsumedEnergy = out.consumption; + flightBatt->setData(batteryData); + + battTime=battTime.addMSecs(settings.baroAltRate); + } + } + /*******************************/ // Update AirspeedActual object if (settings.airspeedActualEnabled){ diff --git a/ground/openpilotgcs/src/plugins/hitl/simulator.h b/ground/openpilotgcs/src/plugins/hitl/simulator.h index 000ad633d..2370b269c 100644 --- a/ground/openpilotgcs/src/plugins/hitl/simulator.h +++ b/ground/openpilotgcs/src/plugins/hitl/simulator.h @@ -45,6 +45,7 @@ #include "attitudeactual.h" #include "attitudesettings.h" #include "baroaltitude.h" +#include "flightbatterystate.h" #include "flightstatus.h" #include "gcsreceiver.h" #include "gcstelemetrystats.h" @@ -194,6 +195,10 @@ struct Output2Hardware{ float pitchDesired; float yawDesired; float throttleDesired; + + float voltage; + float current; + float consumption; }; //struct Output2Simulator{ @@ -285,6 +290,7 @@ protected: ActuatorDesired* actDesired; ManualControlCommand* manCtrlCommand; FlightStatus* flightStatus; + FlightBatteryState* flightBatt; BaroAltitude* baroAlt; AirspeedActual* airspeedActual; AttitudeActual* attActual; @@ -323,6 +329,7 @@ private: QTime gpsPosTime; QTime groundTruthTime; QTime baroAltTime; + QTime battTime; QTime gcsRcvrTime; QTime airspeedActualTime; From d776d82518439f6cbacd002bf5ad1423c64572bd Mon Sep 17 00:00:00 2001 From: sambas Date: Tue, 2 Apr 2013 19:57:40 +0300 Subject: [PATCH 10/35] Does this fix simposix and make bamboo happy --- flight/targets/SimPosix/UAVObjects.inc | 2 ++ 1 file changed, 2 insertions(+) diff --git a/flight/targets/SimPosix/UAVObjects.inc b/flight/targets/SimPosix/UAVObjects.inc index 4a6c453ac..23ffde045 100644 --- a/flight/targets/SimPosix/UAVObjects.inc +++ b/flight/targets/SimPosix/UAVObjects.inc @@ -83,6 +83,8 @@ UAVOBJSRCFILENAMES += velocitydesired UAVOBJSRCFILENAMES += watchdogstatus UAVOBJSRCFILENAMES += waypoint UAVOBJSRCFILENAMES += waypointactive +UAVOBJSRCFILENAMES += poilocation +UAVOBJSRCFILENAMES += poilearnsettings UAVOBJSRCFILENAMES += flightstatus UAVOBJSRCFILENAMES += hwsettings UAVOBJSRCFILENAMES += receiveractivity From fb8273459fec467851af7b460cfaa551608c342f Mon Sep 17 00:00:00 2001 From: sambas Date: Sun, 7 Apr 2013 09:49:13 +0300 Subject: [PATCH 11/35] Normalize line endings --- .gitattributes | 31 + CREDITS.txt | 412 +- HISTORY.txt | 408 +- KNOWN_ISSUES.txt | 44 +- LICENSE.txt | 84 +- MILESTONES.txt | 532 +- Makefile | 120 +- flight/.gitattributes | 17 + .../PyMite/platform/openpilot/plat.c | 172 +- .../PyMite/platform/openpilot_sitl/plat.c | 614 +- .../PyMite/platform/windows/stdint.h | 50 +- flight/Libraries/aes.c | 950 +- flight/Libraries/inc/aes.h | 34 +- flight/Libraries/inc/packet_handler.h | 218 +- flight/Libraries/inc/taskmonitor.h | 88 +- flight/Libraries/printf2.c | 1266 +- flight/Libraries/taskmonitor.c | 318 +- flight/Modules/FirmwareIAP/firmwareiap.c | 532 +- flight/Modules/FirmwareIAP/inc/firmwareiap.h | 66 +- flight/Modules/GPS/inc/UBX.h | 448 +- flight/Modules/Osd/osdgen/inc/osdgen.h | 392 +- flight/Modules/Osd/osdgen/osdgen.c | 4952 +- flight/Modules/Osd/osdinput/inc/osdinput.h | 30 +- flight/Modules/Osd/osdinput/osdinput.c | 584 +- .../Modules/Stabilization/inc/stabilization.h | 90 +- flight/PiOS.osx/inc/FreeRTOSConfig.h | 224 +- flight/PiOS.osx/inc/pios_iap.h | 90 +- flight/PiOS.osx/inc/pios_sdcard.h | 226 +- flight/PiOS.osx/inc/pios_tcp.h | 70 +- flight/PiOS.osx/inc/pios_udp.h | 70 +- .../osx/Libraries/FreeRTOS/Source/croutine.c | 760 +- .../FreeRTOS/Source/include/FreeRTOS.h | 938 +- .../FreeRTOS/Source/include/StackMacros.h | 348 +- .../FreeRTOS/Source/include/croutine.h | 1504 +- .../Libraries/FreeRTOS/Source/include/list.h | 628 +- .../FreeRTOS/Source/include/mpu_wrappers.h | 282 +- .../FreeRTOS/Source/include/portable.h | 792 +- .../FreeRTOS/Source/include/projdefs.h | 176 +- .../Libraries/FreeRTOS/Source/include/queue.h | 2540 +- .../FreeRTOS/Source/include/semphr.h | 1434 +- .../Libraries/FreeRTOS/Source/include/task.h | 2644 +- .../FreeRTOS/Source/include/timers.h | 1872 +- .../osx/Libraries/FreeRTOS/Source/list.c | 394 +- .../Source/portable/GCC/Posix/portmacro.h | 340 +- .../FreeRTOS/Source/portable/MemMang/heap_3.c | 226 +- .../osx/Libraries/FreeRTOS/Source/queue.c | 3078 +- .../osx/Libraries/FreeRTOS/Source/task.c | 5278 +- .../osx/Libraries/FreeRTOS/Source/timers.c | 1298 +- flight/PiOS.osx/osx/pios_delay.c | 224 +- flight/PiOS.osx/osx/pios_iap.c | 138 +- flight/PiOS.osx/osx/pios_led.c | 172 +- flight/PiOS.osx/osx/pios_sdcard.c | 600 +- flight/PiOS.osx/osx/pios_tcp.c | 572 +- flight/PiOS.osx/osx/pios_udp.c | 488 +- flight/PiOS.osx/osx/pios_wdg.c | 304 +- flight/PiOS.osx/pios.h | 168 +- flight/PiOS.win32/inc/FreeRTOSConfig.h | 152 +- flight/PiOS.win32/inc/pios_com.h | 112 +- flight/PiOS.win32/inc/pios_delay.h | 74 +- flight/PiOS.win32/inc/pios_initcall.h | 116 +- flight/PiOS.win32/inc/pios_led.h | 86 +- flight/PiOS.win32/inc/pios_sdcard.h | 226 +- flight/PiOS.win32/inc/pios_sys.h | 70 +- flight/PiOS.win32/inc/pios_udp.h | 104 +- flight/PiOS.win32/pios.h | 140 +- .../Libraries/FreeRTOS/Source/croutine.c | 742 +- .../FreeRTOS/Source/include/FreeRTOS.h | 840 +- .../FreeRTOS/Source/include/StackMacros.h | 346 +- .../FreeRTOS/Source/include/croutine.h | 1498 +- .../Libraries/FreeRTOS/Source/include/list.h | 610 +- .../FreeRTOS/Source/include/mpu_wrappers.h | 270 +- .../FreeRTOS/Source/include/portable.h | 782 +- .../FreeRTOS/Source/include/projdefs.h | 154 +- .../Libraries/FreeRTOS/Source/include/queue.h | 2522 +- .../FreeRTOS/Source/include/semphr.h | 1422 +- .../Libraries/FreeRTOS/Source/include/task.h | 2526 +- .../win32/Libraries/FreeRTOS/Source/list.c | 382 +- .../Source/portable/GCC/Win32/cpuemu.h | 172 +- .../FreeRTOS/Source/portable/GCC/Win32/port.c | 1894 +- .../Source/portable/GCC/Win32/portmacro.h | 354 +- .../FreeRTOS/Source/portable/MemMang/heap_3.c | 234 +- .../win32/Libraries/FreeRTOS/Source/queue.c | 2930 +- .../win32/Libraries/FreeRTOS/Source/tasks.c | 4636 +- flight/PiOS.win32/win32/pios_com.c | 392 +- flight/PiOS.win32/win32/pios_delay.c | 176 +- flight/PiOS.win32/win32/pios_led.c | 204 +- flight/PiOS.win32/win32/pios_sdcard.c | 600 +- flight/PiOS.win32/win32/pios_sys.c | 372 +- flight/PiOS.win32/win32/pios_udp.c | 954 +- flight/PiOS.win32/win32/pios_wdg.c | 244 +- flight/PiOS/Boards/STM32103CB_CC_Rev1.h | 564 +- .../PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h | 628 +- flight/PiOS/Boards/STM3210E_OP.h | 668 +- flight/PiOS/Boards/STM32F4xx_OSD.h | 584 +- .../Source/BasicMathFunctions/arm_abs_f32.c | 244 +- .../Source/BasicMathFunctions/arm_abs_q15.c | 340 +- .../Source/BasicMathFunctions/arm_abs_q31.c | 240 +- .../Source/BasicMathFunctions/arm_abs_q7.c | 286 +- .../Source/BasicMathFunctions/arm_add_f32.c | 242 +- .../Source/BasicMathFunctions/arm_add_q15.c | 254 +- .../Source/BasicMathFunctions/arm_add_q31.c | 258 +- .../Source/BasicMathFunctions/arm_add_q7.c | 252 +- .../BasicMathFunctions/arm_dot_prod_f32.c | 244 +- .../BasicMathFunctions/arm_dot_prod_q15.c | 264 +- .../BasicMathFunctions/arm_dot_prod_q31.c | 248 +- .../BasicMathFunctions/arm_dot_prod_q7.c | 326 +- .../Source/BasicMathFunctions/arm_mult_f32.c | 252 +- .../Source/BasicMathFunctions/arm_mult_q15.c | 238 +- .../Source/BasicMathFunctions/arm_mult_q31.c | 242 +- .../Source/BasicMathFunctions/arm_mult_q7.c | 250 +- .../BasicMathFunctions/arm_negate_f32.c | 234 +- .../BasicMathFunctions/arm_negate_q15.c | 280 +- .../BasicMathFunctions/arm_negate_q31.c | 238 +- .../Source/BasicMathFunctions/arm_negate_q7.c | 244 +- .../BasicMathFunctions/arm_offset_f32.c | 244 +- .../BasicMathFunctions/arm_offset_q15.c | 256 +- .../BasicMathFunctions/arm_offset_q31.c | 252 +- .../Source/BasicMathFunctions/arm_offset_q7.c | 254 +- .../Source/BasicMathFunctions/arm_scale_f32.c | 266 +- .../Source/BasicMathFunctions/arm_scale_q15.c | 324 +- .../Source/BasicMathFunctions/arm_scale_q31.c | 234 +- .../Source/BasicMathFunctions/arm_scale_q7.c | 282 +- .../Source/BasicMathFunctions/arm_shift_q15.c | 478 +- .../Source/BasicMathFunctions/arm_shift_q31.c | 282 +- .../Source/BasicMathFunctions/arm_shift_q7.c | 404 +- .../Source/BasicMathFunctions/arm_sub_f32.c | 244 +- .../Source/BasicMathFunctions/arm_sub_q15.c | 248 +- .../Source/BasicMathFunctions/arm_sub_q31.c | 250 +- .../Source/BasicMathFunctions/arm_sub_q7.c | 246 +- .../Source/CommonTables/arm_common_tables.c | 288 +- .../ComplexMathFunctions/arm_cmplx_conj_f32.c | 282 +- .../ComplexMathFunctions/arm_cmplx_conj_q15.c | 246 +- .../ComplexMathFunctions/arm_cmplx_conj_q31.c | 262 +- .../arm_cmplx_dot_prod_f32.c | 314 +- .../arm_cmplx_dot_prod_q15.c | 282 +- .../arm_cmplx_dot_prod_q31.c | 284 +- .../ComplexMathFunctions/arm_cmplx_mag_f32.c | 308 +- .../ComplexMathFunctions/arm_cmplx_mag_q15.c | 306 +- .../ComplexMathFunctions/arm_cmplx_mag_q31.c | 302 +- .../arm_cmplx_mag_squared_f32.c | 310 +- .../arm_cmplx_mag_squared_q15.c | 296 +- .../arm_cmplx_mag_squared_q31.c | 300 +- .../arm_cmplx_mult_cmplx_f32.c | 360 +- .../arm_cmplx_mult_cmplx_q15.c | 364 +- .../arm_cmplx_mult_cmplx_q31.c | 418 +- .../arm_cmplx_mult_real_f32.c | 314 +- .../arm_cmplx_mult_real_q15.c | 302 +- .../arm_cmplx_mult_real_q31.c | 302 +- .../ControllerFunctions/arm_pid_init_f32.c | 152 +- .../ControllerFunctions/arm_pid_init_q15.c | 222 +- .../ControllerFunctions/arm_pid_init_q31.c | 192 +- .../ControllerFunctions/arm_pid_reset_f32.c | 108 +- .../ControllerFunctions/arm_pid_reset_q15.c | 106 +- .../ControllerFunctions/arm_pid_reset_q31.c | 108 +- .../ControllerFunctions/arm_sin_cos_f32.c | 816 +- .../ControllerFunctions/arm_sin_cos_q31.c | 622 +- .../Source/FastMathFunctions/arm_cos_f32.c | 508 +- .../Source/FastMathFunctions/arm_cos_q15.c | 378 +- .../Source/FastMathFunctions/arm_cos_q31.c | 450 +- .../Source/FastMathFunctions/arm_sin_f32.c | 514 +- .../Source/FastMathFunctions/arm_sin_q15.c | 384 +- .../Source/FastMathFunctions/arm_sin_q31.c | 454 +- .../Source/FastMathFunctions/arm_sqrt_q15.c | 356 +- .../Source/FastMathFunctions/arm_sqrt_q31.c | 398 +- .../arm_biquad_cascade_df1_32x64_init_q31.c | 204 +- .../arm_biquad_cascade_df1_32x64_q31.c | 952 +- .../arm_biquad_cascade_df1_f32.c | 836 +- .../arm_biquad_cascade_df1_fast_q15.c | 566 +- .../arm_biquad_cascade_df1_fast_q31.c | 542 +- .../arm_biquad_cascade_df1_init_f32.c | 208 +- .../arm_biquad_cascade_df1_init_q15.c | 212 +- .../arm_biquad_cascade_df1_init_q31.c | 212 +- .../arm_biquad_cascade_df1_q15.c | 760 +- .../arm_biquad_cascade_df1_q31.c | 724 +- .../arm_biquad_cascade_df2T_f32.c | 718 +- .../arm_biquad_cascade_df2T_init_f32.c | 188 +- .../Source/FilteringFunctions/arm_conv_f32.c | 1246 +- .../FilteringFunctions/arm_conv_fast_q15.c | 1354 +- .../FilteringFunctions/arm_conv_fast_q31.c | 1134 +- .../FilteringFunctions/arm_conv_partial_f32.c | 1282 +- .../arm_conv_partial_fast_q15.c | 1410 +- .../arm_conv_partial_fast_q31.c | 1186 +- .../FilteringFunctions/arm_conv_partial_q15.c | 1530 +- .../FilteringFunctions/arm_conv_partial_q31.c | 1232 +- .../FilteringFunctions/arm_conv_partial_q7.c | 1446 +- .../Source/FilteringFunctions/arm_conv_q15.c | 1454 +- .../Source/FilteringFunctions/arm_conv_q31.c | 1166 +- .../Source/FilteringFunctions/arm_conv_q7.c | 1360 +- .../FilteringFunctions/arm_correlate_f32.c | 1436 +- .../arm_correlate_fast_q15.c | 1244 +- .../arm_correlate_fast_q31.c | 1198 +- .../FilteringFunctions/arm_correlate_q15.c | 1428 +- .../FilteringFunctions/arm_correlate_q31.c | 1366 +- .../FilteringFunctions/arm_correlate_q7.c | 1560 +- .../FilteringFunctions/arm_fir_decimate_f32.c | 740 +- .../arm_fir_decimate_fast_q15.c | 398 +- .../arm_fir_decimate_fast_q31.c | 440 +- .../arm_fir_decimate_init_f32.c | 218 +- .../arm_fir_decimate_init_q15.c | 222 +- .../arm_fir_decimate_init_q31.c | 218 +- .../FilteringFunctions/arm_fir_decimate_q15.c | 570 +- .../FilteringFunctions/arm_fir_decimate_q31.c | 606 +- .../Source/FilteringFunctions/arm_fir_f32.c | 872 +- .../FilteringFunctions/arm_fir_fast_q15.c | 558 +- .../FilteringFunctions/arm_fir_fast_q31.c | 606 +- .../FilteringFunctions/arm_fir_init_f32.c | 182 +- .../FilteringFunctions/arm_fir_init_q15.c | 298 +- .../FilteringFunctions/arm_fir_init_q31.c | 182 +- .../FilteringFunctions/arm_fir_init_q7.c | 178 +- .../arm_fir_interpolate_f32.c | 798 +- .../arm_fir_interpolate_init_f32.c | 226 +- .../arm_fir_interpolate_init_q15.c | 224 +- .../arm_fir_interpolate_init_q31.c | 226 +- .../arm_fir_interpolate_q15.c | 698 +- .../arm_fir_interpolate_q31.c | 680 +- .../FilteringFunctions/arm_fir_lattice_f32.c | 992 +- .../arm_fir_lattice_init_f32.c | 150 +- .../arm_fir_lattice_init_q15.c | 150 +- .../arm_fir_lattice_init_q31.c | 150 +- .../FilteringFunctions/arm_fir_lattice_q15.c | 1056 +- .../FilteringFunctions/arm_fir_lattice_q31.c | 880 +- .../Source/FilteringFunctions/arm_fir_q15.c | 736 +- .../Source/FilteringFunctions/arm_fir_q31.c | 766 +- .../Source/FilteringFunctions/arm_fir_q7.c | 770 +- .../FilteringFunctions/arm_fir_sparse_f32.c | 724 +- .../arm_fir_sparse_init_f32.c | 198 +- .../arm_fir_sparse_init_q15.c | 198 +- .../arm_fir_sparse_init_q31.c | 196 +- .../arm_fir_sparse_init_q7.c | 198 +- .../FilteringFunctions/arm_fir_sparse_q15.c | 806 +- .../FilteringFunctions/arm_fir_sparse_q31.c | 734 +- .../FilteringFunctions/arm_fir_sparse_q7.c | 790 +- .../FilteringFunctions/arm_iir_lattice_f32.c | 804 +- .../arm_iir_lattice_init_f32.c | 166 +- .../arm_iir_lattice_init_q15.c | 166 +- .../arm_iir_lattice_init_q31.c | 166 +- .../FilteringFunctions/arm_iir_lattice_q15.c | 806 +- .../FilteringFunctions/arm_iir_lattice_q31.c | 684 +- .../Source/FilteringFunctions/arm_lms_f32.c | 862 +- .../FilteringFunctions/arm_lms_init_f32.c | 174 +- .../FilteringFunctions/arm_lms_init_q15.c | 194 +- .../FilteringFunctions/arm_lms_init_q31.c | 194 +- .../FilteringFunctions/arm_lms_norm_f32.c | 906 +- .../arm_lms_norm_init_f32.c | 194 +- .../arm_lms_norm_init_q15.c | 208 +- .../arm_lms_norm_init_q31.c | 206 +- .../FilteringFunctions/arm_lms_norm_q15.c | 772 +- .../FilteringFunctions/arm_lms_norm_q31.c | 808 +- .../Source/FilteringFunctions/arm_lms_q15.c | 662 +- .../Source/FilteringFunctions/arm_lms_q31.c | 694 +- .../Source/MatrixFunctions/arm_mat_add_f32.c | 308 +- .../Source/MatrixFunctions/arm_mat_add_q15.c | 316 +- .../Source/MatrixFunctions/arm_mat_add_q31.c | 314 +- .../Source/MatrixFunctions/arm_mat_init_f32.c | 166 +- .../Source/MatrixFunctions/arm_mat_init_q15.c | 150 +- .../Source/MatrixFunctions/arm_mat_init_q31.c | 158 +- .../MatrixFunctions/arm_mat_inverse_f32.c | 1330 +- .../Source/MatrixFunctions/arm_mat_mult_f32.c | 540 +- .../MatrixFunctions/arm_mat_mult_fast_q15.c | 568 +- .../MatrixFunctions/arm_mat_mult_fast_q31.c | 404 +- .../Source/MatrixFunctions/arm_mat_mult_q15.c | 756 +- .../Source/MatrixFunctions/arm_mat_mult_q31.c | 556 +- .../MatrixFunctions/arm_mat_scale_f32.c | 312 +- .../MatrixFunctions/arm_mat_scale_q15.c | 300 +- .../MatrixFunctions/arm_mat_scale_q31.c | 304 +- .../Source/MatrixFunctions/arm_mat_sub_f32.c | 302 +- .../Source/MatrixFunctions/arm_mat_sub_q15.c | 310 +- .../Source/MatrixFunctions/arm_mat_sub_q31.c | 316 +- .../MatrixFunctions/arm_mat_trans_f32.c | 426 +- .../MatrixFunctions/arm_mat_trans_q15.c | 468 +- .../MatrixFunctions/arm_mat_trans_q31.c | 410 +- .../Source/StatisticsFunctions/arm_max_f32.c | 254 +- .../Source/StatisticsFunctions/arm_max_q15.c | 238 +- .../Source/StatisticsFunctions/arm_max_q31.c | 242 +- .../Source/StatisticsFunctions/arm_max_q7.c | 412 +- .../Source/StatisticsFunctions/arm_mean_f32.c | 244 +- .../Source/StatisticsFunctions/arm_mean_q15.c | 238 +- .../Source/StatisticsFunctions/arm_mean_q31.c | 238 +- .../Source/StatisticsFunctions/arm_mean_q7.c | 238 +- .../Source/StatisticsFunctions/arm_min_f32.c | 266 +- .../Source/StatisticsFunctions/arm_min_q15.c | 254 +- .../Source/StatisticsFunctions/arm_min_q31.c | 250 +- .../Source/StatisticsFunctions/arm_min_q7.c | 408 +- .../StatisticsFunctions/arm_power_f32.c | 270 +- .../StatisticsFunctions/arm_power_q15.c | 282 +- .../StatisticsFunctions/arm_power_q31.c | 264 +- .../Source/StatisticsFunctions/arm_power_q7.c | 274 +- .../Source/StatisticsFunctions/arm_rms_f32.c | 260 +- .../Source/StatisticsFunctions/arm_rms_q15.c | 300 +- .../Source/StatisticsFunctions/arm_rms_q31.c | 286 +- .../Source/StatisticsFunctions/arm_std_f32.c | 444 +- .../Source/StatisticsFunctions/arm_std_q15.c | 458 +- .../Source/StatisticsFunctions/arm_std_q31.c | 438 +- .../Source/StatisticsFunctions/arm_var_f32.c | 438 +- .../Source/StatisticsFunctions/arm_var_q15.c | 428 +- .../Source/StatisticsFunctions/arm_var_q31.c | 432 +- .../Source/SupportFunctions/arm_copy_f32.c | 242 +- .../Source/SupportFunctions/arm_copy_q15.c | 260 +- .../Source/SupportFunctions/arm_copy_q31.c | 218 +- .../Source/SupportFunctions/arm_copy_q7.c | 214 +- .../Source/SupportFunctions/arm_fill_f32.c | 244 +- .../Source/SupportFunctions/arm_fill_q15.c | 224 +- .../Source/SupportFunctions/arm_fill_q31.c | 218 +- .../Source/SupportFunctions/arm_fill_q7.c | 220 +- .../SupportFunctions/arm_float_to_q15.c | 386 +- .../SupportFunctions/arm_float_to_q31.c | 400 +- .../Source/SupportFunctions/arm_float_to_q7.c | 384 +- .../SupportFunctions/arm_q15_to_float.c | 246 +- .../Source/SupportFunctions/arm_q15_to_q31.c | 232 +- .../Source/SupportFunctions/arm_q15_to_q7.c | 234 +- .../SupportFunctions/arm_q31_to_float.c | 240 +- .../Source/SupportFunctions/arm_q31_to_q15.c | 232 +- .../Source/SupportFunctions/arm_q31_to_q7.c | 232 +- .../Source/SupportFunctions/arm_q7_to_float.c | 240 +- .../Source/SupportFunctions/arm_q7_to_q15.c | 238 +- .../Source/SupportFunctions/arm_q7_to_q31.c | 232 +- .../TransformFunctions/arm_cfft_radix4_f32.c | 2472 +- .../arm_cfft_radix4_init_f32.c | 2386 +- .../arm_cfft_radix4_init_q15.c | 830 +- .../arm_cfft_radix4_init_q31.c | 1340 +- .../TransformFunctions/arm_cfft_radix4_q15.c | 3904 +- .../TransformFunctions/arm_cfft_radix4_q31.c | 1812 +- .../Source/TransformFunctions/arm_dct4_f32.c | 900 +- .../TransformFunctions/arm_dct4_init_f32.c | 8416 +-- .../TransformFunctions/arm_dct4_init_q15.c | 2380 +- .../TransformFunctions/arm_dct4_init_q31.c | 4396 +- .../Source/TransformFunctions/arm_dct4_q15.c | 766 +- .../Source/TransformFunctions/arm_dct4_q31.c | 768 +- .../Source/TransformFunctions/arm_rfft_f32.c | 766 +- .../TransformFunctions/arm_rfft_init_f32.c | 3414 +- .../TransformFunctions/arm_rfft_init_q15.c | 1376 +- .../TransformFunctions/arm_rfft_init_q31.c | 1362 +- .../Source/TransformFunctions/arm_rfft_q15.c | 914 +- .../Source/TransformFunctions/arm_rfft_q31.c | 652 +- .../FreeRTOS/Source/include/FreeRTOS.h | 1044 +- .../FreeRTOS/Source/include/StackMacros.h | 362 +- .../FreeRTOS/Source/include/croutine.h | 1518 +- .../Libraries/FreeRTOS/Source/include/list.h | 674 +- .../FreeRTOS/Source/include/mpu_wrappers.h | 292 +- .../FreeRTOS/Source/include/portable.h | 806 +- .../FreeRTOS/Source/include/projdefs.h | 180 +- .../Libraries/FreeRTOS/Source/include/queue.h | 2600 +- .../FreeRTOS/Source/include/semphr.h | 1574 +- .../Libraries/FreeRTOS/Source/include/task.h | 2630 +- .../FreeRTOS/Source/include/timers.h | 1904 +- .../Common/Libraries/FreeRTOS/Source/list.c | 408 +- .../Common/Libraries/FreeRTOS/Source/queue.c | 3364 +- .../Common/Libraries/FreeRTOS/Source/tasks.c | 4992 +- .../Common/Libraries/FreeRTOS/Source/timers.c | 1372 +- flight/PiOS/Common/pios_video.c | 944 +- .../Libraries/CMSIS/Core/CM3/core_cm3.c | 1568 +- .../CM3/startup/gcc/startup_stm32f10x_cl.s | 934 +- .../CM3/startup/gcc/startup_stm32f10x_hd.s | 928 +- .../CM3/startup/gcc/startup_stm32f10x_ld.s | 684 +- .../CM3/startup/gcc/startup_stm32f10x_md.s | 714 +- .../Libraries/CMSIS/Core/CM3/stm32f10x.h | 16646 ++--- .../CMSIS/Core/CM3/system_stm32f10x.c | 1860 +- .../CMSIS/Core/CM3/system_stm32f10x.h | 194 +- .../Source/portable/GCC/ARM_CM3/port.c | 600 +- .../Source/portable/GCC/ARM_CM3/portmacro.h | 346 +- .../FreeRTOS/Source/portable/MemMang/heap_1.c | 320 +- .../FreeRTOS/Source/portable/MemMang/heap_2.c | 588 +- .../FreeRTOS/Source/portable/MemMang/heap_3.c | 234 +- .../STM32F10x_StdPeriph_Driver/inc/misc.h | 438 +- .../inc/stm32f10x_adc.h | 964 +- .../inc/stm32f10x_bkp.h | 388 +- .../inc/stm32f10x_can.h | 1166 +- .../inc/stm32f10x_cec.h | 418 +- .../inc/stm32f10x_crc.h | 186 +- .../inc/stm32f10x_dac.h | 632 +- .../inc/stm32f10x_dbgmcu.h | 236 +- .../inc/stm32f10x_dma.h | 876 +- .../inc/stm32f10x_exti.h | 366 +- .../inc/stm32f10x_flash.h | 850 +- .../inc/stm32f10x_fsmc.h | 1464 +- .../inc/stm32f10x_gpio.h | 768 +- .../inc/stm32f10x_i2c.h | 1340 +- .../inc/stm32f10x_iwdg.h | 278 +- .../inc/stm32f10x_pwr.h | 310 +- .../inc/stm32f10x_rcc.h | 1452 +- .../inc/stm32f10x_rtc.h | 268 +- .../inc/stm32f10x_sdio.h | 1060 +- .../inc/stm32f10x_spi.h | 972 +- .../inc/stm32f10x_tim.h | 2274 +- .../inc/stm32f10x_usart.h | 822 +- .../inc/stm32f10x_wwdg.h | 228 +- .../STM32F10x_StdPeriph_Driver/src/misc.c | 446 +- .../src/stm32f10x_adc.c | 2612 +- .../src/stm32f10x_bkp.c | 614 +- .../src/stm32f10x_can.c | 2332 +- .../src/stm32f10x_cec.c | 864 +- .../src/stm32f10x_crc.c | 318 +- .../src/stm32f10x_dac.c | 1140 +- .../src/stm32f10x_dbgmcu.c | 322 +- .../src/stm32f10x_dma.c | 1422 +- .../src/stm32f10x_exti.c | 536 +- .../src/stm32f10x_flash.c | 3366 +- .../src/stm32f10x_fsmc.c | 1726 +- .../src/stm32f10x_gpio.c | 1294 +- .../src/stm32f10x_i2c.c | 2570 +- .../src/stm32f10x_iwdg.c | 378 +- .../src/stm32f10x_pwr.c | 612 +- .../src/stm32f10x_rcc.c | 2938 +- .../src/stm32f10x_rtc.c | 676 +- .../src/stm32f10x_sdio.c | 1596 +- .../src/stm32f10x_spi.c | 1814 +- .../src/stm32f10x_tim.c | 5776 +- .../src/stm32f10x_usart.c | 2110 +- .../src/stm32f10x_wwdg.c | 446 +- .../STM32_USB-FS-Device_Driver/inc/usb_core.h | 494 +- .../STM32_USB-FS-Device_Driver/inc/usb_def.h | 160 +- .../STM32_USB-FS-Device_Driver/inc/usb_init.h | 98 +- .../STM32_USB-FS-Device_Driver/inc/usb_int.h | 66 +- .../STM32_USB-FS-Device_Driver/inc/usb_lib.h | 100 +- .../STM32_USB-FS-Device_Driver/inc/usb_mem.h | 64 +- .../STM32_USB-FS-Device_Driver/inc/usb_regs.h | 1342 +- .../STM32_USB-FS-Device_Driver/inc/usb_sil.h | 68 +- .../STM32_USB-FS-Device_Driver/inc/usb_type.h | 148 +- .../STM32_USB-FS-Device_Driver/src/usb_core.c | 2172 +- .../STM32_USB-FS-Device_Driver/src/usb_init.c | 126 +- .../STM32_USB-FS-Device_Driver/src/usb_int.c | 376 +- .../STM32_USB-FS-Device_Driver/src/usb_mem.c | 150 +- .../STM32_USB-FS-Device_Driver/src/usb_regs.c | 1500 +- .../STM32_USB-FS-Device_Driver/src/usb_sil.c | 252 +- flight/PiOS/STM32F10x/Libraries/msd/msd.c | 882 +- flight/PiOS/STM32F10x/Libraries/msd/msd.h | 156 +- flight/PiOS/STM32F10x/Libraries/msd/msd_bot.c | 668 +- flight/PiOS/STM32F10x/Libraries/msd/msd_bot.h | 190 +- .../PiOS/STM32F10x/Libraries/msd/msd_desc.c | 270 +- .../PiOS/STM32F10x/Libraries/msd/msd_desc.h | 96 +- .../PiOS/STM32F10x/Libraries/msd/msd_memory.c | 484 +- .../PiOS/STM32F10x/Libraries/msd/msd_memory.h | 86 +- .../PiOS/STM32F10x/Libraries/msd/msd_scsi.c | 860 +- .../PiOS/STM32F10x/Libraries/msd/msd_scsi.h | 284 +- .../STM32F10x/Libraries/msd/msd_scsi_data.c | 288 +- flight/PiOS/STM32F10x/library.mk | 2 +- .../link_STM32103CB_CC_Rev1_BL_sections.ld | 228 +- .../link_STM32103CB_CC_Rev1_memory.ld | 14 +- .../link_STM32103CB_CC_Rev1_sections.ld | 288 +- .../link_STM32103CB_PIPXTREME_BL_sections.ld | 228 +- .../link_STM32103CB_PIPXTREME_memory.ld | 16 +- .../link_STM32103CB_PIPXTREME_sections.ld | 288 +- .../STM32F10x/link_STM3210E_OP_BL_sections.ld | 712 +- .../PiOS/STM32F10x/link_STM3210E_OP_memory.ld | 24 +- .../STM32F10x/link_STM3210E_OP_sections.ld | 766 +- flight/PiOS/STM32F10x/link_stm32f10x_HD.ld | 822 +- flight/PiOS/STM32F10x/link_stm32f10x_MD.ld | 174 +- flight/PiOS/STM32F10x/pios_eeprom.c | 312 +- flight/PiOS/STM32F10x/pios_iap.c | 252 +- flight/PiOS/STM32F10x/startup_stm32f10x_HD.S | 954 +- .../PiOS/STM32F10x/startup_stm32f10x_HD_OP.S | 1082 +- flight/PiOS/STM32F10x/startup_stm32f10x_MD.S | 710 +- .../PiOS/STM32F10x/startup_stm32f10x_MD_CC.S | 854 +- .../PiOS/STM32F10x/startup_stm32f10x_MD_PX.S | 854 +- .../STM32F4xx/Source/osd/system_stm32f4xx.c | 1106 +- .../Source/portable/GCC/ARM_CM4F/port.c | 700 +- .../Source/portable/GCC/ARM_CM4F/portmacro.h | 356 +- flight/PiOS/inc/pios_eeprom.h | 100 +- flight/PiOS/inc/pios_iap.h | 90 +- flight/PiOS/inc/pios_overo.h | 84 +- flight/PiOS/inc/pios_overo_priv.h | 116 +- flight/PiOS/inc/pios_rfm22b_priv.h | 1616 +- flight/PiOS/inc/pios_spi.h | 124 +- flight/PiOS/inc/pios_udp.h | 70 +- flight/PiOS/inc/pios_video.h | 208 +- flight/PiOS/inc/stm32f2xx_conf.h | 176 +- flight/PiOS/inc/stm32f4xx_conf.h | 176 +- flight/PiOS/pios_sim_posix.h | 156 +- .../Libraries/FreeRTOS/Source/croutine.c | 742 +- .../FreeRTOS/Source/include/FreeRTOS.h | 840 +- .../FreeRTOS/Source/include/StackMacros.h | 346 +- .../FreeRTOS/Source/include/croutine.h | 1498 +- .../Libraries/FreeRTOS/Source/include/list.h | 610 +- .../FreeRTOS/Source/include/mpu_wrappers.h | 270 +- .../FreeRTOS/Source/include/portable.h | 782 +- .../FreeRTOS/Source/include/projdefs.h | 154 +- .../Libraries/FreeRTOS/Source/include/queue.h | 2522 +- .../FreeRTOS/Source/include/semphr.h | 1422 +- .../Libraries/FreeRTOS/Source/include/task.h | 2526 +- .../posix/Libraries/FreeRTOS/Source/list.c | 382 +- .../Source/portable/GCC/Posix/portmacro.h | 318 +- .../FreeRTOS/Source/portable/MemMang/heap_3.c | 234 +- .../posix/Libraries/FreeRTOS/Source/queue.c | 2930 +- flight/PiOS/posix/pios_delay.c | 200 +- flight/PiOS/posix/pios_iap.c | 138 +- flight/PiOS/posix/pios_led.c | 196 +- flight/PiOS/posix/pios_sdcard.c | 600 +- flight/PiOS/posix/pios_sys.c | 392 +- flight/PiOS/posix/pios_udp.c | 478 +- flight/PiOS/posix/pios_wdg.c | 248 +- .../BootloaderUpdater/inc/pios_config.h | 90 +- flight/targets/BootloaderUpdater/main.c | 332 +- .../Bootloaders/CopterControl/inc/common.h | 230 +- .../Bootloaders/CopterControl/inc/op_dfu.h | 120 +- .../CopterControl/inc/pios_config.h | 106 +- .../targets/Bootloaders/CopterControl/main.c | 410 +- .../Bootloaders/CopterControl/op_dfu.c | 934 +- flight/targets/Bootloaders/OSD/inc/common.h | 230 +- flight/targets/Bootloaders/OSD/inc/op_dfu.h | 120 +- flight/targets/Bootloaders/OSD/main.c | 416 +- flight/targets/Bootloaders/OSD/op_dfu.c | 936 +- .../Bootloaders/PipXtreme/inc/common.h | 230 +- .../Bootloaders/PipXtreme/inc/op_dfu.h | 120 +- .../Bootloaders/PipXtreme/inc/pios_config.h | 104 +- flight/targets/Bootloaders/PipXtreme/main.c | 410 +- flight/targets/Bootloaders/PipXtreme/op_dfu.c | 934 +- .../targets/Bootloaders/RevoMini/inc/common.h | 230 +- .../targets/Bootloaders/RevoMini/inc/op_dfu.h | 120 +- .../Bootloaders/RevoMini/inc/pios_config.h | 86 +- flight/targets/Bootloaders/RevoMini/main.c | 460 +- flight/targets/Bootloaders/RevoMini/op_dfu.c | 936 +- .../Bootloaders/Revolution/inc/common.h | 230 +- .../Bootloaders/Revolution/inc/op_dfu.h | 120 +- flight/targets/Bootloaders/Revolution/main.c | 460 +- .../targets/Bootloaders/Revolution/op_dfu.c | 936 +- flight/targets/CopterControl/System/alarms.c | 428 +- .../targets/CopterControl/System/inc/alarms.h | 98 +- .../CopterControl/System/inc/openpilot.h | 102 +- .../System/inc/pios_board_posix.h | 168 +- .../CopterControl/System/inc/pios_config.h | 340 +- .../System/inc/pios_config_posix.h | 92 +- flight/targets/OSD/System/alarms.c | 420 +- flight/targets/OSD/System/font_outlined8x14.c | 536 +- flight/targets/OSD/System/font_outlined8x8.c | 364 +- flight/targets/OSD/System/fonts.c | 70 +- flight/targets/OSD/System/inc/alarms.h | 100 +- flight/targets/OSD/System/inc/font12x18.h | 19490 +++--- flight/targets/OSD/System/inc/font8x10.h | 11296 ++-- .../OSD/System/inc/font_outlined8x14.h | 24 +- .../targets/OSD/System/inc/font_outlined8x8.h | 24 +- flight/targets/OSD/System/inc/fonts.h | 96 +- flight/targets/OSD/System/inc/openpilot.h | 102 +- flight/targets/OSD/System/inc/pios_config.h | 340 +- flight/targets/OSD/System/inc/splash.h | 2898 +- flight/targets/OSD/System/osd.c | 480 +- flight/targets/PipXtreme/System/alarms.c | 428 +- flight/targets/PipXtreme/System/inc/alarms.h | 98 +- .../targets/PipXtreme/System/inc/openpilot.h | 102 +- .../PipXtreme/System/inc/pios_board_posix.h | 168 +- .../PipXtreme/System/inc/pios_config.h | 334 +- .../PipXtreme/System/inc/pios_config_posix.h | 106 +- flight/targets/RevoMini/Makefile.osx | 1316 +- flight/targets/RevoMini/System/alarms.c | 420 +- flight/targets/RevoMini/System/inc/alarms.h | 98 +- .../targets/RevoMini/System/inc/openpilot.h | 102 +- .../RevoMini/System/inc/pios_board_sim.h | 170 +- .../targets/RevoMini/System/inc/pios_config.h | 342 +- .../RevoMini/System/inc/pios_config_sim.h | 158 +- flight/targets/RevoMini/System/revolution.c | 284 +- flight/targets/Revolution/Makefile.osx | 1310 +- flight/targets/Revolution/System/alarms.c | 420 +- flight/targets/Revolution/System/inc/alarms.h | 98 +- .../targets/Revolution/System/inc/openpilot.h | 102 +- .../Revolution/System/inc/pios_board_sim.h | 170 +- .../Revolution/System/inc/pios_config.h | 350 +- .../Revolution/System/inc/pios_config_sim.h | 164 +- flight/targets/Revolution/System/revolution.c | 284 +- .../SimPosix/System/inc/FreeRTOSConfig.h | 214 +- .../targets/SimPosix/System/inc/openpilot.h | 104 +- .../targets/UAVObjects/inc/eventdispatcher.h | 96 +- .../targets/UAVObjects/inc/uavobjectmanager.h | 418 +- .../UAVObjects/inc/uavobjectsinittemplate.h | 68 +- .../UAVObjects/inc/uavobjecttemplate.h | 208 +- .../UAVObjects/uavobjectsinittemplate.c | 80 +- flight/targets/UAVObjects/uavobjecttemplate.c | 234 +- ground/.gitattributes | 17 + ground/ground.pro | 53 +- ground/openpilotgcs/bin/bin.pro | 28 +- ground/openpilotgcs/copydata.pro | 166 +- ground/openpilotgcs/openpilotgcs.pri | 270 +- ground/openpilotgcs/openpilotgcs.pro | 39 +- .../translations/translations.pro | 172 +- ground/openpilotgcs/share/share.pro | 46 +- ground/openpilotgcs/src/app/app.pro | 76 +- ground/openpilotgcs/src/app/gcssplashscreen.h | 2 +- .../openpilotgcs/src/app/gcsversioninfo.pri | 76 +- .../experimental/USB_UPLOAD_TOOL/SSP/common.h | 36 +- .../experimental/USB_UPLOAD_TOOL/SSP/main.cpp | 150 +- .../experimental/USB_UPLOAD_TOOL/SSP/port.cpp | 82 +- .../experimental/USB_UPLOAD_TOOL/SSP/port.h | 96 +- .../experimental/USB_UPLOAD_TOOL/SSP/qssp.cpp | 1562 +- .../experimental/USB_UPLOAD_TOOL/SSP/qssp.h | 192 +- .../USB_UPLOAD_TOOL/SSP/qsspt.cpp | 150 +- .../experimental/USB_UPLOAD_TOOL/SSP/qsspt.h | 66 +- .../experimental/USB_UPLOAD_TOOL/SSP/ssp.cpp | 1634 +- .../experimental/USB_UPLOAD_TOOL/SSP/ssp.h | 242 +- .../USB_UPLOAD_TOOL/SSP/ssp_test.pro | 84 +- .../experimental/USB_UPLOAD_TOOL/delay.cpp | 6 +- .../src/experimental/USB_UPLOAD_TOOL/delay.h | 26 +- .../experimental/USB_UPLOAD_TOOL/op_dfu.cpp | 1736 +- .../src/experimental/USB_UPLOAD_TOOL/op_dfu.h | 316 +- .../experimental/USB_UPLOAD_TOOL/upload.pro | 156 +- .../src/experimental/finaltest/finaltest.pro | 40 +- .../src/experimental/finaltest/main.cpp | 20 +- .../src/experimental/finaltest/mainwindow.cpp | 296 +- .../src/experimental/finaltest/mainwindow.h | 88 +- .../src/experimental/finaltest/mainwindow.ui | 510 +- .../experimental/finaltest/ui_mainwindow.h | 608 +- .../DocumentationHelper.pro | 32 +- .../tools/DocumentationHelper/main.cpp | 76 +- .../tools/DocumentationHelper/mainwindow.cpp | 488 +- .../tools/DocumentationHelper/mainwindow.h | 118 +- .../tools/DocumentationHelper/mainwindow.ui | 532 +- ground/openpilotgcs/src/gcs_version_info.h | 6 + .../src/libs/aggregation/aggregation.pro | 24 +- .../libs/extensionsystem/extensionsystem.pro | 66 +- .../libs/extensionsystem/plugindetailsview.ui | 448 +- .../libs/extensionsystem/pluginmanager.cpp | 1528 +- .../src/libs/extensionsystem/pluginview.ui | 142 +- .../src/libs/glc_lib/3rdparty/zlib/adler32.c | 298 +- .../src/libs/glc_lib/3rdparty/zlib/compress.c | 158 +- .../src/libs/glc_lib/3rdparty/zlib/crc32.c | 846 +- .../src/libs/glc_lib/3rdparty/zlib/crc32.h | 882 +- .../src/libs/glc_lib/3rdparty/zlib/deflate.c | 3472 +- .../src/libs/glc_lib/3rdparty/zlib/deflate.h | 662 +- .../src/libs/glc_lib/3rdparty/zlib/example.c | 1130 +- .../src/libs/glc_lib/3rdparty/zlib/gzio.c | 2052 +- .../src/libs/glc_lib/3rdparty/zlib/infback.c | 1246 +- .../src/libs/glc_lib/3rdparty/zlib/inffast.c | 636 +- .../src/libs/glc_lib/3rdparty/zlib/inffast.h | 22 +- .../src/libs/glc_lib/3rdparty/zlib/inffixed.h | 188 +- .../src/libs/glc_lib/3rdparty/zlib/inflate.c | 2736 +- .../src/libs/glc_lib/3rdparty/zlib/inflate.h | 230 +- .../src/libs/glc_lib/3rdparty/zlib/inftrees.c | 658 +- .../src/libs/glc_lib/3rdparty/zlib/inftrees.h | 110 +- .../src/libs/glc_lib/3rdparty/zlib/minigzip.c | 644 +- .../src/libs/glc_lib/3rdparty/zlib/trees.c | 2438 +- .../src/libs/glc_lib/3rdparty/zlib/trees.h | 256 +- .../src/libs/glc_lib/3rdparty/zlib/uncompr.c | 122 +- .../src/libs/glc_lib/3rdparty/zlib/zconf.h | 664 +- .../src/libs/glc_lib/3rdparty/zlib/zconf.in.h | 664 +- .../src/libs/glc_lib/3rdparty/zlib/zlib.h | 2736 +- .../src/libs/glc_lib/3rdparty/zlib/zutil.c | 636 +- .../src/libs/glc_lib/3rdparty/zlib/zutil.h | 538 +- .../src/libs/glc_lib/glc_config.h | 88 +- .../libs/glc_lib/glc_fileformatexception.cpp | 102 +- .../libs/glc_lib/glc_fileformatexception.h | 154 +- .../src/libs/glc_lib/io/glc_objmtlloader.cpp | 790 +- .../src/libs/glc_lib/io/glc_objmtlloader.h | 264 +- .../src/libs/glc_lib/io/glc_objtoworld.cpp | 1796 +- .../src/libs/glc_lib/io/glc_objtoworld.h | 538 +- .../src/libs/glc_lib/sceneGraph/glc_world.cpp | 200 +- .../src/libs/glc_lib/sceneGraph/glc_world.h | 570 +- .../glc_lib/shading/glc_selectionmaterial.cpp | 360 +- .../glc_lib/shading/glc_selectionmaterial.h | 216 +- .../libs/libqxt/src/berkeley/qxtbdbtree.cpp | 48 +- .../src/libs/libqxt/src/core/qxtnull.cpp | 54 +- .../libs/libqxt/src/gui/qxtapplication.cpp | 258 +- .../src/libs/libqxt/src/gui/qxtapplication.h | 136 +- .../libqxt/src/gui/qxtapplication_mac.cpp | 46 +- .../libs/libqxt/src/gui/qxtapplication_p.h | 80 +- .../libqxt/src/gui/qxtapplication_win.cpp | 80 +- .../libqxt/src/gui/qxtapplication_x11.cpp | 46 +- .../libs/libqxt/src/gui/qxtbasespinbox.cpp | 434 +- .../libs/libqxt/src/gui/qxtfilterdialog.cpp | 600 +- .../src/libs/libqxt/src/gui/qxtfilterdialog.h | 114 +- .../libs/libqxt/src/gui/qxtfilterdialog_p.h | 110 +- .../src/libs/libqxt/src/gui/qxtflowview.cpp | 1532 +- .../src/libs/libqxt/src/gui/qxtflowview.h | 300 +- .../src/libs/libqxt/src/gui/qxtflowview_p.cpp | 1428 +- .../src/libs/libqxt/src/gui/qxtflowview_p.h | 596 +- .../libs/libqxt/src/gui/qxtglobalshortcut.cpp | 382 +- .../libs/libqxt/src/gui/qxtglobalshortcut.h | 116 +- .../libqxt/src/gui/qxtglobalshortcut_mac.cpp | 414 +- .../libs/libqxt/src/gui/qxtglobalshortcut_p.h | 126 +- .../libqxt/src/gui/qxtglobalshortcut_win.cpp | 428 +- .../libqxt/src/gui/qxtglobalshortcut_x11.cpp | 230 +- .../libs/libqxt/src/gui/qxtlookuplineedit.cpp | 372 +- .../libs/libqxt/src/gui/qxtlookuplineedit.h | 96 +- .../libs/libqxt/src/gui/qxtlookuplineedit_p.h | 56 +- .../libqxt/src/gui/qxtnativeeventfilter.h | 116 +- .../src/libs/libqxt/src/gui/qxtproxystyle.cpp | 14 +- .../src/gui/qxtscheduleheaderwidget.cpp | 178 +- .../libqxt/src/gui/qxtscheduleheaderwidget.h | 98 +- .../src/gui/qxtscheduleitemdelegate.cpp | 564 +- .../libqxt/src/gui/qxtscheduleitemdelegate.h | 130 +- .../libs/libqxt/src/gui/qxtscheduleview.cpp | 1894 +- .../src/libs/libqxt/src/gui/qxtscheduleview.h | 272 +- .../libs/libqxt/src/gui/qxtscheduleview_p.cpp | 1524 +- .../libs/libqxt/src/gui/qxtscheduleview_p.h | 366 +- .../src/gui/qxtscheduleviewheadermodel_p.cpp | 422 +- .../src/gui/qxtscheduleviewheadermodel_p.h | 162 +- .../src/gui/qxtsortfilterproxymodel.cpp | 596 +- .../libqxt/src/gui/qxtsortfilterproxymodel.h | 130 +- .../gui/qxtstyleoptionscheduleviewitem.cpp | 82 +- .../src/gui/qxtstyleoptionscheduleviewitem.h | 112 +- .../libqxt/src/gui/qxtwindowsystem_x11.cpp | 364 +- ground/openpilotgcs/src/libs/libs.pro | 34 +- .../src/libs/opmapcontrol/src/common.pri | 20 +- .../libs/opmapcontrol/src/core/accessmode.h | 172 +- .../opmapcontrol/src/core/alllayersoftype.cpp | 174 +- .../opmapcontrol/src/core/alllayersoftype.h | 86 +- .../src/libs/opmapcontrol/src/core/cache.h | 124 +- .../opmapcontrol/src/core/cacheitemqueue.cpp | 158 +- .../opmapcontrol/src/core/cacheitemqueue.h | 138 +- .../src/libs/opmapcontrol/src/core/core.pro | 80 +- .../libs/opmapcontrol/src/core/debugheader.h | 26 +- .../opmapcontrol/src/core/diagnostics.cpp | 62 +- .../libs/opmapcontrol/src/core/diagnostics.h | 94 +- .../opmapcontrol/src/core/geodecoderstatus.h | 262 +- .../opmapcontrol/src/core/kibertilecache.cpp | 138 +- .../opmapcontrol/src/core/kibertilecache.h | 116 +- .../opmapcontrol/src/core/languagetype.cpp | 200 +- .../libs/opmapcontrol/src/core/languagetype.h | 266 +- .../src/libs/opmapcontrol/src/core/maptype.h | 258 +- .../opmapcontrol/src/core/memorycache.cpp | 120 +- .../libs/opmapcontrol/src/core/memorycache.h | 102 +- .../libs/opmapcontrol/src/core/placemark.cpp | 56 +- .../libs/opmapcontrol/src/core/placemark.h | 108 +- .../src/libs/opmapcontrol/src/core/point.cpp | 148 +- .../src/libs/opmapcontrol/src/core/point.h | 144 +- .../opmapcontrol/src/core/providerstrings.cpp | 176 +- .../opmapcontrol/src/core/providerstrings.h | 170 +- .../libs/opmapcontrol/src/core/pureimage.cpp | 92 +- .../libs/opmapcontrol/src/core/pureimage.h | 88 +- .../libs/opmapcontrol/src/core/rawtile.cpp | 152 +- .../src/libs/opmapcontrol/src/core/rawtile.h | 112 +- .../src/libs/opmapcontrol/src/core/size.cpp | 66 +- .../src/libs/opmapcontrol/src/core/size.h | 116 +- .../opmapcontrol/src/core/tilecachequeue.h | 118 +- .../src/internals/MouseWheelZoomType.cpp | 64 +- .../src/internals/copyrightstrings.h | 82 +- .../opmapcontrol/src/internals/debugheader.h | 16 +- .../opmapcontrol/src/internals/internals.pro | 70 +- .../opmapcontrol/src/internals/loadtask.cpp | 70 +- .../opmapcontrol/src/internals/loadtask.h | 130 +- .../src/internals/mousewheelzoomtype.h | 178 +- .../src/internals/pointlatlng.cpp | 110 +- .../opmapcontrol/src/internals/pointlatlng.h | 260 +- .../internals/projections/lks94projection.cpp | 1582 +- .../internals/projections/lks94projection.h | 144 +- .../projections/mercatorprojection.cpp | 196 +- .../projections/mercatorprojection.h | 110 +- .../projections/mercatorprojectionyandex.cpp | 224 +- .../projections/mercatorprojectionyandex.h | 118 +- .../projections/platecarreeprojection.cpp | 194 +- .../projections/platecarreeprojection.h | 112 +- .../platecarreeprojectionpergo.cpp | 192 +- .../projections/platecarreeprojectionpergo.h | 112 +- .../src/internals/pureprojection.cpp | 554 +- .../src/internals/pureprojection.h | 230 +- .../opmapcontrol/src/internals/rectangle.cpp | 158 +- .../opmapcontrol/src/internals/rectangle.h | 316 +- .../opmapcontrol/src/internals/rectlatlng.cpp | 96 +- .../opmapcontrol/src/internals/rectlatlng.h | 528 +- .../opmapcontrol/src/internals/sizelatlng.cpp | 120 +- .../opmapcontrol/src/internals/sizelatlng.h | 272 +- .../libs/opmapcontrol/src/internals/tile.cpp | 120 +- .../libs/opmapcontrol/src/internals/tile.h | 134 +- .../opmapcontrol/src/internals/tilematrix.cpp | 296 +- .../opmapcontrol/src/internals/tilematrix.h | 108 +- .../src/mapwidget/configuration.cpp | 120 +- .../src/mapwidget/configuration.h | 372 +- .../opmapcontrol/src/mapwidget/homeitem.cpp | 310 +- .../opmapcontrol/src/mapwidget/homeitem.h | 176 +- .../opmapcontrol/src/mapwidget/mapripform.cpp | 108 +- .../opmapcontrol/src/mapwidget/mapripform.h | 106 +- .../opmapcontrol/src/mapwidget/mapripform.ui | 142 +- .../opmapcontrol/src/mapwidget/mapripper.cpp | 312 +- .../opmapcontrol/src/mapwidget/mapripper.h | 134 +- .../opmapcontrol/src/mapwidget/trailitem.cpp | 122 +- .../opmapcontrol/src/mapwidget/trailitem.h | 126 +- .../src/mapwidget/traillineitem.cpp | 96 +- .../src/mapwidget/traillineitem.h | 120 +- .../src/mapwidget/uavmapfollowtype.h | 172 +- .../opmapcontrol/src/mapwidget/uavtrailtype.h | 180 +- .../src/mapwidget/waypointitem.cpp | 1010 +- .../opmapcontrol/src/mapwidget/waypointitem.h | 488 +- .../src/libs/opmapcontrol/src/src.pro | 12 +- .../src/qextserialport_global.h | 30 +- .../src/libs/qextserialport/src/src.pro | 56 +- .../src/libs/qscispinbox/QScienceSpinBox.cpp | 1088 +- .../src/libs/qscispinbox/QScienceSpinBox.h | 100 +- .../src/libs/qscispinbox/qscispinbox.pro | 22 +- .../src/libs/qtconcurrent/qtconcurrent.pro | 20 +- ground/openpilotgcs/src/libs/qwt/qwt.pro | 28 +- .../openpilotgcs/src/libs/qwt/qwtconfig.pri | 252 +- ground/openpilotgcs/src/libs/qwt/src/qwt.h | 44 +- .../src/libs/qwt/src/qwt_abstract_scale.cpp | 620 +- .../src/libs/qwt/src/qwt_abstract_scale.h | 140 +- .../libs/qwt/src/qwt_abstract_scale_draw.cpp | 824 +- .../libs/qwt/src/qwt_abstract_scale_draw.h | 278 +- .../src/libs/qwt/src/qwt_abstract_slider.cpp | 1194 +- .../src/libs/qwt/src/qwt_abstract_slider.h | 376 +- .../src/libs/qwt/src/qwt_analog_clock.cpp | 456 +- .../src/libs/qwt/src/qwt_analog_clock.h | 192 +- .../src/libs/qwt/src/qwt_arrow_button.cpp | 664 +- .../src/libs/qwt/src/qwt_arrow_button.h | 104 +- .../src/libs/qwt/src/qwt_clipper.cpp | 972 +- .../src/libs/qwt/src/qwt_clipper.h | 74 +- .../src/libs/qwt/src/qwt_color_map.cpp | 880 +- .../src/libs/qwt/src/qwt_color_map.h | 396 +- .../src/libs/qwt/src/qwt_column_symbol.cpp | 592 +- .../src/libs/qwt/src/qwt_column_symbol.h | 322 +- .../src/libs/qwt/src/qwt_compass.cpp | 584 +- .../src/libs/qwt/src/qwt_compass.h | 130 +- .../src/libs/qwt/src/qwt_compass_rose.cpp | 540 +- .../src/libs/qwt/src/qwt_compass_rose.h | 178 +- .../src/libs/qwt/src/qwt_compat.h | 80 +- .../src/libs/qwt/src/qwt_counter.cpp | 1206 +- .../src/libs/qwt/src/qwt_counter.h | 320 +- .../src/libs/qwt/src/qwt_curve_fitter.cpp | 810 +- .../src/libs/qwt/src/qwt_curve_fitter.h | 256 +- .../src/libs/qwt/src/qwt_dial.cpp | 2310 +- .../openpilotgcs/src/libs/qwt/src/qwt_dial.h | 430 +- .../src/libs/qwt/src/qwt_dial_needle.cpp | 904 +- .../src/libs/qwt/src/qwt_dial_needle.h | 380 +- .../src/libs/qwt/src/qwt_double_range.cpp | 820 +- .../src/libs/qwt/src/qwt_double_range.h | 156 +- .../src/libs/qwt/src/qwt_dyngrid_layout.cpp | 1142 +- .../src/libs/qwt/src/qwt_dyngrid_layout.h | 166 +- .../src/libs/qwt/src/qwt_event_pattern.cpp | 548 +- .../src/libs/qwt/src/qwt_event_pattern.h | 450 +- .../src/libs/qwt/src/qwt_global.h | 88 +- .../src/libs/qwt/src/qwt_interval.cpp | 668 +- .../src/libs/qwt/src/qwt_interval.h | 592 +- .../src/libs/qwt/src/qwt_interval_symbol.cpp | 596 +- .../src/libs/qwt/src/qwt_interval_symbol.h | 172 +- .../src/libs/qwt/src/qwt_knob.cpp | 1332 +- .../openpilotgcs/src/libs/qwt/src/qwt_knob.h | 318 +- .../src/libs/qwt/src/qwt_legend.cpp | 1036 +- .../src/libs/qwt/src/qwt_legend.h | 190 +- .../src/libs/qwt/src/qwt_legend_item.cpp | 808 +- .../src/libs/qwt/src/qwt_legend_item.h | 156 +- .../src/libs/qwt/src/qwt_legend_itemmanager.h | 132 +- .../src/libs/qwt/src/qwt_magnifier.cpp | 946 +- .../src/libs/qwt/src/qwt_magnifier.h | 172 +- .../src/libs/qwt/src/qwt_math.cpp | 90 +- .../openpilotgcs/src/libs/qwt/src/qwt_math.h | 364 +- .../libs/qwt/src/qwt_matrix_raster_data.cpp | 540 +- .../src/libs/qwt/src/qwt_matrix_raster_data.h | 142 +- .../src/libs/qwt/src/qwt_null_paintdevice.cpp | 856 +- .../src/libs/qwt/src/qwt_null_paintdevice.h | 178 +- .../src/libs/qwt/src/qwt_painter.cpp | 1408 +- .../src/libs/qwt/src/qwt_painter.h | 298 +- .../src/libs/qwt/src/qwt_panner.cpp | 1068 +- .../src/libs/qwt/src/qwt_panner.h | 200 +- .../src/libs/qwt/src/qwt_picker.cpp | 2868 +- .../src/libs/qwt/src/qwt_picker.h | 654 +- .../src/libs/qwt/src/qwt_picker_machine.cpp | 900 +- .../src/libs/qwt/src/qwt_picker_machine.h | 380 +- .../src/libs/qwt/src/qwt_plot.cpp | 1496 +- .../openpilotgcs/src/libs/qwt/src/qwt_plot.h | 580 +- .../src/libs/qwt/src/qwt_plot_axis.cpp | 1340 +- .../src/libs/qwt/src/qwt_plot_canvas.cpp | 2158 +- .../src/libs/qwt/src/qwt_plot_canvas.h | 336 +- .../src/libs/qwt/src/qwt_plot_curve.cpp | 2248 +- .../src/libs/qwt/src/qwt_plot_curve.h | 638 +- .../src/libs/qwt/src/qwt_plot_dict.cpp | 376 +- .../src/libs/qwt/src/qwt_plot_dict.h | 112 +- .../libs/qwt/src/qwt_plot_directpainter.cpp | 626 +- .../src/libs/qwt/src/qwt_plot_directpainter.h | 200 +- .../src/libs/qwt/src/qwt_plot_grid.cpp | 734 +- .../src/libs/qwt/src/qwt_plot_grid.h | 168 +- .../src/libs/qwt/src/qwt_plot_histogram.cpp | 1296 +- .../src/libs/qwt/src/qwt_plot_histogram.h | 268 +- .../libs/qwt/src/qwt_plot_intervalcurve.cpp | 1094 +- .../src/libs/qwt/src/qwt_plot_intervalcurve.h | 260 +- .../src/libs/qwt/src/qwt_plot_item.cpp | 1084 +- .../src/libs/qwt/src/qwt_plot_item.h | 384 +- .../src/libs/qwt/src/qwt_plot_layout.cpp | 2454 +- .../src/libs/qwt/src/qwt_plot_layout.h | 210 +- .../src/libs/qwt/src/qwt_plot_magnifier.cpp | 286 +- .../src/libs/qwt/src/qwt_plot_magnifier.h | 110 +- .../src/libs/qwt/src/qwt_plot_marker.cpp | 1204 +- .../src/libs/qwt/src/qwt_plot_marker.h | 248 +- .../src/libs/qwt/src/qwt_plot_panner.cpp | 350 +- .../src/libs/qwt/src/qwt_plot_panner.h | 120 +- .../src/libs/qwt/src/qwt_plot_picker.cpp | 764 +- .../src/libs/qwt/src/qwt_plot_picker.h | 226 +- .../src/libs/qwt/src/qwt_plot_rasteritem.cpp | 1808 +- .../src/libs/qwt/src/qwt_plot_rasteritem.h | 292 +- .../src/libs/qwt/src/qwt_plot_renderer.cpp | 1666 +- .../src/libs/qwt/src/qwt_plot_renderer.h | 308 +- .../src/libs/qwt/src/qwt_plot_rescaler.cpp | 1248 +- .../src/libs/qwt/src/qwt_plot_rescaler.h | 286 +- .../src/libs/qwt/src/qwt_plot_scaleitem.cpp | 886 +- .../src/libs/qwt/src/qwt_plot_scaleitem.h | 188 +- .../src/libs/qwt/src/qwt_plot_seriesitem.cpp | 180 +- .../src/libs/qwt/src/qwt_plot_seriesitem.h | 406 +- .../libs/qwt/src/qwt_plot_spectrocurve.cpp | 600 +- .../src/libs/qwt/src/qwt_plot_spectrocurve.h | 152 +- .../src/libs/qwt/src/qwt_plot_spectrogram.cpp | 1330 +- .../src/libs/qwt/src/qwt_plot_spectrogram.h | 230 +- .../src/libs/qwt/src/qwt_plot_svgitem.cpp | 428 +- .../src/libs/qwt/src/qwt_plot_svgitem.h | 122 +- .../src/libs/qwt/src/qwt_plot_xml.cpp | 82 +- .../src/libs/qwt/src/qwt_plot_zoomer.cpp | 1214 +- .../src/libs/qwt/src/qwt_plot_zoomer.h | 208 +- .../src/libs/qwt/src/qwt_point_3d.cpp | 44 +- .../src/libs/qwt/src/qwt_point_3d.h | 378 +- .../src/libs/qwt/src/qwt_point_polar.cpp | 228 +- .../src/libs/qwt/src/qwt_point_polar.h | 390 +- .../src/libs/qwt/src/qwt_raster_data.cpp | 780 +- .../src/libs/qwt/src/qwt_raster_data.h | 190 +- .../src/libs/qwt/src/qwt_round_scale_draw.cpp | 612 +- .../src/libs/qwt/src/qwt_round_scale_draw.h | 136 +- .../src/libs/qwt/src/qwt_sampling_thread.cpp | 212 +- .../src/libs/qwt/src/qwt_sampling_thread.h | 100 +- .../src/libs/qwt/src/qwt_scale_div.cpp | 346 +- .../src/libs/qwt/src/qwt_scale_div.h | 264 +- .../src/libs/qwt/src/qwt_scale_draw.cpp | 1798 +- .../src/libs/qwt/src/qwt_scale_draw.h | 234 +- .../src/libs/qwt/src/qwt_scale_engine.cpp | 1884 +- .../src/libs/qwt/src/qwt_scale_engine.h | 434 +- .../src/libs/qwt/src/qwt_scale_map.cpp | 688 +- .../src/libs/qwt/src/qwt_scale_map.h | 438 +- .../src/libs/qwt/src/qwt_scale_widget.cpp | 1834 +- .../src/libs/qwt/src/qwt_scale_widget.h | 270 +- .../src/libs/qwt/src/qwt_series_data.cpp | 1172 +- .../src/libs/qwt/src/qwt_series_data.h | 884 +- .../src/libs/qwt/src/qwt_slider.cpp | 1610 +- .../src/libs/qwt/src/qwt_slider.h | 300 +- .../src/libs/qwt/src/qwt_spline.cpp | 760 +- .../src/libs/qwt/src/qwt_spline.h | 202 +- .../src/libs/qwt/src/qwt_symbol.cpp | 2008 +- .../src/libs/qwt/src/qwt_symbol.h | 308 +- .../src/libs/qwt/src/qwt_system_clock.cpp | 728 +- .../src/libs/qwt/src/qwt_system_clock.h | 98 +- .../src/libs/qwt/src/qwt_text.cpp | 1286 +- .../openpilotgcs/src/libs/qwt/src/qwt_text.h | 432 +- .../src/libs/qwt/src/qwt_text_engine.cpp | 688 +- .../src/libs/qwt/src/qwt_text_engine.h | 344 +- .../src/libs/qwt/src/qwt_text_label.cpp | 612 +- .../src/libs/qwt/src/qwt_text_label.h | 144 +- .../src/libs/qwt/src/qwt_thermo.cpp | 2072 +- .../src/libs/qwt/src/qwt_thermo.h | 404 +- .../src/libs/qwt/src/qwt_wheel.cpp | 1076 +- .../openpilotgcs/src/libs/qwt/src/qwt_wheel.h | 178 +- ground/openpilotgcs/src/libs/qwt/src/src.pro | 412 +- .../src/libs/sdlgamepad/sdlgamepad.cpp | 378 +- .../src/libs/sdlgamepad/sdlgamepad.h | 722 +- .../src/libs/sdlgamepad/sdlgamepad_global.h | 72 +- .../src/libs/utils/homelocationutil.cpp | 148 +- .../src/libs/utils/homelocationutil.h | 106 +- .../src/libs/utils/svgimageprovider.cpp | 484 +- .../src/libs/utils/svgimageprovider.h | 114 +- ground/openpilotgcs/src/libs/utils/utils.pro | 248 +- .../openpilotgcs/src/openpilotgcslibrary.pri | 46 +- .../openpilotgcs/src/openpilotgcsplugin.pri | 100 +- .../antennatrack/AntennaTrack.pluginspec | 22 +- .../src/plugins/antennatrack/antennatrack.pro | 50 +- .../antennatrack/antennatrackgadget.cpp | 310 +- .../plugins/antennatrack/antennatrackgadget.h | 144 +- .../antennatrackgadgetconfiguration.cpp | 218 +- .../antennatrackgadgetconfiguration.h | 156 +- .../antennatrackgadgetfactory.cpp | 120 +- .../antennatrack/antennatrackgadgetfactory.h | 104 +- .../antennatrackgadgetoptionspage.cpp | 532 +- .../antennatrackgadgetoptionspage.h | 152 +- .../antennatrackgadgetoptionspage.ui | 372 +- .../antennatrack/antennatrackplugin.cpp | 68 +- .../plugins/antennatrack/antennatrackplugin.h | 42 +- .../antennatrack/antennatrackwidget.cpp | 412 +- .../plugins/antennatrack/antennatrackwidget.h | 150 +- .../antennatrack/antennatrackwidget.ui | 958 +- .../src/plugins/antennatrack/gpsparser.cpp | 86 +- .../src/plugins/antennatrack/gpsparser.h | 118 +- .../plugins/antennatrack/telemetryparser.cpp | 162 +- .../plugins/antennatrack/telemetryparser.h | 104 +- .../src/plugins/config/Config.pluginspec | 30 +- .../src/plugins/config/assertions.h | 156 +- .../src/plugins/config/camerastabilization.ui | 3298 +- .../src/plugins/config/cc_hw_settings.ui | 1268 +- .../src/plugins/config/ccattitude.ui | 1180 +- .../src/plugins/config/pipxtreme.ui | 4032 +- .../src/plugins/config/stabilization.ui | 50296 ++++++++-------- .../openpilotgcs/src/plugins/config/txpid.ui | 1700 +- .../plugins/consolegadget/consolegadget.cpp | 102 +- .../src/plugins/consolegadget/consolegadget.h | 118 +- .../consolegadget/consolegadgetfactory.cpp | 94 +- .../consolegadget/consolegadgetfactory.h | 100 +- .../consolegadget/consolegadgetwidget.cpp | 88 +- .../consolegadget/consolegadgetwidget.h | 88 +- .../plugins/consolegadget/consoleplugin.cpp | 130 +- .../src/plugins/consolegadget/consoleplugin.h | 94 +- .../consolegadget/texteditloggerengine.cpp | 270 +- .../consolegadget/texteditloggerengine.h | 114 +- .../src/plugins/coreplugin/Core.pluginspec | 14 +- .../actionmanager/actioncontainer.cpp | 938 +- .../actionmanager/actioncontainer.h | 138 +- .../actionmanager/actioncontainer_p.h | 254 +- .../actionmanager/actionmanager.cpp | 998 +- .../coreplugin/actionmanager/actionmanager.h | 134 +- .../actionmanager/actionmanager_p.h | 238 +- .../coreplugin/actionmanager/command.cpp | 1018 +- .../coreplugin/actionmanager/command.h | 172 +- .../coreplugin/actionmanager/command_p.h | 320 +- .../coreplugin/actionmanager/commandsfile.cpp | 238 +- .../coreplugin/actionmanager/commandsfile.h | 120 +- .../src/plugins/coreplugin/authorsdialog.cpp | 265 +- .../src/plugins/coreplugin/authorsdialog.h | 94 +- .../src/plugins/coreplugin/basemode.cpp | 170 +- .../src/plugins/coreplugin/basemode.h | 152 +- .../src/plugins/coreplugin/baseview.cpp | 182 +- .../src/plugins/coreplugin/baseview.h | 130 +- .../src/plugins/coreplugin/core_global.h | 80 +- .../src/plugins/coreplugin/coreconstants.h | 498 +- .../src/plugins/coreplugin/coreplugin.cpp | 162 +- .../src/plugins/coreplugin/coreplugin.h | 122 +- .../coreplugin/dialogs/ioptionspage.cpp | 90 +- .../plugins/coreplugin/dialogs/ioptionspage.h | 144 +- .../plugins/coreplugin/dialogs/iwizard.cpp | 328 +- .../src/plugins/coreplugin/dialogs/iwizard.h | 146 +- .../coreplugin/dialogs/settingsdialog.cpp | 782 +- .../coreplugin/dialogs/settingsdialog.h | 172 +- .../coreplugin/dialogs/shortcutsettings.cpp | 734 +- .../coreplugin/dialogs/shortcutsettings.h | 216 +- .../coreplugin/eventfilteringmainwindow.cpp | 104 +- .../coreplugin/eventfilteringmainwindow.h | 122 +- .../src/plugins/coreplugin/fancyactionbar.cpp | 356 +- .../src/plugins/coreplugin/fancyactionbar.h | 152 +- .../src/plugins/coreplugin/fancytabwidget.cpp | 964 +- .../src/plugins/coreplugin/fancytabwidget.h | 322 +- .../plugins/coreplugin/fileiconprovider.cpp | 326 +- .../src/plugins/coreplugin/fileiconprovider.h | 146 +- .../src/plugins/coreplugin/iconnection.cpp | 60 +- .../src/plugins/coreplugin/icontext.h | 148 +- .../src/plugins/coreplugin/icore.cpp | 694 +- .../src/plugins/coreplugin/icorelistener.h | 144 +- .../src/plugins/coreplugin/imode.h | 116 +- .../src/plugins/coreplugin/ioutputpane.h | 228 +- .../src/plugins/coreplugin/iuavgadget.cpp | 56 +- .../src/plugins/coreplugin/iuavgadget.h | 162 +- .../coreplugin/iuavgadgetconfiguration.cpp | 78 +- .../coreplugin/iuavgadgetconfiguration.h | 144 +- .../plugins/coreplugin/iuavgadgetfactory.h | 160 +- .../src/plugins/coreplugin/iversioncontrol.h | 236 +- .../src/plugins/coreplugin/iview.h | 106 +- .../src/plugins/coreplugin/manhattanstyle.cpp | 2188 +- .../src/plugins/coreplugin/manhattanstyle.h | 190 +- .../src/plugins/coreplugin/messagemanager.cpp | 188 +- .../src/plugins/coreplugin/messagemanager.h | 138 +- .../coreplugin/messageoutputwindow.cpp | 230 +- .../plugins/coreplugin/messageoutputwindow.h | 150 +- .../src/plugins/coreplugin/mimedatabase.cpp | 2360 +- .../src/plugins/coreplugin/mimedatabase.h | 452 +- .../src/plugins/coreplugin/minisplitter.cpp | 206 +- .../src/plugins/coreplugin/minisplitter.h | 110 +- .../src/plugins/coreplugin/modemanager.cpp | 676 +- .../src/plugins/coreplugin/modemanager.h | 226 +- .../src/plugins/coreplugin/outputpane.h | 286 +- .../src/plugins/coreplugin/plugindialog.cpp | 278 +- .../src/plugins/coreplugin/plugindialog.h | 140 +- .../src/plugins/coreplugin/rightpane.cpp | 484 +- .../src/plugins/coreplugin/rightpane.h | 238 +- .../plugins/coreplugin/settingsdatabase.cpp | 514 +- .../src/plugins/coreplugin/settingsdatabase.h | 138 +- .../src/plugins/coreplugin/sidebar.cpp | 754 +- .../src/plugins/coreplugin/sidebar.h | 364 +- .../src/plugins/coreplugin/styleanimator.cpp | 306 +- .../src/plugins/coreplugin/styleanimator.h | 200 +- .../coreplugin/tabpositionindicator.cpp | 104 +- .../plugins/coreplugin/tabpositionindicator.h | 108 +- .../src/plugins/coreplugin/threadmanager.cpp | 106 +- .../src/plugins/coreplugin/threadmanager.h | 124 +- .../plugins/coreplugin/uavgadgetdecorator.cpp | 260 +- .../plugins/coreplugin/uavgadgetdecorator.h | 134 +- .../uavgadgetmanager/splitterorview.cpp | 750 +- .../uavgadgetmanager/splitterorview.h | 220 +- .../uavgadgetmanager/uavgadgetmanager.cpp | 890 +- .../uavgadgetmanager/uavgadgetmanager.h | 276 +- .../uavgadgetmanager/uavgadgetview.cpp | 586 +- .../uavgadgetmanager/uavgadgetview.h | 214 +- .../uavgadgetoptionspagedecorator.cpp | 218 +- .../uavgadgetoptionspagedecorator.h | 160 +- .../plugins/coreplugin/uniqueidmanager.cpp | 130 +- .../src/plugins/coreplugin/uniqueidmanager.h | 116 +- .../plugins/coreplugin/variablemanager.cpp | 224 +- .../src/plugins/coreplugin/variablemanager.h | 140 +- .../src/plugins/coreplugin/versiondialog.cpp | 262 +- .../src/plugins/coreplugin/versiondialog.h | 99 +- .../plugins/coreplugin/workspacesettings.cpp | 504 +- .../plugins/coreplugin/workspacesettings.h | 196 +- .../src/plugins/dial/DialGadget.pluginspec | 22 +- ground/openpilotgcs/src/plugins/dial/dial.pro | 44 +- .../src/plugins/dial/dialgadget.h | 114 +- .../src/plugins/dial/dialgadgetfactory.cpp | 122 +- .../src/plugins/dial/dialgadgetfactory.h | 106 +- .../src/plugins/dial/dialgadgetoptionspage.h | 146 +- .../src/plugins/dial/dialplugin.cpp | 134 +- .../src/plugins/dial/dialplugin.h | 96 +- .../plugins/donothing/DoNothing.pluginspec | 20 +- .../src/plugins/donothing/donothing.pro | 20 +- .../src/plugins/donothing/donothingplugin.cpp | 116 +- .../src/plugins/donothing/donothingplugin.h | 84 +- .../src/plugins/emptygadget/emptygadget.h | 118 +- .../emptygadget/emptygadgetfactory.cpp | 94 +- .../plugins/emptygadget/emptygadgetfactory.h | 100 +- .../plugins/emptygadget/emptygadgetwidget.cpp | 100 +- .../plugins/emptygadget/emptygadgetwidget.h | 88 +- .../src/plugins/emptygadget/emptyplugin.cpp | 130 +- .../src/plugins/emptygadget/emptyplugin.h | 94 +- .../src/plugins/gcscontrol/gcscontrolgadget.h | 194 +- .../gcscontrolgadgetconfiguration.cpp | 324 +- .../gcscontrolgadgetconfiguration.h | 180 +- .../gcscontrol/gcscontrolgadgetfactory.cpp | 118 +- .../gcscontrol/gcscontrolgadgetfactory.h | 110 +- .../gcscontrolgadgetoptionspage.cpp | 814 +- .../gcscontrol/gcscontrolgadgetoptionspage.h | 188 +- .../gcscontrol/gcscontrolgadgetoptionspage.ui | 2214 +- .../gcscontrol/gcscontrolgadgetwidget.h | 148 +- .../plugins/gcscontrol/gcscontrolplugin.cpp | 150 +- .../src/plugins/gcscontrol/gcscontrolplugin.h | 102 +- .../gcscontrol/gcsonctrolgadgetwidget.h | 88 +- .../gpsdisplay/GpsDisplayGadget.pluginspec | 22 +- .../src/plugins/gpsdisplay/buffer.cpp | 278 +- .../src/plugins/gpsdisplay/buffer.h | 174 +- .../gpsdisplay/gpsconstellationwidget.h | 134 +- .../src/plugins/gpsdisplay/gpsdisplay.pro | 70 +- .../src/plugins/gpsdisplay/gpsdisplaygadget.h | 146 +- .../gpsdisplaygadgetconfiguration.cpp | 218 +- .../gpsdisplaygadgetconfiguration.h | 156 +- .../gpsdisplay/gpsdisplaygadgetfactory.cpp | 120 +- .../gpsdisplay/gpsdisplaygadgetfactory.h | 104 +- .../gpsdisplaygadgetoptionspage.cpp | 536 +- .../gpsdisplay/gpsdisplaygadgetoptionspage.h | 152 +- .../gpsdisplay/gpsdisplaygadgetoptionspage.ui | 564 +- .../plugins/gpsdisplay/gpsdisplayplugin.cpp | 130 +- .../src/plugins/gpsdisplay/gpsdisplayplugin.h | 94 +- .../plugins/gpsdisplay/gpsdisplaywidget.cpp | 316 +- .../src/plugins/gpsdisplay/gpsdisplaywidget.h | 124 +- .../src/plugins/gpsdisplay/gpsparser.cpp | 86 +- .../src/plugins/gpsdisplay/gpsparser.h | 116 +- .../src/plugins/gpsdisplay/gpssnrwidget.cpp | 268 +- .../src/plugins/gpsdisplay/gpssnrwidget.h | 70 +- .../src/plugins/gpsdisplay/nmeaparser.cpp | 1028 +- .../src/plugins/gpsdisplay/nmeaparser.h | 172 +- .../plugins/gpsdisplay/telemetryparser.cpp | 250 +- .../src/plugins/gpsdisplay/telemetryparser.h | 110 +- .../src/plugins/hitl/fgsimulator.cpp | 700 +- .../src/plugins/hitl/fgsimulator.h | 140 +- .../src/plugins/hitl/hitl.pluginspec | 24 +- .../src/plugins/hitl/hitlconfiguration.cpp | 328 +- .../src/plugins/hitl/hitlconfiguration.h | 124 +- .../src/plugins/hitl/hitlfactory.cpp | 122 +- .../src/plugins/hitl/hitlfactory.h | 104 +- .../src/plugins/hitl/hitlgadget.h | 120 +- .../src/plugins/hitl/hitlnoisegeneration.cpp | 156 +- .../src/plugins/hitl/hitlnoisegeneration.h | 132 +- .../src/plugins/hitl/hitloptionspage.cpp | 350 +- .../src/plugins/hitl/hitloptionspage.h | 130 +- .../src/plugins/hitl/hitlplugin.cpp | 150 +- .../src/plugins/hitl/hitlplugin.h | 142 +- .../src/plugins/hitl/hitlwidget.cpp | 424 +- .../src/plugins/hitl/hitlwidget.h | 144 +- .../src/plugins/hitl/hitlwidget.ui | 942 +- .../src/plugins/hitl/il2simulator.cpp | 594 +- .../src/plugins/hitl/il2simulator.h | 152 +- .../src/plugins/hitl/isimulator.h | 148 +- .../src/plugins/hitl/simulator.cpp | 1706 +- .../openpilotgcs/src/plugins/hitl/simulator.h | 740 +- .../src/plugins/hitl/xplanesimulator.cpp | 748 +- .../src/plugins/hitl/xplanesimulator.h | 182 +- .../ipconnection/IPconnection.pluginspec | 20 +- .../src/plugins/ipconnection/ipconnection.pro | 34 +- .../ipconnection/ipconnection_global.h | 78 +- .../ipconnection/ipconnection_internal.h | 46 +- .../ipconnectionconfiguration.cpp | 186 +- .../ipconnection/ipconnectionconfiguration.h | 148 +- .../ipconnection/ipconnectionoptionspage.cpp | 164 +- .../ipconnection/ipconnectionoptionspage.h | 142 +- .../lineardial/LineardialGadget.pluginspec | 22 +- .../src/plugins/lineardial/lineardialgadget.h | 112 +- .../lineardial/lineardialgadgetfactory.cpp | 120 +- .../lineardial/lineardialgadgetfactory.h | 104 +- .../lineardial/lineardialgadgetoptionspage.h | 144 +- .../plugins/lineardial/lineardialplugin.cpp | 132 +- .../src/plugins/lineardial/lineardialplugin.h | 94 +- .../src/plugins/logging/logginggadget.h | 120 +- .../plugins/logging/logginggadgetfactory.cpp | 98 +- .../plugins/logging/logginggadgetfactory.h | 110 +- .../magicwaypoint/magicwaypointgadget.h | 120 +- .../magicwaypointgadgetfactory.cpp | 96 +- .../magicwaypointgadgetfactory.h | 100 +- .../magicwaypointgadgetwidget.cpp | 286 +- .../magicwaypoint/magicwaypointgadgetwidget.h | 122 +- .../magicwaypoint/magicwaypointplugin.cpp | 138 +- .../magicwaypoint/magicwaypointplugin.h | 94 +- .../modelview/ModelViewGadget.pluginspec | 20 +- .../src/plugins/modelview/modelviewgadget.h | 112 +- .../modelviewgadgetconfiguration.cpp | 128 +- .../modelview/modelviewgadgetconfiguration.h | 118 +- .../modelview/modelviewgadgetfactory.cpp | 118 +- .../modelview/modelviewgadgetfactory.h | 104 +- .../modelview/modelviewgadgetoptionspage.cpp | 146 +- .../modelview/modelviewgadgetoptionspage.h | 148 +- .../plugins/modelview/modelviewgadgetwidget.h | 194 +- .../src/plugins/modelview/modelviewplugin.cpp | 130 +- .../src/plugins/modelview/modelviewplugin.h | 94 +- .../plugins/notify/NotifyPlugin.pluginspec | 22 +- .../src/plugins/notify/notify.pro | 66 +- .../src/plugins/notify/notifyitemdelegate.cpp | 312 +- .../src/plugins/notify/notifyitemdelegate.h | 112 +- .../plugins/notify/notifypluginfactory.cpp | 122 +- .../src/plugins/notify/notifypluginfactory.h | 106 +- .../src/plugins/notify/notifyplugingadget.h | 112 +- .../plugins/notify/notifypluginoptionspage.ui | 850 +- .../src/plugins/notify/notifytablemodel.cpp | 532 +- .../src/plugins/notify/notifytablemodel.h | 180 +- .../openpilotgcs/src/plugins/notify/res.qrc | 20 +- .../opmap/opmap_edit_waypoint_dialog.cpp | 622 +- .../opmap/opmap_edit_waypoint_dialog.h | 146 +- .../opmap/opmap_edit_waypoint_dialog.ui | 1680 +- .../src/plugins/opmap/opmap_overlay_widget.ui | 800 +- .../plugins/opmap/opmap_statusbar_widget.cpp | 82 +- .../plugins/opmap/opmap_statusbar_widget.h | 98 +- .../plugins/opmap/opmap_statusbar_widget.ui | 368 +- .../opmap/opmap_zoom_slider_widget.cpp | 82 +- .../plugins/opmap/opmap_zoom_slider_widget.h | 98 +- .../plugins/opmap/opmap_zoom_slider_widget.ui | 392 +- .../src/plugins/opmap/opmapgadget.h | 120 +- .../opmap/opmapgadgetconfiguration.cpp | 274 +- .../plugins/opmap/opmapgadgetconfiguration.h | 204 +- .../plugins/opmap/opmapgadgetoptionspage.cpp | 298 +- .../plugins/opmap/opmapgadgetoptionspage.h | 134 +- .../plugins/opmap/opmapgadgetoptionspage.ui | 1030 +- .../src/plugins/opmap/opmapplugin.cpp | 126 +- .../src/plugins/opmap/opmapplugin.h | 94 +- .../OsgEarthviewGadget.pluginspec | 22 +- .../plugins/osgearthview/osgearthviewgadget.h | 110 +- .../osgearthviewgadgetconfiguration.cpp | 114 +- .../osgearthviewgadgetconfiguration.h | 92 +- .../osgearthviewgadgetfactory.cpp | 116 +- .../osgearthview/osgearthviewgadgetfactory.h | 104 +- .../osgearthviewgadgetoptionspage.cpp | 142 +- .../osgearthviewgadgetoptionspage.h | 130 +- .../osgearthview/osgearthviewplugin.cpp | 136 +- .../plugins/osgearthview/osgearthviewplugin.h | 94 +- .../osgearthview/osgearthviewwidget.cpp | 252 +- .../plugins/osgearthview/osgearthviewwidget.h | 206 +- .../pathactioneditor/browseritemdelegate.cpp | 150 +- .../pathactioneditor/browseritemdelegate.h | 116 +- .../pathactioneditor/fieldtreeitem.cpp | 58 +- .../pathactioneditor/pathactioneditorgadget.h | 118 +- .../pathactioneditorgadgetfactory.cpp | 94 +- .../pathactioneditorgadgetfactory.h | 98 +- .../pathactioneditorgadgetwidget.cpp | 226 +- .../pathactioneditorgadgetwidget.h | 122 +- .../pathactioneditorplugin.cpp | 136 +- .../pathactioneditor/pathactioneditorplugin.h | 92 +- .../pathactioneditortreemodel.cpp | 846 +- .../pathactioneditortreemodel.h | 196 +- .../src/plugins/pathactioneditor/treeitem.cpp | 244 +- .../src/plugins/pathactioneditor/treeitem.h | 376 +- .../src/plugins/pfd/PFDGadget.pluginspec | 22 +- .../openpilotgcs/src/plugins/pfd/pfdgadget.h | 112 +- .../plugins/pfd/pfdgadgetconfiguration.cpp | 148 +- .../src/plugins/pfd/pfdgadgetconfiguration.h | 126 +- .../src/plugins/pfd/pfdgadgetfactory.cpp | 120 +- .../src/plugins/pfd/pfdgadgetfactory.h | 104 +- .../src/plugins/pfd/pfdgadgetoptionspage.cpp | 178 +- .../src/plugins/pfd/pfdgadgetoptionspage.h | 130 +- .../src/plugins/pfd/pfdgadgetwidget.cpp | 2178 +- .../src/plugins/pfd/pfdgadgetwidget.h | 312 +- .../src/plugins/pfd/pfdplugin.cpp | 132 +- .../openpilotgcs/src/plugins/pfd/pfdplugin.h | 94 +- .../src/plugins/pfdqml/PfdQml.pluginspec | 24 +- .../pfdqml/pfdqmlgadgetconfiguration.cpp | 182 +- .../pfdqml/pfdqmlgadgetconfiguration.h | 130 +- .../plugins/pfdqml/pfdqmlgadgetfactory.cpp | 98 +- .../src/plugins/pfdqml/pfdqmlgadgetfactory.h | 82 +- .../pfdqml/pfdqmlgadgetoptionspage.cpp | 202 +- .../plugins/pfdqml/pfdqmlgadgetoptionspage.h | 108 +- .../src/plugins/pfdqml/pfdqmlgadgetwidget.cpp | 340 +- .../src/plugins/pfdqml/pfdqmlgadgetwidget.h | 162 +- .../src/plugins/pfdqml/pfdqmlplugin.cpp | 110 +- .../src/plugins/pfdqml/pfdqmlplugin.h | 72 +- ground/openpilotgcs/src/plugins/plugins.pro | 502 +- .../src/plugins/qmlview/QMLView.pluginspec | 24 +- .../src/plugins/qmlview/qmlviewgadget.h | 112 +- .../qmlview/qmlviewgadgetconfiguration.cpp | 134 +- .../qmlview/qmlviewgadgetconfiguration.h | 114 +- .../plugins/qmlview/qmlviewgadgetfactory.cpp | 120 +- .../plugins/qmlview/qmlviewgadgetfactory.h | 104 +- .../qmlview/qmlviewgadgetoptionspage.cpp | 166 +- .../qmlview/qmlviewgadgetoptionspage.h | 130 +- .../plugins/qmlview/qmlviewgadgetwidget.cpp | 212 +- .../src/plugins/qmlview/qmlviewgadgetwidget.h | 120 +- .../src/plugins/qmlview/qmlviewplugin.cpp | 132 +- .../src/plugins/qmlview/qmlviewplugin.h | 94 +- .../src/plugins/rawhid/RawHID.pluginspec | 20 +- .../src/plugins/rawhid/rawhid_global.h | 78 +- .../src/plugins/scope/plotdata.cpp | 508 +- .../openpilotgcs/src/plugins/scope/plotdata.h | 350 +- .../src/plugins/scope/scopegadget.h | 140 +- .../serialconnection/Serial.pluginspec | 20 +- .../plugins/serialconnection/serial_global.h | 80 +- .../serialconnection/serialconnection.pro | 30 +- .../SystemHealthGadget.pluginspec | 24 +- .../plugins/systemhealth/systemhealthgadget.h | 112 +- .../systemhealthgadgetconfiguration.cpp | 128 +- .../systemhealthgadgetconfiguration.h | 118 +- .../systemhealthgadgetfactory.cpp | 120 +- .../systemhealth/systemhealthgadgetfactory.h | 104 +- .../systemhealthgadgetoptionspage.cpp | 152 +- .../systemhealthgadgetoptionspage.h | 130 +- .../systemhealth/systemhealthplugin.cpp | 130 +- .../plugins/systemhealth/systemhealthplugin.h | 94 +- .../UAVObjectBrowser.pluginspec | 22 +- .../uavobjectbrowser/browseritemdelegate.cpp | 150 +- .../uavobjectbrowser/browseritemdelegate.h | 116 +- .../uavobjectbrowser/browserplugin.cpp | 126 +- .../plugins/uavobjectbrowser/browserplugin.h | 94 +- .../uavobjectbrowser/fieldtreeitem.cpp | 58 +- .../src/plugins/uavobjectbrowser/treeitem.cpp | 466 +- .../src/plugins/uavobjectbrowser/treeitem.h | 548 +- .../uavobjectbrowser/uavobjectbrowser.h | 118 +- .../uavobjectbrowserconfiguration.cpp | 164 +- .../uavobjectbrowserconfiguration.h | 162 +- .../uavobjectbrowserfactory.cpp | 118 +- .../uavobjectbrowserfactory.h | 104 +- .../uavobjectbrowseroptionspage.cpp | 144 +- .../uavobjectbrowseroptionspage.h | 136 +- .../uavobjectbrowserwidget.cpp | 520 +- .../uavobjectbrowser/uavobjectbrowserwidget.h | 174 +- .../uavobjectbrowser/uavobjecttreemodel.cpp | 918 +- .../uavobjectbrowser/uavobjecttreemodel.h | 228 +- .../plugins/uavobjects/UAVObjects.pluginspec | 20 +- .../src/plugins/uavobjects/tests/main.cpp | 24 +- .../uavobjects/tests/uavobjectstest.cpp | 298 +- .../plugins/uavobjects/tests/uavobjectstest.h | 72 +- .../uavobjects/tests/uavobjectstest.pro | 84 +- .../src/plugins/uavobjects/uavdataobject.cpp | 200 +- .../src/plugins/uavobjects/uavdataobject.h | 116 +- .../src/plugins/uavobjects/uavmetaobject.cpp | 218 +- .../src/plugins/uavobjects/uavmetaobject.h | 108 +- .../src/plugins/uavobjects/uavobject.cpp | 1246 +- .../src/plugins/uavobjects/uavobject.h | 360 +- .../src/plugins/uavobjects/uavobjectfield.cpp | 2110 +- .../src/plugins/uavobjects/uavobjectfield.h | 206 +- .../plugins/uavobjects/uavobjectmanager.cpp | 686 +- .../src/plugins/uavobjects/uavobjectmanager.h | 150 +- .../uavobjects/uavobjects_dependencies.pri | 2 +- .../plugins/uavobjects/uavobjects_global.h | 80 +- .../src/plugins/uavobjects/uavobjectsinit.h | 70 +- .../uavobjects/uavobjectsinittemplate.cpp | 84 +- .../plugins/uavobjects/uavobjectsplugin.cpp | 128 +- .../src/plugins/uavobjects/uavobjectsplugin.h | 100 +- .../plugins/uavobjects/uavobjecttemplate.cpp | 302 +- .../plugins/uavobjects/uavobjecttemplate.h | 182 +- .../uavobjectutil/UAVObjectUtil.pluginspec | 22 +- .../plugins/uavobjectutil/uavobjectutil.pro | 30 +- .../uavobjectutil/uavobjectutil_global.h | 80 +- .../uavobjectutil/uavobjectutilmanager.cpp | 936 +- .../uavobjectutil/uavobjectutilmanager.h | 192 +- .../uavobjectutil/uavobjectutilplugin.cpp | 118 +- .../uavobjectutil/uavobjectutilplugin.h | 98 +- .../uavsettingsimportexport.cpp | 162 +- .../uavsettingsimportexport.h | 106 +- .../uavsettingsimportexport.pluginspec | 24 +- .../uavsettingsimportexport_dependencies.pri | 6 +- .../uavsettingsimportexportfactory.h | 2 +- .../src/plugins/uavtalk/UAVTalk.pluginspec | 22 +- .../src/plugins/uavtalk/telemetry.cpp | 1182 +- .../src/plugins/uavtalk/telemetry.h | 306 +- .../src/plugins/uavtalk/telemetrymonitor.cpp | 538 +- .../src/plugins/uavtalk/telemetrymonitor.h | 162 +- .../src/plugins/uavtalk/uavtalk.pro | 36 +- .../src/plugins/uavtalk/uavtalk_global.h | 78 +- .../src/plugins/uploader/Uploader.pluginspec | 28 +- .../src/plugins/uploader/uploader.pro | 6 +- .../src/plugins/uploader/uploadergadget.h | 114 +- .../uploader/uploadergadgetconfiguration.cpp | 210 +- .../uploader/uploadergadgetconfiguration.h | 148 +- .../uploader/uploadergadgetfactory.cpp | 120 +- .../plugins/uploader/uploadergadgetfactory.h | 116 +- .../uploader/uploadergadgetoptionspage.cpp | 146 +- .../uploader/uploadergadgetoptionspage.h | 154 +- .../plugins/uploader/uploadergadgetwidget.cpp | 2 +- .../src/plugins/uploader/uploaderplugin.cpp | 126 +- .../src/plugins/uploader/uploaderplugin.h | 96 +- .../src/plugins/welcome/Welcome.pluginspec | 20 +- .../src/plugins/welcome/welcome.pro | 32 +- .../src/plugins/welcome/welcome_global.h | 80 +- .../src/plugins/welcome/welcomemode.h | 154 +- .../src/plugins/welcome/welcomeplugin.cpp | 190 +- .../src/plugins/welcome/welcomeplugin.h | 120 +- ground/openpilotgcs/src/rpath.pri | 22 +- ground/openpilotgcs/src/src.pro | 14 +- .../uavobject-synthetics.pro} | 32 +- ground/uavobjgenerator/uavobjectparser.cpp | 1230 +- ground/uavobjgenerator/uavobjectparser.h | 276 +- ground/uavobjgenerator/uavobjgenerator.pro | 62 +- make/.gitattributes | 10 + make/apps-defs.mk | 352 +- make/boot-defs.mk | 256 +- make/common-defs.mk | 558 +- .../templates/OPLicenseTemplate.txt | 0 make/templates/build-info.txt | 66 +- ...template.h => gcs_version_info_template.h} | 0 make/tools.mk | 209 +- make/winx86/cmd/sh.cmd | 18 +- matlab/.gitattributes | 6 + package/.gitattributes | 5 + package/Windows.mk | 2 +- package/linux/deb_common/rules | 9 +- package/osx/libraries | 114 +- package/osx/package | 12 +- package/winx86/openpilotgcs.nsi | 4 +- shared/.gitattributes | 5 + .../uavobjectdefinition/actuatorcommand.xml | 26 +- .../uavobjectdefinition/actuatordesired.xml | 30 +- shared/uavobjectdefinition/attitudeactual.xml | 32 +- .../uavobjectdefinition/attitudesimulated.xml | 36 +- shared/uavobjectdefinition/firmwareiapobj.xml | 34 +- .../flightbatterysettings.xml | 38 +- .../flightbatterystate.xml | 32 +- .../uavobjectdefinition/flightplancontrol.xml | 20 +- .../flightplansettings.xml | 20 +- .../uavobjectdefinition/flightplanstatus.xml | 28 +- .../flighttelemetrystats.xml | 30 +- .../uavobjectdefinition/gcstelemetrystats.xml | 30 +- .../manualcontrolcommand.xml | 32 +- shared/uavobjectdefinition/mixersettings.xml | 178 +- shared/uavobjectdefinition/mixerstatus.xml | 42 +- .../uavobjectdefinition/objectpersistence.xml | 26 +- shared/uavobjectdefinition/osdsettings.xml | 50 +- .../uavobjectdefinition/overosyncsettings.xml | 20 +- shared/uavobjectdefinition/overosyncstats.xml | 32 +- shared/uavobjectdefinition/positionactual.xml | 24 +- .../relaytuningsettings.xml | 30 +- .../uavobjectdefinition/revocalibration.xml | 60 +- shared/uavobjectdefinition/revosettings.xml | 20 +- .../stabilizationdesired.xml | 30 +- .../stabilizationsettings.xml | 90 +- shared/uavobjectdefinition/systemalarms.xml | 62 +- shared/uavobjectdefinition/systemstats.xml | 34 +- shared/uavobjectdefinition/taskinfo.xml | 206 +- shared/uavobjectdefinition/txpidsettings.xml | 60 +- 1430 files changed, 375086 insertions(+), 374819 deletions(-) create mode 100644 .gitattributes create mode 100644 flight/.gitattributes create mode 100644 ground/.gitattributes create mode 100644 ground/openpilotgcs/src/gcs_version_info.h rename ground/{uavobjects/uavobjects.pro => uavobject-synthetics/uavobject-synthetics.pro} (52%) create mode 100644 make/.gitattributes rename OPLicenseTemplate.txt => make/templates/OPLicenseTemplate.txt (100%) rename make/templates/{gcsversioninfotemplate.h => gcs_version_info_template.h} (100%) create mode 100644 matlab/.gitattributes create mode 100644 package/.gitattributes create mode 100644 shared/.gitattributes diff --git a/.gitattributes b/.gitattributes new file mode 100644 index 000000000..260bbe52b --- /dev/null +++ b/.gitattributes @@ -0,0 +1,31 @@ +# +# Line endings normalization: http://wiki.openpilot.org/display/Doc/Coding+Style +# You need at least git 1.7.2 for this to work (previous versions ignore text and eol attributes). +# +# Make sure you have committed all local changes first. Then use the following bash commands +# to normalize your local repository to be able to merge it with a mainline: +# +# Minimal normalization: +# git rm --cached -r . +# git reset --hard +# git add . +# git commit -m "Normalize line endings" +# +# Or full normalization (don't do that on Windows, it breaks file modes): +# git rm --cached -r . +# git diff --cached --name-only -z | xargs -0 git add +# git commit -m "Normalize line endings" +# git ls-files -z | xargs -0 rm +# git checkout . +# + +# Set default behaviour (do not convert line endings regardless of local git core settings) +* -text + +# All *.txt files in the root should be Windows-readable (CRLF) +/*.txt text eol=crlf + +# Root Makefile has LF line endings +/Makefile text eol=lf + +# More attributes are defined in per-directory .gitattributes which override this file diff --git a/CREDITS.txt b/CREDITS.txt index 1aef5dc27..ac785d256 100644 --- a/CREDITS.txt +++ b/CREDITS.txt @@ -1,206 +1,206 @@ -This is a credits file of people that are or have been key contributors to the OpenPilot code base in this Git repository. -Without the work of the people in this file and many that are not who help the community, OpenPilot would not be what it is today. - -It is sorted alphabetically by name and formatted so that it allows for easy grepping and beautification by scripts. - -The fields are: - -Name (N) -Description of work (D) -Current maintainer function (M) - ----------- - -N: Connor Abbott -D: Win32 OpenPilot port - -N: David Ankers -D: Co-founder, Project Coordination -D: Minor GCS infrastructure, updating the credit file -M: Admin - -N: Sergiy Anikeyev -D: Improvments to Camera Gimbal control - -N: Pedro Assuncao -D: Initial GCS Settings Gadget work - -N: Fredrik Arvidsson -D: GCS Setup Wizard -M: GCS Setup Wizard - -N: Werner Backes -D: Port of CopterControl to PS3 Move Controller (MoveCopter) - -N: Jose Barros -D: Next-Gen OP Map Lib, Y-Modem Library, Uploader Plugin -D: OP Bootloader, AHRS Bootloader, OPUploadTool and much else -M: Bootloader, OP MAP Lib - -N: David "Buzz" Carlson -D: 3D ModelView GCS Plugin, sponsor of HITL merge work and XPlane addition - -N: James Cotton -D: Multiplatform HID implementation (firmware & GCS), GCS Joystick control -D: Posix OpenPilot work and Mac implementation -D: Firmware implementation of Professor Schinstock's INS/GPS -D: Android GCS and much else -M: Architecture co-lead, Android GCS Lead - -N: Steve Doll -D: Much Artwork, Logo rework, Welcome page design - -N: Piotr Esden-Tempski -D: Floss-JTAG Rev A, 4-layer initial design - -N: Richard Flay -D: Multiple fixes / Review guru - -N: Darren Furniss -D: GCS Artwork and Android GCS Artwork - -N: Frederic Goddeeris -D: I2C work and FreeRTOS work, MK integration -D: EagleTree OSD implementation - -N: Daniel Godin -D: Sponsor: Notify Plugin for the GCS - -N: Bani Greyling -D: GCS Scope plugin - -N: Nuno Guedes -D: 3D artwork, moving surfaces and work on ModelView -D: PFD Artwork - -N: Erik Gustavsson -D: Attitude LPF improvments to Self Level - -N: Peter Gunnarsson -D: GCS Core Developer -D: Multiple GCS plugins, Gadget foundations, UAVObject viewer - -N: Dean Hall -D: Creator of http://pythononachip.org - -N: Joe Hlebasko -D: Early versions of Main Board & Production OP GPS -M: Hardware Architecture Team - -N: Andy Honecker -D: Hardware design review and optimisation - -N: Mark James -D: Some of Silk Icon set used in GCS - http://www.famfamfam.com/lab/icons/silk - -N: Sami Korhonen -D: GPS Module, Spektrum RC Module, OSD work -M: OpenPilot OSD - -N: Thorsten Klose -D: Embedded STM32 infrastructure - -N: Hallvard Kristiansen -D: GCS Artwork, Quad layout diagrams - -N: Mike Labranche -D: Tab bar Telem Monitor - -N: Edouard Lafargue -D: GCS Dial Plugins, GCS PFD Plugin, GCS GPS plugin, GCS Config plugin -D: Artwork including standard display dials - -N: Matt Lipski -D: Deluxe Dials Set artwork, (Artificial Horizon, Compass, Turn Indicator) - -N: Les Newell -D: Advanced mixer matrix, SPI protocol based on UAVObjects, feedforward - -N: Ken Northup -D: 3D Modelling, Easystar adaption from FMS - -N: Guy McCaldin -D: Artwork and design including work on the Deluxe Dial Set - -N: Alessio Morale -D: Firmware/Architecture Lead - -N: Cathy Moss -D: Hardware design Lead: Gen 2 Mainboard, PipXtreme, Current Sensor -D: PipXtreme designer, creator OP Map Plugin - -N: Angus Peart -D: Co-founder, Principal hardware architect. -D: Hardware design of early OpenPilot, AHRS, GPS and other hardware - -N: Dmytro Poplavskiy -D: QML PFD, QML Welcome page -M: Qml plugins - -N: Eric Price -D: IL2 HITL GCS Plugin, Posix OpenPilot, Advanced stabilisation module -M: SITL Posix, SLAM work - -N: Richard Querin -D: Graphic Design, OpenPilot Logo - -N: Laurent Ribon -D: The GLC_lib as used in the ModelView Plugin -D: See: http://www.glc-lib.net/ - -N: Julien Rouviere -D: GCS Framework and Plugins for the GCS - -N: Zik Saleeba -D: Initial schematic based on Zik's Flying Fox schematic - -N: Professor Dale Schinstock -D: Lead INS Developer -D: Creator of the OpenPilot INS / EKF - -N: Professor Kenn Sebesta -D: Lead Fixed Wing Developer CC3D / Controls -D: GCS improvments including HiTL Merge -M: Fixed Wing support CC3D - -N: Oleg Semyonov -D: Core Developer & Project organisation -D: TxPID module -M: CameraStab module -M: Common part of multi-platform packaging system -M: Windows NSIS Installer - -N: Stacey Sheldon -D: Core Embedded Developer -D: SPI protocol for AHRS, I2C rewrite and much core work - -N: Troy Schultz -D: INS design review and optimisation - -N: Dr. Erhard Siegl -D: Configuration engine for the GCS - -N: Pete Stapley -D: PPM inputs - -N: Rowan Taubitz -D: Hardware debugging and testing, creation of 2-layer Floss-JTAG Rev B -D: Creation of Next-Gen FOSS-JTAG board - -N: Andrew Thoms -D: IP Telemtry plugin for the GCS -D: Helicopter support code and mixing for CCPM - -N: Vassilis Varveropoulos -D: Co-founder, Principal embedded software architect. -D: Module architecture and UAVTalk/UAVObjects implementation. - -N: Alex Vrubel -D: Russian translation of the GCS - -N: Brian Webb -D: Modem lead developer -M: OP Modems - -N: Dmitriy Zaitsev -D: AeroSim-RC HiTL plugin +This is a credits file of people that are or have been key contributors to the OpenPilot code base in this Git repository. +Without the work of the people in this file and many that are not who help the community, OpenPilot would not be what it is today. + +It is sorted alphabetically by name and formatted so that it allows for easy grepping and beautification by scripts. + +The fields are: + +Name (N) +Description of work (D) +Current maintainer function (M) + +---------- + +N: Connor Abbott +D: Win32 OpenPilot port + +N: David Ankers +D: Co-founder, Project Coordination +D: Minor GCS infrastructure, updating the credit file +M: Admin + +N: Sergiy Anikeyev +D: Improvments to Camera Gimbal control + +N: Pedro Assuncao +D: Initial GCS Settings Gadget work + +N: Fredrik Arvidsson +D: GCS Setup Wizard +M: GCS Setup Wizard + +N: Werner Backes +D: Port of CopterControl to PS3 Move Controller (MoveCopter) + +N: Jose Barros +D: Next-Gen OP Map Lib, Y-Modem Library, Uploader Plugin +D: OP Bootloader, AHRS Bootloader, OPUploadTool and much else +M: Bootloader, OP MAP Lib + +N: David "Buzz" Carlson +D: 3D ModelView GCS Plugin, sponsor of HITL merge work and XPlane addition + +N: James Cotton +D: Multiplatform HID implementation (firmware & GCS), GCS Joystick control +D: Posix OpenPilot work and Mac implementation +D: Firmware implementation of Professor Schinstock's INS/GPS +D: Android GCS and much else +M: Architecture co-lead, Android GCS Lead + +N: Steve Doll +D: Much Artwork, Logo rework, Welcome page design + +N: Piotr Esden-Tempski +D: Floss-JTAG Rev A, 4-layer initial design + +N: Richard Flay +D: Multiple fixes / Review guru + +N: Darren Furniss +D: GCS Artwork and Android GCS Artwork + +N: Frederic Goddeeris +D: I2C work and FreeRTOS work, MK integration +D: EagleTree OSD implementation + +N: Daniel Godin +D: Sponsor: Notify Plugin for the GCS + +N: Bani Greyling +D: GCS Scope plugin + +N: Nuno Guedes +D: 3D artwork, moving surfaces and work on ModelView +D: PFD Artwork + +N: Erik Gustavsson +D: Attitude LPF improvments to Self Level + +N: Peter Gunnarsson +D: GCS Core Developer +D: Multiple GCS plugins, Gadget foundations, UAVObject viewer + +N: Dean Hall +D: Creator of http://pythononachip.org + +N: Joe Hlebasko +D: Early versions of Main Board & Production OP GPS +M: Hardware Architecture Team + +N: Andy Honecker +D: Hardware design review and optimisation + +N: Mark James +D: Some of Silk Icon set used in GCS - http://www.famfamfam.com/lab/icons/silk + +N: Sami Korhonen +D: GPS Module, Spektrum RC Module, OSD work +M: OpenPilot OSD + +N: Thorsten Klose +D: Embedded STM32 infrastructure + +N: Hallvard Kristiansen +D: GCS Artwork, Quad layout diagrams + +N: Mike Labranche +D: Tab bar Telem Monitor + +N: Edouard Lafargue +D: GCS Dial Plugins, GCS PFD Plugin, GCS GPS plugin, GCS Config plugin +D: Artwork including standard display dials + +N: Matt Lipski +D: Deluxe Dials Set artwork, (Artificial Horizon, Compass, Turn Indicator) + +N: Les Newell +D: Advanced mixer matrix, SPI protocol based on UAVObjects, feedforward + +N: Ken Northup +D: 3D Modelling, Easystar adaption from FMS + +N: Guy McCaldin +D: Artwork and design including work on the Deluxe Dial Set + +N: Alessio Morale +D: Firmware/Architecture Lead + +N: Cathy Moss +D: Hardware design Lead: Gen 2 Mainboard, PipXtreme, Current Sensor +D: PipXtreme designer, creator OP Map Plugin + +N: Angus Peart +D: Co-founder, Principal hardware architect. +D: Hardware design of early OpenPilot, AHRS, GPS and other hardware + +N: Dmytro Poplavskiy +D: QML PFD, QML Welcome page +M: Qml plugins + +N: Eric Price +D: IL2 HITL GCS Plugin, Posix OpenPilot, Advanced stabilisation module +M: SITL Posix, SLAM work + +N: Richard Querin +D: Graphic Design, OpenPilot Logo + +N: Laurent Ribon +D: The GLC_lib as used in the ModelView Plugin +D: See: http://www.glc-lib.net/ + +N: Julien Rouviere +D: GCS Framework and Plugins for the GCS + +N: Zik Saleeba +D: Initial schematic based on Zik's Flying Fox schematic + +N: Professor Dale Schinstock +D: Lead INS Developer +D: Creator of the OpenPilot INS / EKF + +N: Professor Kenn Sebesta +D: Lead Fixed Wing Developer CC3D / Controls +D: GCS improvments including HiTL Merge +M: Fixed Wing support CC3D + +N: Oleg Semyonov +D: Core Developer & Project organisation +D: TxPID module +M: CameraStab module +M: Common part of multi-platform packaging system +M: Windows NSIS Installer + +N: Stacey Sheldon +D: Core Embedded Developer +D: SPI protocol for AHRS, I2C rewrite and much core work + +N: Troy Schultz +D: INS design review and optimisation + +N: Dr. Erhard Siegl +D: Configuration engine for the GCS + +N: Pete Stapley +D: PPM inputs + +N: Rowan Taubitz +D: Hardware debugging and testing, creation of 2-layer Floss-JTAG Rev B +D: Creation of Next-Gen FOSS-JTAG board + +N: Andrew Thoms +D: IP Telemtry plugin for the GCS +D: Helicopter support code and mixing for CCPM + +N: Vassilis Varveropoulos +D: Co-founder, Principal embedded software architect. +D: Module architecture and UAVTalk/UAVObjects implementation. + +N: Alex Vrubel +D: Russian translation of the GCS + +N: Brian Webb +D: Modem lead developer +M: OP Modems + +N: Dmitriy Zaitsev +D: AeroSim-RC HiTL plugin diff --git a/HISTORY.txt b/HISTORY.txt index 23cf292fe..abeb39b4c 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -1,205 +1,205 @@ -Short summary of changes. For a complete list see the git log. - -2012-11-17 -Advanced camera stabilization features. -They include optional manual control input filtering (moved from camera -stabilization to manual control input and now available also for main controls), -optional airframe attitude filtering used by camera stabilization, and optional -camera actuator feed forward to improve gimbal response. +Short summary of changes. For a complete list see the git log. + +2012-11-17 +Advanced camera stabilization features. +They include optional manual control input filtering (moved from camera +stabilization to manual control input and now available also for main controls), +optional airframe attitude filtering used by camera stabilization, and optional +camera actuator feed forward to improve gimbal response. + +--- RELEASE-12.10.2 --- Mayan Apocalypse Release --- + +List of issues resolved in this maintenance release: +http://progress.openpilot.org/issues/?filter=10361 + +OP-459, OP-545, OP-674, OP-679, OP-685, OP-686, OP-687, OP-690, OP-691, +OP-702, OP-703, OP-714, OP-715, OP-716, OP-721, OP-728, OP-746, OP-748, +OP-749, OP-750, OP-758, OP-759, OP-760 + +2012-11-12 +Implemented smoothing filter for accelerometer data. +Added support for Mode 3 and Mode 4 to the TX Configuration Wizard. + +--- RELEASE-12.10.1 --- + +2012-10-26 +Temporary disabled AutoTune GCS GUI. It was listed as an experimental +feature in the previous release, there were however a few cases where +it did not behave as expected. + +--- RELEASE-12.10 --- + +2012-10-06 +Receiver port can now be configured as PPM *and* PWM inputs. +Pin 1 is PPM, other pins are PWM inputs. + +2012-07-27 +Added the ability to load stylesheets from external file according to operating system: +macos.qss, linux.qss, windows.qss +Files should be placed inside the app folder. + +2012-07-27 +Several UI changes. +MixerCurveWidget refactoring, now as a simple and advanced view. + +2012-07-27 +Added "advanced mode" option to general settings. Right now it only shows the hidden apply buttons. +To enable go to tools->options->General and click one of the checkboxes to give focus to the form, +then press F7 + +2012-07-27 +Made the flight mode switch and accessory pots move according to user input on the input wizard. + +2012-07-27 +Changed the board pictures on the uploader widget + +2012-07-27 +Add more verbose debug output on the UAVOBJECTS saving code. + +2012-08-11 +CopterControl can now emulate an 8-channel USB HID joystick. Primarily, +this lets you use any RC transmitter with flight simulators on your PC. + +2012-07-20 +AeroSimRC simulator plugin is now included into the Windows distribution +(will be installed into .../OpenPilot/misc/AeroSIM-RC directory). Still +being an experimental development tool, it could be used to play with +HITL version 2. Other platforms include udp_test utility which can be +used to check the connectivity with AeroSimRC plugin running on Windows +machine. + +2012-07-10 +On Windows the installation mode was changed from per-user to per-machine +(for all users) installation. It is recommended to completely uninstall +previous version before installing new one to remove per-user installed +files. Per-machine installation requires elevated (administrator) previleges +during install. But since the same rights are now required to install +optional CDC driver (virtual communication port), it was deemed acceptable. + +2012-06-04 +AeroSimRC support merged into next + +2012-05-26 +VirtualFlybar which allows a more aggressive flight mode than rate mode +support. Also PiroCompensation added. + +2012-05-26 +Revert some UI changes that didn't work consistently between OSX and Windows. + +2012-05-24 +Merged the updated firmware for the PipXtreme, thanks to Brian for a lot of +work on this. + +2012-05-04 +Support for CC3D. This involved changes to various things such as the sensors +being split from AttitudeRaw to Accels,Gyros,Magnetometer. A single firmware +image fw_coptercontrol will run on both CC and CC3D. When compiling the +bootloader one must set the HW_REVISION to the appropriate value. 0x01 is for +CC and 0x02 is for CC3D. If the wrong bootloader is installed the firmware +will not run. + +2012-05-02 +Reduction in the memory usage due to the UAVObject metadata. Now the update +periods are using a smaller data type and the various flags relating to access +controls and update modes are stored in a bitfield. The UAVObjectBrowser has +not been updated to allow these modes to be easily changed. + +2012-03-31 +Support for ground vehicle configuration has been added to the the GCS. + +2012-02-14 +New QML based system to allow more flexible UI. Upgraded stabilization +configuration. + +2012-01-02 +CC FW now supports USB Virtual Com Port (VCP/CDC) in addition to the original HID interface +New ComUsbBridge module can bridge any serial port to the USB CDC port +CC FW now detects repeated faults during init and boots with default hwsettings + +2012-01-02 +Added new camera stabilization features: AxisLock mode and LPF. + +2011-12-10 +Merged a change that sorts the UAVO fields based on size. Because this changes +all of the objects, erase all existing flash files based on this. + +2011-11-04 +New Spektrum/JR satellite receiver driver implementation. +It now provides explicit selection of DSM2 (and DSMJ), DSMX (10bit) and +DSMX (11bit) serial protocol variations to better serve different frame +and resolution modes. The protocol name used now is DSM instead of +previously used Spektrum to make it less ambiguous when used with JR +2.4GHz radios. + +2011-10-20 +Inputs can be remapped to outputs to allow up to 10 channels of control. The +receiver inputs remap as follows: +Receiver 3 because output channel 7 +Receiver 4 because output channel 8 +Receiver 5 because output channel 9 +Receiver 6 because output channel 10 + +2011-10-11 +Fix for the Mac telemetry rates and specifically how long enumeration took. + +2011-10-08 +Make the flash chip need to be have bad magic for a full second before erasing +settings. Should avoid random lost settings. + +2011-09-12 +Max rate now ONLY applies to attitude and axis lock mode. Manual rate is the +only term that limits the rate mode now (and in axis lock when you push stick +only manual rate applies). Also integrals are reset when unused. + +2011-09-09 +Some large updates to the input system. Now multiple receivers can be +connected at once. A wizard was added for configuring the input channels. A +specific collective pitch channel was added. + +2011-09-04 +Improvements to the failsafe handling code for inputs. PWM power off is now +detected properly. Powering on transmitter for Spektrum Satellite no longer +causes a glitch on servos. + +2011-08-10 +Added Camera Stabilization and a gui to configure this. This is a software +selectable module from the GUI. However, a restart is required to make it +active. The GUI does not currently expose the configuration for using the +transmitter to change the view angle but this is supported by the hardware. + +2011-08-10 +By default a lot of diagnostic objects that were enabled by default are now +disabled in the build. This include TaskInfo (and all the FreeRTOS options +that provide that debugging information). Also MixerStatus, I2CStatus, +WatchdogStatus and RateDesired. These can be reenabled for debugging with +-DDIAG_ALL. + +2011-08-04 +Fixed packaging aesthetic issues. Also avoid runtime issues on OSX Lion by +disabling the ModelView and Notify plugins for now (sorry). + +2011-07-29 +Added support for PPM receivers from James W. Now all 4 interfaces (R/C +standard PWM, combined PPM (MK), Spektrum satellite, Futaba S.Bus) are +supported and configurable through the GCS hardware configuration tab. + +2011-07-17 +Updated module initialization from Mathieu which separates the initialization +from the task startup. Also implements a method to reclaim unused ram from +initialization and end of memory for the FreeRTOS heap. + +2011-07-12 +Improvements to the stabilization code. Included a LPF on the gyros to smooth +out noise in high vibration environments. Also two new modes: axis-lock and +weak leveling. Axis-lock will try and hold an axis at a fixed position and +reject any disturbances. This is like heading-hold on a heli for the tail but +can be useful for other axes. Weak leveling is rate mode with a weak +correction to self level the craft - good for easier rate mode flying. + +2011-07-07 +Dynamic hardware configuration from Stac. The input type is now +selected from ManualControlSettings.InputMode and the aircraft must be rebooted +after changing this. Also for CopterControl the HwSettings object must +indicate which modules are connected to which ports. PPM currently not +working. ---- RELEASE-12.10.2 --- Mayan Apocalypse Release --- - -List of issues resolved in this maintenance release: -http://progress.openpilot.org/issues/?filter=10361 - -OP-459, OP-545, OP-674, OP-679, OP-685, OP-686, OP-687, OP-690, OP-691, -OP-702, OP-703, OP-714, OP-715, OP-716, OP-721, OP-728, OP-746, OP-748, -OP-749, OP-750, OP-758, OP-759, OP-760 - -2012-11-12 -Implemented smoothing filter for accelerometer data. -Added support for Mode 3 and Mode 4 to the TX Configuration Wizard. - ---- RELEASE-12.10.1 --- - -2012-10-26 -Temporary disabled AutoTune GCS GUI. It was listed as an experimental -feature in the previous release, there were however a few cases where -it did not behave as expected. - ---- RELEASE-12.10 --- - -2012-10-06 -Receiver port can now be configured as PPM *and* PWM inputs. -Pin 1 is PPM, other pins are PWM inputs. - -2012-07-27 -Added the ability to load stylesheets from external file according to operating system: -macos.qss, linux.qss, windows.qss -Files should be placed inside the app folder. - -2012-07-27 -Several UI changes. -MixerCurveWidget refactoring, now as a simple and advanced view. - -2012-07-27 -Added "advanced mode" option to general settings. Right now it only shows the hidden apply buttons. -To enable go to tools->options->General and click one of the checkboxes to give focus to the form, -then press F7 - -2012-07-27 -Made the flight mode switch and accessory pots move according to user input on the input wizard. - -2012-07-27 -Changed the board pictures on the uploader widget - -2012-07-27 -Add more verbose debug output on the UAVOBJECTS saving code. - -2012-08-11 -CopterControl can now emulate an 8-channel USB HID joystick. Primarily, -this lets you use any RC transmitter with flight simulators on your PC. - -2012-07-20 -AeroSimRC simulator plugin is now included into the Windows distribution -(will be installed into .../OpenPilot/misc/AeroSIM-RC directory). Still -being an experimental development tool, it could be used to play with -HITL version 2. Other platforms include udp_test utility which can be -used to check the connectivity with AeroSimRC plugin running on Windows -machine. - -2012-07-10 -On Windows the installation mode was changed from per-user to per-machine -(for all users) installation. It is recommended to completely uninstall -previous version before installing new one to remove per-user installed -files. Per-machine installation requires elevated (administrator) previleges -during install. But since the same rights are now required to install -optional CDC driver (virtual communication port), it was deemed acceptable. - -2012-06-04 -AeroSimRC support merged into next - -2012-05-26 -VirtualFlybar which allows a more aggressive flight mode than rate mode -support. Also PiroCompensation added. - -2012-05-26 -Revert some UI changes that didn't work consistently between OSX and Windows. - -2012-05-24 -Merged the updated firmware for the PipXtreme, thanks to Brian for a lot of -work on this. - -2012-05-04 -Support for CC3D. This involved changes to various things such as the sensors -being split from AttitudeRaw to Accels,Gyros,Magnetometer. A single firmware -image fw_coptercontrol will run on both CC and CC3D. When compiling the -bootloader one must set the HW_REVISION to the appropriate value. 0x01 is for -CC and 0x02 is for CC3D. If the wrong bootloader is installed the firmware -will not run. - -2012-05-02 -Reduction in the memory usage due to the UAVObject metadata. Now the update -periods are using a smaller data type and the various flags relating to access -controls and update modes are stored in a bitfield. The UAVObjectBrowser has -not been updated to allow these modes to be easily changed. - -2012-03-31 -Support for ground vehicle configuration has been added to the the GCS. - -2012-02-14 -New QML based system to allow more flexible UI. Upgraded stabilization -configuration. - -2012-01-02 -CC FW now supports USB Virtual Com Port (VCP/CDC) in addition to the original HID interface -New ComUsbBridge module can bridge any serial port to the USB CDC port -CC FW now detects repeated faults during init and boots with default hwsettings - -2012-01-02 -Added new camera stabilization features: AxisLock mode and LPF. - -2011-12-10 -Merged a change that sorts the UAVO fields based on size. Because this changes -all of the objects, erase all existing flash files based on this. - -2011-11-04 -New Spektrum/JR satellite receiver driver implementation. -It now provides explicit selection of DSM2 (and DSMJ), DSMX (10bit) and -DSMX (11bit) serial protocol variations to better serve different frame -and resolution modes. The protocol name used now is DSM instead of -previously used Spektrum to make it less ambiguous when used with JR -2.4GHz radios. - -2011-10-20 -Inputs can be remapped to outputs to allow up to 10 channels of control. The -receiver inputs remap as follows: -Receiver 3 because output channel 7 -Receiver 4 because output channel 8 -Receiver 5 because output channel 9 -Receiver 6 because output channel 10 - -2011-10-11 -Fix for the Mac telemetry rates and specifically how long enumeration took. - -2011-10-08 -Make the flash chip need to be have bad magic for a full second before erasing -settings. Should avoid random lost settings. - -2011-09-12 -Max rate now ONLY applies to attitude and axis lock mode. Manual rate is the -only term that limits the rate mode now (and in axis lock when you push stick -only manual rate applies). Also integrals are reset when unused. - -2011-09-09 -Some large updates to the input system. Now multiple receivers can be -connected at once. A wizard was added for configuring the input channels. A -specific collective pitch channel was added. - -2011-09-04 -Improvements to the failsafe handling code for inputs. PWM power off is now -detected properly. Powering on transmitter for Spektrum Satellite no longer -causes a glitch on servos. - -2011-08-10 -Added Camera Stabilization and a gui to configure this. This is a software -selectable module from the GUI. However, a restart is required to make it -active. The GUI does not currently expose the configuration for using the -transmitter to change the view angle but this is supported by the hardware. - -2011-08-10 -By default a lot of diagnostic objects that were enabled by default are now -disabled in the build. This include TaskInfo (and all the FreeRTOS options -that provide that debugging information). Also MixerStatus, I2CStatus, -WatchdogStatus and RateDesired. These can be reenabled for debugging with --DDIAG_ALL. - -2011-08-04 -Fixed packaging aesthetic issues. Also avoid runtime issues on OSX Lion by -disabling the ModelView and Notify plugins for now (sorry). - -2011-07-29 -Added support for PPM receivers from James W. Now all 4 interfaces (R/C -standard PWM, combined PPM (MK), Spektrum satellite, Futaba S.Bus) are -supported and configurable through the GCS hardware configuration tab. - -2011-07-17 -Updated module initialization from Mathieu which separates the initialization -from the task startup. Also implements a method to reclaim unused ram from -initialization and end of memory for the FreeRTOS heap. - -2011-07-12 -Improvements to the stabilization code. Included a LPF on the gyros to smooth -out noise in high vibration environments. Also two new modes: axis-lock and -weak leveling. Axis-lock will try and hold an axis at a fixed position and -reject any disturbances. This is like heading-hold on a heli for the tail but -can be useful for other axes. Weak leveling is rate mode with a weak -correction to self level the craft - good for easier rate mode flying. - -2011-07-07 -Dynamic hardware configuration from Stac. The input type is now -selected from ManualControlSettings.InputMode and the aircraft must be rebooted -after changing this. Also for CopterControl the HwSettings object must -indicate which modules are connected to which ports. PPM currently not -working. - diff --git a/KNOWN_ISSUES.txt b/KNOWN_ISSUES.txt index 3cd746b7a..a35b55945 100644 --- a/KNOWN_ISSUES.txt +++ b/KNOWN_ISSUES.txt @@ -1,22 +1,22 @@ -Here is a list of some known unresolved issues. If an issue has JIRA ID [OP-XXX], you may track it using the -following URL: http://bugs.openpilot.org/browse/OP-XXX - -+ Missing Translations, use English. -+ Radio Wizard confused by a reversed throttle, fix it on your transmitter before starting wizard. -+ Radio Wizard Throttle display does not show full range properly. -+ [Windows 8] USB Driver is broken. -+ Firmware Update Instructions on Firmware Tab not entirely accurate for all upgrade paths. -+ Tricopter's using Vehicle Wizard need to check servo does not need reversed manually. -+ XAircraft ESCs uses non-standard PPM range which may cause issues with Vehicle Wizard. -+ Spectrum Satellite Receivers setup in Radio Wizard may have wrong protocol set. -+ Old Intel 965 have an OpenGL bug that turns the QML PFD black and while. -+ [OP-732] Import UAV Settings for inactive modules crashes the running firmware (board restarts). - Workaround: update firmware, power cycle, enable modules, power cycle, import configuration. -+ [OP-747] Board infinitely reboots itself after firmware upgrade (settings erase firmware is a workaround). -+ [OP-723] GCS uses the system language ot the 1st run. After restart it uses English (can be changed later). -+ [OP-725] GCS camera stab config error message disappears too fast (but config error is cleared as it should) -+ [OP-767] GCS does not send AttitudeActual packets over serial port when GPS is connected and system is armed -+ [OP-768] GCS does not show UAV position on the map (master or next CC branches, but works in Revo branches) -+ [OP-682] GCS crashes on firmware page. Noted on Windows and OSX platforms, difficult to reproduce. - Workaround: use Vehicle setup wizard to update the firmware. -+ [OP-769] Can't enter "12,45" on German system. Workaround: change GCS language (in fact, locale) to German. +Here is a list of some known unresolved issues. If an issue has JIRA ID [OP-XXX], you may track it using the +following URL: http://bugs.openpilot.org/browse/OP-XXX + ++ Missing Translations, use English. ++ Radio Wizard confused by a reversed throttle, fix it on your transmitter before starting wizard. ++ Radio Wizard Throttle display does not show full range properly. ++ [Windows 8] USB Driver is broken. ++ Firmware Update Instructions on Firmware Tab not entirely accurate for all upgrade paths. ++ Tricopter's using Vehicle Wizard need to check servo does not need reversed manually. ++ XAircraft ESCs uses non-standard PPM range which may cause issues with Vehicle Wizard. ++ Spectrum Satellite Receivers setup in Radio Wizard may have wrong protocol set. ++ Old Intel 965 have an OpenGL bug that turns the QML PFD black and while. ++ [OP-732] Import UAV Settings for inactive modules crashes the running firmware (board restarts). + Workaround: update firmware, power cycle, enable modules, power cycle, import configuration. ++ [OP-747] Board infinitely reboots itself after firmware upgrade (settings erase firmware is a workaround). ++ [OP-723] GCS uses the system language ot the 1st run. After restart it uses English (can be changed later). ++ [OP-725] GCS camera stab config error message disappears too fast (but config error is cleared as it should) ++ [OP-767] GCS does not send AttitudeActual packets over serial port when GPS is connected and system is armed ++ [OP-768] GCS does not show UAV position on the map (master or next CC branches, but works in Revo branches) ++ [OP-682] GCS crashes on firmware page. Noted on Windows and OSX platforms, difficult to reproduce. + Workaround: use Vehicle setup wizard to update the firmware. ++ [OP-769] Can't enter "12,45" on German system. Workaround: change GCS language (in fact, locale) to German. diff --git a/LICENSE.txt b/LICENSE.txt index 711b56a96..8b960825e 100644 --- a/LICENSE.txt +++ b/LICENSE.txt @@ -1,42 +1,42 @@ - -The OpenPilot code is licensed under the GPLv3, there are a few minor exceptions to this so please see the headers of all source code for copyright and license information. - -The full text of the GPLv3 can be read here: http://www.gnu.org/licenses/gpl-3.0.txt - -Artwork is licensed under the Creative Commons BY-SA v3 license. - -Documentation including translations is also licensed under the Creative Commons BY-SA v3 license. - -For details please see: http://creativecommons.org/licenses/by-sa/3.0/ - -Licenses for the hardware files are included in the directories that contain the hardware, not all items are under the same license and you must check the files for each individual hardware design. - -Please note that some of the hardware files are licensed under the Creative Commons BY-NC-SA v3 license, this is a Non-commercial license. OpenPilot is purely a non-profit hobby project with zero commercial intent, if you just want people to work for free or do your R&D for zero cost, please find a project that allows this as that not what OpenPilot is about. -We are hobbyists and we want to share our work with fellow hobbyists, additionally we need to ensure the future of the project and make sure it is sustainable. - -If you wish to sell / distribute OpenPilot hardware or derivatives of OpenPilot hardware that are under a non-commercial license, please get in touch with one of the members of OpenPilot Foundation's administration committee. We can then negotiate a license waiver where a portion of the profits are donated to the OpenPilot Project to ensure its survival and future progression. Please note that this is in reference to PCB and Schematic designs, for people wishing to combine OpenPilot in to a Ready to Fly solution, this is perfectly fine as long as OpenPilot PCBs are bought from the OpenPilot project or one of the approved distributors. - -For details the Non-Commercial license please see: http://creativecommons.org/licenses/by-nc-sa/3.0/ - -A quick summary of what this license talk means, firstly using any work that is licensed under a form of the Creative Commons BY license, requires that credit is to be given. - -The SA or Share Alike part of the license means that you must also use the same license in any work derived from the work under this license. - -Hardware -The items under the non-commercial license means exactly that: they are for non-commercial use only and any derivatives that are made are also covered by the same non-commercial license. The hardware files under a non-commercial license are for -reference and for fellow hobbyists; they are not to be used to generate profit of any kind. Please note that even the OpenPilot project its self is a non-profit project. - -For all items both non-commercial and items that allows commercial use, the OP logo must be placed on any work or derivative work and be clearly visible. If any web addresses are present on the hardware, these are also required to remain on any replications or any derivative work. - -Documentation -In documentation, authors names must be kept along with any logos. If documentation is for a physical product such as a schematic, the OpenPilot logo should be shown and any web addresses also displayed on the final physical hardware it was derived from. - -Artwork -If artwork is to be reused, the OpenPilot project should be credited. If for example this is a software application, credit should be given on the application splash screen or in a separate part of the application that is visible to users. For example the Help / About screen. - -Contact Us -If you are unsure, please contact one of the OpenPilot Foundation's administrators. Additionally, if you plan to use parts of the OpenPilot project in your own work, we would appreciate it if you get in touch with us anyway, it is possible we could combine efforts or have some work already in progress that might be helpful. This of course is our baby and we want to see what great things people do with it as well. - -A final note, OpenPilot is a non-profit for fun project and we have only volunteers. A great deal of time, money and effort has been donated to this project; please respect the people that are part of it and their generosity. OpenPilot is funded entirely by the generous people who donate money and time to the community and help it grow. Giving full and proper credit is not only a legal requirement of the CC-BY-SA license, it is also the right thing to do. - -Buying hardware from the OpenPilot project is very important to the survival and continuing progress of the project, a project like OpenPilot is extremely expensive to produce. + +The OpenPilot code is licensed under the GPLv3, there are a few minor exceptions to this so please see the headers of all source code for copyright and license information. + +The full text of the GPLv3 can be read here: http://www.gnu.org/licenses/gpl-3.0.txt + +Artwork is licensed under the Creative Commons BY-SA v3 license. + +Documentation including translations is also licensed under the Creative Commons BY-SA v3 license. + +For details please see: http://creativecommons.org/licenses/by-sa/3.0/ + +Licenses for the hardware files are included in the directories that contain the hardware, not all items are under the same license and you must check the files for each individual hardware design. + +Please note that some of the hardware files are licensed under the Creative Commons BY-NC-SA v3 license, this is a Non-commercial license. OpenPilot is purely a non-profit hobby project with zero commercial intent, if you just want people to work for free or do your R&D for zero cost, please find a project that allows this as that not what OpenPilot is about. +We are hobbyists and we want to share our work with fellow hobbyists, additionally we need to ensure the future of the project and make sure it is sustainable. + +If you wish to sell / distribute OpenPilot hardware or derivatives of OpenPilot hardware that are under a non-commercial license, please get in touch with one of the members of OpenPilot Foundation's administration committee. We can then negotiate a license waiver where a portion of the profits are donated to the OpenPilot Project to ensure its survival and future progression. Please note that this is in reference to PCB and Schematic designs, for people wishing to combine OpenPilot in to a Ready to Fly solution, this is perfectly fine as long as OpenPilot PCBs are bought from the OpenPilot project or one of the approved distributors. + +For details the Non-Commercial license please see: http://creativecommons.org/licenses/by-nc-sa/3.0/ + +A quick summary of what this license talk means, firstly using any work that is licensed under a form of the Creative Commons BY license, requires that credit is to be given. + +The SA or Share Alike part of the license means that you must also use the same license in any work derived from the work under this license. + +Hardware +The items under the non-commercial license means exactly that: they are for non-commercial use only and any derivatives that are made are also covered by the same non-commercial license. The hardware files under a non-commercial license are for +reference and for fellow hobbyists; they are not to be used to generate profit of any kind. Please note that even the OpenPilot project its self is a non-profit project. + +For all items both non-commercial and items that allows commercial use, the OP logo must be placed on any work or derivative work and be clearly visible. If any web addresses are present on the hardware, these are also required to remain on any replications or any derivative work. + +Documentation +In documentation, authors names must be kept along with any logos. If documentation is for a physical product such as a schematic, the OpenPilot logo should be shown and any web addresses also displayed on the final physical hardware it was derived from. + +Artwork +If artwork is to be reused, the OpenPilot project should be credited. If for example this is a software application, credit should be given on the application splash screen or in a separate part of the application that is visible to users. For example the Help / About screen. + +Contact Us +If you are unsure, please contact one of the OpenPilot Foundation's administrators. Additionally, if you plan to use parts of the OpenPilot project in your own work, we would appreciate it if you get in touch with us anyway, it is possible we could combine efforts or have some work already in progress that might be helpful. This of course is our baby and we want to see what great things people do with it as well. + +A final note, OpenPilot is a non-profit for fun project and we have only volunteers. A great deal of time, money and effort has been donated to this project; please respect the people that are part of it and their generosity. OpenPilot is funded entirely by the generous people who donate money and time to the community and help it grow. Giving full and proper credit is not only a legal requirement of the CC-BY-SA license, it is also the right thing to do. + +Buying hardware from the OpenPilot project is very important to the survival and continuing progress of the project, a project like OpenPilot is extremely expensive to produce. diff --git a/MILESTONES.txt b/MILESTONES.txt index b2e6b4944..0ea7d4c3d 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -1,267 +1,267 @@ -This is the Milestones file of the OpenPilot project, its intent is to record the major accomplishments achieved by people using the OpenPilot platform and who gets the karma for performing them. - - -The CREDITS.txt in SVN records the developers and the achievements made by each individual; this file is different as it is aimed at recording and giving credit to the people who achieve milestones in the use of OpenPilot. - - -The fields are: - -Milestone description (M) -Credited to (C) -Date (D) -Video (V) - Optional link to video showing milestone - - -M: OpenPilot driving EagleTree OSD -C: Frederic Goddeeris -D: August 2010 -V: http://vimeo.com/13659819 - -M: First manual fixed wing flight -C: James Cotton -D: September 2010 - -M: First stabilised fixed wing flight -C: Edouard Lafargue -D: September 2010 - -M: First stabilised Quad flight -C: James Cotton -D: September 2010 - -M: First stabilised Tri-Copter flight -C: Gary Mortimer and the Scorpion -D: October 2010 - -M: First communication between by PipX modems -C: Cathy Moss -D: October 2010 - -M: First OpenPilot night flight -C: Dale Schinstock -D: October 2010 -V: http://www.youtube.com/watch?v=yk8ckeRMV8U - -M: First stabilised Hexa flight -C: Sami Korhonen (Sambas) -D: November 2010 -V: http://www.youtube.com/watch?v=CIL29Yqt8Ck - -M: First -10 Deg C flight -C: Sami Korhonen (Sambas) -D: November 2010 -V: http://vimeo.com/17488702 - -M: First solid OpenPilot Position Hold -C: Dale Schinstock -D: December 2010 -V: http://www.youtube.com/watch?v=BBCGVP0Vpgw - -M: First intentional flip on a multirotor with OpenPilot -C: Sami Korhonen (Sambas) -D: December 2010 -V: http://vimeo.com/18318478 - -M: First CopterControl flight on a Quad -C: Sami Korhonen (Sambas) -D: January 2011 -V: http://vimeo.com/19592820 - -M: First UAVTalk connection across several continents - over the Internet -C: Eric Price (CorvusCorax), James Cotton -D: February 2011 -V: http://cybertrench.com/vixen/internet-telemetry_small.avi - -M: First CopterControl flight on a Fixed Wing -C: Oleg Semyonov (osnwt) -D: February 2011 -V: http://www.youtube.com/watch?v=gt1ok7iSGDY - -M: First intentional flip on a multirotor with CopterControl -C: Sami Korhonen (Sambas) -D: February 2011 -V: http://vimeo.com/20159015 - -M: First CopterControl Position Hold on a Fixed Wing -C: Eric Price (Corvus Corax) -D: March 2011 -V: http://www.youtube.com/watch?v=QtaefhmGbio - -M: Dave's First Flight. Pathetically delayed. -C: David Ankers -D: March 2011 -V: http://vimeo.com/22221798 - -M: First CopterControl flight on a Hexa -C: Edouard Lafargue -D: March 2011 -V: http://vimeo.com/21476466 - -M: First CopterControl flight on a Tri -C: Gary Mortimer and the Scorpion -D: March 2011 -V: http://vimeo.com/22104334 - -M: First Y6 OpenPilot flight -C: Sami Korhonen (Sambas) -D: May 2011 -V: http://www.vimeo.com/23637586 - -M: First CopterControl flight on a Flybarless Heli -C: Oleg Semyonov (osnwt) -D: May 2011 -V: http://www.youtube.com/watch?v=-J8cxqzxxWw - -M: First V8 Octo OpenPilot flight -C: Sami Korhonen (Sambas) -D: May 2011 -V: http://vimeo.com/24258192 - -M: First Y6 CopterControl flight -C: Michel Pet -D: June 2011 -V: http://www.youtube.com/watch?v=QsE2MQELPZY - -M: First MoveCopter flight -C: Werner Backes -D: July 2011 -V: http://vimeo.com/25983655 - -M: First Y4 CopterControl flight -C: Mat Wellington -D: July 2011 -V: http://www.youtube.com/watch?v=TxZ4MDGIj1o - -M: First V-Tail4 CopterControl flight -C: Mat Wellington -D: July 2011 -V: http://www.youtube.com/watch?v=YE4Fd9vdg1I - -M: First CopterControl Flybared Heli inverted flight (2:33) -C: Maxim Izergin (Maximus43) -D: August 2011 -V: http://www.youtube.com/watch?v=8SrfIS7OkB4 - -M: First CopterControl Flybared Heli funnel (4:18), loop (5:35) -C: Sergey Solodennikov (alconaft43) -D: August 2011 -V: http://www.youtube.com/watch?v=8SrfIS7OkB4 +This is the Milestones file of the OpenPilot project, its intent is to record the major accomplishments achieved by people using the OpenPilot platform and who gets the karma for performing them. + + +The CREDITS.txt in SVN records the developers and the achievements made by each individual; this file is different as it is aimed at recording and giving credit to the people who achieve milestones in the use of OpenPilot. + + +The fields are: + +Milestone description (M) +Credited to (C) +Date (D) +Video (V) - Optional link to video showing milestone + + +M: OpenPilot driving EagleTree OSD +C: Frederic Goddeeris +D: August 2010 +V: http://vimeo.com/13659819 + +M: First manual fixed wing flight +C: James Cotton +D: September 2010 + +M: First stabilised fixed wing flight +C: Edouard Lafargue +D: September 2010 + +M: First stabilised Quad flight +C: James Cotton +D: September 2010 + +M: First stabilised Tri-Copter flight +C: Gary Mortimer and the Scorpion +D: October 2010 + +M: First communication between by PipX modems +C: Cathy Moss +D: October 2010 + +M: First OpenPilot night flight +C: Dale Schinstock +D: October 2010 +V: http://www.youtube.com/watch?v=yk8ckeRMV8U + +M: First stabilised Hexa flight +C: Sami Korhonen (Sambas) +D: November 2010 +V: http://www.youtube.com/watch?v=CIL29Yqt8Ck + +M: First -10 Deg C flight +C: Sami Korhonen (Sambas) +D: November 2010 +V: http://vimeo.com/17488702 + +M: First solid OpenPilot Position Hold +C: Dale Schinstock +D: December 2010 +V: http://www.youtube.com/watch?v=BBCGVP0Vpgw + +M: First intentional flip on a multirotor with OpenPilot +C: Sami Korhonen (Sambas) +D: December 2010 +V: http://vimeo.com/18318478 + +M: First CopterControl flight on a Quad +C: Sami Korhonen (Sambas) +D: January 2011 +V: http://vimeo.com/19592820 + +M: First UAVTalk connection across several continents - over the Internet +C: Eric Price (CorvusCorax), James Cotton +D: February 2011 +V: http://cybertrench.com/vixen/internet-telemetry_small.avi + +M: First CopterControl flight on a Fixed Wing +C: Oleg Semyonov (osnwt) +D: February 2011 +V: http://www.youtube.com/watch?v=gt1ok7iSGDY + +M: First intentional flip on a multirotor with CopterControl +C: Sami Korhonen (Sambas) +D: February 2011 +V: http://vimeo.com/20159015 + +M: First CopterControl Position Hold on a Fixed Wing +C: Eric Price (Corvus Corax) +D: March 2011 +V: http://www.youtube.com/watch?v=QtaefhmGbio + +M: Dave's First Flight. Pathetically delayed. +C: David Ankers +D: March 2011 +V: http://vimeo.com/22221798 + +M: First CopterControl flight on a Hexa +C: Edouard Lafargue +D: March 2011 +V: http://vimeo.com/21476466 + +M: First CopterControl flight on a Tri +C: Gary Mortimer and the Scorpion +D: March 2011 +V: http://vimeo.com/22104334 + +M: First Y6 OpenPilot flight +C: Sami Korhonen (Sambas) +D: May 2011 +V: http://www.vimeo.com/23637586 + +M: First CopterControl flight on a Flybarless Heli +C: Oleg Semyonov (osnwt) +D: May 2011 +V: http://www.youtube.com/watch?v=-J8cxqzxxWw + +M: First V8 Octo OpenPilot flight +C: Sami Korhonen (Sambas) +D: May 2011 +V: http://vimeo.com/24258192 + +M: First Y6 CopterControl flight +C: Michel Pet +D: June 2011 +V: http://www.youtube.com/watch?v=QsE2MQELPZY + +M: First MoveCopter flight +C: Werner Backes +D: July 2011 +V: http://vimeo.com/25983655 + +M: First Y4 CopterControl flight +C: Mat Wellington +D: July 2011 +V: http://www.youtube.com/watch?v=TxZ4MDGIj1o + +M: First V-Tail4 CopterControl flight +C: Mat Wellington +D: July 2011 +V: http://www.youtube.com/watch?v=YE4Fd9vdg1I + +M: First CopterControl Flybared Heli inverted flight (2:33) +C: Maxim Izergin (Maximus43) +D: August 2011 +V: http://www.youtube.com/watch?v=8SrfIS7OkB4 + +M: First CopterControl Flybared Heli funnel (4:18), loop (5:35) +C: Sergey Solodennikov (alconaft43) +D: August 2011 +V: http://www.youtube.com/watch?v=8SrfIS7OkB4 + + +M: First CopterControl Return to Base Fixed Wing +C: Eric Price (Corvus Corax) +D: August 2011 +V: http://www.youtube.com/watch?v=CugI0oBSQn8 + +M: First CopterControl flip on a Flybarless Heli +C: Anders Johansson (dezent) +D: November 2011 +V: http://www.youtube.com/watch?v=Xfas2TUhOPw + +M: First CopterControl over 1km FixedWing navigation flight +C: Eric Price (Corvus Corax) +D: December 2011 +V: http://www.youtube.com/watch?v=nWNWuUiUTNg + +M: First CopterControl over 5km FixedWing navigation flight +C: Kavin Gustafson (k_g) +D: October 2012 +V: http://www.youtube.com/watch?v=MGO68TqIwKk + +M: First CopterControl over 10km FixedWing navigation flight +C: +D: +V: + +M: First successful flight using the GCS only and no RC TX +C: +D: +V: + +M: First successful flight using just a mobile phone +C: Jose (please complete details), demoed in Portugal +D: +V: + + +M: First Revo Altitude Hold using Sonar +C: +D: +V: + +M: First CopterControl Navigation on RC Ground Vechicle +C: +D: +V: + +M: First CopterControl Navigation on RC Water Vechicle +C: +D: +V: + +M: First Revo Navigated flight on a FixedWing +C: It got done somewhere along the line, likely Corvus. + +M: First Revo Navigated flight on a MultiRotor +C: It got done somewhere along the line, James or Sami + +M: First Revo Navigated flight on a Heli +C: +D: +V: + +M: First Revo 1km Navigated flight on a MultiRotor +C: +D: +V: + +M: First Revo 5km Navigated flight on a MultiRotor +C: +D: +V: + +M: First Revo 5km Navigated flight on a FixedWing +C: Eric Price (Corvus Corax) +D: March 2012 +V: + +M: First Revo 1km Navigated flight on a Heli +C: +D: +V: + +M: First Revo 5km Navigated flight on a Heli +C: +D: +V: + +M: First use of the Magic Waypoint feature +C: +D: +V: + +M: First Auto spot landing on a fixed Wing using Revo +C: +D: +V: + +M: First Auto take-off on a MultiRotor using Revo +C: +D: +V: + +M: First Auto landing on a MultiRotor using Revo +C: +D: +V: + +M: First Auto take-off on a Heli using Revo +C: +D: +V: + +M: First Auto landing on a Heli using Revo +C: +D: +V: - -M: First CopterControl Return to Base Fixed Wing -C: Eric Price (Corvus Corax) -D: August 2011 -V: http://www.youtube.com/watch?v=CugI0oBSQn8 - -M: First CopterControl flip on a Flybarless Heli -C: Anders Johansson (dezent) -D: November 2011 -V: http://www.youtube.com/watch?v=Xfas2TUhOPw - -M: First CopterControl over 1km FixedWing navigation flight -C: Eric Price (Corvus Corax) -D: December 2011 -V: http://www.youtube.com/watch?v=nWNWuUiUTNg - -M: First CopterControl over 5km FixedWing navigation flight -C: Kavin Gustafson (k_g) -D: October 2012 -V: http://www.youtube.com/watch?v=MGO68TqIwKk - -M: First CopterControl over 10km FixedWing navigation flight -C: -D: -V: - -M: First successful flight using the GCS only and no RC TX -C: -D: -V: - -M: First successful flight using just a mobile phone -C: Jose (please complete details), demoed in Portugal -D: -V: - - -M: First Revo Altitude Hold using Sonar -C: -D: -V: - -M: First CopterControl Navigation on RC Ground Vechicle -C: -D: -V: - -M: First CopterControl Navigation on RC Water Vechicle -C: -D: -V: - -M: First Revo Navigated flight on a FixedWing -C: It got done somewhere along the line, likely Corvus. - -M: First Revo Navigated flight on a MultiRotor -C: It got done somewhere along the line, James or Sami - -M: First Revo Navigated flight on a Heli -C: -D: -V: - -M: First Revo 1km Navigated flight on a MultiRotor -C: -D: -V: - -M: First Revo 5km Navigated flight on a MultiRotor -C: -D: -V: - -M: First Revo 5km Navigated flight on a FixedWing -C: Eric Price (Corvus Corax) -D: March 2012 -V: - -M: First Revo 1km Navigated flight on a Heli -C: -D: -V: - -M: First Revo 5km Navigated flight on a Heli -C: -D: -V: - -M: First use of the Magic Waypoint feature -C: -D: -V: - -M: First Auto spot landing on a fixed Wing using Revo -C: -D: -V: - -M: First Auto take-off on a MultiRotor using Revo -C: -D: -V: - -M: First Auto landing on a MultiRotor using Revo -C: -D: -V: - -M: First Auto take-off on a Heli using Revo -C: -D: -V: - -M: First Auto landing on a Heli using Revo -C: -D: -V: - diff --git a/Makefile b/Makefile index 057d7f2f4..d18a66497 100644 --- a/Makefile +++ b/Makefile @@ -24,14 +24,27 @@ # existance by each sub-make. export OPENPILOT_IS_COOL := Fuck Yeah! -# Set up a default goal -.DEFAULT_GOAL := help +# It is possible to set OPENPILOT_DL_DIR and/or OPENPILOT_TOOLS_DIR environment +# variables to override local tools download and installation directorys. So the +# same toolchains can be used for all working copies. Particularly useful for CI +# server build agents, but also for local installations. +# +# If no OPENPILOT_* variables found, makefile internal DL_DIR and TOOLS_DIR paths +# will be used. They still can be overriden by the make command line parameters: +# make DL_DIR=/path/to/download/directory TOOLS_DIR=/path/to/tools/directory targets... + +# Function for converting Windows style slashes into Unix style +slashfix = $(subst \,/,$(1)) + +# Function for converting an absolute path to one relative +# to the top of the source tree +toprel = $(subst $(realpath $(ROOT_DIR))/,,$(abspath $(1))) # Set up some macros for common directories within the tree export ROOT_DIR := $(realpath $(dir $(lastword $(MAKEFILE_LIST)))) -export TOOLS_DIR := $(ROOT_DIR)/tools +export DL_DIR := $(if $(OPENPILOT_DL_DIR),$(call slashfix,$(OPENPILOT_DL_DIR)),$(ROOT_DIR)/downloads) +export TOOLS_DIR := $(if $(OPENPILOT_TOOLS_DIR),$(call slashfix,$(OPENPILOT_TOOLS_DIR)),$(ROOT_DIR)/tools) export BUILD_DIR := $(ROOT_DIR)/build -export DL_DIR := $(ROOT_DIR)/downloads export PACKAGE_DIR := $(ROOT_DIR)/build/package # Set up default build configurations (debug | release) @@ -40,15 +53,11 @@ UAVOGEN_BUILD_CONF := release ANDROIDGCS_BUILD_CONF := debug GOOGLE_API_VERSION := 14 -# Function for converting an absolute path to one relative -# to the top of the source tree. -toprel = $(subst $(realpath $(ROOT_DIR))/,,$(abspath $(1))) - # Clean out undesirable variables from the environment and command-line # to remove the chance that they will cause problems with our build define SANITIZE_VAR $(if $(filter-out undefined,$(origin $(1))), - $(info *NOTE* Sanitized $(2) variable '$(1)' from $(origin $(1))) + $(info $(EMPTY) NOTE Sanitized $(2) variable '$(1)' from $(origin $(1))) MAKEOVERRIDES = $(filter-out $(1)=%,$(MAKEOVERRIDES)) override $(1) := unexport $(1) @@ -102,6 +111,7 @@ export ANT := ant export JAVAC := javac export JAR := jar export GIT := git +export CURL := curl export PYTHON := python export INSTALL := install @@ -110,64 +120,25 @@ export VERSION_INFO := $(PYTHON) "$(ROOT_DIR)/make/scripts/version-info.py" --pa # Test if quotes are needed for the echo-command ifeq (${shell $(ECHO) "test"}, test) - export QUOTE := ' + export QUOTE := ' # This line is just to clear out the single quote above ' else - export QUOTE := -endif - -# The tools.mk uses wget to fetch tarballs or packages -ifeq ($(shell [ -x "$(TOOLS_DIR)/bin/wget" ] && $(ECHO) "exists"), exists) - WGET := $(TOOLS_DIR)/bin/wget -else - # not installed, hope it's in the path... - WGET ?= wget + export QUOTE := endif # Include tools installers include $(ROOT_DIR)/make/tools.mk -# Set up paths to tools -ifeq ($(shell [ -d "$(QT_SDK_DIR)" ] && $(ECHO) "exists"), exists) - QMAKE := $(QT_SDK_QMAKE_PATH) -else - # not installed, hope it's in the path... - QMAKE ?= qmake -endif - -ifeq ($(shell [ -d "$(ARM_SDK_DIR)" ] && $(ECHO) "exists"), exists) - export ARM_SDK_PREFIX := $(ARM_SDK_DIR)/bin/arm-none-eabi- -else - # not installed, hope it's in the path... - export ARM_SDK_PREFIX ?= arm-none-eabi- -endif - -ifeq ($(shell [ -d "$(OPENOCD_DIR)" ] && $(ECHO) "exists"), exists) - export OPENOCD := $(OPENOCD_DIR)/bin/openocd -else - # not installed, hope it's in the path... - export OPENOCD ?= openocd -endif - -ifeq ($(shell [ -d "$(ANDROID_SDK_DIR)" ] && $(ECHO) "exists"), exists) - ANDROID := $(ANDROID_SDK_DIR)/tools/android - ANDROID_DX := $(ANDROID_SDK_DIR)/platform-tools/dx -else - # not installed, hope it's in the path... - ANDROID ?= android - ANDROID_DX ?= dx -endif - # We almost need to consider autoconf/automake instead of this ifeq ($(UNAME), Linux) QT_SPEC = linux-g++ - UAVOBJGENERATOR = "$(BUILD_DIR)/ground/uavobjgenerator/uavobjgenerator" + UAVOBJGENERATOR = "$(BUILD_DIR)/uavobjgenerator/uavobjgenerator" else ifeq ($(UNAME), Darwin) QT_SPEC = macx-g++ - UAVOBJGENERATOR = "$(BUILD_DIR)/ground/uavobjgenerator/uavobjgenerator" + UAVOBJGENERATOR = "$(BUILD_DIR)/uavobjgenerator/uavobjgenerator" else QT_SPEC = win32-g++ - UAVOBJGENERATOR = "$(BUILD_DIR)/ground/uavobjgenerator/$(UAVOGEN_BUILD_CONF)/uavobjgenerator.exe" + UAVOBJGENERATOR = "$(BUILD_DIR)/uavobjgenerator/$(UAVOGEN_BUILD_CONF)/uavobjgenerator.exe" endif ############################## @@ -206,8 +177,8 @@ endif .PHONY: uavobjgenerator uavobjgenerator: - $(V1) $(MKDIR) -p $(BUILD_DIR)/ground/$@ - $(V1) ( cd $(BUILD_DIR)/ground/$@ && \ + $(V1) $(MKDIR) -p $(BUILD_DIR)/$@ + $(V1) ( cd $(BUILD_DIR)/$@ && \ $(QMAKE) $(ROOT_DIR)/ground/uavobjgenerator/uavobjgenerator.pro -spec $(QT_SPEC) -r CONFIG+="$(UAVOGEN_BUILD_CONF) $(UAVOGEN_SILENT)" && \ $(MAKE) --no-print-directory -w ; \ ) @@ -251,6 +222,7 @@ export OPUAVTALK := $(ROOT_DIR)/flight/targets/UAVTalk export HWDEFS := $(ROOT_DIR)/flight/targets/board_hw_defs export DOXYGENDIR := $(ROOT_DIR)/flight/Doc/Doxygen export OPUAVSYNTHDIR := $(BUILD_DIR)/uavobject-synthetics/flight +export OPGCSSYNTHDIR := $(BUILD_DIR)/openpilotgcs-synthetics # Define supported board lists ALL_BOARDS := coptercontrol pipxtreme revolution revomini osd simposix @@ -509,7 +481,6 @@ all_ground: openpilotgcs .PHONY: gcs gcs_clean gcs_all_clean gcs: openpilotgcs gcs_clean: openpilotgcs_clean -gcs_all_clean: openpilotgcs_all_clean ifeq ($(V), 1) GCS_SILENT := @@ -519,8 +490,8 @@ endif .PHONY: openpilotgcs openpilotgcs: uavobjects_gcs - $(V1) $(MKDIR) -p $(BUILD_DIR)/ground/$@/$(GCS_BUILD_CONF) - $(V1) ( cd $(BUILD_DIR)/ground/$@/$(GCS_BUILD_CONF) && \ + $(V1) $(MKDIR) -p $(BUILD_DIR)/$@_$(GCS_BUILD_CONF) + $(V1) ( cd $(BUILD_DIR)/$@_$(GCS_BUILD_CONF) && \ $(QMAKE) $(ROOT_DIR)/ground/openpilotgcs/openpilotgcs.pro -spec $(QT_SPEC) -r CONFIG+="$(GCS_BUILD_CONF) $(GCS_SILENT)" $(GCS_QMAKE_OPTS) && \ $(MAKE) -w ; \ ) @@ -528,12 +499,7 @@ openpilotgcs: uavobjects_gcs .PHONY: openpilotgcs_clean openpilotgcs_clean: $(V0) @$(ECHO) " CLEAN $@" - $(V1) [ ! -d "$(BUILD_DIR)/ground/openpilotgcs/$(GCS_BUILD_CONF)" ] || $(RM) -r "$(BUILD_DIR)/ground/openpilotgcs/$(GCS_BUILD_CONF)" - -.PHONY: openpilotgcs_all_clean -openpilotgcs_all_clean: - $(V0) @$(ECHO) " CLEAN $@" - $(V1) [ ! -d "$(BUILD_DIR)/ground/openpilotgcs" ] || $(RM) -r "$(BUILD_DIR)/ground/openpilotgcs" + $(V1) [ ! -d "$(BUILD_DIR)/openpilotgcs_$(GCS_BUILD_CONF)" ] || $(RM) -r "$(BUILD_DIR)/openpilotgcs_$(GCS_BUILD_CONF)" ################################ # @@ -755,7 +721,7 @@ $(foreach ut, $(ALL_UNITTESTS), $(eval $(call UT_TEMPLATE,$(ut)))) # output is interleaved with the rest of the make output. ifneq ($(strip $(filter all_ut_run,$(MAKECMDGOALS))),) .NOTPARALLEL: - $(info *NOTE* Parallel make disabled by all_ut_run target so we have sane console output) + $(info $(EMPTY) NOTE Parallel make disabled by all_ut_run target so we have sane console output) endif ############################## @@ -771,8 +737,8 @@ PACKAGE_ELF_TARGETS := $(filter fw_simposix, $(FW_TARGETS)) # Rules to generate GCS resources used to embed firmware binaries into the GCS. # They are used later by the vehicle setup wizard to update board firmware. # To open a firmware image use ":/firmware/fw_coptercontrol.opfw" -OPFW_RESOURCE := $(BUILD_DIR)/ground/opfw_resource/opfw_resource.qrc -OPFW_RESOURCE_PREFIX := ../../../ +OPFW_RESOURCE := $(OPGCSSYNTHDIR)/opfw_resource.qrc +OPFW_RESOURCE_PREFIX := ../../ OPFW_FILES := $(foreach fw_targ, $(PACKAGE_FW_TARGETS), $(call toprel, $(BUILD_DIR)/$(fw_targ)/$(fw_targ).opfw)) OPFW_CONTENTS := \ \ @@ -789,8 +755,8 @@ $(OPFW_RESOURCE): $(FW_TARGETS) $(V1) $(MKDIR) -p $(dir $@) $(V1) $(ECHO) $(QUOTE)$(OPFW_CONTENTS)$(QUOTE) > $@ -# If opfw_resource is requested, GCS should depend on it -ifneq ($(strip $(filter opfw_resource,$(MAKECMDGOALS))),) +# If opfw_resource or all are requested, GCS should depend on the resource +ifneq ($(strip $(filter opfw_resource all,$(MAKECMDGOALS))),) $(eval openpilotgcs: | opfw_resource) endif @@ -869,6 +835,8 @@ build-info: # ############################## +.DEFAULT_GOAL := help + .PHONY: help help: @$(ECHO) @@ -884,6 +852,12 @@ help: @$(ECHO) " stm32flash_install - Install the stm32flash tool for unbricking F1-based boards" @$(ECHO) " dfuutil_install - Install the dfu-util tool for unbricking F4-based boards" @$(ECHO) " android_sdk_install - Install the Android SDK tools" + @$(ECHO) " all_sdk_install - Install all of above (platform-dependent)" + @$(ECHO) + @$(ECHO) " Other tool options are:" + @$(ECHO) " _version - Display version" + @$(ECHO) " _clean - Remove installed " + @$(ECHO) " _distclean - Remove downloaded distribution file(s)" @$(ECHO) @$(ECHO) " [Big Hammer]" @$(ECHO) " all - Generate UAVObjects, build openpilot firmware and gcs" @@ -895,7 +869,7 @@ help: @$(ECHO) " all_clean - Remove your build directory ($(BUILD_DIR))" @$(ECHO) " all_flight_clean - Remove all firmware, bootloaders and bootloader updaters" @$(ECHO) " all_fw_clean - Remove firmware for all boards" - @$(ECHO) " all_bl_clean - Remove bootlaoders for all boards" + @$(ECHO) " all_bl_clean - Remove bootloaders for all boards" @$(ECHO) " all_bu_clean - Remove bootloader updaters for all boards" @$(ECHO) @$(ECHO) " all_ - Build all available images for " @@ -970,7 +944,7 @@ help: @$(ECHO) @$(ECHO) " Hint: Add V=1 to your command line to see verbose build output." @$(ECHO) - @$(ECHO) " Note: All tools will be installed into $(TOOLS_DIR)" - @$(ECHO) " All build output will be placed in $(BUILD_DIR)" - @$(ECHO) " Package will be placed into $(PACKAGE_DIR)" + @$(ECHO) " Notes: All tool distribution files will be downloaded into $(DL_DIR)" + @$(ECHO) " All tools will be installed into $(TOOLS_DIR)" + @$(ECHO) " All build output will be placed in $(BUILD_DIR)" @$(ECHO) diff --git a/flight/.gitattributes b/flight/.gitattributes new file mode 100644 index 000000000..e85fe7958 --- /dev/null +++ b/flight/.gitattributes @@ -0,0 +1,17 @@ +# +# Flight source code files should always have LF line endings by agreement +# http://wiki.openpilot.org/display/Doc/Coding+Style +# + +*.c text eol=lf +*.h text eol=lf +*.py text eol=lf + +*.s text eol=lf +*.S text eol=lf +*.ld text eol=lf +*.inc text eol=lf + +Makefile text eol=lf +Makefile.* text eol=lf +*.mk text eol=lf diff --git a/flight/Libraries/PyMite/platform/openpilot/plat.c b/flight/Libraries/PyMite/platform/openpilot/plat.c index f68ac7af6..7f8e10546 100644 --- a/flight/Libraries/PyMite/platform/openpilot/plat.c +++ b/flight/Libraries/PyMite/platform/openpilot/plat.c @@ -1,86 +1,86 @@ -/** - * @file plat.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PyMite platform definitions for OpenPilot - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pm.h" -#include "openpilot.h" - -int pylinenum; - -PmReturn_t plat_init(void) -{ - return PM_RET_OK; -} - -PmReturn_t plat_deinit(void) -{ - return PM_RET_OK; -} - -/* - * Gets a byte from the address in the designated memory space - * Post-increments *paddr. - */ -uint8_t plat_memGetByte(PmMemSpace_t memspace, uint8_t const **paddr) -{ - uint8_t b = 0; - - switch (memspace) - { - case MEMSPACE_RAM: - case MEMSPACE_PROG: - b = **paddr; - *paddr += 1; - return b; - case MEMSPACE_EEPROM: - case MEMSPACE_SEEPROM: - case MEMSPACE_OTHER0: - case MEMSPACE_OTHER1: - case MEMSPACE_OTHER2: - case MEMSPACE_OTHER3: - default: - return 0; - } -} - -PmReturn_t plat_getByte(uint8_t *b) -{ - return PM_RET_ERR; -} - -PmReturn_t plat_putByte(uint8_t b) -{ - return PM_RET_ERR; -} - -PmReturn_t plat_getMsTicks(uint32_t *r_ticks) -{ - *r_ticks = xTaskGetTickCount() * portTICK_RATE_MS; - return PM_RET_OK; -} - -void plat_reportError(PmReturn_t result) -{ - /* TODO: Copy error information to UAVObject */ - /* gVmGlobal.errVmRelease gVmGlobal.errFileId gVmGlobal.errLineNum */ -} +/** + * @file plat.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PyMite platform definitions for OpenPilot + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pm.h" +#include "openpilot.h" + +int pylinenum; + +PmReturn_t plat_init(void) +{ + return PM_RET_OK; +} + +PmReturn_t plat_deinit(void) +{ + return PM_RET_OK; +} + +/* + * Gets a byte from the address in the designated memory space + * Post-increments *paddr. + */ +uint8_t plat_memGetByte(PmMemSpace_t memspace, uint8_t const **paddr) +{ + uint8_t b = 0; + + switch (memspace) + { + case MEMSPACE_RAM: + case MEMSPACE_PROG: + b = **paddr; + *paddr += 1; + return b; + case MEMSPACE_EEPROM: + case MEMSPACE_SEEPROM: + case MEMSPACE_OTHER0: + case MEMSPACE_OTHER1: + case MEMSPACE_OTHER2: + case MEMSPACE_OTHER3: + default: + return 0; + } +} + +PmReturn_t plat_getByte(uint8_t *b) +{ + return PM_RET_ERR; +} + +PmReturn_t plat_putByte(uint8_t b) +{ + return PM_RET_ERR; +} + +PmReturn_t plat_getMsTicks(uint32_t *r_ticks) +{ + *r_ticks = xTaskGetTickCount() * portTICK_RATE_MS; + return PM_RET_OK; +} + +void plat_reportError(PmReturn_t result) +{ + /* TODO: Copy error information to UAVObject */ + /* gVmGlobal.errVmRelease gVmGlobal.errFileId gVmGlobal.errLineNum */ +} diff --git a/flight/Libraries/PyMite/platform/openpilot_sitl/plat.c b/flight/Libraries/PyMite/platform/openpilot_sitl/plat.c index 3b14d3a53..2539c6fc9 100644 --- a/flight/Libraries/PyMite/platform/openpilot_sitl/plat.c +++ b/flight/Libraries/PyMite/platform/openpilot_sitl/plat.c @@ -1,307 +1,307 @@ -/** - * @file plat.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PyMite platform definitions for OpenPilot - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pm.h" -#include "openpilot.h" - -PmReturn_t plat_init(void) -{ - return PM_RET_OK; -} - -PmReturn_t plat_deinit(void) -{ - return PM_RET_OK; -} - -/* - * Gets a byte from the address in the designated memory space - * Post-increments *paddr. - */ -uint8_t plat_memGetByte(PmMemSpace_t memspace, uint8_t const **paddr) -{ - uint8_t b = 0; - - switch (memspace) - { - case MEMSPACE_RAM: - case MEMSPACE_PROG: - b = **paddr; - *paddr += 1; - return b; - case MEMSPACE_EEPROM: - case MEMSPACE_SEEPROM: - case MEMSPACE_OTHER0: - case MEMSPACE_OTHER1: - case MEMSPACE_OTHER2: - case MEMSPACE_OTHER3: - default: - return 0; - } -} - -PmReturn_t plat_getByte(uint8_t *b) -{ - int c; - PmReturn_t retval = PM_RET_OK; - - c = getchar(); - *b = c & 0xFF; - - if (c == EOF) - { - PM_RAISE(retval, PM_RET_EX_IO); - } - - return retval; -} - -PmReturn_t plat_putByte(uint8_t b) -{ - int i; - PmReturn_t retval = PM_RET_OK; - - i = putchar(b); - fflush(stdout); - - if ((i != b) || (i == EOF)) - { - PM_RAISE(retval, PM_RET_EX_IO); - } - - return retval; -} - -PmReturn_t plat_getMsTicks(uint32_t *r_ticks) -{ - *r_ticks = xTaskGetTickCount() * portTICK_RATE_MS; - return PM_RET_OK; -} - -void plat_reportError(PmReturn_t result) -{ -#ifdef HAVE_DEBUG_INFO -#define LEN_FNLOOKUP 26 -#define LEN_EXNLOOKUP 17 - - uint8_t res; - pPmFrame_t pframe; - pPmObj_t pstr; - PmReturn_t retval; - uint8_t bcindex; - uint16_t bcsum; - uint16_t linesum; - uint16_t len_lnotab; - uint8_t const *plnotab; - uint16_t i; - - /* This table should match src/vm/fileid.txt */ - char const * const fnlookup[LEN_FNLOOKUP] = { - "", - "codeobj.c", - "dict.c", - "frame.c", - "func.c", - "global.c", - "heap.c", - "img.c", - "int.c", - "interp.c", - "pmstdlib_nat.c", - "list.c", - "main.c", - "mem.c", - "module.c", - "obj.c", - "seglist.c", - "sli.c", - "strobj.c", - "tuple.c", - "seq.c", - "pm.c", - "thread.c", - "float.c", - "class.c", - "bytearray.c", - }; - - /* This table should match src/vm/pm.h PmReturn_t */ - char const * const exnlookup[LEN_EXNLOOKUP] = { - "Exception", - "SystemExit", - "IoError", - "ZeroDivisionError", - "AssertionError", - "AttributeError", - "ImportError", - "IndexError", - "KeyError", - "MemoryError", - "NameError", - "SyntaxError", - "SystemError", - "TypeError", - "ValueError", - "StopIteration", - "Warning", - }; - - /* Print traceback */ - printf("Traceback (most recent call first):\n"); - - /* Get the top frame */ - pframe = gVmGlobal.pthread->pframe; - - /* If it's the native frame, print the native function name */ - if (pframe == (pPmFrame_t)&(gVmGlobal.nativeframe)) - { - - /* The last name in the names tuple of the code obj is the name */ - retval = tuple_getItem((pPmObj_t)gVmGlobal.nativeframe.nf_func-> - f_co->co_names, -1, &pstr); - if ((retval) != PM_RET_OK) - { - printf(" Unable to get native func name.\n"); - return; - } - else - { - printf(" %s() __NATIVE__\n", ((pPmString_t)pstr)->val); - } - - /* Get the frame that called the native frame */ - pframe = (pPmFrame_t)gVmGlobal.nativeframe.nf_back; - } - - /* Print the remaining frame stack */ - for (; pframe != C_NULL; pframe = pframe->fo_back) - { - /* The last name in the names tuple of the code obj is the name */ - retval = tuple_getItem((pPmObj_t)pframe->fo_func->f_co->co_names, - -1, - &pstr); - if ((retval) != PM_RET_OK) break; - - /* - * Get the line number of the current bytecode. Algorithm comes from: - * http://svn.python.org/view/python/trunk/Objects/lnotab_notes.txt?view=markup - */ - bcindex = pframe->fo_ip - pframe->fo_func->f_co->co_codeaddr; - plnotab = pframe->fo_func->f_co->co_lnotab; - len_lnotab = mem_getWord(MEMSPACE_PROG, &plnotab); - bcsum = 0; - linesum = pframe->fo_func->f_co->co_firstlineno; - for (i = 0; i < len_lnotab; i += 2) - { - bcsum += mem_getByte(MEMSPACE_PROG, &plnotab); - if (bcsum > bcindex) break; - linesum += mem_getByte(MEMSPACE_PROG, &plnotab); - } - printf(" File \"%s\", line %d, in %s\n", - ((pPmFrame_t)pframe)->fo_func->f_co->co_filename, - linesum, - ((pPmString_t)pstr)->val); - } - - /* Print error */ - res = (uint8_t)result; - if ((res > 0) && ((res - PM_RET_EX) < LEN_EXNLOOKUP)) - { - printf("%s", exnlookup[res - PM_RET_EX]); - } - else - { - printf("Error code 0x%02X", result); - } - printf(" detected by "); - - if ((gVmGlobal.errFileId > 0) && (gVmGlobal.errFileId < LEN_FNLOOKUP)) - { - printf("%s:", fnlookup[gVmGlobal.errFileId]); - } - else - { - printf("FileId 0x%02X line ", gVmGlobal.errFileId); - } - printf("%d\n", gVmGlobal.errLineNum); - -#else /* HAVE_DEBUG_INFO */ - - /* Print error */ - printf("Error: 0x%02X\n", result); - printf(" Release: 0x%02X\n", gVmGlobal.errVmRelease); - printf(" FileId: 0x%02X\n", gVmGlobal.errFileId); - printf(" LineNum: %d\n", gVmGlobal.errLineNum); - - /* Print traceback */ - { - pPmObj_t pframe; - pPmObj_t pstr; - PmReturn_t retval; - - printf("Traceback (top first):\n"); - - /* Get the top frame */ - pframe = (pPmObj_t)gVmGlobal.pthread->pframe; - - /* If it's the native frame, print the native function name */ - if (pframe == (pPmObj_t)&(gVmGlobal.nativeframe)) - { - - /* The last name in the names tuple of the code obj is the name */ - retval = tuple_getItem((pPmObj_t)gVmGlobal.nativeframe.nf_func-> - f_co->co_names, -1, &pstr); - if ((retval) != PM_RET_OK) - { - printf(" Unable to get native func name.\n"); - return; - } - else - { - printf(" %s() __NATIVE__\n", ((pPmString_t)pstr)->val); - } - - /* Get the frame that called the native frame */ - pframe = (pPmObj_t)gVmGlobal.nativeframe.nf_back; - } - - /* Print the remaining frame stack */ - for (; - pframe != C_NULL; - pframe = (pPmObj_t)((pPmFrame_t)pframe)->fo_back) - { - /* The last name in the names tuple of the code obj is the name */ - retval = tuple_getItem((pPmObj_t)((pPmFrame_t)pframe)-> - fo_func->f_co->co_names, -1, &pstr); - if ((retval) != PM_RET_OK) break; - - printf(" %s()\n", ((pPmString_t)pstr)->val); - } - printf(" .\n"); - } -#endif /* HAVE_DEBUG_INFO */ - - /* TODO: Copy error information to UAVObject */ - /* gVmGlobal.errVmRelease gVmGlobal.errFileId gVmGlobal.errLineNum */ -} +/** + * @file plat.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PyMite platform definitions for OpenPilot + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pm.h" +#include "openpilot.h" + +PmReturn_t plat_init(void) +{ + return PM_RET_OK; +} + +PmReturn_t plat_deinit(void) +{ + return PM_RET_OK; +} + +/* + * Gets a byte from the address in the designated memory space + * Post-increments *paddr. + */ +uint8_t plat_memGetByte(PmMemSpace_t memspace, uint8_t const **paddr) +{ + uint8_t b = 0; + + switch (memspace) + { + case MEMSPACE_RAM: + case MEMSPACE_PROG: + b = **paddr; + *paddr += 1; + return b; + case MEMSPACE_EEPROM: + case MEMSPACE_SEEPROM: + case MEMSPACE_OTHER0: + case MEMSPACE_OTHER1: + case MEMSPACE_OTHER2: + case MEMSPACE_OTHER3: + default: + return 0; + } +} + +PmReturn_t plat_getByte(uint8_t *b) +{ + int c; + PmReturn_t retval = PM_RET_OK; + + c = getchar(); + *b = c & 0xFF; + + if (c == EOF) + { + PM_RAISE(retval, PM_RET_EX_IO); + } + + return retval; +} + +PmReturn_t plat_putByte(uint8_t b) +{ + int i; + PmReturn_t retval = PM_RET_OK; + + i = putchar(b); + fflush(stdout); + + if ((i != b) || (i == EOF)) + { + PM_RAISE(retval, PM_RET_EX_IO); + } + + return retval; +} + +PmReturn_t plat_getMsTicks(uint32_t *r_ticks) +{ + *r_ticks = xTaskGetTickCount() * portTICK_RATE_MS; + return PM_RET_OK; +} + +void plat_reportError(PmReturn_t result) +{ +#ifdef HAVE_DEBUG_INFO +#define LEN_FNLOOKUP 26 +#define LEN_EXNLOOKUP 17 + + uint8_t res; + pPmFrame_t pframe; + pPmObj_t pstr; + PmReturn_t retval; + uint8_t bcindex; + uint16_t bcsum; + uint16_t linesum; + uint16_t len_lnotab; + uint8_t const *plnotab; + uint16_t i; + + /* This table should match src/vm/fileid.txt */ + char const * const fnlookup[LEN_FNLOOKUP] = { + "", + "codeobj.c", + "dict.c", + "frame.c", + "func.c", + "global.c", + "heap.c", + "img.c", + "int.c", + "interp.c", + "pmstdlib_nat.c", + "list.c", + "main.c", + "mem.c", + "module.c", + "obj.c", + "seglist.c", + "sli.c", + "strobj.c", + "tuple.c", + "seq.c", + "pm.c", + "thread.c", + "float.c", + "class.c", + "bytearray.c", + }; + + /* This table should match src/vm/pm.h PmReturn_t */ + char const * const exnlookup[LEN_EXNLOOKUP] = { + "Exception", + "SystemExit", + "IoError", + "ZeroDivisionError", + "AssertionError", + "AttributeError", + "ImportError", + "IndexError", + "KeyError", + "MemoryError", + "NameError", + "SyntaxError", + "SystemError", + "TypeError", + "ValueError", + "StopIteration", + "Warning", + }; + + /* Print traceback */ + printf("Traceback (most recent call first):\n"); + + /* Get the top frame */ + pframe = gVmGlobal.pthread->pframe; + + /* If it's the native frame, print the native function name */ + if (pframe == (pPmFrame_t)&(gVmGlobal.nativeframe)) + { + + /* The last name in the names tuple of the code obj is the name */ + retval = tuple_getItem((pPmObj_t)gVmGlobal.nativeframe.nf_func-> + f_co->co_names, -1, &pstr); + if ((retval) != PM_RET_OK) + { + printf(" Unable to get native func name.\n"); + return; + } + else + { + printf(" %s() __NATIVE__\n", ((pPmString_t)pstr)->val); + } + + /* Get the frame that called the native frame */ + pframe = (pPmFrame_t)gVmGlobal.nativeframe.nf_back; + } + + /* Print the remaining frame stack */ + for (; pframe != C_NULL; pframe = pframe->fo_back) + { + /* The last name in the names tuple of the code obj is the name */ + retval = tuple_getItem((pPmObj_t)pframe->fo_func->f_co->co_names, + -1, + &pstr); + if ((retval) != PM_RET_OK) break; + + /* + * Get the line number of the current bytecode. Algorithm comes from: + * http://svn.python.org/view/python/trunk/Objects/lnotab_notes.txt?view=markup + */ + bcindex = pframe->fo_ip - pframe->fo_func->f_co->co_codeaddr; + plnotab = pframe->fo_func->f_co->co_lnotab; + len_lnotab = mem_getWord(MEMSPACE_PROG, &plnotab); + bcsum = 0; + linesum = pframe->fo_func->f_co->co_firstlineno; + for (i = 0; i < len_lnotab; i += 2) + { + bcsum += mem_getByte(MEMSPACE_PROG, &plnotab); + if (bcsum > bcindex) break; + linesum += mem_getByte(MEMSPACE_PROG, &plnotab); + } + printf(" File \"%s\", line %d, in %s\n", + ((pPmFrame_t)pframe)->fo_func->f_co->co_filename, + linesum, + ((pPmString_t)pstr)->val); + } + + /* Print error */ + res = (uint8_t)result; + if ((res > 0) && ((res - PM_RET_EX) < LEN_EXNLOOKUP)) + { + printf("%s", exnlookup[res - PM_RET_EX]); + } + else + { + printf("Error code 0x%02X", result); + } + printf(" detected by "); + + if ((gVmGlobal.errFileId > 0) && (gVmGlobal.errFileId < LEN_FNLOOKUP)) + { + printf("%s:", fnlookup[gVmGlobal.errFileId]); + } + else + { + printf("FileId 0x%02X line ", gVmGlobal.errFileId); + } + printf("%d\n", gVmGlobal.errLineNum); + +#else /* HAVE_DEBUG_INFO */ + + /* Print error */ + printf("Error: 0x%02X\n", result); + printf(" Release: 0x%02X\n", gVmGlobal.errVmRelease); + printf(" FileId: 0x%02X\n", gVmGlobal.errFileId); + printf(" LineNum: %d\n", gVmGlobal.errLineNum); + + /* Print traceback */ + { + pPmObj_t pframe; + pPmObj_t pstr; + PmReturn_t retval; + + printf("Traceback (top first):\n"); + + /* Get the top frame */ + pframe = (pPmObj_t)gVmGlobal.pthread->pframe; + + /* If it's the native frame, print the native function name */ + if (pframe == (pPmObj_t)&(gVmGlobal.nativeframe)) + { + + /* The last name in the names tuple of the code obj is the name */ + retval = tuple_getItem((pPmObj_t)gVmGlobal.nativeframe.nf_func-> + f_co->co_names, -1, &pstr); + if ((retval) != PM_RET_OK) + { + printf(" Unable to get native func name.\n"); + return; + } + else + { + printf(" %s() __NATIVE__\n", ((pPmString_t)pstr)->val); + } + + /* Get the frame that called the native frame */ + pframe = (pPmObj_t)gVmGlobal.nativeframe.nf_back; + } + + /* Print the remaining frame stack */ + for (; + pframe != C_NULL; + pframe = (pPmObj_t)((pPmFrame_t)pframe)->fo_back) + { + /* The last name in the names tuple of the code obj is the name */ + retval = tuple_getItem((pPmObj_t)((pPmFrame_t)pframe)-> + fo_func->f_co->co_names, -1, &pstr); + if ((retval) != PM_RET_OK) break; + + printf(" %s()\n", ((pPmString_t)pstr)->val); + } + printf(" .\n"); + } +#endif /* HAVE_DEBUG_INFO */ + + /* TODO: Copy error information to UAVObject */ + /* gVmGlobal.errVmRelease gVmGlobal.errFileId gVmGlobal.errLineNum */ +} diff --git a/flight/Libraries/PyMite/platform/windows/stdint.h b/flight/Libraries/PyMite/platform/windows/stdint.h index 31d1ef60a..d0160e6f2 100644 --- a/flight/Libraries/PyMite/platform/windows/stdint.h +++ b/flight/Libraries/PyMite/platform/windows/stdint.h @@ -1,26 +1,26 @@ -/* - * Small stdint.h replacement to be used with the MS Visual C++ environment - */ - -#ifndef __stdint_h__ -#define __stdint_h__ - -#if defined(_MSC_VER) - // Visual Studio does not include stdint.h, so we do it inline here - typedef char int8_t; - typedef short int16_t; - typedef int int32_t; - typedef unsigned char uint8_t; - typedef unsigned short uint16_t; - typedef unsigned int uint32_t; - - // change the default VS _DEBUG into PyMite __DEBUG__ - #if defined(_DEBUG) - #define __DEBUG__ 1 - #endif -#else - //#include -#endif - - +/* + * Small stdint.h replacement to be used with the MS Visual C++ environment + */ + +#ifndef __stdint_h__ +#define __stdint_h__ + +#if defined(_MSC_VER) + // Visual Studio does not include stdint.h, so we do it inline here + typedef char int8_t; + typedef short int16_t; + typedef int int32_t; + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + + // change the default VS _DEBUG into PyMite __DEBUG__ + #if defined(_DEBUG) + #define __DEBUG__ 1 + #endif +#else + //#include +#endif + + #endif /* __stdint_h__ */ \ No newline at end of file diff --git a/flight/Libraries/aes.c b/flight/Libraries/aes.c index c21ce2f9e..c89636dfa 100644 --- a/flight/Libraries/aes.c +++ b/flight/Libraries/aes.c @@ -1,475 +1,475 @@ - -// http://gladman.plushost.co.uk/oldsite/AES/index.php - -#include - -#include "aes.h" - -#define BPOLY 0x1B -#define DPOLY 0x8D - -const uint8_t sbox[256] = -{ - 0x63,0x7c,0x77,0x7b,0xf2,0x6b,0x6f,0xc5,0x30,0x01,0x67,0x2b,0xfe,0xd7,0xab,0x76, - 0xca,0x82,0xc9,0x7d,0xfa,0x59,0x47,0xf0,0xad,0xd4,0xa2,0xaf,0x9c,0xa4,0x72,0xc0, - 0xb7,0xfd,0x93,0x26,0x36,0x3f,0xf7,0xcc,0x34,0xa5,0xe5,0xf1,0x71,0xd8,0x31,0x15, - 0x04,0xc7,0x23,0xc3,0x18,0x96,0x05,0x9a,0x07,0x12,0x80,0xe2,0xeb,0x27,0xb2,0x75, - 0x09,0x83,0x2c,0x1a,0x1b,0x6e,0x5a,0xa0,0x52,0x3b,0xd6,0xb3,0x29,0xe3,0x2f,0x84, - 0x53,0xd1,0x00,0xed,0x20,0xfc,0xb1,0x5b,0x6a,0xcb,0xbe,0x39,0x4a,0x4c,0x58,0xcf, - 0xd0,0xef,0xaa,0xfb,0x43,0x4d,0x33,0x85,0x45,0xf9,0x02,0x7f,0x50,0x3c,0x9f,0xa8, - 0x51,0xa3,0x40,0x8f,0x92,0x9d,0x38,0xf5,0xbc,0xb6,0xda,0x21,0x10,0xff,0xf3,0xd2, - 0xcd,0x0c,0x13,0xec,0x5f,0x97,0x44,0x17,0xc4,0xa7,0x7e,0x3d,0x64,0x5d,0x19,0x73, - 0x60,0x81,0x4f,0xdc,0x22,0x2a,0x90,0x88,0x46,0xee,0xb8,0x14,0xde,0x5e,0x0b,0xdb, - 0xe0,0x32,0x3a,0x0a,0x49,0x06,0x24,0x5c,0xc2,0xd3,0xac,0x62,0x91,0x95,0xe4,0x79, - 0xe7,0xc8,0x37,0x6d,0x8d,0xd5,0x4e,0xa9,0x6c,0x56,0xf4,0xea,0x65,0x7a,0xae,0x08, - 0xba,0x78,0x25,0x2e,0x1c,0xa6,0xb4,0xc6,0xe8,0xdd,0x74,0x1f,0x4b,0xbd,0x8b,0x8a, - 0x70,0x3e,0xb5,0x66,0x48,0x03,0xf6,0x0e,0x61,0x35,0x57,0xb9,0x86,0xc1,0x1d,0x9e, - 0xe1,0xf8,0x98,0x11,0x69,0xd9,0x8e,0x94,0x9b,0x1e,0x87,0xe9,0xce,0x55,0x28,0xdf, - 0x8c,0xa1,0x89,0x0d,0xbf,0xe6,0x42,0x68,0x41,0x99,0x2d,0x0f,0xb0,0x54,0xbb,0x16 -}; - -const uint8_t isbox[256] = -{ - 0x52,0x09,0x6a,0xd5,0x30,0x36,0xa5,0x38,0xbf,0x40,0xa3,0x9e,0x81,0xf3,0xd7,0xfb, - 0x7c,0xe3,0x39,0x82,0x9b,0x2f,0xff,0x87,0x34,0x8e,0x43,0x44,0xc4,0xde,0xe9,0xcb, - 0x54,0x7b,0x94,0x32,0xa6,0xc2,0x23,0x3d,0xee,0x4c,0x95,0x0b,0x42,0xfa,0xc3,0x4e, - 0x08,0x2e,0xa1,0x66,0x28,0xd9,0x24,0xb2,0x76,0x5b,0xa2,0x49,0x6d,0x8b,0xd1,0x25, - 0x72,0xf8,0xf6,0x64,0x86,0x68,0x98,0x16,0xd4,0xa4,0x5c,0xcc,0x5d,0x65,0xb6,0x92, - 0x6c,0x70,0x48,0x50,0xfd,0xed,0xb9,0xda,0x5e,0x15,0x46,0x57,0xa7,0x8d,0x9d,0x84, - 0x90,0xd8,0xab,0x00,0x8c,0xbc,0xd3,0x0a,0xf7,0xe4,0x58,0x05,0xb8,0xb3,0x45,0x06, - 0xd0,0x2c,0x1e,0x8f,0xca,0x3f,0x0f,0x02,0xc1,0xaf,0xbd,0x03,0x01,0x13,0x8a,0x6b, - 0x3a,0x91,0x11,0x41,0x4f,0x67,0xdc,0xea,0x97,0xf2,0xcf,0xce,0xf0,0xb4,0xe6,0x73, - 0x96,0xac,0x74,0x22,0xe7,0xad,0x35,0x85,0xe2,0xf9,0x37,0xe8,0x1c,0x75,0xdf,0x6e, - 0x47,0xf1,0x1a,0x71,0x1d,0x29,0xc5,0x89,0x6f,0xb7,0x62,0x0e,0xaa,0x18,0xbe,0x1b, - 0xfc,0x56,0x3e,0x4b,0xc6,0xd2,0x79,0x20,0x9a,0xdb,0xc0,0xfe,0x78,0xcd,0x5a,0xf4, - 0x1f,0xdd,0xa8,0x33,0x88,0x07,0xc7,0x31,0xb1,0x12,0x10,0x59,0x27,0x80,0xec,0x5f, - 0x60,0x51,0x7f,0xa9,0x19,0xb5,0x4a,0x0d,0x2d,0xe5,0x7a,0x9f,0x93,0xc9,0x9c,0xef, - 0xa0,0xe0,0x3b,0x4d,0xae,0x2a,0xf5,0xb0,0xc8,0xeb,0xbb,0x3c,0x83,0x53,0x99,0x61, - 0x17,0x2b,0x04,0x7e,0xba,0x77,0xd6,0x26,0xe1,0x69,0x14,0x63,0x55,0x21,0x0c,0x7d -}; - -//#define xtime(x) ( (x << 1) ^ (((x >> 7) & 1) * BPOLY) ) -//#define xtime(x) ( (x << 1) ^ ((x & 0x80) ? BPOLY : 0) ) - -const uint8_t xtime[256] = -{ - 0x00,0x02,0x04,0x06,0x08,0x0a,0x0c,0x0e,0x10,0x12,0x14,0x16,0x18,0x1a,0x1c,0x1e, - 0x20,0x22,0x24,0x26,0x28,0x2a,0x2c,0x2e,0x30,0x32,0x34,0x36,0x38,0x3a,0x3c,0x3e, - 0x40,0x42,0x44,0x46,0x48,0x4a,0x4c,0x4e,0x50,0x52,0x54,0x56,0x58,0x5a,0x5c,0x5e, - 0x60,0x62,0x64,0x66,0x68,0x6a,0x6c,0x6e,0x70,0x72,0x74,0x76,0x78,0x7a,0x7c,0x7e, - 0x80,0x82,0x84,0x86,0x88,0x8a,0x8c,0x8e,0x90,0x92,0x94,0x96,0x98,0x9a,0x9c,0x9e, - 0xa0,0xa2,0xa4,0xa6,0xa8,0xaa,0xac,0xae,0xb0,0xb2,0xb4,0xb6,0xb8,0xba,0xbc,0xbe, - 0xc0,0xc2,0xc4,0xc6,0xc8,0xca,0xcc,0xce,0xd0,0xd2,0xd4,0xd6,0xd8,0xda,0xdc,0xde, - 0xe0,0xe2,0xe4,0xe6,0xe8,0xea,0xec,0xee,0xf0,0xf2,0xf4,0xf6,0xf8,0xfa,0xfc,0xfe, - 0x1b,0x19,0x1f,0x1d,0x13,0x11,0x17,0x15,0x0b,0x09,0x0f,0x0d,0x03,0x01,0x07,0x05, - 0x3b,0x39,0x3f,0x3d,0x33,0x31,0x37,0x35,0x2b,0x29,0x2f,0x2d,0x23,0x21,0x27,0x25, - 0x5b,0x59,0x5f,0x5d,0x53,0x51,0x57,0x55,0x4b,0x49,0x4f,0x4d,0x43,0x41,0x47,0x45, - 0x7b,0x79,0x7f,0x7d,0x73,0x71,0x77,0x75,0x6b,0x69,0x6f,0x6d,0x63,0x61,0x67,0x65, - 0x9b,0x99,0x9f,0x9d,0x93,0x91,0x97,0x95,0x8b,0x89,0x8f,0x8d,0x83,0x81,0x87,0x85, - 0xbb,0xb9,0xbf,0xbd,0xb3,0xb1,0xb7,0xb5,0xab,0xa9,0xaf,0xad,0xa3,0xa1,0xa7,0xa5, - 0xdb,0xd9,0xdf,0xdd,0xd3,0xd1,0xd7,0xd5,0xcb,0xc9,0xcf,0xcd,0xc3,0xc1,0xc7,0xc5, - 0xfb,0xf9,0xff,0xfd,0xf3,0xf1,0xf7,0xf5,0xeb,0xe9,0xef,0xed,0xe3,0xe1,0xe7,0xe5 -}; - -// *********************************************************************************** -/* -void createXTimeTable(void) -{ - uint8_t i = 0; - do { - xtime[i] = (i << 1) ^ ((i & 0x80) ? BPOLY : 0); - } while (++i != 0); -} -*/ -// *********************************************************************************** -/* -uint8_t powTable[256]; -uint8_t logTable[256]; - -uint8_t sbox[256]; -uint8_t isbox[256]; - -void createPowLogTables(void) -{ - uint8_t i = 0; - uint8_t t = 1; - - do { - powTable[i] = t; - logTable[t] = i; - i++; - t ^= (t << 1) ^ ((t & 0x80) ? BPOLY : 0); - } while (t != 1); - - powTable[255] = powTable[0]; -} - -void createSubstitueBoxTable(void) -{ - int i = 0; - do { - uint8_t temp; - - if (i > 0) - temp = powTable[255 - logTable[i]]; - else - temp = 0; - - uint8_t sb = temp ^ 0x63; - for (int j = 0; j < 4; j++) - { - temp = (temp << 1) | (temp >> 7); - sb ^= temp; - } - - sbox[i] = sb; - } while (++i != 0); -} - -void createInverseSubstitueBoxTable(void) -{ - uint8_t i = 0; - uint8_t j = 0; - do { - do { - if (sbox[j] == i) - { - isbox[i] = j; - j = 255; - } - } while (++j != 0); - } while (++i != 0); -} -*/ -// *********************************************************************************** - -void copy_block(void *d, void *s) -{ - if (d == s) return; - - register uint8_t *src = s; - register uint8_t *dest = d; - for (int i = N_BLOCK; i; --i) - *dest++ = *src++; -} - -void xor_block(void *d, void *s) -{ - register uint8_t *src = s; - register uint8_t *dest = d; - for (int i = N_BLOCK; i; --i) - *dest++ ^= *src++; -} - -void xor_word(uint8_t *d, uint8_t *s) -{ - *d++ ^= *s++; - *d++ ^= *s++; - *d++ ^= *s++; - *d++ ^= *s++; -} - -void xor_sub_word(uint8_t *d, uint8_t *s) -{ - *d++ ^= sbox[*s++]; - *d++ ^= sbox[*s++]; - *d++ ^= sbox[*s++]; - *d++ ^= sbox[*s++]; -} - -void xor_sub_rot_word(uint8_t *d, uint8_t *s, uint8_t rc) -{ - *d++ ^= sbox[s[1]] ^ rc; - *d++ ^= sbox[s[2]]; - *d++ ^= sbox[s[3]]; - *d++ ^= sbox[s[0]]; -} - -void mix_sub_column(uint8_t *a) -{ - uint8_t a0 = a[0]; - uint8_t a1 = a[1]; - uint8_t a2 = a[2]; - uint8_t a3 = a[3]; - uint8_t tmp = a0 ^ a1 ^ a2 ^ a3; - a[0] = a0 ^ xtime[a0 ^ a1] ^ tmp; - a[1] = a1 ^ xtime[a1 ^ a2] ^ tmp; - a[2] = a2 ^ xtime[a2 ^ a3] ^ tmp; - a[3] = a3 ^ xtime[a3 ^ a0] ^ tmp; -} - -void mix_sub_columns(void *a) -{ - mix_sub_column((uint8_t*)a + 0); - mix_sub_column((uint8_t*)a + 4); - mix_sub_column((uint8_t*)a + 8); - mix_sub_column((uint8_t*)a + 12); -} - -void inv_mix_sub_column(uint8_t *a) -{ - uint8_t tmp; - tmp = xtime[xtime[a[0] ^ a[2]]]; - a[0] ^= tmp; - a[2] ^= tmp; - tmp = xtime[xtime[a[1] ^ a[3]]]; - a[1] ^= tmp; - a[3] ^= tmp; -} - -void inv_mix_sub_columns(void *a) -{ - inv_mix_sub_column((uint8_t*)a + 0); - inv_mix_sub_column((uint8_t*)a + 4); - inv_mix_sub_column((uint8_t*)a + 8); - inv_mix_sub_column((uint8_t*)a + 12); - - mix_sub_columns(a); -} - -void shift_sub_rows(uint8_t *a) -{ - uint8_t tmp; - - a[0] = sbox[a[0]]; - a[4] = sbox[a[4]]; - a[8] = sbox[a[8]]; - a[12] = sbox[a[12]]; - - tmp = a[1]; - a[1] = sbox[a[5]]; - a[5] = sbox[a[9]]; - a[9] = sbox[a[13]]; - a[13] = sbox[tmp]; - - tmp = a[2]; - a[2] = sbox[a[10]]; - a[10] = sbox[tmp]; - tmp = a[6]; - a[6] = sbox[a[14]]; - a[14] = sbox[tmp]; - - tmp = a[15]; - a[15] = sbox[a[11]]; - a[11] = sbox[a[7]]; - a[7] = sbox[a[3]]; - a[3] = sbox[tmp]; -} - -void inv_shift_sub_rows(uint8_t *a) -{ - uint8_t tmp; - - a[0] = isbox[a[0]]; - a[4] = isbox[a[4]]; - a[8] = isbox[a[8]]; - a[12] = isbox[a[12]]; - - tmp = a[13]; - a[13] = isbox[a[9]]; - a[9] = isbox[a[5]]; - a[5] = isbox[a[1]]; - a[1] = isbox[tmp]; - - tmp = a[2]; - a[2] = isbox[a[10]]; - a[10] = isbox[tmp]; - tmp = a[6]; - a[6] = isbox[a[14]]; - a[14] = isbox[tmp]; - - tmp = a[3]; - a[3] = isbox[a[7]]; - a[7] = isbox[a[11]]; - a[11] = isbox[a[15]]; - a[15] = isbox[tmp]; -} - -// *********************************************************************************** - -// 'on the fly' encryption key update for 128 bit keys -void update_encrypt_key_128(uint8_t *k, uint8_t *rc) -{ - xor_sub_rot_word(k + 0, k + 12, *rc); - - *rc = (*rc << 1) ^ ((*rc & 0x80) ? BPOLY : 0); - - for (int i = 4; i < 16; i += 4) - xor_word(k + i + 0, k + i - 4); -} - -// Encrypt a single block of 16 bytes -void aes_encrypt_cbc_128(void *data, void *key, void *chain_block) -{ - uint8_t rc = 1; - - if (chain_block) - xor_block(data, chain_block); - - for (int round = 10; round; --round) - { - xor_block(data, key); // add_round_key - update_encrypt_key_128((uint8_t *)key, &rc); - shift_sub_rows(data); - if (round <= 1) continue; - mix_sub_columns(data); - } - xor_block(data, key); // add_round_key - - if (chain_block) - copy_block(chain_block, data); -} - -// 'on the fly' decryption key update for 128 bit keys -void update_decrypt_key_128(uint8_t *k, uint8_t *rc) -{ - for (int i = 12; i; i -= 4) - xor_word(k + i + 0, k + i - 4); - - *rc = (*rc >> 1) ^ ((*rc & 1) ? DPOLY : 0); - - xor_sub_rot_word(k + 0, k + 12, *rc); -} - -// Decrypt a single block of 16 bytes -void aes_decrypt_cbc_128(void *data, void *key, void *chain_block) -{ - uint8_t tmp_data[N_BLOCK]; - - uint8_t rc = 0x6c; - - copy_block(tmp_data, data); - - xor_block(data, key); // add_round_key - for (int round = 10; round; --round) - { - inv_shift_sub_rows(data); - update_decrypt_key_128(key, &rc); - xor_block(data, key); // add_round_key - if (round <= 1) continue; - inv_mix_sub_columns(data); - } - - if (chain_block) - { - xor_block(data, chain_block); - copy_block(chain_block, tmp_data); - } -} - -void aes_decrypt_key_128_create(void *enc_key, void *dec_key) -{ - copy_block(dec_key, enc_key); - - uint8_t rc = 1; - for (int i = 0; i < 10; i++) - update_encrypt_key_128(dec_key, &rc); -} - -// *********************************************************************************** - -// 'on the fly' encryption key update for 256 bit keys -void update_encrypt_key_256(uint8_t *k, uint8_t *rc) -{ - xor_sub_rot_word(k + 0, k + 28, *rc); - - *rc = (*rc << 1) ^ ((*rc & 0x80) ? BPOLY : 0); - - for (int i = 4; i < 16; i += 4) - xor_word(k + i + 0, k + i - 4); - - xor_sub_word(k + 16, k + 12); - - for (int i = 20; i < 32; i += 4) - xor_word(k + i + 0, k + i - 4); -} - -// Encrypt a single block of 16 bytes -void aes_encrypt_cbc_256(void *data, void *key, void *chain_block) -{ - uint8_t rc = 1; - - if (chain_block) - xor_block(data, chain_block); - - for (int round = 7; round; --round) - { -// printf("key - "); -// uint8_t *p = key; -// for (int i = 0; i < 32; i++) printf("%0.2X ", *p++); -// printf("\r\n"); - - xor_block(data, key); // add_round_key - shift_sub_rows(data); - mix_sub_columns(data); - xor_block(data, (uint8_t*)key + 16); // add_round_key - update_encrypt_key_256(key, &rc); - shift_sub_rows(data); - if (round <= 1) continue; - mix_sub_columns(data); - } - xor_block(data, key); // add_round_key - - if (chain_block) - copy_block(chain_block, data); -} - -// 'on the fly' decryption key update for 256 bit keys -void update_decrypt_key_256(uint8_t *k, uint8_t *rc) -{ - for (int i = 28; i >= 20; i -= 4) - xor_word(k + i + 0, k + i - 4); - - xor_sub_word(k + 16, k + 12); - - for (int i = 12; i; i -= 4) - xor_word(k + i + 0, k + i - 4); - - *rc = (*rc >> 1) ^ ((*rc & 1) ? DPOLY : 0); - - xor_sub_rot_word(k + 0, k + 28, *rc); -} - -// Decrypt a single block of 16 bytes -void aes_decrypt_cbc_256(void *data, void *key, void *chain_block) -{ - uint8_t tmp_data[N_BLOCK]; - - uint8_t rc = 0x80; - - copy_block(tmp_data, data); - - xor_block(data, key); // add_round_key - for (int round = 7; round; --round) - { - inv_shift_sub_rows(data); - update_decrypt_key_256(key, &rc); - xor_block(data, (uint8_t*)key + 16); // add_round_key - inv_mix_sub_columns(data); - inv_shift_sub_rows(data); - xor_block(data, key); // add_round_key - if (round <= 1) continue; - inv_mix_sub_columns(data); - } - - if (chain_block) - { - xor_block(data, chain_block); - copy_block(chain_block, tmp_data); - } -} - -void aes_decrypt_key_256_create(void *enc_key, void *dec_key) -{ - if (dec_key != enc_key) - { - copy_block(dec_key, enc_key); - copy_block((uint8_t*)dec_key + 16, (uint8_t*)enc_key + 16); - } - - uint8_t rc = 1; - for (int i = 7; i; --i) - update_encrypt_key_256(dec_key, &rc); -} - -// *********************************************************************************** + +// http://gladman.plushost.co.uk/oldsite/AES/index.php + +#include + +#include "aes.h" + +#define BPOLY 0x1B +#define DPOLY 0x8D + +const uint8_t sbox[256] = +{ + 0x63,0x7c,0x77,0x7b,0xf2,0x6b,0x6f,0xc5,0x30,0x01,0x67,0x2b,0xfe,0xd7,0xab,0x76, + 0xca,0x82,0xc9,0x7d,0xfa,0x59,0x47,0xf0,0xad,0xd4,0xa2,0xaf,0x9c,0xa4,0x72,0xc0, + 0xb7,0xfd,0x93,0x26,0x36,0x3f,0xf7,0xcc,0x34,0xa5,0xe5,0xf1,0x71,0xd8,0x31,0x15, + 0x04,0xc7,0x23,0xc3,0x18,0x96,0x05,0x9a,0x07,0x12,0x80,0xe2,0xeb,0x27,0xb2,0x75, + 0x09,0x83,0x2c,0x1a,0x1b,0x6e,0x5a,0xa0,0x52,0x3b,0xd6,0xb3,0x29,0xe3,0x2f,0x84, + 0x53,0xd1,0x00,0xed,0x20,0xfc,0xb1,0x5b,0x6a,0xcb,0xbe,0x39,0x4a,0x4c,0x58,0xcf, + 0xd0,0xef,0xaa,0xfb,0x43,0x4d,0x33,0x85,0x45,0xf9,0x02,0x7f,0x50,0x3c,0x9f,0xa8, + 0x51,0xa3,0x40,0x8f,0x92,0x9d,0x38,0xf5,0xbc,0xb6,0xda,0x21,0x10,0xff,0xf3,0xd2, + 0xcd,0x0c,0x13,0xec,0x5f,0x97,0x44,0x17,0xc4,0xa7,0x7e,0x3d,0x64,0x5d,0x19,0x73, + 0x60,0x81,0x4f,0xdc,0x22,0x2a,0x90,0x88,0x46,0xee,0xb8,0x14,0xde,0x5e,0x0b,0xdb, + 0xe0,0x32,0x3a,0x0a,0x49,0x06,0x24,0x5c,0xc2,0xd3,0xac,0x62,0x91,0x95,0xe4,0x79, + 0xe7,0xc8,0x37,0x6d,0x8d,0xd5,0x4e,0xa9,0x6c,0x56,0xf4,0xea,0x65,0x7a,0xae,0x08, + 0xba,0x78,0x25,0x2e,0x1c,0xa6,0xb4,0xc6,0xe8,0xdd,0x74,0x1f,0x4b,0xbd,0x8b,0x8a, + 0x70,0x3e,0xb5,0x66,0x48,0x03,0xf6,0x0e,0x61,0x35,0x57,0xb9,0x86,0xc1,0x1d,0x9e, + 0xe1,0xf8,0x98,0x11,0x69,0xd9,0x8e,0x94,0x9b,0x1e,0x87,0xe9,0xce,0x55,0x28,0xdf, + 0x8c,0xa1,0x89,0x0d,0xbf,0xe6,0x42,0x68,0x41,0x99,0x2d,0x0f,0xb0,0x54,0xbb,0x16 +}; + +const uint8_t isbox[256] = +{ + 0x52,0x09,0x6a,0xd5,0x30,0x36,0xa5,0x38,0xbf,0x40,0xa3,0x9e,0x81,0xf3,0xd7,0xfb, + 0x7c,0xe3,0x39,0x82,0x9b,0x2f,0xff,0x87,0x34,0x8e,0x43,0x44,0xc4,0xde,0xe9,0xcb, + 0x54,0x7b,0x94,0x32,0xa6,0xc2,0x23,0x3d,0xee,0x4c,0x95,0x0b,0x42,0xfa,0xc3,0x4e, + 0x08,0x2e,0xa1,0x66,0x28,0xd9,0x24,0xb2,0x76,0x5b,0xa2,0x49,0x6d,0x8b,0xd1,0x25, + 0x72,0xf8,0xf6,0x64,0x86,0x68,0x98,0x16,0xd4,0xa4,0x5c,0xcc,0x5d,0x65,0xb6,0x92, + 0x6c,0x70,0x48,0x50,0xfd,0xed,0xb9,0xda,0x5e,0x15,0x46,0x57,0xa7,0x8d,0x9d,0x84, + 0x90,0xd8,0xab,0x00,0x8c,0xbc,0xd3,0x0a,0xf7,0xe4,0x58,0x05,0xb8,0xb3,0x45,0x06, + 0xd0,0x2c,0x1e,0x8f,0xca,0x3f,0x0f,0x02,0xc1,0xaf,0xbd,0x03,0x01,0x13,0x8a,0x6b, + 0x3a,0x91,0x11,0x41,0x4f,0x67,0xdc,0xea,0x97,0xf2,0xcf,0xce,0xf0,0xb4,0xe6,0x73, + 0x96,0xac,0x74,0x22,0xe7,0xad,0x35,0x85,0xe2,0xf9,0x37,0xe8,0x1c,0x75,0xdf,0x6e, + 0x47,0xf1,0x1a,0x71,0x1d,0x29,0xc5,0x89,0x6f,0xb7,0x62,0x0e,0xaa,0x18,0xbe,0x1b, + 0xfc,0x56,0x3e,0x4b,0xc6,0xd2,0x79,0x20,0x9a,0xdb,0xc0,0xfe,0x78,0xcd,0x5a,0xf4, + 0x1f,0xdd,0xa8,0x33,0x88,0x07,0xc7,0x31,0xb1,0x12,0x10,0x59,0x27,0x80,0xec,0x5f, + 0x60,0x51,0x7f,0xa9,0x19,0xb5,0x4a,0x0d,0x2d,0xe5,0x7a,0x9f,0x93,0xc9,0x9c,0xef, + 0xa0,0xe0,0x3b,0x4d,0xae,0x2a,0xf5,0xb0,0xc8,0xeb,0xbb,0x3c,0x83,0x53,0x99,0x61, + 0x17,0x2b,0x04,0x7e,0xba,0x77,0xd6,0x26,0xe1,0x69,0x14,0x63,0x55,0x21,0x0c,0x7d +}; + +//#define xtime(x) ( (x << 1) ^ (((x >> 7) & 1) * BPOLY) ) +//#define xtime(x) ( (x << 1) ^ ((x & 0x80) ? BPOLY : 0) ) + +const uint8_t xtime[256] = +{ + 0x00,0x02,0x04,0x06,0x08,0x0a,0x0c,0x0e,0x10,0x12,0x14,0x16,0x18,0x1a,0x1c,0x1e, + 0x20,0x22,0x24,0x26,0x28,0x2a,0x2c,0x2e,0x30,0x32,0x34,0x36,0x38,0x3a,0x3c,0x3e, + 0x40,0x42,0x44,0x46,0x48,0x4a,0x4c,0x4e,0x50,0x52,0x54,0x56,0x58,0x5a,0x5c,0x5e, + 0x60,0x62,0x64,0x66,0x68,0x6a,0x6c,0x6e,0x70,0x72,0x74,0x76,0x78,0x7a,0x7c,0x7e, + 0x80,0x82,0x84,0x86,0x88,0x8a,0x8c,0x8e,0x90,0x92,0x94,0x96,0x98,0x9a,0x9c,0x9e, + 0xa0,0xa2,0xa4,0xa6,0xa8,0xaa,0xac,0xae,0xb0,0xb2,0xb4,0xb6,0xb8,0xba,0xbc,0xbe, + 0xc0,0xc2,0xc4,0xc6,0xc8,0xca,0xcc,0xce,0xd0,0xd2,0xd4,0xd6,0xd8,0xda,0xdc,0xde, + 0xe0,0xe2,0xe4,0xe6,0xe8,0xea,0xec,0xee,0xf0,0xf2,0xf4,0xf6,0xf8,0xfa,0xfc,0xfe, + 0x1b,0x19,0x1f,0x1d,0x13,0x11,0x17,0x15,0x0b,0x09,0x0f,0x0d,0x03,0x01,0x07,0x05, + 0x3b,0x39,0x3f,0x3d,0x33,0x31,0x37,0x35,0x2b,0x29,0x2f,0x2d,0x23,0x21,0x27,0x25, + 0x5b,0x59,0x5f,0x5d,0x53,0x51,0x57,0x55,0x4b,0x49,0x4f,0x4d,0x43,0x41,0x47,0x45, + 0x7b,0x79,0x7f,0x7d,0x73,0x71,0x77,0x75,0x6b,0x69,0x6f,0x6d,0x63,0x61,0x67,0x65, + 0x9b,0x99,0x9f,0x9d,0x93,0x91,0x97,0x95,0x8b,0x89,0x8f,0x8d,0x83,0x81,0x87,0x85, + 0xbb,0xb9,0xbf,0xbd,0xb3,0xb1,0xb7,0xb5,0xab,0xa9,0xaf,0xad,0xa3,0xa1,0xa7,0xa5, + 0xdb,0xd9,0xdf,0xdd,0xd3,0xd1,0xd7,0xd5,0xcb,0xc9,0xcf,0xcd,0xc3,0xc1,0xc7,0xc5, + 0xfb,0xf9,0xff,0xfd,0xf3,0xf1,0xf7,0xf5,0xeb,0xe9,0xef,0xed,0xe3,0xe1,0xe7,0xe5 +}; + +// *********************************************************************************** +/* +void createXTimeTable(void) +{ + uint8_t i = 0; + do { + xtime[i] = (i << 1) ^ ((i & 0x80) ? BPOLY : 0); + } while (++i != 0); +} +*/ +// *********************************************************************************** +/* +uint8_t powTable[256]; +uint8_t logTable[256]; + +uint8_t sbox[256]; +uint8_t isbox[256]; + +void createPowLogTables(void) +{ + uint8_t i = 0; + uint8_t t = 1; + + do { + powTable[i] = t; + logTable[t] = i; + i++; + t ^= (t << 1) ^ ((t & 0x80) ? BPOLY : 0); + } while (t != 1); + + powTable[255] = powTable[0]; +} + +void createSubstitueBoxTable(void) +{ + int i = 0; + do { + uint8_t temp; + + if (i > 0) + temp = powTable[255 - logTable[i]]; + else + temp = 0; + + uint8_t sb = temp ^ 0x63; + for (int j = 0; j < 4; j++) + { + temp = (temp << 1) | (temp >> 7); + sb ^= temp; + } + + sbox[i] = sb; + } while (++i != 0); +} + +void createInverseSubstitueBoxTable(void) +{ + uint8_t i = 0; + uint8_t j = 0; + do { + do { + if (sbox[j] == i) + { + isbox[i] = j; + j = 255; + } + } while (++j != 0); + } while (++i != 0); +} +*/ +// *********************************************************************************** + +void copy_block(void *d, void *s) +{ + if (d == s) return; + + register uint8_t *src = s; + register uint8_t *dest = d; + for (int i = N_BLOCK; i; --i) + *dest++ = *src++; +} + +void xor_block(void *d, void *s) +{ + register uint8_t *src = s; + register uint8_t *dest = d; + for (int i = N_BLOCK; i; --i) + *dest++ ^= *src++; +} + +void xor_word(uint8_t *d, uint8_t *s) +{ + *d++ ^= *s++; + *d++ ^= *s++; + *d++ ^= *s++; + *d++ ^= *s++; +} + +void xor_sub_word(uint8_t *d, uint8_t *s) +{ + *d++ ^= sbox[*s++]; + *d++ ^= sbox[*s++]; + *d++ ^= sbox[*s++]; + *d++ ^= sbox[*s++]; +} + +void xor_sub_rot_word(uint8_t *d, uint8_t *s, uint8_t rc) +{ + *d++ ^= sbox[s[1]] ^ rc; + *d++ ^= sbox[s[2]]; + *d++ ^= sbox[s[3]]; + *d++ ^= sbox[s[0]]; +} + +void mix_sub_column(uint8_t *a) +{ + uint8_t a0 = a[0]; + uint8_t a1 = a[1]; + uint8_t a2 = a[2]; + uint8_t a3 = a[3]; + uint8_t tmp = a0 ^ a1 ^ a2 ^ a3; + a[0] = a0 ^ xtime[a0 ^ a1] ^ tmp; + a[1] = a1 ^ xtime[a1 ^ a2] ^ tmp; + a[2] = a2 ^ xtime[a2 ^ a3] ^ tmp; + a[3] = a3 ^ xtime[a3 ^ a0] ^ tmp; +} + +void mix_sub_columns(void *a) +{ + mix_sub_column((uint8_t*)a + 0); + mix_sub_column((uint8_t*)a + 4); + mix_sub_column((uint8_t*)a + 8); + mix_sub_column((uint8_t*)a + 12); +} + +void inv_mix_sub_column(uint8_t *a) +{ + uint8_t tmp; + tmp = xtime[xtime[a[0] ^ a[2]]]; + a[0] ^= tmp; + a[2] ^= tmp; + tmp = xtime[xtime[a[1] ^ a[3]]]; + a[1] ^= tmp; + a[3] ^= tmp; +} + +void inv_mix_sub_columns(void *a) +{ + inv_mix_sub_column((uint8_t*)a + 0); + inv_mix_sub_column((uint8_t*)a + 4); + inv_mix_sub_column((uint8_t*)a + 8); + inv_mix_sub_column((uint8_t*)a + 12); + + mix_sub_columns(a); +} + +void shift_sub_rows(uint8_t *a) +{ + uint8_t tmp; + + a[0] = sbox[a[0]]; + a[4] = sbox[a[4]]; + a[8] = sbox[a[8]]; + a[12] = sbox[a[12]]; + + tmp = a[1]; + a[1] = sbox[a[5]]; + a[5] = sbox[a[9]]; + a[9] = sbox[a[13]]; + a[13] = sbox[tmp]; + + tmp = a[2]; + a[2] = sbox[a[10]]; + a[10] = sbox[tmp]; + tmp = a[6]; + a[6] = sbox[a[14]]; + a[14] = sbox[tmp]; + + tmp = a[15]; + a[15] = sbox[a[11]]; + a[11] = sbox[a[7]]; + a[7] = sbox[a[3]]; + a[3] = sbox[tmp]; +} + +void inv_shift_sub_rows(uint8_t *a) +{ + uint8_t tmp; + + a[0] = isbox[a[0]]; + a[4] = isbox[a[4]]; + a[8] = isbox[a[8]]; + a[12] = isbox[a[12]]; + + tmp = a[13]; + a[13] = isbox[a[9]]; + a[9] = isbox[a[5]]; + a[5] = isbox[a[1]]; + a[1] = isbox[tmp]; + + tmp = a[2]; + a[2] = isbox[a[10]]; + a[10] = isbox[tmp]; + tmp = a[6]; + a[6] = isbox[a[14]]; + a[14] = isbox[tmp]; + + tmp = a[3]; + a[3] = isbox[a[7]]; + a[7] = isbox[a[11]]; + a[11] = isbox[a[15]]; + a[15] = isbox[tmp]; +} + +// *********************************************************************************** + +// 'on the fly' encryption key update for 128 bit keys +void update_encrypt_key_128(uint8_t *k, uint8_t *rc) +{ + xor_sub_rot_word(k + 0, k + 12, *rc); + + *rc = (*rc << 1) ^ ((*rc & 0x80) ? BPOLY : 0); + + for (int i = 4; i < 16; i += 4) + xor_word(k + i + 0, k + i - 4); +} + +// Encrypt a single block of 16 bytes +void aes_encrypt_cbc_128(void *data, void *key, void *chain_block) +{ + uint8_t rc = 1; + + if (chain_block) + xor_block(data, chain_block); + + for (int round = 10; round; --round) + { + xor_block(data, key); // add_round_key + update_encrypt_key_128((uint8_t *)key, &rc); + shift_sub_rows(data); + if (round <= 1) continue; + mix_sub_columns(data); + } + xor_block(data, key); // add_round_key + + if (chain_block) + copy_block(chain_block, data); +} + +// 'on the fly' decryption key update for 128 bit keys +void update_decrypt_key_128(uint8_t *k, uint8_t *rc) +{ + for (int i = 12; i; i -= 4) + xor_word(k + i + 0, k + i - 4); + + *rc = (*rc >> 1) ^ ((*rc & 1) ? DPOLY : 0); + + xor_sub_rot_word(k + 0, k + 12, *rc); +} + +// Decrypt a single block of 16 bytes +void aes_decrypt_cbc_128(void *data, void *key, void *chain_block) +{ + uint8_t tmp_data[N_BLOCK]; + + uint8_t rc = 0x6c; + + copy_block(tmp_data, data); + + xor_block(data, key); // add_round_key + for (int round = 10; round; --round) + { + inv_shift_sub_rows(data); + update_decrypt_key_128(key, &rc); + xor_block(data, key); // add_round_key + if (round <= 1) continue; + inv_mix_sub_columns(data); + } + + if (chain_block) + { + xor_block(data, chain_block); + copy_block(chain_block, tmp_data); + } +} + +void aes_decrypt_key_128_create(void *enc_key, void *dec_key) +{ + copy_block(dec_key, enc_key); + + uint8_t rc = 1; + for (int i = 0; i < 10; i++) + update_encrypt_key_128(dec_key, &rc); +} + +// *********************************************************************************** + +// 'on the fly' encryption key update for 256 bit keys +void update_encrypt_key_256(uint8_t *k, uint8_t *rc) +{ + xor_sub_rot_word(k + 0, k + 28, *rc); + + *rc = (*rc << 1) ^ ((*rc & 0x80) ? BPOLY : 0); + + for (int i = 4; i < 16; i += 4) + xor_word(k + i + 0, k + i - 4); + + xor_sub_word(k + 16, k + 12); + + for (int i = 20; i < 32; i += 4) + xor_word(k + i + 0, k + i - 4); +} + +// Encrypt a single block of 16 bytes +void aes_encrypt_cbc_256(void *data, void *key, void *chain_block) +{ + uint8_t rc = 1; + + if (chain_block) + xor_block(data, chain_block); + + for (int round = 7; round; --round) + { +// printf("key - "); +// uint8_t *p = key; +// for (int i = 0; i < 32; i++) printf("%0.2X ", *p++); +// printf("\r\n"); + + xor_block(data, key); // add_round_key + shift_sub_rows(data); + mix_sub_columns(data); + xor_block(data, (uint8_t*)key + 16); // add_round_key + update_encrypt_key_256(key, &rc); + shift_sub_rows(data); + if (round <= 1) continue; + mix_sub_columns(data); + } + xor_block(data, key); // add_round_key + + if (chain_block) + copy_block(chain_block, data); +} + +// 'on the fly' decryption key update for 256 bit keys +void update_decrypt_key_256(uint8_t *k, uint8_t *rc) +{ + for (int i = 28; i >= 20; i -= 4) + xor_word(k + i + 0, k + i - 4); + + xor_sub_word(k + 16, k + 12); + + for (int i = 12; i; i -= 4) + xor_word(k + i + 0, k + i - 4); + + *rc = (*rc >> 1) ^ ((*rc & 1) ? DPOLY : 0); + + xor_sub_rot_word(k + 0, k + 28, *rc); +} + +// Decrypt a single block of 16 bytes +void aes_decrypt_cbc_256(void *data, void *key, void *chain_block) +{ + uint8_t tmp_data[N_BLOCK]; + + uint8_t rc = 0x80; + + copy_block(tmp_data, data); + + xor_block(data, key); // add_round_key + for (int round = 7; round; --round) + { + inv_shift_sub_rows(data); + update_decrypt_key_256(key, &rc); + xor_block(data, (uint8_t*)key + 16); // add_round_key + inv_mix_sub_columns(data); + inv_shift_sub_rows(data); + xor_block(data, key); // add_round_key + if (round <= 1) continue; + inv_mix_sub_columns(data); + } + + if (chain_block) + { + xor_block(data, chain_block); + copy_block(chain_block, tmp_data); + } +} + +void aes_decrypt_key_256_create(void *enc_key, void *dec_key) +{ + if (dec_key != enc_key) + { + copy_block(dec_key, enc_key); + copy_block((uint8_t*)dec_key + 16, (uint8_t*)enc_key + 16); + } + + uint8_t rc = 1; + for (int i = 7; i; --i) + update_encrypt_key_256(dec_key, &rc); +} + +// *********************************************************************************** diff --git a/flight/Libraries/inc/aes.h b/flight/Libraries/inc/aes.h index 725bc4414..44e12ba58 100644 --- a/flight/Libraries/inc/aes.h +++ b/flight/Libraries/inc/aes.h @@ -1,17 +1,17 @@ - -#ifndef _AES_H_ -#define _AES_H_ - -#define N_ROW 4 -#define N_COL 4 -#define N_BLOCK (N_ROW * N_COL) - -void aes_encrypt_cbc_128(void *data, void *key, void *chain_block); -void aes_decrypt_cbc_128(void *data, void *key, void *chain_block); -void aes_decrypt_key_128_create(void *enc_key, void *dec_key); - -void aes_encrypt_cbc_256(void *data, void *key, void *chain_block); -void aes_decrypt_cbc_256(void *data, void *key, void *chain_block); -void aes_decrypt_key_256_create(void *enc_key, void *dec_key); - -#endif + +#ifndef _AES_H_ +#define _AES_H_ + +#define N_ROW 4 +#define N_COL 4 +#define N_BLOCK (N_ROW * N_COL) + +void aes_encrypt_cbc_128(void *data, void *key, void *chain_block); +void aes_decrypt_cbc_128(void *data, void *key, void *chain_block); +void aes_decrypt_key_128_create(void *enc_key, void *dec_key); + +void aes_encrypt_cbc_256(void *data, void *key, void *chain_block); +void aes_decrypt_cbc_256(void *data, void *key, void *chain_block); +void aes_decrypt_key_256_create(void *enc_key, void *dec_key); + +#endif diff --git a/flight/Libraries/inc/packet_handler.h b/flight/Libraries/inc/packet_handler.h index 8bdfb4eb0..a734e2a48 100644 --- a/flight/Libraries/inc/packet_handler.h +++ b/flight/Libraries/inc/packet_handler.h @@ -1,109 +1,109 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * - * @file packet_handler.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @brief A packet handler for handeling radio packet transmission. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef __PACKET_HANDLER_H__ -#define __PACKET_HANDLER_H__ - -#include -#include -#include -#include - -// Public defines / macros -#define PHPacketSize(p) ((uint8_t*)(p->data) + p->header.data_size - (uint8_t*)p) -#define PHPacketSizeECC(p) ((uint8_t*)(p->data) + p->header.data_size + RS_ECC_NPARITY - (uint8_t*)p) - -// Public types -typedef enum { - PACKET_TYPE_NONE = 0, - PACKET_TYPE_STATUS, // broadcasts status of this modem - PACKET_TYPE_CON_REQUEST, // request a connection to another modem - PACKET_TYPE_DATA, // data packet (packet contains user data) - PACKET_TYPE_DUPLICATE_DATA, // a duplicate data packet - PACKET_TYPE_PPM, // PPM relay values - PACKET_TYPE_ACK, // Acknowlege the receipt of a packet - PACKET_TYPE_ACK_RTS, // Acknowlege the receipt of a packet and indicate that the receiving side has data to send (ready to send) - PACKET_TYPE_NACK, // Acknowlege the receipt of an uncorrectable packet -} PHPacketType; - -typedef struct { - uint32_t destination_id; - uint32_t source_id; - uint8_t type; - uint8_t data_size; - uint16_t seq_num; -} PHPacketHeader; - -#define PH_MAX_DATA (PIOS_PH_MAX_PACKET - sizeof(PHPacketHeader) - RS_ECC_NPARITY) -#define PH_PACKET_SIZE(p) ((p)->data + (p)->header.data_size - (uint8_t*)(p) + RS_ECC_NPARITY) -typedef struct { - PHPacketHeader header; - uint8_t data[PH_MAX_DATA + RS_ECC_NPARITY]; -} PHPacket, *PHPacketHandle; - -#define PH_ACK_NACK_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) -typedef struct { - PHPacketHeader header; - uint8_t ecc[RS_ECC_NPARITY]; -} PHAckNackPacket, *PHAckNackPacketHandle; - -#define PH_PPM_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) -typedef struct { - PHPacketHeader header; - uint16_t channels[PIOS_RFM22B_RCVR_MAX_CHANNELS]; - uint8_t ecc[RS_ECC_NPARITY]; -} PHPpmPacket, *PHPpmPacketHandle; - -#define PH_STATUS_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) -typedef struct { - PHPacketHeader header; - uint8_t link_quality; - int8_t received_rssi; - uint8_t ecc[RS_ECC_NPARITY]; -} PHStatusPacket, *PHStatusPacketHandle; - -#define PH_CONNECTION_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) -typedef struct { - PHPacketHeader header; - uint8_t datarate; - uint32_t frequency_hz; - uint32_t min_frequency; - uint32_t max_frequency; - uint8_t max_tx_power; - OPLinkSettingsOutputConnectionOptions port; - OPLinkSettingsComSpeedOptions com_speed; - uint8_t ecc[RS_ECC_NPARITY]; -} PHConnectionPacket, *PHConnectionPacketHandle; - -#endif // __PACKET_HANDLER_H__ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * + * @file packet_handler.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief A packet handler for handeling radio packet transmission. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef __PACKET_HANDLER_H__ +#define __PACKET_HANDLER_H__ + +#include +#include +#include +#include + +// Public defines / macros +#define PHPacketSize(p) ((uint8_t*)(p->data) + p->header.data_size - (uint8_t*)p) +#define PHPacketSizeECC(p) ((uint8_t*)(p->data) + p->header.data_size + RS_ECC_NPARITY - (uint8_t*)p) + +// Public types +typedef enum { + PACKET_TYPE_NONE = 0, + PACKET_TYPE_STATUS, // broadcasts status of this modem + PACKET_TYPE_CON_REQUEST, // request a connection to another modem + PACKET_TYPE_DATA, // data packet (packet contains user data) + PACKET_TYPE_DUPLICATE_DATA, // a duplicate data packet + PACKET_TYPE_PPM, // PPM relay values + PACKET_TYPE_ACK, // Acknowlege the receipt of a packet + PACKET_TYPE_ACK_RTS, // Acknowlege the receipt of a packet and indicate that the receiving side has data to send (ready to send) + PACKET_TYPE_NACK, // Acknowlege the receipt of an uncorrectable packet +} PHPacketType; + +typedef struct { + uint32_t destination_id; + uint32_t source_id; + uint8_t type; + uint8_t data_size; + uint16_t seq_num; +} PHPacketHeader; + +#define PH_MAX_DATA (PIOS_PH_MAX_PACKET - sizeof(PHPacketHeader) - RS_ECC_NPARITY) +#define PH_PACKET_SIZE(p) ((p)->data + (p)->header.data_size - (uint8_t*)(p) + RS_ECC_NPARITY) +typedef struct { + PHPacketHeader header; + uint8_t data[PH_MAX_DATA + RS_ECC_NPARITY]; +} PHPacket, *PHPacketHandle; + +#define PH_ACK_NACK_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) +typedef struct { + PHPacketHeader header; + uint8_t ecc[RS_ECC_NPARITY]; +} PHAckNackPacket, *PHAckNackPacketHandle; + +#define PH_PPM_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) +typedef struct { + PHPacketHeader header; + uint16_t channels[PIOS_RFM22B_RCVR_MAX_CHANNELS]; + uint8_t ecc[RS_ECC_NPARITY]; +} PHPpmPacket, *PHPpmPacketHandle; + +#define PH_STATUS_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) +typedef struct { + PHPacketHeader header; + uint8_t link_quality; + int8_t received_rssi; + uint8_t ecc[RS_ECC_NPARITY]; +} PHStatusPacket, *PHStatusPacketHandle; + +#define PH_CONNECTION_DATA_SIZE(p) ((uint8_t*)((p)->ecc) - (uint8_t*)(((PHPacketHandle)(p))->data)) +typedef struct { + PHPacketHeader header; + uint8_t datarate; + uint32_t frequency_hz; + uint32_t min_frequency; + uint32_t max_frequency; + uint8_t max_tx_power; + OPLinkSettingsOutputConnectionOptions port; + OPLinkSettingsComSpeedOptions com_speed; + uint8_t ecc[RS_ECC_NPARITY]; +} PHConnectionPacket, *PHConnectionPacketHandle; + +#endif // __PACKET_HANDLER_H__ + +/** + * @} + * @} + */ diff --git a/flight/Libraries/inc/taskmonitor.h b/flight/Libraries/inc/taskmonitor.h index 6492cee06..73987f2b1 100644 --- a/flight/Libraries/inc/taskmonitor.h +++ b/flight/Libraries/inc/taskmonitor.h @@ -1,44 +1,44 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file taskmonitor.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the task monitoring library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef TASKMONITOR_H -#define TASKMONITOR_H - -#include "taskinfo.h" - -int32_t TaskMonitorInitialize(void); -int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle); -int32_t TaskMonitorRemove(TaskInfoRunningElem task); -bool TaskMonitorQueryRunning(TaskInfoRunningElem task); -void TaskMonitorUpdateAll(void); - -#endif // TASKMONITOR_H - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file taskmonitor.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the task monitoring library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef TASKMONITOR_H +#define TASKMONITOR_H + +#include "taskinfo.h" + +int32_t TaskMonitorInitialize(void); +int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle); +int32_t TaskMonitorRemove(TaskInfoRunningElem task); +bool TaskMonitorQueryRunning(TaskInfoRunningElem task); +void TaskMonitorUpdateAll(void); + +#endif // TASKMONITOR_H + +/** + * @} + * @} + */ diff --git a/flight/Libraries/printf2.c b/flight/Libraries/printf2.c index ce8af285a..775fb294e 100644 --- a/flight/Libraries/printf2.c +++ b/flight/Libraries/printf2.c @@ -1,633 +1,633 @@ -/******************************************************************************* - Copyright 2001, 2002 Georges Menie () - This program is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 2 of the License, or - (at your option) any later version. - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - You should have received a copy of the GNU Lesser General Public License - along with this program; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -/******************************************************************************* - putchar is the only external dependency for this file, - if you have a working putchar, just remove the following - define. If the function should be called something else, - replace outbyte(c) by your own function call. -*/ -//******************************************************************************* -// Updated by Daniel D Miller. Changes to the original Menie code are -// Copyright 2009-2012 Daniel D Miller -// All such changes are distributed under the same license as the original, -// as described above. -// 11/06/09 - adding floating-point support -// 03/19/10 - pad fractional portion of floating-point number with 0s -// 03/30/10 - document the \% bug -// 07/20/10 - Fix a round-off bug in floating-point conversions -// ( 0.99 with %.1f did not round to 1.0 ) -// 10/25/11 - Add support for %+ format (always show + on positive numbers) -// 01/19/12 - fix handling of %f with no decimal; it was defaulting to 0 -// decimal places, rather than printf's 6. -//******************************************************************************* -// BUGS -// If '%' is included in a format string, in the form \% with the intent -// of including the percent sign in the output string, this function will -// mis-handle the data entirely!! -// Essentially, it will just discard the character following the percent sign. -// This bug is not easy to fix in the existing code; -// for now, I'll just try to remember to use %% instead of \% ... -//******************************************************************************* - -//lint -esym(752, debug_output) -//lint -esym(766, stdio.h) - -// #define TEST_PRINTF 1 - -#include - -static uint use_leading_plus = 0 ; - -/* based on a example-code from Keil for CS G++ */ - -/* for caddr_t (typedef char * caddr_t;) */ -#include - -//* NEWLIB STUBS *// -#include -#include -#include -#include -#include - -/*============================================================================== - * Environment variables. - * A pointer to a list of environment variables and their values. For a minimal - * environment, this empty list is adequate: - */ -char *__env[1] = { 0 }; -char **environ = __env; - -/*============================================================================== - * Close a file. - */ -int _close(int file) -{ - return -1; -} - -/*============================================================================== - * Transfer control to a new process. - */ -int _execve(char *name, char **argv, char **env) -{ - errno = ENOMEM; - return -1; -} - -/*============================================================================== - * Exit a program without cleaning up files. - */ -void _exit( int code ) -{ - /* Should we force a system reset? */ - while( 1 ) - { - ; - } -} - -/*============================================================================== - * Create a new process. - */ -int _fork(void) -{ - errno = EAGAIN; - return -1; -} - -/*============================================================================== - * Status of an open file. - */ -int _fstat(int file, struct stat *st) -{ - st->st_mode = S_IFCHR; - return 0; -} - -/*============================================================================== - * Process-ID - */ -int _getpid(void) -{ - return 1; -} - -/*============================================================================== - * Query whether output stream is a terminal. - */ -int _isatty(int file) -{ - return 1; -} - -/*============================================================================== - * Send a signal. - */ -int _kill(int pid, int sig) -{ - errno = EINVAL; - return -1; -} - -/*============================================================================== - * Establish a new name for an existing file. - */ -int _link(char *old, char *new) -{ - errno = EMLINK; - return -1; -} - -/*============================================================================== - * Set position in a file. - */ -int _lseek(int file, int ptr, int dir) -{ - return 0; -} - -/*============================================================================== - * Open a file. - */ -int _open(const char *name, int flags, int mode) -{ - return -1; -} - -/*============================================================================== - * Read from a file. - */ -int _read(int file, char *ptr, int len) -{ - return 0; -} - -/*============================================================================== - * Write to a file. libc subroutines will use this system routine for output to - * all files, including stdout—so if you need to generate any output, for - * example to a serial port for debugging, you should make your minimal write - * capable of doing this. - */ -int _write_r( void * reent, int file, char * ptr, int len ) -{ - return 0; -} - -/*============================================================================== - * Increase program data space. As malloc and related functions depend on this, - * it is useful to have a working implementation. The following suffices for a - * standalone system; it exploits the symbol _end automatically defined by the - * GNU linker. - */ -caddr_t _sbrk(int incr) -{ - extern char _end; /* Defined by the linker */ - static char *heap_end; - char *prev_heap_end; - char * stack_ptr; - - if (heap_end == 0) - { - heap_end = &_end; - } - - prev_heap_end = heap_end; - asm volatile ("MRS %0, msp" : "=r" (stack_ptr) ); - if (heap_end + incr > stack_ptr) - { - _write_r ((void *)0, 1, "Heap and stack collision\n", 25); - _exit (1); - } - - heap_end += incr; - return (caddr_t) prev_heap_end; -} - -/*============================================================================== - * Status of a file (by name). - */ -int _stat(char *file, struct stat *st) -{ - st->st_mode = S_IFCHR; - return 0; -} - -/*============================================================================== - * Timing information for current process. - */ -int _times(struct tms *buf) -{ - return -1; -} - -/*============================================================================== - * Remove a file's directory entry. - */ -int _unlink(char *name) -{ - errno = ENOENT; - return -1; -} - -/*============================================================================== - * Wait for a child process. - */ -int _wait(int *status) -{ - errno = ECHILD; - return -1; -} -//* NEWLIB STUBS *// - - -//**************************************************************************** -static void printchar (char **str, int c) -{ - if (str) { - **str = c; - ++(*str); - } -#ifdef TEST_PRINTF - else { - extern int putchar (int c); - (void) putchar (c); - } -#endif -} - -//**************************************************************************** -static uint my_strlen(char *str) -{ - if (str == 0) - return 0; - uint slen = 0 ; - while (*str != 0) { - slen++ ; - str++ ; - } - return slen; -} - -//**************************************************************************** -// This version returns the length of the output string. -// It is more useful when implementing a walking-string function. -//**************************************************************************** -static const double round_nums[8] = { - 0.5, - 0.05, - 0.005, - 0.0005, - 0.00005, - 0.000005, - 0.0000005, - 0.00000005 -} ; - -static unsigned dbl2stri(char *outbfr, double dbl, unsigned dec_digits) -{ - static char local_bfr[128] ; - char *output = (outbfr == 0) ? local_bfr : outbfr ; - - //******************************************* - // extract negative info - //******************************************* - if (dbl < 0.0) { - *output++ = '-' ; - dbl *= -1.0 ; - } else { - if (use_leading_plus) { - *output++ = '+' ; - } - - } - - // handling rounding by adding .5LSB to the floating-point data - if (dec_digits < 8) { - dbl += round_nums[dec_digits] ; - } - - //************************************************************************** - // construct fractional multiplier for specified number of digits. - //************************************************************************** - uint mult = 1 ; - uint idx ; - for (idx=0; idx < dec_digits; idx++) - mult *= 10 ; - - // printf("mult=%u\n", mult) ; - uint wholeNum = (uint) dbl ; - uint decimalNum = (uint) ((dbl - wholeNum) * mult); - - //******************************************* - // convert integer portion - //******************************************* - char tbfr[40] ; - idx = 0 ; - while (wholeNum != 0) { - tbfr[idx++] = '0' + (wholeNum % 10) ; - wholeNum /= 10 ; - } - // printf("%.3f: whole=%s, dec=%d\n", dbl, tbfr, decimalNum) ; - if (idx == 0) { - *output++ = '0' ; - } else { - while (idx > 0) { - *output++ = tbfr[idx-1] ; //lint !e771 - idx-- ; - } - } - if (dec_digits > 0) { - *output++ = '.' ; - - //******************************************* - // convert fractional portion - //******************************************* - idx = 0 ; - while (decimalNum != 0) { - tbfr[idx++] = '0' + (decimalNum % 10) ; - decimalNum /= 10 ; - } - // pad the decimal portion with 0s as necessary; - // We wouldn't want to report 3.093 as 3.93, would we?? - while (idx < dec_digits) { - tbfr[idx++] = '0' ; - } - // printf("decimal=%s\n", tbfr) ; - if (idx == 0) { - *output++ = '0' ; - } else { - while (idx > 0) { - *output++ = tbfr[idx-1] ; - idx-- ; - } - } - } - *output = 0 ; - - // prepare output - output = (outbfr == 0) ? local_bfr : outbfr ; - return my_strlen(output) ; -} - -//**************************************************************************** -#define PAD_RIGHT 1 -#define PAD_ZERO 2 - -static int prints (char **out, const char *string, int width, int pad) -{ - register int pc = 0, padchar = ' '; - if (width > 0) { - int len = 0; - const char *ptr; - for (ptr = string; *ptr; ++ptr) - ++len; - if (len >= width) - width = 0; - else - width -= len; - if (pad & PAD_ZERO) - padchar = '0'; - } - if (!(pad & PAD_RIGHT)) { - for (; width > 0; --width) { - printchar (out, padchar); - ++pc; - } - } - for (; *string; ++string) { - printchar (out, *string); - ++pc; - } - for (; width > 0; --width) { - printchar (out, padchar); - ++pc; - } - return pc; -} - -//**************************************************************************** -/* the following should be enough for 32 bit int */ -#define PRINT_BUF_LEN 12 -static int printi (char **out, int i, int b, int sg, int width, int pad, int letbase) -{ - char print_buf[PRINT_BUF_LEN]; - char *s; - int t, neg = 0, pc = 0; - unsigned u = (unsigned) i; - if (i == 0) { - print_buf[0] = '0'; - print_buf[1] = '\0'; - return prints (out, print_buf, width, pad); - } - if (sg && b == 10 && i < 0) { - neg = 1; - u = (unsigned) -i; - } - // make sure print_buf is NULL-term - s = print_buf + PRINT_BUF_LEN - 1; - *s = '\0'; - - - while (u) { - t = u % b; //lint !e573 Warning 573: Signed-unsigned mix with divide - if (t >= 10) - t += letbase - '0' - 10; - *--s = t + '0'; - u /= b; //lint !e573 Warning 573: Signed-unsigned mix with divide - } - if (neg) { - if (width && (pad & PAD_ZERO)) { - printchar (out, '-'); - ++pc; - --width; - } - else { - *--s = '-'; - } - } else { - if (use_leading_plus) { - *--s = '+'; - } - } - return pc + prints (out, s, width, pad); -} - -//**************************************************************************** -static int print (char **out, int *varg) -{ - int post_decimal ; - int width, pad ; - unsigned dec_width = 6 ; - int pc = 0; - char *format = (char *) (*varg++); - char scr[2]; - use_leading_plus = 0 ; // start out with this clear - for (; *format != 0; ++format) { - if (*format == '%') { - dec_width = 6 ; - ++format; - width = pad = 0; - if (*format == '\0') - break; - if (*format == '%') - goto out_lbl; - if (*format == '-') { - ++format; - pad = PAD_RIGHT; - } - if (*format == '+') { - ++format; - use_leading_plus = 1 ; - } - while (*format == '0') { - ++format; - pad |= PAD_ZERO; - } - post_decimal = 0 ; - if (*format == '.' || - (*format >= '0' && *format <= '9')) { - - while (1) { - if (*format == '.') { - post_decimal = 1 ; - dec_width = 0 ; - format++ ; - } else if ((*format >= '0' && *format <= '9')) { - if (post_decimal) { - dec_width *= 10; - dec_width += *format - '0'; - } else { - width *= 10; - width += *format - '0'; - } - format++ ; - } else { - break; - } - } - } - if (*format == 'l') - ++format; - switch (*format) { - case 's': - { - // char *s = *((char **) varg++); //lint !e740 - char *s = (char *) *varg++ ; //lint !e740 !e826 convert to double pointer - pc += prints (out, s ? s : "(null)", width, pad); - use_leading_plus = 0 ; // reset this flag after printing one value - } - break; - case 'd': - pc += printi (out, *varg++, 10, 1, width, pad, 'a'); - use_leading_plus = 0 ; // reset this flag after printing one value - break; - case 'x': - pc += printi (out, *varg++, 16, 0, width, pad, 'a'); - use_leading_plus = 0 ; // reset this flag after printing one value - break; - case 'X': - pc += printi (out, *varg++, 16, 0, width, pad, 'A'); - use_leading_plus = 0 ; // reset this flag after printing one value - break; - case 'u': - pc += printi (out, *varg++, 10, 0, width, pad, 'a'); - use_leading_plus = 0 ; // reset this flag after printing one value - break; - case 'c': - /* char are converted to int then pushed on the stack */ - scr[0] = *varg++; - scr[1] = '\0'; - pc += prints (out, scr, width, pad); - use_leading_plus = 0 ; // reset this flag after printing one value - break; - - case 'f': - { - // http://wiki.debian.org/ArmEabiPort#Structpackingandalignment - // Stack alignment - // - // The ARM EABI requires 8-byte stack alignment at public function entry points, - // compared to the previous 4-byte alignment. -#ifdef USE_NEWLIB - char *cptr = (char *) varg ; //lint !e740 !e826 convert to double pointer - uint caddr = (uint) cptr ; - if ((caddr & 0xF) != 0) { - cptr += 4 ; - } - double *dblptr = (double *) cptr ; //lint !e740 !e826 convert to double pointer -#else - double *dblptr = (double *) varg ; //lint !e740 !e826 convert to double pointer -#endif - double dbl = *dblptr++ ; // increment double pointer - varg = (int *) dblptr ; //lint !e740 copy updated pointer back to base pointer - char bfr[81] ; - // unsigned slen = - dbl2stri(bfr, dbl, dec_width) ; - // stuff_talkf("[%s], width=%u, dec_width=%u\n", bfr, width, dec_width) ; - pc += prints (out, bfr, width, pad); - use_leading_plus = 0 ; // reset this flag after printing one value - } - break; - - default: - printchar (out, '%'); - printchar (out, *format); - use_leading_plus = 0 ; // reset this flag after printing one value - break; - } - } else - // if (*format == '\\') { - // - // } else - { -out_lbl: - printchar (out, *format); - ++pc; - } - } // for each char in format string - if (out) //lint !e850 - **out = '\0'; - return pc; -} - -//**************************************************************************** -int stringf (char *out, const char *format, ...) -{ - // create a pointer into the stack. - // Thematically this should be a void*, since the actual usage of the - // pointer will vary. However, int* works fine too. - // Either way, the called function will need to re-cast the pointer - // for any type which isn't sizeof(int) - int *varg = (int *) (char *) (&format); - return print (&out, varg); -} - -int printf(const char *format, ...) -{ - int *varg = (int *) (char *) (&format); - return print (0, varg); -} - -int sprintf(char *out, const char *format, ...) -{ - int *varg = (int *) (char *) (&format); - return print (&out, varg); -} - -/** - * @} - */ +/******************************************************************************* + Copyright 2001, 2002 Georges Menie () + This program is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 2 of the License, or + (at your option) any later version. + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + You should have received a copy of the GNU Lesser General Public License + along with this program; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +/******************************************************************************* + putchar is the only external dependency for this file, + if you have a working putchar, just remove the following + define. If the function should be called something else, + replace outbyte(c) by your own function call. +*/ +//******************************************************************************* +// Updated by Daniel D Miller. Changes to the original Menie code are +// Copyright 2009-2012 Daniel D Miller +// All such changes are distributed under the same license as the original, +// as described above. +// 11/06/09 - adding floating-point support +// 03/19/10 - pad fractional portion of floating-point number with 0s +// 03/30/10 - document the \% bug +// 07/20/10 - Fix a round-off bug in floating-point conversions +// ( 0.99 with %.1f did not round to 1.0 ) +// 10/25/11 - Add support for %+ format (always show + on positive numbers) +// 01/19/12 - fix handling of %f with no decimal; it was defaulting to 0 +// decimal places, rather than printf's 6. +//******************************************************************************* +// BUGS +// If '%' is included in a format string, in the form \% with the intent +// of including the percent sign in the output string, this function will +// mis-handle the data entirely!! +// Essentially, it will just discard the character following the percent sign. +// This bug is not easy to fix in the existing code; +// for now, I'll just try to remember to use %% instead of \% ... +//******************************************************************************* + +//lint -esym(752, debug_output) +//lint -esym(766, stdio.h) + +// #define TEST_PRINTF 1 + +#include + +static uint use_leading_plus = 0 ; + +/* based on a example-code from Keil for CS G++ */ + +/* for caddr_t (typedef char * caddr_t;) */ +#include + +//* NEWLIB STUBS *// +#include +#include +#include +#include +#include + +/*============================================================================== + * Environment variables. + * A pointer to a list of environment variables and their values. For a minimal + * environment, this empty list is adequate: + */ +char *__env[1] = { 0 }; +char **environ = __env; + +/*============================================================================== + * Close a file. + */ +int _close(int file) +{ + return -1; +} + +/*============================================================================== + * Transfer control to a new process. + */ +int _execve(char *name, char **argv, char **env) +{ + errno = ENOMEM; + return -1; +} + +/*============================================================================== + * Exit a program without cleaning up files. + */ +void _exit( int code ) +{ + /* Should we force a system reset? */ + while( 1 ) + { + ; + } +} + +/*============================================================================== + * Create a new process. + */ +int _fork(void) +{ + errno = EAGAIN; + return -1; +} + +/*============================================================================== + * Status of an open file. + */ +int _fstat(int file, struct stat *st) +{ + st->st_mode = S_IFCHR; + return 0; +} + +/*============================================================================== + * Process-ID + */ +int _getpid(void) +{ + return 1; +} + +/*============================================================================== + * Query whether output stream is a terminal. + */ +int _isatty(int file) +{ + return 1; +} + +/*============================================================================== + * Send a signal. + */ +int _kill(int pid, int sig) +{ + errno = EINVAL; + return -1; +} + +/*============================================================================== + * Establish a new name for an existing file. + */ +int _link(char *old, char *new) +{ + errno = EMLINK; + return -1; +} + +/*============================================================================== + * Set position in a file. + */ +int _lseek(int file, int ptr, int dir) +{ + return 0; +} + +/*============================================================================== + * Open a file. + */ +int _open(const char *name, int flags, int mode) +{ + return -1; +} + +/*============================================================================== + * Read from a file. + */ +int _read(int file, char *ptr, int len) +{ + return 0; +} + +/*============================================================================== + * Write to a file. libc subroutines will use this system routine for output to + * all files, including stdout—so if you need to generate any output, for + * example to a serial port for debugging, you should make your minimal write + * capable of doing this. + */ +int _write_r( void * reent, int file, char * ptr, int len ) +{ + return 0; +} + +/*============================================================================== + * Increase program data space. As malloc and related functions depend on this, + * it is useful to have a working implementation. The following suffices for a + * standalone system; it exploits the symbol _end automatically defined by the + * GNU linker. + */ +caddr_t _sbrk(int incr) +{ + extern char _end; /* Defined by the linker */ + static char *heap_end; + char *prev_heap_end; + char * stack_ptr; + + if (heap_end == 0) + { + heap_end = &_end; + } + + prev_heap_end = heap_end; + asm volatile ("MRS %0, msp" : "=r" (stack_ptr) ); + if (heap_end + incr > stack_ptr) + { + _write_r ((void *)0, 1, "Heap and stack collision\n", 25); + _exit (1); + } + + heap_end += incr; + return (caddr_t) prev_heap_end; +} + +/*============================================================================== + * Status of a file (by name). + */ +int _stat(char *file, struct stat *st) +{ + st->st_mode = S_IFCHR; + return 0; +} + +/*============================================================================== + * Timing information for current process. + */ +int _times(struct tms *buf) +{ + return -1; +} + +/*============================================================================== + * Remove a file's directory entry. + */ +int _unlink(char *name) +{ + errno = ENOENT; + return -1; +} + +/*============================================================================== + * Wait for a child process. + */ +int _wait(int *status) +{ + errno = ECHILD; + return -1; +} +//* NEWLIB STUBS *// + + +//**************************************************************************** +static void printchar (char **str, int c) +{ + if (str) { + **str = c; + ++(*str); + } +#ifdef TEST_PRINTF + else { + extern int putchar (int c); + (void) putchar (c); + } +#endif +} + +//**************************************************************************** +static uint my_strlen(char *str) +{ + if (str == 0) + return 0; + uint slen = 0 ; + while (*str != 0) { + slen++ ; + str++ ; + } + return slen; +} + +//**************************************************************************** +// This version returns the length of the output string. +// It is more useful when implementing a walking-string function. +//**************************************************************************** +static const double round_nums[8] = { + 0.5, + 0.05, + 0.005, + 0.0005, + 0.00005, + 0.000005, + 0.0000005, + 0.00000005 +} ; + +static unsigned dbl2stri(char *outbfr, double dbl, unsigned dec_digits) +{ + static char local_bfr[128] ; + char *output = (outbfr == 0) ? local_bfr : outbfr ; + + //******************************************* + // extract negative info + //******************************************* + if (dbl < 0.0) { + *output++ = '-' ; + dbl *= -1.0 ; + } else { + if (use_leading_plus) { + *output++ = '+' ; + } + + } + + // handling rounding by adding .5LSB to the floating-point data + if (dec_digits < 8) { + dbl += round_nums[dec_digits] ; + } + + //************************************************************************** + // construct fractional multiplier for specified number of digits. + //************************************************************************** + uint mult = 1 ; + uint idx ; + for (idx=0; idx < dec_digits; idx++) + mult *= 10 ; + + // printf("mult=%u\n", mult) ; + uint wholeNum = (uint) dbl ; + uint decimalNum = (uint) ((dbl - wholeNum) * mult); + + //******************************************* + // convert integer portion + //******************************************* + char tbfr[40] ; + idx = 0 ; + while (wholeNum != 0) { + tbfr[idx++] = '0' + (wholeNum % 10) ; + wholeNum /= 10 ; + } + // printf("%.3f: whole=%s, dec=%d\n", dbl, tbfr, decimalNum) ; + if (idx == 0) { + *output++ = '0' ; + } else { + while (idx > 0) { + *output++ = tbfr[idx-1] ; //lint !e771 + idx-- ; + } + } + if (dec_digits > 0) { + *output++ = '.' ; + + //******************************************* + // convert fractional portion + //******************************************* + idx = 0 ; + while (decimalNum != 0) { + tbfr[idx++] = '0' + (decimalNum % 10) ; + decimalNum /= 10 ; + } + // pad the decimal portion with 0s as necessary; + // We wouldn't want to report 3.093 as 3.93, would we?? + while (idx < dec_digits) { + tbfr[idx++] = '0' ; + } + // printf("decimal=%s\n", tbfr) ; + if (idx == 0) { + *output++ = '0' ; + } else { + while (idx > 0) { + *output++ = tbfr[idx-1] ; + idx-- ; + } + } + } + *output = 0 ; + + // prepare output + output = (outbfr == 0) ? local_bfr : outbfr ; + return my_strlen(output) ; +} + +//**************************************************************************** +#define PAD_RIGHT 1 +#define PAD_ZERO 2 + +static int prints (char **out, const char *string, int width, int pad) +{ + register int pc = 0, padchar = ' '; + if (width > 0) { + int len = 0; + const char *ptr; + for (ptr = string; *ptr; ++ptr) + ++len; + if (len >= width) + width = 0; + else + width -= len; + if (pad & PAD_ZERO) + padchar = '0'; + } + if (!(pad & PAD_RIGHT)) { + for (; width > 0; --width) { + printchar (out, padchar); + ++pc; + } + } + for (; *string; ++string) { + printchar (out, *string); + ++pc; + } + for (; width > 0; --width) { + printchar (out, padchar); + ++pc; + } + return pc; +} + +//**************************************************************************** +/* the following should be enough for 32 bit int */ +#define PRINT_BUF_LEN 12 +static int printi (char **out, int i, int b, int sg, int width, int pad, int letbase) +{ + char print_buf[PRINT_BUF_LEN]; + char *s; + int t, neg = 0, pc = 0; + unsigned u = (unsigned) i; + if (i == 0) { + print_buf[0] = '0'; + print_buf[1] = '\0'; + return prints (out, print_buf, width, pad); + } + if (sg && b == 10 && i < 0) { + neg = 1; + u = (unsigned) -i; + } + // make sure print_buf is NULL-term + s = print_buf + PRINT_BUF_LEN - 1; + *s = '\0'; + + + while (u) { + t = u % b; //lint !e573 Warning 573: Signed-unsigned mix with divide + if (t >= 10) + t += letbase - '0' - 10; + *--s = t + '0'; + u /= b; //lint !e573 Warning 573: Signed-unsigned mix with divide + } + if (neg) { + if (width && (pad & PAD_ZERO)) { + printchar (out, '-'); + ++pc; + --width; + } + else { + *--s = '-'; + } + } else { + if (use_leading_plus) { + *--s = '+'; + } + } + return pc + prints (out, s, width, pad); +} + +//**************************************************************************** +static int print (char **out, int *varg) +{ + int post_decimal ; + int width, pad ; + unsigned dec_width = 6 ; + int pc = 0; + char *format = (char *) (*varg++); + char scr[2]; + use_leading_plus = 0 ; // start out with this clear + for (; *format != 0; ++format) { + if (*format == '%') { + dec_width = 6 ; + ++format; + width = pad = 0; + if (*format == '\0') + break; + if (*format == '%') + goto out_lbl; + if (*format == '-') { + ++format; + pad = PAD_RIGHT; + } + if (*format == '+') { + ++format; + use_leading_plus = 1 ; + } + while (*format == '0') { + ++format; + pad |= PAD_ZERO; + } + post_decimal = 0 ; + if (*format == '.' || + (*format >= '0' && *format <= '9')) { + + while (1) { + if (*format == '.') { + post_decimal = 1 ; + dec_width = 0 ; + format++ ; + } else if ((*format >= '0' && *format <= '9')) { + if (post_decimal) { + dec_width *= 10; + dec_width += *format - '0'; + } else { + width *= 10; + width += *format - '0'; + } + format++ ; + } else { + break; + } + } + } + if (*format == 'l') + ++format; + switch (*format) { + case 's': + { + // char *s = *((char **) varg++); //lint !e740 + char *s = (char *) *varg++ ; //lint !e740 !e826 convert to double pointer + pc += prints (out, s ? s : "(null)", width, pad); + use_leading_plus = 0 ; // reset this flag after printing one value + } + break; + case 'd': + pc += printi (out, *varg++, 10, 1, width, pad, 'a'); + use_leading_plus = 0 ; // reset this flag after printing one value + break; + case 'x': + pc += printi (out, *varg++, 16, 0, width, pad, 'a'); + use_leading_plus = 0 ; // reset this flag after printing one value + break; + case 'X': + pc += printi (out, *varg++, 16, 0, width, pad, 'A'); + use_leading_plus = 0 ; // reset this flag after printing one value + break; + case 'u': + pc += printi (out, *varg++, 10, 0, width, pad, 'a'); + use_leading_plus = 0 ; // reset this flag after printing one value + break; + case 'c': + /* char are converted to int then pushed on the stack */ + scr[0] = *varg++; + scr[1] = '\0'; + pc += prints (out, scr, width, pad); + use_leading_plus = 0 ; // reset this flag after printing one value + break; + + case 'f': + { + // http://wiki.debian.org/ArmEabiPort#Structpackingandalignment + // Stack alignment + // + // The ARM EABI requires 8-byte stack alignment at public function entry points, + // compared to the previous 4-byte alignment. +#ifdef USE_NEWLIB + char *cptr = (char *) varg ; //lint !e740 !e826 convert to double pointer + uint caddr = (uint) cptr ; + if ((caddr & 0xF) != 0) { + cptr += 4 ; + } + double *dblptr = (double *) cptr ; //lint !e740 !e826 convert to double pointer +#else + double *dblptr = (double *) varg ; //lint !e740 !e826 convert to double pointer +#endif + double dbl = *dblptr++ ; // increment double pointer + varg = (int *) dblptr ; //lint !e740 copy updated pointer back to base pointer + char bfr[81] ; + // unsigned slen = + dbl2stri(bfr, dbl, dec_width) ; + // stuff_talkf("[%s], width=%u, dec_width=%u\n", bfr, width, dec_width) ; + pc += prints (out, bfr, width, pad); + use_leading_plus = 0 ; // reset this flag after printing one value + } + break; + + default: + printchar (out, '%'); + printchar (out, *format); + use_leading_plus = 0 ; // reset this flag after printing one value + break; + } + } else + // if (*format == '\\') { + // + // } else + { +out_lbl: + printchar (out, *format); + ++pc; + } + } // for each char in format string + if (out) //lint !e850 + **out = '\0'; + return pc; +} + +//**************************************************************************** +int stringf (char *out, const char *format, ...) +{ + // create a pointer into the stack. + // Thematically this should be a void*, since the actual usage of the + // pointer will vary. However, int* works fine too. + // Either way, the called function will need to re-cast the pointer + // for any type which isn't sizeof(int) + int *varg = (int *) (char *) (&format); + return print (&out, varg); +} + +int printf(const char *format, ...) +{ + int *varg = (int *) (char *) (&format); + return print (0, varg); +} + +int sprintf(char *out, const char *format, ...) +{ + int *varg = (int *) (char *) (&format); + return print (&out, varg); +} + +/** + * @} + */ diff --git a/flight/Libraries/taskmonitor.c b/flight/Libraries/taskmonitor.c index 332e94cbf..ba9fad228 100644 --- a/flight/Libraries/taskmonitor.c +++ b/flight/Libraries/taskmonitor.c @@ -1,159 +1,159 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file taskmonitor.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Task monitoring library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#include "openpilot.h" -//#include "taskmonitor.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; -static xTaskHandle handles[TASKINFO_RUNNING_NUMELEM]; -static uint32_t lastMonitorTime; - -// Private functions - -/** - * Initialize library - */ -int32_t TaskMonitorInitialize(void) -{ - lock = xSemaphoreCreateRecursiveMutex(); - memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM); - lastMonitorTime = 0; -#ifdef DIAG_TASKS - lastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE(); -#endif - return 0; -} - -/** - * Register a task handle with the library - */ -int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle) -{ - if (task < TASKINFO_RUNNING_NUMELEM) - { - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - handles[task] = handle; - xSemaphoreGiveRecursive(lock); - return 0; - } - else - { - return -1; - } -} - -/** - * Remove a task handle from the library - */ -int32_t TaskMonitorRemove(TaskInfoRunningElem task) -{ - if (task < TASKINFO_RUNNING_NUMELEM) - { - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - handles[task] = 0; - xSemaphoreGiveRecursive(lock); - return 0; - } - else - { - return -1; - } -} - -/** - * Query if a task is running - */ -bool TaskMonitorQueryRunning(TaskInfoRunningElem task) -{ - if (task < TASKINFO_RUNNING_NUMELEM && handles[task] != 0) - return true; - return false; -} - -/** - * Update the status of all tasks - */ -void TaskMonitorUpdateAll(void) -{ -#ifdef DIAG_TASKS - TaskInfoData data; - int n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - uint32_t currentTime; - uint32_t deltaTime; - - /* - * Calculate the amount of elapsed run time between the last time we - * measured and now. Scale so that we can convert task run times - * directly to percentages. - */ - currentTime = portGET_RUN_TIME_COUNTER_VALUE(); - deltaTime = ((currentTime - lastMonitorTime) / 100) ? : 1; /* avoid divide-by-zero if the interval is too small */ - lastMonitorTime = currentTime; -#endif - - // Update all task information - for (n = 0; n < TASKINFO_RUNNING_NUMELEM; ++n) - { - if (handles[n] != 0) - { - data.Running[n] = TASKINFO_RUNNING_TRUE; -#if defined(ARCH_POSIX) || defined(ARCH_WIN32) - data.StackRemaining[n] = 10000; -#else - data.StackRemaining[n] = uxTaskGetStackHighWaterMark(handles[n]) * 4; -#endif -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - /* Generate run time stats */ - data.RunningTime[n] = uxTaskGetRunTime(handles[n]) / deltaTime; -#endif - - } - else - { - data.Running[n] = TASKINFO_RUNNING_FALSE; - data.StackRemaining[n] = 0; - data.RunningTime[n] = 0; - } - } - - // Update object - TaskInfoSet(&data); - - // Done - xSemaphoreGiveRecursive(lock); -#endif -} +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file taskmonitor.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Task monitoring library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "openpilot.h" +//#include "taskmonitor.h" + +// Private constants + +// Private types + +// Private variables +static xSemaphoreHandle lock; +static xTaskHandle handles[TASKINFO_RUNNING_NUMELEM]; +static uint32_t lastMonitorTime; + +// Private functions + +/** + * Initialize library + */ +int32_t TaskMonitorInitialize(void) +{ + lock = xSemaphoreCreateRecursiveMutex(); + memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM); + lastMonitorTime = 0; +#ifdef DIAG_TASKS + lastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE(); +#endif + return 0; +} + +/** + * Register a task handle with the library + */ +int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle) +{ + if (task < TASKINFO_RUNNING_NUMELEM) + { + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + handles[task] = handle; + xSemaphoreGiveRecursive(lock); + return 0; + } + else + { + return -1; + } +} + +/** + * Remove a task handle from the library + */ +int32_t TaskMonitorRemove(TaskInfoRunningElem task) +{ + if (task < TASKINFO_RUNNING_NUMELEM) + { + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + handles[task] = 0; + xSemaphoreGiveRecursive(lock); + return 0; + } + else + { + return -1; + } +} + +/** + * Query if a task is running + */ +bool TaskMonitorQueryRunning(TaskInfoRunningElem task) +{ + if (task < TASKINFO_RUNNING_NUMELEM && handles[task] != 0) + return true; + return false; +} + +/** + * Update the status of all tasks + */ +void TaskMonitorUpdateAll(void) +{ +#ifdef DIAG_TASKS + TaskInfoData data; + int n; + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + uint32_t currentTime; + uint32_t deltaTime; + + /* + * Calculate the amount of elapsed run time between the last time we + * measured and now. Scale so that we can convert task run times + * directly to percentages. + */ + currentTime = portGET_RUN_TIME_COUNTER_VALUE(); + deltaTime = ((currentTime - lastMonitorTime) / 100) ? : 1; /* avoid divide-by-zero if the interval is too small */ + lastMonitorTime = currentTime; +#endif + + // Update all task information + for (n = 0; n < TASKINFO_RUNNING_NUMELEM; ++n) + { + if (handles[n] != 0) + { + data.Running[n] = TASKINFO_RUNNING_TRUE; +#if defined(ARCH_POSIX) || defined(ARCH_WIN32) + data.StackRemaining[n] = 10000; +#else + data.StackRemaining[n] = uxTaskGetStackHighWaterMark(handles[n]) * 4; +#endif +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + /* Generate run time stats */ + data.RunningTime[n] = uxTaskGetRunTime(handles[n]) / deltaTime; +#endif + + } + else + { + data.Running[n] = TASKINFO_RUNNING_FALSE; + data.StackRemaining[n] = 0; + data.RunningTime[n] = 0; + } + } + + // Update object + TaskInfoSet(&data); + + // Done + xSemaphoreGiveRecursive(lock); +#endif +} diff --git a/flight/Modules/FirmwareIAP/firmwareiap.c b/flight/Modules/FirmwareIAP/firmwareiap.c index f3a7ee8bd..f8e6fd231 100644 --- a/flight/Modules/FirmwareIAP/firmwareiap.c +++ b/flight/Modules/FirmwareIAP/firmwareiap.c @@ -1,266 +1,266 @@ -/** - ****************************************************************************** - * - * @file firmwareiap.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief In Application Programming module to support firmware upgrades by - * providing a means to enter the bootloader. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#include - -#include "pios.h" -#include -#include "openpilot.h" -#include "firmwareiap.h" -#include "firmwareiapobj.h" -#include "flightstatus.h" - -// Private constants -#define IAP_CMD_STEP_1 1122 -#define IAP_CMD_STEP_2 2233 -#define IAP_CMD_STEP_3 3344 - -#define IAP_CMD_CRC 100 -#define IAP_CMD_VERIFY 101 -#define IAP_CMD_VERSION 102 - -#define IAP_STATE_READY 0 -#define IAP_STATE_STEP_1 1 -#define IAP_STATE_STEP_2 2 -#define IAP_STATE_RESETTING 3 - -#define RESET_DELAY 500 /* delay between sending reset ot INS */ - -#define TICKS2MS(t) ((t)/portTICK_RATE_MS) -#define MS2TICKS(m) ((m)*portTICK_RATE_MS) - -const uint32_t iap_time_2_low_end = 500; -const uint32_t iap_time_2_high_end = 5000; -const uint32_t iap_time_3_low_end = 500; -const uint32_t iap_time_3_high_end = 5000; - -// Private types - -// Private variables -static uint8_t reset_count = 0; -static portTickType lastResetSysTime; - -// Private functions -static void FirmwareIAPCallback(UAVObjEvent* ev); - -static uint32_t get_time(void); - -// Private types - -// Private functions -static void resetTask(UAVObjEvent *); - -/** - * Initialise the module, called on startup. - * \returns 0 on success or -1 if initialisation failed - */ - -/*! - * \brief Performs object initialization functions. - * \param None. - * \return 0 - under all cases - * - * \note - * - */ -MODULE_INITCALL(FirmwareIAPInitialize, 0) -int32_t FirmwareIAPInitialize() -{ - - FirmwareIAPObjInitialize(); - - const struct pios_board_info * bdinfo = &pios_board_info_blob; - - FirmwareIAPObjData data; - FirmwareIAPObjGet(&data); - - data.BoardType= bdinfo->board_type; - PIOS_BL_HELPER_FLASH_Read_Description(data.Description,FIRMWAREIAPOBJ_DESCRIPTION_NUMELEM); - PIOS_SYS_SerialNumberGetBinary(data.CPUSerial); - data.BoardRevision= bdinfo->board_rev; - data.ArmReset=0; - data.crc = 0; - FirmwareIAPObjSet( &data ); - if(bdinfo->magic==PIOS_BOARD_INFO_BLOB_MAGIC) FirmwareIAPObjConnectCallback( &FirmwareIAPCallback ); - return 0; -} - -int32_t FirmwareIAPStart() -{ - return 0; -} - -/*! - * \brief FirmwareIAPCallback - callback function for firmware IAP requests - * \param[in] ev - pointer objevent - * \retval None. - * - * \note - * - */ -static uint8_t iap_state = IAP_STATE_READY; -static void FirmwareIAPCallback(UAVObjEvent* ev) -{ - const struct pios_board_info * bdinfo = &pios_board_info_blob; - static uint32_t last_time = 0; - uint32_t this_time; - uint32_t delta; - - if(iap_state == IAP_STATE_RESETTING) - return; - - FirmwareIAPObjData data; - FirmwareIAPObjGet(&data); - - if ( ev->obj == FirmwareIAPObjHandle() ) { - // Get the input object data - FirmwareIAPObjGet(&data); - this_time = get_time(); - delta = this_time - last_time; - last_time = this_time; - if((data.BoardType==bdinfo->board_type)&&(data.crc != PIOS_BL_HELPER_CRC_Memory_Calc())) - { - PIOS_BL_HELPER_FLASH_Read_Description(data.Description,FIRMWAREIAPOBJ_DESCRIPTION_NUMELEM); - PIOS_SYS_SerialNumberGetBinary(data.CPUSerial); - data.BoardRevision=bdinfo->board_rev; - data.crc = PIOS_BL_HELPER_CRC_Memory_Calc(); - FirmwareIAPObjSet( &data ); - } - if((data.ArmReset==1)&&(iap_state!=IAP_STATE_RESETTING)) - { - data.ArmReset=0; - FirmwareIAPObjSet( &data ); - } - switch(iap_state) { - case IAP_STATE_READY: - if( data.Command == IAP_CMD_STEP_1 ) { - iap_state = IAP_STATE_STEP_1; - } break; - case IAP_STATE_STEP_1: - if( data.Command == IAP_CMD_STEP_2 ) { - if( delta > iap_time_2_low_end && delta < iap_time_2_high_end ) { - iap_state = IAP_STATE_STEP_2; - } else { - iap_state = IAP_STATE_READY; - } - } else { - iap_state = IAP_STATE_READY; - } - break; - case IAP_STATE_STEP_2: - if( data.Command == IAP_CMD_STEP_3 ) { - if( delta > iap_time_3_low_end && delta < iap_time_3_high_end ) { - - FlightStatusData flightStatus; - FlightStatusGet(&flightStatus); - - if(flightStatus.Armed != FLIGHTSTATUS_ARMED_DISARMED) { - // Abort any attempts if not disarmed - iap_state = IAP_STATE_READY; - break; - } - - // we've met the three sequence of command numbers - // we've met the time requirements. - PIOS_IAP_SetRequest1(); - PIOS_IAP_SetRequest2(); - - /* Note: Cant just wait timeout value, because first time is randomized */ - reset_count = 0; - lastResetSysTime = xTaskGetTickCount(); - UAVObjEvent * ev = pvPortMalloc(sizeof(UAVObjEvent)); - memset(ev,0,sizeof(UAVObjEvent)); - EventPeriodicCallbackCreate(ev, resetTask, 100); - iap_state = IAP_STATE_RESETTING; - } else { - iap_state = IAP_STATE_READY; - } - } else { - iap_state = IAP_STATE_READY; - } - break; - case IAP_STATE_RESETTING: - // stay here permanentally, should reboot - break; - default: - iap_state = IAP_STATE_READY; - last_time = 0; // Reset the time counter, as we are not doing a IAP reset - break; - } - } -} - - - -// Returns number of milliseconds from the start of the kernel. - -/*! - * \brief Returns number of milliseconds from the start of the kernel - * \param None. - * \return number of milliseconds from the start of the kernel. - * - * \note - * - */ - -static uint32_t get_time(void) -{ - portTickType ticks; - - ticks = xTaskGetTickCount(); - - return TICKS2MS(ticks); -} - -/** - * Executed by event dispatcher callback to reset INS before resetting OP - */ -static void resetTask(UAVObjEvent * ev) -{ -#if defined (PIOS_LED_HEARTBEAT) - PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); -#endif /* PIOS_LED_HEARTBEAT */ - -#if defined (PIOS_LED_ALARM) - PIOS_LED_Toggle(PIOS_LED_ALARM); -#endif /* PIOS_LED_ALARM */ - - FirmwareIAPObjData data; - FirmwareIAPObjGet(&data); - - if((portTickType) (xTaskGetTickCount() - lastResetSysTime) > RESET_DELAY / portTICK_RATE_MS) { - lastResetSysTime = xTaskGetTickCount(); - data.BoardType=0xFF; - data.ArmReset=1; - data.crc=reset_count; /* Must change a value for this to get to INS */ - FirmwareIAPObjSet(&data); - ++reset_count; - if(reset_count>3) - { - PIOS_SYS_Reset(); - } - } -} +/** + ****************************************************************************** + * + * @file firmwareiap.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief In Application Programming module to support firmware upgrades by + * providing a means to enter the bootloader. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include + +#include "pios.h" +#include +#include "openpilot.h" +#include "firmwareiap.h" +#include "firmwareiapobj.h" +#include "flightstatus.h" + +// Private constants +#define IAP_CMD_STEP_1 1122 +#define IAP_CMD_STEP_2 2233 +#define IAP_CMD_STEP_3 3344 + +#define IAP_CMD_CRC 100 +#define IAP_CMD_VERIFY 101 +#define IAP_CMD_VERSION 102 + +#define IAP_STATE_READY 0 +#define IAP_STATE_STEP_1 1 +#define IAP_STATE_STEP_2 2 +#define IAP_STATE_RESETTING 3 + +#define RESET_DELAY 500 /* delay between sending reset ot INS */ + +#define TICKS2MS(t) ((t)/portTICK_RATE_MS) +#define MS2TICKS(m) ((m)*portTICK_RATE_MS) + +const uint32_t iap_time_2_low_end = 500; +const uint32_t iap_time_2_high_end = 5000; +const uint32_t iap_time_3_low_end = 500; +const uint32_t iap_time_3_high_end = 5000; + +// Private types + +// Private variables +static uint8_t reset_count = 0; +static portTickType lastResetSysTime; + +// Private functions +static void FirmwareIAPCallback(UAVObjEvent* ev); + +static uint32_t get_time(void); + +// Private types + +// Private functions +static void resetTask(UAVObjEvent *); + +/** + * Initialise the module, called on startup. + * \returns 0 on success or -1 if initialisation failed + */ + +/*! + * \brief Performs object initialization functions. + * \param None. + * \return 0 - under all cases + * + * \note + * + */ +MODULE_INITCALL(FirmwareIAPInitialize, 0) +int32_t FirmwareIAPInitialize() +{ + + FirmwareIAPObjInitialize(); + + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + FirmwareIAPObjData data; + FirmwareIAPObjGet(&data); + + data.BoardType= bdinfo->board_type; + PIOS_BL_HELPER_FLASH_Read_Description(data.Description,FIRMWAREIAPOBJ_DESCRIPTION_NUMELEM); + PIOS_SYS_SerialNumberGetBinary(data.CPUSerial); + data.BoardRevision= bdinfo->board_rev; + data.ArmReset=0; + data.crc = 0; + FirmwareIAPObjSet( &data ); + if(bdinfo->magic==PIOS_BOARD_INFO_BLOB_MAGIC) FirmwareIAPObjConnectCallback( &FirmwareIAPCallback ); + return 0; +} + +int32_t FirmwareIAPStart() +{ + return 0; +} + +/*! + * \brief FirmwareIAPCallback - callback function for firmware IAP requests + * \param[in] ev - pointer objevent + * \retval None. + * + * \note + * + */ +static uint8_t iap_state = IAP_STATE_READY; +static void FirmwareIAPCallback(UAVObjEvent* ev) +{ + const struct pios_board_info * bdinfo = &pios_board_info_blob; + static uint32_t last_time = 0; + uint32_t this_time; + uint32_t delta; + + if(iap_state == IAP_STATE_RESETTING) + return; + + FirmwareIAPObjData data; + FirmwareIAPObjGet(&data); + + if ( ev->obj == FirmwareIAPObjHandle() ) { + // Get the input object data + FirmwareIAPObjGet(&data); + this_time = get_time(); + delta = this_time - last_time; + last_time = this_time; + if((data.BoardType==bdinfo->board_type)&&(data.crc != PIOS_BL_HELPER_CRC_Memory_Calc())) + { + PIOS_BL_HELPER_FLASH_Read_Description(data.Description,FIRMWAREIAPOBJ_DESCRIPTION_NUMELEM); + PIOS_SYS_SerialNumberGetBinary(data.CPUSerial); + data.BoardRevision=bdinfo->board_rev; + data.crc = PIOS_BL_HELPER_CRC_Memory_Calc(); + FirmwareIAPObjSet( &data ); + } + if((data.ArmReset==1)&&(iap_state!=IAP_STATE_RESETTING)) + { + data.ArmReset=0; + FirmwareIAPObjSet( &data ); + } + switch(iap_state) { + case IAP_STATE_READY: + if( data.Command == IAP_CMD_STEP_1 ) { + iap_state = IAP_STATE_STEP_1; + } break; + case IAP_STATE_STEP_1: + if( data.Command == IAP_CMD_STEP_2 ) { + if( delta > iap_time_2_low_end && delta < iap_time_2_high_end ) { + iap_state = IAP_STATE_STEP_2; + } else { + iap_state = IAP_STATE_READY; + } + } else { + iap_state = IAP_STATE_READY; + } + break; + case IAP_STATE_STEP_2: + if( data.Command == IAP_CMD_STEP_3 ) { + if( delta > iap_time_3_low_end && delta < iap_time_3_high_end ) { + + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + + if(flightStatus.Armed != FLIGHTSTATUS_ARMED_DISARMED) { + // Abort any attempts if not disarmed + iap_state = IAP_STATE_READY; + break; + } + + // we've met the three sequence of command numbers + // we've met the time requirements. + PIOS_IAP_SetRequest1(); + PIOS_IAP_SetRequest2(); + + /* Note: Cant just wait timeout value, because first time is randomized */ + reset_count = 0; + lastResetSysTime = xTaskGetTickCount(); + UAVObjEvent * ev = pvPortMalloc(sizeof(UAVObjEvent)); + memset(ev,0,sizeof(UAVObjEvent)); + EventPeriodicCallbackCreate(ev, resetTask, 100); + iap_state = IAP_STATE_RESETTING; + } else { + iap_state = IAP_STATE_READY; + } + } else { + iap_state = IAP_STATE_READY; + } + break; + case IAP_STATE_RESETTING: + // stay here permanentally, should reboot + break; + default: + iap_state = IAP_STATE_READY; + last_time = 0; // Reset the time counter, as we are not doing a IAP reset + break; + } + } +} + + + +// Returns number of milliseconds from the start of the kernel. + +/*! + * \brief Returns number of milliseconds from the start of the kernel + * \param None. + * \return number of milliseconds from the start of the kernel. + * + * \note + * + */ + +static uint32_t get_time(void) +{ + portTickType ticks; + + ticks = xTaskGetTickCount(); + + return TICKS2MS(ticks); +} + +/** + * Executed by event dispatcher callback to reset INS before resetting OP + */ +static void resetTask(UAVObjEvent * ev) +{ +#if defined (PIOS_LED_HEARTBEAT) + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); +#endif /* PIOS_LED_HEARTBEAT */ + +#if defined (PIOS_LED_ALARM) + PIOS_LED_Toggle(PIOS_LED_ALARM); +#endif /* PIOS_LED_ALARM */ + + FirmwareIAPObjData data; + FirmwareIAPObjGet(&data); + + if((portTickType) (xTaskGetTickCount() - lastResetSysTime) > RESET_DELAY / portTICK_RATE_MS) { + lastResetSysTime = xTaskGetTickCount(); + data.BoardType=0xFF; + data.ArmReset=1; + data.crc=reset_count; /* Must change a value for this to get to INS */ + FirmwareIAPObjSet(&data); + ++reset_count; + if(reset_count>3) + { + PIOS_SYS_Reset(); + } + } +} diff --git a/flight/Modules/FirmwareIAP/inc/firmwareiap.h b/flight/Modules/FirmwareIAP/inc/firmwareiap.h index aba32d155..f62a51d4a 100644 --- a/flight/Modules/FirmwareIAP/inc/firmwareiap.h +++ b/flight/Modules/FirmwareIAP/inc/firmwareiap.h @@ -1,33 +1,33 @@ -/** - ****************************************************************************** - * - * @file firmwareiap.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Example module to be used as a template for actual modules. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef FIRMWAREIAP_H -#define FIRMWAREIAP_H - -int32_t FirmwareIAPInitialize(); -int32_t FirmwareIAPStart(); - -#endif // FIRMWAREIAP_H - +/** + ****************************************************************************** + * + * @file firmwareiap.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Example module to be used as a template for actual modules. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef FIRMWAREIAP_H +#define FIRMWAREIAP_H + +int32_t FirmwareIAPInitialize(); +int32_t FirmwareIAPStart(); + +#endif // FIRMWAREIAP_H + diff --git a/flight/Modules/GPS/inc/UBX.h b/flight/Modules/GPS/inc/UBX.h index dc27fa798..f7718bb3c 100644 --- a/flight/Modules/GPS/inc/UBX.h +++ b/flight/Modules/GPS/inc/UBX.h @@ -1,224 +1,224 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules - * @{ - * @addtogroup GSPModule GPS Module - * @brief Process GPS information - * @{ - * - * @file UBX.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief GPS module, handles GPS and NMEA stream - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef UBX_H -#define UBX_H -#include "openpilot.h" -#include "gpsposition.h" -#include "GPS.h" - - -#define UBX_SYNC1 0xb5 // UBX protocol synchronization characters -#define UBX_SYNC2 0x62 - -// From u-blox6 receiver protocol specification - -// Messages classes -#define UBX_CLASS_NAV 0x01 - -// Message IDs -#define UBX_ID_POSLLH 0x02 -#define UBX_ID_STATUS 0x03 -#define UBX_ID_DOP 0x04 -#define UBX_ID_SOL 0x06 -#define UBX_ID_VELNED 0x12 -#define UBX_ID_TIMEUTC 0x21 -#define UBX_ID_SVINFO 0x30 - -// private structures - -// Geodetic Position Solution -struct UBX_NAV_POSLLH { - uint32_t iTOW; // GPS Millisecond Time of Week (ms) - int32_t lon; // Longitude (deg*1e-7) - int32_t lat; // Latitude (deg*1e-7) - int32_t height; // Height above Ellipsoid (mm) - int32_t hMSL; // Height above mean sea level (mm) - uint32_t hAcc; // Horizontal Accuracy Estimate (mm) - uint32_t vAcc; // Vertical Accuracy Estimate (mm) -}; - -// Receiver Navigation Status - -#define STATUS_GPSFIX_NOFIX 0x00 -#define STATUS_GPSFIX_DRONLY 0x01 -#define STATUS_GPSFIX_2DFIX 0x02 -#define STATUS_GPSFIX_3DFIX 0x03 -#define STATUS_GPSFIX_GPSDR 0x04 -#define STATUS_GPSFIX_TIMEONLY 0x05 - -#define STATUS_FLAGS_GPSFIX_OK (1 << 0) -#define STATUS_FLAGS_DIFFSOLN (1 << 1) -#define STATUS_FLAGS_WKNSET (1 << 2) -#define STATUS_FLAGS_TOWSET (1 << 3) - -struct UBX_NAV_STATUS { - uint32_t iTOW; // GPS Millisecond Time of Week (ms) - uint8_t gpsFix; // GPS fix type - uint8_t flags; // Navigation Status Flags - uint8_t fixStat; // Fix Status Information - uint8_t flags2; // Additional navigation output information - uint32_t ttff; // Time to first fix (ms) - uint32_t msss; // Milliseconds since startup/reset (ms) -}; - -// Dilution of precision -struct UBX_NAV_DOP { - uint32_t iTOW; // GPS Millisecond Time of Week (ms) - uint16_t gDOP; // Geometric DOP - uint16_t pDOP; // Position DOP - uint16_t tDOP; // Time DOP - uint16_t vDOP; // Vertical DOP - uint16_t hDOP; // Horizontal DOP - uint16_t nDOP; // Northing DOP - uint16_t eDOP; // Easting DOP -}; - -// Navigation solution - -struct UBX_NAV_SOL { - uint32_t iTOW; // GPS Millisecond Time of Week (ms) - int32_t fTOW; // fractional nanoseconds (ns) - int16_t week; // GPS week - uint8_t gpsFix; // GPS fix type - uint8_t flags; // Fix status flags - int32_t ecefX; // ECEF X coordinate (cm) - int32_t ecefY; // ECEF Y coordinate (cm) - int32_t ecefZ; // ECEF Z coordinate (cm) - uint32_t pAcc; // 3D Position Accuracy Estimate (cm) - int32_t ecefVX; // ECEF X coordinate (cm/s) - int32_t ecefVY; // ECEF Y coordinate (cm/s) - int32_t ecefVZ; // ECEF Z coordinate (cm/s) - uint32_t sAcc; // Speed Accuracy Estimate - uint16_t pDOP; // Position DOP - uint8_t reserved1; // Reserved - uint8_t numSV; // Number of SVs used in Nav Solution - uint32_t reserved2; // Reserved -}; - -// North/East/Down velocity - -struct UBX_NAV_VELNED { - uint32_t iTOW; // ms GPS Millisecond Time of Week - int32_t velN; // cm/s NED north velocity - int32_t velE; // cm/s NED east velocity - int32_t velD; // cm/s NED down velocity - uint32_t speed; // cm/s Speed (3-D) - uint32_t gSpeed; // cm/s Ground Speed (2-D) - int32_t heading; // 1e-5 *deg Heading of motion 2-D - uint32_t sAcc; // cm/s Speed Accuracy Estimate - uint32_t cAcc; // 1e-5 *deg Course / Heading Accuracy Estimate -}; - -// UTC Time Solution - -#define TIMEUTC_VALIDTOW (1 << 0) -#define TIMEUTC_VALIDWKN (1 << 1) -#define TIMEUTC_VALIDUTC (1 << 2) - -struct UBX_NAV_TIMEUTC { - uint32_t iTOW; // GPS Millisecond Time of Week (ms) - uint32_t tAcc; // Time Accuracy Estimate (ns) - int32_t nano; // Nanoseconds of second - uint16_t year; - uint8_t month; - uint8_t day; - uint8_t hour; - uint8_t min; - uint8_t sec; - uint8_t valid; // Validity Flags -}; - -// Space Vehicle (SV) Information - -// Single SV information block - -#define SVUSED (1 << 0) // This SV is used for navigation -#define DIFFCORR (1 << 1) // Differential correction available -#define ORBITAVAIL (1 << 2) // Orbit information available -#define ORBITEPH (1 << 3) // Orbit information is Ephemeris -#define UNHEALTHY (1 << 4) // SV is unhealthy -#define ORBITALM (1 << 5) // Orbit information is Almanac Plus -#define ORBITAOP (1 << 6) // Orbit information is AssistNow Autonomous -#define SMOOTHED (1 << 7) // Carrier smoothed pseudoranges used - -struct UBX_NAV_SVINFO_SV { - uint8_t chn; // Channel number - uint8_t svid; // Satellite ID - uint8_t flags; // Misc SV information - uint8_t quality; // Misc quality indicators - uint8_t cno; // Carrier to Noise Ratio (dbHz) - int8_t elev; // Elevation (integer degrees) - int16_t azim; // Azimuth (integer degrees) - int32_t prRes; // Pseudo range residual (cm) -}; - -// SV information message -#define MAX_SVS 16 - -struct UBX_NAV_SVINFO { - uint32_t iTOW; // GPS Millisecond Time of Week (ms) - uint8_t numCh; // Number of channels - uint8_t globalFlags; // - uint16_t reserved2; // Reserved - struct UBX_NAV_SVINFO_SV sv[MAX_SVS]; // Repeated 'numCh' times -}; - -typedef union { - uint8_t payload[0]; - struct UBX_NAV_POSLLH nav_posllh; - struct UBX_NAV_STATUS nav_status; - struct UBX_NAV_DOP nav_dop; - struct UBX_NAV_SOL nav_sol; - struct UBX_NAV_VELNED nav_velned; -#if !defined(PIOS_GPS_MINIMAL) - struct UBX_NAV_TIMEUTC nav_timeutc; - struct UBX_NAV_SVINFO nav_svinfo; -#endif -} UBXPayload; - -struct UBXHeader { - uint8_t class; - uint8_t id; - uint16_t len; - uint8_t ck_a; - uint8_t ck_b; -}; - -struct UBXPacket { - struct UBXHeader header; - UBXPayload payload; -}; - -bool checksum_ubx_message(struct UBXPacket *); -uint32_t parse_ubx_message(struct UBXPacket *, GPSPositionData *); -int parse_ubx_stream(uint8_t, char *, GPSPositionData *, struct GPS_RX_STATS *); - -#endif /* UBX_H */ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup GSPModule GPS Module + * @brief Process GPS information + * @{ + * + * @file UBX.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief GPS module, handles GPS and NMEA stream + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef UBX_H +#define UBX_H +#include "openpilot.h" +#include "gpsposition.h" +#include "GPS.h" + + +#define UBX_SYNC1 0xb5 // UBX protocol synchronization characters +#define UBX_SYNC2 0x62 + +// From u-blox6 receiver protocol specification + +// Messages classes +#define UBX_CLASS_NAV 0x01 + +// Message IDs +#define UBX_ID_POSLLH 0x02 +#define UBX_ID_STATUS 0x03 +#define UBX_ID_DOP 0x04 +#define UBX_ID_SOL 0x06 +#define UBX_ID_VELNED 0x12 +#define UBX_ID_TIMEUTC 0x21 +#define UBX_ID_SVINFO 0x30 + +// private structures + +// Geodetic Position Solution +struct UBX_NAV_POSLLH { + uint32_t iTOW; // GPS Millisecond Time of Week (ms) + int32_t lon; // Longitude (deg*1e-7) + int32_t lat; // Latitude (deg*1e-7) + int32_t height; // Height above Ellipsoid (mm) + int32_t hMSL; // Height above mean sea level (mm) + uint32_t hAcc; // Horizontal Accuracy Estimate (mm) + uint32_t vAcc; // Vertical Accuracy Estimate (mm) +}; + +// Receiver Navigation Status + +#define STATUS_GPSFIX_NOFIX 0x00 +#define STATUS_GPSFIX_DRONLY 0x01 +#define STATUS_GPSFIX_2DFIX 0x02 +#define STATUS_GPSFIX_3DFIX 0x03 +#define STATUS_GPSFIX_GPSDR 0x04 +#define STATUS_GPSFIX_TIMEONLY 0x05 + +#define STATUS_FLAGS_GPSFIX_OK (1 << 0) +#define STATUS_FLAGS_DIFFSOLN (1 << 1) +#define STATUS_FLAGS_WKNSET (1 << 2) +#define STATUS_FLAGS_TOWSET (1 << 3) + +struct UBX_NAV_STATUS { + uint32_t iTOW; // GPS Millisecond Time of Week (ms) + uint8_t gpsFix; // GPS fix type + uint8_t flags; // Navigation Status Flags + uint8_t fixStat; // Fix Status Information + uint8_t flags2; // Additional navigation output information + uint32_t ttff; // Time to first fix (ms) + uint32_t msss; // Milliseconds since startup/reset (ms) +}; + +// Dilution of precision +struct UBX_NAV_DOP { + uint32_t iTOW; // GPS Millisecond Time of Week (ms) + uint16_t gDOP; // Geometric DOP + uint16_t pDOP; // Position DOP + uint16_t tDOP; // Time DOP + uint16_t vDOP; // Vertical DOP + uint16_t hDOP; // Horizontal DOP + uint16_t nDOP; // Northing DOP + uint16_t eDOP; // Easting DOP +}; + +// Navigation solution + +struct UBX_NAV_SOL { + uint32_t iTOW; // GPS Millisecond Time of Week (ms) + int32_t fTOW; // fractional nanoseconds (ns) + int16_t week; // GPS week + uint8_t gpsFix; // GPS fix type + uint8_t flags; // Fix status flags + int32_t ecefX; // ECEF X coordinate (cm) + int32_t ecefY; // ECEF Y coordinate (cm) + int32_t ecefZ; // ECEF Z coordinate (cm) + uint32_t pAcc; // 3D Position Accuracy Estimate (cm) + int32_t ecefVX; // ECEF X coordinate (cm/s) + int32_t ecefVY; // ECEF Y coordinate (cm/s) + int32_t ecefVZ; // ECEF Z coordinate (cm/s) + uint32_t sAcc; // Speed Accuracy Estimate + uint16_t pDOP; // Position DOP + uint8_t reserved1; // Reserved + uint8_t numSV; // Number of SVs used in Nav Solution + uint32_t reserved2; // Reserved +}; + +// North/East/Down velocity + +struct UBX_NAV_VELNED { + uint32_t iTOW; // ms GPS Millisecond Time of Week + int32_t velN; // cm/s NED north velocity + int32_t velE; // cm/s NED east velocity + int32_t velD; // cm/s NED down velocity + uint32_t speed; // cm/s Speed (3-D) + uint32_t gSpeed; // cm/s Ground Speed (2-D) + int32_t heading; // 1e-5 *deg Heading of motion 2-D + uint32_t sAcc; // cm/s Speed Accuracy Estimate + uint32_t cAcc; // 1e-5 *deg Course / Heading Accuracy Estimate +}; + +// UTC Time Solution + +#define TIMEUTC_VALIDTOW (1 << 0) +#define TIMEUTC_VALIDWKN (1 << 1) +#define TIMEUTC_VALIDUTC (1 << 2) + +struct UBX_NAV_TIMEUTC { + uint32_t iTOW; // GPS Millisecond Time of Week (ms) + uint32_t tAcc; // Time Accuracy Estimate (ns) + int32_t nano; // Nanoseconds of second + uint16_t year; + uint8_t month; + uint8_t day; + uint8_t hour; + uint8_t min; + uint8_t sec; + uint8_t valid; // Validity Flags +}; + +// Space Vehicle (SV) Information + +// Single SV information block + +#define SVUSED (1 << 0) // This SV is used for navigation +#define DIFFCORR (1 << 1) // Differential correction available +#define ORBITAVAIL (1 << 2) // Orbit information available +#define ORBITEPH (1 << 3) // Orbit information is Ephemeris +#define UNHEALTHY (1 << 4) // SV is unhealthy +#define ORBITALM (1 << 5) // Orbit information is Almanac Plus +#define ORBITAOP (1 << 6) // Orbit information is AssistNow Autonomous +#define SMOOTHED (1 << 7) // Carrier smoothed pseudoranges used + +struct UBX_NAV_SVINFO_SV { + uint8_t chn; // Channel number + uint8_t svid; // Satellite ID + uint8_t flags; // Misc SV information + uint8_t quality; // Misc quality indicators + uint8_t cno; // Carrier to Noise Ratio (dbHz) + int8_t elev; // Elevation (integer degrees) + int16_t azim; // Azimuth (integer degrees) + int32_t prRes; // Pseudo range residual (cm) +}; + +// SV information message +#define MAX_SVS 16 + +struct UBX_NAV_SVINFO { + uint32_t iTOW; // GPS Millisecond Time of Week (ms) + uint8_t numCh; // Number of channels + uint8_t globalFlags; // + uint16_t reserved2; // Reserved + struct UBX_NAV_SVINFO_SV sv[MAX_SVS]; // Repeated 'numCh' times +}; + +typedef union { + uint8_t payload[0]; + struct UBX_NAV_POSLLH nav_posllh; + struct UBX_NAV_STATUS nav_status; + struct UBX_NAV_DOP nav_dop; + struct UBX_NAV_SOL nav_sol; + struct UBX_NAV_VELNED nav_velned; +#if !defined(PIOS_GPS_MINIMAL) + struct UBX_NAV_TIMEUTC nav_timeutc; + struct UBX_NAV_SVINFO nav_svinfo; +#endif +} UBXPayload; + +struct UBXHeader { + uint8_t class; + uint8_t id; + uint16_t len; + uint8_t ck_a; + uint8_t ck_b; +}; + +struct UBXPacket { + struct UBXHeader header; + UBXPayload payload; +}; + +bool checksum_ubx_message(struct UBXPacket *); +uint32_t parse_ubx_message(struct UBXPacket *, GPSPositionData *); +int parse_ubx_stream(uint8_t, char *, GPSPositionData *, struct GPS_RX_STATS *); + +#endif /* UBX_H */ diff --git a/flight/Modules/Osd/osdgen/inc/osdgen.h b/flight/Modules/Osd/osdgen/inc/osdgen.h index d2f3aef23..75b341bd3 100644 --- a/flight/Modules/Osd/osdgen/inc/osdgen.h +++ b/flight/Modules/Osd/osdgen/inc/osdgen.h @@ -1,196 +1,196 @@ -/* - * osdgen.h - * - * Created on: 2.10.2011 - * Author: Samba - */ - -#ifndef OSDGEN_H_ -#define OSDGEN_H_ - -#include "openpilot.h" -#include "pios.h" - -int32_t osdgenInitialize(void); - - -// Size of an array (num items.) -#define SIZEOF_ARRAY(x) (sizeof(x) / sizeof((x)[0])) - -#define HUD_VSCALE_FLAG_CLEAR 1 -#define HUD_VSCALE_FLAG_NO_NEGATIVE 2 - -// Macros for computing addresses and bit positions. -// NOTE: /16 in y is because we are addressing by word not byte. -#define CALC_BUFF_ADDR(x, y) (((x) / 8) + ((y) * (GRAPHICS_WIDTH_REAL / 8))) -#define CALC_BIT_IN_WORD(x) ((x) & 7) -#define DEBUG_DELAY -// Macro for writing a word with a mode (NAND = clear, OR = set, XOR = toggle) -// at a given position -#define WRITE_WORD_MODE(buff, addr, mask, mode) \ - switch(mode) { \ - case 0: buff[addr] &= ~mask; break; \ - case 1: buff[addr] |= mask; break; \ - case 2: buff[addr] ^= mask; break; } - -#define WRITE_WORD_NAND(buff, addr, mask) { buff[addr] &= ~mask; DEBUG_DELAY; } -#define WRITE_WORD_OR(buff, addr, mask) { buff[addr] |= mask; DEBUG_DELAY; } -#define WRITE_WORD_XOR(buff, addr, mask) { buff[addr] ^= mask; DEBUG_DELAY; } - -// Horizontal line calculations. -// Edge cases. -#define COMPUTE_HLINE_EDGE_L_MASK(b) ((1 << (8 - (b))) - 1) -#define COMPUTE_HLINE_EDGE_R_MASK(b) (~((1 << (7 - (b))) - 1)) -// This computes an island mask. -#define COMPUTE_HLINE_ISLAND_MASK(b0, b1) (COMPUTE_HLINE_EDGE_L_MASK(b0) ^ COMPUTE_HLINE_EDGE_L_MASK(b1)); - -// Macro for initializing stroke/fill modes. Add new modes here -// if necessary. -#define SETUP_STROKE_FILL(stroke, fill, mode) \ - stroke = 0; fill = 0; \ - if(mode == 0) { stroke = 0; fill = 1; } \ - if(mode == 1) { stroke = 1; fill = 0; } \ - -// Line endcaps (for horizontal and vertical lines.) -#define ENDCAP_NONE 0 -#define ENDCAP_ROUND 1 -#define ENDCAP_FLAT 2 - -#define DRAW_ENDCAP_HLINE(e, x, y, s, f, l) \ - if((e) == ENDCAP_ROUND) /* single pixel endcap */ \ - { write_pixel_lm(x, y, f, l); } \ - else if((e) == ENDCAP_FLAT) /* flat endcap: FIXME, quicker to draw a vertical line(?) */ \ - { write_pixel_lm(x, y - 1, s, l); write_pixel_lm(x, y, s, l); write_pixel_lm(x, y + 1, s, l); } - -#define DRAW_ENDCAP_VLINE(e, x, y, s, f, l) \ - if((e) == ENDCAP_ROUND) /* single pixel endcap */ \ - { write_pixel_lm(x, y, f, l); } \ - else if((e) == ENDCAP_FLAT) /* flat endcap: FIXME, quicker to draw a horizontal line(?) */ \ - { write_pixel_lm(x - 1, y, s, l); write_pixel_lm(x, y, s, l); write_pixel_lm(x + 1, y, s, l); } - -// Macros for writing pixels in a midpoint circle algorithm. -#define CIRCLE_PLOT_8(buff, cx, cy, x, y, mode) \ - CIRCLE_PLOT_4(buff, cx, cy, x, y, mode); \ - if((x) != (y)) CIRCLE_PLOT_4(buff, cx, cy, y, x, mode); - -#define CIRCLE_PLOT_4(buff, cx, cy, x, y, mode) \ - write_pixel(buff, (cx) + (x), (cy) + (y), mode); \ - write_pixel(buff, (cx) - (x), (cy) + (y), mode); \ - write_pixel(buff, (cx) + (x), (cy) - (y), mode); \ - write_pixel(buff, (cx) - (x), (cy) - (y), mode); - - - -// Font flags. -#define FONT_BOLD 1 // bold text (no outline) -#define FONT_INVERT 2 // invert: border white, inside black - -// Text alignments. -#define TEXT_VA_TOP 0 -#define TEXT_VA_MIDDLE 1 -#define TEXT_VA_BOTTOM 2 -#define TEXT_HA_LEFT 0 -#define TEXT_HA_CENTER 1 -#define TEXT_HA_RIGHT 2 - -// Text dimension structures. -struct FontDimensions -{ - int width, height; -}; - - -// Max/Min macros. -#define MAX(a, b) ((a) > (b) ? (a) : (b)) -#define MIN(a, b) ((a) < (b) ? (a) : (b)) -#define MAX3(a, b, c) MAX(a, MAX(b, c)) -#define MIN3(a, b, c) MIN(a, MIN(b, c)) - -// Apply DeadBand -#define APPLY_DEADBAND(x, y) { x = (x)+GRAPHICS_HDEADBAND; y=(y)+GRAPHICS_VDEADBAND; } -#define APPLY_VDEADBAND(y) ((y)+GRAPHICS_VDEADBAND) -#define APPLY_HDEADBAND(x) ((x)+GRAPHICS_HDEADBAND) - -// Check if coordinates are valid. If not, return. -#define CHECK_COORDS(x, y) if(x < 0 || x >= GRAPHICS_WIDTH_REAL || y < 0 || y >= GRAPHICS_HEIGHT_REAL) return; -#define CHECK_COORD_X(x) if(x < 0 || x >= GRAPHICS_WIDTH_REAL) return; -#define CHECK_COORD_Y(y) if(y < 0 || y >= GRAPHICS_HEIGHT_REAL) return; - -// Clip coordinates out of range. -#define CLIP_COORD_X(x) { x = MAX(0, MIN(x, GRAPHICS_WIDTH_REAL)); } -#define CLIP_COORD_Y(y) { y = MAX(0, MIN(y, GRAPHICS_HEIGHT_REAL)); } -#define CLIP_COORDS(x, y) { CLIP_COORD_X(x); CLIP_COORD_Y(y); } - -// Macro to swap two variables using XOR swap. -#define SWAP(a, b) { a ^= b; b ^= a; a ^= b; } - - -// Line triggering -#define LAST_LINE 312 //625/2 //PAL -//#define LAST_LINE 525/2 //NTSC - -// Global vars - -#define DELAY_1_NOP() asm("nop\r\n") -#define DELAY_2_NOP() asm("nop\r\nnop\r\n") -#define DELAY_3_NOP() asm("nop\r\nnop\r\nnop\r\n") -#define DELAY_4_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\n") -#define DELAY_5_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") -#define DELAY_6_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") -#define DELAY_7_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") -#define DELAY_8_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") -#define DELAY_9_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") -#define DELAY_10_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") - - - -uint8_t getCharData(uint16_t charPos); -void introText(); - -void clearGraphics(); -uint8_t validPos(uint16_t x, uint16_t y); -void setPixel(uint16_t x, uint16_t y, uint8_t state); -void drawCircle(uint16_t x0, uint16_t y0, uint16_t radius); -void swap(uint16_t* a, uint16_t* b); -void drawLine(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1); -void drawBox(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); -void drawArrow(uint16_t x, uint16_t y, uint16_t angle, uint16_t size); -void drawAttitude(uint16_t x, uint16_t y, int16_t pitch, int16_t roll, uint16_t size); -void introGraphics(); -void updateGraphics(); -void drawGraphicsLine(); - -void write_char16(char ch, unsigned int x, unsigned int y, int font); -void write_pixel(uint8_t *buff, unsigned int x, unsigned int y, int mode); -void write_pixel_lm(unsigned int x, unsigned int y, int mmode, int lmode); -void write_hline(uint8_t *buff, unsigned int x0, unsigned int x1, unsigned int y, int mode); -void write_hline_lm(unsigned int x0, unsigned int x1, unsigned int y, int lmode, int mmode); -void write_hline_outlined(unsigned int x0, unsigned int x1, unsigned int y, int endcap0, int endcap1, int mode, int mmode); -void write_vline(uint8_t *buff, unsigned int x, unsigned int y0, unsigned int y1, int mode); -void write_vline_lm(unsigned int x, unsigned int y0, unsigned int y1, int lmode, int mmode); -void write_vline_outlined(unsigned int x, unsigned int y0, unsigned int y1, int endcap0, int endcap1, int mode, int mmode); -void write_filled_rectangle(uint8_t *buff, unsigned int x, unsigned int y, unsigned int width, unsigned int height, int mode); -void write_filled_rectangle_lm(unsigned int x, unsigned int y, unsigned int width, unsigned int height, int lmode, int mmode); -void write_rectangle_outlined(unsigned int x, unsigned int y, int width, int height, int mode, int mmode); -void write_circle(uint8_t *buff, unsigned int cx, unsigned int cy, unsigned int r, unsigned int dashp, int mode); -void write_circle_outlined(unsigned int cx, unsigned int cy, unsigned int r, unsigned int dashp, int bmode, int mode, int mmode); -void write_circle_filled(uint8_t *buff, unsigned int cx, unsigned int cy, unsigned int r, int mode); -void write_line(uint8_t *buff, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int mode); -void write_line_lm(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int mmode, int lmode); -void write_line_outlined(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int endcap0, int endcap1, int mode, int mmode); -void write_word_misaligned(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff, int mode); -void write_word_misaligned_NAND(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff); -void write_word_misaligned_OR(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff); -void write_word_misaligned_lm(uint16_t wordl, uint16_t wordm, unsigned int addr, unsigned int xoff, int lmode, int mmode); -//int fetch_font_info(char ch, int font, struct FontEntry *font_info, char *lookup); -void write_char(char ch, unsigned int x, unsigned int y, int flags, int font); -//void calc_text_dimensions(char *str, struct FontEntry font, int xs, int ys, struct FontDimensions *dim); -void write_string(char *str, unsigned int x, unsigned int y, unsigned int xs, unsigned int ys, int va, int ha, int flags, int font); -void write_string_formatted(char *str, unsigned int x, unsigned int y, unsigned int xs, unsigned int ys, int va, int ha, int flags); - -void updateOnceEveryFrame(); - - - - -#endif /* OSDGEN_H_ */ +/* + * osdgen.h + * + * Created on: 2.10.2011 + * Author: Samba + */ + +#ifndef OSDGEN_H_ +#define OSDGEN_H_ + +#include "openpilot.h" +#include "pios.h" + +int32_t osdgenInitialize(void); + + +// Size of an array (num items.) +#define SIZEOF_ARRAY(x) (sizeof(x) / sizeof((x)[0])) + +#define HUD_VSCALE_FLAG_CLEAR 1 +#define HUD_VSCALE_FLAG_NO_NEGATIVE 2 + +// Macros for computing addresses and bit positions. +// NOTE: /16 in y is because we are addressing by word not byte. +#define CALC_BUFF_ADDR(x, y) (((x) / 8) + ((y) * (GRAPHICS_WIDTH_REAL / 8))) +#define CALC_BIT_IN_WORD(x) ((x) & 7) +#define DEBUG_DELAY +// Macro for writing a word with a mode (NAND = clear, OR = set, XOR = toggle) +// at a given position +#define WRITE_WORD_MODE(buff, addr, mask, mode) \ + switch(mode) { \ + case 0: buff[addr] &= ~mask; break; \ + case 1: buff[addr] |= mask; break; \ + case 2: buff[addr] ^= mask; break; } + +#define WRITE_WORD_NAND(buff, addr, mask) { buff[addr] &= ~mask; DEBUG_DELAY; } +#define WRITE_WORD_OR(buff, addr, mask) { buff[addr] |= mask; DEBUG_DELAY; } +#define WRITE_WORD_XOR(buff, addr, mask) { buff[addr] ^= mask; DEBUG_DELAY; } + +// Horizontal line calculations. +// Edge cases. +#define COMPUTE_HLINE_EDGE_L_MASK(b) ((1 << (8 - (b))) - 1) +#define COMPUTE_HLINE_EDGE_R_MASK(b) (~((1 << (7 - (b))) - 1)) +// This computes an island mask. +#define COMPUTE_HLINE_ISLAND_MASK(b0, b1) (COMPUTE_HLINE_EDGE_L_MASK(b0) ^ COMPUTE_HLINE_EDGE_L_MASK(b1)); + +// Macro for initializing stroke/fill modes. Add new modes here +// if necessary. +#define SETUP_STROKE_FILL(stroke, fill, mode) \ + stroke = 0; fill = 0; \ + if(mode == 0) { stroke = 0; fill = 1; } \ + if(mode == 1) { stroke = 1; fill = 0; } \ + +// Line endcaps (for horizontal and vertical lines.) +#define ENDCAP_NONE 0 +#define ENDCAP_ROUND 1 +#define ENDCAP_FLAT 2 + +#define DRAW_ENDCAP_HLINE(e, x, y, s, f, l) \ + if((e) == ENDCAP_ROUND) /* single pixel endcap */ \ + { write_pixel_lm(x, y, f, l); } \ + else if((e) == ENDCAP_FLAT) /* flat endcap: FIXME, quicker to draw a vertical line(?) */ \ + { write_pixel_lm(x, y - 1, s, l); write_pixel_lm(x, y, s, l); write_pixel_lm(x, y + 1, s, l); } + +#define DRAW_ENDCAP_VLINE(e, x, y, s, f, l) \ + if((e) == ENDCAP_ROUND) /* single pixel endcap */ \ + { write_pixel_lm(x, y, f, l); } \ + else if((e) == ENDCAP_FLAT) /* flat endcap: FIXME, quicker to draw a horizontal line(?) */ \ + { write_pixel_lm(x - 1, y, s, l); write_pixel_lm(x, y, s, l); write_pixel_lm(x + 1, y, s, l); } + +// Macros for writing pixels in a midpoint circle algorithm. +#define CIRCLE_PLOT_8(buff, cx, cy, x, y, mode) \ + CIRCLE_PLOT_4(buff, cx, cy, x, y, mode); \ + if((x) != (y)) CIRCLE_PLOT_4(buff, cx, cy, y, x, mode); + +#define CIRCLE_PLOT_4(buff, cx, cy, x, y, mode) \ + write_pixel(buff, (cx) + (x), (cy) + (y), mode); \ + write_pixel(buff, (cx) - (x), (cy) + (y), mode); \ + write_pixel(buff, (cx) + (x), (cy) - (y), mode); \ + write_pixel(buff, (cx) - (x), (cy) - (y), mode); + + + +// Font flags. +#define FONT_BOLD 1 // bold text (no outline) +#define FONT_INVERT 2 // invert: border white, inside black + +// Text alignments. +#define TEXT_VA_TOP 0 +#define TEXT_VA_MIDDLE 1 +#define TEXT_VA_BOTTOM 2 +#define TEXT_HA_LEFT 0 +#define TEXT_HA_CENTER 1 +#define TEXT_HA_RIGHT 2 + +// Text dimension structures. +struct FontDimensions +{ + int width, height; +}; + + +// Max/Min macros. +#define MAX(a, b) ((a) > (b) ? (a) : (b)) +#define MIN(a, b) ((a) < (b) ? (a) : (b)) +#define MAX3(a, b, c) MAX(a, MAX(b, c)) +#define MIN3(a, b, c) MIN(a, MIN(b, c)) + +// Apply DeadBand +#define APPLY_DEADBAND(x, y) { x = (x)+GRAPHICS_HDEADBAND; y=(y)+GRAPHICS_VDEADBAND; } +#define APPLY_VDEADBAND(y) ((y)+GRAPHICS_VDEADBAND) +#define APPLY_HDEADBAND(x) ((x)+GRAPHICS_HDEADBAND) + +// Check if coordinates are valid. If not, return. +#define CHECK_COORDS(x, y) if(x < 0 || x >= GRAPHICS_WIDTH_REAL || y < 0 || y >= GRAPHICS_HEIGHT_REAL) return; +#define CHECK_COORD_X(x) if(x < 0 || x >= GRAPHICS_WIDTH_REAL) return; +#define CHECK_COORD_Y(y) if(y < 0 || y >= GRAPHICS_HEIGHT_REAL) return; + +// Clip coordinates out of range. +#define CLIP_COORD_X(x) { x = MAX(0, MIN(x, GRAPHICS_WIDTH_REAL)); } +#define CLIP_COORD_Y(y) { y = MAX(0, MIN(y, GRAPHICS_HEIGHT_REAL)); } +#define CLIP_COORDS(x, y) { CLIP_COORD_X(x); CLIP_COORD_Y(y); } + +// Macro to swap two variables using XOR swap. +#define SWAP(a, b) { a ^= b; b ^= a; a ^= b; } + + +// Line triggering +#define LAST_LINE 312 //625/2 //PAL +//#define LAST_LINE 525/2 //NTSC + +// Global vars + +#define DELAY_1_NOP() asm("nop\r\n") +#define DELAY_2_NOP() asm("nop\r\nnop\r\n") +#define DELAY_3_NOP() asm("nop\r\nnop\r\nnop\r\n") +#define DELAY_4_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\n") +#define DELAY_5_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") +#define DELAY_6_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") +#define DELAY_7_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") +#define DELAY_8_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") +#define DELAY_9_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") +#define DELAY_10_NOP() asm("nop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\nnop\r\n") + + + +uint8_t getCharData(uint16_t charPos); +void introText(); + +void clearGraphics(); +uint8_t validPos(uint16_t x, uint16_t y); +void setPixel(uint16_t x, uint16_t y, uint8_t state); +void drawCircle(uint16_t x0, uint16_t y0, uint16_t radius); +void swap(uint16_t* a, uint16_t* b); +void drawLine(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1); +void drawBox(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); +void drawArrow(uint16_t x, uint16_t y, uint16_t angle, uint16_t size); +void drawAttitude(uint16_t x, uint16_t y, int16_t pitch, int16_t roll, uint16_t size); +void introGraphics(); +void updateGraphics(); +void drawGraphicsLine(); + +void write_char16(char ch, unsigned int x, unsigned int y, int font); +void write_pixel(uint8_t *buff, unsigned int x, unsigned int y, int mode); +void write_pixel_lm(unsigned int x, unsigned int y, int mmode, int lmode); +void write_hline(uint8_t *buff, unsigned int x0, unsigned int x1, unsigned int y, int mode); +void write_hline_lm(unsigned int x0, unsigned int x1, unsigned int y, int lmode, int mmode); +void write_hline_outlined(unsigned int x0, unsigned int x1, unsigned int y, int endcap0, int endcap1, int mode, int mmode); +void write_vline(uint8_t *buff, unsigned int x, unsigned int y0, unsigned int y1, int mode); +void write_vline_lm(unsigned int x, unsigned int y0, unsigned int y1, int lmode, int mmode); +void write_vline_outlined(unsigned int x, unsigned int y0, unsigned int y1, int endcap0, int endcap1, int mode, int mmode); +void write_filled_rectangle(uint8_t *buff, unsigned int x, unsigned int y, unsigned int width, unsigned int height, int mode); +void write_filled_rectangle_lm(unsigned int x, unsigned int y, unsigned int width, unsigned int height, int lmode, int mmode); +void write_rectangle_outlined(unsigned int x, unsigned int y, int width, int height, int mode, int mmode); +void write_circle(uint8_t *buff, unsigned int cx, unsigned int cy, unsigned int r, unsigned int dashp, int mode); +void write_circle_outlined(unsigned int cx, unsigned int cy, unsigned int r, unsigned int dashp, int bmode, int mode, int mmode); +void write_circle_filled(uint8_t *buff, unsigned int cx, unsigned int cy, unsigned int r, int mode); +void write_line(uint8_t *buff, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int mode); +void write_line_lm(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int mmode, int lmode); +void write_line_outlined(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int endcap0, int endcap1, int mode, int mmode); +void write_word_misaligned(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff, int mode); +void write_word_misaligned_NAND(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff); +void write_word_misaligned_OR(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff); +void write_word_misaligned_lm(uint16_t wordl, uint16_t wordm, unsigned int addr, unsigned int xoff, int lmode, int mmode); +//int fetch_font_info(char ch, int font, struct FontEntry *font_info, char *lookup); +void write_char(char ch, unsigned int x, unsigned int y, int flags, int font); +//void calc_text_dimensions(char *str, struct FontEntry font, int xs, int ys, struct FontDimensions *dim); +void write_string(char *str, unsigned int x, unsigned int y, unsigned int xs, unsigned int ys, int va, int ha, int flags, int font); +void write_string_formatted(char *str, unsigned int x, unsigned int y, unsigned int xs, unsigned int ys, int va, int ha, int flags); + +void updateOnceEveryFrame(); + + + + +#endif /* OSDGEN_H_ */ diff --git a/flight/Modules/Osd/osdgen/osdgen.c b/flight/Modules/Osd/osdgen/osdgen.c index b2e64e795..0c686c87f 100644 --- a/flight/Modules/Osd/osdgen/osdgen.c +++ b/flight/Modules/Osd/osdgen/osdgen.c @@ -1,193 +1,193 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules - * @{ - * @addtogroup OSDGENModule osdgen Module - * @brief Process OSD information - * @{ - * - * @file osdgen.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup OSDGENModule osdgen Module + * @brief Process OSD information + * @{ + * + * @file osdgen.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief OSD gen module, handles OSD draw. Parts from CL-OSD and SUPEROSD projects - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -// **************** - -#include "openpilot.h" -#include "osdgen.h" -#include "attitudeactual.h" -#include "gpsposition.h" -#include "homelocation.h" -#include "gpstime.h" -#include "gpssatellites.h" -#include "osdsettings.h" -#include "baroaltitude.h" - -#include "fonts.h" -#include "font12x18.h" -#include "font8x10.h" -#include "WMMInternal.h" - -#include "splash.h" -/* -static uint16_t angleA=0; -static int16_t angleB=90; -static int16_t angleC=0; -static int16_t sum=2; - -static int16_t m_pitch=0; -static int16_t m_roll=0; -static int16_t m_yaw=0; -static int16_t m_batt=0; -static int16_t m_alt=0; - -static uint8_t m_gpsStatus=0; -static int32_t m_gpsLat=0; -static int32_t m_gpsLon=0; -static float m_gpsAlt=0; -static float m_gpsSpd=0;*/ - -extern uint8_t *draw_buffer_level; -extern uint8_t *draw_buffer_mask; -extern uint8_t *disp_buffer_level; -extern uint8_t *disp_buffer_mask; - - -TTime timex; - -// **************** -// Private functions - -static void osdgenTask(void *parameters); - -// **************** -// Private constants -#define LONG_TIME 0xffff -xSemaphoreHandle osdSemaphore = NULL; - -#define STACK_SIZE_BYTES 4096 - -#define TASK_PRIORITY (tskIDLE_PRIORITY + 4) -#define UPDATE_PERIOD 100 - -// **************** -// Private variables - -static xTaskHandle osdgenTaskHandle; - -struct splashEntry -{ - unsigned int width, height; - const uint16_t *level; - const uint16_t *mask; -}; - -struct splashEntry splash[3] = { - { oplogo_width, - oplogo_height, - oplogo_bits, - oplogo_mask_bits }, - { level_width, - level_height, - level_bits, - level_mask_bits }, - { llama_width, - llama_height, - llama_bits, - llama_mask_bits }, - -}; - -uint16_t mirror(uint16_t source) -{ - int result = ((source & 0x8000) >> 7) | ((source & 0x4000) >> 5) | - ((source & 0x2000) >> 3) | ((source & 0x1000) >> 1) | - ((source & 0x0800) << 1) | ((source & 0x0400) << 3) | - ((source & 0x0200) << 5) | ((source & 0x0100) << 7) | - ((source & 0x0080) >> 7) | ((source & 0x0040) >> 5) | - ((source & 0x0020) >> 3) | ((source & 0x0010) >> 1) | - ((source & 0x0008) << 1) | ((source & 0x0004) << 3) | - ((source & 0x0002) << 5) | ((source & 0x0001) << 7); - - return result; -} - -void clearGraphics() { - memset((uint8_t *) draw_buffer_mask, 0, GRAPHICS_WIDTH * GRAPHICS_HEIGHT); - memset((uint8_t *) draw_buffer_level, 0, GRAPHICS_WIDTH * GRAPHICS_HEIGHT); -} - -void copyimage(uint16_t offsetx, uint16_t offsety, int image) { - //check top/left position - if (!validPos(offsetx, offsety)) { - return; - } - struct splashEntry splash_info; - splash_info = splash[image]; - offsetx=offsetx/8; - for (uint16_t y = offsety; y < ((splash_info.height)+offsety); y++) { - uint16_t x1=offsetx; - for (uint16_t x = offsetx; x < (((splash_info.width)/16)+offsetx); x++) { - draw_buffer_level[y*GRAPHICS_WIDTH+x1+1] = (uint8_t)(mirror(splash_info.level[(y-offsety)*((splash_info.width)/16)+(x-offsetx)])>>8); - draw_buffer_level[y*GRAPHICS_WIDTH+x1] = (uint8_t)(mirror(splash_info.level[(y-offsety)*((splash_info.width)/16)+(x-offsetx)])&0xFF); - draw_buffer_mask[y*GRAPHICS_WIDTH+x1+1] = (uint8_t)(mirror(splash_info.mask[(y-offsety)*((splash_info.width)/16)+(x-offsetx)])>>8); - draw_buffer_mask[y*GRAPHICS_WIDTH+x1] = (uint8_t)(mirror(splash_info.mask[(y-offsety)*((splash_info.width)/16)+(x-offsetx)])&0xFF); - x1+=2; - } - } -} - -uint8_t validPos(uint16_t x, uint16_t y) { - if ( x < GRAPHICS_HDEADBAND || x >= GRAPHICS_WIDTH_REAL || y >= GRAPHICS_HEIGHT_REAL) { - return 0; - } - return 1; -} - -// Credit for this one goes to wikipedia! :-) -void drawCircle(uint16_t x0, uint16_t y0, uint16_t radius) { - int f = 1 - radius; - int ddF_x = 1; - int ddF_y = -2 * radius; - int x = 0; - int y = radius; - + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +// **************** + +#include "openpilot.h" +#include "osdgen.h" +#include "attitudeactual.h" +#include "gpsposition.h" +#include "homelocation.h" +#include "gpstime.h" +#include "gpssatellites.h" +#include "osdsettings.h" +#include "baroaltitude.h" + +#include "fonts.h" +#include "font12x18.h" +#include "font8x10.h" +#include "WMMInternal.h" + +#include "splash.h" +/* +static uint16_t angleA=0; +static int16_t angleB=90; +static int16_t angleC=0; +static int16_t sum=2; + +static int16_t m_pitch=0; +static int16_t m_roll=0; +static int16_t m_yaw=0; +static int16_t m_batt=0; +static int16_t m_alt=0; + +static uint8_t m_gpsStatus=0; +static int32_t m_gpsLat=0; +static int32_t m_gpsLon=0; +static float m_gpsAlt=0; +static float m_gpsSpd=0;*/ + +extern uint8_t *draw_buffer_level; +extern uint8_t *draw_buffer_mask; +extern uint8_t *disp_buffer_level; +extern uint8_t *disp_buffer_mask; + + +TTime timex; + +// **************** +// Private functions + +static void osdgenTask(void *parameters); + +// **************** +// Private constants +#define LONG_TIME 0xffff +xSemaphoreHandle osdSemaphore = NULL; + +#define STACK_SIZE_BYTES 4096 + +#define TASK_PRIORITY (tskIDLE_PRIORITY + 4) +#define UPDATE_PERIOD 100 + +// **************** +// Private variables + +static xTaskHandle osdgenTaskHandle; + +struct splashEntry +{ + unsigned int width, height; + const uint16_t *level; + const uint16_t *mask; +}; + +struct splashEntry splash[3] = { + { oplogo_width, + oplogo_height, + oplogo_bits, + oplogo_mask_bits }, + { level_width, + level_height, + level_bits, + level_mask_bits }, + { llama_width, + llama_height, + llama_bits, + llama_mask_bits }, + +}; + +uint16_t mirror(uint16_t source) +{ + int result = ((source & 0x8000) >> 7) | ((source & 0x4000) >> 5) | + ((source & 0x2000) >> 3) | ((source & 0x1000) >> 1) | + ((source & 0x0800) << 1) | ((source & 0x0400) << 3) | + ((source & 0x0200) << 5) | ((source & 0x0100) << 7) | + ((source & 0x0080) >> 7) | ((source & 0x0040) >> 5) | + ((source & 0x0020) >> 3) | ((source & 0x0010) >> 1) | + ((source & 0x0008) << 1) | ((source & 0x0004) << 3) | + ((source & 0x0002) << 5) | ((source & 0x0001) << 7); + + return result; +} + +void clearGraphics() { + memset((uint8_t *) draw_buffer_mask, 0, GRAPHICS_WIDTH * GRAPHICS_HEIGHT); + memset((uint8_t *) draw_buffer_level, 0, GRAPHICS_WIDTH * GRAPHICS_HEIGHT); +} + +void copyimage(uint16_t offsetx, uint16_t offsety, int image) { + //check top/left position + if (!validPos(offsetx, offsety)) { + return; + } + struct splashEntry splash_info; + splash_info = splash[image]; + offsetx=offsetx/8; + for (uint16_t y = offsety; y < ((splash_info.height)+offsety); y++) { + uint16_t x1=offsetx; + for (uint16_t x = offsetx; x < (((splash_info.width)/16)+offsetx); x++) { + draw_buffer_level[y*GRAPHICS_WIDTH+x1+1] = (uint8_t)(mirror(splash_info.level[(y-offsety)*((splash_info.width)/16)+(x-offsetx)])>>8); + draw_buffer_level[y*GRAPHICS_WIDTH+x1] = (uint8_t)(mirror(splash_info.level[(y-offsety)*((splash_info.width)/16)+(x-offsetx)])&0xFF); + draw_buffer_mask[y*GRAPHICS_WIDTH+x1+1] = (uint8_t)(mirror(splash_info.mask[(y-offsety)*((splash_info.width)/16)+(x-offsetx)])>>8); + draw_buffer_mask[y*GRAPHICS_WIDTH+x1] = (uint8_t)(mirror(splash_info.mask[(y-offsety)*((splash_info.width)/16)+(x-offsetx)])&0xFF); + x1+=2; + } + } +} + +uint8_t validPos(uint16_t x, uint16_t y) { + if ( x < GRAPHICS_HDEADBAND || x >= GRAPHICS_WIDTH_REAL || y >= GRAPHICS_HEIGHT_REAL) { + return 0; + } + return 1; +} + +// Credit for this one goes to wikipedia! :-) +void drawCircle(uint16_t x0, uint16_t y0, uint16_t radius) { + int f = 1 - radius; + int ddF_x = 1; + int ddF_y = -2 * radius; + int x = 0; + int y = radius; + write_pixel_lm(x0, y0 + radius,1,1); write_pixel_lm(x0, y0 - radius,1,1); write_pixel_lm(x0 + radius, y0,1,1); write_pixel_lm(x0 - radius, y0,1,1); - - while(x < y) - { - // ddF_x == 2 * x + 1; - // ddF_y == -2 * y; - // f == x*x + y*y - radius*radius + 2*x - y + 1; - if(f >= 0) - { - y--; - ddF_y += 2; - f += ddF_y; - } - x++; - ddF_x += 2; - f += ddF_x; + + while(x < y) + { + // ddF_x == 2 * x + 1; + // ddF_y == -2 * y; + // f == x*x + y*y - radius*radius + 2*x - y + 1; + if(f >= 0) + { + y--; + ddF_y += 2; + f += ddF_y; + } + x++; + ddF_x += 2; + f += ddF_x; write_pixel_lm(x0 + x, y0 + y,1,1); write_pixel_lm(x0 - x, y0 + y,1,1); write_pixel_lm(x0 + x, y0 - y,1,1); @@ -196,2015 +196,2015 @@ void drawCircle(uint16_t x0, uint16_t y0, uint16_t radius) { write_pixel_lm(x0 - y, y0 + x,1,1); write_pixel_lm(x0 + y, y0 - x,1,1); write_pixel_lm(x0 - y, y0 - x,1,1); - } -} - -void swap(uint16_t* a, uint16_t* b) { - uint16_t temp = *a; - *a = *b; - *b = temp; -} - - -const static int8_t sinData[91] = { - 0, 2, 3, 5, 7, 9, 10, 12, 14, 16, 17, 19, 21, 22, 24, 26, 28, 29, 31, 33, - 34, 36, 37, 39, 41, 42, 44, 45, 47, 48, 50, 52, 53, 54, 56, 57, 59, 60, 62, - 63, 64, 66, 67, 68, 69, 71, 72, 73, 74, 75, 77, 78, 79, 80, 81, 82, 83, 84, - 85, 86, 87, 87, 88, 89, 90, 91, 91, 92, 93, 93, 94, 95, 95, 96, 96, 97, 97, - 97, 98, 98, 98, 99, 99, 99, 99, 100, 100, 100, 100, 100, 100}; - -static int8_t mySin(uint16_t angle) { - uint16_t pos = 0; - pos = angle % 360; - int8_t mult = 1; - // 180-359 is same as 0-179 but negative. - if (pos >= 180) { - pos = pos - 180; - mult = -1; - } - // 0-89 is equal to 90-179 except backwards. - if (pos >= 90) { - pos = 180 - pos; - } - return mult * (int8_t)(sinData[pos]); -} - -static int8_t myCos(uint16_t angle) { - return mySin(angle + 90); -} - -/// Draws four points relative to the given center point. -/// -/// \li centerX + X, centerY + Y -/// \li centerX + X, centerY - Y -/// \li centerX - X, centerY + Y -/// \li centerX - X, centerY - Y -/// -/// \param centerX the x coordinate of the center point -/// \param centerY the y coordinate of the center point -/// \param deltaX the difference between the centerX coordinate and each pixel drawn -/// \param deltaY the difference between the centerY coordinate and each pixel drawn -/// \param color the color to draw the pixels with. -void plotFourQuadrants(int32_t centerX, int32_t centerY, int32_t deltaX, int32_t deltaY) -{ + } +} + +void swap(uint16_t* a, uint16_t* b) { + uint16_t temp = *a; + *a = *b; + *b = temp; +} + + +const static int8_t sinData[91] = { + 0, 2, 3, 5, 7, 9, 10, 12, 14, 16, 17, 19, 21, 22, 24, 26, 28, 29, 31, 33, + 34, 36, 37, 39, 41, 42, 44, 45, 47, 48, 50, 52, 53, 54, 56, 57, 59, 60, 62, + 63, 64, 66, 67, 68, 69, 71, 72, 73, 74, 75, 77, 78, 79, 80, 81, 82, 83, 84, + 85, 86, 87, 87, 88, 89, 90, 91, 91, 92, 93, 93, 94, 95, 95, 96, 96, 97, 97, + 97, 98, 98, 98, 99, 99, 99, 99, 100, 100, 100, 100, 100, 100}; + +static int8_t mySin(uint16_t angle) { + uint16_t pos = 0; + pos = angle % 360; + int8_t mult = 1; + // 180-359 is same as 0-179 but negative. + if (pos >= 180) { + pos = pos - 180; + mult = -1; + } + // 0-89 is equal to 90-179 except backwards. + if (pos >= 90) { + pos = 180 - pos; + } + return mult * (int8_t)(sinData[pos]); +} + +static int8_t myCos(uint16_t angle) { + return mySin(angle + 90); +} + +/// Draws four points relative to the given center point. +/// +/// \li centerX + X, centerY + Y +/// \li centerX + X, centerY - Y +/// \li centerX - X, centerY + Y +/// \li centerX - X, centerY - Y +/// +/// \param centerX the x coordinate of the center point +/// \param centerY the y coordinate of the center point +/// \param deltaX the difference between the centerX coordinate and each pixel drawn +/// \param deltaY the difference between the centerY coordinate and each pixel drawn +/// \param color the color to draw the pixels with. +void plotFourQuadrants(int32_t centerX, int32_t centerY, int32_t deltaX, int32_t deltaY) +{ write_pixel_lm(centerX + deltaX, centerY + deltaY,1,1); // Ist Quadrant write_pixel_lm(centerX - deltaX, centerY + deltaY,1,1); // IInd Quadrant write_pixel_lm(centerX - deltaX, centerY - deltaY,1,1); // IIIrd Quadrant write_pixel_lm(centerX + deltaX, centerY - deltaY,1,1); // IVth Quadrant -} - -/// Implements the midpoint ellipse drawing algorithm which is a bresenham -/// style DDF. -/// -/// \param centerX the x coordinate of the center of the ellipse -/// \param centerY the y coordinate of the center of the ellipse -/// \param horizontalRadius the horizontal radius of the ellipse -/// \param verticalRadius the vertical radius of the ellipse -/// \param color the color of the ellipse border -void ellipse(int centerX, int centerY, int horizontalRadius, int verticalRadius) -{ - int64_t doubleHorizontalRadius = horizontalRadius * horizontalRadius; - int64_t doubleVerticalRadius = verticalRadius * verticalRadius; - - int64_t error = doubleVerticalRadius - doubleHorizontalRadius * verticalRadius + (doubleVerticalRadius >> 2); - - int x = 0; - int y = verticalRadius; - int deltaX = 0; - int deltaY = (doubleHorizontalRadius << 1) * y; - - plotFourQuadrants(centerX, centerY, x, y); - - while(deltaY >= deltaX) - { - x++; - deltaX += (doubleVerticalRadius << 1); - - error += deltaX + doubleVerticalRadius; - - if(error >= 0) - { - y--; - deltaY -= (doubleHorizontalRadius << 1); - - error -= deltaY; - } - plotFourQuadrants(centerX, centerY, x, y); - } - - error = (int64_t)(doubleVerticalRadius * (x + 1 / 2.0) * (x + 1 / 2.0) + doubleHorizontalRadius * (y - 1) * (y - 1) - doubleHorizontalRadius * doubleVerticalRadius); - - while (y>=0) - { - error += doubleHorizontalRadius; - y--; - deltaY -= (doubleHorizontalRadius<<1); - error -= deltaY; - - if(error <= 0) - { - x++; - deltaX += (doubleVerticalRadius << 1); - error += deltaX; - } - - plotFourQuadrants(centerX, centerY, x, y); - } -} - - -void drawArrow(uint16_t x, uint16_t y, uint16_t angle, uint16_t size) -{ - int16_t a = myCos(angle); - int16_t b = mySin(angle); - a = (a * (size/2)) / 100; - b = (b * (size/2)) / 100; +} + +/// Implements the midpoint ellipse drawing algorithm which is a bresenham +/// style DDF. +/// +/// \param centerX the x coordinate of the center of the ellipse +/// \param centerY the y coordinate of the center of the ellipse +/// \param horizontalRadius the horizontal radius of the ellipse +/// \param verticalRadius the vertical radius of the ellipse +/// \param color the color of the ellipse border +void ellipse(int centerX, int centerY, int horizontalRadius, int verticalRadius) +{ + int64_t doubleHorizontalRadius = horizontalRadius * horizontalRadius; + int64_t doubleVerticalRadius = verticalRadius * verticalRadius; + + int64_t error = doubleVerticalRadius - doubleHorizontalRadius * verticalRadius + (doubleVerticalRadius >> 2); + + int x = 0; + int y = verticalRadius; + int deltaX = 0; + int deltaY = (doubleHorizontalRadius << 1) * y; + + plotFourQuadrants(centerX, centerY, x, y); + + while(deltaY >= deltaX) + { + x++; + deltaX += (doubleVerticalRadius << 1); + + error += deltaX + doubleVerticalRadius; + + if(error >= 0) + { + y--; + deltaY -= (doubleHorizontalRadius << 1); + + error -= deltaY; + } + plotFourQuadrants(centerX, centerY, x, y); + } + + error = (int64_t)(doubleVerticalRadius * (x + 1 / 2.0) * (x + 1 / 2.0) + doubleHorizontalRadius * (y - 1) * (y - 1) - doubleHorizontalRadius * doubleVerticalRadius); + + while (y>=0) + { + error += doubleHorizontalRadius; + y--; + deltaY -= (doubleHorizontalRadius<<1); + error -= deltaY; + + if(error <= 0) + { + x++; + deltaX += (doubleVerticalRadius << 1); + error += deltaX; + } + + plotFourQuadrants(centerX, centerY, x, y); + } +} + + +void drawArrow(uint16_t x, uint16_t y, uint16_t angle, uint16_t size) +{ + int16_t a = myCos(angle); + int16_t b = mySin(angle); + a = (a * (size/2)) / 100; + b = (b * (size/2)) / 100; write_line_lm((x)-1 - b, (y)-1 + a, (x)-1 + b, (y)-1 - a, 1, 1); //Direction line //write_line_lm((GRAPHICS_SIZE/2)-1 + a/2, (GRAPHICS_SIZE/2)-1 + b/2, (GRAPHICS_SIZE/2)-1 - a/2, (GRAPHICS_SIZE/2)-1 - b/2, 1, 1); //Arrow bottom line write_line_lm((x)-1 + b, (y)-1 - a, (x)-1 - a/2, (y)-1 - b/2, 1, 1); // Arrow "wings" write_line_lm((x)-1 + b, (y)-1 - a, (x)-1 + a/2, (y)-1 + b/2, 1, 1); -} - -void drawBox(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) -{ +} + +void drawBox(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2) +{ write_line_lm(x1, y1, x2, y1, 1, 1); //top write_line_lm(x1, y1, x1, y2, 1, 1); //left write_line_lm(x2, y1, x2, y2, 1, 1); //right write_line_lm(x1, y2, x2, y2, 1, 1); //bottom -} - -// simple routines - -// SUPEROSD routines, modified - -/** - * write_pixel: Write a pixel at an x,y position to a given surface. - * - * @param buff pointer to buffer to write in - * @param x x coordinate - * @param y y coordinate - * @param mode 0 = clear bit, 1 = set bit, 2 = toggle bit - */ -void write_pixel(uint8_t *buff, unsigned int x, unsigned int y, int mode) -{ - CHECK_COORDS(x, y); - // Determine the bit in the word to be set and the word - // index to set it in. - int bitnum = CALC_BIT_IN_WORD(x); - int wordnum = CALC_BUFF_ADDR(x, y); - // Apply a mask. - uint16_t mask = 1 << (7 - bitnum); - WRITE_WORD_MODE(buff, wordnum, mask, mode); -} - -/** - * write_pixel_lm: write the pixel on both surfaces (level and mask.) - * Uses current draw buffer. - * - * @param x x coordinate - * @param y y coordinate - * @param mmode 0 = clear, 1 = set, 2 = toggle - * @param lmode 0 = black, 1 = white, 2 = toggle - */ -void write_pixel_lm(unsigned int x, unsigned int y, int mmode, int lmode) -{ - CHECK_COORDS(x, y); - // Determine the bit in the word to be set and the word - // index to set it in. - int bitnum = CALC_BIT_IN_WORD(x); - int wordnum = CALC_BUFF_ADDR(x, y); - // Apply the masks. - uint16_t mask = 1 << (7 - bitnum); - WRITE_WORD_MODE(draw_buffer_mask, wordnum, mask, mmode); - WRITE_WORD_MODE(draw_buffer_level, wordnum, mask, lmode); -} - - -/** - * write_hline: optimised horizontal line writing algorithm - * - * @param buff pointer to buffer to write in - * @param x0 x0 coordinate - * @param x1 x1 coordinate - * @param y y coordinate - * @param mode 0 = clear, 1 = set, 2 = toggle - */ -void write_hline(uint8_t *buff, unsigned int x0, unsigned int x1, unsigned int y, int mode) -{ - CLIP_COORDS(x0, y); - CLIP_COORDS(x1, y); - if(x0 > x1) - { - SWAP(x0, x1); - } - if(x0 == x1) return; - /* This is an optimised algorithm for writing horizontal lines. - * We begin by finding the addresses of the x0 and x1 points. */ - int addr0 = CALC_BUFF_ADDR(x0, y); - int addr1 = CALC_BUFF_ADDR(x1, y); - int addr0_bit = CALC_BIT_IN_WORD(x0); - int addr1_bit = CALC_BIT_IN_WORD(x1); - int mask, mask_l, mask_r, i; - /* If the addresses are equal, we only need to write one word - * which is an island. */ - if(addr0 == addr1) - { - mask = COMPUTE_HLINE_ISLAND_MASK(addr0_bit, addr1_bit); - WRITE_WORD_MODE(buff, addr0, mask, mode); - } - /* Otherwise we need to write the edges and then the middle. */ - else - { - mask_l = COMPUTE_HLINE_EDGE_L_MASK(addr0_bit); - mask_r = COMPUTE_HLINE_EDGE_R_MASK(addr1_bit); - WRITE_WORD_MODE(buff, addr0, mask_l, mode); - WRITE_WORD_MODE(buff, addr1, mask_r, mode); - // Now write 0xffff words from start+1 to end-1. - for(i = addr0 + 1; i <= addr1 - 1; i++) - { - uint8_t m=0xff; - WRITE_WORD_MODE(buff, i, m, mode); - } - } -} - -/** - * write_hline_lm: write both level and mask buffers. - * - * @param x0 x0 coordinate - * @param x1 x1 coordinate - * @param y y coordinate - * @param lmode 0 = clear, 1 = set, 2 = toggle - * @param mmode 0 = clear, 1 = set, 2 = toggle - */ -void write_hline_lm(unsigned int x0, unsigned int x1, unsigned int y, int lmode, int mmode) -{ - // TODO: an optimisation would compute the masks and apply to - // both buffers simultaneously. - write_hline(draw_buffer_level, x0, x1, y, lmode); - write_hline(draw_buffer_mask, x0, x1, y, mmode); -} - -/** - * write_hline_outlined: outlined horizontal line with varying endcaps - * Always uses draw buffer. - * - * @param x0 x0 coordinate - * @param x1 x1 coordinate - * @param y y coordinate - * @param endcap0 0 = none, 1 = single pixel, 2 = full cap - * @param endcap1 0 = none, 1 = single pixel, 2 = full cap - * @param mode 0 = black outline, white body, 1 = white outline, black body - * @param mmode 0 = clear, 1 = set, 2 = toggle - */ -void write_hline_outlined(unsigned int x0, unsigned int x1, unsigned int y, int endcap0, int endcap1, int mode, int mmode) -{ - int stroke, fill; - SETUP_STROKE_FILL(stroke, fill, mode) - if(x0 > x1) - { - SWAP(x0, x1); - } - // Draw the main body of the line. - write_hline_lm(x0 + 1, x1 - 1, y - 1, stroke, mmode); - write_hline_lm(x0 + 1, x1 - 1, y + 1, stroke, mmode); - write_hline_lm(x0 + 1, x1 - 1, y, fill, mmode); - // Draw the endcaps, if any. - DRAW_ENDCAP_HLINE(endcap0, x0, y, stroke, fill, mmode); - DRAW_ENDCAP_HLINE(endcap1, x1, y, stroke, fill, mmode); -} - -/** - * write_vline: optimised vertical line writing algorithm - * - * @param buff pointer to buffer to write in - * @param x x coordinate - * @param y0 y0 coordinate - * @param y1 y1 coordinate - * @param mode 0 = clear, 1 = set, 2 = toggle - */ -void write_vline(uint8_t *buff, unsigned int x, unsigned int y0, unsigned int y1, int mode) -{ - unsigned int a; - CLIP_COORDS(x, y0); - CLIP_COORDS(x, y1); - if(y0 > y1) - { - SWAP(y0, y1); - } - if(y0 == y1) return; - /* This is an optimised algorithm for writing vertical lines. - * We begin by finding the addresses of the x,y0 and x,y1 points. */ - int addr0 = CALC_BUFF_ADDR(x, y0); - int addr1 = CALC_BUFF_ADDR(x, y1); - /* Then we calculate the pixel data to be written. */ - int bitnum = CALC_BIT_IN_WORD(x); - uint16_t mask = 1 << (7 - bitnum); - /* Run from addr0 to addr1 placing pixels. Increment by the number - * of words n each graphics line. */ - for(a = addr0; a <= addr1; a += GRAPHICS_WIDTH_REAL / 8) - { - WRITE_WORD_MODE(buff, a, mask, mode); - } -} - -/** - * write_vline_lm: write both level and mask buffers. - * - * @param x x coordinate - * @param y0 y0 coordinate - * @param y1 y1 coordinate - * @param lmode 0 = clear, 1 = set, 2 = toggle - * @param mmode 0 = clear, 1 = set, 2 = toggle - */ -void write_vline_lm(unsigned int x, unsigned int y0, unsigned int y1, int lmode, int mmode) -{ - // TODO: an optimisation would compute the masks and apply to - // both buffers simultaneously. - write_vline(draw_buffer_level, x, y0, y1, lmode); - write_vline(draw_buffer_mask, x, y0, y1, mmode); -} - -/** - * write_vline_outlined: outlined vertical line with varying endcaps - * Always uses draw buffer. - * - * @param x x coordinate - * @param y0 y0 coordinate - * @param y1 y1 coordinate - * @param endcap0 0 = none, 1 = single pixel, 2 = full cap - * @param endcap1 0 = none, 1 = single pixel, 2 = full cap - * @param mode 0 = black outline, white body, 1 = white outline, black body - * @param mmode 0 = clear, 1 = set, 2 = toggle - */ -void write_vline_outlined(unsigned int x, unsigned int y0, unsigned int y1, int endcap0, int endcap1, int mode, int mmode) -{ - int stroke, fill; - if(y0 > y1) - { - SWAP(y0, y1); - } - SETUP_STROKE_FILL(stroke, fill, mode); - // Draw the main body of the line. - write_vline_lm(x - 1, y0 + 1, y1 - 1, stroke, mmode); - write_vline_lm(x + 1, y0 + 1, y1 - 1, stroke, mmode); - write_vline_lm(x, y0 + 1, y1 - 1, fill, mmode); - // Draw the endcaps, if any. - DRAW_ENDCAP_VLINE(endcap0, x, y0, stroke, fill, mmode); - DRAW_ENDCAP_VLINE(endcap1, x, y1, stroke, fill, mmode); -} - -/** - * write_filled_rectangle: draw a filled rectangle. - * - * Uses an optimised algorithm which is similar to the horizontal - * line writing algorithm, but optimised for writing the lines - * multiple times without recalculating lots of stuff. - * - * @param buff pointer to buffer to write in - * @param x x coordinate (left) - * @param y y coordinate (top) - * @param width rectangle width - * @param height rectangle height - * @param mode 0 = clear, 1 = set, 2 = toggle - */ -void write_filled_rectangle(uint8_t *buff, unsigned int x, unsigned int y, unsigned int width, unsigned int height, int mode) -{ - int yy, addr0_old, addr1_old; - CHECK_COORDS(x, y); - CHECK_COORD_X(x + width); - CHECK_COORD_Y(y + height); - if(width <= 0 || height <= 0) return; - // Calculate as if the rectangle was only a horizontal line. We then - // step these addresses through each row until we iterate `height` times. - int addr0 = CALC_BUFF_ADDR(x, y); - int addr1 = CALC_BUFF_ADDR(x + width, y); - int addr0_bit = CALC_BIT_IN_WORD(x); - int addr1_bit = CALC_BIT_IN_WORD(x + width); - int mask, mask_l, mask_r, i; - // If the addresses are equal, we need to write one word vertically. - if(addr0 == addr1) - { - mask = COMPUTE_HLINE_ISLAND_MASK(addr0_bit, addr1_bit); - while(height--) - { - WRITE_WORD_MODE(buff, addr0, mask, mode); - addr0 += GRAPHICS_WIDTH_REAL / 8; - } - } - // Otherwise we need to write the edges and then the middle repeatedly. - else - { - mask_l = COMPUTE_HLINE_EDGE_L_MASK(addr0_bit); - mask_r = COMPUTE_HLINE_EDGE_R_MASK(addr1_bit); - // Write edges first. - yy = 0; - addr0_old = addr0; - addr1_old = addr1; - while(yy < height) - { - WRITE_WORD_MODE(buff, addr0, mask_l, mode); - WRITE_WORD_MODE(buff, addr1, mask_r, mode); - addr0 += GRAPHICS_WIDTH_REAL / 8; - addr1 += GRAPHICS_WIDTH_REAL / 8; - yy++; - } - // Now write 0xffff words from start+1 to end-1 for each row. - yy = 0; - addr0 = addr0_old; - addr1 = addr1_old; - while(yy < height) - { - for(i = addr0 + 1; i <= addr1 - 1; i++) - { - uint8_t m=0xff; - WRITE_WORD_MODE(buff, i, m, mode); - } - addr0 += GRAPHICS_WIDTH_REAL / 8; - addr1 += GRAPHICS_WIDTH_REAL / 8; - yy++; - } - } -} - -/** - * write_filled_rectangle_lm: draw a filled rectangle on both draw buffers. - * - * @param x x coordinate (left) - * @param y y coordinate (top) - * @param width rectangle width - * @param height rectangle height - * @param lmode 0 = clear, 1 = set, 2 = toggle - * @param mmode 0 = clear, 1 = set, 2 = toggle - */ -void write_filled_rectangle_lm(unsigned int x, unsigned int y, unsigned int width, unsigned int height, int lmode, int mmode) -{ - write_filled_rectangle(draw_buffer_mask, x, y, width, height, mmode); - write_filled_rectangle(draw_buffer_level, x, y, width, height, lmode); -} - -/** - * write_rectangle_outlined: draw an outline of a rectangle. Essentially - * a convenience wrapper for draw_hline_outlined and draw_vline_outlined. - * - * @param x x coordinate (left) - * @param y y coordinate (top) - * @param width rectangle width - * @param height rectangle height - * @param mode 0 = black outline, white body, 1 = white outline, black body - * @param mmode 0 = clear, 1 = set, 2 = toggle - */ -void write_rectangle_outlined(unsigned int x, unsigned int y, int width, int height, int mode, int mmode) -{ - //CHECK_COORDS(x, y); - //CHECK_COORDS(x + width, y + height); - //if((x + width) > DISP_WIDTH) width = DISP_WIDTH - x; - //if((y + height) > DISP_HEIGHT) height = DISP_HEIGHT - y; - write_hline_outlined(x, x + width, y, ENDCAP_ROUND, ENDCAP_ROUND, mode, mmode); - write_hline_outlined(x, x + width, y + height, ENDCAP_ROUND, ENDCAP_ROUND, mode, mmode); - write_vline_outlined(x, y, y + height, ENDCAP_ROUND, ENDCAP_ROUND, mode, mmode); - write_vline_outlined(x + width, y, y + height, ENDCAP_ROUND, ENDCAP_ROUND, mode, mmode); -} - -/** - * write_circle: draw the outline of a circle on a given buffer, - * with an optional dash pattern for the line instead of a normal line. - * - * @param buff pointer to buffer to write in - * @param cx origin x coordinate - * @param cy origin y coordinate - * @param r radius - * @param dashp dash period (pixels) - zero for no dash - * @param mode 0 = clear, 1 = set, 2 = toggle - */ -void write_circle(uint8_t *buff, unsigned int cx, unsigned int cy, unsigned int r, unsigned int dashp, int mode) -{ - CHECK_COORDS(cx, cy); - int error = -r, x = r, y = 0; - while(x >= y) - { - if(dashp == 0 || (y % dashp) < (dashp / 2)) - { - CIRCLE_PLOT_8(buff, cx, cy, x, y, mode); - } - error += (y * 2) + 1; - y++; - if(error >= 0) - { - --x; - error -= x * 2; - } - } -} - -/** - * write_circle_outlined: draw an outlined circle on the draw buffer. - * - * @param cx origin x coordinate - * @param cy origin y coordinate - * @param r radius - * @param dashp dash period (pixels) - zero for no dash - * @param bmode 0 = 4-neighbour border, 1 = 8-neighbour border - * @param mode 0 = black outline, white body, 1 = white outline, black body - * @param mmode 0 = clear, 1 = set, 2 = toggle - */ -void write_circle_outlined(unsigned int cx, unsigned int cy, unsigned int r, unsigned int dashp, int bmode, int mode, int mmode) -{ - int stroke, fill; - CHECK_COORDS(cx, cy); - SETUP_STROKE_FILL(stroke, fill, mode); - // This is a two step procedure. First, we draw the outline of the - // circle, then we draw the inner part. - int error = -r, x = r, y = 0; - while(x >= y) - { - if(dashp == 0 || (y % dashp) < (dashp / 2)) - { - CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x + 1, y, mmode); - CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x + 1, y, stroke); - CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x, y + 1, mmode); - CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x, y + 1, stroke); - CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x - 1, y, mmode); - CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x - 1, y, stroke); - CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x, y - 1, mmode); - CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x, y - 1, stroke); - if(bmode == 1) - { - CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x + 1, y + 1, mmode); - CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x + 1, y + 1, stroke); - CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x - 1, y - 1, mmode); - CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x - 1, y - 1, stroke); - } - } - error += (y * 2) + 1; - y++; - if(error >= 0) - { - --x; - error -= x * 2; - } - } - error = -r; - x = r; - y = 0; - while(x >= y) - { - if(dashp == 0 || (y % dashp) < (dashp / 2)) - { - CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x, y, mmode); - CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x, y, fill); - } - error += (y * 2) + 1; - y++; - if(error >= 0) - { - --x; - error -= x * 2; - } - } -} - -/** - * write_circle_filled: fill a circle on a given buffer. - * - * @param buff pointer to buffer to write in - * @param cx origin x coordinate - * @param cy origin y coordinate - * @param r radius - * @param mode 0 = clear, 1 = set, 2 = toggle - */ -void write_circle_filled(uint8_t *buff, unsigned int cx, unsigned int cy, unsigned int r, int mode) -{ - CHECK_COORDS(cx, cy); - int error = -r, x = r, y = 0, xch = 0; - // It turns out that filled circles can take advantage of the midpoint - // circle algorithm. We simply draw very fast horizontal lines across each - // pair of X,Y coordinates. In some cases, this can even be faster than - // drawing an outlined circle! - // - // Due to multiple writes to each set of pixels, we have a special exception - // for when using the toggling draw mode. - while(x >= y) - { - if(y != 0) - { - write_hline(buff, cx - x, cx + x, cy + y, mode); - write_hline(buff, cx - x, cx + x, cy - y, mode); - if(mode != 2 || (mode == 2 && xch && (cx - x) != (cx - y))) - { - write_hline(buff, cx - y, cx + y, cy + x, mode); - write_hline(buff, cx - y, cx + y, cy - x, mode); - xch = 0; - } - } - error += (y * 2) + 1; - y++; - if(error >= 0) - { - --x; - xch = 1; - error -= x * 2; - } - } - // Handle toggle mode. - if(mode == 2) - { - write_hline(buff, cx - r, cx + r, cy, mode); - } -} - -/** - * write_line: Draw a line of arbitrary angle. - * - * @param buff pointer to buffer to write in - * @param x0 first x coordinate - * @param y0 first y coordinate - * @param x1 second x coordinate - * @param y1 second y coordinate - * @param mode 0 = clear, 1 = set, 2 = toggle - */ -void write_line(uint8_t *buff, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int mode) -{ - // Based on http://en.wikipedia.org/wiki/Bresenham%27s_line_algorithm - int steep = abs(y1 - y0) > abs(x1 - x0); - if(steep) - { - SWAP(x0, y0); - SWAP(x1, y1); - } - if(x0 > x1) - { - SWAP(x0, x1); - SWAP(y0, y1); - } - int deltax = x1 - x0; - int deltay = abs(y1 - y0); - int error = deltax / 2; - int ystep; - int y = y0; - int x; //, lasty = y, stox = 0; - if(y0 < y1) - ystep = 1; - else - ystep = -1; - for(x = x0; x < x1; x++) - { - if(steep) - { - write_pixel(buff, y, x, mode); - } - else - { - write_pixel(buff, x, y, mode); - } - error -= deltay; - if(error < 0) - { - y += ystep; - error += deltax; - } - } -} - -/** - * write_line_lm: Draw a line of arbitrary angle. - * - * @param x0 first x coordinate - * @param y0 first y coordinate - * @param x1 second x coordinate - * @param y1 second y coordinate - * @param mmode 0 = clear, 1 = set, 2 = toggle - * @param lmode 0 = clear, 1 = set, 2 = toggle - */ -void write_line_lm(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int mmode, int lmode) -{ - write_line(draw_buffer_mask, x0, y0, x1, y1, mmode); - write_line(draw_buffer_level, x0, y0, x1, y1, lmode); -} - -/** - * write_line_outlined: Draw a line of arbitrary angle, with an outline. - * - * @param buff pointer to buffer to write in - * @param x0 first x coordinate - * @param y0 first y coordinate - * @param x1 second x coordinate - * @param y1 second y coordinate - * @param endcap0 0 = none, 1 = single pixel, 2 = full cap - * @param endcap1 0 = none, 1 = single pixel, 2 = full cap - * @param mode 0 = black outline, white body, 1 = white outline, black body - * @param mmode 0 = clear, 1 = set, 2 = toggle - */ -void write_line_outlined(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int endcap0, int endcap1, int mode, int mmode) -{ - // Based on http://en.wikipedia.org/wiki/Bresenham%27s_line_algorithm - // This could be improved for speed. - int omode, imode; - if(mode == 0) - { - omode = 0; - imode = 1; - } - else - { - omode = 1; - imode = 0; - } - int steep = abs(y1 - y0) > abs(x1 - x0); - if(steep) - { - SWAP(x0, y0); - SWAP(x1, y1); - } - if(x0 > x1) - { - SWAP(x0, x1); - SWAP(y0, y1); - } - int deltax = x1 - x0; - int deltay = abs(y1 - y0); - int error = deltax / 2; - int ystep; - int y = y0; - int x; - if(y0 < y1) - ystep = 1; - else - ystep = -1; - // Draw the outline. - for(x = x0; x < x1; x++) - { - if(steep) - { - write_pixel_lm(y - 1, x, mmode, omode); - write_pixel_lm(y + 1, x, mmode, omode); - write_pixel_lm(y, x - 1, mmode, omode); - write_pixel_lm(y, x + 1, mmode, omode); - } - else - { - write_pixel_lm(x - 1, y, mmode, omode); - write_pixel_lm(x + 1, y, mmode, omode); - write_pixel_lm(x, y - 1, mmode, omode); - write_pixel_lm(x, y + 1, mmode, omode); - } - error -= deltay; - if(error < 0) - { - y += ystep; - error += deltax; - } - } - // Now draw the innards. - error = deltax / 2; - y = y0; - for(x = x0; x < x1; x++) - { - if(steep) - { - write_pixel_lm(y, x, mmode, imode); - } - else - { - write_pixel_lm(x, y, mmode, imode); - } - error -= deltay; - if(error < 0) - { - y += ystep; - error += deltax; - } - } -} - -/** - * write_word_misaligned: Write a misaligned word across two addresses - * with an x offset. - * - * This allows for many pixels to be set in one write. - * - * @param buff buffer to write in - * @param word word to write (16 bits) - * @param addr address of first word - * @param xoff x offset (0-15) - * @param mode 0 = clear, 1 = set, 2 = toggle - */ -void write_word_misaligned(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff, int mode) -{ - uint16_t firstmask = word >> xoff; - uint16_t lastmask = word << (16 - xoff); - WRITE_WORD_MODE(buff, addr+1, firstmask && 0x00ff, mode); - WRITE_WORD_MODE(buff, addr, (firstmask & 0xff00) >> 8, mode); - if(xoff > 0) - WRITE_WORD_MODE(buff, addr+2, (lastmask & 0xff00) >> 8, mode); -} - -/** - * write_word_misaligned_NAND: Write a misaligned word across two addresses - * with an x offset, using a NAND mask. - * - * This allows for many pixels to be set in one write. - * - * @param buff buffer to write in - * @param word word to write (16 bits) - * @param addr address of first word - * @param xoff x offset (0-15) - * - * This is identical to calling write_word_misaligned with a mode of 0 but - * it doesn't go through a lot of switch logic which slows down text writing - * a lot. - */ -void write_word_misaligned_NAND(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff) -{ - uint16_t firstmask = word >> xoff; - uint16_t lastmask = word << (16 - xoff); - WRITE_WORD_NAND(buff, addr+1, firstmask & 0x00ff); - WRITE_WORD_NAND(buff, addr, (firstmask & 0xff00) >> 8); - if(xoff > 0) - WRITE_WORD_NAND(buff, addr+2, (lastmask & 0xff00) >> 8); -} - -/** - * write_word_misaligned_OR: Write a misaligned word across two addresses - * with an x offset, using an OR mask. - * - * This allows for many pixels to be set in one write. - * - * @param buff buffer to write in - * @param word word to write (16 bits) - * @param addr address of first word - * @param xoff x offset (0-15) - * - * This is identical to calling write_word_misaligned with a mode of 1 but - * it doesn't go through a lot of switch logic which slows down text writing - * a lot. - */ -void write_word_misaligned_OR(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff) -{ - uint16_t firstmask = word >> xoff; - uint16_t lastmask = word << (16 - xoff); - WRITE_WORD_OR(buff, addr+1, firstmask & 0x00ff); - WRITE_WORD_OR(buff, addr, (firstmask & 0xff00) >> 8); - if(xoff > 0) - WRITE_WORD_OR(buff, addr + 2, (lastmask & 0xff00) >> 8); - -} - -/** - * write_word_misaligned_lm: Write a misaligned word across two - * words, in both level and mask buffers. This is core to the text - * writing routines. - * - * @param buff buffer to write in - * @param word word to write (16 bits) - * @param addr address of first word - * @param xoff x offset (0-15) - * @param lmode 0 = clear, 1 = set, 2 = toggle - * @param mmode 0 = clear, 1 = set, 2 = toggle - */ -void write_word_misaligned_lm(uint16_t wordl, uint16_t wordm, unsigned int addr, unsigned int xoff, int lmode, int mmode) -{ - write_word_misaligned(draw_buffer_level, wordl, addr, xoff, lmode); - write_word_misaligned(draw_buffer_mask, wordm, addr, xoff, mmode); -} - -/** - * fetch_font_info: Fetch font info structs. - * - * @param ch character - * @param font font id - */ -int fetch_font_info(uint8_t ch, int font, struct FontEntry *font_info, char *lookup) -{ - // First locate the font struct. - if(font > SIZEOF_ARRAY(fonts)) - return 0; // font does not exist, exit.*/ - // Load the font info; IDs are always sequential. - *font_info = fonts[font]; - // Locate character in font lookup table. (If required.) - if(lookup != NULL) - { - *lookup = font_info->lookup[ch]; - if(*lookup == 0xff) - return 0; // character doesn't exist, don't bother writing it. - } - return 1; -} - - -/** - * write_char16: Draw a character on the current draw buffer. - * Currently supports outlined characters and characters with - * a width of up to 8 pixels. - * - * @param ch character to write - * @param x x coordinate (left) - * @param y y coordinate (top) - * @param flags flags to write with (see gfx.h) - * @param font font to use - */ -void write_char16(char ch, unsigned int x, unsigned int y, int font) -{ - int yy, addr_temp, row, row_temp, xshift; - uint16_t and_mask, or_mask, level_bits; - struct FontEntry font_info; - //char lookup = 0; - fetch_font_info(0, font, &font_info, NULL); - - // Compute starting address (for x,y) of character. - int addr = CALC_BUFF_ADDR(x, y); - int wbit = CALC_BIT_IN_WORD(x); - // If font only supports lowercase or uppercase, make the letter - // lowercase or uppercase. - // How big is the character? We handle characters up to 8 pixels - // wide for now. Support for large characters may be added in future. - { - // Ensure we don't overflow. - if(x + wbit > GRAPHICS_WIDTH_REAL) - return; - // Load data pointer. - row = ch * font_info.height; - row_temp = row; - addr_temp = addr; - xshift = 16 - font_info.width; - // We can write mask words easily. - for(yy = y; yy < y + font_info.height; yy++) - { - if(font==3) - write_word_misaligned_OR(draw_buffer_mask, font_mask12x18[row] << xshift, addr, wbit); - else - write_word_misaligned_OR(draw_buffer_mask, font_mask8x10[row] << xshift, addr, wbit); - addr += GRAPHICS_WIDTH_REAL / 8; - row++; - } - // Level bits are more complicated. We need to set or clear - // level bits, but only where the mask bit is set; otherwise, - // we need to leave them alone. To do this, for each word, we - // construct an AND mask and an OR mask, and apply each individually. - row = row_temp; - addr = addr_temp; - for(yy = y; yy < y + font_info.height; yy++) - { - if(font==3) - { - level_bits = font_frame12x18[row]; - //if(!(flags & FONT_INVERT)) // data is normally inverted - level_bits = ~level_bits; - or_mask = font_mask12x18[row] << xshift; - and_mask = (font_mask12x18[row] & level_bits) << xshift; - } else { - level_bits = font_frame8x10[row]; - //if(!(flags & FONT_INVERT)) // data is normally inverted - level_bits = ~level_bits; - or_mask = font_mask8x10[row] << xshift; - and_mask = (font_mask8x10[row] & level_bits) << xshift; - } - write_word_misaligned_OR(draw_buffer_level, or_mask, addr, wbit); - // If we're not bold write the AND mask. - //if(!(flags & FONT_BOLD)) - write_word_misaligned_NAND(draw_buffer_level, and_mask, addr, wbit); - addr += GRAPHICS_WIDTH_REAL / 8; - row++; - } - } -} - - - -/** - * write_char: Draw a character on the current draw buffer. - * Currently supports outlined characters and characters with - * a width of up to 8 pixels. - * - * @param ch character to write - * @param x x coordinate (left) - * @param y y coordinate (top) - * @param flags flags to write with (see gfx.h) - * @param font font to use - */ -void write_char(char ch, unsigned int x, unsigned int y, int flags, int font) -{ - int yy, addr_temp, row, row_temp, xshift; - uint16_t and_mask, or_mask, level_bits; - struct FontEntry font_info; - char lookup = 0; - fetch_font_info(ch, font, &font_info, &lookup); - // Compute starting address (for x,y) of character. - int addr = CALC_BUFF_ADDR(x, y); - int wbit = CALC_BIT_IN_WORD(x); - // If font only supports lowercase or uppercase, make the letter - // lowercase or uppercase. - /*if(font_info.flags & FONT_LOWERCASE_ONLY) - ch = tolower(ch); - if(font_info.flags & FONT_UPPERCASE_ONLY) - ch = toupper(ch);*/ - fetch_font_info(ch, font, &font_info, &lookup); - // How big is the character? We handle characters up to 8 pixels - // wide for now. Support for large characters may be added in future. - if(font_info.width <= 8) - { - // Ensure we don't overflow. - if(x + wbit > GRAPHICS_WIDTH_REAL) - return; - // Load data pointer. - row = lookup * font_info.height * 2; - row_temp = row; - addr_temp = addr; - xshift = 16 - font_info.width; - // We can write mask words easily. - for(yy = y; yy < y + font_info.height; yy++) - { - write_word_misaligned_OR(draw_buffer_mask, font_info.data[row] << xshift, addr, wbit); - addr += GRAPHICS_WIDTH_REAL / 8; - row++; - } - // Level bits are more complicated. We need to set or clear - // level bits, but only where the mask bit is set; otherwise, - // we need to leave them alone. To do this, for each word, we - // construct an AND mask and an OR mask, and apply each individually. - row = row_temp; - addr = addr_temp; - for(yy = y; yy < y + font_info.height; yy++) - { - level_bits = font_info.data[row + font_info.height]; - if(!(flags & FONT_INVERT)) // data is normally inverted - level_bits = ~level_bits; - or_mask = font_info.data[row] << xshift; - and_mask = (font_info.data[row] & level_bits) << xshift; - write_word_misaligned_OR(draw_buffer_level, or_mask, addr, wbit); - // If we're not bold write the AND mask. - //if(!(flags & FONT_BOLD)) - write_word_misaligned_NAND(draw_buffer_level, and_mask, addr, wbit); - addr += GRAPHICS_WIDTH_REAL / 8; - row++; - } - } -} - -/** -* calc_text_dimensions: Calculate the dimensions of a -* string in a given font. Supports new lines and -* carriage returns in text. -* -* @param str string to calculate dimensions of -* @param font_info font info structure -* @param xs horizontal spacing -* @param ys vertical spacing -* @param dim return result: struct FontDimensions -*/ -void calc_text_dimensions(char *str, struct FontEntry font, int xs, int ys, struct FontDimensions *dim) -{ - int max_length = 0, line_length = 0, lines = 1; - while(*str != 0) - { - line_length++; - if(*str == '\n' || *str == '\r') - { - if(line_length > max_length) - max_length = line_length; - line_length = 0; - lines++; - } - str++; - } - if(line_length > max_length) - max_length = line_length; - dim->width = max_length * (font.width + xs); - dim->height = lines * (font.height + ys); -} - -/** -* write_string: Draw a string on the screen with certain -* alignment parameters. -* -* @param str string to write -* @param x x coordinate -* @param y y coordinate -* @param xs horizontal spacing -* @param ys horizontal spacing -* @param va vertical align -* @param ha horizontal align -* @param flags flags (passed to write_char) -* @param font font -*/ -void write_string(char *str, unsigned int x, unsigned int y, unsigned int xs, unsigned int ys, int va, int ha, int flags, int font) -{ - int xx = 0, yy = 0, xx_original = 0; - struct FontEntry font_info; - struct FontDimensions dim; - // Determine font info and dimensions/position of the string. - fetch_font_info(0, font, &font_info, NULL); - calc_text_dimensions(str, font_info, xs, ys, &dim); - switch(va) - { - case TEXT_VA_TOP: yy = y; break; - case TEXT_VA_MIDDLE: yy = y - (dim.height / 2); break; - case TEXT_VA_BOTTOM: yy = y - dim.height; break; - } - switch(ha) - { - case TEXT_HA_LEFT: xx = x; break; - case TEXT_HA_CENTER: xx = x - (dim.width / 2); break; - case TEXT_HA_RIGHT: xx = x - dim.width; break; - } - // Then write each character. - xx_original = xx; - while(*str != 0) - { - if(*str == '\n' || *str == '\r') - { - yy += ys + font_info.height; - xx = xx_original; - } - else - { - if(xx >= 0 && xx < GRAPHICS_WIDTH_REAL) - { - if(font_info.id<2) - write_char(*str, xx, yy, flags, font); - else - write_char16(*str, xx, yy, font); - } - xx += font_info.width + xs; - } - str++; - } -} - -/** -* write_string_formatted: Draw a string with format escape -* sequences in it. Allows for complex text effects. -* -* @param str string to write (with format data) -* @param x x coordinate -* @param y y coordinate -* @param xs default horizontal spacing -* @param ys default horizontal spacing -* @param va vertical align -* @param ha horizontal align -* @param flags flags (passed to write_char) -*/ -void write_string_formatted(char *str, unsigned int x, unsigned int y, unsigned int xs, unsigned int ys, int va, int ha, int flags) -{ - int fcode = 0, fptr = 0, font = 0, fwidth = 0, fheight = 0, xx = x, yy = y, max_xx = 0, max_height = 0; - struct FontEntry font_info; - // Retrieve sizes of the fonts: bigfont and smallfont. - fetch_font_info(0, 0, &font_info, NULL); - int smallfontwidth = font_info.width, smallfontheight = font_info.height; - fetch_font_info(0, 1, &font_info, NULL); - int bigfontwidth = font_info.width, bigfontheight = font_info.height; - // 11 byte stack with last byte as NUL. - char fstack[11]; - fstack[10] = '\0'; - // First, we need to parse the string for format characters and - // work out a bounding box. We'll parse again for the final output. - // This is a simple state machine parser. - char *ostr = str; - while(*str) - { - if(*str == '<' && fcode == 1) // escape code: skip - fcode = 0; - if(*str == '<' && fcode == 0) // begin format code? - { - fcode = 1; - fptr = 0; - } - if(*str == '>' && fcode == 1) - { - fcode = 0; - if(strcmp(fstack, "B")) // switch to "big" font (font #1) - { - fwidth = bigfontwidth; - fheight = bigfontheight; - } - else if(strcmp(fstack, "S")) // switch to "small" font (font #0) - { - fwidth = smallfontwidth; - fheight = smallfontheight; - } - if(fheight > max_height) - max_height = fheight; - // Skip over this byte. Go to next byte. - str++; - continue; - } - if(*str != '<' && *str != '>' && fcode == 1) - { - // Add to the format stack (up to 10 bytes.) - if(fptr > 10) // stop adding bytes - { - str++; // go to next byte - continue; - } - fstack[fptr++] = *str; - fstack[fptr] = '\0'; // clear next byte (ready for next char or to terminate string.) - } - if(fcode == 0) - { - // Not a format code, raw text. - xx += fwidth + xs; - if(*str == '\n') - { - if(xx > max_xx) - max_xx = xx; - xx = x; - yy += fheight + ys; - } - } - str++; - } - // Reset string pointer. - str = ostr; - // Now we've parsed it and got a bbox, we need to work out the dimensions of it - // and how to align it. - /*int width = max_xx - x; - int height = yy - y; - int ay, ax; - switch(va) - { - case TEXT_VA_TOP: ay = yy; break; - case TEXT_VA_MIDDLE: ay = yy - (height / 2); break; - case TEXT_VA_BOTTOM: ay = yy - height; break; - } - switch(ha) - { - case TEXT_HA_LEFT: ax = x; break; - case TEXT_HA_CENTER: ax = x - (width / 2); break; - case TEXT_HA_RIGHT: ax = x - width; break; - }*/ - // So ax,ay is our new text origin. Parse the text format again and paint - // the text on the display. - fcode = 0; - fptr = 0; - font = 0; - xx = 0; - yy = 0; - while(*str) - { - if(*str == '<' && fcode == 1) // escape code: skip - fcode = 0; - if(*str == '<' && fcode == 0) // begin format code? - { - fcode = 1; - fptr = 0; - } - if(*str == '>' && fcode == 1) - { - fcode = 0; - if(strcmp(fstack, "B")) // switch to "big" font (font #1) - { - fwidth = bigfontwidth; - fheight = bigfontheight; - font = 1; - } - else if(strcmp(fstack, "S")) // switch to "small" font (font #0) - { - fwidth = smallfontwidth; - fheight = smallfontheight; - font = 0; - } - // Skip over this byte. Go to next byte. - str++; - continue; - } - if(*str != '<' && *str != '>' && fcode == 1) - { - // Add to the format stack (up to 10 bytes.) - if(fptr > 10) // stop adding bytes - { - str++; // go to next byte - continue; - } - fstack[fptr++] = *str; - fstack[fptr] = '\0'; // clear next byte (ready for next char or to terminate string.) - } - if(fcode == 0) - { - // Not a format code, raw text. So we draw it. - // TODO - different font sizes. - write_char(*str, xx, yy + (max_height - fheight), flags, font); - xx += fwidth + xs; - if(*str == '\n') - { - if(xx > max_xx) - max_xx = xx; - xx = x; - yy += fheight + ys; - } - } - str++; - } -} - - -//SUPEROSD- - - -// graphics - -void drawAttitude(uint16_t x, uint16_t y, int16_t pitch, int16_t roll, uint16_t size) -{ - int16_t a = mySin(roll+360); - int16_t b = myCos(roll+360); - int16_t c = mySin(roll+90+360)*5/100; - int16_t d = myCos(roll+90+360)*5/100; - - int16_t k; - int16_t l; - - int16_t indi30x1=myCos(30)*(size/2+1) / 100; - int16_t indi30y1=mySin(30)*(size/2+1) / 100; - - int16_t indi30x2=myCos(30)*(size/2+4) / 100; - int16_t indi30y2=mySin(30)*(size/2+4) / 100; - - int16_t indi60x1=myCos(60)*(size/2+1) / 100; - int16_t indi60y1=mySin(60)*(size/2+1) / 100; - - int16_t indi60x2=myCos(60)*(size/2+4) / 100; - int16_t indi60y2=mySin(60)*(size/2+4) / 100; - - pitch=pitch%90; - if(pitch>90) - { - pitch=pitch-90; - } - if(pitch<-90) - { - pitch=pitch+90; - } - a = (a * (size/2)) / 100; - b = (b * (size/2)) / 100; - - if(roll<-90 || roll>90) - pitch=pitch*-1; - k = a*pitch/90; - l = b*pitch/90; - - // scale - //0 - //drawLine((x)-1-(size/2+4), (y)-1, (x)-1 - (size/2+1), (y)-1); - //drawLine((x)-1+(size/2+4), (y)-1, (x)-1 + (size/2+1), (y)-1); - write_line_outlined((x)-1-(size/2+4), (y)-1, (x)-1 - (size/2+1), (y)-1,0,0,0,1); - write_line_outlined((x)-1+(size/2+4), (y)-1, (x)-1 + (size/2+1), (y)-1,0,0,0,1); - - //30 - //drawLine((x)-1+indi30x1, (y)-1-indi30y1, (x)-1 + indi30x2, (y)-1 - indi30y2); - //drawLine((x)-1-indi30x1, (y)-1-indi30y1, (x)-1 - indi30x2, (y)-1 - indi30y2); - write_line_outlined((x)-1+indi30x1, (y)-1-indi30y1, (x)-1 + indi30x2, (y)-1 - indi30y2,0,0,0,1); - write_line_outlined((x)-1-indi30x1, (y)-1-indi30y1, (x)-1 - indi30x2, (y)-1 - indi30y2,0,0,0,1); - //60 - //drawLine((x)-1+indi60x1, (y)-1-indi60y1, (x)-1 + indi60x2, (y)-1 - indi60y2); - //drawLine((x)-1-indi60x1, (y)-1-indi60y1, (x)-1 - indi60x2, (y)-1 - indi60y2); - write_line_outlined((x)-1+indi60x1, (y)-1-indi60y1, (x)-1 + indi60x2, (y)-1 - indi60y2,0,0,0,1); - write_line_outlined((x)-1-indi60x1, (y)-1-indi60y1, (x)-1 - indi60x2, (y)-1 - indi60y2,0,0,0,1); - //90 - //drawLine((x)-1, (y)-1-(size/2+4), (x)-1, (y)-1 - (size/2+1)); - write_line_outlined((x)-1, (y)-1-(size/2+4), (x)-1, (y)-1 - (size/2+1),0,0,0,1); - - - //roll - //drawLine((x)-1 - b, (y)-1 + a, (x)-1 + b, (y)-1 - a); //Direction line - write_line_outlined((x)-1 - b, (y)-1 + a, (x)-1 + b, (y)-1 - a,0,0,0,1); //Direction line - //"wingtips" - //drawLine((x)-1 - b, (y)-1 + a, (x)-1 - b + d, (y)-1 + a - c); - //drawLine((x)-1 + b + d, (y)-1 - a - c, (x)-1 + b, (y)-1 - a); - write_line_outlined((x)-1 - b, (y)-1 + a, (x)-1 - b + d, (y)-1 + a - c,0,0,0,1); - write_line_outlined((x)-1 + b + d, (y)-1 - a - c, (x)-1 + b, (y)-1 - a,0,0,0,1); - - //pitch - //drawLine((x)-1, (y)-1, (x)-1 - k, (y)-1 - l); - write_line_outlined((x)-1, (y)-1, (x)-1 - k, (y)-1 - l,0,0,0,1); - - - //drawCircle(x-1, y-1, 5); - //write_circle_outlined(x-1, y-1, 5,0,0,0,1); - //drawCircle(x-1, y-1, size/2+4); - //write_circle_outlined(x-1, y-1, size/2+4,0,0,0,1); -} - -void drawBattery(uint16_t x, uint16_t y, uint8_t battery, uint16_t size) -{ - int i=0; - int batteryLines; - //top - /*drawLine((x)-1+(size/2-size/4), (y)-1, (x)-1 + (size/2+size/4), (y)-1); - drawLine((x)-1+(size/2-size/4), (y)-1+1, (x)-1 + (size/2+size/4), (y)-1+1); - - drawLine((x)-1, (y)-1+2, (x)-1 + size, (y)-1+2); - //bottom - drawLine((x)-1, (y)-1+size*3, (x)-1 + size, (y)-1+size*3); - //left - drawLine((x)-1, (y)-1+2, (x)-1, (y)-1+size*3); - - //right - drawLine((x)-1+size, (y)-1+2, (x)-1+size, (y)-1+size*3);*/ - - write_rectangle_outlined((x)-1, (y)-1+2,size,size*3,0,1); - write_vline_lm((x)-1+(size/2+size/4)+1,(y)-2,(y)-1+1,0,1); - write_vline_lm((x)-1+(size/2-size/4)-1,(y)-2,(y)-1+1,0,1); - write_hline_lm((x)-1+(size/2-size/4),(x)-1 + (size/2+size/4),(y)-2,0,1); - write_hline_lm((x)-1+(size/2-size/4),(x)-1 + (size/2+size/4),(y)-1,1,1); - write_hline_lm((x)-1+(size/2-size/4),(x)-1 + (size/2+size/4),(y)-1+1,1,1); - - batteryLines = battery*(size*3-2)/100; - for(i=0;i= -1 && halign <= 1); - // Compute the position of the elements. - int majtick_start = 0, majtick_end = 0, mintick_start = 0, mintick_end = 0, boundtick_start = 0, boundtick_end = 0; - if(halign == -1) - { - majtick_start = x; - majtick_end = x + majtick_len; - mintick_start = x; - mintick_end = x + mintick_len; - boundtick_start = x; - boundtick_end = x + boundtick_len; - } - else if(halign == +1) - { - x=x-GRAPHICS_HDEADBAND; - majtick_start = GRAPHICS_WIDTH_REAL - x - 1; - majtick_end = GRAPHICS_WIDTH_REAL - x - majtick_len - 1; - mintick_start = GRAPHICS_WIDTH_REAL - x - 1; - mintick_end = GRAPHICS_WIDTH_REAL - x - mintick_len - 1; - boundtick_start = GRAPHICS_WIDTH_REAL - x - 1; - boundtick_end = GRAPHICS_WIDTH_REAL - x - boundtick_len - 1; - } - // Retrieve width of large font (font #0); from this calculate the x spacing. - fetch_font_info(0, 0, &font_info, NULL); - int arrow_len = (font_info.height / 2) + 1; // FIXME, font info being loaded correctly?? - int text_x_spacing = arrow_len; - int max_text_y = 0, text_length = 0; - int small_font_char_width = font_info.width + 1; // +1 for horizontal spacing = 1 - // For -(range / 2) to +(range / 2), draw the scale. - int range_2 = range / 2; //, height_2 = height / 2; - int r = 0, rr = 0, rv = 0, ys = 0, style = 0; //calc_ys = 0, - // Iterate through each step. - for(r = -range_2; r <= +range_2; r++) - { - style = 0; - rr = r + range_2 - v; // normalise range for modulo, subtract value to move ticker tape - rv = -rr + range_2; // for number display - if(flags & HUD_VSCALE_FLAG_NO_NEGATIVE) - rr += majtick_step / 2; - if(rr % majtick_step == 0) - style = 1; // major tick - else if(rr % mintick_step == 0) - style = 2; // minor tick - else - style = 0; - if(flags & HUD_VSCALE_FLAG_NO_NEGATIVE && rv < 0) - continue; - if(style) - { - // Calculate y position. - ys = ((long int)(r * height) / (long int)range) + y; - //sprintf(temp, "ys=%d", ys); - //con_puts(temp, 0); - // Depending on style, draw a minor or a major tick. - if(style == 1) - { - write_hline_outlined(majtick_start, majtick_end, ys, 2, 2, 0, 1); - memset(temp, ' ', 10); - //my_itoa(rv, temp); - sprintf(temp,"%d",rv); - text_length = (strlen(temp) + 1) * small_font_char_width; // add 1 for margin - if(text_length > max_text_y) - max_text_y = text_length; - if(halign == -1) - write_string(temp, majtick_end + text_x_spacing, ys, 1, 0, TEXT_VA_MIDDLE, TEXT_HA_LEFT, 0, 1); - else - write_string(temp, majtick_end - text_x_spacing + 1, ys, 1, 0, TEXT_VA_MIDDLE, TEXT_HA_RIGHT, 0, 1); - } - else if(style == 2) - write_hline_outlined(mintick_start, mintick_end, ys, 2, 2, 0, 1); - } - } - // Generate the string for the value, as well as calculating its dimensions. - memset(temp, ' ', 10); - //my_itoa(v, temp); - sprintf(temp,"%d",v); - // TODO: add auto-sizing. - calc_text_dimensions(temp, font_info, 1, 0, &dim); - int xx = 0, i = 0; - if(halign == -1) - xx = majtick_end + text_x_spacing; - else - xx = majtick_end - text_x_spacing; - // Draw an arrow from the number to the point. - for(i = 0; i < arrow_len; i++) - { - if(halign == -1) - { - write_pixel_lm(xx - arrow_len + i, y - i - 1, 1, 1); - write_pixel_lm(xx - arrow_len + i, y + i - 1, 1, 1); - write_hline_lm(xx + dim.width - 1, xx - arrow_len + i + 1, y - i - 1, 0, 1); - write_hline_lm(xx + dim.width - 1, xx - arrow_len + i + 1, y + i - 1, 0, 1); - } - else - { - write_pixel_lm(xx + arrow_len - i, y - i - 1, 1, 1); - write_pixel_lm(xx + arrow_len - i, y + i - 1, 1, 1); - write_hline_lm(xx - dim.width - 1, xx + arrow_len - i - 1, y - i - 1, 0, 1); - write_hline_lm(xx - dim.width - 1, xx + arrow_len - i - 1, y + i - 1, 0, 1); - } - // FIXME - // write_hline_lm(xx - dim.width - 1, xx + (arrow_len - i), y - i - 1, 1, 1); - // write_hline_lm(xx - dim.width - 1, xx + (arrow_len - i), y + i - 1, 1, 1); - } - if(halign == -1) - { - write_hline_lm(xx, xx + dim.width - 1, y - arrow_len, 1, 1); - write_hline_lm(xx, xx + dim.width - 1, y + arrow_len - 2, 1, 1); - write_vline_lm(xx + dim.width - 1, y - arrow_len, y + arrow_len - 2, 1, 1); - } - else - { - write_hline_lm(xx, xx - dim.width - 1, y - arrow_len, 1, 1); - write_hline_lm(xx, xx - dim.width - 1, y + arrow_len - 2, 1, 1); - write_vline_lm(xx - dim.width - 1, y - arrow_len, y + arrow_len - 2, 1, 1); - } - // Draw the text. - if(halign == -1) - write_string(temp, xx, y, 1, 0, TEXT_VA_MIDDLE, TEXT_HA_LEFT, 0, 0); - else - write_string(temp, xx, y, 1, 0, TEXT_VA_MIDDLE, TEXT_HA_RIGHT, 0, 0); - // Then, add a slow cut off on the edges, so the text doesn't sharply - // disappear. We simply clear the areas above and below the ticker, and we - // use little markers on the edges. - if(halign == -1) - { - write_filled_rectangle_lm(majtick_end + text_x_spacing, y + (height / 2) - (font_info.height / 2), max_text_y - boundtick_start, font_info.height, 0, 0); - write_filled_rectangle_lm(majtick_end + text_x_spacing, y - (height / 2) - (font_info.height / 2), max_text_y - boundtick_start, font_info.height, 0, 0); - } - else - { - write_filled_rectangle_lm(majtick_end - text_x_spacing - max_text_y, y + (height / 2) - (font_info.height / 2), max_text_y, font_info.height, 0, 0); - write_filled_rectangle_lm(majtick_end - text_x_spacing - max_text_y, y - (height / 2) - (font_info.height / 2), max_text_y, font_info.height, 0, 0); - } - write_hline_outlined(boundtick_start, boundtick_end, y + (height / 2), 2, 2, 0, 1); - write_hline_outlined(boundtick_start, boundtick_end, y - (height / 2), 2, 2, 0, 1); -} - -/** - * hud_draw_compass: Draw a compass. - * - * @param v value for the compass - * @param range range about value to display (+/- range/2 each direction) - * @param width length in pixels - * @param x x displacement (typ. half display width) - * @param y y displacement (typ. bottom of display) - * @param mintick_step how often a minor tick is shown - * @param majtick_step how often a major tick (heading "xx") is shown - * @param mintick_len minor tick length - * @param majtick_len major tick length - * @param flags special flags (see hud.h.) - */ -void hud_draw_linear_compass(int v, int range, int width, int x, int y, int mintick_step, int majtick_step, int mintick_len, int majtick_len, int flags) -{ - v %= 360; // wrap, just in case. - struct FontEntry font_info; - int majtick_start = 0, majtick_end = 0, mintick_start = 0, mintick_end = 0, textoffset = 0; - char headingstr[4]; - majtick_start = y; - majtick_end = y - majtick_len; - mintick_start = y; - mintick_end = y - mintick_len; - textoffset = 8; - int r, style, rr, xs; // rv, - int range_2 = range / 2; - for(r = -range_2; r <= +range_2; r++) - { - style = 0; - rr = (v + r + 360) % 360; // normalise range for modulo, add to move compass track - //rv = -rr + range_2; // for number display - if(rr % majtick_step == 0) - style = 1; // major tick - else if(rr % mintick_step == 0) - style = 2; // minor tick - if(style) - { - // Calculate x position. - xs = ((long int)(r * width) / (long int)range) + x; - // Draw it. - if(style == 1) - { - write_vline_outlined(xs, majtick_start, majtick_end, 2, 2, 0, 1); - // Draw heading above this tick. - // If it's not one of north, south, east, west, draw the heading. - // Otherwise, draw one of the identifiers. - if(rr % 90 != 0) - { - // We abbreviate heading to two digits. This has the side effect of being easy to compute. - headingstr[0] = '0' + (rr / 100); - headingstr[1] = '0' + ((rr / 10) % 10); - headingstr[2] = 0; - headingstr[3] = 0; // nul to terminate - } - else - { - switch(rr) - { - case 0: headingstr[0] = 'N'; break; - case 90: headingstr[0] = 'E'; break; - case 180: headingstr[0] = 'S'; break; - case 270: headingstr[0] = 'W'; break; - } - headingstr[1] = 0; - headingstr[2] = 0; - headingstr[3] = 0; - } - // +1 fudge...! - write_string(headingstr, xs + 1, majtick_start + textoffset, 1, 0, TEXT_VA_MIDDLE, TEXT_HA_CENTER, 0, 1); - } - else if(style == 2) - write_vline_outlined(xs, mintick_start, mintick_end, 2, 2, 0, 1); - } - } - // Then, draw a rectangle with the present heading in it. - // We want to cover up any other markers on the bottom. - // First compute font size. - fetch_font_info(0, 3, &font_info, NULL); - int text_width = (font_info.width + 1) * 3; - int rect_width = text_width + 2; - write_filled_rectangle_lm(x - (rect_width / 2), majtick_start + 2, rect_width, font_info.height + 2, 0, 1); - write_rectangle_outlined(x - (rect_width / 2), majtick_start + 2, rect_width, font_info.height + 2, 0, 1); - headingstr[0] = '0' + (v / 100); - headingstr[1] = '0' + ((v / 10) % 10); - headingstr[2] = '0' + (v % 10); - headingstr[3] = 0; - write_string(headingstr, x + 1, majtick_start + textoffset+2, 0, 0, TEXT_VA_MIDDLE, TEXT_HA_CENTER, 1, 3); -} -// CORE draw routines end here - -void draw_artificial_horizon(float angle, float pitch, int16_t l_x, int16_t l_y, int16_t size ) -{ - float alpha; - uint8_t vertical=0,horizontal=0; - int16_t x1,x2; - int16_t y1,y2; - int16_t refx,refy; - alpha=DEG2RAD(angle); - refx=l_x + size/2; - refy=l_y + size/2; - - // - float k=0; - float dx = sinf(alpha)*(pitch/90.0f*(size/2)); - float dy = cosf(alpha)*(pitch/90.0f*(size/2)); - int16_t x0 = (size/2)-dx; - int16_t y0 = (size/2)+dy; - // calculate the line function - if((angle != 90) && (angle != -90)) - { - k = tanf(alpha); - vertical = 0; - if(k==0) - { - horizontal=1; - } - } - else - { - vertical = 1; - } - - // crossing point of line - if(!vertical && !horizontal) - { - // y-y0=k(x-x0) - int16_t x=0; - int16_t y=k*(x-x0)+y0; - // find right crossing point - x1=x; - y1=y; - if(y<0) - { - y1=0; - x1=((y1-y0)+k*x0)/k; - } - if(y>size) - { - y1=size; - x1=((y1-y0)+k*x0)/k; - } - // left crossing point - x=size; - y=k*(x-x0)+y0; - x2=x; - y2=y; - if(y<0) - { - y2=0; - x2=((y2-y0)+k*x0)/k; - } - if(y>size) - { - y2=size; - x2=((y2-y0)+k*x0)/k; - } - // move to location - // horizon line - write_line_outlined(x1+l_x,y1+l_y,x2+l_x,y2+l_y,0,0,0,1); - //fill - if(angle<=0 && angle>-90) - { - //write_string("1", APPLY_HDEADBAND((GRAPHICS_RIGHT/2)),APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_CENTER, 0, 3); - for(int i=y2;isize) - x2=size; - if(x2<0) - x2=0; - write_hline_lm(x2+l_x,size+l_x,i+l_y,1,1); - } - } - else if(angle<-90) - { - //write_string("2", APPLY_HDEADBAND((GRAPHICS_RIGHT/2)),APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_CENTER, 0, 3); - for(int i=0;isize) - x2=size; - if(x2<0) - x2=0; - write_hline_lm(size+l_x,x2+l_x,i+l_y,1,1); - } - } - else if(angle>0 && angle<90) - { - //write_string("3", APPLY_HDEADBAND((GRAPHICS_RIGHT/2)),APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_CENTER, 0, 3); - for(int i=y1;isize) - x2=size; - if(x2<0) - x2=0; - write_hline_lm(0+l_x,x2+l_x,i+l_y,1,1); - } - } - else if(angle>90) - { - //write_string("4", APPLY_HDEADBAND((GRAPHICS_RIGHT/2)),APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_CENTER, 0, 3); - for(int i=0;isize) - x2=size; - if(x2<0) - x2=0; - write_hline_lm(x2+l_x,0+l_x,i+l_y,1,1); - } - } - } - else if(vertical) - { - // horizon line - write_line_outlined(x0+l_x,0+l_y,x0+l_x,size+l_y,0,0,0,1); - if(angle==90) - { - //write_string("5", APPLY_HDEADBAND((GRAPHICS_RIGHT/2)),APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_CENTER, 0, 3); - for(int i=0;i x1) + { + SWAP(x0, x1); + } + if(x0 == x1) return; + /* This is an optimised algorithm for writing horizontal lines. + * We begin by finding the addresses of the x0 and x1 points. */ + int addr0 = CALC_BUFF_ADDR(x0, y); + int addr1 = CALC_BUFF_ADDR(x1, y); + int addr0_bit = CALC_BIT_IN_WORD(x0); + int addr1_bit = CALC_BIT_IN_WORD(x1); + int mask, mask_l, mask_r, i; + /* If the addresses are equal, we only need to write one word + * which is an island. */ + if(addr0 == addr1) + { + mask = COMPUTE_HLINE_ISLAND_MASK(addr0_bit, addr1_bit); + WRITE_WORD_MODE(buff, addr0, mask, mode); + } + /* Otherwise we need to write the edges and then the middle. */ + else + { + mask_l = COMPUTE_HLINE_EDGE_L_MASK(addr0_bit); + mask_r = COMPUTE_HLINE_EDGE_R_MASK(addr1_bit); + WRITE_WORD_MODE(buff, addr0, mask_l, mode); + WRITE_WORD_MODE(buff, addr1, mask_r, mode); + // Now write 0xffff words from start+1 to end-1. + for(i = addr0 + 1; i <= addr1 - 1; i++) + { + uint8_t m=0xff; + WRITE_WORD_MODE(buff, i, m, mode); + } + } +} + +/** + * write_hline_lm: write both level and mask buffers. + * + * @param x0 x0 coordinate + * @param x1 x1 coordinate + * @param y y coordinate + * @param lmode 0 = clear, 1 = set, 2 = toggle + * @param mmode 0 = clear, 1 = set, 2 = toggle + */ +void write_hline_lm(unsigned int x0, unsigned int x1, unsigned int y, int lmode, int mmode) +{ + // TODO: an optimisation would compute the masks and apply to + // both buffers simultaneously. + write_hline(draw_buffer_level, x0, x1, y, lmode); + write_hline(draw_buffer_mask, x0, x1, y, mmode); +} + +/** + * write_hline_outlined: outlined horizontal line with varying endcaps + * Always uses draw buffer. + * + * @param x0 x0 coordinate + * @param x1 x1 coordinate + * @param y y coordinate + * @param endcap0 0 = none, 1 = single pixel, 2 = full cap + * @param endcap1 0 = none, 1 = single pixel, 2 = full cap + * @param mode 0 = black outline, white body, 1 = white outline, black body + * @param mmode 0 = clear, 1 = set, 2 = toggle + */ +void write_hline_outlined(unsigned int x0, unsigned int x1, unsigned int y, int endcap0, int endcap1, int mode, int mmode) +{ + int stroke, fill; + SETUP_STROKE_FILL(stroke, fill, mode) + if(x0 > x1) + { + SWAP(x0, x1); + } + // Draw the main body of the line. + write_hline_lm(x0 + 1, x1 - 1, y - 1, stroke, mmode); + write_hline_lm(x0 + 1, x1 - 1, y + 1, stroke, mmode); + write_hline_lm(x0 + 1, x1 - 1, y, fill, mmode); + // Draw the endcaps, if any. + DRAW_ENDCAP_HLINE(endcap0, x0, y, stroke, fill, mmode); + DRAW_ENDCAP_HLINE(endcap1, x1, y, stroke, fill, mmode); +} + +/** + * write_vline: optimised vertical line writing algorithm + * + * @param buff pointer to buffer to write in + * @param x x coordinate + * @param y0 y0 coordinate + * @param y1 y1 coordinate + * @param mode 0 = clear, 1 = set, 2 = toggle + */ +void write_vline(uint8_t *buff, unsigned int x, unsigned int y0, unsigned int y1, int mode) +{ + unsigned int a; + CLIP_COORDS(x, y0); + CLIP_COORDS(x, y1); + if(y0 > y1) + { + SWAP(y0, y1); + } + if(y0 == y1) return; + /* This is an optimised algorithm for writing vertical lines. + * We begin by finding the addresses of the x,y0 and x,y1 points. */ + int addr0 = CALC_BUFF_ADDR(x, y0); + int addr1 = CALC_BUFF_ADDR(x, y1); + /* Then we calculate the pixel data to be written. */ + int bitnum = CALC_BIT_IN_WORD(x); + uint16_t mask = 1 << (7 - bitnum); + /* Run from addr0 to addr1 placing pixels. Increment by the number + * of words n each graphics line. */ + for(a = addr0; a <= addr1; a += GRAPHICS_WIDTH_REAL / 8) + { + WRITE_WORD_MODE(buff, a, mask, mode); + } +} + +/** + * write_vline_lm: write both level and mask buffers. + * + * @param x x coordinate + * @param y0 y0 coordinate + * @param y1 y1 coordinate + * @param lmode 0 = clear, 1 = set, 2 = toggle + * @param mmode 0 = clear, 1 = set, 2 = toggle + */ +void write_vline_lm(unsigned int x, unsigned int y0, unsigned int y1, int lmode, int mmode) +{ + // TODO: an optimisation would compute the masks and apply to + // both buffers simultaneously. + write_vline(draw_buffer_level, x, y0, y1, lmode); + write_vline(draw_buffer_mask, x, y0, y1, mmode); +} + +/** + * write_vline_outlined: outlined vertical line with varying endcaps + * Always uses draw buffer. + * + * @param x x coordinate + * @param y0 y0 coordinate + * @param y1 y1 coordinate + * @param endcap0 0 = none, 1 = single pixel, 2 = full cap + * @param endcap1 0 = none, 1 = single pixel, 2 = full cap + * @param mode 0 = black outline, white body, 1 = white outline, black body + * @param mmode 0 = clear, 1 = set, 2 = toggle + */ +void write_vline_outlined(unsigned int x, unsigned int y0, unsigned int y1, int endcap0, int endcap1, int mode, int mmode) +{ + int stroke, fill; + if(y0 > y1) + { + SWAP(y0, y1); + } + SETUP_STROKE_FILL(stroke, fill, mode); + // Draw the main body of the line. + write_vline_lm(x - 1, y0 + 1, y1 - 1, stroke, mmode); + write_vline_lm(x + 1, y0 + 1, y1 - 1, stroke, mmode); + write_vline_lm(x, y0 + 1, y1 - 1, fill, mmode); + // Draw the endcaps, if any. + DRAW_ENDCAP_VLINE(endcap0, x, y0, stroke, fill, mmode); + DRAW_ENDCAP_VLINE(endcap1, x, y1, stroke, fill, mmode); +} + +/** + * write_filled_rectangle: draw a filled rectangle. + * + * Uses an optimised algorithm which is similar to the horizontal + * line writing algorithm, but optimised for writing the lines + * multiple times without recalculating lots of stuff. + * + * @param buff pointer to buffer to write in + * @param x x coordinate (left) + * @param y y coordinate (top) + * @param width rectangle width + * @param height rectangle height + * @param mode 0 = clear, 1 = set, 2 = toggle + */ +void write_filled_rectangle(uint8_t *buff, unsigned int x, unsigned int y, unsigned int width, unsigned int height, int mode) +{ + int yy, addr0_old, addr1_old; + CHECK_COORDS(x, y); + CHECK_COORD_X(x + width); + CHECK_COORD_Y(y + height); + if(width <= 0 || height <= 0) return; + // Calculate as if the rectangle was only a horizontal line. We then + // step these addresses through each row until we iterate `height` times. + int addr0 = CALC_BUFF_ADDR(x, y); + int addr1 = CALC_BUFF_ADDR(x + width, y); + int addr0_bit = CALC_BIT_IN_WORD(x); + int addr1_bit = CALC_BIT_IN_WORD(x + width); + int mask, mask_l, mask_r, i; + // If the addresses are equal, we need to write one word vertically. + if(addr0 == addr1) + { + mask = COMPUTE_HLINE_ISLAND_MASK(addr0_bit, addr1_bit); + while(height--) + { + WRITE_WORD_MODE(buff, addr0, mask, mode); + addr0 += GRAPHICS_WIDTH_REAL / 8; + } + } + // Otherwise we need to write the edges and then the middle repeatedly. + else + { + mask_l = COMPUTE_HLINE_EDGE_L_MASK(addr0_bit); + mask_r = COMPUTE_HLINE_EDGE_R_MASK(addr1_bit); + // Write edges first. + yy = 0; + addr0_old = addr0; + addr1_old = addr1; + while(yy < height) + { + WRITE_WORD_MODE(buff, addr0, mask_l, mode); + WRITE_WORD_MODE(buff, addr1, mask_r, mode); + addr0 += GRAPHICS_WIDTH_REAL / 8; + addr1 += GRAPHICS_WIDTH_REAL / 8; + yy++; + } + // Now write 0xffff words from start+1 to end-1 for each row. + yy = 0; + addr0 = addr0_old; + addr1 = addr1_old; + while(yy < height) + { + for(i = addr0 + 1; i <= addr1 - 1; i++) + { + uint8_t m=0xff; + WRITE_WORD_MODE(buff, i, m, mode); + } + addr0 += GRAPHICS_WIDTH_REAL / 8; + addr1 += GRAPHICS_WIDTH_REAL / 8; + yy++; + } + } +} + +/** + * write_filled_rectangle_lm: draw a filled rectangle on both draw buffers. + * + * @param x x coordinate (left) + * @param y y coordinate (top) + * @param width rectangle width + * @param height rectangle height + * @param lmode 0 = clear, 1 = set, 2 = toggle + * @param mmode 0 = clear, 1 = set, 2 = toggle + */ +void write_filled_rectangle_lm(unsigned int x, unsigned int y, unsigned int width, unsigned int height, int lmode, int mmode) +{ + write_filled_rectangle(draw_buffer_mask, x, y, width, height, mmode); + write_filled_rectangle(draw_buffer_level, x, y, width, height, lmode); +} + +/** + * write_rectangle_outlined: draw an outline of a rectangle. Essentially + * a convenience wrapper for draw_hline_outlined and draw_vline_outlined. + * + * @param x x coordinate (left) + * @param y y coordinate (top) + * @param width rectangle width + * @param height rectangle height + * @param mode 0 = black outline, white body, 1 = white outline, black body + * @param mmode 0 = clear, 1 = set, 2 = toggle + */ +void write_rectangle_outlined(unsigned int x, unsigned int y, int width, int height, int mode, int mmode) +{ + //CHECK_COORDS(x, y); + //CHECK_COORDS(x + width, y + height); + //if((x + width) > DISP_WIDTH) width = DISP_WIDTH - x; + //if((y + height) > DISP_HEIGHT) height = DISP_HEIGHT - y; + write_hline_outlined(x, x + width, y, ENDCAP_ROUND, ENDCAP_ROUND, mode, mmode); + write_hline_outlined(x, x + width, y + height, ENDCAP_ROUND, ENDCAP_ROUND, mode, mmode); + write_vline_outlined(x, y, y + height, ENDCAP_ROUND, ENDCAP_ROUND, mode, mmode); + write_vline_outlined(x + width, y, y + height, ENDCAP_ROUND, ENDCAP_ROUND, mode, mmode); +} + +/** + * write_circle: draw the outline of a circle on a given buffer, + * with an optional dash pattern for the line instead of a normal line. + * + * @param buff pointer to buffer to write in + * @param cx origin x coordinate + * @param cy origin y coordinate + * @param r radius + * @param dashp dash period (pixels) - zero for no dash + * @param mode 0 = clear, 1 = set, 2 = toggle + */ +void write_circle(uint8_t *buff, unsigned int cx, unsigned int cy, unsigned int r, unsigned int dashp, int mode) +{ + CHECK_COORDS(cx, cy); + int error = -r, x = r, y = 0; + while(x >= y) + { + if(dashp == 0 || (y % dashp) < (dashp / 2)) + { + CIRCLE_PLOT_8(buff, cx, cy, x, y, mode); + } + error += (y * 2) + 1; + y++; + if(error >= 0) + { + --x; + error -= x * 2; + } + } +} + +/** + * write_circle_outlined: draw an outlined circle on the draw buffer. + * + * @param cx origin x coordinate + * @param cy origin y coordinate + * @param r radius + * @param dashp dash period (pixels) - zero for no dash + * @param bmode 0 = 4-neighbour border, 1 = 8-neighbour border + * @param mode 0 = black outline, white body, 1 = white outline, black body + * @param mmode 0 = clear, 1 = set, 2 = toggle + */ +void write_circle_outlined(unsigned int cx, unsigned int cy, unsigned int r, unsigned int dashp, int bmode, int mode, int mmode) +{ + int stroke, fill; + CHECK_COORDS(cx, cy); + SETUP_STROKE_FILL(stroke, fill, mode); + // This is a two step procedure. First, we draw the outline of the + // circle, then we draw the inner part. + int error = -r, x = r, y = 0; + while(x >= y) + { + if(dashp == 0 || (y % dashp) < (dashp / 2)) + { + CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x + 1, y, mmode); + CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x + 1, y, stroke); + CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x, y + 1, mmode); + CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x, y + 1, stroke); + CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x - 1, y, mmode); + CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x - 1, y, stroke); + CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x, y - 1, mmode); + CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x, y - 1, stroke); + if(bmode == 1) + { + CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x + 1, y + 1, mmode); + CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x + 1, y + 1, stroke); + CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x - 1, y - 1, mmode); + CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x - 1, y - 1, stroke); + } + } + error += (y * 2) + 1; + y++; + if(error >= 0) + { + --x; + error -= x * 2; + } + } + error = -r; + x = r; + y = 0; + while(x >= y) + { + if(dashp == 0 || (y % dashp) < (dashp / 2)) + { + CIRCLE_PLOT_8(draw_buffer_mask, cx, cy, x, y, mmode); + CIRCLE_PLOT_8(draw_buffer_level, cx, cy, x, y, fill); + } + error += (y * 2) + 1; + y++; + if(error >= 0) + { + --x; + error -= x * 2; + } + } +} + +/** + * write_circle_filled: fill a circle on a given buffer. + * + * @param buff pointer to buffer to write in + * @param cx origin x coordinate + * @param cy origin y coordinate + * @param r radius + * @param mode 0 = clear, 1 = set, 2 = toggle + */ +void write_circle_filled(uint8_t *buff, unsigned int cx, unsigned int cy, unsigned int r, int mode) +{ + CHECK_COORDS(cx, cy); + int error = -r, x = r, y = 0, xch = 0; + // It turns out that filled circles can take advantage of the midpoint + // circle algorithm. We simply draw very fast horizontal lines across each + // pair of X,Y coordinates. In some cases, this can even be faster than + // drawing an outlined circle! + // + // Due to multiple writes to each set of pixels, we have a special exception + // for when using the toggling draw mode. + while(x >= y) + { + if(y != 0) + { + write_hline(buff, cx - x, cx + x, cy + y, mode); + write_hline(buff, cx - x, cx + x, cy - y, mode); + if(mode != 2 || (mode == 2 && xch && (cx - x) != (cx - y))) + { + write_hline(buff, cx - y, cx + y, cy + x, mode); + write_hline(buff, cx - y, cx + y, cy - x, mode); + xch = 0; + } + } + error += (y * 2) + 1; + y++; + if(error >= 0) + { + --x; + xch = 1; + error -= x * 2; + } + } + // Handle toggle mode. + if(mode == 2) + { + write_hline(buff, cx - r, cx + r, cy, mode); + } +} + +/** + * write_line: Draw a line of arbitrary angle. + * + * @param buff pointer to buffer to write in + * @param x0 first x coordinate + * @param y0 first y coordinate + * @param x1 second x coordinate + * @param y1 second y coordinate + * @param mode 0 = clear, 1 = set, 2 = toggle + */ +void write_line(uint8_t *buff, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int mode) +{ + // Based on http://en.wikipedia.org/wiki/Bresenham%27s_line_algorithm + int steep = abs(y1 - y0) > abs(x1 - x0); + if(steep) + { + SWAP(x0, y0); + SWAP(x1, y1); + } + if(x0 > x1) + { + SWAP(x0, x1); + SWAP(y0, y1); + } + int deltax = x1 - x0; + int deltay = abs(y1 - y0); + int error = deltax / 2; + int ystep; + int y = y0; + int x; //, lasty = y, stox = 0; + if(y0 < y1) + ystep = 1; + else + ystep = -1; + for(x = x0; x < x1; x++) + { + if(steep) + { + write_pixel(buff, y, x, mode); + } + else + { + write_pixel(buff, x, y, mode); + } + error -= deltay; + if(error < 0) + { + y += ystep; + error += deltax; + } + } +} + +/** + * write_line_lm: Draw a line of arbitrary angle. + * + * @param x0 first x coordinate + * @param y0 first y coordinate + * @param x1 second x coordinate + * @param y1 second y coordinate + * @param mmode 0 = clear, 1 = set, 2 = toggle + * @param lmode 0 = clear, 1 = set, 2 = toggle + */ +void write_line_lm(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int mmode, int lmode) +{ + write_line(draw_buffer_mask, x0, y0, x1, y1, mmode); + write_line(draw_buffer_level, x0, y0, x1, y1, lmode); +} + +/** + * write_line_outlined: Draw a line of arbitrary angle, with an outline. + * + * @param buff pointer to buffer to write in + * @param x0 first x coordinate + * @param y0 first y coordinate + * @param x1 second x coordinate + * @param y1 second y coordinate + * @param endcap0 0 = none, 1 = single pixel, 2 = full cap + * @param endcap1 0 = none, 1 = single pixel, 2 = full cap + * @param mode 0 = black outline, white body, 1 = white outline, black body + * @param mmode 0 = clear, 1 = set, 2 = toggle + */ +void write_line_outlined(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, int endcap0, int endcap1, int mode, int mmode) +{ + // Based on http://en.wikipedia.org/wiki/Bresenham%27s_line_algorithm + // This could be improved for speed. + int omode, imode; + if(mode == 0) + { + omode = 0; + imode = 1; + } + else + { + omode = 1; + imode = 0; + } + int steep = abs(y1 - y0) > abs(x1 - x0); + if(steep) + { + SWAP(x0, y0); + SWAP(x1, y1); + } + if(x0 > x1) + { + SWAP(x0, x1); + SWAP(y0, y1); + } + int deltax = x1 - x0; + int deltay = abs(y1 - y0); + int error = deltax / 2; + int ystep; + int y = y0; + int x; + if(y0 < y1) + ystep = 1; + else + ystep = -1; + // Draw the outline. + for(x = x0; x < x1; x++) + { + if(steep) + { + write_pixel_lm(y - 1, x, mmode, omode); + write_pixel_lm(y + 1, x, mmode, omode); + write_pixel_lm(y, x - 1, mmode, omode); + write_pixel_lm(y, x + 1, mmode, omode); + } + else + { + write_pixel_lm(x - 1, y, mmode, omode); + write_pixel_lm(x + 1, y, mmode, omode); + write_pixel_lm(x, y - 1, mmode, omode); + write_pixel_lm(x, y + 1, mmode, omode); + } + error -= deltay; + if(error < 0) + { + y += ystep; + error += deltax; + } + } + // Now draw the innards. + error = deltax / 2; + y = y0; + for(x = x0; x < x1; x++) + { + if(steep) + { + write_pixel_lm(y, x, mmode, imode); + } + else + { + write_pixel_lm(x, y, mmode, imode); + } + error -= deltay; + if(error < 0) + { + y += ystep; + error += deltax; + } + } +} + +/** + * write_word_misaligned: Write a misaligned word across two addresses + * with an x offset. + * + * This allows for many pixels to be set in one write. + * + * @param buff buffer to write in + * @param word word to write (16 bits) + * @param addr address of first word + * @param xoff x offset (0-15) + * @param mode 0 = clear, 1 = set, 2 = toggle + */ +void write_word_misaligned(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff, int mode) +{ + uint16_t firstmask = word >> xoff; + uint16_t lastmask = word << (16 - xoff); + WRITE_WORD_MODE(buff, addr+1, firstmask && 0x00ff, mode); + WRITE_WORD_MODE(buff, addr, (firstmask & 0xff00) >> 8, mode); + if(xoff > 0) + WRITE_WORD_MODE(buff, addr+2, (lastmask & 0xff00) >> 8, mode); +} + +/** + * write_word_misaligned_NAND: Write a misaligned word across two addresses + * with an x offset, using a NAND mask. + * + * This allows for many pixels to be set in one write. + * + * @param buff buffer to write in + * @param word word to write (16 bits) + * @param addr address of first word + * @param xoff x offset (0-15) + * + * This is identical to calling write_word_misaligned with a mode of 0 but + * it doesn't go through a lot of switch logic which slows down text writing + * a lot. + */ +void write_word_misaligned_NAND(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff) +{ + uint16_t firstmask = word >> xoff; + uint16_t lastmask = word << (16 - xoff); + WRITE_WORD_NAND(buff, addr+1, firstmask & 0x00ff); + WRITE_WORD_NAND(buff, addr, (firstmask & 0xff00) >> 8); + if(xoff > 0) + WRITE_WORD_NAND(buff, addr+2, (lastmask & 0xff00) >> 8); +} + +/** + * write_word_misaligned_OR: Write a misaligned word across two addresses + * with an x offset, using an OR mask. + * + * This allows for many pixels to be set in one write. + * + * @param buff buffer to write in + * @param word word to write (16 bits) + * @param addr address of first word + * @param xoff x offset (0-15) + * + * This is identical to calling write_word_misaligned with a mode of 1 but + * it doesn't go through a lot of switch logic which slows down text writing + * a lot. + */ +void write_word_misaligned_OR(uint8_t *buff, uint16_t word, unsigned int addr, unsigned int xoff) +{ + uint16_t firstmask = word >> xoff; + uint16_t lastmask = word << (16 - xoff); + WRITE_WORD_OR(buff, addr+1, firstmask & 0x00ff); + WRITE_WORD_OR(buff, addr, (firstmask & 0xff00) >> 8); + if(xoff > 0) + WRITE_WORD_OR(buff, addr + 2, (lastmask & 0xff00) >> 8); + +} + +/** + * write_word_misaligned_lm: Write a misaligned word across two + * words, in both level and mask buffers. This is core to the text + * writing routines. + * + * @param buff buffer to write in + * @param word word to write (16 bits) + * @param addr address of first word + * @param xoff x offset (0-15) + * @param lmode 0 = clear, 1 = set, 2 = toggle + * @param mmode 0 = clear, 1 = set, 2 = toggle + */ +void write_word_misaligned_lm(uint16_t wordl, uint16_t wordm, unsigned int addr, unsigned int xoff, int lmode, int mmode) +{ + write_word_misaligned(draw_buffer_level, wordl, addr, xoff, lmode); + write_word_misaligned(draw_buffer_mask, wordm, addr, xoff, mmode); +} + +/** + * fetch_font_info: Fetch font info structs. + * + * @param ch character + * @param font font id + */ +int fetch_font_info(uint8_t ch, int font, struct FontEntry *font_info, char *lookup) +{ + // First locate the font struct. + if(font > SIZEOF_ARRAY(fonts)) + return 0; // font does not exist, exit.*/ + // Load the font info; IDs are always sequential. + *font_info = fonts[font]; + // Locate character in font lookup table. (If required.) + if(lookup != NULL) + { + *lookup = font_info->lookup[ch]; + if(*lookup == 0xff) + return 0; // character doesn't exist, don't bother writing it. + } + return 1; +} + + +/** + * write_char16: Draw a character on the current draw buffer. + * Currently supports outlined characters and characters with + * a width of up to 8 pixels. + * + * @param ch character to write + * @param x x coordinate (left) + * @param y y coordinate (top) + * @param flags flags to write with (see gfx.h) + * @param font font to use + */ +void write_char16(char ch, unsigned int x, unsigned int y, int font) +{ + int yy, addr_temp, row, row_temp, xshift; + uint16_t and_mask, or_mask, level_bits; + struct FontEntry font_info; + //char lookup = 0; + fetch_font_info(0, font, &font_info, NULL); + + // Compute starting address (for x,y) of character. + int addr = CALC_BUFF_ADDR(x, y); + int wbit = CALC_BIT_IN_WORD(x); + // If font only supports lowercase or uppercase, make the letter + // lowercase or uppercase. + // How big is the character? We handle characters up to 8 pixels + // wide for now. Support for large characters may be added in future. + { + // Ensure we don't overflow. + if(x + wbit > GRAPHICS_WIDTH_REAL) + return; + // Load data pointer. + row = ch * font_info.height; + row_temp = row; + addr_temp = addr; + xshift = 16 - font_info.width; + // We can write mask words easily. + for(yy = y; yy < y + font_info.height; yy++) + { + if(font==3) + write_word_misaligned_OR(draw_buffer_mask, font_mask12x18[row] << xshift, addr, wbit); + else + write_word_misaligned_OR(draw_buffer_mask, font_mask8x10[row] << xshift, addr, wbit); + addr += GRAPHICS_WIDTH_REAL / 8; + row++; + } + // Level bits are more complicated. We need to set or clear + // level bits, but only where the mask bit is set; otherwise, + // we need to leave them alone. To do this, for each word, we + // construct an AND mask and an OR mask, and apply each individually. + row = row_temp; + addr = addr_temp; + for(yy = y; yy < y + font_info.height; yy++) + { + if(font==3) + { + level_bits = font_frame12x18[row]; + //if(!(flags & FONT_INVERT)) // data is normally inverted + level_bits = ~level_bits; + or_mask = font_mask12x18[row] << xshift; + and_mask = (font_mask12x18[row] & level_bits) << xshift; + } else { + level_bits = font_frame8x10[row]; + //if(!(flags & FONT_INVERT)) // data is normally inverted + level_bits = ~level_bits; + or_mask = font_mask8x10[row] << xshift; + and_mask = (font_mask8x10[row] & level_bits) << xshift; + } + write_word_misaligned_OR(draw_buffer_level, or_mask, addr, wbit); + // If we're not bold write the AND mask. + //if(!(flags & FONT_BOLD)) + write_word_misaligned_NAND(draw_buffer_level, and_mask, addr, wbit); + addr += GRAPHICS_WIDTH_REAL / 8; + row++; + } + } +} + + + +/** + * write_char: Draw a character on the current draw buffer. + * Currently supports outlined characters and characters with + * a width of up to 8 pixels. + * + * @param ch character to write + * @param x x coordinate (left) + * @param y y coordinate (top) + * @param flags flags to write with (see gfx.h) + * @param font font to use + */ +void write_char(char ch, unsigned int x, unsigned int y, int flags, int font) +{ + int yy, addr_temp, row, row_temp, xshift; + uint16_t and_mask, or_mask, level_bits; + struct FontEntry font_info; + char lookup = 0; + fetch_font_info(ch, font, &font_info, &lookup); + // Compute starting address (for x,y) of character. + int addr = CALC_BUFF_ADDR(x, y); + int wbit = CALC_BIT_IN_WORD(x); + // If font only supports lowercase or uppercase, make the letter + // lowercase or uppercase. + /*if(font_info.flags & FONT_LOWERCASE_ONLY) + ch = tolower(ch); + if(font_info.flags & FONT_UPPERCASE_ONLY) + ch = toupper(ch);*/ + fetch_font_info(ch, font, &font_info, &lookup); + // How big is the character? We handle characters up to 8 pixels + // wide for now. Support for large characters may be added in future. + if(font_info.width <= 8) + { + // Ensure we don't overflow. + if(x + wbit > GRAPHICS_WIDTH_REAL) + return; + // Load data pointer. + row = lookup * font_info.height * 2; + row_temp = row; + addr_temp = addr; + xshift = 16 - font_info.width; + // We can write mask words easily. + for(yy = y; yy < y + font_info.height; yy++) + { + write_word_misaligned_OR(draw_buffer_mask, font_info.data[row] << xshift, addr, wbit); + addr += GRAPHICS_WIDTH_REAL / 8; + row++; + } + // Level bits are more complicated. We need to set or clear + // level bits, but only where the mask bit is set; otherwise, + // we need to leave them alone. To do this, for each word, we + // construct an AND mask and an OR mask, and apply each individually. + row = row_temp; + addr = addr_temp; + for(yy = y; yy < y + font_info.height; yy++) + { + level_bits = font_info.data[row + font_info.height]; + if(!(flags & FONT_INVERT)) // data is normally inverted + level_bits = ~level_bits; + or_mask = font_info.data[row] << xshift; + and_mask = (font_info.data[row] & level_bits) << xshift; + write_word_misaligned_OR(draw_buffer_level, or_mask, addr, wbit); + // If we're not bold write the AND mask. + //if(!(flags & FONT_BOLD)) + write_word_misaligned_NAND(draw_buffer_level, and_mask, addr, wbit); + addr += GRAPHICS_WIDTH_REAL / 8; + row++; + } + } +} + +/** +* calc_text_dimensions: Calculate the dimensions of a +* string in a given font. Supports new lines and +* carriage returns in text. +* +* @param str string to calculate dimensions of +* @param font_info font info structure +* @param xs horizontal spacing +* @param ys vertical spacing +* @param dim return result: struct FontDimensions +*/ +void calc_text_dimensions(char *str, struct FontEntry font, int xs, int ys, struct FontDimensions *dim) +{ + int max_length = 0, line_length = 0, lines = 1; + while(*str != 0) + { + line_length++; + if(*str == '\n' || *str == '\r') + { + if(line_length > max_length) + max_length = line_length; + line_length = 0; + lines++; + } + str++; + } + if(line_length > max_length) + max_length = line_length; + dim->width = max_length * (font.width + xs); + dim->height = lines * (font.height + ys); +} + +/** +* write_string: Draw a string on the screen with certain +* alignment parameters. +* +* @param str string to write +* @param x x coordinate +* @param y y coordinate +* @param xs horizontal spacing +* @param ys horizontal spacing +* @param va vertical align +* @param ha horizontal align +* @param flags flags (passed to write_char) +* @param font font +*/ +void write_string(char *str, unsigned int x, unsigned int y, unsigned int xs, unsigned int ys, int va, int ha, int flags, int font) +{ + int xx = 0, yy = 0, xx_original = 0; + struct FontEntry font_info; + struct FontDimensions dim; + // Determine font info and dimensions/position of the string. + fetch_font_info(0, font, &font_info, NULL); + calc_text_dimensions(str, font_info, xs, ys, &dim); + switch(va) + { + case TEXT_VA_TOP: yy = y; break; + case TEXT_VA_MIDDLE: yy = y - (dim.height / 2); break; + case TEXT_VA_BOTTOM: yy = y - dim.height; break; + } + switch(ha) + { + case TEXT_HA_LEFT: xx = x; break; + case TEXT_HA_CENTER: xx = x - (dim.width / 2); break; + case TEXT_HA_RIGHT: xx = x - dim.width; break; + } + // Then write each character. + xx_original = xx; + while(*str != 0) + { + if(*str == '\n' || *str == '\r') + { + yy += ys + font_info.height; + xx = xx_original; + } + else + { + if(xx >= 0 && xx < GRAPHICS_WIDTH_REAL) + { + if(font_info.id<2) + write_char(*str, xx, yy, flags, font); + else + write_char16(*str, xx, yy, font); + } + xx += font_info.width + xs; + } + str++; + } +} + +/** +* write_string_formatted: Draw a string with format escape +* sequences in it. Allows for complex text effects. +* +* @param str string to write (with format data) +* @param x x coordinate +* @param y y coordinate +* @param xs default horizontal spacing +* @param ys default horizontal spacing +* @param va vertical align +* @param ha horizontal align +* @param flags flags (passed to write_char) +*/ +void write_string_formatted(char *str, unsigned int x, unsigned int y, unsigned int xs, unsigned int ys, int va, int ha, int flags) +{ + int fcode = 0, fptr = 0, font = 0, fwidth = 0, fheight = 0, xx = x, yy = y, max_xx = 0, max_height = 0; + struct FontEntry font_info; + // Retrieve sizes of the fonts: bigfont and smallfont. + fetch_font_info(0, 0, &font_info, NULL); + int smallfontwidth = font_info.width, smallfontheight = font_info.height; + fetch_font_info(0, 1, &font_info, NULL); + int bigfontwidth = font_info.width, bigfontheight = font_info.height; + // 11 byte stack with last byte as NUL. + char fstack[11]; + fstack[10] = '\0'; + // First, we need to parse the string for format characters and + // work out a bounding box. We'll parse again for the final output. + // This is a simple state machine parser. + char *ostr = str; + while(*str) + { + if(*str == '<' && fcode == 1) // escape code: skip + fcode = 0; + if(*str == '<' && fcode == 0) // begin format code? + { + fcode = 1; + fptr = 0; + } + if(*str == '>' && fcode == 1) + { + fcode = 0; + if(strcmp(fstack, "B")) // switch to "big" font (font #1) + { + fwidth = bigfontwidth; + fheight = bigfontheight; + } + else if(strcmp(fstack, "S")) // switch to "small" font (font #0) + { + fwidth = smallfontwidth; + fheight = smallfontheight; + } + if(fheight > max_height) + max_height = fheight; + // Skip over this byte. Go to next byte. + str++; + continue; + } + if(*str != '<' && *str != '>' && fcode == 1) + { + // Add to the format stack (up to 10 bytes.) + if(fptr > 10) // stop adding bytes + { + str++; // go to next byte + continue; + } + fstack[fptr++] = *str; + fstack[fptr] = '\0'; // clear next byte (ready for next char or to terminate string.) + } + if(fcode == 0) + { + // Not a format code, raw text. + xx += fwidth + xs; + if(*str == '\n') + { + if(xx > max_xx) + max_xx = xx; + xx = x; + yy += fheight + ys; + } + } + str++; + } + // Reset string pointer. + str = ostr; + // Now we've parsed it and got a bbox, we need to work out the dimensions of it + // and how to align it. + /*int width = max_xx - x; + int height = yy - y; + int ay, ax; + switch(va) + { + case TEXT_VA_TOP: ay = yy; break; + case TEXT_VA_MIDDLE: ay = yy - (height / 2); break; + case TEXT_VA_BOTTOM: ay = yy - height; break; + } + switch(ha) + { + case TEXT_HA_LEFT: ax = x; break; + case TEXT_HA_CENTER: ax = x - (width / 2); break; + case TEXT_HA_RIGHT: ax = x - width; break; + }*/ + // So ax,ay is our new text origin. Parse the text format again and paint + // the text on the display. + fcode = 0; + fptr = 0; + font = 0; + xx = 0; + yy = 0; + while(*str) + { + if(*str == '<' && fcode == 1) // escape code: skip + fcode = 0; + if(*str == '<' && fcode == 0) // begin format code? + { + fcode = 1; + fptr = 0; + } + if(*str == '>' && fcode == 1) + { + fcode = 0; + if(strcmp(fstack, "B")) // switch to "big" font (font #1) + { + fwidth = bigfontwidth; + fheight = bigfontheight; + font = 1; + } + else if(strcmp(fstack, "S")) // switch to "small" font (font #0) + { + fwidth = smallfontwidth; + fheight = smallfontheight; + font = 0; + } + // Skip over this byte. Go to next byte. + str++; + continue; + } + if(*str != '<' && *str != '>' && fcode == 1) + { + // Add to the format stack (up to 10 bytes.) + if(fptr > 10) // stop adding bytes + { + str++; // go to next byte + continue; + } + fstack[fptr++] = *str; + fstack[fptr] = '\0'; // clear next byte (ready for next char or to terminate string.) + } + if(fcode == 0) + { + // Not a format code, raw text. So we draw it. + // TODO - different font sizes. + write_char(*str, xx, yy + (max_height - fheight), flags, font); + xx += fwidth + xs; + if(*str == '\n') + { + if(xx > max_xx) + max_xx = xx; + xx = x; + yy += fheight + ys; + } + } + str++; + } +} + + +//SUPEROSD- + + +// graphics + +void drawAttitude(uint16_t x, uint16_t y, int16_t pitch, int16_t roll, uint16_t size) +{ + int16_t a = mySin(roll+360); + int16_t b = myCos(roll+360); + int16_t c = mySin(roll+90+360)*5/100; + int16_t d = myCos(roll+90+360)*5/100; + + int16_t k; + int16_t l; + + int16_t indi30x1=myCos(30)*(size/2+1) / 100; + int16_t indi30y1=mySin(30)*(size/2+1) / 100; + + int16_t indi30x2=myCos(30)*(size/2+4) / 100; + int16_t indi30y2=mySin(30)*(size/2+4) / 100; + + int16_t indi60x1=myCos(60)*(size/2+1) / 100; + int16_t indi60y1=mySin(60)*(size/2+1) / 100; + + int16_t indi60x2=myCos(60)*(size/2+4) / 100; + int16_t indi60y2=mySin(60)*(size/2+4) / 100; + + pitch=pitch%90; + if(pitch>90) + { + pitch=pitch-90; + } + if(pitch<-90) + { + pitch=pitch+90; + } + a = (a * (size/2)) / 100; + b = (b * (size/2)) / 100; + + if(roll<-90 || roll>90) + pitch=pitch*-1; + k = a*pitch/90; + l = b*pitch/90; + + // scale + //0 + //drawLine((x)-1-(size/2+4), (y)-1, (x)-1 - (size/2+1), (y)-1); + //drawLine((x)-1+(size/2+4), (y)-1, (x)-1 + (size/2+1), (y)-1); + write_line_outlined((x)-1-(size/2+4), (y)-1, (x)-1 - (size/2+1), (y)-1,0,0,0,1); + write_line_outlined((x)-1+(size/2+4), (y)-1, (x)-1 + (size/2+1), (y)-1,0,0,0,1); + + //30 + //drawLine((x)-1+indi30x1, (y)-1-indi30y1, (x)-1 + indi30x2, (y)-1 - indi30y2); + //drawLine((x)-1-indi30x1, (y)-1-indi30y1, (x)-1 - indi30x2, (y)-1 - indi30y2); + write_line_outlined((x)-1+indi30x1, (y)-1-indi30y1, (x)-1 + indi30x2, (y)-1 - indi30y2,0,0,0,1); + write_line_outlined((x)-1-indi30x1, (y)-1-indi30y1, (x)-1 - indi30x2, (y)-1 - indi30y2,0,0,0,1); + //60 + //drawLine((x)-1+indi60x1, (y)-1-indi60y1, (x)-1 + indi60x2, (y)-1 - indi60y2); + //drawLine((x)-1-indi60x1, (y)-1-indi60y1, (x)-1 - indi60x2, (y)-1 - indi60y2); + write_line_outlined((x)-1+indi60x1, (y)-1-indi60y1, (x)-1 + indi60x2, (y)-1 - indi60y2,0,0,0,1); + write_line_outlined((x)-1-indi60x1, (y)-1-indi60y1, (x)-1 - indi60x2, (y)-1 - indi60y2,0,0,0,1); + //90 + //drawLine((x)-1, (y)-1-(size/2+4), (x)-1, (y)-1 - (size/2+1)); + write_line_outlined((x)-1, (y)-1-(size/2+4), (x)-1, (y)-1 - (size/2+1),0,0,0,1); + + + //roll + //drawLine((x)-1 - b, (y)-1 + a, (x)-1 + b, (y)-1 - a); //Direction line + write_line_outlined((x)-1 - b, (y)-1 + a, (x)-1 + b, (y)-1 - a,0,0,0,1); //Direction line + //"wingtips" + //drawLine((x)-1 - b, (y)-1 + a, (x)-1 - b + d, (y)-1 + a - c); + //drawLine((x)-1 + b + d, (y)-1 - a - c, (x)-1 + b, (y)-1 - a); + write_line_outlined((x)-1 - b, (y)-1 + a, (x)-1 - b + d, (y)-1 + a - c,0,0,0,1); + write_line_outlined((x)-1 + b + d, (y)-1 - a - c, (x)-1 + b, (y)-1 - a,0,0,0,1); + + //pitch + //drawLine((x)-1, (y)-1, (x)-1 - k, (y)-1 - l); + write_line_outlined((x)-1, (y)-1, (x)-1 - k, (y)-1 - l,0,0,0,1); + + + //drawCircle(x-1, y-1, 5); + //write_circle_outlined(x-1, y-1, 5,0,0,0,1); + //drawCircle(x-1, y-1, size/2+4); + //write_circle_outlined(x-1, y-1, size/2+4,0,0,0,1); +} + +void drawBattery(uint16_t x, uint16_t y, uint8_t battery, uint16_t size) +{ + int i=0; + int batteryLines; + //top + /*drawLine((x)-1+(size/2-size/4), (y)-1, (x)-1 + (size/2+size/4), (y)-1); + drawLine((x)-1+(size/2-size/4), (y)-1+1, (x)-1 + (size/2+size/4), (y)-1+1); + + drawLine((x)-1, (y)-1+2, (x)-1 + size, (y)-1+2); + //bottom + drawLine((x)-1, (y)-1+size*3, (x)-1 + size, (y)-1+size*3); + //left + drawLine((x)-1, (y)-1+2, (x)-1, (y)-1+size*3); + + //right + drawLine((x)-1+size, (y)-1+2, (x)-1+size, (y)-1+size*3);*/ + + write_rectangle_outlined((x)-1, (y)-1+2,size,size*3,0,1); + write_vline_lm((x)-1+(size/2+size/4)+1,(y)-2,(y)-1+1,0,1); + write_vline_lm((x)-1+(size/2-size/4)-1,(y)-2,(y)-1+1,0,1); + write_hline_lm((x)-1+(size/2-size/4),(x)-1 + (size/2+size/4),(y)-2,0,1); + write_hline_lm((x)-1+(size/2-size/4),(x)-1 + (size/2+size/4),(y)-1,1,1); + write_hline_lm((x)-1+(size/2-size/4),(x)-1 + (size/2+size/4),(y)-1+1,1,1); + + batteryLines = battery*(size*3-2)/100; + for(i=0;i= -1 && halign <= 1); + // Compute the position of the elements. + int majtick_start = 0, majtick_end = 0, mintick_start = 0, mintick_end = 0, boundtick_start = 0, boundtick_end = 0; + if(halign == -1) + { + majtick_start = x; + majtick_end = x + majtick_len; + mintick_start = x; + mintick_end = x + mintick_len; + boundtick_start = x; + boundtick_end = x + boundtick_len; + } + else if(halign == +1) + { + x=x-GRAPHICS_HDEADBAND; + majtick_start = GRAPHICS_WIDTH_REAL - x - 1; + majtick_end = GRAPHICS_WIDTH_REAL - x - majtick_len - 1; + mintick_start = GRAPHICS_WIDTH_REAL - x - 1; + mintick_end = GRAPHICS_WIDTH_REAL - x - mintick_len - 1; + boundtick_start = GRAPHICS_WIDTH_REAL - x - 1; + boundtick_end = GRAPHICS_WIDTH_REAL - x - boundtick_len - 1; + } + // Retrieve width of large font (font #0); from this calculate the x spacing. + fetch_font_info(0, 0, &font_info, NULL); + int arrow_len = (font_info.height / 2) + 1; // FIXME, font info being loaded correctly?? + int text_x_spacing = arrow_len; + int max_text_y = 0, text_length = 0; + int small_font_char_width = font_info.width + 1; // +1 for horizontal spacing = 1 + // For -(range / 2) to +(range / 2), draw the scale. + int range_2 = range / 2; //, height_2 = height / 2; + int r = 0, rr = 0, rv = 0, ys = 0, style = 0; //calc_ys = 0, + // Iterate through each step. + for(r = -range_2; r <= +range_2; r++) + { + style = 0; + rr = r + range_2 - v; // normalise range for modulo, subtract value to move ticker tape + rv = -rr + range_2; // for number display + if(flags & HUD_VSCALE_FLAG_NO_NEGATIVE) + rr += majtick_step / 2; + if(rr % majtick_step == 0) + style = 1; // major tick + else if(rr % mintick_step == 0) + style = 2; // minor tick + else + style = 0; + if(flags & HUD_VSCALE_FLAG_NO_NEGATIVE && rv < 0) + continue; + if(style) + { + // Calculate y position. + ys = ((long int)(r * height) / (long int)range) + y; + //sprintf(temp, "ys=%d", ys); + //con_puts(temp, 0); + // Depending on style, draw a minor or a major tick. + if(style == 1) + { + write_hline_outlined(majtick_start, majtick_end, ys, 2, 2, 0, 1); + memset(temp, ' ', 10); + //my_itoa(rv, temp); + sprintf(temp,"%d",rv); + text_length = (strlen(temp) + 1) * small_font_char_width; // add 1 for margin + if(text_length > max_text_y) + max_text_y = text_length; + if(halign == -1) + write_string(temp, majtick_end + text_x_spacing, ys, 1, 0, TEXT_VA_MIDDLE, TEXT_HA_LEFT, 0, 1); + else + write_string(temp, majtick_end - text_x_spacing + 1, ys, 1, 0, TEXT_VA_MIDDLE, TEXT_HA_RIGHT, 0, 1); + } + else if(style == 2) + write_hline_outlined(mintick_start, mintick_end, ys, 2, 2, 0, 1); + } + } + // Generate the string for the value, as well as calculating its dimensions. + memset(temp, ' ', 10); + //my_itoa(v, temp); + sprintf(temp,"%d",v); + // TODO: add auto-sizing. + calc_text_dimensions(temp, font_info, 1, 0, &dim); + int xx = 0, i = 0; + if(halign == -1) + xx = majtick_end + text_x_spacing; + else + xx = majtick_end - text_x_spacing; + // Draw an arrow from the number to the point. + for(i = 0; i < arrow_len; i++) + { + if(halign == -1) + { + write_pixel_lm(xx - arrow_len + i, y - i - 1, 1, 1); + write_pixel_lm(xx - arrow_len + i, y + i - 1, 1, 1); + write_hline_lm(xx + dim.width - 1, xx - arrow_len + i + 1, y - i - 1, 0, 1); + write_hline_lm(xx + dim.width - 1, xx - arrow_len + i + 1, y + i - 1, 0, 1); + } + else + { + write_pixel_lm(xx + arrow_len - i, y - i - 1, 1, 1); + write_pixel_lm(xx + arrow_len - i, y + i - 1, 1, 1); + write_hline_lm(xx - dim.width - 1, xx + arrow_len - i - 1, y - i - 1, 0, 1); + write_hline_lm(xx - dim.width - 1, xx + arrow_len - i - 1, y + i - 1, 0, 1); + } + // FIXME + // write_hline_lm(xx - dim.width - 1, xx + (arrow_len - i), y - i - 1, 1, 1); + // write_hline_lm(xx - dim.width - 1, xx + (arrow_len - i), y + i - 1, 1, 1); + } + if(halign == -1) + { + write_hline_lm(xx, xx + dim.width - 1, y - arrow_len, 1, 1); + write_hline_lm(xx, xx + dim.width - 1, y + arrow_len - 2, 1, 1); + write_vline_lm(xx + dim.width - 1, y - arrow_len, y + arrow_len - 2, 1, 1); + } + else + { + write_hline_lm(xx, xx - dim.width - 1, y - arrow_len, 1, 1); + write_hline_lm(xx, xx - dim.width - 1, y + arrow_len - 2, 1, 1); + write_vline_lm(xx - dim.width - 1, y - arrow_len, y + arrow_len - 2, 1, 1); + } + // Draw the text. + if(halign == -1) + write_string(temp, xx, y, 1, 0, TEXT_VA_MIDDLE, TEXT_HA_LEFT, 0, 0); + else + write_string(temp, xx, y, 1, 0, TEXT_VA_MIDDLE, TEXT_HA_RIGHT, 0, 0); + // Then, add a slow cut off on the edges, so the text doesn't sharply + // disappear. We simply clear the areas above and below the ticker, and we + // use little markers on the edges. + if(halign == -1) + { + write_filled_rectangle_lm(majtick_end + text_x_spacing, y + (height / 2) - (font_info.height / 2), max_text_y - boundtick_start, font_info.height, 0, 0); + write_filled_rectangle_lm(majtick_end + text_x_spacing, y - (height / 2) - (font_info.height / 2), max_text_y - boundtick_start, font_info.height, 0, 0); + } + else + { + write_filled_rectangle_lm(majtick_end - text_x_spacing - max_text_y, y + (height / 2) - (font_info.height / 2), max_text_y, font_info.height, 0, 0); + write_filled_rectangle_lm(majtick_end - text_x_spacing - max_text_y, y - (height / 2) - (font_info.height / 2), max_text_y, font_info.height, 0, 0); + } + write_hline_outlined(boundtick_start, boundtick_end, y + (height / 2), 2, 2, 0, 1); + write_hline_outlined(boundtick_start, boundtick_end, y - (height / 2), 2, 2, 0, 1); +} + +/** + * hud_draw_compass: Draw a compass. + * + * @param v value for the compass + * @param range range about value to display (+/- range/2 each direction) + * @param width length in pixels + * @param x x displacement (typ. half display width) + * @param y y displacement (typ. bottom of display) + * @param mintick_step how often a minor tick is shown + * @param majtick_step how often a major tick (heading "xx") is shown + * @param mintick_len minor tick length + * @param majtick_len major tick length + * @param flags special flags (see hud.h.) + */ +void hud_draw_linear_compass(int v, int range, int width, int x, int y, int mintick_step, int majtick_step, int mintick_len, int majtick_len, int flags) +{ + v %= 360; // wrap, just in case. + struct FontEntry font_info; + int majtick_start = 0, majtick_end = 0, mintick_start = 0, mintick_end = 0, textoffset = 0; + char headingstr[4]; + majtick_start = y; + majtick_end = y - majtick_len; + mintick_start = y; + mintick_end = y - mintick_len; + textoffset = 8; + int r, style, rr, xs; // rv, + int range_2 = range / 2; + for(r = -range_2; r <= +range_2; r++) + { + style = 0; + rr = (v + r + 360) % 360; // normalise range for modulo, add to move compass track + //rv = -rr + range_2; // for number display + if(rr % majtick_step == 0) + style = 1; // major tick + else if(rr % mintick_step == 0) + style = 2; // minor tick + if(style) + { + // Calculate x position. + xs = ((long int)(r * width) / (long int)range) + x; + // Draw it. + if(style == 1) + { + write_vline_outlined(xs, majtick_start, majtick_end, 2, 2, 0, 1); + // Draw heading above this tick. + // If it's not one of north, south, east, west, draw the heading. + // Otherwise, draw one of the identifiers. + if(rr % 90 != 0) + { + // We abbreviate heading to two digits. This has the side effect of being easy to compute. + headingstr[0] = '0' + (rr / 100); + headingstr[1] = '0' + ((rr / 10) % 10); + headingstr[2] = 0; + headingstr[3] = 0; // nul to terminate + } + else + { + switch(rr) + { + case 0: headingstr[0] = 'N'; break; + case 90: headingstr[0] = 'E'; break; + case 180: headingstr[0] = 'S'; break; + case 270: headingstr[0] = 'W'; break; + } + headingstr[1] = 0; + headingstr[2] = 0; + headingstr[3] = 0; + } + // +1 fudge...! + write_string(headingstr, xs + 1, majtick_start + textoffset, 1, 0, TEXT_VA_MIDDLE, TEXT_HA_CENTER, 0, 1); + } + else if(style == 2) + write_vline_outlined(xs, mintick_start, mintick_end, 2, 2, 0, 1); + } + } + // Then, draw a rectangle with the present heading in it. + // We want to cover up any other markers on the bottom. + // First compute font size. + fetch_font_info(0, 3, &font_info, NULL); + int text_width = (font_info.width + 1) * 3; + int rect_width = text_width + 2; + write_filled_rectangle_lm(x - (rect_width / 2), majtick_start + 2, rect_width, font_info.height + 2, 0, 1); + write_rectangle_outlined(x - (rect_width / 2), majtick_start + 2, rect_width, font_info.height + 2, 0, 1); + headingstr[0] = '0' + (v / 100); + headingstr[1] = '0' + ((v / 10) % 10); + headingstr[2] = '0' + (v % 10); + headingstr[3] = 0; + write_string(headingstr, x + 1, majtick_start + textoffset+2, 0, 0, TEXT_VA_MIDDLE, TEXT_HA_CENTER, 1, 3); +} +// CORE draw routines end here + +void draw_artificial_horizon(float angle, float pitch, int16_t l_x, int16_t l_y, int16_t size ) +{ + float alpha; + uint8_t vertical=0,horizontal=0; + int16_t x1,x2; + int16_t y1,y2; + int16_t refx,refy; + alpha=DEG2RAD(angle); + refx=l_x + size/2; + refy=l_y + size/2; + + // + float k=0; + float dx = sinf(alpha)*(pitch/90.0f*(size/2)); + float dy = cosf(alpha)*(pitch/90.0f*(size/2)); + int16_t x0 = (size/2)-dx; + int16_t y0 = (size/2)+dy; + // calculate the line function + if((angle != 90) && (angle != -90)) + { + k = tanf(alpha); + vertical = 0; + if(k==0) + { + horizontal=1; + } + } + else + { + vertical = 1; + } + + // crossing point of line + if(!vertical && !horizontal) + { + // y-y0=k(x-x0) + int16_t x=0; + int16_t y=k*(x-x0)+y0; + // find right crossing point + x1=x; + y1=y; + if(y<0) + { + y1=0; + x1=((y1-y0)+k*x0)/k; + } + if(y>size) + { + y1=size; + x1=((y1-y0)+k*x0)/k; + } + // left crossing point + x=size; + y=k*(x-x0)+y0; + x2=x; + y2=y; + if(y<0) + { + y2=0; + x2=((y2-y0)+k*x0)/k; + } + if(y>size) + { + y2=size; + x2=((y2-y0)+k*x0)/k; + } + // move to location + // horizon line + write_line_outlined(x1+l_x,y1+l_y,x2+l_x,y2+l_y,0,0,0,1); + //fill + if(angle<=0 && angle>-90) + { + //write_string("1", APPLY_HDEADBAND((GRAPHICS_RIGHT/2)),APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_CENTER, 0, 3); + for(int i=y2;isize) + x2=size; + if(x2<0) + x2=0; + write_hline_lm(x2+l_x,size+l_x,i+l_y,1,1); + } + } + else if(angle<-90) + { + //write_string("2", APPLY_HDEADBAND((GRAPHICS_RIGHT/2)),APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_CENTER, 0, 3); + for(int i=0;isize) + x2=size; + if(x2<0) + x2=0; + write_hline_lm(size+l_x,x2+l_x,i+l_y,1,1); + } + } + else if(angle>0 && angle<90) + { + //write_string("3", APPLY_HDEADBAND((GRAPHICS_RIGHT/2)),APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_CENTER, 0, 3); + for(int i=y1;isize) + x2=size; + if(x2<0) + x2=0; + write_hline_lm(0+l_x,x2+l_x,i+l_y,1,1); + } + } + else if(angle>90) + { + //write_string("4", APPLY_HDEADBAND((GRAPHICS_RIGHT/2)),APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_CENTER, 0, 3); + for(int i=0;isize) + x2=size; + if(x2<0) + x2=0; + write_hline_lm(x2+l_x,0+l_x,i+l_y,1,1); + } + } + } + else if(vertical) + { + // horizon line + write_line_outlined(x0+l_x,0+l_y,x0+l_x,size+l_y,0,0,0,1); + if(angle==90) + { + //write_string("5", APPLY_HDEADBAND((GRAPHICS_RIGHT/2)),APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_CENTER, 0, 3); + for(int i=0;i180) - calcHomeArrow((int16_t)(gpsData.Heading-360)); - else - calcHomeArrow((int16_t)(gpsData.Heading)); - } - break; - case 1: - { - /*drawBox(2,2,GRAPHICS_WIDTH_REAL-4,GRAPHICS_HEIGHT_REAL-4); - write_filled_rectangle(draw_buffer_mask,0,0,GRAPHICS_WIDTH_REAL-2,GRAPHICS_HEIGHT_REAL-2,0); - write_filled_rectangle(draw_buffer_mask,2,2,GRAPHICS_WIDTH_REAL-4-2,GRAPHICS_HEIGHT_REAL-4-2,2); - write_filled_rectangle(draw_buffer_mask,3,3,GRAPHICS_WIDTH_REAL-4-1,GRAPHICS_HEIGHT_REAL-4-1,0);*/ - //write_filled_rectangle(draw_buffer_mask,5,5,GRAPHICS_WIDTH_REAL-4-5,GRAPHICS_HEIGHT_REAL-4-5,0); - //write_rectangle_outlined(10,10,GRAPHICS_WIDTH_REAL-20,GRAPHICS_HEIGHT_REAL-20,0,0); - //drawLine(GRAPHICS_WIDTH_REAL-1, GRAPHICS_HEIGHT_REAL-1,(GRAPHICS_WIDTH_REAL/2)-1, GRAPHICS_HEIGHT_REAL-1 ); - //drawCircle((GRAPHICS_WIDTH_REAL/2)-1, (GRAPHICS_HEIGHT_REAL/2)-1, (GRAPHICS_HEIGHT_REAL/2)-1); - //drawCircle((GRAPHICS_SIZE/2)-1, (GRAPHICS_SIZE/2)-1, (GRAPHICS_SIZE/2)-2); - //drawLine(0, (GRAPHICS_SIZE/2)-1, GRAPHICS_SIZE-1, (GRAPHICS_SIZE/2)-1); - //drawLine((GRAPHICS_SIZE/2)-1, 0, (GRAPHICS_SIZE/2)-1, GRAPHICS_SIZE-1); - /*angleA++; - if(angleB<=-90) - { - sum=2; - } - if(angleB>=90) - { - sum=-2; - } - angleB+=sum; - angleC+=2;*/ - - // GPS HACK - if(gpsData.Heading>180) - calcHomeArrow((int16_t)(gpsData.Heading-360)); - else - calcHomeArrow((int16_t)(gpsData.Heading)); - - /* Draw Attitude Indicator */ - if(OsdSettings.Attitude == OSDSETTINGS_ATTITUDE_ENABLED) - { - drawAttitude(APPLY_HDEADBAND(OsdSettings.AttitudeSetup[OSDSETTINGS_ATTITUDESETUP_X]),APPLY_VDEADBAND(OsdSettings.AttitudeSetup[OSDSETTINGS_ATTITUDESETUP_Y]),attitude.Pitch,attitude.Roll,96); - } - //write_string("Hello OP-OSD", 60, 12, 1, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 0); - //printText16( 60, 12,"Hello OP-OSD"); - - char temp[50]={0}; - memset(temp, ' ', 40); - sprintf(temp,"Lat:%11.7f",gpsData.Latitude/10000000.0f); - write_string(temp, APPLY_HDEADBAND(5), APPLY_VDEADBAND(5), 0, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 2); - sprintf(temp,"Lon:%11.7f",gpsData.Longitude/10000000.0f); - write_string(temp, APPLY_HDEADBAND(5), APPLY_VDEADBAND(15), 0, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 2); - sprintf(temp,"Fix:%d",(int)gpsData.Status); - write_string(temp, APPLY_HDEADBAND(5), APPLY_VDEADBAND(25), 0, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 2); - sprintf(temp,"Sat:%d",(int)gpsData.Satellites); - write_string(temp, APPLY_HDEADBAND(5), APPLY_VDEADBAND(35), 0, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 2); - - - /* Print RTC time */ - if(OsdSettings.Time == OSDSETTINGS_TIME_ENABLED) - { - printTime(APPLY_HDEADBAND(OsdSettings.TimeSetup[OSDSETTINGS_TIMESETUP_X]),APPLY_VDEADBAND(OsdSettings.TimeSetup[OSDSETTINGS_TIMESETUP_Y])); - } - - /* Print Number of detected video Lines */ - sprintf(temp,"Lines:%4d",PIOS_Video_GetOSDLines()); - write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(5), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); - - /* Print ADC voltage */ - //sprintf(temp,"Rssi:%4dV",(int)(PIOS_ADC_PinGet(4)*3000/4096)); - //write_string(temp, (GRAPHICS_WIDTH_REAL - 2),15, 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); - sprintf(temp,"Rssi:%4.2fV",(PIOS_ADC_PinGet(5)*3.0f/4096.0f)); - write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(15), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); - - /* Print CPU temperature */ - sprintf(temp,"Temp:%4.2fC",(PIOS_ADC_PinGet(3)*0.29296875f-264)); - write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(25), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); - - /* Print ADC voltage FLIGHT*/ - sprintf(temp,"FltV:%4.2fV",(PIOS_ADC_PinGet(2)*3.0f*6.1f/4096.0f)); - write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(35), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); - - /* Print ADC voltage VIDEO*/ - sprintf(temp,"VidV:%4.2fV",(PIOS_ADC_PinGet(4)*3.0f*6.1f/4096.0f)); - write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(45), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); - - /* Print ADC voltage RSSI */ - //sprintf(temp,"Curr:%4dA",(int)(PIOS_ADC_PinGet(0)*300*61/4096)); - //write_string(temp, (GRAPHICS_WIDTH_REAL - 2),60, 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); - - /* Draw Battery Gauge */ - /*m_batt++; - uint8_t dir=3; - if(m_batt==101) - m_batt=0; - if(m_pitch>0) - { - dir=0; - m_alt+=m_pitch/2; - } - else if(m_pitch<0) - { - dir=1; - m_alt+=m_pitch/2; - }*/ - - /*if(OsdSettings.Battery == OSDSETTINGS_BATTERY_ENABLED) - { - drawBattery(APPLY_HDEADBAND(OsdSettings.BatterySetup[OSDSETTINGS_BATTERYSETUP_X]),APPLY_VDEADBAND(OsdSettings.BatterySetup[OSDSETTINGS_BATTERYSETUP_Y]),m_batt,16); - }*/ - - //drawAltitude(200,50,m_alt,dir); - - - //drawArrow(96,GRAPHICS_HEIGHT_REAL/2,angleB,32); - - // Draw airspeed (left side.) - if(OsdSettings.Speed == OSDSETTINGS_SPEED_ENABLED) - { - hud_draw_vertical_scale((int)gpsData.Groundspeed, 100, -1, APPLY_HDEADBAND(OsdSettings.SpeedSetup[OSDSETTINGS_SPEEDSETUP_X]), - APPLY_VDEADBAND(OsdSettings.SpeedSetup[OSDSETTINGS_SPEEDSETUP_Y]), 100, 10, 20, 7, 12, 15, 1000, HUD_VSCALE_FLAG_NO_NEGATIVE); - } - // Draw altimeter (right side.) - if(OsdSettings.Altitude == OSDSETTINGS_ALTITUDE_ENABLED) - { - hud_draw_vertical_scale((int)gpsData.Altitude, 200, +1, APPLY_HDEADBAND(OsdSettings.AltitudeSetup[OSDSETTINGS_ALTITUDESETUP_X]), - APPLY_VDEADBAND(OsdSettings.AltitudeSetup[OSDSETTINGS_ALTITUDESETUP_Y]), 100, 20, 100, 7, 12, 15, 500, 0); - } - // Draw compass. - if(OsdSettings.Heading == OSDSETTINGS_HEADING_ENABLED) - { - if(attitude.Yaw<0) { - hud_draw_linear_compass(360+attitude.Yaw, 150, 120, APPLY_HDEADBAND(OsdSettings.HeadingSetup[OSDSETTINGS_HEADINGSETUP_X]), - APPLY_VDEADBAND(OsdSettings.HeadingSetup[OSDSETTINGS_HEADINGSETUP_Y]), 15, 30, 7, 12, 0); - } else { - hud_draw_linear_compass(attitude.Yaw, 150, 120, APPLY_HDEADBAND(OsdSettings.HeadingSetup[OSDSETTINGS_HEADINGSETUP_X]), - APPLY_VDEADBAND(OsdSettings.HeadingSetup[OSDSETTINGS_HEADINGSETUP_Y]), 15, 30, 7, 12, 0); - } - } - } - break; - case 2: - { - int size=64; - int x=((GRAPHICS_RIGHT/2)-(size/2)),y=(GRAPHICS_BOTTOM-size-2); - draw_artificial_horizon(-attitude.Roll,attitude.Pitch,APPLY_HDEADBAND(x),APPLY_VDEADBAND(y),size); - hud_draw_vertical_scale((int)gpsData.Groundspeed, 20, +1, APPLY_HDEADBAND(GRAPHICS_RIGHT-(x-1)), - APPLY_VDEADBAND(y+(size/2)), size, 5, 10, 4, 7, 10, 100, HUD_VSCALE_FLAG_NO_NEGATIVE); - if(OsdSettings.AltitudeSource == OSDSETTINGS_ALTITUDESOURCE_BARO) - { - hud_draw_vertical_scale((int)baro.Altitude, 50, -1, APPLY_HDEADBAND((x+size+1)), - APPLY_VDEADBAND(y+(size/2)), size, 10, 20, 4, 7, 10, 500, 0); - } - else - { - hud_draw_vertical_scale((int)gpsData.Altitude, 50, -1, APPLY_HDEADBAND((x+size+1)), - APPLY_VDEADBAND(y+(size/2)), size, 10, 20, 4, 7, 10, 500, 0); - } - - } - break; + + char temp[50]={0}; + memset(temp, ' ', 40); + sprintf(temp,"Lat:%11.7f",gpsData.Latitude/10000000.0f); + write_string(temp, APPLY_HDEADBAND(20), APPLY_VDEADBAND(GRAPHICS_BOTTOM-30), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_LEFT, 0, 3); + sprintf(temp,"Lon:%11.7f",gpsData.Longitude/10000000.0f); + write_string(temp, APPLY_HDEADBAND(20), APPLY_VDEADBAND(GRAPHICS_BOTTOM-10), 0, 0, TEXT_VA_BOTTOM, TEXT_HA_LEFT, 0, 3); + sprintf(temp,"Sat:%d",(int)gpsData.Satellites); + write_string(temp, APPLY_HDEADBAND(GRAPHICS_RIGHT-40), APPLY_VDEADBAND(30), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); + + /* Print ADC voltage FLIGHT*/ + sprintf(temp,"V:%5.2fV",(PIOS_ADC_PinGet(2)*3*6.1f/4096)); + write_string(temp, APPLY_HDEADBAND(20), APPLY_VDEADBAND(20), 0, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 3); + + if(gpsData.Heading>180) + calcHomeArrow((int16_t)(gpsData.Heading-360)); + else + calcHomeArrow((int16_t)(gpsData.Heading)); + } + break; + case 1: + { + /*drawBox(2,2,GRAPHICS_WIDTH_REAL-4,GRAPHICS_HEIGHT_REAL-4); + write_filled_rectangle(draw_buffer_mask,0,0,GRAPHICS_WIDTH_REAL-2,GRAPHICS_HEIGHT_REAL-2,0); + write_filled_rectangle(draw_buffer_mask,2,2,GRAPHICS_WIDTH_REAL-4-2,GRAPHICS_HEIGHT_REAL-4-2,2); + write_filled_rectangle(draw_buffer_mask,3,3,GRAPHICS_WIDTH_REAL-4-1,GRAPHICS_HEIGHT_REAL-4-1,0);*/ + //write_filled_rectangle(draw_buffer_mask,5,5,GRAPHICS_WIDTH_REAL-4-5,GRAPHICS_HEIGHT_REAL-4-5,0); + //write_rectangle_outlined(10,10,GRAPHICS_WIDTH_REAL-20,GRAPHICS_HEIGHT_REAL-20,0,0); + //drawLine(GRAPHICS_WIDTH_REAL-1, GRAPHICS_HEIGHT_REAL-1,(GRAPHICS_WIDTH_REAL/2)-1, GRAPHICS_HEIGHT_REAL-1 ); + //drawCircle((GRAPHICS_WIDTH_REAL/2)-1, (GRAPHICS_HEIGHT_REAL/2)-1, (GRAPHICS_HEIGHT_REAL/2)-1); + //drawCircle((GRAPHICS_SIZE/2)-1, (GRAPHICS_SIZE/2)-1, (GRAPHICS_SIZE/2)-2); + //drawLine(0, (GRAPHICS_SIZE/2)-1, GRAPHICS_SIZE-1, (GRAPHICS_SIZE/2)-1); + //drawLine((GRAPHICS_SIZE/2)-1, 0, (GRAPHICS_SIZE/2)-1, GRAPHICS_SIZE-1); + /*angleA++; + if(angleB<=-90) + { + sum=2; + } + if(angleB>=90) + { + sum=-2; + } + angleB+=sum; + angleC+=2;*/ + + // GPS HACK + if(gpsData.Heading>180) + calcHomeArrow((int16_t)(gpsData.Heading-360)); + else + calcHomeArrow((int16_t)(gpsData.Heading)); + + /* Draw Attitude Indicator */ + if(OsdSettings.Attitude == OSDSETTINGS_ATTITUDE_ENABLED) + { + drawAttitude(APPLY_HDEADBAND(OsdSettings.AttitudeSetup[OSDSETTINGS_ATTITUDESETUP_X]),APPLY_VDEADBAND(OsdSettings.AttitudeSetup[OSDSETTINGS_ATTITUDESETUP_Y]),attitude.Pitch,attitude.Roll,96); + } + //write_string("Hello OP-OSD", 60, 12, 1, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 0); + //printText16( 60, 12,"Hello OP-OSD"); + + char temp[50]={0}; + memset(temp, ' ', 40); + sprintf(temp,"Lat:%11.7f",gpsData.Latitude/10000000.0f); + write_string(temp, APPLY_HDEADBAND(5), APPLY_VDEADBAND(5), 0, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 2); + sprintf(temp,"Lon:%11.7f",gpsData.Longitude/10000000.0f); + write_string(temp, APPLY_HDEADBAND(5), APPLY_VDEADBAND(15), 0, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 2); + sprintf(temp,"Fix:%d",(int)gpsData.Status); + write_string(temp, APPLY_HDEADBAND(5), APPLY_VDEADBAND(25), 0, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 2); + sprintf(temp,"Sat:%d",(int)gpsData.Satellites); + write_string(temp, APPLY_HDEADBAND(5), APPLY_VDEADBAND(35), 0, 0, TEXT_VA_TOP, TEXT_HA_LEFT, 0, 2); + + + /* Print RTC time */ + if(OsdSettings.Time == OSDSETTINGS_TIME_ENABLED) + { + printTime(APPLY_HDEADBAND(OsdSettings.TimeSetup[OSDSETTINGS_TIMESETUP_X]),APPLY_VDEADBAND(OsdSettings.TimeSetup[OSDSETTINGS_TIMESETUP_Y])); + } + + /* Print Number of detected video Lines */ + sprintf(temp,"Lines:%4d",PIOS_Video_GetOSDLines()); + write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(5), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); + + /* Print ADC voltage */ + //sprintf(temp,"Rssi:%4dV",(int)(PIOS_ADC_PinGet(4)*3000/4096)); + //write_string(temp, (GRAPHICS_WIDTH_REAL - 2),15, 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); + sprintf(temp,"Rssi:%4.2fV",(PIOS_ADC_PinGet(5)*3.0f/4096.0f)); + write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(15), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); + + /* Print CPU temperature */ + sprintf(temp,"Temp:%4.2fC",(PIOS_ADC_PinGet(3)*0.29296875f-264)); + write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(25), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); + + /* Print ADC voltage FLIGHT*/ + sprintf(temp,"FltV:%4.2fV",(PIOS_ADC_PinGet(2)*3.0f*6.1f/4096.0f)); + write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(35), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); + + /* Print ADC voltage VIDEO*/ + sprintf(temp,"VidV:%4.2fV",(PIOS_ADC_PinGet(4)*3.0f*6.1f/4096.0f)); + write_string(temp, APPLY_HDEADBAND((GRAPHICS_RIGHT - 8)),APPLY_VDEADBAND(45), 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); + + /* Print ADC voltage RSSI */ + //sprintf(temp,"Curr:%4dA",(int)(PIOS_ADC_PinGet(0)*300*61/4096)); + //write_string(temp, (GRAPHICS_WIDTH_REAL - 2),60, 0, 0, TEXT_VA_TOP, TEXT_HA_RIGHT, 0, 2); + + /* Draw Battery Gauge */ + /*m_batt++; + uint8_t dir=3; + if(m_batt==101) + m_batt=0; + if(m_pitch>0) + { + dir=0; + m_alt+=m_pitch/2; + } + else if(m_pitch<0) + { + dir=1; + m_alt+=m_pitch/2; + }*/ + + /*if(OsdSettings.Battery == OSDSETTINGS_BATTERY_ENABLED) + { + drawBattery(APPLY_HDEADBAND(OsdSettings.BatterySetup[OSDSETTINGS_BATTERYSETUP_X]),APPLY_VDEADBAND(OsdSettings.BatterySetup[OSDSETTINGS_BATTERYSETUP_Y]),m_batt,16); + }*/ + + //drawAltitude(200,50,m_alt,dir); + + + //drawArrow(96,GRAPHICS_HEIGHT_REAL/2,angleB,32); + + // Draw airspeed (left side.) + if(OsdSettings.Speed == OSDSETTINGS_SPEED_ENABLED) + { + hud_draw_vertical_scale((int)gpsData.Groundspeed, 100, -1, APPLY_HDEADBAND(OsdSettings.SpeedSetup[OSDSETTINGS_SPEEDSETUP_X]), + APPLY_VDEADBAND(OsdSettings.SpeedSetup[OSDSETTINGS_SPEEDSETUP_Y]), 100, 10, 20, 7, 12, 15, 1000, HUD_VSCALE_FLAG_NO_NEGATIVE); + } + // Draw altimeter (right side.) + if(OsdSettings.Altitude == OSDSETTINGS_ALTITUDE_ENABLED) + { + hud_draw_vertical_scale((int)gpsData.Altitude, 200, +1, APPLY_HDEADBAND(OsdSettings.AltitudeSetup[OSDSETTINGS_ALTITUDESETUP_X]), + APPLY_VDEADBAND(OsdSettings.AltitudeSetup[OSDSETTINGS_ALTITUDESETUP_Y]), 100, 20, 100, 7, 12, 15, 500, 0); + } + // Draw compass. + if(OsdSettings.Heading == OSDSETTINGS_HEADING_ENABLED) + { + if(attitude.Yaw<0) { + hud_draw_linear_compass(360+attitude.Yaw, 150, 120, APPLY_HDEADBAND(OsdSettings.HeadingSetup[OSDSETTINGS_HEADINGSETUP_X]), + APPLY_VDEADBAND(OsdSettings.HeadingSetup[OSDSETTINGS_HEADINGSETUP_Y]), 15, 30, 7, 12, 0); + } else { + hud_draw_linear_compass(attitude.Yaw, 150, 120, APPLY_HDEADBAND(OsdSettings.HeadingSetup[OSDSETTINGS_HEADINGSETUP_X]), + APPLY_VDEADBAND(OsdSettings.HeadingSetup[OSDSETTINGS_HEADINGSETUP_Y]), 15, 30, 7, 12, 0); + } + } + } + break; + case 2: + { + int size=64; + int x=((GRAPHICS_RIGHT/2)-(size/2)),y=(GRAPHICS_BOTTOM-size-2); + draw_artificial_horizon(-attitude.Roll,attitude.Pitch,APPLY_HDEADBAND(x),APPLY_VDEADBAND(y),size); + hud_draw_vertical_scale((int)gpsData.Groundspeed, 20, +1, APPLY_HDEADBAND(GRAPHICS_RIGHT-(x-1)), + APPLY_VDEADBAND(y+(size/2)), size, 5, 10, 4, 7, 10, 100, HUD_VSCALE_FLAG_NO_NEGATIVE); + if(OsdSettings.AltitudeSource == OSDSETTINGS_ALTITUDESOURCE_BARO) + { + hud_draw_vertical_scale((int)baro.Altitude, 50, -1, APPLY_HDEADBAND((x+size+1)), + APPLY_VDEADBAND(y+(size/2)), size, 10, 20, 4, 7, 10, 500, 0); + } + else + { + hud_draw_vertical_scale((int)gpsData.Altitude, 50, -1, APPLY_HDEADBAND((x+size+1)), + APPLY_VDEADBAND(y+(size/2)), size, 10, 20, 4, 7, 10, 500, 0); + } + + } + break; case 3: { lamas(); } break; - case 4: - case 5: - case 6: - { - int image=OsdSettings.Screen-4; - struct splashEntry splash_info; - splash_info = splash[image]; - - copyimage(APPLY_HDEADBAND(GRAPHICS_RIGHT/2-(splash_info.width)/2), APPLY_VDEADBAND(GRAPHICS_BOTTOM/2-(splash_info.height)/2),image); - } + case 4: + case 5: + case 6: + { + int image=OsdSettings.Screen-4; + struct splashEntry splash_info; + splash_info = splash[image]; + + copyimage(APPLY_HDEADBAND(GRAPHICS_RIGHT/2-(splash_info.width)/2), APPLY_VDEADBAND(GRAPHICS_BOTTOM/2-(splash_info.height)/2),image); + } break; - default: - write_vline_lm( APPLY_HDEADBAND(GRAPHICS_RIGHT/2),APPLY_VDEADBAND(0),APPLY_VDEADBAND(GRAPHICS_BOTTOM),1,1); - write_hline_lm( APPLY_HDEADBAND(0),APPLY_HDEADBAND(GRAPHICS_RIGHT),APPLY_VDEADBAND(GRAPHICS_BOTTOM/2),1,1); - break; - } - - // Must mask out last half-word because SPI keeps clocking it out otherwise - for (uint32_t i = 0; i < 8; i++) { - write_vline( draw_buffer_level,GRAPHICS_WIDTH_REAL-i-1,0,GRAPHICS_HEIGHT_REAL-1,0); - write_vline( draw_buffer_mask,GRAPHICS_WIDTH_REAL-i-1,0,GRAPHICS_HEIGHT_REAL-1,0); - } -} - -void updateOnceEveryFrame() { - clearGraphics(); - updateGraphics(); -} - - -// **************** -/** - * Initialise the gps module - * \return -1 if initialisation failed - * \return 0 on success - */ - -int32_t osdgenStart(void) -{ - // Start gps task - vSemaphoreCreateBinary( osdSemaphore); - xTaskCreate(osdgenTask, (signed char *)"OSDGEN", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &osdgenTaskHandle); - TaskMonitorAdd(TASKINFO_RUNNING_OSDGEN, osdgenTaskHandle); - - return 0; -} - -/** - * Initialise the osd module - * \return -1 if initialisation failed - * \return 0 on success - */ -int32_t osdgenInitialize(void) -{ - AttitudeActualInitialize(); -#ifdef PIOS_INCLUDE_GPS - GPSPositionInitialize(); -#if !defined(PIOS_GPS_MINIMAL) - GPSTimeInitialize(); - GPSSatellitesInitialize(); -#endif -#ifdef PIOS_GPS_SETS_HOMELOCATION - HomeLocationInitialize(); -#endif -#endif - OsdSettingsInitialize(); - BaroAltitudeInitialize(); - - return 0; -} -MODULE_INITCALL(osdgenInitialize, osdgenStart) - -// **************** -/** - * Main osd task. It does not return. - */ - -static void osdgenTask(void *parameters) -{ - //portTickType lastSysTime; - // Loop forever - //lastSysTime = xTaskGetTickCount(); - OsdSettingsData OsdSettings; - OsdSettingsGet (&OsdSettings); - - PIOS_Servo_Set(0,OsdSettings.White); - PIOS_Servo_Set(1,OsdSettings.Black); - - // intro - for(int i=0; i<63; i++) - { - if( xSemaphoreTake( osdSemaphore, LONG_TIME ) == pdTRUE ) - { - clearGraphics(); - introGraphics(); - } - } - for(int i=0; i<63; i++) - { - if( xSemaphoreTake( osdSemaphore, LONG_TIME ) == pdTRUE ) - { - clearGraphics(); - introGraphics(); - introText(); - } - } - - while (1) - { - if( xSemaphoreTake( osdSemaphore, LONG_TIME ) == pdTRUE ) - { - updateOnceEveryFrame(); - } - //xSemaphoreTake(osdSemaphore, portMAX_DELAY); - //vTaskDelayUntil(&lastSysTime, 10 / portTICK_RATE_MS); - } -} - - -// **************** - -/** - * @} - * @} - */ + default: + write_vline_lm( APPLY_HDEADBAND(GRAPHICS_RIGHT/2),APPLY_VDEADBAND(0),APPLY_VDEADBAND(GRAPHICS_BOTTOM),1,1); + write_hline_lm( APPLY_HDEADBAND(0),APPLY_HDEADBAND(GRAPHICS_RIGHT),APPLY_VDEADBAND(GRAPHICS_BOTTOM/2),1,1); + break; + } + + // Must mask out last half-word because SPI keeps clocking it out otherwise + for (uint32_t i = 0; i < 8; i++) { + write_vline( draw_buffer_level,GRAPHICS_WIDTH_REAL-i-1,0,GRAPHICS_HEIGHT_REAL-1,0); + write_vline( draw_buffer_mask,GRAPHICS_WIDTH_REAL-i-1,0,GRAPHICS_HEIGHT_REAL-1,0); + } +} + +void updateOnceEveryFrame() { + clearGraphics(); + updateGraphics(); +} + + +// **************** +/** + * Initialise the gps module + * \return -1 if initialisation failed + * \return 0 on success + */ + +int32_t osdgenStart(void) +{ + // Start gps task + vSemaphoreCreateBinary( osdSemaphore); + xTaskCreate(osdgenTask, (signed char *)"OSDGEN", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &osdgenTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_OSDGEN, osdgenTaskHandle); + + return 0; +} + +/** + * Initialise the osd module + * \return -1 if initialisation failed + * \return 0 on success + */ +int32_t osdgenInitialize(void) +{ + AttitudeActualInitialize(); +#ifdef PIOS_INCLUDE_GPS + GPSPositionInitialize(); +#if !defined(PIOS_GPS_MINIMAL) + GPSTimeInitialize(); + GPSSatellitesInitialize(); +#endif +#ifdef PIOS_GPS_SETS_HOMELOCATION + HomeLocationInitialize(); +#endif +#endif + OsdSettingsInitialize(); + BaroAltitudeInitialize(); + + return 0; +} +MODULE_INITCALL(osdgenInitialize, osdgenStart) + +// **************** +/** + * Main osd task. It does not return. + */ + +static void osdgenTask(void *parameters) +{ + //portTickType lastSysTime; + // Loop forever + //lastSysTime = xTaskGetTickCount(); + OsdSettingsData OsdSettings; + OsdSettingsGet (&OsdSettings); + + PIOS_Servo_Set(0,OsdSettings.White); + PIOS_Servo_Set(1,OsdSettings.Black); + + // intro + for(int i=0; i<63; i++) + { + if( xSemaphoreTake( osdSemaphore, LONG_TIME ) == pdTRUE ) + { + clearGraphics(); + introGraphics(); + } + } + for(int i=0; i<63; i++) + { + if( xSemaphoreTake( osdSemaphore, LONG_TIME ) == pdTRUE ) + { + clearGraphics(); + introGraphics(); + introText(); + } + } + + while (1) + { + if( xSemaphoreTake( osdSemaphore, LONG_TIME ) == pdTRUE ) + { + updateOnceEveryFrame(); + } + //xSemaphoreTake(osdSemaphore, portMAX_DELAY); + //vTaskDelayUntil(&lastSysTime, 10 / portTICK_RATE_MS); + } +} + + +// **************** + +/** + * @} + * @} + */ diff --git a/flight/Modules/Osd/osdinput/inc/osdinput.h b/flight/Modules/Osd/osdinput/inc/osdinput.h index b19318a47..58e506ae1 100644 --- a/flight/Modules/Osd/osdinput/inc/osdinput.h +++ b/flight/Modules/Osd/osdinput/inc/osdinput.h @@ -1,15 +1,15 @@ -/* - * OpOsd.h - * - * Created on: 2.10.2011 - * Author: Samba - */ - -#ifndef OPOSD_H_ -#define OPOSD_H_ - -#include "openpilot.h" - -int32_t OpOsdInitialize(void); - -#endif /* OPOSD_H_ */ +/* + * OpOsd.h + * + * Created on: 2.10.2011 + * Author: Samba + */ + +#ifndef OPOSD_H_ +#define OPOSD_H_ + +#include "openpilot.h" + +int32_t OpOsdInitialize(void); + +#endif /* OPOSD_H_ */ diff --git a/flight/Modules/Osd/osdinput/osdinput.c b/flight/Modules/Osd/osdinput/osdinput.c index 33c81405d..b0a6acd89 100644 --- a/flight/Modules/Osd/osdinput/osdinput.c +++ b/flight/Modules/Osd/osdinput/osdinput.c @@ -1,292 +1,292 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules - * @{ - * @addtogroup osdinputModule osdinput Module - * @brief Process osdinput information - * @{ - * - * @file osdinput.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief osdinput module, handles osdinput stream - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -// **************** - -#include "openpilot.h" -#include "osdinput.h" -#include "attitudeactual.h" -#include "fifo_buffer.h" - - -// **************** -// Private functions - -static void OpOsdTask(void *parameters); - -// **************** -// Private constants - -#define GPS_TIMEOUT_MS 500 -#define NMEA_MAX_PACKET_LENGTH 33 // 82 max NMEA msg size plus 12 margin (because some vendors add custom crap) plus CR plus Linefeed -// same as in COM buffer - - -#ifdef PIOS_GPS_SETS_HOMELOCATION -// Unfortunately need a good size stack for the WMM calculation - #define STACK_SIZE_BYTES 800 -#else - #define STACK_SIZE_BYTES 1024 -#endif - -#define TASK_PRIORITY (tskIDLE_PRIORITY + 4) - -// **************** -// Private variables - -static uint32_t oposdPort; - -static xTaskHandle OpOsdTaskHandle; - -static char* oposd_rx_buffer; -t_fifo_buffer rx; - -static uint32_t timeOfLastCommandMs; -static uint32_t timeOfLastUpdateMs; -static uint32_t numUpdates; -static uint32_t numChecksumErrors; -static uint32_t numParsingErrors; - -// **************** -/** - * Initialise the gps module - * \return -1 if initialisation failed - * \return 0 on success - */ - -int32_t OpOsdStart(void) -{ - // Start gps task - xTaskCreate(OpOsdTask, (signed char *)"OSD", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &OpOsdTaskHandle); - //TaskMonitorAdd(TASKINFO_RUNNING_GPS, OpOsdTaskHandle); - - return 0; -} -/** - * Initialise the gps module - * \return -1 if initialisation failed - * \return 0 on success - */ -int32_t OpOsdInitialize(void) -{ - AttitudeActualInitialize(); - // Initialize quaternion - AttitudeActualData attitude; - AttitudeActualGet(&attitude); - attitude.q1 = 1; - attitude.q2 = 0; - attitude.q3 = 0; - attitude.q4 = 0; - attitude.Roll = 0; - attitude.Pitch = 0; - attitude.Yaw = 0; - AttitudeActualSet(&attitude); - - - // TODO: Get gps settings object - oposdPort = PIOS_COM_OSD; - - oposd_rx_buffer = pvPortMalloc(NMEA_MAX_PACKET_LENGTH); - PIOS_Assert(oposd_rx_buffer); - - return 0; -} -MODULE_INITCALL(OpOsdInitialize, OpOsdStart) - -// **************** -/** - * Main gps task. It does not return. - */ - -static void OpOsdTask(void *parameters) -{ - portTickType xDelay = 100 / portTICK_RATE_MS; - portTickType lastSysTime; - // Loop forever - lastSysTime = xTaskGetTickCount(); //portTickType xDelay = 100 / portTICK_RATE_MS; - uint32_t timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS;; - //GPSPositionData GpsData; - - //uint8_t rx_count = 0; - //bool start_flag = false; - //bool found_cr = false; - //int32_t gpsRxOverflow = 0; - - numUpdates = 0; - numChecksumErrors = 0; - numParsingErrors = 0; - - timeOfLastUpdateMs = timeNowMs; - timeOfLastCommandMs = timeNowMs; - uint8_t rx_count = 0; - bool start_flag = false; - //bool found_cr = false; - int32_t gpsRxOverflow = 0; - uint8_t c=0xAA; - // Loop forever - while (1) - { - /*//DMA_Cmd(DMA1_Stream2, DISABLE); //prohibit channel3 for a little time - uint16_t cnt = DMA_GetCurrDataCounter(DMA1_Stream2); - rx.wr = rx.buf_size-cnt; - if(rx.wr) - { - //PIOS_LED_Toggle(LED2); - while ( fifoBuf_getData(&rx, &c, 1) > 0) - { - - // detect start while acquiring stream - if (!start_flag && ((c == 0xCB) || (c == 0x34))) - { - start_flag = true; - rx_count = 0; - } - else - if (!start_flag) - continue; - - if (rx_count >= 11) - { - // The buffer is already full and we haven't found a valid NMEA sentence. - // Flush the buffer and note the overflow event. - gpsRxOverflow++; - start_flag = false; - rx_count = 0; - } - else - { - oposd_rx_buffer[rx_count] = c; - rx_count++; - } - if (start_flag && rx_count == 11) - { - //PIOS_LED_Toggle(LED3); - if(oposd_rx_buffer[1]==3) - { - AttitudeActualData attitude; - AttitudeActualGet(&attitude); - attitude.q1 = 1; - attitude.q2 = 0; - attitude.q3 = 0; - attitude.q4 = 0; - attitude.Roll = (int16_t)(oposd_rx_buffer[3] | oposd_rx_buffer[4]<<8); - attitude.Pitch = (int16_t)(oposd_rx_buffer[5] | oposd_rx_buffer[6]<<8); - attitude.Yaw = (int16_t)(oposd_rx_buffer[7] | oposd_rx_buffer[8]<<8); - AttitudeActualSet(&attitude); - //setAttitudeOsd((int16_t)(oposd_rx_buffer[5] | oposd_rx_buffer[6]<<8), //pitch - // (int16_t)(oposd_rx_buffer[3] | oposd_rx_buffer[4]<<8), //roll - // (int16_t)(oposd_rx_buffer[7] | oposd_rx_buffer[8]<<8)); //yaw - - } - //frame completed - start_flag = false; - rx_count = 0; - } - } - } - //DMA_Cmd(DMA1_Stream2, ENABLE); - - */ - - //PIOS_COM_SendBufferNonBlocking(oposdPort, &c, 1); - - // This blocks the task until there is something on the buffer - while (PIOS_COM_ReceiveBuffer(oposdPort, &c, 1, xDelay) > 0) - { - - // detect start while acquiring stream - if (!start_flag && ((c == 0xCB) || (c == 0x34))) - { - start_flag = true; - rx_count = 0; - } - else - if (!start_flag) - continue; - - if (rx_count >= 11) - { - // The buffer is already full and we haven't found a valid NMEA sentence. - // Flush the buffer and note the overflow event. - gpsRxOverflow++; - start_flag = false; - rx_count = 0; - } - else - { - oposd_rx_buffer[rx_count] = c; - rx_count++; - } - if (rx_count == 11) - { - if(oposd_rx_buffer[1]==3) - { - AttitudeActualData attitude; - AttitudeActualGet(&attitude); - attitude.q1 = 1; - attitude.q2 = 0; - attitude.q3 = 0; - attitude.q4 = 0; - attitude.Roll = (int16_t)(oposd_rx_buffer[3] | oposd_rx_buffer[4]<<8); - attitude.Pitch = (int16_t)(oposd_rx_buffer[5] | oposd_rx_buffer[6]<<8); - attitude.Yaw = (int16_t)(oposd_rx_buffer[7] | oposd_rx_buffer[8]<<8); - AttitudeActualSet(&attitude); - } - //frame completed - start_flag = false; - rx_count = 0; - - } - } - vTaskDelayUntil(&lastSysTime, 50 / portTICK_RATE_MS); - // Check for GPS timeout - timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; - if ((timeNowMs - timeOfLastUpdateMs) >= GPS_TIMEOUT_MS) - { // we have not received any valid GPS sentences for a while. - // either the GPS is not plugged in or a hardware problem or the GPS has locked up. - - - } - else - { // we appear to be receiving GPS sentences OK, we've had an update - - - } - - } -} - - -// **************** - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup osdinputModule osdinput Module + * @brief Process osdinput information + * @{ + * + * @file osdinput.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief osdinput module, handles osdinput stream + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +// **************** + +#include "openpilot.h" +#include "osdinput.h" +#include "attitudeactual.h" +#include "fifo_buffer.h" + + +// **************** +// Private functions + +static void OpOsdTask(void *parameters); + +// **************** +// Private constants + +#define GPS_TIMEOUT_MS 500 +#define NMEA_MAX_PACKET_LENGTH 33 // 82 max NMEA msg size plus 12 margin (because some vendors add custom crap) plus CR plus Linefeed +// same as in COM buffer + + +#ifdef PIOS_GPS_SETS_HOMELOCATION +// Unfortunately need a good size stack for the WMM calculation + #define STACK_SIZE_BYTES 800 +#else + #define STACK_SIZE_BYTES 1024 +#endif + +#define TASK_PRIORITY (tskIDLE_PRIORITY + 4) + +// **************** +// Private variables + +static uint32_t oposdPort; + +static xTaskHandle OpOsdTaskHandle; + +static char* oposd_rx_buffer; +t_fifo_buffer rx; + +static uint32_t timeOfLastCommandMs; +static uint32_t timeOfLastUpdateMs; +static uint32_t numUpdates; +static uint32_t numChecksumErrors; +static uint32_t numParsingErrors; + +// **************** +/** + * Initialise the gps module + * \return -1 if initialisation failed + * \return 0 on success + */ + +int32_t OpOsdStart(void) +{ + // Start gps task + xTaskCreate(OpOsdTask, (signed char *)"OSD", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &OpOsdTaskHandle); + //TaskMonitorAdd(TASKINFO_RUNNING_GPS, OpOsdTaskHandle); + + return 0; +} +/** + * Initialise the gps module + * \return -1 if initialisation failed + * \return 0 on success + */ +int32_t OpOsdInitialize(void) +{ + AttitudeActualInitialize(); + // Initialize quaternion + AttitudeActualData attitude; + AttitudeActualGet(&attitude); + attitude.q1 = 1; + attitude.q2 = 0; + attitude.q3 = 0; + attitude.q4 = 0; + attitude.Roll = 0; + attitude.Pitch = 0; + attitude.Yaw = 0; + AttitudeActualSet(&attitude); + + + // TODO: Get gps settings object + oposdPort = PIOS_COM_OSD; + + oposd_rx_buffer = pvPortMalloc(NMEA_MAX_PACKET_LENGTH); + PIOS_Assert(oposd_rx_buffer); + + return 0; +} +MODULE_INITCALL(OpOsdInitialize, OpOsdStart) + +// **************** +/** + * Main gps task. It does not return. + */ + +static void OpOsdTask(void *parameters) +{ + portTickType xDelay = 100 / portTICK_RATE_MS; + portTickType lastSysTime; + // Loop forever + lastSysTime = xTaskGetTickCount(); //portTickType xDelay = 100 / portTICK_RATE_MS; + uint32_t timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS;; + //GPSPositionData GpsData; + + //uint8_t rx_count = 0; + //bool start_flag = false; + //bool found_cr = false; + //int32_t gpsRxOverflow = 0; + + numUpdates = 0; + numChecksumErrors = 0; + numParsingErrors = 0; + + timeOfLastUpdateMs = timeNowMs; + timeOfLastCommandMs = timeNowMs; + uint8_t rx_count = 0; + bool start_flag = false; + //bool found_cr = false; + int32_t gpsRxOverflow = 0; + uint8_t c=0xAA; + // Loop forever + while (1) + { + /*//DMA_Cmd(DMA1_Stream2, DISABLE); //prohibit channel3 for a little time + uint16_t cnt = DMA_GetCurrDataCounter(DMA1_Stream2); + rx.wr = rx.buf_size-cnt; + if(rx.wr) + { + //PIOS_LED_Toggle(LED2); + while ( fifoBuf_getData(&rx, &c, 1) > 0) + { + + // detect start while acquiring stream + if (!start_flag && ((c == 0xCB) || (c == 0x34))) + { + start_flag = true; + rx_count = 0; + } + else + if (!start_flag) + continue; + + if (rx_count >= 11) + { + // The buffer is already full and we haven't found a valid NMEA sentence. + // Flush the buffer and note the overflow event. + gpsRxOverflow++; + start_flag = false; + rx_count = 0; + } + else + { + oposd_rx_buffer[rx_count] = c; + rx_count++; + } + if (start_flag && rx_count == 11) + { + //PIOS_LED_Toggle(LED3); + if(oposd_rx_buffer[1]==3) + { + AttitudeActualData attitude; + AttitudeActualGet(&attitude); + attitude.q1 = 1; + attitude.q2 = 0; + attitude.q3 = 0; + attitude.q4 = 0; + attitude.Roll = (int16_t)(oposd_rx_buffer[3] | oposd_rx_buffer[4]<<8); + attitude.Pitch = (int16_t)(oposd_rx_buffer[5] | oposd_rx_buffer[6]<<8); + attitude.Yaw = (int16_t)(oposd_rx_buffer[7] | oposd_rx_buffer[8]<<8); + AttitudeActualSet(&attitude); + //setAttitudeOsd((int16_t)(oposd_rx_buffer[5] | oposd_rx_buffer[6]<<8), //pitch + // (int16_t)(oposd_rx_buffer[3] | oposd_rx_buffer[4]<<8), //roll + // (int16_t)(oposd_rx_buffer[7] | oposd_rx_buffer[8]<<8)); //yaw + + } + //frame completed + start_flag = false; + rx_count = 0; + } + } + } + //DMA_Cmd(DMA1_Stream2, ENABLE); + + */ + + //PIOS_COM_SendBufferNonBlocking(oposdPort, &c, 1); + + // This blocks the task until there is something on the buffer + while (PIOS_COM_ReceiveBuffer(oposdPort, &c, 1, xDelay) > 0) + { + + // detect start while acquiring stream + if (!start_flag && ((c == 0xCB) || (c == 0x34))) + { + start_flag = true; + rx_count = 0; + } + else + if (!start_flag) + continue; + + if (rx_count >= 11) + { + // The buffer is already full and we haven't found a valid NMEA sentence. + // Flush the buffer and note the overflow event. + gpsRxOverflow++; + start_flag = false; + rx_count = 0; + } + else + { + oposd_rx_buffer[rx_count] = c; + rx_count++; + } + if (rx_count == 11) + { + if(oposd_rx_buffer[1]==3) + { + AttitudeActualData attitude; + AttitudeActualGet(&attitude); + attitude.q1 = 1; + attitude.q2 = 0; + attitude.q3 = 0; + attitude.q4 = 0; + attitude.Roll = (int16_t)(oposd_rx_buffer[3] | oposd_rx_buffer[4]<<8); + attitude.Pitch = (int16_t)(oposd_rx_buffer[5] | oposd_rx_buffer[6]<<8); + attitude.Yaw = (int16_t)(oposd_rx_buffer[7] | oposd_rx_buffer[8]<<8); + AttitudeActualSet(&attitude); + } + //frame completed + start_flag = false; + rx_count = 0; + + } + } + vTaskDelayUntil(&lastSysTime, 50 / portTICK_RATE_MS); + // Check for GPS timeout + timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; + if ((timeNowMs - timeOfLastUpdateMs) >= GPS_TIMEOUT_MS) + { // we have not received any valid GPS sentences for a while. + // either the GPS is not plugged in or a hardware problem or the GPS has locked up. + + + } + else + { // we appear to be receiving GPS sentences OK, we've had an update + + + } + + } +} + + +// **************** + +/** + * @} + * @} + */ diff --git a/flight/Modules/Stabilization/inc/stabilization.h b/flight/Modules/Stabilization/inc/stabilization.h index ec0ae4e9f..81adb6235 100644 --- a/flight/Modules/Stabilization/inc/stabilization.h +++ b/flight/Modules/Stabilization/inc/stabilization.h @@ -1,45 +1,45 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules - * @{ - * @addtogroup StabilizationModule Stabilization Module - * @brief Stabilization PID loops in an airframe type independent manner - * @note This object updates the @ref ActuatorDesired "Actuator Desired" based on the - * PID loops on the @ref AttitudeDesired "Attitude Desired" and @ref AttitudeActual "Attitude Actual" - * @{ - * - * @file stabilization.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Attitude stabilization module. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef STABILIZATION_H -#define STABILIZATION_H - -enum {ROLL,PITCH,YAW,MAX_AXES}; - -int32_t StabilizationInitialize(); - -#endif // STABILIZATION_H - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup StabilizationModule Stabilization Module + * @brief Stabilization PID loops in an airframe type independent manner + * @note This object updates the @ref ActuatorDesired "Actuator Desired" based on the + * PID loops on the @ref AttitudeDesired "Attitude Desired" and @ref AttitudeActual "Attitude Actual" + * @{ + * + * @file stabilization.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Attitude stabilization module. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef STABILIZATION_H +#define STABILIZATION_H + +enum {ROLL,PITCH,YAW,MAX_AXES}; + +int32_t StabilizationInitialize(); + +#endif // STABILIZATION_H + +/** + * @} + * @} + */ diff --git a/flight/PiOS.osx/inc/FreeRTOSConfig.h b/flight/PiOS.osx/inc/FreeRTOSConfig.h index d82725de1..46bb2dcb4 100644 --- a/flight/PiOS.osx/inc/FreeRTOSConfig.h +++ b/flight/PiOS.osx/inc/FreeRTOSConfig.h @@ -1,112 +1,112 @@ - -#ifndef FREERTOS_CONFIG_H -#define FREERTOS_CONFIG_H - -/*----------------------------------------------------------- - * Application specific definitions. - * - * These definitions should be adjusted for your particular hardware and - * application requirements. - * - * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE - * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. - * - * See http://www.freertos.org/a00110.html. - *----------------------------------------------------------*/ - -/* Notes: We use 5 task priorities */ - - -#ifdef __APPLE__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES - #define RUNNING_THREAD_MUTEX -// #define TICK_SIGNAL -// #define TICK_SIGWAIT - #define IDLE_SLEEPS - - #define configUSE_PREEMPTION 1 - #define configIDLE_SHOULD_YIELD 0 -#endif -#ifdef __CYGWIN__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES -// #define RUNNING_THREAD_MUTEX -// #define TICK_SIGNAL - #define TICK_SIGWAIT - #define IDLE_SLEEPS - - #define configUSE_PREEMPTION 0 - #define configIDLE_SHOULD_YIELD 1 -#endif -#ifdef __linux__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES - #define RUNNING_THREAD_MUTEX -// #define TICK_SIGNAL -// #define TICK_SIGWAIT - #define IDLE_SLEEPS - - #define configUSE_PREEMPTION 1 - #define configIDLE_SHOULD_YIELD 0 -#endif - - -#define configUSE_IDLE_HOOK 1 -#define configUSE_TICK_HOOK 0 -#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) -#define configTICK_RATE_HZ ( ( portTickType ) 1000 ) -#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) -#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 ) -#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 45 * 1024 ) ) -#define configMAX_TASK_NAME_LEN ( 16 ) -#define configUSE_TRACE_FACILITY 0 -#define configUSE_16_BIT_TICKS 0 -#define configUSE_MUTEXES 1 -#define configUSE_RECURSIVE_MUTEXES 1 -#define configUSE_COUNTING_SEMAPHORES 0 -#define configUSE_ALTERNATIVE_API 0 -#define configCHECK_FOR_STACK_OVERFLOW 2 -#define configQUEUE_REGISTRY_SIZE 10 - - -/* Co-routine definitions. */ -#define configUSE_CO_ROUTINES 0 -#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) - -/* Set the following definitions to 1 to include the API function, or zero -to exclude the API function. */ - -#define INCLUDE_vTaskPrioritySet 1 -#define INCLUDE_uxTaskPriorityGet 1 -#define INCLUDE_vTaskDelete 1 -#define INCLUDE_vTaskCleanUpResources 0 -#define INCLUDE_vTaskSuspend 1 -#define INCLUDE_vTaskDelayUntil 1 -#define INCLUDE_vTaskDelay 1 -#define INCLUDE_xTaskGetSchedulerState 1 -#define INCLUDE_xTaskGetCurrentTaskHandle 1 -#define INCLUDE_uxTaskGetStackHighWaterMark 0 - -/* Enable run time stats collection */ -#define configGENERATE_RUN_TIME_STATS 1 -#define INCLUDE_uxTaskGetRunTime 1 - -#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() -#define portGET_RUN_TIME_COUNTER_VALUE() clock() - -#error Here -/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 -(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ -#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ -#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ - - -/* This is the value being used as per the ST library which permits 16 -priority values, 0 to 15. This must correspond to the -configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest -NVIC value of 255. */ -#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 - -#endif /* FREERTOS_CONFIG_H */ - + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html. + *----------------------------------------------------------*/ + +/* Notes: We use 5 task priorities */ + + +#ifdef __APPLE__ + #define COND_SIGNALING + #define CHECK_TASK_RESUMES + #define RUNNING_THREAD_MUTEX +// #define TICK_SIGNAL +// #define TICK_SIGWAIT + #define IDLE_SLEEPS + + #define configUSE_PREEMPTION 1 + #define configIDLE_SHOULD_YIELD 0 +#endif +#ifdef __CYGWIN__ + #define COND_SIGNALING + #define CHECK_TASK_RESUMES +// #define RUNNING_THREAD_MUTEX +// #define TICK_SIGNAL + #define TICK_SIGWAIT + #define IDLE_SLEEPS + + #define configUSE_PREEMPTION 0 + #define configIDLE_SHOULD_YIELD 1 +#endif +#ifdef __linux__ + #define COND_SIGNALING + #define CHECK_TASK_RESUMES + #define RUNNING_THREAD_MUTEX +// #define TICK_SIGNAL +// #define TICK_SIGWAIT + #define IDLE_SLEEPS + + #define configUSE_PREEMPTION 1 + #define configIDLE_SHOULD_YIELD 0 +#endif + + +#define configUSE_IDLE_HOOK 1 +#define configUSE_TICK_HOOK 0 +#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) +#define configTICK_RATE_HZ ( ( portTickType ) 1000 ) +#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) +#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 ) +#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 45 * 1024 ) ) +#define configMAX_TASK_NAME_LEN ( 16 ) +#define configUSE_TRACE_FACILITY 0 +#define configUSE_16_BIT_TICKS 0 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 0 +#define configUSE_ALTERNATIVE_API 0 +#define configCHECK_FOR_STACK_OVERFLOW 2 +#define configQUEUE_REGISTRY_SIZE 10 + + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ + +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 0 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 1 +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 0 + +/* Enable run time stats collection */ +#define configGENERATE_RUN_TIME_STATS 1 +#define INCLUDE_uxTaskGetRunTime 1 + +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() +#define portGET_RUN_TIME_COUNTER_VALUE() clock() + +#error Here +/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 +(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ +#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ + + +/* This is the value being used as per the ST library which permits 16 +priority values, 0 to 15. This must correspond to the +configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest +NVIC value of 255. */ +#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 + +#endif /* FREERTOS_CONFIG_H */ + diff --git a/flight/PiOS.osx/inc/pios_iap.h b/flight/PiOS.osx/inc/pios_iap.h index d9b41170b..5119711d5 100644 --- a/flight/PiOS.osx/inc/pios_iap.h +++ b/flight/PiOS.osx/inc/pios_iap.h @@ -1,45 +1,45 @@ -/*! - * @File iap.h - * @Brief Header file for the In-Application-Programming Module - * - * Created on: Sep 6, 2010 - * Author: joe - */ - -#ifndef PIOS_IAP_H_ -#define PIOS_IAP_H_ - - -/**************************************************************************************** - * Header files - ****************************************************************************************/ - -/***************************************************************************************** - * Public Definitions/Macros - ****************************************************************************************/ -#if defined(STM32F4XX) -#define MAGIC_REG_1 RTC_BKP_DR1 -#define MAGIC_REG_2 RTC_BKP_DR2 -#define IAP_BOOTCOUNT RTC_BKP_DR3 -#else -#define MAGIC_REG_1 BKP_DR1 -#define MAGIC_REG_2 BKP_DR2 -#define IAP_BOOTCOUNT BKP_DR3 -#endif - -/**************************************************************************************** - * Public Functions - ****************************************************************************************/ -void PIOS_IAP_Init(void); -uint32_t PIOS_IAP_CheckRequest( void ); -void PIOS_IAP_SetRequest1(void); -void PIOS_IAP_SetRequest2(void); -void PIOS_IAP_ClearRequest(void); -uint16_t PIOS_IAP_ReadBootCount(void); -void PIOS_IAP_WriteBootCount(uint16_t); - -/**************************************************************************************** - * Public Data - ****************************************************************************************/ - -#endif /* PIOS_IAP_H_ */ +/*! + * @File iap.h + * @Brief Header file for the In-Application-Programming Module + * + * Created on: Sep 6, 2010 + * Author: joe + */ + +#ifndef PIOS_IAP_H_ +#define PIOS_IAP_H_ + + +/**************************************************************************************** + * Header files + ****************************************************************************************/ + +/***************************************************************************************** + * Public Definitions/Macros + ****************************************************************************************/ +#if defined(STM32F4XX) +#define MAGIC_REG_1 RTC_BKP_DR1 +#define MAGIC_REG_2 RTC_BKP_DR2 +#define IAP_BOOTCOUNT RTC_BKP_DR3 +#else +#define MAGIC_REG_1 BKP_DR1 +#define MAGIC_REG_2 BKP_DR2 +#define IAP_BOOTCOUNT BKP_DR3 +#endif + +/**************************************************************************************** + * Public Functions + ****************************************************************************************/ +void PIOS_IAP_Init(void); +uint32_t PIOS_IAP_CheckRequest( void ); +void PIOS_IAP_SetRequest1(void); +void PIOS_IAP_SetRequest2(void); +void PIOS_IAP_ClearRequest(void); +uint16_t PIOS_IAP_ReadBootCount(void); +void PIOS_IAP_WriteBootCount(uint16_t); + +/**************************************************************************************** + * Public Data + ****************************************************************************************/ + +#endif /* PIOS_IAP_H_ */ diff --git a/flight/PiOS.osx/inc/pios_sdcard.h b/flight/PiOS.osx/inc/pios_sdcard.h index 225d9de80..2927def2d 100644 --- a/flight/PiOS.osx/inc/pios_sdcard.h +++ b/flight/PiOS.osx/inc/pios_sdcard.h @@ -1,113 +1,113 @@ -/** - ****************************************************************************** - * - * @file pios_sdcard.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief System and hardware Init functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_SDCARD_H -#define PIOS_SDCARD_H - -#if defined(PIOS_INCLUDE_SDCARD) - -/* Public Functions */ -typedef struct { - uint8_t CSDStruct; /* CSD structure */ - uint8_t SysSpecVersion; /* System specification version */ - uint8_t Reserved1; /* Reserved */ - uint8_t TAAC; /* Data read access-time 1 */ - uint8_t NSAC; /* Data read access-time 2 in CLK cycles */ - uint8_t MaxBusClkFrec; /* Max. bus clock frequency */ - uint16_t CardComdClasses; /* Card command classes */ - uint8_t RdBlockLen; /* Max. read data block length */ - uint8_t PartBlockRead; /* Partial blocks for read allowed */ - uint8_t WrBlockMisalign; /* Write block misalignment */ - uint8_t RdBlockMisalign; /* Read block misalignment */ - uint8_t DSRImpl; /* DSR implemented */ - uint8_t Reserved2; /* Reserved */ - uint16_t DeviceSize; /* Device Size */ - uint8_t MaxRdCurrentVDDMin; /* Max. read current @ VDD min */ - uint8_t MaxRdCurrentVDDMax; /* Max. read current @ VDD max */ - uint8_t MaxWrCurrentVDDMin; /* Max. write current @ VDD min */ - uint8_t MaxWrCurrentVDDMax; /* Max. write current @ VDD max */ - uint8_t DeviceSizeMul; /* Device size multiplier */ - uint8_t EraseGrSize; /* Erase group size */ - uint8_t EraseGrMul; /* Erase group size multiplier */ - uint8_t WrProtectGrSize; /* Write protect group size */ - uint8_t WrProtectGrEnable; /* Write protect group enable */ - uint8_t ManDeflECC; /* Manufacturer default ECC */ - uint8_t WrSpeedFact; /* Write speed factor */ - uint8_t MaxWrBlockLen; /* Max. write data block length */ - uint8_t WriteBlockPaPartial; /* Partial blocks for write allowed */ - uint8_t Reserved3; /* Reserved */ - uint8_t ContentProtectAppli; /* Content protection application */ - uint8_t FileFormatGrouop; /* File format group */ - uint8_t CopyFlag; /* Copy flag (OTP) */ - uint8_t PermWrProtect; /* Permanent write protection */ - uint8_t TempWrProtect; /* Temporary write protection */ - uint8_t FileFormat; /* File Format */ - uint8_t ECC; /* ECC code */ - uint8_t msd_CRC; /* CRC */ - uint8_t Reserved4; /* always 1*/ -} SDCARDCsdTypeDef; - -/* Structure taken from Mass Storage Driver example provided by STM */ -typedef struct { - uint8_t ManufacturerID; /* ManufacturerID */ - uint16_t OEM_AppliID; /* OEM/Application ID */ - char ProdName[6]; /* Product Name */ - uint8_t ProdRev; /* Product Revision */ - uint32_t ProdSN; /* Product Serial Number */ - uint8_t Reserved1; /* Reserved1 */ - uint16_t ManufactDate; /* Manufacturing Date */ - uint8_t msd_CRC; /* CRC */ - uint8_t Reserved2; /* always 1*/ -} SDCARDCidTypeDef; - -/* Global Variables */ -//extern VOLINFO PIOS_SDCARD_VolInfo; -//extern uint8_t PIOS_SDCARD_Sector[SECTOR_SIZE]; - -/* Prototypes */ -extern int32_t PIOS_SDCARD_Init(void); -extern int32_t PIOS_SDCARD_PowerOn(void); -extern int32_t PIOS_SDCARD_PowerOff(void); -extern int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available); -extern int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc); -extern int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer); -extern int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer); -extern int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid); -extern int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd); - -extern int32_t PIOS_SDCARD_StartupLog(void); -extern int32_t PIOS_SDCARD_IsMounted(); -extern int32_t PIOS_SDCARD_MountFS(uint32_t StartupLog); -extern int32_t PIOS_SDCARD_GetFree(void); - -//extern int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len); -//extern int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len); -extern int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination); -extern int32_t PIOS_SDCARD_FileDelete(char *Filename); - -#endif - -#endif /* PIOS_SDCARD_H */ +/** + ****************************************************************************** + * + * @file pios_sdcard.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief System and hardware Init functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_SDCARD_H +#define PIOS_SDCARD_H + +#if defined(PIOS_INCLUDE_SDCARD) + +/* Public Functions */ +typedef struct { + uint8_t CSDStruct; /* CSD structure */ + uint8_t SysSpecVersion; /* System specification version */ + uint8_t Reserved1; /* Reserved */ + uint8_t TAAC; /* Data read access-time 1 */ + uint8_t NSAC; /* Data read access-time 2 in CLK cycles */ + uint8_t MaxBusClkFrec; /* Max. bus clock frequency */ + uint16_t CardComdClasses; /* Card command classes */ + uint8_t RdBlockLen; /* Max. read data block length */ + uint8_t PartBlockRead; /* Partial blocks for read allowed */ + uint8_t WrBlockMisalign; /* Write block misalignment */ + uint8_t RdBlockMisalign; /* Read block misalignment */ + uint8_t DSRImpl; /* DSR implemented */ + uint8_t Reserved2; /* Reserved */ + uint16_t DeviceSize; /* Device Size */ + uint8_t MaxRdCurrentVDDMin; /* Max. read current @ VDD min */ + uint8_t MaxRdCurrentVDDMax; /* Max. read current @ VDD max */ + uint8_t MaxWrCurrentVDDMin; /* Max. write current @ VDD min */ + uint8_t MaxWrCurrentVDDMax; /* Max. write current @ VDD max */ + uint8_t DeviceSizeMul; /* Device size multiplier */ + uint8_t EraseGrSize; /* Erase group size */ + uint8_t EraseGrMul; /* Erase group size multiplier */ + uint8_t WrProtectGrSize; /* Write protect group size */ + uint8_t WrProtectGrEnable; /* Write protect group enable */ + uint8_t ManDeflECC; /* Manufacturer default ECC */ + uint8_t WrSpeedFact; /* Write speed factor */ + uint8_t MaxWrBlockLen; /* Max. write data block length */ + uint8_t WriteBlockPaPartial; /* Partial blocks for write allowed */ + uint8_t Reserved3; /* Reserved */ + uint8_t ContentProtectAppli; /* Content protection application */ + uint8_t FileFormatGrouop; /* File format group */ + uint8_t CopyFlag; /* Copy flag (OTP) */ + uint8_t PermWrProtect; /* Permanent write protection */ + uint8_t TempWrProtect; /* Temporary write protection */ + uint8_t FileFormat; /* File Format */ + uint8_t ECC; /* ECC code */ + uint8_t msd_CRC; /* CRC */ + uint8_t Reserved4; /* always 1*/ +} SDCARDCsdTypeDef; + +/* Structure taken from Mass Storage Driver example provided by STM */ +typedef struct { + uint8_t ManufacturerID; /* ManufacturerID */ + uint16_t OEM_AppliID; /* OEM/Application ID */ + char ProdName[6]; /* Product Name */ + uint8_t ProdRev; /* Product Revision */ + uint32_t ProdSN; /* Product Serial Number */ + uint8_t Reserved1; /* Reserved1 */ + uint16_t ManufactDate; /* Manufacturing Date */ + uint8_t msd_CRC; /* CRC */ + uint8_t Reserved2; /* always 1*/ +} SDCARDCidTypeDef; + +/* Global Variables */ +//extern VOLINFO PIOS_SDCARD_VolInfo; +//extern uint8_t PIOS_SDCARD_Sector[SECTOR_SIZE]; + +/* Prototypes */ +extern int32_t PIOS_SDCARD_Init(void); +extern int32_t PIOS_SDCARD_PowerOn(void); +extern int32_t PIOS_SDCARD_PowerOff(void); +extern int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available); +extern int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc); +extern int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer); +extern int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer); +extern int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid); +extern int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd); + +extern int32_t PIOS_SDCARD_StartupLog(void); +extern int32_t PIOS_SDCARD_IsMounted(); +extern int32_t PIOS_SDCARD_MountFS(uint32_t StartupLog); +extern int32_t PIOS_SDCARD_GetFree(void); + +//extern int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len); +//extern int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len); +extern int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination); +extern int32_t PIOS_SDCARD_FileDelete(char *Filename); + +#endif + +#endif /* PIOS_SDCARD_H */ diff --git a/flight/PiOS.osx/inc/pios_tcp.h b/flight/PiOS.osx/inc/pios_tcp.h index 7982dc64e..589c90978 100644 --- a/flight/PiOS.osx/inc/pios_tcp.h +++ b/flight/PiOS.osx/inc/pios_tcp.h @@ -1,35 +1,35 @@ -/** - ****************************************************************************** - * - * @file pios_usart.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief UDP functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_TCP_H -#define PIOS_TCP_H - - -/* Global Types */ - -/* Public Functions */ - -#endif /* PIOS_UDP_H */ +/** + ****************************************************************************** + * + * @file pios_usart.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief UDP functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_TCP_H +#define PIOS_TCP_H + + +/* Global Types */ + +/* Public Functions */ + +#endif /* PIOS_UDP_H */ diff --git a/flight/PiOS.osx/inc/pios_udp.h b/flight/PiOS.osx/inc/pios_udp.h index 36964a342..48a3b0987 100644 --- a/flight/PiOS.osx/inc/pios_udp.h +++ b/flight/PiOS.osx/inc/pios_udp.h @@ -1,35 +1,35 @@ -/** - ****************************************************************************** - * - * @file pios_usart.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief UDP functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_UDP_H -#define PIOS_UDP_H - - -/* Global Types */ - -/* Public Functions */ - -#endif /* PIOS_UDP_H */ +/** + ****************************************************************************** + * + * @file pios_usart.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief UDP functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_UDP_H +#define PIOS_UDP_H + + +/* Global Types */ + +/* Public Functions */ + +#endif /* PIOS_UDP_H */ diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/croutine.c b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/croutine.c index 58fb1bf4b..fe567306a 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/croutine.c +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/croutine.c @@ -1,380 +1,380 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#include "FreeRTOS.h" -#include "task.h" -#include "croutine.h" - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - - -/* Lists for ready and blocked co-routines. --------------------*/ -static xList pxReadyCoRoutineLists[ configMAX_CO_ROUTINE_PRIORITIES ]; /*< Prioritised ready co-routines. */ -static xList xDelayedCoRoutineList1; /*< Delayed co-routines. */ -static xList xDelayedCoRoutineList2; /*< Delayed co-routines (two lists are used - one for delays that have overflowed the current tick count. */ -static xList * pxDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used. */ -static xList * pxOverflowDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used to hold co-routines that have overflowed the current tick count. */ -static xList xPendingReadyCoRoutineList; /*< Holds co-routines that have been readied by an external event. They cannot be added directly to the ready lists as the ready lists cannot be accessed by interrupts. */ - -/* Other file private variables. --------------------------------*/ -corCRCB * pxCurrentCoRoutine = NULL; -static unsigned portBASE_TYPE uxTopCoRoutineReadyPriority = 0; -static portTickType xCoRoutineTickCount = 0, xLastTickCount = 0, xPassedTicks = 0; - -/* The initial state of the co-routine when it is created. */ -#define corINITIAL_STATE ( 0 ) - -/* - * Place the co-routine represented by pxCRCB into the appropriate ready queue - * for the priority. It is inserted at the end of the list. - * - * This macro accesses the co-routine ready lists and therefore must not be - * used from within an ISR. - */ -#define prvAddCoRoutineToReadyQueue( pxCRCB ) \ -{ \ - if( pxCRCB->uxPriority > uxTopCoRoutineReadyPriority ) \ - { \ - uxTopCoRoutineReadyPriority = pxCRCB->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyCoRoutineLists[ pxCRCB->uxPriority ] ), &( pxCRCB->xGenericListItem ) ); \ -} - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first co-routine. - */ -static void prvInitialiseCoRoutineLists( void ); - -/* - * Co-routines that are readied by an interrupt cannot be placed directly into - * the ready lists (there is no mutual exclusion). Instead they are placed in - * in the pending ready list in order that they can later be moved to the ready - * list by the co-routine scheduler. - */ -static void prvCheckPendingReadyList( void ); - -/* - * Macro that looks at the list of co-routines that are currently delayed to - * see if any require waking. - * - * Co-routines are stored in the queue in the order of their wake time - - * meaning once one co-routine has been found whose timer has not expired - * we need not look any further down the list. - */ -static void prvCheckDelayedList( void ); - -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ) -{ -signed portBASE_TYPE xReturn; -corCRCB *pxCoRoutine; - - /* Allocate the memory that will store the co-routine control block. */ - pxCoRoutine = ( corCRCB * ) pvPortMalloc( sizeof( corCRCB ) ); - if( pxCoRoutine ) - { - /* If pxCurrentCoRoutine is NULL then this is the first co-routine to - be created and the co-routine data structures need initialising. */ - if( pxCurrentCoRoutine == NULL ) - { - pxCurrentCoRoutine = pxCoRoutine; - prvInitialiseCoRoutineLists(); - } - - /* Check the priority is within limits. */ - if( uxPriority >= configMAX_CO_ROUTINE_PRIORITIES ) - { - uxPriority = configMAX_CO_ROUTINE_PRIORITIES - 1; - } - - /* Fill out the co-routine control block from the function parameters. */ - pxCoRoutine->uxState = corINITIAL_STATE; - pxCoRoutine->uxPriority = uxPriority; - pxCoRoutine->uxIndex = uxIndex; - pxCoRoutine->pxCoRoutineFunction = pxCoRoutineCode; - - /* Initialise all the other co-routine control block parameters. */ - vListInitialiseItem( &( pxCoRoutine->xGenericListItem ) ); - vListInitialiseItem( &( pxCoRoutine->xEventListItem ) ); - - /* Set the co-routine control block as a link back from the xListItem. - This is so we can get back to the containing CRCB from a generic item - in a list. */ - listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xGenericListItem ), pxCoRoutine ); - listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xEventListItem ), pxCoRoutine ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxCoRoutine->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - - /* Now the co-routine has been initialised it can be added to the ready - list at the correct priority. */ - prvAddCoRoutineToReadyQueue( pxCoRoutine ); - - xReturn = pdPASS; - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ) -{ -portTickType xTimeToWake; - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xCoRoutineTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentCoRoutine->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xCoRoutineTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - } - - if( pxEventList ) - { - /* Also add the co-routine to an event list. If this is done then the - function must be called with interrupts disabled. */ - vListInsert( pxEventList, &( pxCurrentCoRoutine->xEventListItem ) ); - } -} -/*-----------------------------------------------------------*/ - -static void prvCheckPendingReadyList( void ) -{ - /* Are there any co-routines waiting to get moved to the ready list? These - are co-routines that have been readied by an ISR. The ISR cannot access - the ready lists itself. */ - while( listLIST_IS_EMPTY( &xPendingReadyCoRoutineList ) == pdFALSE ) - { - corCRCB *pxUnblockedCRCB; - - /* The pending ready list can be accessed by an ISR. */ - portDISABLE_INTERRUPTS(); - { - pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( (&xPendingReadyCoRoutineList) ); - vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); - } - portENABLE_INTERRUPTS(); - - vListRemove( &( pxUnblockedCRCB->xGenericListItem ) ); - prvAddCoRoutineToReadyQueue( pxUnblockedCRCB ); - } -} -/*-----------------------------------------------------------*/ - -static void prvCheckDelayedList( void ) -{ -corCRCB *pxCRCB; - - xPassedTicks = xTaskGetTickCount() - xLastTickCount; - while( xPassedTicks ) - { - xCoRoutineTickCount++; - xPassedTicks--; - - /* If the tick count has overflowed we need to swap the ready lists. */ - if( xCoRoutineTickCount == 0 ) - { - xList * pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. If there are - any items in pxDelayedCoRoutineList here then there is an error! */ - pxTemp = pxDelayedCoRoutineList; - pxDelayedCoRoutineList = pxOverflowDelayedCoRoutineList; - pxOverflowDelayedCoRoutineList = pxTemp; - } - - /* See if this tick has made a timeout expire. */ - while( listLIST_IS_EMPTY( pxDelayedCoRoutineList ) == pdFALSE ) - { - pxCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedCoRoutineList ); - - if( xCoRoutineTickCount < listGET_LIST_ITEM_VALUE( &( pxCRCB->xGenericListItem ) ) ) - { - /* Timeout not yet expired. */ - break; - } - - portDISABLE_INTERRUPTS(); - { - /* The event could have occurred just before this critical - section. If this is the case then the generic list item will - have been moved to the pending ready list and the following - line is still valid. Also the pvContainer parameter will have - been set to NULL so the following lines are also valid. */ - vListRemove( &( pxCRCB->xGenericListItem ) ); - - /* Is the co-routine waiting on an event also? */ - if( pxCRCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxCRCB->xEventListItem ) ); - } - } - portENABLE_INTERRUPTS(); - - prvAddCoRoutineToReadyQueue( pxCRCB ); - } - } - - xLastTickCount = xCoRoutineTickCount; -} -/*-----------------------------------------------------------*/ - -void vCoRoutineSchedule( void ) -{ - /* See if any co-routines readied by events need moving to the ready lists. */ - prvCheckPendingReadyList(); - - /* See if any delayed co-routines have timed out. */ - prvCheckDelayedList(); - - /* Find the highest priority queue that contains ready co-routines. */ - while( listLIST_IS_EMPTY( &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ) ) - { - if( uxTopCoRoutineReadyPriority == 0 ) - { - /* No more co-routines to check. */ - return; - } - --uxTopCoRoutineReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the co-routines - of the same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentCoRoutine, &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ); - - /* Call the co-routine. */ - ( pxCurrentCoRoutine->pxCoRoutineFunction )( pxCurrentCoRoutine, pxCurrentCoRoutine->uxIndex ); - - return; -} -/*-----------------------------------------------------------*/ - -static void prvInitialiseCoRoutineLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = 0; uxPriority < configMAX_CO_ROUTINE_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyCoRoutineLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedCoRoutineList1 ); - vListInitialise( ( xList * ) &xDelayedCoRoutineList2 ); - vListInitialise( ( xList * ) &xPendingReadyCoRoutineList ); - - /* Start with pxDelayedCoRoutineList using list1 and the - pxOverflowDelayedCoRoutineList using list2. */ - pxDelayedCoRoutineList = &xDelayedCoRoutineList1; - pxOverflowDelayedCoRoutineList = &xDelayedCoRoutineList2; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ) -{ -corCRCB *pxUnblockedCRCB; -signed portBASE_TYPE xReturn; - - /* This function is called from within an interrupt. It can only access - event lists and the pending ready list. This function assumes that a - check has already been made to ensure pxEventList is not empty. */ - pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); - vListInsertEnd( ( xList * ) &( xPendingReadyCoRoutineList ), &( pxUnblockedCRCB->xEventListItem ) ); - - if( pxUnblockedCRCB->uxPriority >= pxCurrentCoRoutine->uxPriority ) - { - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#include "FreeRTOS.h" +#include "task.h" +#include "croutine.h" + +/* + * Some kernel aware debuggers require data to be viewed to be global, rather + * than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + + +/* Lists for ready and blocked co-routines. --------------------*/ +static xList pxReadyCoRoutineLists[ configMAX_CO_ROUTINE_PRIORITIES ]; /*< Prioritised ready co-routines. */ +static xList xDelayedCoRoutineList1; /*< Delayed co-routines. */ +static xList xDelayedCoRoutineList2; /*< Delayed co-routines (two lists are used - one for delays that have overflowed the current tick count. */ +static xList * pxDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used. */ +static xList * pxOverflowDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used to hold co-routines that have overflowed the current tick count. */ +static xList xPendingReadyCoRoutineList; /*< Holds co-routines that have been readied by an external event. They cannot be added directly to the ready lists as the ready lists cannot be accessed by interrupts. */ + +/* Other file private variables. --------------------------------*/ +corCRCB * pxCurrentCoRoutine = NULL; +static unsigned portBASE_TYPE uxTopCoRoutineReadyPriority = 0; +static portTickType xCoRoutineTickCount = 0, xLastTickCount = 0, xPassedTicks = 0; + +/* The initial state of the co-routine when it is created. */ +#define corINITIAL_STATE ( 0 ) + +/* + * Place the co-routine represented by pxCRCB into the appropriate ready queue + * for the priority. It is inserted at the end of the list. + * + * This macro accesses the co-routine ready lists and therefore must not be + * used from within an ISR. + */ +#define prvAddCoRoutineToReadyQueue( pxCRCB ) \ +{ \ + if( pxCRCB->uxPriority > uxTopCoRoutineReadyPriority ) \ + { \ + uxTopCoRoutineReadyPriority = pxCRCB->uxPriority; \ + } \ + vListInsertEnd( ( xList * ) &( pxReadyCoRoutineLists[ pxCRCB->uxPriority ] ), &( pxCRCB->xGenericListItem ) ); \ +} + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first co-routine. + */ +static void prvInitialiseCoRoutineLists( void ); + +/* + * Co-routines that are readied by an interrupt cannot be placed directly into + * the ready lists (there is no mutual exclusion). Instead they are placed in + * in the pending ready list in order that they can later be moved to the ready + * list by the co-routine scheduler. + */ +static void prvCheckPendingReadyList( void ); + +/* + * Macro that looks at the list of co-routines that are currently delayed to + * see if any require waking. + * + * Co-routines are stored in the queue in the order of their wake time - + * meaning once one co-routine has been found whose timer has not expired + * we need not look any further down the list. + */ +static void prvCheckDelayedList( void ); + +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ) +{ +signed portBASE_TYPE xReturn; +corCRCB *pxCoRoutine; + + /* Allocate the memory that will store the co-routine control block. */ + pxCoRoutine = ( corCRCB * ) pvPortMalloc( sizeof( corCRCB ) ); + if( pxCoRoutine ) + { + /* If pxCurrentCoRoutine is NULL then this is the first co-routine to + be created and the co-routine data structures need initialising. */ + if( pxCurrentCoRoutine == NULL ) + { + pxCurrentCoRoutine = pxCoRoutine; + prvInitialiseCoRoutineLists(); + } + + /* Check the priority is within limits. */ + if( uxPriority >= configMAX_CO_ROUTINE_PRIORITIES ) + { + uxPriority = configMAX_CO_ROUTINE_PRIORITIES - 1; + } + + /* Fill out the co-routine control block from the function parameters. */ + pxCoRoutine->uxState = corINITIAL_STATE; + pxCoRoutine->uxPriority = uxPriority; + pxCoRoutine->uxIndex = uxIndex; + pxCoRoutine->pxCoRoutineFunction = pxCoRoutineCode; + + /* Initialise all the other co-routine control block parameters. */ + vListInitialiseItem( &( pxCoRoutine->xGenericListItem ) ); + vListInitialiseItem( &( pxCoRoutine->xEventListItem ) ); + + /* Set the co-routine control block as a link back from the xListItem. + This is so we can get back to the containing CRCB from a generic item + in a list. */ + listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xGenericListItem ), pxCoRoutine ); + listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xEventListItem ), pxCoRoutine ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxCoRoutine->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); + + /* Now the co-routine has been initialised it can be added to the ready + list at the correct priority. */ + prvAddCoRoutineToReadyQueue( pxCoRoutine ); + + xReturn = pdPASS; + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ) +{ +portTickType xTimeToWake; + + /* Calculate the time to wake - this may overflow but this is + not a problem. */ + xTimeToWake = xCoRoutineTickCount + xTicksToDelay; + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentCoRoutine->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xCoRoutineTickCount ) + { + /* Wake time has overflowed. Place this item in the + overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the + current block list. */ + vListInsert( ( xList * ) pxDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + } + + if( pxEventList ) + { + /* Also add the co-routine to an event list. If this is done then the + function must be called with interrupts disabled. */ + vListInsert( pxEventList, &( pxCurrentCoRoutine->xEventListItem ) ); + } +} +/*-----------------------------------------------------------*/ + +static void prvCheckPendingReadyList( void ) +{ + /* Are there any co-routines waiting to get moved to the ready list? These + are co-routines that have been readied by an ISR. The ISR cannot access + the ready lists itself. */ + while( listLIST_IS_EMPTY( &xPendingReadyCoRoutineList ) == pdFALSE ) + { + corCRCB *pxUnblockedCRCB; + + /* The pending ready list can be accessed by an ISR. */ + portDISABLE_INTERRUPTS(); + { + pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( (&xPendingReadyCoRoutineList) ); + vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); + } + portENABLE_INTERRUPTS(); + + vListRemove( &( pxUnblockedCRCB->xGenericListItem ) ); + prvAddCoRoutineToReadyQueue( pxUnblockedCRCB ); + } +} +/*-----------------------------------------------------------*/ + +static void prvCheckDelayedList( void ) +{ +corCRCB *pxCRCB; + + xPassedTicks = xTaskGetTickCount() - xLastTickCount; + while( xPassedTicks ) + { + xCoRoutineTickCount++; + xPassedTicks--; + + /* If the tick count has overflowed we need to swap the ready lists. */ + if( xCoRoutineTickCount == 0 ) + { + xList * pxTemp; + + /* Tick count has overflowed so we need to swap the delay lists. If there are + any items in pxDelayedCoRoutineList here then there is an error! */ + pxTemp = pxDelayedCoRoutineList; + pxDelayedCoRoutineList = pxOverflowDelayedCoRoutineList; + pxOverflowDelayedCoRoutineList = pxTemp; + } + + /* See if this tick has made a timeout expire. */ + while( listLIST_IS_EMPTY( pxDelayedCoRoutineList ) == pdFALSE ) + { + pxCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedCoRoutineList ); + + if( xCoRoutineTickCount < listGET_LIST_ITEM_VALUE( &( pxCRCB->xGenericListItem ) ) ) + { + /* Timeout not yet expired. */ + break; + } + + portDISABLE_INTERRUPTS(); + { + /* The event could have occurred just before this critical + section. If this is the case then the generic list item will + have been moved to the pending ready list and the following + line is still valid. Also the pvContainer parameter will have + been set to NULL so the following lines are also valid. */ + vListRemove( &( pxCRCB->xGenericListItem ) ); + + /* Is the co-routine waiting on an event also? */ + if( pxCRCB->xEventListItem.pvContainer ) + { + vListRemove( &( pxCRCB->xEventListItem ) ); + } + } + portENABLE_INTERRUPTS(); + + prvAddCoRoutineToReadyQueue( pxCRCB ); + } + } + + xLastTickCount = xCoRoutineTickCount; +} +/*-----------------------------------------------------------*/ + +void vCoRoutineSchedule( void ) +{ + /* See if any co-routines readied by events need moving to the ready lists. */ + prvCheckPendingReadyList(); + + /* See if any delayed co-routines have timed out. */ + prvCheckDelayedList(); + + /* Find the highest priority queue that contains ready co-routines. */ + while( listLIST_IS_EMPTY( &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ) ) + { + if( uxTopCoRoutineReadyPriority == 0 ) + { + /* No more co-routines to check. */ + return; + } + --uxTopCoRoutineReadyPriority; + } + + /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the co-routines + of the same priority get an equal share of the processor time. */ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentCoRoutine, &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ); + + /* Call the co-routine. */ + ( pxCurrentCoRoutine->pxCoRoutineFunction )( pxCurrentCoRoutine, pxCurrentCoRoutine->uxIndex ); + + return; +} +/*-----------------------------------------------------------*/ + +static void prvInitialiseCoRoutineLists( void ) +{ +unsigned portBASE_TYPE uxPriority; + + for( uxPriority = 0; uxPriority < configMAX_CO_ROUTINE_PRIORITIES; uxPriority++ ) + { + vListInitialise( ( xList * ) &( pxReadyCoRoutineLists[ uxPriority ] ) ); + } + + vListInitialise( ( xList * ) &xDelayedCoRoutineList1 ); + vListInitialise( ( xList * ) &xDelayedCoRoutineList2 ); + vListInitialise( ( xList * ) &xPendingReadyCoRoutineList ); + + /* Start with pxDelayedCoRoutineList using list1 and the + pxOverflowDelayedCoRoutineList using list2. */ + pxDelayedCoRoutineList = &xDelayedCoRoutineList1; + pxOverflowDelayedCoRoutineList = &xDelayedCoRoutineList2; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ) +{ +corCRCB *pxUnblockedCRCB; +signed portBASE_TYPE xReturn; + + /* This function is called from within an interrupt. It can only access + event lists and the pending ready list. This function assumes that a + check has already been made to ensure pxEventList is not empty. */ + pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); + vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); + vListInsertEnd( ( xList * ) &( xPendingReadyCoRoutineList ), &( pxUnblockedCRCB->xEventListItem ) ); + + if( pxUnblockedCRCB->uxPriority >= pxCurrentCoRoutine->uxPriority ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/FreeRTOS.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/FreeRTOS.h index 73fc375ae..9648c70bf 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/FreeRTOS.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/FreeRTOS.h @@ -1,469 +1,469 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef INC_FREERTOS_H -#define INC_FREERTOS_H - - -/* - * Include the generic headers required for the FreeRTOS port being used. - */ -#include - -/* Basic FreeRTOS definitions. */ -#include "projdefs.h" - -/* Application specific configuration options. */ -#include "FreeRTOSConfig.h" - -/* Definitions specific to the port being used. */ -#include "portable.h" - - -/* Defines the prototype to which the application task hook function must -conform. */ -typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); - - - - - -/* - * Check all the required application specific macros have been defined. - * These macros are application specific and (as downloaded) are defined - * within FreeRTOSConfig.h. - */ - -#ifndef configUSE_PREEMPTION - #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_IDLE_HOOK - #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_TICK_HOOK - #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_CO_ROUTINES - #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskPrioritySet - #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_uxTaskPriorityGet - #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelete - #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskCleanUpResources - #error Missing definition: INCLUDE_vTaskCleanUpResources should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskSuspend - #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelayUntil - #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelay - #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_16_BIT_TICKS - #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_APPLICATION_TASK_TAG - #define configUSE_APPLICATION_TASK_TAG 0 -#endif - -#ifndef INCLUDE_uxTaskGetStackHighWaterMark - #define INCLUDE_uxTaskGetStackHighWaterMark 0 -#endif - -#ifndef configUSE_RECURSIVE_MUTEXES - #define configUSE_RECURSIVE_MUTEXES 0 -#endif - -#ifndef configUSE_MUTEXES - #define configUSE_MUTEXES 0 -#endif - -#ifndef configUSE_TIMERS -#error HERE - #define configUSE_TIMERS 0 -#endif - -#ifndef configUSE_COUNTING_SEMAPHORES - #define configUSE_COUNTING_SEMAPHORES 0 -#endif - -#ifndef configUSE_ALTERNATIVE_API - #define configUSE_ALTERNATIVE_API 0 -#endif - -#ifndef portCRITICAL_NESTING_IN_TCB - #define portCRITICAL_NESTING_IN_TCB 0 -#endif - -#ifndef configMAX_TASK_NAME_LEN - #define configMAX_TASK_NAME_LEN 16 -#endif - -#ifndef configIDLE_SHOULD_YIELD - #define configIDLE_SHOULD_YIELD 1 -#endif - -#if configMAX_TASK_NAME_LEN < 1 - #error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h -#endif - -#ifndef INCLUDE_xTaskResumeFromISR - #define INCLUDE_xTaskResumeFromISR 1 -#endif - -#ifndef configASSERT - #define configASSERT( x ) -#endif - -/* The timers module relies on xTaskGetSchedulerState(). */ -#if configUSE_TIMERS == 1 - - #ifndef configTIMER_TASK_PRIORITY - #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined. - #endif /* configTIMER_TASK_PRIORITY */ - - #ifndef configTIMER_QUEUE_LENGTH - #error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined. - #endif /* configTIMER_QUEUE_LENGTH */ - - #ifndef configTIMER_TASK_STACK_DEPTH - #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined. - #endif /* configTIMER_TASK_STACK_DEPTH */ - -#endif /* configUSE_TIMERS */ - -#ifndef INCLUDE_xTaskGetSchedulerState - #define INCLUDE_xTaskGetSchedulerState 0 -#endif - -#ifndef INCLUDE_xTaskGetCurrentTaskHandle - #define INCLUDE_xTaskGetCurrentTaskHandle 0 -#endif - - -#ifndef portSET_INTERRUPT_MASK_FROM_ISR - #define portSET_INTERRUPT_MASK_FROM_ISR() 0 -#endif - -#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR - #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue -#endif - - -#ifndef configQUEUE_REGISTRY_SIZE - #define configQUEUE_REGISTRY_SIZE 0U -#endif - -#if ( configQUEUE_REGISTRY_SIZE < 1U ) - #define vQueueAddToRegistry( xQueue, pcName ) - #define vQueueUnregisterQueue( xQueue ) -#endif - - -/* Remove any unused trace macros. */ -#ifndef traceSTART - /* Used to perform any necessary initialisation - for example, open a file - into which trace is to be written. */ - #define traceSTART() -#endif - -#ifndef traceEND - /* Use to close a trace, for example close a file into which trace has been - written. */ - #define traceEND() -#endif - -#ifndef traceTASK_SWITCHED_IN - /* Called after a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the selected task. */ - #define traceTASK_SWITCHED_IN() -#endif - -#ifndef traceTASK_SWITCHED_OUT - /* Called before a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the task being switched out. */ - #define traceTASK_SWITCHED_OUT() -#endif - -#ifndef traceBLOCKING_ON_QUEUE_RECEIVE - /* Task is about to block because it cannot read from a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the read was attempted. pxCurrentTCB points to the TCB of the - task that attempted the read. */ - #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceBLOCKING_ON_QUEUE_SEND - /* Task is about to block because it cannot write to a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the write was attempted. pxCurrentTCB points to the TCB of the - task that attempted the write. */ - #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) -#endif - -#ifndef configCHECK_FOR_STACK_OVERFLOW - #define configCHECK_FOR_STACK_OVERFLOW 0 -#endif - -/* The following event macros are embedded in the kernel API calls. */ - -#ifndef traceQUEUE_CREATE - #define traceQUEUE_CREATE( pxNewQueue ) -#endif - -#ifndef traceQUEUE_CREATE_FAILED - #define traceQUEUE_CREATE_FAILED() -#endif - -#ifndef traceCREATE_MUTEX - #define traceCREATE_MUTEX( pxNewQueue ) -#endif - -#ifndef traceCREATE_MUTEX_FAILED - #define traceCREATE_MUTEX_FAILED() -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE - #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED - #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) -#endif - -#ifndef traceTAKE_MUTEX_RECURSIVE - #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED - #define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ) -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE - #define traceCREATE_COUNTING_SEMAPHORE() -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED - #define traceCREATE_COUNTING_SEMAPHORE_FAILED() -#endif - -#ifndef traceQUEUE_SEND - #define traceQUEUE_SEND( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FAILED - #define traceQUEUE_SEND_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE - #define traceQUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceQUEUE_PEEK - #define traceQUEUE_PEEK( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FAILED - #define traceQUEUE_RECEIVE_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR - #define traceQUEUE_SEND_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR_FAILED - #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR - #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED - #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_DELETE - #define traceQUEUE_DELETE( pxQueue ) -#endif - -#ifndef traceTASK_CREATE - #define traceTASK_CREATE( pxNewTCB ) -#endif - -#ifndef traceTASK_CREATE_FAILED - #define traceTASK_CREATE_FAILED() -#endif - -#ifndef traceTASK_DELETE - #define traceTASK_DELETE( pxTaskToDelete ) -#endif - -#ifndef traceTASK_DELAY_UNTIL - #define traceTASK_DELAY_UNTIL() -#endif - -#ifndef traceTASK_DELAY - #define traceTASK_DELAY() -#endif - -#ifndef traceTASK_PRIORITY_SET - #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) -#endif - -#ifndef traceTASK_SUSPEND - #define traceTASK_SUSPEND( pxTaskToSuspend ) -#endif - -#ifndef traceTASK_RESUME - #define traceTASK_RESUME( pxTaskToResume ) -#endif - -#ifndef traceTASK_RESUME_FROM_ISR - #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) -#endif - -#ifndef traceTASK_INCREMENT_TICK - #define traceTASK_INCREMENT_TICK( xTickCount ) -#endif - -#ifndef traceTIMER_CREATE - #define traceTIMER_CREATE( pxNewTimer ) -#endif - -#ifndef traceTIMER_CREATE_FAILED - #define traceTIMER_CREATE_FAILED() -#endif - -#ifndef traceTIMER_COMMAND_SEND - #define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn ) -#endif - -#ifndef traceTIMER_EXPIRED - #define traceTIMER_EXPIRED( pxTimer ) -#endif - -#ifndef traceTIMER_COMMAND_RECEIVED - #define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue ) -#endif - -#ifndef configGENERATE_RUN_TIME_STATS - #define configGENERATE_RUN_TIME_STATS 0 -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. - #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ - - #ifndef portGET_RUN_TIME_COUNTER_VALUE - #ifndef portALT_GET_RUN_TIME_COUNTER_VALUE - #error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined. See the examples provided and the FreeRTOS web site for more information. - #endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */ - #endif /* portGET_RUN_TIME_COUNTER_VALUE */ - -#endif /* configGENERATE_RUN_TIME_STATS */ - -#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() -#endif - -#ifndef configUSE_MALLOC_FAILED_HOOK - #define configUSE_MALLOC_FAILED_HOOK 0 -#endif - -#ifndef portPRIVILEGE_BIT - #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) -#endif - -#ifndef portYIELD_WITHIN_API - #define portYIELD_WITHIN_API portYIELD -#endif - -#ifndef pvPortMallocAligned - #define pvPortMallocAligned( x, puxStackBuffer ) ( ( ( puxStackBuffer ) == NULL ) ? ( pvPortMalloc( ( x ) ) ) : ( puxStackBuffer ) ) -#endif - -#ifndef vPortFreeAligned - #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) -#endif - -#endif /* INC_FREERTOS_H */ - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef INC_FREERTOS_H +#define INC_FREERTOS_H + + +/* + * Include the generic headers required for the FreeRTOS port being used. + */ +#include + +/* Basic FreeRTOS definitions. */ +#include "projdefs.h" + +/* Application specific configuration options. */ +#include "FreeRTOSConfig.h" + +/* Definitions specific to the port being used. */ +#include "portable.h" + + +/* Defines the prototype to which the application task hook function must +conform. */ +typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); + + + + + +/* + * Check all the required application specific macros have been defined. + * These macros are application specific and (as downloaded) are defined + * within FreeRTOSConfig.h. + */ + +#ifndef configUSE_PREEMPTION + #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_IDLE_HOOK + #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_TICK_HOOK + #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_CO_ROUTINES + #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskPrioritySet + #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_uxTaskPriorityGet + #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelete + #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskCleanUpResources + #error Missing definition: INCLUDE_vTaskCleanUpResources should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskSuspend + #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelayUntil + #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelay + #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_16_BIT_TICKS + #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_APPLICATION_TASK_TAG + #define configUSE_APPLICATION_TASK_TAG 0 +#endif + +#ifndef INCLUDE_uxTaskGetStackHighWaterMark + #define INCLUDE_uxTaskGetStackHighWaterMark 0 +#endif + +#ifndef configUSE_RECURSIVE_MUTEXES + #define configUSE_RECURSIVE_MUTEXES 0 +#endif + +#ifndef configUSE_MUTEXES + #define configUSE_MUTEXES 0 +#endif + +#ifndef configUSE_TIMERS +#error HERE + #define configUSE_TIMERS 0 +#endif + +#ifndef configUSE_COUNTING_SEMAPHORES + #define configUSE_COUNTING_SEMAPHORES 0 +#endif + +#ifndef configUSE_ALTERNATIVE_API + #define configUSE_ALTERNATIVE_API 0 +#endif + +#ifndef portCRITICAL_NESTING_IN_TCB + #define portCRITICAL_NESTING_IN_TCB 0 +#endif + +#ifndef configMAX_TASK_NAME_LEN + #define configMAX_TASK_NAME_LEN 16 +#endif + +#ifndef configIDLE_SHOULD_YIELD + #define configIDLE_SHOULD_YIELD 1 +#endif + +#if configMAX_TASK_NAME_LEN < 1 + #error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h +#endif + +#ifndef INCLUDE_xTaskResumeFromISR + #define INCLUDE_xTaskResumeFromISR 1 +#endif + +#ifndef configASSERT + #define configASSERT( x ) +#endif + +/* The timers module relies on xTaskGetSchedulerState(). */ +#if configUSE_TIMERS == 1 + + #ifndef configTIMER_TASK_PRIORITY + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined. + #endif /* configTIMER_TASK_PRIORITY */ + + #ifndef configTIMER_QUEUE_LENGTH + #error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined. + #endif /* configTIMER_QUEUE_LENGTH */ + + #ifndef configTIMER_TASK_STACK_DEPTH + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined. + #endif /* configTIMER_TASK_STACK_DEPTH */ + +#endif /* configUSE_TIMERS */ + +#ifndef INCLUDE_xTaskGetSchedulerState + #define INCLUDE_xTaskGetSchedulerState 0 +#endif + +#ifndef INCLUDE_xTaskGetCurrentTaskHandle + #define INCLUDE_xTaskGetCurrentTaskHandle 0 +#endif + + +#ifndef portSET_INTERRUPT_MASK_FROM_ISR + #define portSET_INTERRUPT_MASK_FROM_ISR() 0 +#endif + +#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR + #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue +#endif + + +#ifndef configQUEUE_REGISTRY_SIZE + #define configQUEUE_REGISTRY_SIZE 0U +#endif + +#if ( configQUEUE_REGISTRY_SIZE < 1U ) + #define vQueueAddToRegistry( xQueue, pcName ) + #define vQueueUnregisterQueue( xQueue ) +#endif + + +/* Remove any unused trace macros. */ +#ifndef traceSTART + /* Used to perform any necessary initialisation - for example, open a file + into which trace is to be written. */ + #define traceSTART() +#endif + +#ifndef traceEND + /* Use to close a trace, for example close a file into which trace has been + written. */ + #define traceEND() +#endif + +#ifndef traceTASK_SWITCHED_IN + /* Called after a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the selected task. */ + #define traceTASK_SWITCHED_IN() +#endif + +#ifndef traceTASK_SWITCHED_OUT + /* Called before a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the task being switched out. */ + #define traceTASK_SWITCHED_OUT() +#endif + +#ifndef traceBLOCKING_ON_QUEUE_RECEIVE + /* Task is about to block because it cannot read from a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the read was attempted. pxCurrentTCB points to the TCB of the + task that attempted the read. */ + #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_SEND + /* Task is about to block because it cannot write to a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the write was attempted. pxCurrentTCB points to the TCB of the + task that attempted the write. */ + #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) +#endif + +#ifndef configCHECK_FOR_STACK_OVERFLOW + #define configCHECK_FOR_STACK_OVERFLOW 0 +#endif + +/* The following event macros are embedded in the kernel API calls. */ + +#ifndef traceQUEUE_CREATE + #define traceQUEUE_CREATE( pxNewQueue ) +#endif + +#ifndef traceQUEUE_CREATE_FAILED + #define traceQUEUE_CREATE_FAILED() +#endif + +#ifndef traceCREATE_MUTEX + #define traceCREATE_MUTEX( pxNewQueue ) +#endif + +#ifndef traceCREATE_MUTEX_FAILED + #define traceCREATE_MUTEX_FAILED() +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE + #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED + #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE + #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED + #define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE + #define traceCREATE_COUNTING_SEMAPHORE() +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED + #define traceCREATE_COUNTING_SEMAPHORE_FAILED() +#endif + +#ifndef traceQUEUE_SEND + #define traceQUEUE_SEND( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FAILED + #define traceQUEUE_SEND_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE + #define traceQUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK + #define traceQUEUE_PEEK( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FAILED + #define traceQUEUE_RECEIVE_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR + #define traceQUEUE_SEND_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR_FAILED + #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR + #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED + #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_DELETE + #define traceQUEUE_DELETE( pxQueue ) +#endif + +#ifndef traceTASK_CREATE + #define traceTASK_CREATE( pxNewTCB ) +#endif + +#ifndef traceTASK_CREATE_FAILED + #define traceTASK_CREATE_FAILED() +#endif + +#ifndef traceTASK_DELETE + #define traceTASK_DELETE( pxTaskToDelete ) +#endif + +#ifndef traceTASK_DELAY_UNTIL + #define traceTASK_DELAY_UNTIL() +#endif + +#ifndef traceTASK_DELAY + #define traceTASK_DELAY() +#endif + +#ifndef traceTASK_PRIORITY_SET + #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) +#endif + +#ifndef traceTASK_SUSPEND + #define traceTASK_SUSPEND( pxTaskToSuspend ) +#endif + +#ifndef traceTASK_RESUME + #define traceTASK_RESUME( pxTaskToResume ) +#endif + +#ifndef traceTASK_RESUME_FROM_ISR + #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) +#endif + +#ifndef traceTASK_INCREMENT_TICK + #define traceTASK_INCREMENT_TICK( xTickCount ) +#endif + +#ifndef traceTIMER_CREATE + #define traceTIMER_CREATE( pxNewTimer ) +#endif + +#ifndef traceTIMER_CREATE_FAILED + #define traceTIMER_CREATE_FAILED() +#endif + +#ifndef traceTIMER_COMMAND_SEND + #define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn ) +#endif + +#ifndef traceTIMER_EXPIRED + #define traceTIMER_EXPIRED( pxTimer ) +#endif + +#ifndef traceTIMER_COMMAND_RECEIVED + #define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue ) +#endif + +#ifndef configGENERATE_RUN_TIME_STATS + #define configGENERATE_RUN_TIME_STATS 0 +#endif + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. + #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ + + #ifndef portGET_RUN_TIME_COUNTER_VALUE + #ifndef portALT_GET_RUN_TIME_COUNTER_VALUE + #error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined. See the examples provided and the FreeRTOS web site for more information. + #endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */ + #endif /* portGET_RUN_TIME_COUNTER_VALUE */ + +#endif /* configGENERATE_RUN_TIME_STATS */ + +#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() +#endif + +#ifndef configUSE_MALLOC_FAILED_HOOK + #define configUSE_MALLOC_FAILED_HOOK 0 +#endif + +#ifndef portPRIVILEGE_BIT + #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) +#endif + +#ifndef portYIELD_WITHIN_API + #define portYIELD_WITHIN_API portYIELD +#endif + +#ifndef pvPortMallocAligned + #define pvPortMallocAligned( x, puxStackBuffer ) ( ( ( puxStackBuffer ) == NULL ) ? ( pvPortMalloc( ( x ) ) ) : ( puxStackBuffer ) ) +#endif + +#ifndef vPortFreeAligned + #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) +#endif + +#endif /* INC_FREERTOS_H */ + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/StackMacros.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/StackMacros.h index 1114b6d29..547a58cf1 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/StackMacros.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/StackMacros.h @@ -1,174 +1,174 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef STACK_MACROS_H -#define STACK_MACROS_H - -/* - * Call the stack overflow hook function if the stack of the task being swapped - * out is currently overflowed, or looks like it might have overflowed in the - * past. - * - * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check - * the current stack state only - comparing the current top of stack value to - * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 - * will also cause the last few stack bytes to be checked to ensure the value - * to which the bytes were set when the task was created have not been - * overwritten. Note this second test does not guarantee that an overflowed - * stack will always be recognised. - */ - -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) - - /* FreeRTOSConfig.h is not set to check for stack overflows. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) - - /* FreeRTOSConfig.h is only set to use the first method of - overflow checking. */ - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#endif /* STACK_MACROS_H */ - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef STACK_MACROS_H +#define STACK_MACROS_H + +/* + * Call the stack overflow hook function if the stack of the task being swapped + * out is currently overflowed, or looks like it might have overflowed in the + * past. + * + * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check + * the current stack state only - comparing the current top of stack value to + * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 + * will also cause the last few stack bytes to be checked to ensure the value + * to which the bytes were set when the task was created have not been + * overwritten. Note this second test does not guarantee that an overflowed + * stack will always be recognised. + */ + +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) + + /* FreeRTOSConfig.h is not set to check for stack overflows. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) + + /* FreeRTOSConfig.h is only set to use the first method of + overflow checking. */ + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#endif /* STACK_MACROS_H */ + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/croutine.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/croutine.h index 65fdc48e0..6801c410e 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/croutine.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/croutine.h @@ -1,752 +1,752 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef CO_ROUTINE_H -#define CO_ROUTINE_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include croutine.h" -#endif - -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* Used to hide the implementation of the co-routine control block. The -control block structure however has to be included in the header due to -the macro implementation of the co-routine functionality. */ -typedef void * xCoRoutineHandle; - -/* Defines the prototype to which co-routine functions must conform. */ -typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); - -typedef struct corCoRoutineControlBlock -{ - crCOROUTINE_CODE pxCoRoutineFunction; - xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ - unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ - unsigned short uxState; /*< Used internally by the co-routine implementation. */ -} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ - -/** - * croutine. h - *
- portBASE_TYPE xCoRoutineCreate(
-                                 crCOROUTINE_CODE pxCoRoutineCode,
-                                 unsigned portBASE_TYPE uxPriority,
-                                 unsigned portBASE_TYPE uxIndex
-                               );
- * - * Create a new co-routine and add it to the list of co-routines that are - * ready to run. - * - * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine - * functions require special syntax - see the co-routine section of the WEB - * documentation for more information. - * - * @param uxPriority The priority with respect to other co-routines at which - * the co-routine will run. - * - * @param uxIndex Used to distinguish between different co-routines that - * execute the same function. See the example below and the co-routine section - * of the WEB documentation for further information. - * - * @return pdPASS if the co-routine was successfully created and added to a ready - * list, otherwise an error code defined with ProjDefs.h. - * - * Example usage: -
- // Co-routine to be created.
- void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- static const char cLedToFlash[ 2 ] = { 5, 6 };
- static const portTickType uxFlashRates[ 2 ] = { 200, 400 };
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // This co-routine just delays for a fixed period, then toggles
-         // an LED.  Two co-routines are created using this function, so
-         // the uxIndex parameter is used to tell the co-routine which
-         // LED to flash and how long to delay.  This assumes xQueue has
-         // already been created.
-         vParTestToggleLED( cLedToFlash[ uxIndex ] );
-         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
-
- // Function that creates two co-routines.
- void vOtherFunction( void )
- {
- unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-		
-     // Create two co-routines at priority 0.  The first is given index 0
-     // so (from the code above) toggles LED 5 every 200 ticks.  The second
-     // is given index 1 so toggles LED 6 every 400 ticks.
-     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
-     {
-         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
-     }
- }
-   
- * \defgroup xCoRoutineCreate xCoRoutineCreate - * \ingroup Tasks - */ -signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); - - -/** - * croutine. h - *
- void vCoRoutineSchedule( void );
- * - * Run a co-routine. - * - * vCoRoutineSchedule() executes the highest priority co-routine that is able - * to run. The co-routine will execute until it either blocks, yields or is - * preempted by a task. Co-routines execute cooperatively so one - * co-routine cannot be preempted by another, but can be preempted by a task. - * - * If an application comprises of both tasks and co-routines then - * vCoRoutineSchedule should be called from the idle task (in an idle task - * hook). - * - * Example usage: -
- // This idle task hook will schedule a co-routine each time it is called.
- // The rest of the idle task will execute between co-routine calls.
- void vApplicationIdleHook( void )
- {
-	vCoRoutineSchedule();
- }
-
- // Alternatively, if you do not require any other part of the idle task to
- // execute, the idle task hook can call vCoRoutineScheduler() within an
- // infinite loop.
- void vApplicationIdleHook( void )
- {
-    for( ;; )
-    {
-        vCoRoutineSchedule();
-    }
- }
- 
- * \defgroup vCoRoutineSchedule vCoRoutineSchedule - * \ingroup Tasks - */ -void vCoRoutineSchedule( void ); - -/** - * croutine. h - *
- crSTART( xCoRoutineHandle xHandle );
- * - * This macro MUST always be called at the start of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crSTART( pxCRCB ) switch( ( ( corCRCB * )( pxCRCB ) )->uxState ) { case 0: - -/** - * croutine. h - *
- crEND();
- * - * This macro MUST always be called at the end of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crEND() } - -/* - * These macros are intended for internal use by the co-routine implementation - * only. The macros should not be used directly by application writers. - */ -#define crSET_STATE0( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): -#define crSET_STATE1( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): - -/** - * croutine. h - *
- crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
- * - * Delay a co-routine for a fixed period of time. - * - * crDELAY can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * @param xHandle The handle of the co-routine to delay. This is the xHandle - * parameter of the co-routine function. - * - * @param xTickToDelay The number of ticks that the co-routine should delay - * for. The actual amount of time this equates to is defined by - * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS - * can be used to convert ticks to milliseconds. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- // We are to delay for 200ms.
- static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-        // Delay for 200ms.
-        crDELAY( xHandle, xDelayTime );
-
-        // Do something here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crDELAY crDELAY - * \ingroup Tasks - */ -#define crDELAY( xHandle, xTicksToDelay ) \ - if( ( xTicksToDelay ) > 0 ) \ - { \ - vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL ); \ - } \ - crSET_STATE0( ( xHandle ) ); - -/** - *
- crQUEUE_SEND(
-                  xCoRoutineHandle xHandle,
-                  xQueueHandle pxQueue,
-                  void *pvItemToQueue,
-                  portTickType xTicksToWait,
-                  portBASE_TYPE *pxResult
-             )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_SEND can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue on which the data will be posted. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvItemToQueue A pointer to the data being posted onto the queue. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied from pvItemToQueue into the queue - * itself. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for space to become available on the queue, should space not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example - * below). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully posted onto the queue, otherwise it will be set to an - * error defined within ProjDefs.h. - * - * Example usage: -
- // Co-routine function that blocks for a fixed period then posts a number onto
- // a queue.
- static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xNumberToPost = 0;
- static portBASE_TYPE xResult;
-
-    // Co-routines must begin with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // This assumes the queue has already been created.
-        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
-
-        if( xResult != pdPASS )
-        {
-            // The message was not posted!
-        }
-
-        // Increment the number to be posted onto the queue.
-        xNumberToPost++;
-
-        // Delay for 100 ticks.
-        crDELAY( xHandle, 100 );
-    }
-
-    // Co-routines must end with a call to crEND().
-    crEND();
- }
- * \defgroup crQUEUE_SEND crQUEUE_SEND - * \ingroup Tasks - */ -#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ -{ \ - *( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) ); \ - if( *( pxResult ) == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( ( xHandle ) ); \ - *pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 ); \ - } \ - if( *pxResult == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( ( xHandle ) ); \ - *pxResult = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_RECEIVE(
-                     xCoRoutineHandle xHandle,
-                     xQueueHandle pxQueue,
-                     void *pvBuffer,
-                     portTickType xTicksToWait,
-                     portBASE_TYPE *pxResult
-                 )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_RECEIVE can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue from which the data will be received. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvBuffer The buffer into which the received item is to be copied. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied into pvBuffer. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for data to become available from the queue, should data not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the - * crQUEUE_SEND example). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully retrieved from the queue, otherwise it will be set to - * an error code as defined within ProjDefs.h. - * - * Example usage: -
- // A co-routine receives the number of an LED to flash from a queue.  It
- // blocks on the queue until the number is received.
- static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xResult;
- static unsigned portBASE_TYPE uxLEDToFlash;
-
-    // All co-routines must start with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // Wait for data to become available on the queue.
-        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-        if( xResult == pdPASS )
-        {
-            // We received the LED to flash - flash it!
-            vParTestToggleLED( uxLEDToFlash );
-        }
-    }
-
-    crEND();
- }
- * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ -{ \ - *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) ); \ - if( *( pxResult ) == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( ( xHandle ) ); \ - *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 ); \ - } \ - if( *( pxResult ) == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( ( xHandle ) ); \ - *( pxResult ) = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvItemToQueue,
-                            portBASE_TYPE xCoRoutinePreviouslyWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue - * that is being used from within a co-routine. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto - * the same queue multiple times from a single interrupt. The first call - * should always pass in pdFALSE. Subsequent calls should pass in - * the value returned from the previous call. - * - * @return pdTRUE if a co-routine was woken by posting onto the queue. This is - * used by the ISR to determine if a context switch may be required following - * the ISR. - * - * Example usage: -
- // A co-routine that blocks on a queue waiting for characters to be received.
- static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- char cRxedChar;
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Wait for data to become available on the queue.  This assumes the
-         // queue xCommsRxQueue has already been created!
-         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-         // Was a character received?
-         if( xResult == pdPASS )
-         {
-             // Process the character here.
-         }
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to send characters received on a serial port to
- // a co-routine.
- void vUART_ISR( void )
- {
- char cRxedChar;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     // We loop around reading characters until there are none left in the UART.
-     while( UART_RX_REG_NOT_EMPTY() )
-     {
-         // Obtain the character from the UART.
-         cRxedChar = UART_RX_REG;
-
-         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
-         // the first time around the loop.  If the post causes a co-routine
-         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
-         // In this manner we can ensure that if more than one co-routine is
-         // blocked on the queue only one is woken by this ISR no matter how
-         // many characters are posted to the queue.
-         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
-     }
- }
- * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) ) - - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvBuffer,
-                            portBASE_TYPE * pxCoRoutineWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data - * from a queue that is being used from within a co-routine (a co-routine - * posted to the queue). - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvBuffer A pointer to a buffer into which the received item will be - * placed. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from the queue into - * pvBuffer. - * - * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become - * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a - * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise - * *pxCoRoutineWoken will remain unchanged. - * - * @return pdTRUE an item was successfully received from the queue, otherwise - * pdFALSE. - * - * Example usage: -
- // A co-routine that posts a character to a queue then blocks for a fixed
- // period.  The character is incremented each time.
- static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // cChar holds its value while this co-routine is blocked and must therefore
- // be declared static.
- static char cCharToTx = 'a';
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Send the next character to the queue.
-         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
-
-         if( xResult == pdPASS )
-         {
-             // The character was successfully posted to the queue.
-         }
-		 else
-		 {
-			// Could not post the character to the queue.
-		 }
-
-         // Enable the UART Tx interrupt to cause an interrupt in this
-		 // hypothetical UART.  The interrupt will obtain the character
-		 // from the queue and send it.
-		 ENABLE_RX_INTERRUPT();
-
-		 // Increment to the next character then block for a fixed period.
-		 // cCharToTx will maintain its value across the delay as it is
-		 // declared static.
-		 cCharToTx++;
-		 if( cCharToTx > 'x' )
-		 {
-			cCharToTx = 'a';
-		 }
-		 crDELAY( 100 );
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to receive characters to send on a UART.
- void vUART_ISR( void )
- {
- char cCharToTx;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     while( UART_TX_REG_EMPTY() )
-     {
-         // Are there any characters in the queue waiting to be sent?
-		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
-		 // is woken by the post - ensuring that only a single co-routine is
-		 // woken no matter how many times we go around this loop.
-         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
-		 {
-			 SEND_CHARACTER( cCharToTx );
-		 }
-     }
- }
- * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) ) - -/* - * This function is intended for internal use by the co-routine macros only. - * The macro nature of the co-routine implementation requires that the - * prototype appears here. The function should not be used by application - * writers. - * - * Removes the current co-routine from its ready list and places it in the - * appropriate delayed list. - */ -void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); - -/* - * This function is intended for internal use by the queue implementation only. - * The function should not be used by application writers. - * - * Removes the highest priority co-routine from the event list and places it in - * the pending ready list. - */ -signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); - -#ifdef __cplusplus -} -#endif - -#endif /* CO_ROUTINE_H */ +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef CO_ROUTINE_H +#define CO_ROUTINE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include croutine.h" +#endif + +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Used to hide the implementation of the co-routine control block. The +control block structure however has to be included in the header due to +the macro implementation of the co-routine functionality. */ +typedef void * xCoRoutineHandle; + +/* Defines the prototype to which co-routine functions must conform. */ +typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); + +typedef struct corCoRoutineControlBlock +{ + crCOROUTINE_CODE pxCoRoutineFunction; + xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ + unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ + unsigned short uxState; /*< Used internally by the co-routine implementation. */ +} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ + +/** + * croutine. h + *
+ portBASE_TYPE xCoRoutineCreate(
+                                 crCOROUTINE_CODE pxCoRoutineCode,
+                                 unsigned portBASE_TYPE uxPriority,
+                                 unsigned portBASE_TYPE uxIndex
+                               );
+ * + * Create a new co-routine and add it to the list of co-routines that are + * ready to run. + * + * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine + * functions require special syntax - see the co-routine section of the WEB + * documentation for more information. + * + * @param uxPriority The priority with respect to other co-routines at which + * the co-routine will run. + * + * @param uxIndex Used to distinguish between different co-routines that + * execute the same function. See the example below and the co-routine section + * of the WEB documentation for further information. + * + * @return pdPASS if the co-routine was successfully created and added to a ready + * list, otherwise an error code defined with ProjDefs.h. + * + * Example usage: +
+ // Co-routine to be created.
+ void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ static const char cLedToFlash[ 2 ] = { 5, 6 };
+ static const portTickType uxFlashRates[ 2 ] = { 200, 400 };
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // This co-routine just delays for a fixed period, then toggles
+         // an LED.  Two co-routines are created using this function, so
+         // the uxIndex parameter is used to tell the co-routine which
+         // LED to flash and how long to delay.  This assumes xQueue has
+         // already been created.
+         vParTestToggleLED( cLedToFlash[ uxIndex ] );
+         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+
+ // Function that creates two co-routines.
+ void vOtherFunction( void )
+ {
+ unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+		
+     // Create two co-routines at priority 0.  The first is given index 0
+     // so (from the code above) toggles LED 5 every 200 ticks.  The second
+     // is given index 1 so toggles LED 6 every 400 ticks.
+     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
+     {
+         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
+     }
+ }
+   
+ * \defgroup xCoRoutineCreate xCoRoutineCreate + * \ingroup Tasks + */ +signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); + + +/** + * croutine. h + *
+ void vCoRoutineSchedule( void );
+ * + * Run a co-routine. + * + * vCoRoutineSchedule() executes the highest priority co-routine that is able + * to run. The co-routine will execute until it either blocks, yields or is + * preempted by a task. Co-routines execute cooperatively so one + * co-routine cannot be preempted by another, but can be preempted by a task. + * + * If an application comprises of both tasks and co-routines then + * vCoRoutineSchedule should be called from the idle task (in an idle task + * hook). + * + * Example usage: +
+ // This idle task hook will schedule a co-routine each time it is called.
+ // The rest of the idle task will execute between co-routine calls.
+ void vApplicationIdleHook( void )
+ {
+	vCoRoutineSchedule();
+ }
+
+ // Alternatively, if you do not require any other part of the idle task to
+ // execute, the idle task hook can call vCoRoutineScheduler() within an
+ // infinite loop.
+ void vApplicationIdleHook( void )
+ {
+    for( ;; )
+    {
+        vCoRoutineSchedule();
+    }
+ }
+ 
+ * \defgroup vCoRoutineSchedule vCoRoutineSchedule + * \ingroup Tasks + */ +void vCoRoutineSchedule( void ); + +/** + * croutine. h + *
+ crSTART( xCoRoutineHandle xHandle );
+ * + * This macro MUST always be called at the start of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crSTART( pxCRCB ) switch( ( ( corCRCB * )( pxCRCB ) )->uxState ) { case 0: + +/** + * croutine. h + *
+ crEND();
+ * + * This macro MUST always be called at the end of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crEND() } + +/* + * These macros are intended for internal use by the co-routine implementation + * only. The macros should not be used directly by application writers. + */ +#define crSET_STATE0( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): +#define crSET_STATE1( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): + +/** + * croutine. h + *
+ crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
+ * + * Delay a co-routine for a fixed period of time. + * + * crDELAY can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * @param xHandle The handle of the co-routine to delay. This is the xHandle + * parameter of the co-routine function. + * + * @param xTickToDelay The number of ticks that the co-routine should delay + * for. The actual amount of time this equates to is defined by + * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS + * can be used to convert ticks to milliseconds. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ // We are to delay for 200ms.
+ static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+        // Delay for 200ms.
+        crDELAY( xHandle, xDelayTime );
+
+        // Do something here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crDELAY crDELAY + * \ingroup Tasks + */ +#define crDELAY( xHandle, xTicksToDelay ) \ + if( ( xTicksToDelay ) > 0 ) \ + { \ + vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL ); \ + } \ + crSET_STATE0( ( xHandle ) ); + +/** + *
+ crQUEUE_SEND(
+                  xCoRoutineHandle xHandle,
+                  xQueueHandle pxQueue,
+                  void *pvItemToQueue,
+                  portTickType xTicksToWait,
+                  portBASE_TYPE *pxResult
+             )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_SEND can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue on which the data will be posted. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvItemToQueue A pointer to the data being posted onto the queue. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied from pvItemToQueue into the queue + * itself. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for space to become available on the queue, should space not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example + * below). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully posted onto the queue, otherwise it will be set to an + * error defined within ProjDefs.h. + * + * Example usage: +
+ // Co-routine function that blocks for a fixed period then posts a number onto
+ // a queue.
+ static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xNumberToPost = 0;
+ static portBASE_TYPE xResult;
+
+    // Co-routines must begin with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // This assumes the queue has already been created.
+        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
+
+        if( xResult != pdPASS )
+        {
+            // The message was not posted!
+        }
+
+        // Increment the number to be posted onto the queue.
+        xNumberToPost++;
+
+        // Delay for 100 ticks.
+        crDELAY( xHandle, 100 );
+    }
+
+    // Co-routines must end with a call to crEND().
+    crEND();
+ }
+ * \defgroup crQUEUE_SEND crQUEUE_SEND + * \ingroup Tasks + */ +#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 ); \ + } \ + if( *pxResult == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *pxResult = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_RECEIVE(
+                     xCoRoutineHandle xHandle,
+                     xQueueHandle pxQueue,
+                     void *pvBuffer,
+                     portTickType xTicksToWait,
+                     portBASE_TYPE *pxResult
+                 )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_RECEIVE can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue from which the data will be received. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvBuffer The buffer into which the received item is to be copied. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied into pvBuffer. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for data to become available from the queue, should data not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the + * crQUEUE_SEND example). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully retrieved from the queue, otherwise it will be set to + * an error code as defined within ProjDefs.h. + * + * Example usage: +
+ // A co-routine receives the number of an LED to flash from a queue.  It
+ // blocks on the queue until the number is received.
+ static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xResult;
+ static unsigned portBASE_TYPE uxLEDToFlash;
+
+    // All co-routines must start with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // Wait for data to become available on the queue.
+        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+        if( xResult == pdPASS )
+        {
+            // We received the LED to flash - flash it!
+            vParTestToggleLED( uxLEDToFlash );
+        }
+    }
+
+    crEND();
+ }
+ * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 ); \ + } \ + if( *( pxResult ) == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *( pxResult ) = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvItemToQueue,
+                            portBASE_TYPE xCoRoutinePreviouslyWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue + * that is being used from within a co-routine. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto + * the same queue multiple times from a single interrupt. The first call + * should always pass in pdFALSE. Subsequent calls should pass in + * the value returned from the previous call. + * + * @return pdTRUE if a co-routine was woken by posting onto the queue. This is + * used by the ISR to determine if a context switch may be required following + * the ISR. + * + * Example usage: +
+ // A co-routine that blocks on a queue waiting for characters to be received.
+ static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ char cRxedChar;
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Wait for data to become available on the queue.  This assumes the
+         // queue xCommsRxQueue has already been created!
+         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+         // Was a character received?
+         if( xResult == pdPASS )
+         {
+             // Process the character here.
+         }
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to send characters received on a serial port to
+ // a co-routine.
+ void vUART_ISR( void )
+ {
+ char cRxedChar;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     // We loop around reading characters until there are none left in the UART.
+     while( UART_RX_REG_NOT_EMPTY() )
+     {
+         // Obtain the character from the UART.
+         cRxedChar = UART_RX_REG;
+
+         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
+         // the first time around the loop.  If the post causes a co-routine
+         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
+         // In this manner we can ensure that if more than one co-routine is
+         // blocked on the queue only one is woken by this ISR no matter how
+         // many characters are posted to the queue.
+         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
+     }
+ }
+ * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) ) + + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvBuffer,
+                            portBASE_TYPE * pxCoRoutineWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data + * from a queue that is being used from within a co-routine (a co-routine + * posted to the queue). + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvBuffer A pointer to a buffer into which the received item will be + * placed. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from the queue into + * pvBuffer. + * + * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become + * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a + * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise + * *pxCoRoutineWoken will remain unchanged. + * + * @return pdTRUE an item was successfully received from the queue, otherwise + * pdFALSE. + * + * Example usage: +
+ // A co-routine that posts a character to a queue then blocks for a fixed
+ // period.  The character is incremented each time.
+ static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // cChar holds its value while this co-routine is blocked and must therefore
+ // be declared static.
+ static char cCharToTx = 'a';
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Send the next character to the queue.
+         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
+
+         if( xResult == pdPASS )
+         {
+             // The character was successfully posted to the queue.
+         }
+		 else
+		 {
+			// Could not post the character to the queue.
+		 }
+
+         // Enable the UART Tx interrupt to cause an interrupt in this
+		 // hypothetical UART.  The interrupt will obtain the character
+		 // from the queue and send it.
+		 ENABLE_RX_INTERRUPT();
+
+		 // Increment to the next character then block for a fixed period.
+		 // cCharToTx will maintain its value across the delay as it is
+		 // declared static.
+		 cCharToTx++;
+		 if( cCharToTx > 'x' )
+		 {
+			cCharToTx = 'a';
+		 }
+		 crDELAY( 100 );
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to receive characters to send on a UART.
+ void vUART_ISR( void )
+ {
+ char cCharToTx;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     while( UART_TX_REG_EMPTY() )
+     {
+         // Are there any characters in the queue waiting to be sent?
+		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
+		 // is woken by the post - ensuring that only a single co-routine is
+		 // woken no matter how many times we go around this loop.
+         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
+		 {
+			 SEND_CHARACTER( cCharToTx );
+		 }
+     }
+ }
+ * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) ) + +/* + * This function is intended for internal use by the co-routine macros only. + * The macro nature of the co-routine implementation requires that the + * prototype appears here. The function should not be used by application + * writers. + * + * Removes the current co-routine from its ready list and places it in the + * appropriate delayed list. + */ +void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); + +/* + * This function is intended for internal use by the queue implementation only. + * The function should not be used by application writers. + * + * Removes the highest priority co-routine from the event list and places it in + * the pending ready list. + */ +signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); + +#ifdef __cplusplus +} +#endif + +#endif /* CO_ROUTINE_H */ diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/list.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/list.h index e8b47c439..01e69cbd8 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/list.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/list.h @@ -1,314 +1,314 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/* - * This is the list implementation used by the scheduler. While it is tailored - * heavily for the schedulers needs, it is also available for use by - * application code. - * - * xLists can only store pointers to xListItems. Each xListItem contains a - * numeric value (xItemValue). Most of the time the lists are sorted in - * descending item value order. - * - * Lists are created already containing one list item. The value of this - * item is the maximum possible that can be stored, it is therefore always at - * the end of the list and acts as a marker. The list member pxHead always - * points to this marker - even though it is at the tail of the list. This - * is because the tail contains a wrap back pointer to the true head of - * the list. - * - * In addition to it's value, each list item contains a pointer to the next - * item in the list (pxNext), a pointer to the list it is in (pxContainer) - * and a pointer to back to the object that contains it. These later two - * pointers are included for efficiency of list manipulation. There is - * effectively a two way link between the object containing the list item and - * the list item itself. - * - * - * \page ListIntroduction List Implementation - * \ingroup FreeRTOSIntro - */ - - -#ifndef LIST_H -#define LIST_H - -#ifdef __cplusplus -extern "C" { -#endif -/* - * Definition of the only type of object that a list can contain. - */ -struct xLIST_ITEM -{ - portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ - volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ - volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ - void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ - void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ -}; -typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ - -struct xMINI_LIST_ITEM -{ - portTickType xItemValue; - volatile struct xLIST_ITEM *pxNext; - volatile struct xLIST_ITEM *pxPrevious; -}; -typedef struct xMINI_LIST_ITEM xMiniListItem; - -/* - * Definition of the type of queue used by the scheduler. - */ -typedef struct xLIST -{ - volatile unsigned portBASE_TYPE uxNumberOfItems; - volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ - volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ -} xList; - -/* - * Access macro to set the owner of a list item. The owner of a list item - * is the object (usually a TCB) that contains the list item. - * - * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) - -/* - * Access macro to set the value of the list item. In most cases the value is - * used to sort the list in descending order. - * - * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = ( xValue ) - -/* - * Access macro the retrieve the value of the list item. The value can - * represent anything - for example a the priority of a task, or the time at - * which a task should be unblocked. - * - * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) - -/* - * Access macro the retrieve the value of the list item at the head of a given - * list. - * - * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->xItemValue ) - -/* - * Access macro to determine if a list contains any items. The macro will - * only have the value true if the list is empty. - * - * \page listLIST_IS_EMPTY listLIST_IS_EMPTY - * \ingroup LinkedList - */ -#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) - -/* - * Access macro to return the number of items in the list. - */ -#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) - -/* - * Access function to obtain the owner of the next entry in a list. - * - * The list member pxIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list - * and returns that entries pxOwner parameter. Using multiple calls to this - * function it is therefore possible to move through every item contained in - * a list. - * - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the next item owner is to be returned. - * - * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ -{ \ -xList * const pxConstList = ( pxList ); \ - /* Increment the index to the next item and return the item, ensuring */ \ - /* we don't return the marker used at the end of the list. */ \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ - { \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - } \ - ( pxTCB ) = ( pxConstList )->pxIndex->pvOwner; \ -} - - -/* - * Access function to obtain the owner of the first entry in a list. Lists - * are normally sorted in ascending item value order. - * - * This function returns the pxOwner member of the first item in the list. - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the owner of the head item is to be - * returned. - * - * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner ) - -/* - * Check to see if a list item is within a list. The list item maintains a - * "container" pointer that points to the list it is in. All this macro does - * is check to see if the container and the list match. - * - * @param pxList The list we want to know if the list item is within. - * @param pxListItem The list item we want to know if is in the list. - * @return pdTRUE is the list item is in the list, otherwise pdFALSE. - * pointer against - */ -#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) ( pxList ) ) - -/* - * Must be called before a list is used! This initialises all the members - * of the list structure and inserts the xListEnd item into the list as a - * marker to the back of the list. - * - * @param pxList Pointer to the list being initialised. - * - * \page vListInitialise vListInitialise - * \ingroup LinkedList - */ -void vListInitialise( xList *pxList ); - -/* - * Must be called before a list item is used. This sets the list container to - * null so the item does not think that it is already contained in a list. - * - * @param pxItem Pointer to the list item being initialised. - * - * \page vListInitialiseItem vListInitialiseItem - * \ingroup LinkedList - */ -void vListInitialiseItem( xListItem *pxItem ); - -/* - * Insert a list item into a list. The item will be inserted into the list in - * a position determined by its item value (descending item value order). - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The item to that is to be placed in the list. - * - * \page vListInsert vListInsert - * \ingroup LinkedList - */ -void vListInsert( xList *pxList, xListItem *pxNewListItem ); - -/* - * Insert a list item into a list. The item will be inserted in a position - * such that it will be the last item within the list returned by multiple - * calls to listGET_OWNER_OF_NEXT_ENTRY. - * - * The list member pvIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. - * Placing an item in a list using vListInsertEnd effectively places the item - * in the list position pointed to by pvIndex. This means that every other - * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before - * the pvIndex parameter again points to the item being inserted. - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The list item to be inserted into the list. - * - * \page vListInsertEnd vListInsertEnd - * \ingroup LinkedList - */ -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); - -/* - * Remove an item from a list. The list item has a pointer to the list that - * it is in, so only the list item need be passed into the function. - * - * @param vListRemove The item to be removed. The item will remove itself from - * the list pointed to by it's pxContainer parameter. - * - * \page vListRemove vListRemove - * \ingroup LinkedList - */ -void vListRemove( xListItem *pxItemToRemove ); - -#ifdef __cplusplus -} -#endif - -#endif - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/* + * This is the list implementation used by the scheduler. While it is tailored + * heavily for the schedulers needs, it is also available for use by + * application code. + * + * xLists can only store pointers to xListItems. Each xListItem contains a + * numeric value (xItemValue). Most of the time the lists are sorted in + * descending item value order. + * + * Lists are created already containing one list item. The value of this + * item is the maximum possible that can be stored, it is therefore always at + * the end of the list and acts as a marker. The list member pxHead always + * points to this marker - even though it is at the tail of the list. This + * is because the tail contains a wrap back pointer to the true head of + * the list. + * + * In addition to it's value, each list item contains a pointer to the next + * item in the list (pxNext), a pointer to the list it is in (pxContainer) + * and a pointer to back to the object that contains it. These later two + * pointers are included for efficiency of list manipulation. There is + * effectively a two way link between the object containing the list item and + * the list item itself. + * + * + * \page ListIntroduction List Implementation + * \ingroup FreeRTOSIntro + */ + + +#ifndef LIST_H +#define LIST_H + +#ifdef __cplusplus +extern "C" { +#endif +/* + * Definition of the only type of object that a list can contain. + */ +struct xLIST_ITEM +{ + portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ + volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ + volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ + void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ + void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ +}; +typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ + +struct xMINI_LIST_ITEM +{ + portTickType xItemValue; + volatile struct xLIST_ITEM *pxNext; + volatile struct xLIST_ITEM *pxPrevious; +}; +typedef struct xMINI_LIST_ITEM xMiniListItem; + +/* + * Definition of the type of queue used by the scheduler. + */ +typedef struct xLIST +{ + volatile unsigned portBASE_TYPE uxNumberOfItems; + volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ + volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ +} xList; + +/* + * Access macro to set the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) + +/* + * Access macro to set the value of the list item. In most cases the value is + * used to sort the list in descending order. + * + * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = ( xValue ) + +/* + * Access macro the retrieve the value of the list item. The value can + * represent anything - for example a the priority of a task, or the time at + * which a task should be unblocked. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) + +/* + * Access macro the retrieve the value of the list item at the head of a given + * list. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->xItemValue ) + +/* + * Access macro to determine if a list contains any items. The macro will + * only have the value true if the list is empty. + * + * \page listLIST_IS_EMPTY listLIST_IS_EMPTY + * \ingroup LinkedList + */ +#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) + +/* + * Access macro to return the number of items in the list. + */ +#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) + +/* + * Access function to obtain the owner of the next entry in a list. + * + * The list member pxIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list + * and returns that entries pxOwner parameter. Using multiple calls to this + * function it is therefore possible to move through every item contained in + * a list. + * + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the next item owner is to be returned. + * + * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ +{ \ +xList * const pxConstList = ( pxList ); \ + /* Increment the index to the next item and return the item, ensuring */ \ + /* we don't return the marker used at the end of the list. */ \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ + { \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + } \ + ( pxTCB ) = ( pxConstList )->pxIndex->pvOwner; \ +} + + +/* + * Access function to obtain the owner of the first entry in a list. Lists + * are normally sorted in ascending item value order. + * + * This function returns the pxOwner member of the first item in the list. + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the owner of the head item is to be + * returned. + * + * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner ) + +/* + * Check to see if a list item is within a list. The list item maintains a + * "container" pointer that points to the list it is in. All this macro does + * is check to see if the container and the list match. + * + * @param pxList The list we want to know if the list item is within. + * @param pxListItem The list item we want to know if is in the list. + * @return pdTRUE is the list item is in the list, otherwise pdFALSE. + * pointer against + */ +#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) ( pxList ) ) + +/* + * Must be called before a list is used! This initialises all the members + * of the list structure and inserts the xListEnd item into the list as a + * marker to the back of the list. + * + * @param pxList Pointer to the list being initialised. + * + * \page vListInitialise vListInitialise + * \ingroup LinkedList + */ +void vListInitialise( xList *pxList ); + +/* + * Must be called before a list item is used. This sets the list container to + * null so the item does not think that it is already contained in a list. + * + * @param pxItem Pointer to the list item being initialised. + * + * \page vListInitialiseItem vListInitialiseItem + * \ingroup LinkedList + */ +void vListInitialiseItem( xListItem *pxItem ); + +/* + * Insert a list item into a list. The item will be inserted into the list in + * a position determined by its item value (descending item value order). + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The item to that is to be placed in the list. + * + * \page vListInsert vListInsert + * \ingroup LinkedList + */ +void vListInsert( xList *pxList, xListItem *pxNewListItem ); + +/* + * Insert a list item into a list. The item will be inserted in a position + * such that it will be the last item within the list returned by multiple + * calls to listGET_OWNER_OF_NEXT_ENTRY. + * + * The list member pvIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. + * Placing an item in a list using vListInsertEnd effectively places the item + * in the list position pointed to by pvIndex. This means that every other + * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before + * the pvIndex parameter again points to the item being inserted. + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The list item to be inserted into the list. + * + * \page vListInsertEnd vListInsertEnd + * \ingroup LinkedList + */ +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); + +/* + * Remove an item from a list. The list item has a pointer to the list that + * it is in, so only the list item need be passed into the function. + * + * @param vListRemove The item to be removed. The item will remove itself from + * the list pointed to by it's pxContainer parameter. + * + * \page vListRemove vListRemove + * \ingroup LinkedList + */ +void vListRemove( xListItem *pxItemToRemove ); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/mpu_wrappers.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/mpu_wrappers.h index b7371b9ba..a0c27234b 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/mpu_wrappers.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/mpu_wrappers.h @@ -1,141 +1,141 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef MPU_WRAPPERS_H -#define MPU_WRAPPERS_H - -/* This file redefines API functions to be called through a wrapper macro, but -only for ports that are using the MPU. */ -#ifdef portUSING_MPU_WRAPPERS - - /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is - included from queue.c or task.c to prevent it from having an effect within - those files. */ - #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - - #define xTaskGenericCreate MPU_xTaskGenericCreate - #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions - #define vTaskDelete MPU_vTaskDelete - #define vTaskDelayUntil MPU_vTaskDelayUntil - #define vTaskDelay MPU_vTaskDelay - #define uxTaskPriorityGet MPU_uxTaskPriorityGet - #define vTaskPrioritySet MPU_vTaskPrioritySet - #define vTaskSuspend MPU_vTaskSuspend - #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended - #define vTaskResume MPU_vTaskResume - #define vTaskSuspendAll MPU_vTaskSuspendAll - #define xTaskResumeAll MPU_xTaskResumeAll - #define xTaskGetTickCount MPU_xTaskGetTickCount - #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks - #define vTaskList MPU_vTaskList - #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats - #define vTaskStartTrace MPU_vTaskStartTrace - #define ulTaskEndTrace MPU_ulTaskEndTrace - #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag - #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag - #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook - #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark - #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle - #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState - - #define xQueueCreate MPU_xQueueCreate - #define xQueueCreateMutex MPU_xQueueCreateMutex - #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive - #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive - #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore - #define xQueueGenericSend MPU_xQueueGenericSend - #define xQueueAltGenericSend MPU_xQueueAltGenericSend - #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive - #define xQueueGenericReceive MPU_xQueueGenericReceive - #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting - #define vQueueDelete MPU_vQueueDelete - - #define pvPortMalloc MPU_pvPortMalloc - #define vPortFree MPU_vPortFree - #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize - #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks - - #if configQUEUE_REGISTRY_SIZE > 0 - #define vQueueAddToRegistry MPU_vQueueAddToRegistry - #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue - #endif - - /* Remove the privileged function macro. */ - #define PRIVILEGED_FUNCTION - - #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - - /* Ensure API functions go in the privileged execution section. */ - #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) - #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) - //#define PRIVILEGED_DATA - - #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - -#else /* portUSING_MPU_WRAPPERS */ - - #define PRIVILEGED_FUNCTION - #define PRIVILEGED_DATA - #define portUSING_MPU_WRAPPERS 0 - -#endif /* portUSING_MPU_WRAPPERS */ - - -#endif /* MPU_WRAPPERS_H */ - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef MPU_WRAPPERS_H +#define MPU_WRAPPERS_H + +/* This file redefines API functions to be called through a wrapper macro, but +only for ports that are using the MPU. */ +#ifdef portUSING_MPU_WRAPPERS + + /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is + included from queue.c or task.c to prevent it from having an effect within + those files. */ + #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + + #define xTaskGenericCreate MPU_xTaskGenericCreate + #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions + #define vTaskDelete MPU_vTaskDelete + #define vTaskDelayUntil MPU_vTaskDelayUntil + #define vTaskDelay MPU_vTaskDelay + #define uxTaskPriorityGet MPU_uxTaskPriorityGet + #define vTaskPrioritySet MPU_vTaskPrioritySet + #define vTaskSuspend MPU_vTaskSuspend + #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended + #define vTaskResume MPU_vTaskResume + #define vTaskSuspendAll MPU_vTaskSuspendAll + #define xTaskResumeAll MPU_xTaskResumeAll + #define xTaskGetTickCount MPU_xTaskGetTickCount + #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks + #define vTaskList MPU_vTaskList + #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats + #define vTaskStartTrace MPU_vTaskStartTrace + #define ulTaskEndTrace MPU_ulTaskEndTrace + #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag + #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag + #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook + #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark + #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle + #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState + + #define xQueueCreate MPU_xQueueCreate + #define xQueueCreateMutex MPU_xQueueCreateMutex + #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive + #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive + #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore + #define xQueueGenericSend MPU_xQueueGenericSend + #define xQueueAltGenericSend MPU_xQueueAltGenericSend + #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive + #define xQueueGenericReceive MPU_xQueueGenericReceive + #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting + #define vQueueDelete MPU_vQueueDelete + + #define pvPortMalloc MPU_pvPortMalloc + #define vPortFree MPU_vPortFree + #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize + #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks + + #if configQUEUE_REGISTRY_SIZE > 0 + #define vQueueAddToRegistry MPU_vQueueAddToRegistry + #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue + #endif + + /* Remove the privileged function macro. */ + #define PRIVILEGED_FUNCTION + + #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + + /* Ensure API functions go in the privileged execution section. */ + #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) + #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) + //#define PRIVILEGED_DATA + + #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + +#else /* portUSING_MPU_WRAPPERS */ + + #define PRIVILEGED_FUNCTION + #define PRIVILEGED_DATA + #define portUSING_MPU_WRAPPERS 0 + +#endif /* portUSING_MPU_WRAPPERS */ + + +#endif /* MPU_WRAPPERS_H */ + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/portable.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/portable.h index 288320033..54140ff0b 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/portable.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/portable.h @@ -1,396 +1,396 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Portable layer API. Each function must be defined for each port. - *----------------------------------------------------------*/ - -#ifndef PORTABLE_H -#define PORTABLE_H - -/* Include the macro file relevant to the port being used. */ - -#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT - #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT - #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef GCC_MEGA_AVR - #include "../portable/GCC/ATMega323/portmacro.h" -#endif - -#ifdef IAR_MEGA_AVR - #include "../portable/IAR/ATMega323/portmacro.h" -#endif - -#ifdef MPLAB_PIC24_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_DSPIC_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_PIC18F_PORT - #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" -#endif - -#ifdef MPLAB_PIC32MX_PORT - #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" -#endif - -#ifdef _FEDPICC - #include "libFreeRTOS/Include/portmacro.h" -#endif - -#ifdef SDCC_CYGNAL - #include "../../Source/portable/SDCC/Cygnal/portmacro.h" -#endif - -#ifdef GCC_ARM7 - #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" -#endif - -#ifdef GCC_ARM7_ECLIPSE - #include "portmacro.h" -#endif - -#ifdef ROWLEY_LPC23xx - #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" -#endif - -#ifdef IAR_MSP430 - #include "..\..\Source\portable\IAR\MSP430\portmacro.h" -#endif - -#ifdef GCC_MSP430 - #include "../../Source/portable/GCC/MSP430F449/portmacro.h" -#endif - -#ifdef ROWLEY_MSP430 - #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" -#endif - -#ifdef ARM7_LPC21xx_KEIL_RVDS - #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" -#endif - -#ifdef SAM7_GCC - #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" -#endif - -#ifdef SAM7_IAR - #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" -#endif - -#ifdef SAM9XE_IAR - #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" -#endif - -#ifdef LPC2000_IAR - #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" -#endif - -#ifdef STR71X_IAR - #include "..\..\Source\portable\IAR\STR71x\portmacro.h" -#endif - -#ifdef STR75X_IAR - #include "..\..\Source\portable\IAR\STR75x\portmacro.h" -#endif - -#ifdef STR75X_GCC - #include "..\..\Source\portable\GCC\STR75x\portmacro.h" -#endif - -#ifdef STR91X_IAR - #include "..\..\Source\portable\IAR\STR91x\portmacro.h" -#endif - -#ifdef GCC_H8S - #include "../../Source/portable/GCC/H8S2329/portmacro.h" -#endif - -#ifdef GCC_AT91FR40008 - #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" -#endif - -#ifdef RVDS_ARMCM3_LM3S102 - #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3_LM3S102 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARM_CM3 - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARMCM3_LM - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef HCS12_CODE_WARRIOR - #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" -#endif - -#ifdef MICROBLAZE_GCC - #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" -#endif - -#ifdef TERN_EE - #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" -#endif - -#ifdef GCC_HCS12 - #include "../../Source/portable/GCC/HCS12/portmacro.h" -#endif - -#ifdef GCC_MCF5235 - #include "../../Source/portable/GCC/MCF5235/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_GCC - #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_CODEWARRIOR - #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" -#endif - -#ifdef GCC_PPC405 - #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" -#endif - -#ifdef GCC_PPC440 - #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" -#endif - -#ifdef _16FX_SOFTUNE - #include "..\..\Source\portable\Softune\MB96340\portmacro.h" -#endif - -#ifdef BCC_INDUSTRIAL_PC_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef BCC_FLASH_LITE_186_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef __GNUC__ - #ifdef __AVR32_AVR32A__ - #include "portmacro.h" - #endif -#endif - -#ifdef __ICCAVR32__ - #ifdef __CORE__ - #if __CORE__ == __AVR32A__ - #include "portmacro.h" - #endif - #endif -#endif - -#ifdef __91467D - #include "portmacro.h" -#endif - -#ifdef __96340 - #include "portmacro.h" -#endif - - -#ifdef __IAR_V850ES_Fx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3_L__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Hx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3L__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -/* Catch all to ensure portmacro.h is included in the build. Newer demos -have the path as part of the project options, rather than as relative from -the project location. If portENTER_CRITICAL() has not been defined then -portmacro.h has not yet been included - as every portmacro.h provides a -portENTER_CRITICAL() definition. Check the demo application for your demo -to find the path to the correct portmacro.h file. */ -#ifndef portENTER_CRITICAL - #include "portmacro.h" -#endif - -#if portBYTE_ALIGNMENT == 8 - #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) -#endif - -#if portBYTE_ALIGNMENT == 4 - #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) -#endif - -#if portBYTE_ALIGNMENT == 2 - #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) -#endif - -#if portBYTE_ALIGNMENT == 1 - #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) -#endif - -#ifndef portBYTE_ALIGNMENT_MASK - #error "Invalid portBYTE_ALIGNMENT definition" -#endif - -#ifndef portNUM_CONFIGURABLE_REGIONS - #define portNUM_CONFIGURABLE_REGIONS 1 -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -#include "mpu_wrappers.h" - -/* - * Setup the stack of a new task so it is ready to be placed under the - * scheduler control. The registers have to be placed on the stack in - * the order that the port expects to find them. - * - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; -#else - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ); -#endif - -/* - * Map to the memory management routines required for the port. - */ -void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; -void vPortFree( void *pv ) PRIVILEGED_FUNCTION; -void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; -size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; - -/* - * Setup the hardware ready for the scheduler to take control. This generally - * sets up a tick interrupt and sets timers for the correct tick frequency. - */ -portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so - * the hardware is left in its original condition after the scheduler stops - * executing. - */ -void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * The structures and methods of manipulating the MPU are contained within the - * port layer. - * - * Fills the xMPUSettings structure with the memory region information - * contained in xRegions. - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - struct xMEMORY_REGION; - void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* PORTABLE_H */ - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/*----------------------------------------------------------- + * Portable layer API. Each function must be defined for each port. + *----------------------------------------------------------*/ + +#ifndef PORTABLE_H +#define PORTABLE_H + +/* Include the macro file relevant to the port being used. */ + +#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT + #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT + #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef GCC_MEGA_AVR + #include "../portable/GCC/ATMega323/portmacro.h" +#endif + +#ifdef IAR_MEGA_AVR + #include "../portable/IAR/ATMega323/portmacro.h" +#endif + +#ifdef MPLAB_PIC24_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_DSPIC_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_PIC18F_PORT + #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" +#endif + +#ifdef MPLAB_PIC32MX_PORT + #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" +#endif + +#ifdef _FEDPICC + #include "libFreeRTOS/Include/portmacro.h" +#endif + +#ifdef SDCC_CYGNAL + #include "../../Source/portable/SDCC/Cygnal/portmacro.h" +#endif + +#ifdef GCC_ARM7 + #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" +#endif + +#ifdef GCC_ARM7_ECLIPSE + #include "portmacro.h" +#endif + +#ifdef ROWLEY_LPC23xx + #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" +#endif + +#ifdef IAR_MSP430 + #include "..\..\Source\portable\IAR\MSP430\portmacro.h" +#endif + +#ifdef GCC_MSP430 + #include "../../Source/portable/GCC/MSP430F449/portmacro.h" +#endif + +#ifdef ROWLEY_MSP430 + #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" +#endif + +#ifdef ARM7_LPC21xx_KEIL_RVDS + #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" +#endif + +#ifdef SAM7_GCC + #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" +#endif + +#ifdef SAM7_IAR + #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" +#endif + +#ifdef SAM9XE_IAR + #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" +#endif + +#ifdef LPC2000_IAR + #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" +#endif + +#ifdef STR71X_IAR + #include "..\..\Source\portable\IAR\STR71x\portmacro.h" +#endif + +#ifdef STR75X_IAR + #include "..\..\Source\portable\IAR\STR75x\portmacro.h" +#endif + +#ifdef STR75X_GCC + #include "..\..\Source\portable\GCC\STR75x\portmacro.h" +#endif + +#ifdef STR91X_IAR + #include "..\..\Source\portable\IAR\STR91x\portmacro.h" +#endif + +#ifdef GCC_H8S + #include "../../Source/portable/GCC/H8S2329/portmacro.h" +#endif + +#ifdef GCC_AT91FR40008 + #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" +#endif + +#ifdef RVDS_ARMCM3_LM3S102 + #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3_LM3S102 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARM_CM3 + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARMCM3_LM + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef HCS12_CODE_WARRIOR + #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" +#endif + +#ifdef MICROBLAZE_GCC + #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" +#endif + +#ifdef TERN_EE + #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" +#endif + +#ifdef GCC_HCS12 + #include "../../Source/portable/GCC/HCS12/portmacro.h" +#endif + +#ifdef GCC_MCF5235 + #include "../../Source/portable/GCC/MCF5235/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_GCC + #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_CODEWARRIOR + #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" +#endif + +#ifdef GCC_PPC405 + #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" +#endif + +#ifdef GCC_PPC440 + #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" +#endif + +#ifdef _16FX_SOFTUNE + #include "..\..\Source\portable\Softune\MB96340\portmacro.h" +#endif + +#ifdef BCC_INDUSTRIAL_PC_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef BCC_FLASH_LITE_186_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef __GNUC__ + #ifdef __AVR32_AVR32A__ + #include "portmacro.h" + #endif +#endif + +#ifdef __ICCAVR32__ + #ifdef __CORE__ + #if __CORE__ == __AVR32A__ + #include "portmacro.h" + #endif + #endif +#endif + +#ifdef __91467D + #include "portmacro.h" +#endif + +#ifdef __96340 + #include "portmacro.h" +#endif + + +#ifdef __IAR_V850ES_Fx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3_L__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Hx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3L__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +/* Catch all to ensure portmacro.h is included in the build. Newer demos +have the path as part of the project options, rather than as relative from +the project location. If portENTER_CRITICAL() has not been defined then +portmacro.h has not yet been included - as every portmacro.h provides a +portENTER_CRITICAL() definition. Check the demo application for your demo +to find the path to the correct portmacro.h file. */ +#ifndef portENTER_CRITICAL + #include "portmacro.h" +#endif + +#if portBYTE_ALIGNMENT == 8 + #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) +#endif + +#if portBYTE_ALIGNMENT == 4 + #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) +#endif + +#if portBYTE_ALIGNMENT == 2 + #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) +#endif + +#if portBYTE_ALIGNMENT == 1 + #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) +#endif + +#ifndef portBYTE_ALIGNMENT_MASK + #error "Invalid portBYTE_ALIGNMENT definition" +#endif + +#ifndef portNUM_CONFIGURABLE_REGIONS + #define portNUM_CONFIGURABLE_REGIONS 1 +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#include "mpu_wrappers.h" + +/* + * Setup the stack of a new task so it is ready to be placed under the + * scheduler control. The registers have to be placed on the stack in + * the order that the port expects to find them. + * + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; +#else + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ); +#endif + +/* + * Map to the memory management routines required for the port. + */ +void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; +void vPortFree( void *pv ) PRIVILEGED_FUNCTION; +void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; +size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; + +/* + * Setup the hardware ready for the scheduler to take control. This generally + * sets up a tick interrupt and sets timers for the correct tick frequency. + */ +portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so + * the hardware is left in its original condition after the scheduler stops + * executing. + */ +void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * The structures and methods of manipulating the MPU are contained within the + * port layer. + * + * Fills the xMPUSettings structure with the memory region information + * contained in xRegions. + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + struct xMEMORY_REGION; + void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* PORTABLE_H */ + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/projdefs.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/projdefs.h index 37e432fec..424f0800f 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/projdefs.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/projdefs.h @@ -1,88 +1,88 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef PROJDEFS_H -#define PROJDEFS_H - -void PIOS_DEBUG_PinValue8Bit(unsigned char value); - -/* Defines the prototype to which task functions must conform. */ -typedef void (*pdTASK_CODE)( void * ); - -#define pdTRUE ( 1 ) -#define pdFALSE ( 0 ) - -#define pdPASS ( 1 ) -#define pdFAIL ( 0 ) -#define errQUEUE_EMPTY ( 0 ) -#define errQUEUE_FULL ( 0 ) - -/* Error definitions. */ -#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) -#define errNO_TASK_TO_RUN ( -2 ) -#define errQUEUE_BLOCKED ( -4 ) -#define errQUEUE_YIELD ( -5 ) - -// Uncomment this line to output the second character of the task that is being switched in on the debug-pins -//#define traceTASK_SWITCHED_IN() PIOS_DEBUG_PinValue8Bit(pxCurrentTCB->pcTaskName[1]); - -#endif /* PROJDEFS_H */ - - - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef PROJDEFS_H +#define PROJDEFS_H + +void PIOS_DEBUG_PinValue8Bit(unsigned char value); + +/* Defines the prototype to which task functions must conform. */ +typedef void (*pdTASK_CODE)( void * ); + +#define pdTRUE ( 1 ) +#define pdFALSE ( 0 ) + +#define pdPASS ( 1 ) +#define pdFAIL ( 0 ) +#define errQUEUE_EMPTY ( 0 ) +#define errQUEUE_FULL ( 0 ) + +/* Error definitions. */ +#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) +#define errNO_TASK_TO_RUN ( -2 ) +#define errQUEUE_BLOCKED ( -4 ) +#define errQUEUE_YIELD ( -5 ) + +// Uncomment this line to output the second character of the task that is being switched in on the debug-pins +//#define traceTASK_SWITCHED_IN() PIOS_DEBUG_PinValue8Bit(pxCurrentTCB->pcTaskName[1]); + +#endif /* PROJDEFS_H */ + + + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/queue.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/queue.h index 47add266f..9a6c86a04 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/queue.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/queue.h @@ -1,1270 +1,1270 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef QUEUE_H -#define QUEUE_H - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include queue.h" -#endif - -#ifdef __cplusplus -extern "C" { -#endif - - -#include "mpu_wrappers.h" - -/** - * Type by which queues are referenced. For example, a call to xQueueCreate - * returns (via a pointer parameter) an xQueueHandle variable that can then - * be used as a parameter to xQueueSend(), xQueueReceive(), etc. - */ -typedef void * xQueueHandle; - - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - - -/** - * queue. h - *
- xQueueHandle xQueueCreate(
-							  unsigned portBASE_TYPE uxQueueLength,
-							  unsigned portBASE_TYPE uxItemSize
-						  );
- * 
- * - * Creates a new queue instance. This allocates the storage required by the - * new queue and returns a handle for the queue. - * - * @param uxQueueLength The maximum number of items that the queue can contain. - * - * @param uxItemSize The number of bytes each item in the queue will require. - * Items are queued by copy, not by reference, so this is the number of bytes - * that will be copied for each posted item. Each item on the queue must be - * the same size. - * - * @return If the queue is successfully create then a handle to the newly - * created queue is returned. If the queue cannot be created then 0 is - * returned. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- };
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-	if( xQueue1 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue2 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueCreate xQueueCreate - * \ingroup QueueManagement - */ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ); - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToToFront(
-								   xQueueHandle	xQueue,
-								   const void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the front of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBack(
-								   xQueueHandle	xQueue,
-								   const	void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the back of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the queue - * is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSend(
-							  xQueueHandle xQueue,
-							  const void * pvItemToQueue,
-							  portTickType xTicksToWait
-						 );
- * 
- * - * This is a macro that calls xQueueGenericSend(). It is included for - * backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToFront() and xQueueSendToBack() macros. It is - * equivalent to xQueueSendToBack(). - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSend(
-									xQueueHandle xQueue,
-									const void * pvItemToQueue,
-									portTickType xTicksToWait
-									portBASE_TYPE xCopyPosition
-								);
- * 
- * - * It is preferred that the macros xQueueSend(), xQueueSendToFront() and - * xQueueSendToBack() are used in place of calling this function directly. - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueuePeek(
-							 xQueueHandle xQueue,
-							 void *pvBuffer,
-							 portTickType xTicksToWait
-						 );
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue without removing the item from the queue. - * The item is received by copy so a buffer of adequate size must be - * provided. The number of bytes copied into the buffer was defined when - * the queue was created. - * - * Successfully received items remain on the queue so will be returned again - * by the next call, or a call to xQueueReceive(). - * - * This macro must not be used in an interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue - * is empty. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to peek the data from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Peek a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask, but the item still remains on the queue.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) - -/** - * queue. h - *
- portBASE_TYPE xQueueReceive(
-								 xQueueHandle xQueue,
-								 void *pvBuffer,
-								 portTickType xTicksToWait
-							);
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * Successfully received items are removed from the queue. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. xQueueReceive() will return immediately if xTicksToWait - * is zero and the queue is empty. The time is defined in tick periods so the - * constant portTICK_RATE_MS should be used to convert to real time if this is - * required. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericReceive(
-									   xQueueHandle	xQueue,
-									   void	*pvBuffer,
-									   portTickType	xTicksToWait
-									   portBASE_TYPE	xJustPeek
-									);
- * - * It is preferred that the macro xQueueReceive() be used rather than calling - * this function directly. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueueGenericReceive() will return immediately if the queue is empty and - * xTicksToWait is 0. - * - * @param xJustPeek When set to true, the item received from the queue is not - * actually removed from the queue - meaning a subsequent call to - * xQueueReceive() will return the same item. When set to false, the item - * being received from the queue is also removed from the queue. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); - -/** - * queue. h - *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
- * - * Return the number of messages stored in a queue. - * - * @param xQueue A handle to the queue being queried. - * - * @return The number of messages available in the queue. - * - * \page uxQueueMessagesWaiting uxQueueMessagesWaiting - * \ingroup QueueManagement - */ -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); - -/** - * queue. h - *
void vQueueDelete( xQueueHandle xQueue );
- * - * Delete a queue - freeing all the memory allocated for storing of items - * placed on the queue. - * - * @param xQueue A handle to the queue to be deleted. - * - * \page vQueueDelete vQueueDelete - * \ingroup QueueManagement - */ -void vQueueDelete( xQueueHandle pxQueue ); - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToFrontFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the front of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPrioritTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBackFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the back of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendFromISR(
-									 xQueueHandle pxQueue,
-									 const void *pvItemToQueue,
-									 portBASE_TYPE *pxHigherPriorityTaskWoken
-								);
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). It is included - * for backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() - * macros. - * - * Post an item to the back of a queue. It is safe to use this function from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		// Actual macro used here is port specific.
-		taskYIELD_FROM_ISR ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSendFromISR(
-										   xQueueHandle	pxQueue,
-										   const	void	*pvItemToQueue,
-										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
-										   portBASE_TYPE	xCopyPosition
-									   );
- 
- * - * It is preferred that the macros xQueueSendFromISR(), - * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place - * of calling this function directly. - * - * Post an item on a queue. It is safe to use this function from within an - * interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWokenByPost;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWokenByPost = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post each byte.
-		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.  Note that the
-	// name of the yield function required is port specific.
-	if( xHigherPriorityTaskWokenByPost )
-	{
-		taskYIELD_YIELD_FROM_ISR();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueueReceiveFromISR(
-									   xQueueHandle	pxQueue,
-									   void	*pvBuffer,
-									   portBASE_TYPE	*pxTaskWoken
-								   );
- * 
- * - * Receive an item from a queue. It is safe to use this function from within an - * interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param pxTaskWoken A task may be blocked waiting for space to become - * available on the queue. If xQueueReceiveFromISR causes such a task to - * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will - * remain unchanged. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
-
- xQueueHandle xQueue;
-
- // Function to create a queue and post some values.
- void vAFunction( void *pvParameters )
- {
- char cValueToPost;
- const portTickType xBlockTime = ( portTickType )0xff;
-
-	// Create a queue capable of containing 10 characters.
-	xQueue = xQueueCreate( 10, sizeof( char ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Post some characters that will be used within an ISR.  If the queue
-	// is full then this task will block for xBlockTime ticks.
-	cValueToPost = 'a';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-	cValueToPost = 'b';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-
-	// ... keep posting characters ... this task may block when the queue
-	// becomes full.
-
-	cValueToPost = 'c';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
- }
-
- // ISR that outputs all the characters received on the queue.
- void vISR_Routine( void )
- {
- portBASE_TYPE xTaskWokenByReceive = pdFALSE;
- char cRxedChar;
-
-	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
-	{
-		// A character was received.  Output the character now.
-		vOutputCharacter( cRxedChar );
-
-		// If removing the character from the queue woke the task that was
-		// posting onto the queue cTaskWokenByReceive will have been set to
-		// pdTRUE.  No matter how many times this loop iterates only one
-		// task will be woken.
-	}
-
-	if( cTaskWokenByPost != ( char ) pdFALSE;
-	{
-		taskYIELD ();
-	}
- }
- 
- * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ); - -/* - * Utilities to query queue that are safe to use from an ISR. These utilities - * should be used only from witin an ISR, or within a critical section. - */ -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); - - -/* - * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). - * Likewise xQueueAltGenericReceive() is an alternative version of - * xQueueGenericReceive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); -#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) -#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) -#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) -#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) - -/* - * The functions defined above are for passing data to and from tasks. The - * functions below are the equivalents for passing data to and from - * co-routines. - * - * These functions are called from the co-routine macro implementation and - * should not be called directly from application code. Instead use the macro - * wrappers defined within croutine.h. - */ -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); - -/* - * For internal use only. Use xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting() instead of calling these functions directly. - */ -xQueueHandle xQueueCreateMutex( void ); -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); - -/* - * For internal use only. Use xSemaphoreTakeMutexRecursive() or - * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. - */ -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ); -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ); - -/* - * The registry is provided as a means for kernel aware debuggers to - * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add - * a queue, semaphore or mutex handle to the registry if you want the handle - * to be available to a kernel aware debugger. If you are not using a kernel - * aware debugger then this function can be ignored. - * - * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the - * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 - * within FreeRTOSConfig.h for the registry to be available. Its value - * does not effect the number of queues, semaphores and mutexes that can be - * created - just the number that the registry can hold. - * - * @param xQueue The handle of the queue being added to the registry. This - * is the handle returned by a call to xQueueCreate(). Semaphore and mutex - * handles can also be passed in here. - * - * @param pcName The name to be associated with the handle. This is the - * name that the kernel aware debugger will display. - */ -#if configQUEUE_REGISTRY_SIZE > 0U - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); -#endif - -/* Not a public API function, hence the 'Restricted' in the name. */ -void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ); - - -#ifdef __cplusplus -} -#endif - -#endif /* QUEUE_H */ - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef QUEUE_H +#define QUEUE_H + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include queue.h" +#endif + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "mpu_wrappers.h" + +/** + * Type by which queues are referenced. For example, a call to xQueueCreate + * returns (via a pointer parameter) an xQueueHandle variable that can then + * be used as a parameter to xQueueSend(), xQueueReceive(), etc. + */ +typedef void * xQueueHandle; + + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + + +/** + * queue. h + *
+ xQueueHandle xQueueCreate(
+							  unsigned portBASE_TYPE uxQueueLength,
+							  unsigned portBASE_TYPE uxItemSize
+						  );
+ * 
+ * + * Creates a new queue instance. This allocates the storage required by the + * new queue and returns a handle for the queue. + * + * @param uxQueueLength The maximum number of items that the queue can contain. + * + * @param uxItemSize The number of bytes each item in the queue will require. + * Items are queued by copy, not by reference, so this is the number of bytes + * that will be copied for each posted item. Each item on the queue must be + * the same size. + * + * @return If the queue is successfully create then a handle to the newly + * created queue is returned. If the queue cannot be created then 0 is + * returned. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+	if( xQueue1 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue2 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueCreate xQueueCreate + * \ingroup QueueManagement + */ +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToToFront(
+								   xQueueHandle	xQueue,
+								   const void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the front of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBack(
+								   xQueueHandle	xQueue,
+								   const	void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the back of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the queue + * is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSend(
+							  xQueueHandle xQueue,
+							  const void * pvItemToQueue,
+							  portTickType xTicksToWait
+						 );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). It is included for + * backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToFront() and xQueueSendToBack() macros. It is + * equivalent to xQueueSendToBack(). + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSend(
+									xQueueHandle xQueue,
+									const void * pvItemToQueue,
+									portTickType xTicksToWait
+									portBASE_TYPE xCopyPosition
+								);
+ * 
+ * + * It is preferred that the macros xQueueSend(), xQueueSendToFront() and + * xQueueSendToBack() are used in place of calling this function directly. + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueuePeek(
+							 xQueueHandle xQueue,
+							 void *pvBuffer,
+							 portTickType xTicksToWait
+						 );
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue without removing the item from the queue. + * The item is received by copy so a buffer of adequate size must be + * provided. The number of bytes copied into the buffer was defined when + * the queue was created. + * + * Successfully received items remain on the queue so will be returned again + * by the next call, or a call to xQueueReceive(). + * + * This macro must not be used in an interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue + * is empty. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to peek the data from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Peek a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask, but the item still remains on the queue.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceive(
+								 xQueueHandle xQueue,
+								 void *pvBuffer,
+								 portTickType xTicksToWait
+							);
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * Successfully received items are removed from the queue. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. xQueueReceive() will return immediately if xTicksToWait + * is zero and the queue is empty. The time is defined in tick periods so the + * constant portTICK_RATE_MS should be used to convert to real time if this is + * required. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericReceive(
+									   xQueueHandle	xQueue,
+									   void	*pvBuffer,
+									   portTickType	xTicksToWait
+									   portBASE_TYPE	xJustPeek
+									);
+ * + * It is preferred that the macro xQueueReceive() be used rather than calling + * this function directly. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueueGenericReceive() will return immediately if the queue is empty and + * xTicksToWait is 0. + * + * @param xJustPeek When set to true, the item received from the queue is not + * actually removed from the queue - meaning a subsequent call to + * xQueueReceive() will return the same item. When set to false, the item + * being received from the queue is also removed from the queue. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); + +/** + * queue. h + *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
+ * + * Return the number of messages stored in a queue. + * + * @param xQueue A handle to the queue being queried. + * + * @return The number of messages available in the queue. + * + * \page uxQueueMessagesWaiting uxQueueMessagesWaiting + * \ingroup QueueManagement + */ +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); + +/** + * queue. h + *
void vQueueDelete( xQueueHandle xQueue );
+ * + * Delete a queue - freeing all the memory allocated for storing of items + * placed on the queue. + * + * @param xQueue A handle to the queue to be deleted. + * + * \page vQueueDelete vQueueDelete + * \ingroup QueueManagement + */ +void vQueueDelete( xQueueHandle pxQueue ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToFrontFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the front of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPrioritTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBackFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the back of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendFromISR(
+									 xQueueHandle pxQueue,
+									 const void *pvItemToQueue,
+									 portBASE_TYPE *pxHigherPriorityTaskWoken
+								);
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). It is included + * for backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() + * macros. + * + * Post an item to the back of a queue. It is safe to use this function from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		// Actual macro used here is port specific.
+		taskYIELD_FROM_ISR ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSendFromISR(
+										   xQueueHandle	pxQueue,
+										   const	void	*pvItemToQueue,
+										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
+										   portBASE_TYPE	xCopyPosition
+									   );
+ 
+ * + * It is preferred that the macros xQueueSendFromISR(), + * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place + * of calling this function directly. + * + * Post an item on a queue. It is safe to use this function from within an + * interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWokenByPost;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWokenByPost = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post each byte.
+		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.  Note that the
+	// name of the yield function required is port specific.
+	if( xHigherPriorityTaskWokenByPost )
+	{
+		taskYIELD_YIELD_FROM_ISR();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceiveFromISR(
+									   xQueueHandle	pxQueue,
+									   void	*pvBuffer,
+									   portBASE_TYPE	*pxTaskWoken
+								   );
+ * 
+ * + * Receive an item from a queue. It is safe to use this function from within an + * interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param pxTaskWoken A task may be blocked waiting for space to become + * available on the queue. If xQueueReceiveFromISR causes such a task to + * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will + * remain unchanged. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+
+ xQueueHandle xQueue;
+
+ // Function to create a queue and post some values.
+ void vAFunction( void *pvParameters )
+ {
+ char cValueToPost;
+ const portTickType xBlockTime = ( portTickType )0xff;
+
+	// Create a queue capable of containing 10 characters.
+	xQueue = xQueueCreate( 10, sizeof( char ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Post some characters that will be used within an ISR.  If the queue
+	// is full then this task will block for xBlockTime ticks.
+	cValueToPost = 'a';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+	cValueToPost = 'b';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+
+	// ... keep posting characters ... this task may block when the queue
+	// becomes full.
+
+	cValueToPost = 'c';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+ }
+
+ // ISR that outputs all the characters received on the queue.
+ void vISR_Routine( void )
+ {
+ portBASE_TYPE xTaskWokenByReceive = pdFALSE;
+ char cRxedChar;
+
+	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
+	{
+		// A character was received.  Output the character now.
+		vOutputCharacter( cRxedChar );
+
+		// If removing the character from the queue woke the task that was
+		// posting onto the queue cTaskWokenByReceive will have been set to
+		// pdTRUE.  No matter how many times this loop iterates only one
+		// task will be woken.
+	}
+
+	if( cTaskWokenByPost != ( char ) pdFALSE;
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ); + +/* + * Utilities to query queue that are safe to use from an ISR. These utilities + * should be used only from witin an ISR, or within a critical section. + */ +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); + + +/* + * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). + * Likewise xQueueAltGenericReceive() is an alternative version of + * xQueueGenericReceive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); +#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) +#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) +#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) +#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) + +/* + * The functions defined above are for passing data to and from tasks. The + * functions below are the equivalents for passing data to and from + * co-routines. + * + * These functions are called from the co-routine macro implementation and + * should not be called directly from application code. Instead use the macro + * wrappers defined within croutine.h. + */ +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); + +/* + * For internal use only. Use xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting() instead of calling these functions directly. + */ +xQueueHandle xQueueCreateMutex( void ); +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); + +/* + * For internal use only. Use xSemaphoreTakeMutexRecursive() or + * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. + */ +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ); +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ); + +/* + * The registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add + * a queue, semaphore or mutex handle to the registry if you want the handle + * to be available to a kernel aware debugger. If you are not using a kernel + * aware debugger then this function can be ignored. + * + * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the + * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 + * within FreeRTOSConfig.h for the registry to be available. Its value + * does not effect the number of queues, semaphores and mutexes that can be + * created - just the number that the registry can hold. + * + * @param xQueue The handle of the queue being added to the registry. This + * is the handle returned by a call to xQueueCreate(). Semaphore and mutex + * handles can also be passed in here. + * + * @param pcName The name to be associated with the handle. This is the + * name that the kernel aware debugger will display. + */ +#if configQUEUE_REGISTRY_SIZE > 0U + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); +#endif + +/* Not a public API function, hence the 'Restricted' in the name. */ +void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ); + + +#ifdef __cplusplus +} +#endif + +#endif /* QUEUE_H */ + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/semphr.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/semphr.h index 0130f1d79..7a9e83fa9 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/semphr.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/semphr.h @@ -1,717 +1,717 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef SEMAPHORE_H -#define SEMAPHORE_H - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include semphr.h" -#endif - -#include "queue.h" - -typedef xQueueHandle xSemaphoreHandle; - -#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1U ) -#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0U ) -#define semGIVE_BLOCK_TIME ( ( portTickType ) 0U ) - - -/** - * semphr. h - *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
- * - * Macro that implements a semaphore by using the existing queue mechanism. - * The queue length is 1 as this is a binary semaphore. The data size is 0 - * as we don't want to actually store any data - we just want to know if the - * queue is empty or full. - * - * This type of semaphore can be used for pure synchronisation between tasks or - * between an interrupt and a task. The semaphore need not be given back once - * obtained, so one task/interrupt can continuously 'give' the semaphore while - * another continuously 'takes' the semaphore. For this reason this type of - * semaphore does not use a priority inheritance mechanism. For an alternative - * that does use priority inheritance see xSemaphoreCreateMutex(). - * - * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
-    // This is a macro so pass the variable in directly.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary - * \ingroup Semaphores - */ -#define vSemaphoreCreateBinary( xSemaphore ) { \ - ( xSemaphore ) = xQueueCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH ); \ - if( ( xSemaphore ) != NULL ) \ - { \ - xSemaphoreGive( ( xSemaphore ) ); \ - } \ - } - -/** - * semphr. h - *
xSemaphoreTake( 
- *                   xSemaphoreHandle xSemaphore, 
- *                   portTickType xBlockTime 
- *               )
- * - * Macro to obtain a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). - * - * @param xSemaphore A handle to the semaphore being taken - obtained when - * the semaphore was created. - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. A block - * time of portMAX_DELAY can be used to block indefinitely (provided - * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). - * - * @return pdTRUE if the semaphore was obtained. pdFALSE - * if xBlockTime expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- // A task that creates a semaphore.
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
- }
-
- // A task that uses the semaphore.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xSemaphore != NULL )
-    {
-        // See if we can obtain the semaphore.  If the semaphore is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the semaphore and can now access the
-            // shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource.  Release the 
-            // semaphore.
-            xSemaphoreGive( xSemaphore );
-        }
-        else
-        {
-            // We could not obtain the semaphore and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTake xSemaphoreTake - * \ingroup Semaphores - */ -#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) - -/** - * semphr. h - * xSemaphoreTakeRecursive( - * xSemaphoreHandle xMutex, - * portTickType xBlockTime - * ) - * - * Macro to recursively obtain, or 'take', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being obtained. This is the - * handle returned by xSemaphoreCreateRecursiveMutex(); - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. If - * the task already owns the semaphore then xSemaphoreTakeRecursive() will - * return immediately no matter what the value of xBlockTime. - * - * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime - * expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, but instead buried in a more complex
-			// call structure.  This is just for illustrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive - * \ingroup Semaphores - */ -#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) ) - - -/* - * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) - -/** - * semphr. h - *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). - * - * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for - * an alternative which can be used from an ISR. - * - * This macro must also not be used on semaphores created using - * xSemaphoreCreateRecursiveMutex(). - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. - * Semaphores are implemented using queues. An error can occur if there is - * no space on the queue to post a message - indicating that the - * semaphore was not first obtained correctly. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-        {
-            // We would expect this call to fail because we cannot give
-            // a semaphore without first "taking" it!
-        }
-
-        // Obtain the semaphore - don't block if the semaphore is not
-        // immediately available.
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
-        {
-            // We now have the semaphore and can access the shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource so can free the
-            // semaphore.
-            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-            {
-                // We would not expect this call to fail because we must have
-                // obtained the semaphore to get here.
-            }
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGive xSemaphoreGive - * \ingroup Semaphores - */ -#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
- * - * Macro to recursively release, or 'give', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being released, or 'given'. This is the - * handle returned by xSemaphoreCreateMutex(); - * - * @return pdTRUE if the semaphore was given. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, it would be more likely that the calls
-			// to xSemaphoreGiveRecursive() would be called as a call stack
-			// unwound.  This is just for demonstrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive - * \ingroup Semaphores - */ -#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) ) - -/* - * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
- xSemaphoreGiveFromISR( 
-                          xSemaphoreHandle xSemaphore, 
-                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
-                      )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). - * - * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) - * must not be used with this macro. - * - * This macro can be used from an ISR. - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. - * - * Example usage: -
- \#define LONG_TIME 0xffff
- \#define TICKS_TO_WAIT	10
- xSemaphoreHandle xSemaphore = NULL;
-
- // Repetitive task.
- void vATask( void * pvParameters )
- {
-    for( ;; )
-    {
-        // We want this task to run every 10 ticks of a timer.  The semaphore 
-        // was created before this task was started.
-
-        // Block waiting for the semaphore to become available.
-        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
-        {
-            // It is time to execute.
-
-            // ...
-
-            // We have finished our task.  Return to the top of the loop where
-            // we will block on the semaphore until it is time to execute 
-            // again.  Note when using the semaphore for synchronisation with an
-			// ISR in this manner there is no need to 'give' the semaphore back.
-        }
-    }
- }
-
- // Timer ISR
- void vTimerISR( void * pvParameters )
- {
- static unsigned char ucLocalTickCount = 0;
- static signed portBASE_TYPE xHigherPriorityTaskWoken;
-
-    // A timer tick has occurred.
-
-    // ... Do other time functions.
-
-    // Is it time for vATask () to run?
-	xHigherPriorityTaskWoken = pdFALSE;
-    ucLocalTickCount++;
-    if( ucLocalTickCount >= TICKS_TO_WAIT )
-    {
-        // Unblock the task by releasing the semaphore.
-        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
-
-        // Reset the count so we release the semaphore again in 10 ticks time.
-        ucLocalTickCount = 0;
-    }
-
-    if( xHigherPriorityTaskWoken != pdFALSE )
-    {
-        // We can force a context switch here.  Context switching from an
-        // ISR uses port specific syntax.  Check the demo task for your port
-        // to find the syntax required.
-    }
- }
- 
- * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR - * \ingroup Semaphores - */ -#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateMutex( void )
- * - * Macro that implements a mutex semaphore by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the xSemaphoreTake() - * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and - * xSemaphoreGiveRecursive() macros should not be used. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateMutex() xQueueCreateMutex() - - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
- * - * Macro that implements a recursive mutex by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the - * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The - * xSemaphoreTake() and xSemaphoreGive() macros should not be used. - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateRecursiveMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex() - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
- * - * Macro that creates a counting semaphore by using the existing - * queue mechanism. - * - * Counting semaphores are typically used for two things: - * - * 1) Counting events. - * - * In this usage scenario an event handler will 'give' a semaphore each time - * an event occurs (incrementing the semaphore count value), and a handler - * task will 'take' a semaphore each time it processes an event - * (decrementing the semaphore count value). The count value is therefore - * the difference between the number of events that have occurred and the - * number that have been processed. In this case it is desirable for the - * initial count value to be zero. - * - * 2) Resource management. - * - * In this usage scenario the count value indicates the number of resources - * available. To obtain control of a resource a task must first obtain a - * semaphore - decrementing the semaphore count value. When the count value - * reaches zero there are no free resources. When a task finishes with the - * resource it 'gives' the semaphore back - incrementing the semaphore count - * value. In this case it is desirable for the initial count value to be - * equal to the maximum count value, indicating that all resources are free. - * - * @param uxMaxCount The maximum count value that can be reached. When the - * semaphore reaches this value it can no longer be 'given'. - * - * @param uxInitialCount The count value assigned to the semaphore when it is - * created. - * - * @return Handle to the created semaphore. Null if the semaphore could not be - * created. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
- xSemaphoreHandle xSemaphore = NULL;
-
-    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
-    // The max value to which the semaphore can count should be 10, and the
-    // initial value assigned to the count should be 0.
-    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting - * \ingroup Semaphores - */ -#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) - - -#endif /* SEMAPHORE_H */ - - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef SEMAPHORE_H +#define SEMAPHORE_H + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include semphr.h" +#endif + +#include "queue.h" + +typedef xQueueHandle xSemaphoreHandle; + +#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1U ) +#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0U ) +#define semGIVE_BLOCK_TIME ( ( portTickType ) 0U ) + + +/** + * semphr. h + *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
+ * + * Macro that implements a semaphore by using the existing queue mechanism. + * The queue length is 1 as this is a binary semaphore. The data size is 0 + * as we don't want to actually store any data - we just want to know if the + * queue is empty or full. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
+    // This is a macro so pass the variable in directly.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary + * \ingroup Semaphores + */ +#define vSemaphoreCreateBinary( xSemaphore ) { \ + ( xSemaphore ) = xQueueCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH ); \ + if( ( xSemaphore ) != NULL ) \ + { \ + xSemaphoreGive( ( xSemaphore ) ); \ + } \ + } + +/** + * semphr. h + *
xSemaphoreTake( 
+ *                   xSemaphoreHandle xSemaphore, 
+ *                   portTickType xBlockTime 
+ *               )
+ * + * Macro to obtain a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). + * + * @param xSemaphore A handle to the semaphore being taken - obtained when + * the semaphore was created. + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. A block + * time of portMAX_DELAY can be used to block indefinitely (provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). + * + * @return pdTRUE if the semaphore was obtained. pdFALSE + * if xBlockTime expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // A task that creates a semaphore.
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+ }
+
+ // A task that uses the semaphore.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xSemaphore != NULL )
+    {
+        // See if we can obtain the semaphore.  If the semaphore is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the semaphore and can now access the
+            // shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource.  Release the 
+            // semaphore.
+            xSemaphoreGive( xSemaphore );
+        }
+        else
+        {
+            // We could not obtain the semaphore and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTake xSemaphoreTake + * \ingroup Semaphores + */ +#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) + +/** + * semphr. h + * xSemaphoreTakeRecursive( + * xSemaphoreHandle xMutex, + * portTickType xBlockTime + * ) + * + * Macro to recursively obtain, or 'take', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being obtained. This is the + * handle returned by xSemaphoreCreateRecursiveMutex(); + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. If + * the task already owns the semaphore then xSemaphoreTakeRecursive() will + * return immediately no matter what the value of xBlockTime. + * + * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime + * expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, but instead buried in a more complex
+			// call structure.  This is just for illustrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive + * \ingroup Semaphores + */ +#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) ) + + +/* + * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) + +/** + * semphr. h + *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). + * + * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for + * an alternative which can be used from an ISR. + * + * This macro must also not be used on semaphores created using + * xSemaphoreCreateRecursiveMutex(). + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. + * Semaphores are implemented using queues. An error can occur if there is + * no space on the queue to post a message - indicating that the + * semaphore was not first obtained correctly. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+        {
+            // We would expect this call to fail because we cannot give
+            // a semaphore without first "taking" it!
+        }
+
+        // Obtain the semaphore - don't block if the semaphore is not
+        // immediately available.
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
+        {
+            // We now have the semaphore and can access the shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource so can free the
+            // semaphore.
+            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+            {
+                // We would not expect this call to fail because we must have
+                // obtained the semaphore to get here.
+            }
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGive xSemaphoreGive + * \ingroup Semaphores + */ +#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
+ * + * Macro to recursively release, or 'give', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being released, or 'given'. This is the + * handle returned by xSemaphoreCreateMutex(); + * + * @return pdTRUE if the semaphore was given. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, it would be more likely that the calls
+			// to xSemaphoreGiveRecursive() would be called as a call stack
+			// unwound.  This is just for demonstrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive + * \ingroup Semaphores + */ +#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) ) + +/* + * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
+ xSemaphoreGiveFromISR( 
+                          xSemaphoreHandle xSemaphore, 
+                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR. + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. + * + * Example usage: +
+ \#define LONG_TIME 0xffff
+ \#define TICKS_TO_WAIT	10
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // Repetitive task.
+ void vATask( void * pvParameters )
+ {
+    for( ;; )
+    {
+        // We want this task to run every 10 ticks of a timer.  The semaphore 
+        // was created before this task was started.
+
+        // Block waiting for the semaphore to become available.
+        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
+        {
+            // It is time to execute.
+
+            // ...
+
+            // We have finished our task.  Return to the top of the loop where
+            // we will block on the semaphore until it is time to execute 
+            // again.  Note when using the semaphore for synchronisation with an
+			// ISR in this manner there is no need to 'give' the semaphore back.
+        }
+    }
+ }
+
+ // Timer ISR
+ void vTimerISR( void * pvParameters )
+ {
+ static unsigned char ucLocalTickCount = 0;
+ static signed portBASE_TYPE xHigherPriorityTaskWoken;
+
+    // A timer tick has occurred.
+
+    // ... Do other time functions.
+
+    // Is it time for vATask () to run?
+	xHigherPriorityTaskWoken = pdFALSE;
+    ucLocalTickCount++;
+    if( ucLocalTickCount >= TICKS_TO_WAIT )
+    {
+        // Unblock the task by releasing the semaphore.
+        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
+
+        // Reset the count so we release the semaphore again in 10 ticks time.
+        ucLocalTickCount = 0;
+    }
+
+    if( xHigherPriorityTaskWoken != pdFALSE )
+    {
+        // We can force a context switch here.  Context switching from an
+        // ISR uses port specific syntax.  Check the demo task for your port
+        // to find the syntax required.
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR + * \ingroup Semaphores + */ +#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateMutex( void )
+ * + * Macro that implements a mutex semaphore by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the xSemaphoreTake() + * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and + * xSemaphoreGiveRecursive() macros should not be used. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateMutex() xQueueCreateMutex() + + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
+ * + * Macro that implements a recursive mutex by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the + * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The + * xSemaphoreTake() and xSemaphoreGive() macros should not be used. + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateRecursiveMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex() + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
+ * + * Macro that creates a counting semaphore by using the existing + * queue mechanism. + * + * Counting semaphores are typically used for two things: + * + * 1) Counting events. + * + * In this usage scenario an event handler will 'give' a semaphore each time + * an event occurs (incrementing the semaphore count value), and a handler + * task will 'take' a semaphore each time it processes an event + * (decrementing the semaphore count value). The count value is therefore + * the difference between the number of events that have occurred and the + * number that have been processed. In this case it is desirable for the + * initial count value to be zero. + * + * 2) Resource management. + * + * In this usage scenario the count value indicates the number of resources + * available. To obtain control of a resource a task must first obtain a + * semaphore - decrementing the semaphore count value. When the count value + * reaches zero there are no free resources. When a task finishes with the + * resource it 'gives' the semaphore back - incrementing the semaphore count + * value. In this case it is desirable for the initial count value to be + * equal to the maximum count value, indicating that all resources are free. + * + * @param uxMaxCount The maximum count value that can be reached. When the + * semaphore reaches this value it can no longer be 'given'. + * + * @param uxInitialCount The count value assigned to the semaphore when it is + * created. + * + * @return Handle to the created semaphore. Null if the semaphore could not be + * created. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+ xSemaphoreHandle xSemaphore = NULL;
+
+    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
+    // The max value to which the semaphore can count should be 10, and the
+    // initial value assigned to the count should be 0.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting + * \ingroup Semaphores + */ +#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) + + +#endif /* SEMAPHORE_H */ + + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/task.h index 3ca305f75..1c441fc6c 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/task.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/task.h @@ -1,1322 +1,1322 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef TASK_H -#define TASK_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include task.h" -#endif - -#include "portable.h" -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * MACROS AND DEFINITIONS - *----------------------------------------------------------*/ - -#define tskKERNEL_VERSION_NUMBER "V7.0.1" - -/** - * task. h - * - * Type by which tasks are referenced. For example, a call to xTaskCreate - * returns (via a pointer parameter) an xTaskHandle variable that can then - * be used as a parameter to vTaskDelete to delete the task. - * - * \page xTaskHandle xTaskHandle - * \ingroup Tasks - */ -typedef void * xTaskHandle; - -/* - * Used internally only. - */ -typedef struct xTIME_OUT -{ - portBASE_TYPE xOverflowCount; - portTickType xTimeOnEntering; -} xTimeOutType; - -/* - * Defines the memory ranges allocated to the task when an MPU is used. - */ -typedef struct xMEMORY_REGION -{ - void *pvBaseAddress; - unsigned long ulLengthInBytes; - unsigned long ulParameters; -} xMemoryRegion; - -/* - * Parameters required to create an MPU protected task. - */ -typedef struct xTASK_PARAMTERS -{ - pdTASK_CODE pvTaskCode; - const signed char * const pcName; - unsigned short usStackDepth; - void *pvParameters; - unsigned portBASE_TYPE uxPriority; - portSTACK_TYPE *puxStackBuffer; - xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; -} xTaskParameters; - -/* - * Defines the priority used by the idle task. This must not be modified. - * - * \ingroup TaskUtils - */ -#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0U ) - -/** - * task. h - * - * Macro for forcing a context switch. - * - * \page taskYIELD taskYIELD - * \ingroup SchedulerControl - */ -#define taskYIELD() portYIELD() - -/** - * task. h - * - * Macro to mark the start of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskENTER_CRITICAL taskENTER_CRITICAL - * \ingroup SchedulerControl - */ -#define taskENTER_CRITICAL() portENTER_CRITICAL() - -/** - * task. h - * - * Macro to mark the end of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskEXIT_CRITICAL taskEXIT_CRITICAL - * \ingroup SchedulerControl - */ -#define taskEXIT_CRITICAL() portEXIT_CRITICAL() - -/** - * task. h - * - * Macro to disable all maskable interrupts. - * - * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() - -/** - * task. h - * - * Macro to enable microcontroller interrupts. - * - * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() - -/* Definitions returned by xTaskGetSchedulerState(). */ -#define taskSCHEDULER_NOT_STARTED 0 -#define taskSCHEDULER_RUNNING 1 -#define taskSCHEDULER_SUSPENDED 2 - -/*----------------------------------------------------------- - * TASK CREATION API - *----------------------------------------------------------*/ - -/** - * task. h - *
- portBASE_TYPE xTaskCreate(
-							  pdTASK_CODE pvTaskCode,
-							  const char * const pcName,
-							  unsigned short usStackDepth,
-							  void *pvParameters,
-							  unsigned portBASE_TYPE uxPriority,
-							  xTaskHandle *pvCreatedTask
-						  );
- * - * Create a new task and add it to the list of tasks that are ready to run. - * - * xTaskCreate() can only be used to create a task that has unrestricted - * access to the entire microcontroller memory map. Systems that include MPU - * support can alternatively create an MPU constrained task using - * xTaskCreateRestricted(). - * - * @param pvTaskCode Pointer to the task entry function. Tasks - * must be implemented to never return (i.e. continuous loop). - * - * @param pcName A descriptive name for the task. This is mainly used to - * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default - * is 16. - * - * @param usStackDepth The size of the task stack specified as the number of - * variables the stack can hold - not the number of bytes. For example, if - * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes - * will be allocated for stack storage. - * - * @param pvParameters Pointer that will be used as the parameter for the task - * being created. - * - * @param uxPriority The priority at which the task should run. Systems that - * include MPU support can optionally create tasks in a privileged (system) - * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For - * example, to create a privileged task at priority 2 the uxPriority parameter - * should be set to ( 2 | portPRIVILEGE_BIT ). - * - * @param pvCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
- // Task to be created.
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-	 }
- }
-
- // Function that creates a task.
- void vOtherFunction( void )
- {
- static unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
-	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
-	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
-	 // the new task attempts to access it.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup xTaskCreate xTaskCreate - * \ingroup Tasks - */ -#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) - -/** - * task. h - *
- portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
- * - * xTaskCreateRestricted() should only be used in systems that include an MPU - * implementation. - * - * Create a new task and add it to the list of tasks that are ready to run. - * The function parameters define the memory regions and associated access - * permissions allocated to the task. - * - * @param pxTaskDefinition Pointer to a structure that contains a member - * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API - * documentation) plus an optional stack buffer and the memory region - * definitions. - * - * @param pxCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
-// Create an xTaskParameters structure that defines the task to be created.
-static const xTaskParameters xCheckTaskParameters =
-{
-	vATask,		// pvTaskCode - the function that implements the task.
-	"ATask",	// pcName - just a text name for the task to assist debugging.
-	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
-	NULL,		// pvParameters - passed into the task function as the function parameters.
-	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
-	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
-
-	// xRegions - Allocate up to three separate memory regions for access by
-	// the task, with appropriate access permissions.  Different processors have
-	// different memory alignment requirements - refer to the FreeRTOS documentation
-	// for full information.
-	{											
-		// Base address					Length	Parameters
-        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
-        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
-        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
-	}
-};
-
-int main( void )
-{
-xTaskHandle xHandle;
-
-	// Create a task from the const structure defined above.  The task handle
-	// is requested (the second parameter is not NULL) but in this case just for
-	// demonstration purposes as its not actually used.
-	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
-
-	// Start the scheduler.
-	vTaskStartScheduler();
-
-	// Will only get here if there was insufficient memory to create the idle
-	// task.
-	for( ;; );
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) - -/** - * task. h - *
- void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
- * - * Memory regions are assigned to a restricted task when the task is created by - * a call to xTaskCreateRestricted(). These regions can be redefined using - * vTaskAllocateMPURegions(). - * - * @param xTask The handle of the task being updated. - * - * @param xRegions A pointer to an xMemoryRegion structure that contains the - * new memory region definitions. - * - * Example usage: -
-// Define an array of xMemoryRegion structures that configures an MPU region
-// allowing read/write access for 1024 bytes starting at the beginning of the
-// ucOneKByte array.  The other two of the maximum 3 definable regions are
-// unused so set to zero.
-static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
-{											
-	// Base address		Length		Parameters
-	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
-	{ 0,				0,			0 },
-	{ 0,				0,			0 }
-};
-
-void vATask( void *pvParameters )
-{
-	// This task was created such that it has access to certain regions of
-	// memory as defined by the MPU configuration.  At some point it is
-	// desired that these MPU regions are replaced with that defined in the
-	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
-	// for this purpose.  NULL is used as the task handle to indicate that this
-	// function should modify the MPU regions of the calling task.
-	vTaskAllocateMPURegions( NULL, xAltRegions );
-	
-	// Now the task can continue its function, but from this point on can only
-	// access its stack and the ucOneKByte array (unless any other statically
-	// defined or shared regions have been declared elsewhere).
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelete( xTaskHandle pxTask );
- * - * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Remove a task from the RTOS real time kernels management. The task being - * deleted will be removed from all ready, blocked, suspended and event lists. - * - * NOTE: The idle task is responsible for freeing the kernel allocated - * memory from tasks that have been deleted. It is therefore important that - * the idle task is not starved of microcontroller processing time if your - * application makes any calls to vTaskDelete (). Memory allocated by the - * task code is not automatically freed, and should be freed before the task - * is deleted. - * - * See the demo application file death.c for sample code that utilises - * vTaskDelete (). - * - * @param pxTask The handle of the task to be deleted. Passing NULL will - * cause the calling task to be deleted. - * - * Example usage: -
- void vOtherFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup vTaskDelete vTaskDelete - * \ingroup Tasks - */ -void vTaskDelete( xTaskHandle pxTaskToDelete ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * TASK CONTROL API - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskDelay( portTickType xTicksToDelay );
- * - * Delay a task for a given number of ticks. The actual time that the - * task remains blocked depends on the tick rate. The constant - * portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * - * vTaskDelay() specifies a time at which the task wishes to unblock relative to - * the time at which vTaskDelay() is called. For example, specifying a block - * period of 100 ticks will cause the task to unblock 100 ticks after - * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method - * of controlling the frequency of a cyclical task as the path taken through the - * code, as well as other task and interrupt activity, will effect the frequency - * at which vTaskDelay() gets called and therefore the time at which the task - * next executes. See vTaskDelayUntil() for an alternative API function designed - * to facilitate fixed frequency execution. It does this by specifying an - * absolute time (rather than a relative time) at which the calling task should - * unblock. - * - * @param xTicksToDelay The amount of time, in tick periods, that - * the calling task should block. - * - * Example usage: - - void vTaskFunction( void * pvParameters ) - { - void vTaskFunction( void * pvParameters ) - { - // Block for 500ms. - const portTickType xDelay = 500 / portTICK_RATE_MS; - - for( ;; ) - { - // Simply toggle the LED every 500ms, blocking between each toggle. - vToggleLED(); - vTaskDelay( xDelay ); - } - } - - * \defgroup vTaskDelay vTaskDelay - * \ingroup TaskCtrl - */ -void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
- * - * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Delay a task until a specified time. This function can be used by cyclical - * tasks to ensure a constant execution frequency. - * - * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will - * cause a task to block for the specified number of ticks from the time vTaskDelay () is - * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed - * execution frequency as the time between a task starting to execute and that task - * calling vTaskDelay () may not be fixed [the task may take a different path though the - * code between calls, or may get interrupted or preempted a different number of times - * each time it executes]. - * - * Whereas vTaskDelay () specifies a wake time relative to the time at which the function - * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to - * unblock. - * - * The constant portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the - * task was last unblocked. The variable must be initialised with the current time - * prior to its first use (see the example below). Following this the variable is - * automatically updated within vTaskDelayUntil (). - * - * @param xTimeIncrement The cycle time period. The task will be unblocked at - * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the - * same xTimeIncrement parameter value will cause the task to execute with - * a fixed interface period. - * - * Example usage: -
- // Perform an action every 10 ticks.
- void vTaskFunction( void * pvParameters )
- {
- portTickType xLastWakeTime;
- const portTickType xFrequency = 10;
-
-	 // Initialise the xLastWakeTime variable with the current time.
-	 xLastWakeTime = xTaskGetTickCount ();
-	 for( ;; )
-	 {
-		 // Wait for the next cycle.
-		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
-
-		 // Perform action here.
-	 }
- }
-   
- * \defgroup vTaskDelayUntil vTaskDelayUntil - * \ingroup TaskCtrl - */ -void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
- * - * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Obtain the priority of any task. - * - * @param pxTask Handle of the task to be queried. Passing a NULL - * handle results in the priority of the calling task being returned. - * - * @return The priority of pxTask. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to obtain the priority of the created task.
-	 // It was created with tskIDLE_PRIORITY, but may have changed
-	 // it itself.
-	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
-	 {
-		 // The task has changed it's priority.
-	 }
-
-	 // ...
-
-	 // Is our priority higher than the created task?
-	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
-	 {
-		 // Our priority (obtained using NULL handle) is higher.
-	 }
- }
-   
- * \defgroup uxTaskPriorityGet uxTaskPriorityGet - * \ingroup TaskCtrl - */ -unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
- * - * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Set the priority of any task. - * - * A context switch will occur before the function returns if the priority - * being set is higher than the currently executing task. - * - * @param pxTask Handle to the task for which the priority is being set. - * Passing a NULL handle results in the priority of the calling task being set. - * - * @param uxNewPriority The priority to which the task will be set. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to raise the priority of the created task.
-	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
-
-	 // ...
-
-	 // Use a NULL handle to raise our priority to the same value.
-	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
- }
-   
- * \defgroup vTaskPrioritySet vTaskPrioritySet - * \ingroup TaskCtrl - */ -void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Suspend any task. When suspended a task will never get any microcontroller - * processing time, no matter what its priority. - * - * Calls to vTaskSuspend are not accumulative - - * i.e. calling vTaskSuspend () twice on the same task still only requires one - * call to vTaskResume () to ready the suspended task. - * - * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL - * handle will cause the calling task to be suspended. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Suspend ourselves.
-	 vTaskSuspend( NULL );
-
-	 // We cannot get here unless another task calls vTaskResume
-	 // with our handle as the parameter.
- }
-   
- * \defgroup vTaskSuspend vTaskSuspend - * \ingroup TaskCtrl - */ -void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskResume( xTaskHandle pxTaskToResume );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Resumes a suspended task. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * vTaskResume (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Resume the suspended task ourselves.
-	 vTaskResume( xHandle );
-
-	 // The created task will once again get microcontroller processing
-	 // time in accordance with it priority within the system.
- }
-   
- * \defgroup vTaskResume vTaskResume - * \ingroup TaskCtrl - */ -void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
- * - * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * An implementation of vTaskResume() that can be called from within an ISR. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * xTaskResumeFromISR (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * \defgroup vTaskResumeFromISR vTaskResumeFromISR - * \ingroup TaskCtrl - */ -portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * SCHEDULER CONTROL - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskStartScheduler( void );
- * - * Starts the real time kernel tick processing. After calling the kernel - * has control over which tasks are executed and when. This function - * does not return until an executing task calls vTaskEndScheduler (). - * - * At least one task should be created via a call to xTaskCreate () - * before calling vTaskStartScheduler (). The idle task is created - * automatically when the first application task is created. - * - * See the demo application file main.c for an example of creating - * tasks and starting the kernel. - * - * Example usage: -
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will not get here unless a task calls vTaskEndScheduler ()
- }
-   
- * - * \defgroup vTaskStartScheduler vTaskStartScheduler - * \ingroup SchedulerControl - */ -void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskEndScheduler( void );
- * - * Stops the real time kernel tick. All created tasks will be automatically - * deleted and multitasking (either preemptive or cooperative) will - * stop. Execution then resumes from the point where vTaskStartScheduler () - * was called, as if vTaskStartScheduler () had just returned. - * - * See the demo application file main. c in the demo/PC directory for an - * example that uses vTaskEndScheduler (). - * - * vTaskEndScheduler () requires an exit function to be defined within the - * portable layer (see vPortEndScheduler () in port. c for the PC port). This - * performs hardware specific operations such as stopping the kernel tick. - * - * vTaskEndScheduler () will cause all of the resources allocated by the - * kernel to be freed - but will not free resources allocated by application - * tasks. - * - * Example usage: -
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // At some point we want to end the real time kernel processing
-		 // so call ...
-		 vTaskEndScheduler ();
-	 }
- }
-
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will only get here when the vTaskCode () task has called
-	 // vTaskEndScheduler ().  When we get here we are back to single task
-	 // execution.
- }
-   
- * - * \defgroup vTaskEndScheduler vTaskEndScheduler - * \ingroup SchedulerControl - */ -void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspendAll( void );
- * - * Suspends all real time kernel activity while keeping interrupts (including the - * kernel tick) enabled. - * - * After calling vTaskSuspendAll () the calling task will continue to execute - * without risk of being swapped out until a call to xTaskResumeAll () has been - * made. - * - * API functions that have the potential to cause a context switch (for example, - * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler - * is suspended. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the kernel
-		 // tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.
-		 xTaskResumeAll ();
-	 }
- }
-   
- * \defgroup vTaskSuspendAll vTaskSuspendAll - * \ingroup SchedulerControl - */ -void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
char xTaskResumeAll( void );
- * - * Resumes real time kernel activity following a call to vTaskSuspendAll (). - * After a call to vTaskSuspendAll () the kernel will take control of which - * task is executing at any time. - * - * @return If resuming the scheduler caused a context switch then pdTRUE is - * returned, otherwise pdFALSE is returned. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the real
-		 // time kernel tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.  We want to force
-		 // a context switch - but there is no point if resuming the scheduler
-		 // caused a context switch already.
-		 if( !xTaskResumeAll () )
-		 {
-			  taskYIELD ();
-		 }
-	 }
- }
-   
- * \defgroup xTaskResumeAll xTaskResumeAll - * \ingroup SchedulerControl - */ -signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
- * - * Utility task that simply returns pdTRUE if the task referenced by xTask is - * currently in the Suspended state, or pdFALSE if the task referenced by xTask - * is in any other state. - * - */ -signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * TASK UTILITIES - *----------------------------------------------------------*/ - -/** - * task. h - *
portTickType xTaskGetTickCount( void );
- * - * @return The count of ticks since vTaskStartScheduler was called. - * - * \page xTaskGetTickCount xTaskGetTickCount - * \ingroup TaskUtils - */ -portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
portTickType xTaskGetTickCountFromISR( void );
- * - * @return The count of ticks since vTaskStartScheduler was called. - * - * This is a version of xTaskGetTickCount() that is safe to be called from an - * ISR - provided that portTickType is the natural word size of the - * microcontroller being used or interrupt nesting is either not supported or - * not being used. - * - * \page xTaskGetTickCount xTaskGetTickCount - * \ingroup TaskUtils - */ -portTickType xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned short uxTaskGetNumberOfTasks( void );
- * - * @return The number of tasks that the real time kernel is currently managing. - * This includes all ready, blocked and suspended tasks. A task that - * has been deleted but not yet freed by the idle task will also be - * included in the count. - * - * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks - * \ingroup TaskUtils - */ -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskList( char *pcWriteBuffer );
- * - * configUSE_TRACE_FACILITY must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Lists all the current tasks, along with their current state and stack - * usage high water mark. - * - * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or - * suspended ('S'). - * - * @param pcWriteBuffer A buffer into which the above mentioned details - * will be written, in ascii form. This buffer is assumed to be large - * enough to contain the generated report. Approximately 40 bytes per - * task should be sufficient. - * - * \page vTaskList vTaskList - * \ingroup TaskUtils - */ -void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
- * - * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function - * to be available. The application must also then provide definitions - * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and - * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter - * and return the timers current count value respectively. The counter - * should be at least 10 times the frequency of the tick count. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total - * accumulated execution time being stored for each task. The resolution - * of the accumulated time value depends on the frequency of the timer - * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. - * Calling vTaskGetRunTimeStats() writes the total execution time of each - * task into a buffer, both as an absolute count value and as a percentage - * of the total system execution time. - * - * @param pcWriteBuffer A buffer into which the execution times will be - * written, in ascii form. This buffer is assumed to be large enough to - * contain the generated report. Approximately 40 bytes per task should - * be sufficient. - * - * \page vTaskGetRunTimeStats vTaskGetRunTimeStats - * \ingroup TaskUtils - */ -void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskStartTrace( char * pcBuffer, unsigned portBASE_TYPE uxBufferSize );
- * - * Starts a real time kernel activity trace. The trace logs the identity of - * which task is running when. - * - * The trace file is stored in binary format. A separate DOS utility called - * convtrce.exe is used to convert this into a tab delimited text file which - * can be viewed and plotted in a spread sheet. - * - * @param pcBuffer The buffer into which the trace will be written. - * - * @param ulBufferSize The size of pcBuffer in bytes. The trace will continue - * until either the buffer in full, or ulTaskEndTrace () is called. - * - * \page vTaskStartTrace vTaskStartTrace - * \ingroup TaskUtils - */ -void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned long ulTaskEndTrace( void );
- * - * Stops a kernel activity trace. See vTaskStartTrace (). - * - * @return The number of bytes that have been written into the trace buffer. - * - * \page usTaskEndTrace usTaskEndTrace - * \ingroup TaskUtils - */ -unsigned long ulTaskEndTrace( void ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
- * - * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for - * this function to be available. - * - * Returns the high water mark of the stack associated with xTask. That is, - * the minimum free stack space there has been (in words, so on a 32 bit machine - * a value of 1 means 4 bytes) since the task started. The smaller the returned - * number the closer the task has come to overflowing its stack. - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The smallest amount of free stack space there has been (in bytes) - * since the task referenced by xTask was created. - */ -unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask );
- * - * Returns the run time of selected task - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The run time of selected task - */ -unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ); - -/* When using trace macros it is sometimes necessary to include tasks.h before -FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, -so the following two prototypes will cause a compilation error. This can be -fixed by simply guarding against the inclusion of these two prototypes unless -they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration -constant. */ -#ifdef configUSE_APPLICATION_TASK_TAG - #if configUSE_APPLICATION_TASK_TAG == 1 - /** - * task.h - *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Sets pxHookFunction to be the task hook function used by the task xTask. - * Passing xTask as NULL has the effect of setting the calling tasks hook - * function. - */ - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; - - /** - * task.h - *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
- * - * Returns the pxHookFunction value assigned to the task xTask. - */ - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - #endif /* configUSE_APPLICATION_TASK_TAG ==1 */ -#endif /* ifdef configUSE_APPLICATION_TASK_TAG */ - -/** - * task.h - *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Calls the hook function associated with xTask. Passing xTask as NULL has - * the effect of calling the Running tasks (the calling task) hook function. - * - * pvParameter is passed to the hook function for the task to interpret as it - * wants. - */ -portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; - - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - *----------------------------------------------------------*/ - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Called from the real time kernel tick (either preemptive or cooperative), - * this increments the tick count and checks if any tasks that are blocked - * for a finite period required removing from a blocked list and placing on - * a ready list. - */ -void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes the calling task from the ready list and places it both - * on the list of tasks waiting for a particular event, and the - * list of delayed tasks. The task will be removed from both lists - * and replaced on the ready list should either the event occur (and - * there be no higher priority tasks waiting on the same event) or - * the delay period expires. - * - * @param pxEventList The list containing tasks that are blocked waiting - * for the event to occur. - * - * @param xTicksToWait The maximum amount of time that the task should wait - * for the event to occur. This is specified in kernel ticks,the constant - * portTICK_RATE_MS can be used to convert kernel ticks into a real time - * period. - */ -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * This function performs nearly the same function as vTaskPlaceOnEventList(). - * The difference being that this function does not permit tasks to block - * indefinitely, whereas vTaskPlaceOnEventList() does. - * - * @return pdTRUE if the task being removed has a higher priority than the task - * making the call, otherwise pdFALSE. - */ -void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes a task from both the specified event list and the list of blocked - * tasks, and places it on a ready queue. - * - * xTaskRemoveFromEventList () will be called if either an event occurs to - * unblock a task, or the block timeout period expires. - * - * @return pdTRUE if the task being removed has a higher priority than the task - * making the call, otherwise pdFALSE. - */ -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * INCLUDE_vTaskCleanUpResources and INCLUDE_vTaskSuspend must be defined as 1 - * for this function to be available. - * See the configuration section for more information. - * - * Empties the ready and delayed queues of task control blocks, freeing the - * memory allocated for the task control block and task stacks as it goes. - */ -void vTaskCleanUpResources( void ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Sets the pointer to the current TCB to the TCB of the highest priority task - * that is ready to run. - */ -void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; - -/* - * Return the handle of the calling task. - */ -xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; - -/* - * Capture the current time status for future reference. - */ -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; - -/* - * Compare the time status now with that previously captured to see if the - * timeout has expired. - */ -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * Shortcut used by the queue implementation to prevent unnecessary call to - * taskYIELD(); - */ -void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; - -/* - * Returns the scheduler state as taskSCHEDULER_RUNNING, - * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. - */ -portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; - -/* - * Raises the priority of the mutex holder to that of the calling task should - * the mutex holder have a priority less than the calling task. - */ -void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Set the priority of a task back to its proper priority in the case that it - * inherited a higher priority while it was holding a semaphore. - */ -void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Generic version of the task creation function which is in turn called by the - * xTaskCreate() and xTaskCreateRestricted() macros. - */ -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; - -void printTasks(); - -#ifdef __cplusplus -} -#endif -#endif /* TASK_H */ - - - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef TASK_H +#define TASK_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include task.h" +#endif + +#include "portable.h" +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + +#define tskKERNEL_VERSION_NUMBER "V7.0.1" + +/** + * task. h + * + * Type by which tasks are referenced. For example, a call to xTaskCreate + * returns (via a pointer parameter) an xTaskHandle variable that can then + * be used as a parameter to vTaskDelete to delete the task. + * + * \page xTaskHandle xTaskHandle + * \ingroup Tasks + */ +typedef void * xTaskHandle; + +/* + * Used internally only. + */ +typedef struct xTIME_OUT +{ + portBASE_TYPE xOverflowCount; + portTickType xTimeOnEntering; +} xTimeOutType; + +/* + * Defines the memory ranges allocated to the task when an MPU is used. + */ +typedef struct xMEMORY_REGION +{ + void *pvBaseAddress; + unsigned long ulLengthInBytes; + unsigned long ulParameters; +} xMemoryRegion; + +/* + * Parameters required to create an MPU protected task. + */ +typedef struct xTASK_PARAMTERS +{ + pdTASK_CODE pvTaskCode; + const signed char * const pcName; + unsigned short usStackDepth; + void *pvParameters; + unsigned portBASE_TYPE uxPriority; + portSTACK_TYPE *puxStackBuffer; + xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; +} xTaskParameters; + +/* + * Defines the priority used by the idle task. This must not be modified. + * + * \ingroup TaskUtils + */ +#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0U ) + +/** + * task. h + * + * Macro for forcing a context switch. + * + * \page taskYIELD taskYIELD + * \ingroup SchedulerControl + */ +#define taskYIELD() portYIELD() + +/** + * task. h + * + * Macro to mark the start of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskENTER_CRITICAL taskENTER_CRITICAL + * \ingroup SchedulerControl + */ +#define taskENTER_CRITICAL() portENTER_CRITICAL() + +/** + * task. h + * + * Macro to mark the end of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskEXIT_CRITICAL taskEXIT_CRITICAL + * \ingroup SchedulerControl + */ +#define taskEXIT_CRITICAL() portEXIT_CRITICAL() + +/** + * task. h + * + * Macro to disable all maskable interrupts. + * + * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() + +/** + * task. h + * + * Macro to enable microcontroller interrupts. + * + * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() + +/* Definitions returned by xTaskGetSchedulerState(). */ +#define taskSCHEDULER_NOT_STARTED 0 +#define taskSCHEDULER_RUNNING 1 +#define taskSCHEDULER_SUSPENDED 2 + +/*----------------------------------------------------------- + * TASK CREATION API + *----------------------------------------------------------*/ + +/** + * task. h + *
+ portBASE_TYPE xTaskCreate(
+							  pdTASK_CODE pvTaskCode,
+							  const char * const pcName,
+							  unsigned short usStackDepth,
+							  void *pvParameters,
+							  unsigned portBASE_TYPE uxPriority,
+							  xTaskHandle *pvCreatedTask
+						  );
+ * + * Create a new task and add it to the list of tasks that are ready to run. + * + * xTaskCreate() can only be used to create a task that has unrestricted + * access to the entire microcontroller memory map. Systems that include MPU + * support can alternatively create an MPU constrained task using + * xTaskCreateRestricted(). + * + * @param pvTaskCode Pointer to the task entry function. Tasks + * must be implemented to never return (i.e. continuous loop). + * + * @param pcName A descriptive name for the task. This is mainly used to + * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default + * is 16. + * + * @param usStackDepth The size of the task stack specified as the number of + * variables the stack can hold - not the number of bytes. For example, if + * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes + * will be allocated for stack storage. + * + * @param pvParameters Pointer that will be used as the parameter for the task + * being created. + * + * @param uxPriority The priority at which the task should run. Systems that + * include MPU support can optionally create tasks in a privileged (system) + * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For + * example, to create a privileged task at priority 2 the uxPriority parameter + * should be set to ( 2 | portPRIVILEGE_BIT ). + * + * @param pvCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+ // Task to be created.
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+	 }
+ }
+
+ // Function that creates a task.
+ void vOtherFunction( void )
+ {
+ static unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
+	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
+	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
+	 // the new task attempts to access it.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup xTaskCreate xTaskCreate + * \ingroup Tasks + */ +#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) + +/** + * task. h + *
+ portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
+ * + * xTaskCreateRestricted() should only be used in systems that include an MPU + * implementation. + * + * Create a new task and add it to the list of tasks that are ready to run. + * The function parameters define the memory regions and associated access + * permissions allocated to the task. + * + * @param pxTaskDefinition Pointer to a structure that contains a member + * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API + * documentation) plus an optional stack buffer and the memory region + * definitions. + * + * @param pxCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+// Create an xTaskParameters structure that defines the task to be created.
+static const xTaskParameters xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{											
+		// Base address					Length	Parameters
+        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+};
+
+int main( void )
+{
+xTaskHandle xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// task.
+	for( ;; );
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) + +/** + * task. h + *
+ void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
+ * + * Memory regions are assigned to a restricted task when the task is created by + * a call to xTaskCreateRestricted(). These regions can be redefined using + * vTaskAllocateMPURegions(). + * + * @param xTask The handle of the task being updated. + * + * @param xRegions A pointer to an xMemoryRegion structure that contains the + * new memory region definitions. + * + * Example usage: +
+// Define an array of xMemoryRegion structures that configures an MPU region
+// allowing read/write access for 1024 bytes starting at the beginning of the
+// ucOneKByte array.  The other two of the maximum 3 definable regions are
+// unused so set to zero.
+static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
+{											
+	// Base address		Length		Parameters
+	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
+	{ 0,				0,			0 },
+	{ 0,				0,			0 }
+};
+
+void vATask( void *pvParameters )
+{
+	// This task was created such that it has access to certain regions of
+	// memory as defined by the MPU configuration.  At some point it is
+	// desired that these MPU regions are replaced with that defined in the
+	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
+	// for this purpose.  NULL is used as the task handle to indicate that this
+	// function should modify the MPU regions of the calling task.
+	vTaskAllocateMPURegions( NULL, xAltRegions );
+	
+	// Now the task can continue its function, but from this point on can only
+	// access its stack and the ucOneKByte array (unless any other statically
+	// defined or shared regions have been declared elsewhere).
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelete( xTaskHandle pxTask );
+ * + * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Remove a task from the RTOS real time kernels management. The task being + * deleted will be removed from all ready, blocked, suspended and event lists. + * + * NOTE: The idle task is responsible for freeing the kernel allocated + * memory from tasks that have been deleted. It is therefore important that + * the idle task is not starved of microcontroller processing time if your + * application makes any calls to vTaskDelete (). Memory allocated by the + * task code is not automatically freed, and should be freed before the task + * is deleted. + * + * See the demo application file death.c for sample code that utilises + * vTaskDelete (). + * + * @param pxTask The handle of the task to be deleted. Passing NULL will + * cause the calling task to be deleted. + * + * Example usage: +
+ void vOtherFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup vTaskDelete vTaskDelete + * \ingroup Tasks + */ +void vTaskDelete( xTaskHandle pxTaskToDelete ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK CONTROL API + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskDelay( portTickType xTicksToDelay );
+ * + * Delay a task for a given number of ticks. The actual time that the + * task remains blocked depends on the tick rate. The constant + * portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * + * vTaskDelay() specifies a time at which the task wishes to unblock relative to + * the time at which vTaskDelay() is called. For example, specifying a block + * period of 100 ticks will cause the task to unblock 100 ticks after + * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method + * of controlling the frequency of a cyclical task as the path taken through the + * code, as well as other task and interrupt activity, will effect the frequency + * at which vTaskDelay() gets called and therefore the time at which the task + * next executes. See vTaskDelayUntil() for an alternative API function designed + * to facilitate fixed frequency execution. It does this by specifying an + * absolute time (rather than a relative time) at which the calling task should + * unblock. + * + * @param xTicksToDelay The amount of time, in tick periods, that + * the calling task should block. + * + * Example usage: + + void vTaskFunction( void * pvParameters ) + { + void vTaskFunction( void * pvParameters ) + { + // Block for 500ms. + const portTickType xDelay = 500 / portTICK_RATE_MS; + + for( ;; ) + { + // Simply toggle the LED every 500ms, blocking between each toggle. + vToggleLED(); + vTaskDelay( xDelay ); + } + } + + * \defgroup vTaskDelay vTaskDelay + * \ingroup TaskCtrl + */ +void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
+ * + * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Delay a task until a specified time. This function can be used by cyclical + * tasks to ensure a constant execution frequency. + * + * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will + * cause a task to block for the specified number of ticks from the time vTaskDelay () is + * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed + * execution frequency as the time between a task starting to execute and that task + * calling vTaskDelay () may not be fixed [the task may take a different path though the + * code between calls, or may get interrupted or preempted a different number of times + * each time it executes]. + * + * Whereas vTaskDelay () specifies a wake time relative to the time at which the function + * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to + * unblock. + * + * The constant portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the + * task was last unblocked. The variable must be initialised with the current time + * prior to its first use (see the example below). Following this the variable is + * automatically updated within vTaskDelayUntil (). + * + * @param xTimeIncrement The cycle time period. The task will be unblocked at + * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the + * same xTimeIncrement parameter value will cause the task to execute with + * a fixed interface period. + * + * Example usage: +
+ // Perform an action every 10 ticks.
+ void vTaskFunction( void * pvParameters )
+ {
+ portTickType xLastWakeTime;
+ const portTickType xFrequency = 10;
+
+	 // Initialise the xLastWakeTime variable with the current time.
+	 xLastWakeTime = xTaskGetTickCount ();
+	 for( ;; )
+	 {
+		 // Wait for the next cycle.
+		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
+
+		 // Perform action here.
+	 }
+ }
+   
+ * \defgroup vTaskDelayUntil vTaskDelayUntil + * \ingroup TaskCtrl + */ +void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
+ * + * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Obtain the priority of any task. + * + * @param pxTask Handle of the task to be queried. Passing a NULL + * handle results in the priority of the calling task being returned. + * + * @return The priority of pxTask. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to obtain the priority of the created task.
+	 // It was created with tskIDLE_PRIORITY, but may have changed
+	 // it itself.
+	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
+	 {
+		 // The task has changed it's priority.
+	 }
+
+	 // ...
+
+	 // Is our priority higher than the created task?
+	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
+	 {
+		 // Our priority (obtained using NULL handle) is higher.
+	 }
+ }
+   
+ * \defgroup uxTaskPriorityGet uxTaskPriorityGet + * \ingroup TaskCtrl + */ +unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
+ * + * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Set the priority of any task. + * + * A context switch will occur before the function returns if the priority + * being set is higher than the currently executing task. + * + * @param pxTask Handle to the task for which the priority is being set. + * Passing a NULL handle results in the priority of the calling task being set. + * + * @param uxNewPriority The priority to which the task will be set. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to raise the priority of the created task.
+	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
+
+	 // ...
+
+	 // Use a NULL handle to raise our priority to the same value.
+	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
+ }
+   
+ * \defgroup vTaskPrioritySet vTaskPrioritySet + * \ingroup TaskCtrl + */ +void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Suspend any task. When suspended a task will never get any microcontroller + * processing time, no matter what its priority. + * + * Calls to vTaskSuspend are not accumulative - + * i.e. calling vTaskSuspend () twice on the same task still only requires one + * call to vTaskResume () to ready the suspended task. + * + * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL + * handle will cause the calling task to be suspended. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Suspend ourselves.
+	 vTaskSuspend( NULL );
+
+	 // We cannot get here unless another task calls vTaskResume
+	 // with our handle as the parameter.
+ }
+   
+ * \defgroup vTaskSuspend vTaskSuspend + * \ingroup TaskCtrl + */ +void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskResume( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Resumes a suspended task. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * vTaskResume (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Resume the suspended task ourselves.
+	 vTaskResume( xHandle );
+
+	 // The created task will once again get microcontroller processing
+	 // time in accordance with it priority within the system.
+ }
+   
+ * \defgroup vTaskResume vTaskResume + * \ingroup TaskCtrl + */ +void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * An implementation of vTaskResume() that can be called from within an ISR. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * xTaskResumeFromISR (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * \defgroup vTaskResumeFromISR vTaskResumeFromISR + * \ingroup TaskCtrl + */ +portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * SCHEDULER CONTROL + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskStartScheduler( void );
+ * + * Starts the real time kernel tick processing. After calling the kernel + * has control over which tasks are executed and when. This function + * does not return until an executing task calls vTaskEndScheduler (). + * + * At least one task should be created via a call to xTaskCreate () + * before calling vTaskStartScheduler (). The idle task is created + * automatically when the first application task is created. + * + * See the demo application file main.c for an example of creating + * tasks and starting the kernel. + * + * Example usage: +
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will not get here unless a task calls vTaskEndScheduler ()
+ }
+   
+ * + * \defgroup vTaskStartScheduler vTaskStartScheduler + * \ingroup SchedulerControl + */ +void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskEndScheduler( void );
+ * + * Stops the real time kernel tick. All created tasks will be automatically + * deleted and multitasking (either preemptive or cooperative) will + * stop. Execution then resumes from the point where vTaskStartScheduler () + * was called, as if vTaskStartScheduler () had just returned. + * + * See the demo application file main. c in the demo/PC directory for an + * example that uses vTaskEndScheduler (). + * + * vTaskEndScheduler () requires an exit function to be defined within the + * portable layer (see vPortEndScheduler () in port. c for the PC port). This + * performs hardware specific operations such as stopping the kernel tick. + * + * vTaskEndScheduler () will cause all of the resources allocated by the + * kernel to be freed - but will not free resources allocated by application + * tasks. + * + * Example usage: +
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // At some point we want to end the real time kernel processing
+		 // so call ...
+		 vTaskEndScheduler ();
+	 }
+ }
+
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will only get here when the vTaskCode () task has called
+	 // vTaskEndScheduler ().  When we get here we are back to single task
+	 // execution.
+ }
+   
+ * + * \defgroup vTaskEndScheduler vTaskEndScheduler + * \ingroup SchedulerControl + */ +void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspendAll( void );
+ * + * Suspends all real time kernel activity while keeping interrupts (including the + * kernel tick) enabled. + * + * After calling vTaskSuspendAll () the calling task will continue to execute + * without risk of being swapped out until a call to xTaskResumeAll () has been + * made. + * + * API functions that have the potential to cause a context switch (for example, + * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler + * is suspended. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the kernel
+		 // tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.
+		 xTaskResumeAll ();
+	 }
+ }
+   
+ * \defgroup vTaskSuspendAll vTaskSuspendAll + * \ingroup SchedulerControl + */ +void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
char xTaskResumeAll( void );
+ * + * Resumes real time kernel activity following a call to vTaskSuspendAll (). + * After a call to vTaskSuspendAll () the kernel will take control of which + * task is executing at any time. + * + * @return If resuming the scheduler caused a context switch then pdTRUE is + * returned, otherwise pdFALSE is returned. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the real
+		 // time kernel tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.  We want to force
+		 // a context switch - but there is no point if resuming the scheduler
+		 // caused a context switch already.
+		 if( !xTaskResumeAll () )
+		 {
+			  taskYIELD ();
+		 }
+	 }
+ }
+   
+ * \defgroup xTaskResumeAll xTaskResumeAll + * \ingroup SchedulerControl + */ +signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
+ * + * Utility task that simply returns pdTRUE if the task referenced by xTask is + * currently in the Suspended state, or pdFALSE if the task referenced by xTask + * is in any other state. + * + */ +signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK UTILITIES + *----------------------------------------------------------*/ + +/** + * task. h + *
portTickType xTaskGetTickCount( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * \page xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
portTickType xTaskGetTickCountFromISR( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * This is a version of xTaskGetTickCount() that is safe to be called from an + * ISR - provided that portTickType is the natural word size of the + * microcontroller being used or interrupt nesting is either not supported or + * not being used. + * + * \page xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +portTickType xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned short uxTaskGetNumberOfTasks( void );
+ * + * @return The number of tasks that the real time kernel is currently managing. + * This includes all ready, blocked and suspended tasks. A task that + * has been deleted but not yet freed by the idle task will also be + * included in the count. + * + * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks + * \ingroup TaskUtils + */ +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskList( char *pcWriteBuffer );
+ * + * configUSE_TRACE_FACILITY must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Lists all the current tasks, along with their current state and stack + * usage high water mark. + * + * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or + * suspended ('S'). + * + * @param pcWriteBuffer A buffer into which the above mentioned details + * will be written, in ascii form. This buffer is assumed to be large + * enough to contain the generated report. Approximately 40 bytes per + * task should be sufficient. + * + * \page vTaskList vTaskList + * \ingroup TaskUtils + */ +void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
+ * + * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function + * to be available. The application must also then provide definitions + * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and + * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter + * and return the timers current count value respectively. The counter + * should be at least 10 times the frequency of the tick count. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total + * accumulated execution time being stored for each task. The resolution + * of the accumulated time value depends on the frequency of the timer + * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. + * Calling vTaskGetRunTimeStats() writes the total execution time of each + * task into a buffer, both as an absolute count value and as a percentage + * of the total system execution time. + * + * @param pcWriteBuffer A buffer into which the execution times will be + * written, in ascii form. This buffer is assumed to be large enough to + * contain the generated report. Approximately 40 bytes per task should + * be sufficient. + * + * \page vTaskGetRunTimeStats vTaskGetRunTimeStats + * \ingroup TaskUtils + */ +void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskStartTrace( char * pcBuffer, unsigned portBASE_TYPE uxBufferSize );
+ * + * Starts a real time kernel activity trace. The trace logs the identity of + * which task is running when. + * + * The trace file is stored in binary format. A separate DOS utility called + * convtrce.exe is used to convert this into a tab delimited text file which + * can be viewed and plotted in a spread sheet. + * + * @param pcBuffer The buffer into which the trace will be written. + * + * @param ulBufferSize The size of pcBuffer in bytes. The trace will continue + * until either the buffer in full, or ulTaskEndTrace () is called. + * + * \page vTaskStartTrace vTaskStartTrace + * \ingroup TaskUtils + */ +void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned long ulTaskEndTrace( void );
+ * + * Stops a kernel activity trace. See vTaskStartTrace (). + * + * @return The number of bytes that have been written into the trace buffer. + * + * \page usTaskEndTrace usTaskEndTrace + * \ingroup TaskUtils + */ +unsigned long ulTaskEndTrace( void ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
+ * + * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for + * this function to be available. + * + * Returns the high water mark of the stack associated with xTask. That is, + * the minimum free stack space there has been (in words, so on a 32 bit machine + * a value of 1 means 4 bytes) since the task started. The smaller the returned + * number the closer the task has come to overflowing its stack. + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The smallest amount of free stack space there has been (in bytes) + * since the task referenced by xTask was created. + */ +unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask );
+ * + * Returns the run time of selected task + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The run time of selected task + */ +unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ); + +/* When using trace macros it is sometimes necessary to include tasks.h before +FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, +so the following two prototypes will cause a compilation error. This can be +fixed by simply guarding against the inclusion of these two prototypes unless +they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration +constant. */ +#ifdef configUSE_APPLICATION_TASK_TAG + #if configUSE_APPLICATION_TASK_TAG == 1 + /** + * task.h + *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Sets pxHookFunction to be the task hook function used by the task xTask. + * Passing xTask as NULL has the effect of setting the calling tasks hook + * function. + */ + void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; + + /** + * task.h + *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
+ * + * Returns the pxHookFunction value assigned to the task xTask. + */ + pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + #endif /* configUSE_APPLICATION_TASK_TAG ==1 */ +#endif /* ifdef configUSE_APPLICATION_TASK_TAG */ + +/** + * task.h + *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Calls the hook function associated with xTask. Passing xTask as NULL has + * the effect of calling the Running tasks (the calling task) hook function. + * + * pvParameter is passed to the hook function for the task to interpret as it + * wants. + */ +portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; + + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + *----------------------------------------------------------*/ + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Called from the real time kernel tick (either preemptive or cooperative), + * this increments the tick count and checks if any tasks that are blocked + * for a finite period required removing from a blocked list and placing on + * a ready list. + */ +void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes the calling task from the ready list and places it both + * on the list of tasks waiting for a particular event, and the + * list of delayed tasks. The task will be removed from both lists + * and replaced on the ready list should either the event occur (and + * there be no higher priority tasks waiting on the same event) or + * the delay period expires. + * + * @param pxEventList The list containing tasks that are blocked waiting + * for the event to occur. + * + * @param xTicksToWait The maximum amount of time that the task should wait + * for the event to occur. This is specified in kernel ticks,the constant + * portTICK_RATE_MS can be used to convert kernel ticks into a real time + * period. + */ +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * This function performs nearly the same function as vTaskPlaceOnEventList(). + * The difference being that this function does not permit tasks to block + * indefinitely, whereas vTaskPlaceOnEventList() does. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes a task from both the specified event list and the list of blocked + * tasks, and places it on a ready queue. + * + * xTaskRemoveFromEventList () will be called if either an event occurs to + * unblock a task, or the block timeout period expires. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * INCLUDE_vTaskCleanUpResources and INCLUDE_vTaskSuspend must be defined as 1 + * for this function to be available. + * See the configuration section for more information. + * + * Empties the ready and delayed queues of task control blocks, freeing the + * memory allocated for the task control block and task stacks as it goes. + */ +void vTaskCleanUpResources( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Sets the pointer to the current TCB to the TCB of the highest priority task + * that is ready to run. + */ +void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; + +/* + * Return the handle of the calling task. + */ +xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; + +/* + * Capture the current time status for future reference. + */ +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; + +/* + * Compare the time status now with that previously captured to see if the + * timeout has expired. + */ +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * Shortcut used by the queue implementation to prevent unnecessary call to + * taskYIELD(); + */ +void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; + +/* + * Returns the scheduler state as taskSCHEDULER_RUNNING, + * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. + */ +portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; + +/* + * Raises the priority of the mutex holder to that of the calling task should + * the mutex holder have a priority less than the calling task. + */ +void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Set the priority of a task back to its proper priority in the case that it + * inherited a higher priority while it was holding a semaphore. + */ +void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Generic version of the task creation function which is in turn called by the + * xTaskCreate() and xTaskCreateRestricted() macros. + */ +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; + +void printTasks(); + +#ifdef __cplusplus +} +#endif +#endif /* TASK_H */ + + + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/timers.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/timers.h index 3d78c0ae0..f1bcb0d88 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/timers.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/include/timers.h @@ -1,936 +1,936 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef TIMERS_H -#define TIMERS_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include timers.h" -#endif - -#include "portable.h" -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* IDs for commands that can be sent/received on the timer queue. These are to -be used solely through the macros that make up the public software timer API, -as defined below. */ -#define tmrCOMMAND_START 0 -#define tmrCOMMAND_STOP 1 -#define tmrCOMMAND_CHANGE_PERIOD 2 -#define tmrCOMMAND_DELETE 3 - -/*----------------------------------------------------------- - * MACROS AND DEFINITIONS - *----------------------------------------------------------*/ - - /** - * Type by which software timers are referenced. For example, a call to - * xTimerCreate() returns an xTimerHandle variable that can then be used to - * reference the subject timer in calls to other software timer API functions - * (for example, xTimerStart(), xTimerReset(), etc.). - */ -typedef void * xTimerHandle; - -/* Define the prototype to which timer callback functions must conform. */ -typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); - -/** - * xTimerHandle xTimerCreate( const signed char *pcTimerName, - * portTickType xTimerPeriod, - * unsigned portBASE_TYPE uxAutoReload, - * void * pvTimerID, - * tmrTIMER_CALLBACK pxCallbackFunction ); - * - * Creates a new software timer instance. This allocates the storage required - * by the new timer, initialises the new timers internal state, and returns a - * handle by which the new timer can be referenced. - * - * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), - * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and - * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the - * active state. - * - * @param pcTimerName A text name that is assigned to the timer. This is done - * purely to assist debugging. The kernel itself only ever references a timer by - * its handle, and never by its name. - * - * @param xTimerPeriod The timer period. The time is defined in tick periods so - * the constant portTICK_RATE_MS can be used to convert a time that has been - * specified in milliseconds. For example, if the timer must expire after 100 - * ticks, then xTimerPeriod should be set to 100. Alternatively, if the timer - * must expire after 500ms, then xPeriod can be set to ( 500 / portTICK_RATE_MS ) - * provided configTICK_RATE_HZ is less than or equal to 1000. - * - * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will - * expire repeatedly with a frequency set by the xTimerPeriod parameter. If - * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and - * enter the dormant state after it expires. - * - * @param pvTimerID An identifier that is assigned to the timer being created. - * Typically this would be used in the timer callback function to identify which - * timer expired when the same callback function is assigned to more than one - * timer. - * - * @param pxCallbackFunction The function to call when the timer expires. - * Callback functions must have the prototype defined by tmrTIMER_CALLBACK, - * which is "void vCallbackFunction( xTIMER *xTimer );". - * - * @return If the timer is successfully create then a handle to the newly - * created timer is returned. If the timer cannot be created (because either - * there is insufficient FreeRTOS heap remaining to allocate the timer - * structures, or the timer period was set to 0) then 0 is returned. - * - * Example usage: - * - * - * #define NUM_TIMERS 5 - * - * // An array to hold handles to the created timers. - * xTimerHandle xTimers[ NUM_TIMERS ]; - * - * // An array to hold a count of the number of times each timer expires. - * long lExpireCounters[ NUM_TIMERS ] = { 0 }; - * - * // Define a callback function that will be used by multiple timer instances. - * // The callback function does nothing but count the number of times the - * // associated timer expires, and stop the timer once the timer has expired - * // 10 times. - * void vTimerCallback( xTIMER *pxTimer ) - * { - * long lArrayIndex; - * const long xMaxExpiryCountBeforeStopping = 10; - * - * // Optionally do something if the pxTimer parameter is NULL. - * configASSERT( pxTimer ); - * - * // Which timer expired? - * lArrayIndex = ( long ) pvTimerGetTimerID( pxTimer ); - * - * // Increment the number of times that pxTimer has expired. - * lExpireCounters[ lArrayIndex ] += 1; - * - * // If the timer has expired 10 times then stop it from running. - * if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping ) - * { - * // Do not use a block time if calling a timer API function from a - * // timer callback function, as doing so could cause a deadlock! - * xTimerStop( pxTimer, 0 ); - * } - * } - * - * void main( void ) - * { - * long x; - * - * // Create then start some timers. Starting the timers before the scheduler - * // has been started means the timers will start running immediately that - * // the scheduler starts. - * for( x = 0; x < NUM_TIMERS; x++ ) - * { - * xTimers[ x ] = xTimerCreate( "Timer", // Just a text name, not used by the kernel. - * ( 100 * x ), // The timer period in ticks. - * pdTRUE, // The timers will auto-reload themselves when they expire. - * ( void * ) x, // Assign each timer a unique id equal to its array index. - * vTimerCallback // Each timer calls the same callback when it expires. - * ); - * - * if( xTimers[ x ] == NULL ) - * { - * // The timer was not created. - * } - * else - * { - * // Start the timer. No block time is specified, and even if one was - * // it would be ignored because the scheduler has not yet been - * // started. - * if( xTimerStart( xTimers[ x ], 0 ) != pdPASS ) - * { - * // The timer could not be set into the Active state. - * } - * } - * } - * - * // ... - * // Create tasks here. - * // ... - * - * // Starting the scheduler will start the timers running as they have already - * // been set into the active state. - * xTaskStartScheduler(); - * - * // Should not reach here. - * for( ;; ); - * } - */ -xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void * pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) PRIVILEGED_FUNCTION; - -/** - * void *pvTimerGetTimerID( xTimerHandle xTimer ); - * - * Returns the ID assigned to the timer. - * - * IDs are assigned to timers using the pvTimerID parameter of the call to - * xTimerCreated() that was used to create the timer. - * - * If the same callback function is assigned to multiple timers then the timer - * ID can be used within the callback function to identify which timer actually - * expired. - * - * @param xTimer The timer being queried. - * - * @return The ID assigned to the timer being queried. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - */ -void *pvTimerGetTimerID( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; - -/** - * portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ); - * - * Queries a timer to see if it is active or dormant. - * - * A timer will be dormant if: - * 1) It has been created but not started, or - * 2) It is an expired on-shot timer that has not been restarted. - * - * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), - * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and - * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the - * active state. - * - * @param xTimer The timer being queried. - * - * @return pdFALSE will be returned if the timer is dormant. A value other than - * pdFALSE will be returned if the timer is active. - * - * Example usage: - * - * // This function assumes xTimer has already been created. - * void vAFunction( xTimerHandle xTimer ) - * { - * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" - * { - * // xTimer is active, do something. - * } - * else - * { - * // xTimer is not active, do something else. - * } - * } - */ -portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; - -/** - * portBASE_TYPE xTimerStart( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerStart() starts a timer that was previously created using the - * xTimerCreate() API function. If the timer had already been started and was - * already in the active state, then xTimerStart() has equivalent functionality - * to the xTimerReset() API function. - * - * Starting a timer ensures the timer is in the active state. If the timer - * is not stopped, deleted, or reset in the mean time, the callback function - * associated with the timer will get called 'n' ticks after xTimerStart() was - * called, where 'n' is the timers defined period. - * - * It is valid to call xTimerStart() before the scheduler has been started, but - * when this is done the timer will not actually start until the scheduler is - * started, and the timers expiry time will be relative to when the scheduler is - * started, not relative to when xTimerStart() was called. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart() - * to be available. - * - * @param xTimer The handle of the timer being started/restarted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the start command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerStart() was called. xBlockTime is ignored if xTimerStart() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the start command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system, although the - * timers expiry time is relative to when xTimerStart() is actually called. The - * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - * - */ -#define xTimerStart( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerStop( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerStop() stops a timer that was previously started using either of the - * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(), - * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions. - * - * Stopping a timer ensures the timer is not in the active state. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop() - * to be available. - * - * @param xTimer The handle of the timer being stopped. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the stop command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerStop() was called. xBlockTime is ignored if xTimerStop() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the stop command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system. The timer - * service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - * - */ -#define xTimerStop( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerChangePeriod( xTimerHandle xTimer, - * portTickType xNewPeriod, - * portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerChangePeriod() changes the period of a timer that was previously - * created using the xTimerCreate() API function. - * - * xTimerChangePeriod() can be called to change the period of an active or - * dormant state timer. - * - * The configUSE_TIMERS configuration constant must be set to 1 for - * xTimerChangePeriod() to be available. - * - * @param xTimer The handle of the timer that is having its period changed. - * - * @param xNewPeriod The new period for xTimer. Timer periods are specified in - * tick periods, so the constant portTICK_RATE_MS can be used to convert a time - * that has been specified in milliseconds. For example, if the timer must - * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, - * if the timer must expire after 500ms, then xNewPeriod can be set to - * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than - * or equal to 1000. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the change period command to be - * successfully sent to the timer command queue, should the queue already be - * full when xTimerChangePeriod() was called. xBlockTime is ignored if - * xTimerChangePeriod() is called before the scheduler is started. - * - * @return pdFAIL will be returned if the change period command could not be - * sent to the timer command queue even after xBlockTime ticks had passed. - * pdPASS will be returned if the command was successfully sent to the timer - * command queue. When the command is actually processed will depend on the - * priority of the timer service/daemon task relative to other tasks in the - * system. The timer service/daemon task priority is set by the - * configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This function assumes xTimer has already been created. If the timer - * // referenced by xTimer is already active when it is called, then the timer - * // is deleted. If the timer referenced by xTimer is not active when it is - * // called, then the period of the timer is set to 500ms and the timer is - * // started. - * void vAFunction( xTimerHandle xTimer ) - * { - * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" - * { - * // xTimer is already active - delete it. - * xTimerDelete( xTimer ); - * } - * else - * { - * // xTimer is not active, change its period to 500ms. This will also - * // cause the timer to start. Block for a maximum of 100 ticks if the - * // change period command cannot immediately be sent to the timer - * // command queue. - * if( xTimerChangePeriod( xTimer, 500 / portTICK_RATE_MS, 100 ) == pdPASS ) - * { - * // The command was successfully sent. - * } - * else - * { - * // The command could not be sent, even after waiting for 100 ticks - * // to pass. Take appropriate action here. - * } - * } - * } - */ - #define xTimerChangePeriod( xTimer, xNewPeriod, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerDelete( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerDelete() deletes a timer that was previously created using the - * xTimerCreate() API function. - * - * The configUSE_TIMERS configuration constant must be set to 1 for - * xTimerDelete() to be available. - * - * @param xTimer The handle of the timer being deleted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the delete command to be - * successfully sent to the timer command queue, should the queue already be - * full when xTimerDelete() was called. xBlockTime is ignored if xTimerDelete() - * is called before the scheduler is started. - * - * @return pdFAIL will be returned if the delete command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system. The timer - * service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerChangePeriod() API function example usage scenario. - */ -#define xTimerDelete( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerReset( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerReset() re-starts a timer that was previously created using the - * xTimerCreate() API function. If the timer had already been started and was - * already in the active state, then xTimerReset() will cause the timer to - * re-evaluate its expiry time so that it is relative to when xTimerReset() was - * called. If the timer was in the dormant state then xTimerReset() has - * equivalent functionality to the xTimerStart() API function. - * - * Resetting a timer ensures the timer is in the active state. If the timer - * is not stopped, deleted, or reset in the mean time, the callback function - * associated with the timer will get called 'n' ticks after xTimerReset() was - * called, where 'n' is the timers defined period. - * - * It is valid to call xTimerReset() before the scheduler has been started, but - * when this is done the timer will not actually start until the scheduler is - * started, and the timers expiry time will be relative to when the scheduler is - * started, not relative to when xTimerReset() was called. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset() - * to be available. - * - * @param xTimer The handle of the timer being reset/started/restarted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the reset command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerReset() was called. xBlockTime is ignored if xTimerReset() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the reset command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system, although the - * timers expiry time is relative to when xTimerStart() is actually called. The - * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * // When a key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer. - * - * xTimerHandle xBacklightTimer = NULL; - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTIMER *pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press event handler. - * void vKeyPressEventHandler( char cKey ) - * { - * // Ensure the LCD back-light is on, then reset the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. Wait 10 ticks for the command to be successfully sent - * // if it cannot be sent immediately. - * vSetBacklightState( BACKLIGHT_ON ); - * if( xTimerReset( xBacklightTimer, 100 ) != pdPASS ) - * { - * // The reset command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * } - * - * void main( void ) - * { - * long x; - * - * // Create then start the one-shot timer that is responsible for turning - * // the back-light off if no keys are pressed within a 5 second period. - * xBacklightTimer = xTimerCreate( "BacklightTimer", // Just a text name, not used by the kernel. - * ( 5000 / portTICK_RATE_MS), // The timer period in ticks. - * pdFALSE, // The timer is a one-shot timer. - * 0, // The id is not used by the callback so can take any value. - * vBacklightTimerCallback // The callback function that switches the LCD back-light off. - * ); - * - * if( xBacklightTimer == NULL ) - * { - * // The timer was not created. - * } - * else - * { - * // Start the timer. No block time is specified, and even if one was - * // it would be ignored because the scheduler has not yet been - * // started. - * if( xTimerStart( xBacklightTimer, 0 ) != pdPASS ) - * { - * // The timer could not be set into the Active state. - * } - * } - * - * // ... - * // Create tasks here. - * // ... - * - * // Starting the scheduler will start the timer running as it has already - * // been set into the active state. - * xTaskStartScheduler(); - * - * // Should not reach here. - * for( ;; ); - * } - */ -#define xTimerReset( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerStartFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerStart() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer being started/restarted. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerStartFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerStartFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerStartFromISR() function. If - * xTimerStartFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the start command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system, although the timers expiry time is - * relative to when xTimerStartFromISR() is actually called. The timer service/daemon - * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xBacklightTimer has already been created. When a - * // key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer, and unlike the example given for - * // the xTimerReset() function, the key press event handler is an interrupt - * // service routine. - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTIMER *pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press interrupt service routine. - * void vKeyPressEventInterruptHandler( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // Ensure the LCD back-light is on, then restart the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. This is an interrupt service routine so can only - * // call FreeRTOS API functions that end in "FromISR". - * vSetBacklightState( BACKLIGHT_ON ); - * - * // xTimerStartFromISR() or xTimerResetFromISR() could be called here - * // as both cause the timer to re-calculate its expiry time. - * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was - * // declared (in this function). - * if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The start command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerStopFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerStop() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer being stopped. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerStopFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerStopFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerStopFromISR() function. If - * xTimerStopFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the stop command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system. The timer service/daemon task - * priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xTimer has already been created and started. When - * // an interrupt occurs, the timer should be simply stopped. - * - * // The interrupt service routine that stops the timer. - * void vAnExampleInterruptServiceRoutine( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // The interrupt has occurred - simply stop the timer. - * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined - * // (within this function). As this is an interrupt service routine, only - * // FreeRTOS API functions that end in "FromISR" can be used. - * if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The stop command was not executed successfully. Take appropriate - * // action here. - * } - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0, ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerChangePeriodFromISR( xTimerHandle xTimer, - * portTickType xNewPeriod, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerChangePeriod() that can be called from an interrupt - * service routine. - * - * @param xTimer The handle of the timer that is having its period changed. - * - * @param xNewPeriod The new period for xTimer. Timer periods are specified in - * tick periods, so the constant portTICK_RATE_MS can be used to convert a time - * that has been specified in milliseconds. For example, if the timer must - * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, - * if the timer must expire after 500ms, then xNewPeriod can be set to - * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than - * or equal to 1000. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerChangePeriodFromISR() writes a message to the - * timer command queue, so has the potential to transition the timer service/ - * daemon task out of the Blocked state. If calling xTimerChangePeriodFromISR() - * causes the timer service/daemon task to leave the Blocked state, and the - * timer service/daemon task has a priority equal to or greater than the - * currently executing task (the task that was interrupted), then - * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the - * xTimerChangePeriodFromISR() function. If xTimerChangePeriodFromISR() sets - * this value to pdTRUE then a context switch should be performed before the - * interrupt exits. - * - * @return pdFAIL will be returned if the command to change the timers period - * could not be sent to the timer command queue. pdPASS will be returned if the - * command was successfully sent to the timer command queue. When the command - * is actually processed will depend on the priority of the timer service/daemon - * task relative to other tasks in the system. The timer service/daemon task - * priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xTimer has already been created and started. When - * // an interrupt occurs, the period of xTimer should be changed to 500ms. - * - * // The interrupt service routine that changes the period of xTimer. - * void vAnExampleInterruptServiceRoutine( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // The interrupt has occurred - change the period of xTimer to 500ms. - * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined - * // (within this function). As this is an interrupt service routine, only - * // FreeRTOS API functions that end in "FromISR" can be used. - * if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The command to change the timers period was not executed - * // successfully. Take appropriate action here. - * } - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerResetFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerReset() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer that is to be started, reset, or - * restarted. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerResetFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerResetFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerResetFromISR() function. If - * xTimerResetFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the reset command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system, although the timers expiry time is - * relative to when xTimerResetFromISR() is actually called. The timer service/daemon - * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xBacklightTimer has already been created. When a - * // key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer, and unlike the example given for - * // the xTimerReset() function, the key press event handler is an interrupt - * // service routine. - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTIMER *pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press interrupt service routine. - * void vKeyPressEventInterruptHandler( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // Ensure the LCD back-light is on, then reset the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. This is an interrupt service routine so can only - * // call FreeRTOS API functions that end in "FromISR". - * vSetBacklightState( BACKLIGHT_ON ); - * - * // xTimerStartFromISR() or xTimerResetFromISR() could be called here - * // as both cause the timer to re-calculate its expiry time. - * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was - * // declared (in this function). - * if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The reset command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) - -/* - * Functions beyond this part are not part of the public API and are intended - * for use by the kernel only. - */ -portBASE_TYPE xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; -portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) PRIVILEGED_FUNCTION; - -#ifdef __cplusplus -} -#endif -#endif /* TIMERS_H */ - - - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef TIMERS_H +#define TIMERS_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include timers.h" +#endif + +#include "portable.h" +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* IDs for commands that can be sent/received on the timer queue. These are to +be used solely through the macros that make up the public software timer API, +as defined below. */ +#define tmrCOMMAND_START 0 +#define tmrCOMMAND_STOP 1 +#define tmrCOMMAND_CHANGE_PERIOD 2 +#define tmrCOMMAND_DELETE 3 + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + + /** + * Type by which software timers are referenced. For example, a call to + * xTimerCreate() returns an xTimerHandle variable that can then be used to + * reference the subject timer in calls to other software timer API functions + * (for example, xTimerStart(), xTimerReset(), etc.). + */ +typedef void * xTimerHandle; + +/* Define the prototype to which timer callback functions must conform. */ +typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); + +/** + * xTimerHandle xTimerCreate( const signed char *pcTimerName, + * portTickType xTimerPeriod, + * unsigned portBASE_TYPE uxAutoReload, + * void * pvTimerID, + * tmrTIMER_CALLBACK pxCallbackFunction ); + * + * Creates a new software timer instance. This allocates the storage required + * by the new timer, initialises the new timers internal state, and returns a + * handle by which the new timer can be referenced. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the + * active state. + * + * @param pcTimerName A text name that is assigned to the timer. This is done + * purely to assist debugging. The kernel itself only ever references a timer by + * its handle, and never by its name. + * + * @param xTimerPeriod The timer period. The time is defined in tick periods so + * the constant portTICK_RATE_MS can be used to convert a time that has been + * specified in milliseconds. For example, if the timer must expire after 100 + * ticks, then xTimerPeriod should be set to 100. Alternatively, if the timer + * must expire after 500ms, then xPeriod can be set to ( 500 / portTICK_RATE_MS ) + * provided configTICK_RATE_HZ is less than or equal to 1000. + * + * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will + * expire repeatedly with a frequency set by the xTimerPeriod parameter. If + * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and + * enter the dormant state after it expires. + * + * @param pvTimerID An identifier that is assigned to the timer being created. + * Typically this would be used in the timer callback function to identify which + * timer expired when the same callback function is assigned to more than one + * timer. + * + * @param pxCallbackFunction The function to call when the timer expires. + * Callback functions must have the prototype defined by tmrTIMER_CALLBACK, + * which is "void vCallbackFunction( xTIMER *xTimer );". + * + * @return If the timer is successfully create then a handle to the newly + * created timer is returned. If the timer cannot be created (because either + * there is insufficient FreeRTOS heap remaining to allocate the timer + * structures, or the timer period was set to 0) then 0 is returned. + * + * Example usage: + * + * + * #define NUM_TIMERS 5 + * + * // An array to hold handles to the created timers. + * xTimerHandle xTimers[ NUM_TIMERS ]; + * + * // An array to hold a count of the number of times each timer expires. + * long lExpireCounters[ NUM_TIMERS ] = { 0 }; + * + * // Define a callback function that will be used by multiple timer instances. + * // The callback function does nothing but count the number of times the + * // associated timer expires, and stop the timer once the timer has expired + * // 10 times. + * void vTimerCallback( xTIMER *pxTimer ) + * { + * long lArrayIndex; + * const long xMaxExpiryCountBeforeStopping = 10; + * + * // Optionally do something if the pxTimer parameter is NULL. + * configASSERT( pxTimer ); + * + * // Which timer expired? + * lArrayIndex = ( long ) pvTimerGetTimerID( pxTimer ); + * + * // Increment the number of times that pxTimer has expired. + * lExpireCounters[ lArrayIndex ] += 1; + * + * // If the timer has expired 10 times then stop it from running. + * if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping ) + * { + * // Do not use a block time if calling a timer API function from a + * // timer callback function, as doing so could cause a deadlock! + * xTimerStop( pxTimer, 0 ); + * } + * } + * + * void main( void ) + * { + * long x; + * + * // Create then start some timers. Starting the timers before the scheduler + * // has been started means the timers will start running immediately that + * // the scheduler starts. + * for( x = 0; x < NUM_TIMERS; x++ ) + * { + * xTimers[ x ] = xTimerCreate( "Timer", // Just a text name, not used by the kernel. + * ( 100 * x ), // The timer period in ticks. + * pdTRUE, // The timers will auto-reload themselves when they expire. + * ( void * ) x, // Assign each timer a unique id equal to its array index. + * vTimerCallback // Each timer calls the same callback when it expires. + * ); + * + * if( xTimers[ x ] == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xTimers[ x ], 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timers running as they have already + * // been set into the active state. + * xTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + */ +xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void * pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) PRIVILEGED_FUNCTION; + +/** + * void *pvTimerGetTimerID( xTimerHandle xTimer ); + * + * Returns the ID assigned to the timer. + * + * IDs are assigned to timers using the pvTimerID parameter of the call to + * xTimerCreated() that was used to create the timer. + * + * If the same callback function is assigned to multiple timers then the timer + * ID can be used within the callback function to identify which timer actually + * expired. + * + * @param xTimer The timer being queried. + * + * @return The ID assigned to the timer being queried. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + */ +void *pvTimerGetTimerID( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; + +/** + * portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ); + * + * Queries a timer to see if it is active or dormant. + * + * A timer will be dormant if: + * 1) It has been created but not started, or + * 2) It is an expired on-shot timer that has not been restarted. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the + * active state. + * + * @param xTimer The timer being queried. + * + * @return pdFALSE will be returned if the timer is dormant. A value other than + * pdFALSE will be returned if the timer is active. + * + * Example usage: + * + * // This function assumes xTimer has already been created. + * void vAFunction( xTimerHandle xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is active, do something. + * } + * else + * { + * // xTimer is not active, do something else. + * } + * } + */ +portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; + +/** + * portBASE_TYPE xTimerStart( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStart() starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerStart() has equivalent functionality + * to the xTimerReset() API function. + * + * Starting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerStart() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerStart() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerStart() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart() + * to be available. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the start command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStart() was called. xBlockTime is ignored if xTimerStart() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStart( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerStop( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStop() stops a timer that was previously started using either of the + * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(), + * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions. + * + * Stopping a timer ensures the timer is not in the active state. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop() + * to be available. + * + * @param xTimer The handle of the timer being stopped. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the stop command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStop() was called. xBlockTime is ignored if xTimerStop() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStop( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerChangePeriod( xTimerHandle xTimer, + * portTickType xNewPeriod, + * portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerChangePeriod() changes the period of a timer that was previously + * created using the xTimerCreate() API function. + * + * xTimerChangePeriod() can be called to change the period of an active or + * dormant state timer. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerChangePeriod() to be available. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_RATE_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the change period command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerChangePeriod() was called. xBlockTime is ignored if + * xTimerChangePeriod() is called before the scheduler is started. + * + * @return pdFAIL will be returned if the change period command could not be + * sent to the timer command queue even after xBlockTime ticks had passed. + * pdPASS will be returned if the command was successfully sent to the timer + * command queue. When the command is actually processed will depend on the + * priority of the timer service/daemon task relative to other tasks in the + * system. The timer service/daemon task priority is set by the + * configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This function assumes xTimer has already been created. If the timer + * // referenced by xTimer is already active when it is called, then the timer + * // is deleted. If the timer referenced by xTimer is not active when it is + * // called, then the period of the timer is set to 500ms and the timer is + * // started. + * void vAFunction( xTimerHandle xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is already active - delete it. + * xTimerDelete( xTimer ); + * } + * else + * { + * // xTimer is not active, change its period to 500ms. This will also + * // cause the timer to start. Block for a maximum of 100 ticks if the + * // change period command cannot immediately be sent to the timer + * // command queue. + * if( xTimerChangePeriod( xTimer, 500 / portTICK_RATE_MS, 100 ) == pdPASS ) + * { + * // The command was successfully sent. + * } + * else + * { + * // The command could not be sent, even after waiting for 100 ticks + * // to pass. Take appropriate action here. + * } + * } + * } + */ + #define xTimerChangePeriod( xTimer, xNewPeriod, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerDelete( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerDelete() deletes a timer that was previously created using the + * xTimerCreate() API function. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerDelete() to be available. + * + * @param xTimer The handle of the timer being deleted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the delete command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerDelete() was called. xBlockTime is ignored if xTimerDelete() + * is called before the scheduler is started. + * + * @return pdFAIL will be returned if the delete command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerChangePeriod() API function example usage scenario. + */ +#define xTimerDelete( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerReset( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerReset() re-starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerReset() will cause the timer to + * re-evaluate its expiry time so that it is relative to when xTimerReset() was + * called. If the timer was in the dormant state then xTimerReset() has + * equivalent functionality to the xTimerStart() API function. + * + * Resetting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerReset() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerReset() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerReset() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset() + * to be available. + * + * @param xTimer The handle of the timer being reset/started/restarted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the reset command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerReset() was called. xBlockTime is ignored if xTimerReset() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * // When a key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer. + * + * xTimerHandle xBacklightTimer = NULL; + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTIMER *pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press event handler. + * void vKeyPressEventHandler( char cKey ) + * { + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. Wait 10 ticks for the command to be successfully sent + * // if it cannot be sent immediately. + * vSetBacklightState( BACKLIGHT_ON ); + * if( xTimerReset( xBacklightTimer, 100 ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * } + * + * void main( void ) + * { + * long x; + * + * // Create then start the one-shot timer that is responsible for turning + * // the back-light off if no keys are pressed within a 5 second period. + * xBacklightTimer = xTimerCreate( "BacklightTimer", // Just a text name, not used by the kernel. + * ( 5000 / portTICK_RATE_MS), // The timer period in ticks. + * pdFALSE, // The timer is a one-shot timer. + * 0, // The id is not used by the callback so can take any value. + * vBacklightTimerCallback // The callback function that switches the LCD back-light off. + * ); + * + * if( xBacklightTimer == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xBacklightTimer, 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timer running as it has already + * // been set into the active state. + * xTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + */ +#define xTimerReset( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerStartFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStart() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStartFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStartFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStartFromISR() function. If + * xTimerStartFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerStartFromISR() is actually called. The timer service/daemon + * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTIMER *pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then restart the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The start command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerStopFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStop() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being stopped. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStopFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStopFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStopFromISR() function. If + * xTimerStopFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the timer should be simply stopped. + * + * // The interrupt service routine that stops the timer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - simply stop the timer. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The stop command was not executed successfully. Take appropriate + * // action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0, ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerChangePeriodFromISR( xTimerHandle xTimer, + * portTickType xNewPeriod, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerChangePeriod() that can be called from an interrupt + * service routine. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_RATE_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerChangePeriodFromISR() writes a message to the + * timer command queue, so has the potential to transition the timer service/ + * daemon task out of the Blocked state. If calling xTimerChangePeriodFromISR() + * causes the timer service/daemon task to leave the Blocked state, and the + * timer service/daemon task has a priority equal to or greater than the + * currently executing task (the task that was interrupted), then + * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the + * xTimerChangePeriodFromISR() function. If xTimerChangePeriodFromISR() sets + * this value to pdTRUE then a context switch should be performed before the + * interrupt exits. + * + * @return pdFAIL will be returned if the command to change the timers period + * could not be sent to the timer command queue. pdPASS will be returned if the + * command was successfully sent to the timer command queue. When the command + * is actually processed will depend on the priority of the timer service/daemon + * task relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the period of xTimer should be changed to 500ms. + * + * // The interrupt service routine that changes the period of xTimer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - change the period of xTimer to 500ms. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The command to change the timers period was not executed + * // successfully. Take appropriate action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerResetFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerReset() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer that is to be started, reset, or + * restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerResetFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerResetFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerResetFromISR() function. If + * xTimerResetFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerResetFromISR() is actually called. The timer service/daemon + * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTIMER *pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + +/* + * Functions beyond this part are not part of the public API and are intended + * for use by the kernel only. + */ +portBASE_TYPE xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; +portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) PRIVILEGED_FUNCTION; + +#ifdef __cplusplus +} +#endif +#endif /* TIMERS_H */ + + + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/list.c b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/list.c index ea249cd07..b47ab8c1b 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/list.c +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/list.c @@ -1,197 +1,197 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. - */ - - -#include -#include "FreeRTOS.h" -#include "list.h" - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -void vListInitialise( xList *pxList ) -{ - /* The list structure contains a list item which is used to mark the - end of the list. To initialise the list the list end is inserted - as the only list entry. */ - pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); - - /* The list end value is the highest possible value in the list to - ensure it remains at the end of the list. */ - pxList->xListEnd.xItemValue = portMAX_DELAY; - - /* The list end next and previous pointers point to itself so we know - when the list is empty. */ - pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); - pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); - - pxList->uxNumberOfItems = ( unsigned portBASE_TYPE ) 0U; -} -/*-----------------------------------------------------------*/ - -void vListInitialiseItem( xListItem *pxItem ) -{ - /* Make sure the list item is not recorded as being on a list. */ - pxItem->pvContainer = NULL; -} -/*-----------------------------------------------------------*/ - -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) -{ - volatile xListItem * pxIndex; - - /* Insert a new list item into pxList, but rather than sort the list, - makes the new list item the last item to be removed by a call to - pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by - the pxIndex member. */ - pxIndex = pxList->pxIndex; - - pxNewListItem->pxNext = pxIndex->pxNext; - pxNewListItem->pxPrevious = pxList->pxIndex; - pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; - pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListInsert( xList *pxList, xListItem *pxNewListItem ) -{ - volatile xListItem *pxIterator; - portTickType xValueOfInsertion; - - /* Insert the new list item into the list, sorted in ulListItem order. */ - xValueOfInsertion = pxNewListItem->xItemValue; - - /* If the list already contains a list item with the same item value then - the new list item should be placed after it. This ensures that TCB's which - are stored in ready lists (all of which have the same ulListItem value) - get an equal share of the CPU. However, if the xItemValue is the same as - the back marker the iteration loop below will not end. This means we need - to guard against this by checking the value first and modifying the - algorithm slightly if necessary. */ - if( xValueOfInsertion == portMAX_DELAY ) - { - pxIterator = pxList->xListEnd.pxPrevious; - } - else - { - /* *** NOTE *********************************************************** - If you find your application is crashing here then likely causes are: - 1) Stack overflow - - see http://www.freertos.org/Stacks-and-stack-overflow-checking.html - 2) Incorrect interrupt priority assignment, especially on Cortex-M3 - parts where numerically high priority values denote low actual - interrupt priories, which can seem counter intuitive. See - configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html - 3) Calling an API function from within a critical section or when - the scheduler is suspended. - 4) Using a queue or semaphore before it has been initialised or - before the scheduler has been started (are interrupts firing - before vTaskStartScheduler() has been called?). - See http://www.freertos.org/FAQHelp.html for more tips. - **********************************************************************/ - - for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) - { - /* There is nothing to do here, we are just iterating to the - wanted insertion position. */ - } - } - - pxNewListItem->pxNext = pxIterator->pxNext; - pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxNewListItem->pxPrevious = pxIterator; - pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. This allows fast removal of the - item later. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListRemove( xListItem *pxItemToRemove ) -{ - xList * pxList; - - pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; - pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; - - /* The list item knows which list it is in. Obtain the list from the list - item. */ - pxList = ( xList * ) pxItemToRemove->pvContainer; - - /* Make sure the index is left pointing to a valid item. */ - if( pxList->pxIndex == pxItemToRemove ) - { - pxList->pxIndex = pxItemToRemove->pxPrevious; - } - - pxItemToRemove->pvContainer = NULL; - ( pxList->uxNumberOfItems )--; -} -/*-----------------------------------------------------------*/ - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. + */ + + +#include +#include "FreeRTOS.h" +#include "list.h" + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +void vListInitialise( xList *pxList ) +{ + /* The list structure contains a list item which is used to mark the + end of the list. To initialise the list the list end is inserted + as the only list entry. */ + pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); + + /* The list end value is the highest possible value in the list to + ensure it remains at the end of the list. */ + pxList->xListEnd.xItemValue = portMAX_DELAY; + + /* The list end next and previous pointers point to itself so we know + when the list is empty. */ + pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); + pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); + + pxList->uxNumberOfItems = ( unsigned portBASE_TYPE ) 0U; +} +/*-----------------------------------------------------------*/ + +void vListInitialiseItem( xListItem *pxItem ) +{ + /* Make sure the list item is not recorded as being on a list. */ + pxItem->pvContainer = NULL; +} +/*-----------------------------------------------------------*/ + +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) +{ + volatile xListItem * pxIndex; + + /* Insert a new list item into pxList, but rather than sort the list, + makes the new list item the last item to be removed by a call to + pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by + the pxIndex member. */ + pxIndex = pxList->pxIndex; + + pxNewListItem->pxNext = pxIndex->pxNext; + pxNewListItem->pxPrevious = pxList->pxIndex; + pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; + pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListInsert( xList *pxList, xListItem *pxNewListItem ) +{ + volatile xListItem *pxIterator; + portTickType xValueOfInsertion; + + /* Insert the new list item into the list, sorted in ulListItem order. */ + xValueOfInsertion = pxNewListItem->xItemValue; + + /* If the list already contains a list item with the same item value then + the new list item should be placed after it. This ensures that TCB's which + are stored in ready lists (all of which have the same ulListItem value) + get an equal share of the CPU. However, if the xItemValue is the same as + the back marker the iteration loop below will not end. This means we need + to guard against this by checking the value first and modifying the + algorithm slightly if necessary. */ + if( xValueOfInsertion == portMAX_DELAY ) + { + pxIterator = pxList->xListEnd.pxPrevious; + } + else + { + /* *** NOTE *********************************************************** + If you find your application is crashing here then likely causes are: + 1) Stack overflow - + see http://www.freertos.org/Stacks-and-stack-overflow-checking.html + 2) Incorrect interrupt priority assignment, especially on Cortex-M3 + parts where numerically high priority values denote low actual + interrupt priories, which can seem counter intuitive. See + configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html + 3) Calling an API function from within a critical section or when + the scheduler is suspended. + 4) Using a queue or semaphore before it has been initialised or + before the scheduler has been started (are interrupts firing + before vTaskStartScheduler() has been called?). + See http://www.freertos.org/FAQHelp.html for more tips. + **********************************************************************/ + + for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) + { + /* There is nothing to do here, we are just iterating to the + wanted insertion position. */ + } + } + + pxNewListItem->pxNext = pxIterator->pxNext; + pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxNewListItem->pxPrevious = pxIterator; + pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. This allows fast removal of the + item later. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListRemove( xListItem *pxItemToRemove ) +{ + xList * pxList; + + pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; + pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; + + /* The list item knows which list it is in. Obtain the list from the list + item. */ + pxList = ( xList * ) pxItemToRemove->pvContainer; + + /* Make sure the index is left pointing to a valid item. */ + if( pxList->pxIndex == pxItemToRemove ) + { + pxList->pxIndex = pxItemToRemove->pxPrevious; + } + + pxItemToRemove->pvContainer = NULL; + ( pxList->uxNumberOfItems )--; +} +/*-----------------------------------------------------------*/ + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h index 4da6b124b..4ceafc2b9 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h @@ -1,170 +1,170 @@ -/* - FreeRTOS.org V5.2.0 - Copyright (C) 2003-2009 Richard Barry. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. - - You should have received a copy of the GNU General Public License along - with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef PORTMACRO_H -#define PORTMACRO_H - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * Port specific definitions. - * - * The settings in this file configure FreeRTOS correctly for the - * given hardware and compiler. - * - * These settings should not be altered. - *----------------------------------------------------------- - */ - -/* Type definitions. */ -#define portCHAR char -#define portFLOAT float -#define portDOUBLE double -#define portLONG int -#define portSHORT short -#define portSTACK_TYPE unsigned long -#define portBASE_TYPE long - -#if( configUSE_16_BIT_TICKS == 1 ) - typedef unsigned portSHORT portTickType; - #define portMAX_DELAY ( portTickType ) 0xffff -#else - typedef unsigned portLONG portTickType; - #define portMAX_DELAY ( portTickType ) 0xffffffff -#endif -/*-----------------------------------------------------------*/ - -/* Architecture specifics. */ -#define portSTACK_GROWTH ( -1 ) -#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) -#define portTICK_RATE_MICROSECONDS ( ( portTickType ) 1000000 / configTICK_RATE_HZ ) -#define portBYTE_ALIGNMENT 4 -#define portREMOVE_STATIC_QUALIFIER -/*-----------------------------------------------------------*/ - - -/* Scheduler utilities. */ -extern void vPortYieldFromISR( void ); -extern void vPortYield( void ); - -#define portYIELD() vPortYield() - -#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() -/*-----------------------------------------------------------*/ - - -/* Critical section management. */ -extern void vPortDisableInterrupts( void ); -extern void vPortEnableInterrupts( void ); -#define portSET_INTERRUPT_MASK() ( vPortDisableInterrupts() ) -#define portCLEAR_INTERRUPT_MASK() ( vPortEnableInterrupts() ) - -extern portBASE_TYPE xPortSetInterruptMask( void ); -extern void vPortClearInterruptMask( portBASE_TYPE xMask ); - -#define portSET_INTERRUPT_MASK_FROM_ISR() xPortSetInterruptMask() -#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) vPortClearInterruptMask(x) - - -extern void vPortEnterCritical( void ); -extern void vPortExitCritical( void ); - -#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() -#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() -#define portENTER_CRITICAL() vPortEnterCritical() -#define portEXIT_CRITICAL() vPortExitCritical() -/*-----------------------------------------------------------*/ - -/* Task function macros as described on the FreeRTOS.org WEB site. */ -#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) -#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) - -#define portNOP() - -#define portOUTPUT_BYTE( a, b ) - -extern void vPortForciblyEndThread( void *pxTaskToDelete ); -#define traceTASK_DELETE( pxTaskToDelete ) vPortForciblyEndThread( pxTaskToDelete ) - -extern void vPortAddTaskHandle( void *pxTaskHandle ); -#define traceTASK_CREATE( pxNewTCB ) vPortAddTaskHandle( pxNewTCB ) - -/* Posix Signal definitions that can be changed or read as appropriate. */ -#define SIG_SUSPEND SIGUSR1 -#define SIG_RESUME SIGUSR2 - -/* Enable the following hash defines to make use of the real-time tick where time progresses at real-time. */ -#define SIG_TICK SIGALRM -#define TIMER_TYPE ITIMER_REAL -/* Enable the following hash defines to make use of the process tick where time progresses only when the process is executing. -#define SIG_TICK SIGVTALRM -#define TIMER_TYPE ITIMER_VIRTUAL */ -/* Enable the following hash defines to make use of the profile tick where time progresses when the process or system calls are executing. -#define SIG_TICK SIGPROF -#define TIMER_TYPE ITIMER_PROF */ - -/* Make use of times(man 2) to gather run-time statistics on the tasks. */ -extern void vPortFindTicksPerSecond( void ); -#undef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS -#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vPortFindTicksPerSecond() /* Nothing to do because the timer is already present. */ -extern unsigned long ulPortGetTimerValue( void ); -#undef portGET_RUN_TIME_COUNTER_VALUE -#define portGET_RUN_TIME_COUNTER_VALUE() ulPortGetTimerValue() /* Query the System time stats for this process. */ - -#ifdef __cplusplus -} -#endif - -#endif /* PORTMACRO_H */ - +/* + FreeRTOS.org V5.2.0 - Copyright (C) 2003-2009 Richard Barry. + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify it + under the terms of the GNU General Public License (version 2) as published + by the Free Software Foundation and modified by the FreeRTOS exception. + + FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. + + You should have received a copy of the GNU General Public License along + with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 + Temple Place, Suite 330, Boston, MA 02111-1307 USA. + + A special exception to the GPL is included to allow you to distribute a + combined work that includes FreeRTOS.org without being obliged to provide + the source code for any proprietary components. See the licensing section + of http://www.FreeRTOS.org for full details. + + + *************************************************************************** + * * + * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * + * * + * This is a concise, step by step, 'hands on' guide that describes both * + * general multitasking concepts and FreeRTOS specifics. It presents and * + * explains numerous examples that are written using the FreeRTOS API. * + * Full source code for all the examples is provided in an accompanying * + * .zip file. * + * * + *************************************************************************** + + 1 tab == 4 spaces! + + Please ensure to read the configuration and relevant port sections of the + online documentation. + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef PORTMACRO_H +#define PORTMACRO_H + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * Port specific definitions. + * + * The settings in this file configure FreeRTOS correctly for the + * given hardware and compiler. + * + * These settings should not be altered. + *----------------------------------------------------------- + */ + +/* Type definitions. */ +#define portCHAR char +#define portFLOAT float +#define portDOUBLE double +#define portLONG int +#define portSHORT short +#define portSTACK_TYPE unsigned long +#define portBASE_TYPE long + +#if( configUSE_16_BIT_TICKS == 1 ) + typedef unsigned portSHORT portTickType; + #define portMAX_DELAY ( portTickType ) 0xffff +#else + typedef unsigned portLONG portTickType; + #define portMAX_DELAY ( portTickType ) 0xffffffff +#endif +/*-----------------------------------------------------------*/ + +/* Architecture specifics. */ +#define portSTACK_GROWTH ( -1 ) +#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) +#define portTICK_RATE_MICROSECONDS ( ( portTickType ) 1000000 / configTICK_RATE_HZ ) +#define portBYTE_ALIGNMENT 4 +#define portREMOVE_STATIC_QUALIFIER +/*-----------------------------------------------------------*/ + + +/* Scheduler utilities. */ +extern void vPortYieldFromISR( void ); +extern void vPortYield( void ); + +#define portYIELD() vPortYield() + +#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() +/*-----------------------------------------------------------*/ + + +/* Critical section management. */ +extern void vPortDisableInterrupts( void ); +extern void vPortEnableInterrupts( void ); +#define portSET_INTERRUPT_MASK() ( vPortDisableInterrupts() ) +#define portCLEAR_INTERRUPT_MASK() ( vPortEnableInterrupts() ) + +extern portBASE_TYPE xPortSetInterruptMask( void ); +extern void vPortClearInterruptMask( portBASE_TYPE xMask ); + +#define portSET_INTERRUPT_MASK_FROM_ISR() xPortSetInterruptMask() +#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) vPortClearInterruptMask(x) + + +extern void vPortEnterCritical( void ); +extern void vPortExitCritical( void ); + +#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() +#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() +#define portENTER_CRITICAL() vPortEnterCritical() +#define portEXIT_CRITICAL() vPortExitCritical() +/*-----------------------------------------------------------*/ + +/* Task function macros as described on the FreeRTOS.org WEB site. */ +#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) +#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) + +#define portNOP() + +#define portOUTPUT_BYTE( a, b ) + +extern void vPortForciblyEndThread( void *pxTaskToDelete ); +#define traceTASK_DELETE( pxTaskToDelete ) vPortForciblyEndThread( pxTaskToDelete ) + +extern void vPortAddTaskHandle( void *pxTaskHandle ); +#define traceTASK_CREATE( pxNewTCB ) vPortAddTaskHandle( pxNewTCB ) + +/* Posix Signal definitions that can be changed or read as appropriate. */ +#define SIG_SUSPEND SIGUSR1 +#define SIG_RESUME SIGUSR2 + +/* Enable the following hash defines to make use of the real-time tick where time progresses at real-time. */ +#define SIG_TICK SIGALRM +#define TIMER_TYPE ITIMER_REAL +/* Enable the following hash defines to make use of the process tick where time progresses only when the process is executing. +#define SIG_TICK SIGVTALRM +#define TIMER_TYPE ITIMER_VIRTUAL */ +/* Enable the following hash defines to make use of the profile tick where time progresses when the process or system calls are executing. +#define SIG_TICK SIGPROF +#define TIMER_TYPE ITIMER_PROF */ + +/* Make use of times(man 2) to gather run-time statistics on the tasks. */ +extern void vPortFindTicksPerSecond( void ); +#undef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vPortFindTicksPerSecond() /* Nothing to do because the timer is already present. */ +extern unsigned long ulPortGetTimerValue( void ); +#undef portGET_RUN_TIME_COUNTER_VALUE +#define portGET_RUN_TIME_COUNTER_VALUE() ulPortGetTimerValue() /* Query the System time stats for this process. */ + +#ifdef __cplusplus +} +#endif + +#endif /* PORTMACRO_H */ + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c index e353235c9..8a6aa273b 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c @@ -1,113 +1,113 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -/* - * Implementation of pvPortMalloc() and vPortFree() that relies on the - * compilers own malloc() and free() implementations. - * - * This file can only be used if the linker is configured to to generate - * a heap memory area. - * - * See heap_2.c and heap_1.c for alternative implementations, and the memory - * management pages of http://www.FreeRTOS.org for more information. - */ - -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/*-----------------------------------------------------------*/ - -void *pvPortMalloc( size_t xWantedSize ) -{ -void *pvReturn; - - { - pvReturn = malloc( xWantedSize ); - } - - #if( configUSE_MALLOC_FAILED_HOOK == 1 ) - { - if( pvReturn == NULL ) - { - extern void vApplicationMallocFailedHook( void ); - vApplicationMallocFailedHook(); - } - } - #endif - - return pvReturn; -} -/*-----------------------------------------------------------*/ - -void vPortFree( void *pv ) -{ - if( pv ) - { - { - free( pv ); - } - } -} - - - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +/* + * Implementation of pvPortMalloc() and vPortFree() that relies on the + * compilers own malloc() and free() implementations. + * + * This file can only be used if the linker is configured to to generate + * a heap memory area. + * + * See heap_2.c and heap_1.c for alternative implementations, and the memory + * management pages of http://www.FreeRTOS.org for more information. + */ + +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +void *pvReturn; + + { + pvReturn = malloc( xWantedSize ); + } + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ + if( pv ) + { + { + free( pv ); + } + } +} + + + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/queue.c b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/queue.c index 2ae7c7030..c7ed600e8 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/queue.c +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/queue.c @@ -1,1539 +1,1539 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "croutine.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -/* Constants used with the cRxLock and cTxLock structure members. */ -#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) -#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) - -#define queueERRONEOUS_UNBLOCK ( -1 ) - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - -/* Effectively make a union out of the xQUEUE structure. */ -#define pxMutexHolder pcTail -#define uxQueueType pcHead -#define uxRecursiveCallCount pcReadFrom -#define queueQUEUE_IS_MUTEX NULL - -/* Semaphores do not actually store or copy data, so have an items size of -zero. */ -#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( 0 ) -#define queueDONT_BLOCK ( ( portTickType ) 0 ) -#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0 ) - -/* - * Definition of the queue used by the scheduler. - * Items are queued by copy, not reference. - */ -typedef struct QueueDefinition -{ - signed char *pcHead; /*< Points to the beginning of the queue storage area. */ - signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ - - signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ - signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ - - xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ - xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ - - volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ - unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ - unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ - - signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - -} xQUEUE; -/*-----------------------------------------------------------*/ - -/* - * Inside this file xQueueHandle is a pointer to a xQUEUE structure. - * To keep the definition private the API header file defines it as a - * pointer to void. - */ -typedef xQUEUE * xQueueHandle; - -/* - * Prototypes for public functions are included here so we don't have to - * include the API header file (as it defines xQueueHandle differently). These - * functions are documented in the API header file. - */ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateMutex( void ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * Co-routine queue functions differ from task queue functions. Co-routines are - * an optional component. - */ -#if configUSE_CO_ROUTINES == 1 - signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; -#endif - -/* - * The queue registry is just a means for kernel aware debuggers to locate - * queue structures. It has no other purpose so is an optional component. - */ -#if configQUEUE_REGISTRY_SIZE > 0 - - /* The type stored within the queue registry array. This allows a name - to be assigned to each queue making kernel aware debugging a little - more user friendly. */ - typedef struct QUEUE_REGISTRY_ITEM - { - signed char *pcQueueName; - xQueueHandle xHandle; - } xQueueRegistryItem; - - /* The queue registry is simply an array of xQueueRegistryItem structures. - The pcQueueName member of a structure being NULL is indicative of the - array position being vacant. */ - xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; - - /* Removes a queue from the registry by simply setting the pcQueueName - member to NULL. */ - static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; -#endif - -/* - * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not - * prevent an ISR from adding or removing items to the queue, but does prevent - * an ISR from removing tasks from the queue event lists. If an ISR finds a - * queue is locked it will instead increment the appropriate queue lock count - * to indicate that a task may require unblocking. When the queue in unlocked - * these lock counts are inspected, and the appropriate action taken. - */ -static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any data in a queue. - * - * @return pdTRUE if the queue contains no items, otherwise pdFALSE. - */ -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any space in a queue. - * - * @return pdTRUE if there is no space, otherwise pdFALSE; - */ -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Copies an item into the queue, either at the front of the queue or the - * back of the queue. - */ -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; - -/* - * Copies an item out of a queue. - */ -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; -/*-----------------------------------------------------------*/ - -/* - * Macro to mark a queue as locked. Locking a queue prevents an ISR from - * accessing the queue event lists. - */ -#define prvLockQueue( pxQueue ) \ - taskENTER_CRITICAL(); \ - { \ - if( ( pxQueue )->xRxLock == queueUNLOCKED ) \ - { \ - ( pxQueue )->xRxLock = queueLOCKED_UNMODIFIED; \ - } \ - if( ( pxQueue )->xTxLock == queueUNLOCKED ) \ - { \ - ( pxQueue )->xTxLock = queueLOCKED_UNMODIFIED; \ - } \ - } \ - taskEXIT_CRITICAL() -/*-----------------------------------------------------------*/ - - -/*----------------------------------------------------------- - * PUBLIC QUEUE MANAGEMENT API documented in queue.h - *----------------------------------------------------------*/ - -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) -{ -xQUEUE *pxNewQueue; -size_t xQueueSizeInBytes; -xQueueHandle xReturn = NULL; - - /* Allocate the new queue structure. */ - if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) - { - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Create the list of pointers to queue items. The queue is one byte - longer than asked for to make wrap checking easier/faster. */ - xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; - - pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); - if( pxNewQueue->pcHead != NULL ) - { - /* Initialise the queue members as described above where the - queue type is defined. */ - pxNewQueue->pcTail = pxNewQueue->pcHead + ( uxQueueLength * uxItemSize ); - pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->pcWriteTo = pxNewQueue->pcHead; - pxNewQueue->pcReadFrom = pxNewQueue->pcHead + ( ( uxQueueLength - ( unsigned portBASE_TYPE ) 1U ) * uxItemSize ); - pxNewQueue->uxLength = uxQueueLength; - pxNewQueue->uxItemSize = uxItemSize; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - /* Likewise ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); - - traceQUEUE_CREATE( pxNewQueue ); - xReturn = pxNewQueue; - } - else - { - traceQUEUE_CREATE_FAILED(); - vPortFree( pxNewQueue ); - } - } - } - - configASSERT( xReturn ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - xQueueHandle xQueueCreateMutex( void ) - { - xQUEUE *pxNewQueue; - - /* Allocate the new queue structure. */ - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Information required for priority inheritance. */ - pxNewQueue->pxMutexHolder = NULL; - pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; - - /* Queues used as a mutex no data is actually copied into or out - of the queue. */ - pxNewQueue->pcWriteTo = NULL; - pxNewQueue->pcReadFrom = NULL; - - /* Each mutex has a length of 1 (like a binary semaphore) and - an item size of 0 as nothing is actually copied into or out - of the mutex. */ - pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->uxLength = ( unsigned portBASE_TYPE ) 1U; - pxNewQueue->uxItemSize = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - /* Ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); - - /* Start with the semaphore in the expected state. */ - xQueueGenericSend( pxNewQueue, NULL, ( portTickType ) 0U, queueSEND_TO_BACK ); - - traceCREATE_MUTEX( pxNewQueue ); - } - else - { - traceCREATE_MUTEX_FAILED(); - } - - configASSERT( pxNewQueue ); - return pxNewQueue; - } - -#endif /* configUSE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_RECURSIVE_MUTEXES == 1 - - portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) - { - portBASE_TYPE xReturn; - - configASSERT( pxMutex ); - - /* If this is the task that holds the mutex then pxMutexHolder will not - change outside of this task. If this task does not hold the mutex then - pxMutexHolder can never coincidentally equal the tasks handle, and as - this is the only condition we are interested in it does not matter if - pxMutexHolder is accessed simultaneously by another task. Therefore no - mutual exclusion is required to test the pxMutexHolder variable. */ - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - traceGIVE_MUTEX_RECURSIVE( pxMutex ); - - /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to - the task handle, therefore no underflow check is required. Also, - uxRecursiveCallCount is only modified by the mutex holder, and as - there can only be one, no mutual exclusion is required to modify the - uxRecursiveCallCount member. */ - ( pxMutex->uxRecursiveCallCount )--; - - /* Have we unwound the call count? */ - if( pxMutex->uxRecursiveCallCount == 0 ) - { - /* Return the mutex. This will automatically unblock any other - task that might be waiting to access the mutex. */ - xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); - } - - xReturn = pdPASS; - } - else - { - /* We cannot give the mutex because we are not the holder. */ - xReturn = pdFAIL; - - traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_RECURSIVE_MUTEXES == 1 - - portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) - { - portBASE_TYPE xReturn; - - configASSERT( pxMutex ); - - /* Comments regarding mutual exclusion as per those within - xQueueGiveMutexRecursive(). */ - - traceTAKE_MUTEX_RECURSIVE( pxMutex ); - - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - ( pxMutex->uxRecursiveCallCount )++; - xReturn = pdPASS; - } - else - { - xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); - - /* pdPASS will only be returned if we successfully obtained the mutex, - we may have blocked to reach here. */ - if( xReturn == pdPASS ) - { - ( pxMutex->uxRecursiveCallCount )++; - } - else - { - traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ); - } - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_COUNTING_SEMAPHORES == 1 - - xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) - { - xQueueHandle pxHandle; - - pxHandle = xQueueCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH ); - - if( pxHandle != NULL ) - { - pxHandle->uxMessagesWaiting = uxInitialCount; - - traceCREATE_COUNTING_SEMAPHORE(); - } - else - { - traceCREATE_COUNTING_SEMAPHORE_FAILED(); - } - - configASSERT( pxHandle ); - return pxHandle; - } - -#endif /* configUSE_COUNTING_SEMAPHORES */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; - - configASSERT( pxQueue ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. Yes it is ok to do - this from within the critical section - the kernel - takes care of that. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting the - function. */ - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was full and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting - the function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was full and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - - /* Unlocking the queue means queue events can effect the - event list. It is possible that interrupts occurring now - remove this task from the event list again - but as the - scheduler is suspended the task will go onto the pending - ready last instead of the actual ready list. */ - prvUnlockQueue( pxQueue ); - - /* Resuming the scheduler will move tasks from the pending - ready list into the ready list - so it is feasible that this - task is already in a ready list before it yields - in which - case the yield will not cause a context switch unless there - is also a higher priority task in the pending ready list. */ - if( !xTaskResumeAll() ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - /* The timeout has expired. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - - /* Return to the original privilege level before exiting the - function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } -} -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - - configASSERT( pxQueue ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } - taskEXIT_CRITICAL(); - } - } - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - signed char *pcOriginalReadPosition; - - configASSERT( pxQueue ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - for( ;; ) - { - taskENTER_CRITICAL(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } - taskEXIT_CRITICAL(); - } - } - - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - configASSERT( pxQueue ); - configASSERT( pxHigherPriorityTaskWoken ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* Similar to xQueueGenericSend, except we don't block if there is no room - in the queue. Also we don't directly wake a task that was blocked on a - queue read, instead we return a flag to say whether a context switch is - required or not (i.e. has a task with a higher priority than us been woken - by this post). */ - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND_FROM_ISR( pxQueue ); - - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If the queue is locked we do not alter the event list. This will - be done when the queue is unlocked later. */ - if( pxQueue->xTxLock == queueUNLOCKED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - *pxHigherPriorityTaskWoken = pdTRUE; - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was posted while it was locked. */ - ++( pxQueue->xTxLock ); - } - - xReturn = pdPASS; - } - else - { - traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); - xReturn = errQUEUE_FULL; - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; -signed char *pcOriginalReadPosition; - - configASSERT( pxQueue ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there data in the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was empty and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was empty and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - { - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - } - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - prvUnlockQueue( pxQueue ); - if( !xTaskResumeAll() ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - configASSERT( pxQueue ); - configASSERT( pxTaskWoken ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - /* We cannot block from an ISR, so check there is data available. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - --( pxQueue->uxMessagesWaiting ); - - /* If the queue is locked we will not modify the event list. Instead - we update the lock count so the task that unlocks the queue will know - that an ISR has removed data while the queue was locked. */ - if( pxQueue->xRxLock == queueUNLOCKED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than us so - force a context switch. */ - *pxTaskWoken = pdTRUE; - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was removed while it was locked. */ - ++( pxQueue->xRxLock ); - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - configASSERT( pxQueue ); - - taskENTER_CRITICAL(); - uxReturn = pxQueue->uxMessagesWaiting; - taskEXIT_CRITICAL(); - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - configASSERT( pxQueue ); - - uxReturn = pxQueue->uxMessagesWaiting; - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -void vQueueDelete( xQueueHandle pxQueue ) -{ - configASSERT( pxQueue ); - - traceQUEUE_DELETE( pxQueue ); - vQueueUnregisterQueue( pxQueue ); - vPortFree( pxQueue->pcHead ); - vPortFree( pxQueue ); -} -/*-----------------------------------------------------------*/ - -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) -{ - if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) - { - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* The mutex is no longer being held. */ - vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); - pxQueue->pxMutexHolder = NULL; - } - } - #endif - } - else if( xPosition == queueSEND_TO_BACK ) - { - memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcWriteTo += pxQueue->uxItemSize; - if( pxQueue->pcWriteTo >= pxQueue->pcTail ) - { - pxQueue->pcWriteTo = pxQueue->pcHead; - } - } - else - { - memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcReadFrom -= pxQueue->uxItemSize; - if( pxQueue->pcReadFrom < pxQueue->pcHead ) - { - pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); - } - } - - ++( pxQueue->uxMessagesWaiting ); -} -/*-----------------------------------------------------------*/ - -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) -{ - if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) - { - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - } -} -/*-----------------------------------------------------------*/ - -static void prvUnlockQueue( xQueueHandle pxQueue ) -{ - /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ - - /* The lock counts contains the number of extra data items placed or - removed from the queue while the queue was locked. When a queue is - locked items can be added or removed, but the event lists cannot be - updated. */ - taskENTER_CRITICAL(); - { - /* See if data was added to the queue while it was locked. */ - while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) - { - /* Data was posted while the queue was locked. Are any tasks - blocked waiting for data to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - vTaskMissedYield(); - } - - --( pxQueue->xTxLock ); - } - else - { - break; - } - } - - pxQueue->xTxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); - - /* Do the same for the Rx lock. */ - taskENTER_CRITICAL(); - { - while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - vTaskMissedYield(); - } - - --( pxQueue->xRxLock ); - } - else - { - break; - } - } - - pxQueue->xRxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - configASSERT( pxQueue ); - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - configASSERT( pxQueue ); - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already full we may have to block. A critical section - is required to prevent an interrupt removing something from the queue - between the check to see if the queue is full and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( prvIsQueueFull( pxQueue ) ) - { - /* The queue is full - do we want to block or just leave without - posting? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is called from a coroutine we cannot block directly, but - return indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - /* There is room in the queue, copy the data into the queue. */ - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - xReturn = pdPASS; - - /* Were any co-routines waiting for data to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The co-routine waiting has a higher priority so record - that a yield might be appropriate. */ - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = errQUEUE_FULL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already empty we may have to block. A critical section - is required to prevent an interrupt adding something to the queue - between the check to see if the queue is empty and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) - { - /* There are no messages in the queue, do we want to block or just - leave with nothing? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is a co-routine we cannot block directly, but return - indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Data is available from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - xReturn = pdPASS; - - /* Were any co-routines waiting for space to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = pdFAIL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - - - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) -{ - /* Cannot block within an ISR so if there is no space on the queue then - exit without doing anything. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - - /* We only want to wake one co-routine per ISR, so check that a - co-routine has not already been woken. */ - if( !xCoRoutinePreviouslyWoken ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - return pdTRUE; - } - } - } - } - - return xCoRoutinePreviouslyWoken; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) -{ -signed portBASE_TYPE xReturn; - - /* We cannot block from an ISR, so check there is data available. If - not then just leave without doing anything. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Copy the data from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - if( !( *pxCoRoutineWoken ) ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - *pxCoRoutineWoken = pdTRUE; - } - } - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - } - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) - { - unsigned portBASE_TYPE ux; - - /* See if there is an empty space in the registry. A NULL name denotes - a free slot. */ - for( ux = ( unsigned portBASE_TYPE ) 0U; ux < configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].pcQueueName == NULL ) - { - /* Store the information on this queue. */ - xQueueRegistry[ ux ].pcQueueName = pcQueueName; - xQueueRegistry[ ux ].xHandle = xQueue; - break; - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - static void vQueueUnregisterQueue( xQueueHandle xQueue ) - { - unsigned portBASE_TYPE ux; - - /* See if the handle of the queue being unregistered in actually in the - registry. */ - for( ux = ( unsigned portBASE_TYPE ) 0U; ux < configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].xHandle == xQueue ) - { - /* Set the name to NULL to show that this slot if free again. */ - xQueueRegistry[ ux ].pcQueueName = NULL; - break; - } - } - - } - -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_TIMERS == 1 - - void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) - { - /* This function should not be called by application code hence the - 'Restricted' in its name. It is not part of the public API. It is - designed for use by kernel code, and has special calling requirements. - It can result in vListInsert() being called on a list that can only - possibly ever have one item in it, so the list will be fast, but even - so it should be called with the scheduler locked and not from a critical - section. */ - - /* Only do anything if there are no messages in the queue. This function - will not actually cause the task to block, just place it on a blocked - list. It will not block until the scheduler is unlocked - at which - time a yield will be performed. If an item is added to the queue while - the queue is locked, and the calling task blocks on the queue, then the - calling task will be immediately unblocked when the queue is unlocked. */ - prvLockQueue( pxQueue ); - if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0U ) - { - /* There is nothing in the queue, block for the specified period. */ - vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - } - prvUnlockQueue( pxQueue ); - } - -#endif - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "croutine.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +/* Constants used with the cRxLock and cTxLock structure members. */ +#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) +#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) + +#define queueERRONEOUS_UNBLOCK ( -1 ) + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + +/* Effectively make a union out of the xQUEUE structure. */ +#define pxMutexHolder pcTail +#define uxQueueType pcHead +#define uxRecursiveCallCount pcReadFrom +#define queueQUEUE_IS_MUTEX NULL + +/* Semaphores do not actually store or copy data, so have an items size of +zero. */ +#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( 0 ) +#define queueDONT_BLOCK ( ( portTickType ) 0 ) +#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0 ) + +/* + * Definition of the queue used by the scheduler. + * Items are queued by copy, not reference. + */ +typedef struct QueueDefinition +{ + signed char *pcHead; /*< Points to the beginning of the queue storage area. */ + signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ + + signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ + signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ + + xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ + xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ + + volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ + unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ + unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ + + signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + +} xQUEUE; +/*-----------------------------------------------------------*/ + +/* + * Inside this file xQueueHandle is a pointer to a xQUEUE structure. + * To keep the definition private the API header file defines it as a + * pointer to void. + */ +typedef xQUEUE * xQueueHandle; + +/* + * Prototypes for public functions are included here so we don't have to + * include the API header file (as it defines xQueueHandle differently). These + * functions are documented in the API header file. + */ +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateMutex( void ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * Co-routine queue functions differ from task queue functions. Co-routines are + * an optional component. + */ +#if configUSE_CO_ROUTINES == 1 + signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; +#endif + +/* + * The queue registry is just a means for kernel aware debuggers to locate + * queue structures. It has no other purpose so is an optional component. + */ +#if configQUEUE_REGISTRY_SIZE > 0 + + /* The type stored within the queue registry array. This allows a name + to be assigned to each queue making kernel aware debugging a little + more user friendly. */ + typedef struct QUEUE_REGISTRY_ITEM + { + signed char *pcQueueName; + xQueueHandle xHandle; + } xQueueRegistryItem; + + /* The queue registry is simply an array of xQueueRegistryItem structures. + The pcQueueName member of a structure being NULL is indicative of the + array position being vacant. */ + xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; + + /* Removes a queue from the registry by simply setting the pcQueueName + member to NULL. */ + static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; +#endif + +/* + * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not + * prevent an ISR from adding or removing items to the queue, but does prevent + * an ISR from removing tasks from the queue event lists. If an ISR finds a + * queue is locked it will instead increment the appropriate queue lock count + * to indicate that a task may require unblocking. When the queue in unlocked + * these lock counts are inspected, and the appropriate action taken. + */ +static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any data in a queue. + * + * @return pdTRUE if the queue contains no items, otherwise pdFALSE. + */ +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any space in a queue. + * + * @return pdTRUE if there is no space, otherwise pdFALSE; + */ +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Copies an item into the queue, either at the front of the queue or the + * back of the queue. + */ +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; + +/* + * Copies an item out of a queue. + */ +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; +/*-----------------------------------------------------------*/ + +/* + * Macro to mark a queue as locked. Locking a queue prevents an ISR from + * accessing the queue event lists. + */ +#define prvLockQueue( pxQueue ) \ + taskENTER_CRITICAL(); \ + { \ + if( ( pxQueue )->xRxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->xRxLock = queueLOCKED_UNMODIFIED; \ + } \ + if( ( pxQueue )->xTxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->xTxLock = queueLOCKED_UNMODIFIED; \ + } \ + } \ + taskEXIT_CRITICAL() +/*-----------------------------------------------------------*/ + + +/*----------------------------------------------------------- + * PUBLIC QUEUE MANAGEMENT API documented in queue.h + *----------------------------------------------------------*/ + +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) +{ +xQUEUE *pxNewQueue; +size_t xQueueSizeInBytes; +xQueueHandle xReturn = NULL; + + /* Allocate the new queue structure. */ + if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) + { + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Create the list of pointers to queue items. The queue is one byte + longer than asked for to make wrap checking easier/faster. */ + xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; + + pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); + if( pxNewQueue->pcHead != NULL ) + { + /* Initialise the queue members as described above where the + queue type is defined. */ + pxNewQueue->pcTail = pxNewQueue->pcHead + ( uxQueueLength * uxItemSize ); + pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; + pxNewQueue->pcWriteTo = pxNewQueue->pcHead; + pxNewQueue->pcReadFrom = pxNewQueue->pcHead + ( ( uxQueueLength - ( unsigned portBASE_TYPE ) 1U ) * uxItemSize ); + pxNewQueue->uxLength = uxQueueLength; + pxNewQueue->uxItemSize = uxItemSize; + pxNewQueue->xRxLock = queueUNLOCKED; + pxNewQueue->xTxLock = queueUNLOCKED; + + /* Likewise ensure the event queues start with the correct state. */ + vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + + traceQUEUE_CREATE( pxNewQueue ); + xReturn = pxNewQueue; + } + else + { + traceQUEUE_CREATE_FAILED(); + vPortFree( pxNewQueue ); + } + } + } + + configASSERT( xReturn ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + xQueueHandle xQueueCreateMutex( void ) + { + xQUEUE *pxNewQueue; + + /* Allocate the new queue structure. */ + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Information required for priority inheritance. */ + pxNewQueue->pxMutexHolder = NULL; + pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; + + /* Queues used as a mutex no data is actually copied into or out + of the queue. */ + pxNewQueue->pcWriteTo = NULL; + pxNewQueue->pcReadFrom = NULL; + + /* Each mutex has a length of 1 (like a binary semaphore) and + an item size of 0 as nothing is actually copied into or out + of the mutex. */ + pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; + pxNewQueue->uxLength = ( unsigned portBASE_TYPE ) 1U; + pxNewQueue->uxItemSize = ( unsigned portBASE_TYPE ) 0U; + pxNewQueue->xRxLock = queueUNLOCKED; + pxNewQueue->xTxLock = queueUNLOCKED; + + /* Ensure the event queues start with the correct state. */ + vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + + /* Start with the semaphore in the expected state. */ + xQueueGenericSend( pxNewQueue, NULL, ( portTickType ) 0U, queueSEND_TO_BACK ); + + traceCREATE_MUTEX( pxNewQueue ); + } + else + { + traceCREATE_MUTEX_FAILED(); + } + + configASSERT( pxNewQueue ); + return pxNewQueue; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_RECURSIVE_MUTEXES == 1 + + portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) + { + portBASE_TYPE xReturn; + + configASSERT( pxMutex ); + + /* If this is the task that holds the mutex then pxMutexHolder will not + change outside of this task. If this task does not hold the mutex then + pxMutexHolder can never coincidentally equal the tasks handle, and as + this is the only condition we are interested in it does not matter if + pxMutexHolder is accessed simultaneously by another task. Therefore no + mutual exclusion is required to test the pxMutexHolder variable. */ + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + traceGIVE_MUTEX_RECURSIVE( pxMutex ); + + /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to + the task handle, therefore no underflow check is required. Also, + uxRecursiveCallCount is only modified by the mutex holder, and as + there can only be one, no mutual exclusion is required to modify the + uxRecursiveCallCount member. */ + ( pxMutex->uxRecursiveCallCount )--; + + /* Have we unwound the call count? */ + if( pxMutex->uxRecursiveCallCount == 0 ) + { + /* Return the mutex. This will automatically unblock any other + task that might be waiting to access the mutex. */ + xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); + } + + xReturn = pdPASS; + } + else + { + /* We cannot give the mutex because we are not the holder. */ + xReturn = pdFAIL; + + traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_RECURSIVE_MUTEXES == 1 + + portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) + { + portBASE_TYPE xReturn; + + configASSERT( pxMutex ); + + /* Comments regarding mutual exclusion as per those within + xQueueGiveMutexRecursive(). */ + + traceTAKE_MUTEX_RECURSIVE( pxMutex ); + + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + ( pxMutex->uxRecursiveCallCount )++; + xReturn = pdPASS; + } + else + { + xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); + + /* pdPASS will only be returned if we successfully obtained the mutex, + we may have blocked to reach here. */ + if( xReturn == pdPASS ) + { + ( pxMutex->uxRecursiveCallCount )++; + } + else + { + traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_COUNTING_SEMAPHORES == 1 + + xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) + { + xQueueHandle pxHandle; + + pxHandle = xQueueCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH ); + + if( pxHandle != NULL ) + { + pxHandle->uxMessagesWaiting = uxInitialCount; + + traceCREATE_COUNTING_SEMAPHORE(); + } + else + { + traceCREATE_COUNTING_SEMAPHORE_FAILED(); + } + + configASSERT( pxHandle ); + return pxHandle; + } + +#endif /* configUSE_COUNTING_SEMAPHORES */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. Yes it is ok to do + this from within the critical section - the kernel + takes care of that. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting the + function. */ + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was full and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting + the function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was full and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + + /* Unlocking the queue means queue events can effect the + event list. It is possible that interrupts occurring now + remove this task from the event list again - but as the + scheduler is suspended the task will go onto the pending + ready last instead of the actual ready list. */ + prvUnlockQueue( pxQueue ); + + /* Resuming the scheduler will move tasks from the pending + ready list into the ready list - so it is feasible that this + task is already in a ready list before it yields - in which + case the yield will not cause a context switch unless there + is also a higher priority task in the pending ready list. */ + if( !xTaskResumeAll() ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* The timeout has expired. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + /* Return to the original privilege level before exiting the + function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } +} +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } + taskEXIT_CRITICAL(); + } + } + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + signed char *pcOriginalReadPosition; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + for( ;; ) + { + taskENTER_CRITICAL(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } + taskEXIT_CRITICAL(); + } + } + + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + configASSERT( pxQueue ); + configASSERT( pxHigherPriorityTaskWoken ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* Similar to xQueueGenericSend, except we don't block if there is no room + in the queue. Also we don't directly wake a task that was blocked on a + queue read, instead we return a flag to say whether a context switch is + required or not (i.e. has a task with a higher priority than us been woken + by this post). */ + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND_FROM_ISR( pxQueue ); + + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If the queue is locked we do not alter the event list. This will + be done when the queue is unlocked later. */ + if( pxQueue->xTxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + *pxHigherPriorityTaskWoken = pdTRUE; + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was posted while it was locked. */ + ++( pxQueue->xTxLock ); + } + + xReturn = pdPASS; + } + else + { + traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); + xReturn = errQUEUE_FULL; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; +signed char *pcOriginalReadPosition; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there data in the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was empty and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was empty and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + { + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + } + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( !xTaskResumeAll() ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + configASSERT( pxQueue ); + configASSERT( pxTaskWoken ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* We cannot block from an ISR, so check there is data available. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + --( pxQueue->uxMessagesWaiting ); + + /* If the queue is locked we will not modify the event list. Instead + we update the lock count so the task that unlocks the queue will know + that an ISR has removed data while the queue was locked. */ + if( pxQueue->xRxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than us so + force a context switch. */ + *pxTaskWoken = pdTRUE; + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was removed while it was locked. */ + ++( pxQueue->xRxLock ); + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + uxReturn = pxQueue->uxMessagesWaiting; + taskEXIT_CRITICAL(); + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + configASSERT( pxQueue ); + + uxReturn = pxQueue->uxMessagesWaiting; + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +void vQueueDelete( xQueueHandle pxQueue ) +{ + configASSERT( pxQueue ); + + traceQUEUE_DELETE( pxQueue ); + vQueueUnregisterQueue( pxQueue ); + vPortFree( pxQueue->pcHead ); + vPortFree( pxQueue ); +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) +{ + if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) + { + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* The mutex is no longer being held. */ + vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); + pxQueue->pxMutexHolder = NULL; + } + } + #endif + } + else if( xPosition == queueSEND_TO_BACK ) + { + memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcWriteTo += pxQueue->uxItemSize; + if( pxQueue->pcWriteTo >= pxQueue->pcTail ) + { + pxQueue->pcWriteTo = pxQueue->pcHead; + } + } + else + { + memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcReadFrom -= pxQueue->uxItemSize; + if( pxQueue->pcReadFrom < pxQueue->pcHead ) + { + pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); + } + } + + ++( pxQueue->uxMessagesWaiting ); +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) +{ + if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) + { + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + } +} +/*-----------------------------------------------------------*/ + +static void prvUnlockQueue( xQueueHandle pxQueue ) +{ + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ + + /* The lock counts contains the number of extra data items placed or + removed from the queue while the queue was locked. When a queue is + locked items can be added or removed, but the event lists cannot be + updated. */ + taskENTER_CRITICAL(); + { + /* See if data was added to the queue while it was locked. */ + while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) + { + /* Data was posted while the queue was locked. Are any tasks + blocked waiting for data to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + vTaskMissedYield(); + } + + --( pxQueue->xTxLock ); + } + else + { + break; + } + } + + pxQueue->xTxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); + + /* Do the same for the Rx lock. */ + taskENTER_CRITICAL(); + { + while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + vTaskMissedYield(); + } + + --( pxQueue->xRxLock ); + } + else + { + break; + } + } + + pxQueue->xRxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + configASSERT( pxQueue ); + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + configASSERT( pxQueue ); + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already full we may have to block. A critical section + is required to prevent an interrupt removing something from the queue + between the check to see if the queue is full and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( prvIsQueueFull( pxQueue ) ) + { + /* The queue is full - do we want to block or just leave without + posting? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is called from a coroutine we cannot block directly, but + return indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + /* There is room in the queue, copy the data into the queue. */ + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + xReturn = pdPASS; + + /* Were any co-routines waiting for data to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The co-routine waiting has a higher priority so record + that a yield might be appropriate. */ + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = errQUEUE_FULL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already empty we may have to block. A critical section + is required to prevent an interrupt adding something to the queue + between the check to see if the queue is empty and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) + { + /* There are no messages in the queue, do we want to block or just + leave with nothing? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is a co-routine we cannot block directly, but return + indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Data is available from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + xReturn = pdPASS; + + /* Were any co-routines waiting for space to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = pdFAIL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + + + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) +{ + /* Cannot block within an ISR so if there is no space on the queue then + exit without doing anything. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + + /* We only want to wake one co-routine per ISR, so check that a + co-routine has not already been woken. */ + if( !xCoRoutinePreviouslyWoken ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + return pdTRUE; + } + } + } + } + + return xCoRoutinePreviouslyWoken; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) +{ +signed portBASE_TYPE xReturn; + + /* We cannot block from an ISR, so check there is data available. If + not then just leave without doing anything. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Copy the data from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + if( !( *pxCoRoutineWoken ) ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + *pxCoRoutineWoken = pdTRUE; + } + } + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) + { + unsigned portBASE_TYPE ux; + + /* See if there is an empty space in the registry. A NULL name denotes + a free slot. */ + for( ux = ( unsigned portBASE_TYPE ) 0U; ux < configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].pcQueueName == NULL ) + { + /* Store the information on this queue. */ + xQueueRegistry[ ux ].pcQueueName = pcQueueName; + xQueueRegistry[ ux ].xHandle = xQueue; + break; + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + static void vQueueUnregisterQueue( xQueueHandle xQueue ) + { + unsigned portBASE_TYPE ux; + + /* See if the handle of the queue being unregistered in actually in the + registry. */ + for( ux = ( unsigned portBASE_TYPE ) 0U; ux < configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].xHandle == xQueue ) + { + /* Set the name to NULL to show that this slot if free again. */ + xQueueRegistry[ ux ].pcQueueName = NULL; + break; + } + } + + } + +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_TIMERS == 1 + + void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) + { + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements. + It can result in vListInsert() being called on a list that can only + possibly ever have one item in it, so the list will be fast, but even + so it should be called with the scheduler locked and not from a critical + section. */ + + /* Only do anything if there are no messages in the queue. This function + will not actually cause the task to block, just place it on a blocked + list. It will not block until the scheduler is unlocked - at which + time a yield will be performed. If an item is added to the queue while + the queue is locked, and the calling task blocks on the queue, then the + calling task will be immediately unblocked when the queue is unlocked. */ + prvLockQueue( pxQueue ); + if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0U ) + { + /* There is nothing in the queue, block for the specified period. */ + vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + } + prvUnlockQueue( pxQueue ); + } + +#endif + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/task.c b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/task.c index 13d6713f8..f6f28684a 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/task.c +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/task.c @@ -1,2639 +1,2639 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#include -#include -#include -#include -#include -#include -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "timers.h" -#include "StackMacros.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* - * Macro to define the amount of stack available to the idle task. - */ -#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE - -/* - * Task control block. A task control block (TCB) is allocated to each task, - * and stores the context of the task. - */ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - - #if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ - #endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - - #if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ - #endif - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; - #endif - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ - #endif - - #if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ - #endif - -} tskTCB; - - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - -/*lint -e956 */ -PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; - -/* Lists for ready and blocked tasks. --------------------*/ - -PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ -PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ - -#if ( INCLUDE_vTaskDelete == 1 ) - - PRIVILEGED_DATA static volatile xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ - PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0; - -#endif - -#if ( INCLUDE_vTaskSuspend == 1 ) - - PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ - -#endif - -/* File private variables. --------------------------------*/ -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) portMAX_DELAY; - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - PRIVILEGED_DATA static char pcStatsString[ 50 ] ; - PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; - -#endif - -/* Debugging and trace facilities private variables and macros. ------------*/ - -/* - * The value used to fill the stack of a task when the task is created. This - * is used purely for checking the high water mark for tasks. - */ -#define tskSTACK_FILL_BYTE ( 0xa5U ) - -/* - * Macros used by vListTask to indicate which state a task is in. - */ -#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) -#define tskREADY_CHAR ( ( signed char ) 'R' ) -#define tskDELETED_CHAR ( ( signed char ) 'D' ) -#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) - -/* - * Macros and private variables used by the trace facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define tskSIZE_OF_EACH_TRACE_LINE ( ( unsigned long ) ( sizeof( unsigned long ) + sizeof( unsigned long ) ) ) - PRIVILEGED_DATA static volatile signed char * volatile pcTraceBuffer; - PRIVILEGED_DATA static signed char *pcTraceBufferStart; - PRIVILEGED_DATA static signed char *pcTraceBufferEnd; - PRIVILEGED_DATA static signed portBASE_TYPE xTracing = pdFALSE; - static unsigned portBASE_TYPE uxPreviousTask = 255U; - PRIVILEGED_DATA static char pcStatusString[ 50 ]; - -#endif - -/*-----------------------------------------------------------*/ - -/* - * Macro that writes a trace of scheduler activity to a buffer. This trace - * shows which task is running when and is very useful as a debugging tool. - * As this macro is called each context switch it is a good idea to undefine - * it if not using the facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define vWriteTraceToBuffer() \ - { \ - if( xTracing ) \ - { \ - if( uxPreviousTask != pxCurrentTCB->uxTCBNumber ) \ - { \ - if( ( pcTraceBuffer + tskSIZE_OF_EACH_TRACE_LINE ) < pcTraceBufferEnd ) \ - { \ - uxPreviousTask = pxCurrentTCB->uxTCBNumber; \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) xTickCount; \ - pcTraceBuffer += sizeof( unsigned long ); \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) uxPreviousTask; \ - pcTraceBuffer += sizeof( unsigned long ); \ - } \ - else \ - { \ - xTracing = pdFALSE; \ - } \ - } \ - } \ - } - -#else - - #define vWriteTraceToBuffer() - -#endif -/*-----------------------------------------------------------*/ - -/* - * Place the task represented by pxTCB into the appropriate ready queue for - * the task. It is inserted at the end of the list. One quirk of this is - * that if the task being inserted is at the same priority as the currently - * executing task, then it will only be rescheduled after the currently - * executing task has been rescheduled. - */ -#define prvAddTaskToReadyQueue( pxTCB ) \ - if( ( pxTCB )->uxPriority > uxTopReadyPriority ) \ - { \ - uxTopReadyPriority = ( pxTCB )->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xGenericListItem ) ) -/*-----------------------------------------------------------*/ - -/* - * Macro that looks at the list of tasks that are currently delayed to see if - * any require waking. - * - * Tasks are stored in the queue in the order of their wake time - meaning - * once one tasks has been found whose timer has not expired we need not look - * any further down the list. - */ -#define prvCheckDelayedTasks() \ -{ \ -portTickType xItemValue; \ - \ - /* Is the tick count greater than or equal to the wake time of the first \ - task referenced from the delayed tasks list? */ \ - if( xTickCount >= xNextTaskUnblockTime ) \ - { \ - for( ;; ) \ - { \ - if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) \ - { \ - /* The delayed list is empty. Set xNextTaskUnblockTime to the \ - maximum possible value so it is extremely unlikely that the \ - if( xTickCount >= xNextTaskUnblockTime ) test will pass next \ - time through. */ \ - xNextTaskUnblockTime = portMAX_DELAY; \ - break; \ - } \ - else \ - { \ - /* The delayed list is not empty, get the value of the item at \ - the head of the delayed list. This is the time at which the \ - task at the head of the delayed list should be removed from \ - the Blocked state. */ \ - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); \ - xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); \ - \ - if( xTickCount < xItemValue ) \ - { \ - /* It is not time to unblock this item yet, but the item \ - value is the time at which the task at the head of the \ - blocked list should be removed from the Blocked state - \ - so record the item value in xNextTaskUnblockTime. */ \ - xNextTaskUnblockTime = xItemValue; \ - break; \ - } \ - \ - /* It is time to remove the item from the Blocked state. */ \ - vListRemove( &( pxTCB->xGenericListItem ) ); \ - \ - /* Is the task waiting on an event also? */ \ - if( pxTCB->xEventListItem.pvContainer ) \ - { \ - vListRemove( &( pxTCB->xEventListItem ) ); \ - } \ - prvAddTaskToReadyQueue( pxTCB ); \ - } \ - } \ - } \ -} -/*-----------------------------------------------------------*/ - -/* - * Several functions take an xTaskHandle parameter that can optionally be NULL, - * where NULL is used to indicate that the handle of the currently executing - * task should be used in place of the parameter. This macro simply checks to - * see if the parameter is NULL and returns a pointer to the appropriate TCB. - */ -#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) ( pxHandle ) ) - -/* Callback function prototypes. --------------------------*/ -extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); -extern void vApplicationTickHook( void ); - -/* File private functions. --------------------------------*/ - -/* - * Utility to ready a TCB for a given task. Mainly just copies the parameters - * into the TCB structure. - */ -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first task. - */ -static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; - -/* - * The idle task, which as all tasks is implemented as a never ending loop. - * The idle task is automatically created and added to the ready lists upon - * creation of the first user task. - * - * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); - -/* - * Utility to free all memory allocated by the scheduler to hold a TCB, - * including the stack pointed to by the TCB. - * - * This does not free memory allocated by the task itself (i.e. memory - * allocated by calls to pvPortMalloc from within the tasks application code). - */ -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) - - static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; - -#endif - -/* - * Used only by the idle task. This checks to see if anything has been placed - * in the list of tasks waiting to be deleted. If so the task is cleaned up - * and its TCB deleted. - */ -static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; - -/* - * The currently executing task is entering the Blocked state. Add the task to - * either the current or the overflow delayed task list. - */ -static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) PRIVILEGED_FUNCTION; - -/* - * Allocates memory from the heap for a TCB and associated stack. Checks the - * allocation was successful. - */ -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; - -/* - * Called from vTaskList. vListTasks details all the tasks currently under - * control of the scheduler. The tasks may be in one of a number of lists. - * prvListTaskWithinSingleList accepts a list and details the tasks from - * within just that list. - * - * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM - * NORMAL APPLICATION CODE. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; - -#endif - -/* - * When a task is created, the stack of the task is filled with a known value. - * This function determines the 'high water mark' of the task stack by - * determining how much of the stack remains at the original preset value. - */ -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; - -#endif - - -/*lint +e956 */ - - - -/*----------------------------------------------------------- - * TASK CREATION API documented in task.h - *----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) -{ -signed portBASE_TYPE xReturn; -tskTCB * pxNewTCB; - - configASSERT( pxTaskCode ); - configASSERT( ( uxPriority < configMAX_PRIORITIES ) ); - - /* Allocate the memory required by the TCB and stack for the new task, - checking that the allocation was successful. */ - pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); - - if( pxNewTCB != NULL ) - { - portSTACK_TYPE *pxTopOfStack; - - #if( portUSING_MPU_WRAPPERS == 1 ) - /* Should the task be created in privileged mode? */ - portBASE_TYPE xRunPrivileged; - if( ( uxPriority & portPRIVILEGE_BIT ) != 0x00 ) - { - xRunPrivileged = pdTRUE; - } - else - { - xRunPrivileged = pdFALSE; - } - uxPriority &= ~portPRIVILEGE_BIT; - #endif /* portUSING_MPU_WRAPPERS == 1 */ - - /* Calculate the top of stack address. This depends on whether the - stack grows from high memory to low (as per the 80x86) or visa versa. - portSTACK_GROWTH is used to make the result positive or negative as - required by the port. */ - #if( portSTACK_GROWTH < 0 ) - { - pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - ( unsigned short ) 1 ); - pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( unsigned long ) pxTopOfStack ) & ( ( unsigned long ) ~portBYTE_ALIGNMENT_MASK ) ); - - /* Check the alignment of the calculated top of stack is correct. */ - configASSERT( ( ( ( unsigned long ) pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - } - #else - { - pxTopOfStack = pxNewTCB->pxStack; - - /* Check the alignment of the stack buffer is correct. */ - configASSERT( ( ( ( unsigned long ) pxNewTCB->pxStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - - /* If we want to use stack checking on architectures that use - a positive stack growth direction then we also need to store the - other extreme of the stack space. */ - pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - } - #endif - - /* Setup the newly allocated TCB with the initial state of the task. */ - prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); - - /* Initialize the TCB stack to look as if the task was already running, - but had been interrupted by the scheduler. The return address is set - to the start of the task function. Once the stack has been initialised - the top of stack variable is updated. */ - #if( portUSING_MPU_WRAPPERS == 1 ) - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); - } - #else - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); - } - #endif - - /* Check the alignment of the initialised stack. */ - configASSERT( ( ( ( unsigned long ) pxNewTCB->pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - - if( ( void * ) pxCreatedTask != NULL ) - { - /* Pass the TCB out - in an anonymous way. The calling function/ - task can use this as a handle to delete the task later if - required.*/ - *pxCreatedTask = ( xTaskHandle ) pxNewTCB; - } - - /* We are going to manipulate the task queues to add this task to a - ready list, so must make sure no interrupts occur. */ - taskENTER_CRITICAL(); - { - uxCurrentNumberOfTasks++; - if( pxCurrentTCB == NULL ) - { - /* There are no other tasks, or all the other tasks are in - the suspended state - make this the current task. */ - pxCurrentTCB = pxNewTCB; - - if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) - { - /* This is the first task to be created so do the preliminary - initialisation required. We will not recover if this call - fails, but we will report the failure. */ - prvInitialiseTaskLists(); - } - } - else - { - /* If the scheduler is not already running, make this task the - current task if it is the highest priority task to be created - so far. */ - if( xSchedulerRunning == pdFALSE ) - { - if( pxCurrentTCB->uxPriority <= uxPriority ) - { - pxCurrentTCB = pxNewTCB; - } - } - } - - /* Remember the top priority to make context switching faster. Use - the priority in pxNewTCB as this has been capped to a valid value. */ - if( pxNewTCB->uxPriority > uxTopUsedPriority ) - { - uxTopUsedPriority = pxNewTCB->uxPriority; - } - - #if ( configUSE_TRACE_FACILITY == 1 ) - { - /* Add a counter into the TCB for tracing only. */ - pxNewTCB->uxTCBNumber = uxTaskNumber; - } - #endif - uxTaskNumber++; - - prvAddTaskToReadyQueue( pxNewTCB ); - - xReturn = pdPASS; - traceTASK_CREATE( pxNewTCB ); - } - taskEXIT_CRITICAL(); - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - traceTASK_CREATE_FAILED(); - } - - if( xReturn == pdPASS ) - { - if( xSchedulerRunning != pdFALSE ) - { - /* If the created task is of a higher priority than the current task - then it should run now. */ - if( pxCurrentTCB->uxPriority < uxPriority ) - { - portYIELD_WITHIN_API(); - } - } - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - void vTaskDelete( xTaskHandle pxTaskToDelete ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - deleted. */ - if( pxTaskToDelete == pxCurrentTCB ) - { - pxTaskToDelete = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); - - /* Remove task from the ready list and place in the termination list. - This will stop the task from be scheduled. The idle task will check - the termination list and free up any memory allocated by the - scheduler for the TCB and stack. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); - - /* Increment the ucTasksDeleted variable so the idle task knows - there is a task that has been deleted and that it should therefore - check the xTasksWaitingTermination list. */ - ++uxTasksDeleted; - - /* Increment the uxTaskNumberVariable also so kernel aware debuggers - can detect that the task lists need re-generating. */ - uxTaskNumber++; - - traceTASK_DELETE( pxTCB ); - } - taskEXIT_CRITICAL(); - - /* Force a reschedule if we have just deleted the current task. */ - if( xSchedulerRunning != pdFALSE ) - { - if( ( void * ) pxTaskToDelete == NULL ) - { - portYIELD_WITHIN_API(); - } - } - } - -#endif - - - - - - -/*----------------------------------------------------------- - * TASK CONTROL API documented in task.h - *----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelayUntil == 1 ) - - void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) - { - portTickType xTimeToWake; - portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; - - configASSERT( pxPreviousWakeTime ); - configASSERT( ( xTimeIncrement > 0 ) ); - - vTaskSuspendAll(); - { - /* Generate the tick time at which the task wants to wake. */ - xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; - - if( xTickCount < *pxPreviousWakeTime ) - { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - else - { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - - /* Update the wake time ready for the next call. */ - *pxPreviousWakeTime = xTimeToWake; - - if( xShouldDelay != pdFALSE ) - { - traceTASK_DELAY_UNTIL(); - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - } - xAlreadyYielded = xTaskResumeAll(); - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( !xAlreadyYielded ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelay == 1 ) - - void vTaskDelay( portTickType xTicksToDelay ) - { - portTickType xTimeToWake; - signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* A delay time of zero just forces a reschedule. */ - if( xTicksToDelay > ( portTickType ) 0 ) - { - vTaskSuspendAll(); - { - traceTASK_DELAY(); - - /* A task that is removed from the event list while the - scheduler is suspended will not get placed in the ready - list or removed from the blocked list until the scheduler - is resumed. - - This task cannot be in an event list as it is the currently - executing task. */ - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - xAlreadyYielded = xTaskResumeAll(); - } - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( !xAlreadyYielded ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskPriorityGet == 1 ) - - unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxReturn; - - taskENTER_CRITICAL(); - { - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - uxReturn = pxTCB->uxPriority; - } - taskEXIT_CRITICAL(); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskPrioritySet == 1 ) - - void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxCurrentPriority; - portBASE_TYPE xYieldRequired = pdFALSE; - - configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) ); - - /* Ensure the new priority is valid. */ - if( uxNewPriority >= configMAX_PRIORITIES ) - { - uxNewPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; - } - - taskENTER_CRITICAL(); - { - if( pxTask == pxCurrentTCB ) - { - pxTask = NULL; - } - - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - - traceTASK_PRIORITY_SET( pxTask, uxNewPriority ); - - #if ( configUSE_MUTEXES == 1 ) - { - uxCurrentPriority = pxTCB->uxBasePriority; - } - #else - { - uxCurrentPriority = pxTCB->uxPriority; - } - #endif - - if( uxCurrentPriority != uxNewPriority ) - { - /* The priority change may have readied a task of higher - priority than the calling task. */ - if( uxNewPriority > uxCurrentPriority ) - { - if( pxTask != NULL ) - { - /* The priority of another task is being raised. If we - were raising the priority of the currently running task - there would be no need to switch as it must have already - been the highest priority task. */ - xYieldRequired = pdTRUE; - } - } - else if( pxTask == NULL ) - { - /* Setting our own priority down means there may now be another - task of higher priority that is ready to execute. */ - xYieldRequired = pdTRUE; - } - - - - #if ( configUSE_MUTEXES == 1 ) - { - /* Only change the priority being used if the task is not - currently using an inherited priority. */ - if( pxTCB->uxBasePriority == pxTCB->uxPriority ) - { - pxTCB->uxPriority = uxNewPriority; - } - - /* The base priority gets set whatever. */ - pxTCB->uxBasePriority = uxNewPriority; - } - #else - { - pxTCB->uxPriority = uxNewPriority; - } - #endif - - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); - - /* If the task is in the blocked or suspended list we need do - nothing more than change it's priority variable. However, if - the task is in a ready list it needs to be removed and placed - in the queue appropriate to its new priority. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - /* The task is currently in its ready list - remove before adding - it to it's new ready list. As we are in a critical section we - can do this even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - - if( xYieldRequired == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - taskEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskSuspend( xTaskHandle pxTaskToSuspend ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - suspended. */ - if( pxTaskToSuspend == pxCurrentTCB ) - { - pxTaskToSuspend = NULL; - } - - /* If null is passed in here then we are suspending ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); - - traceTASK_SUSPEND( pxTCB ); - - /* Remove task from the ready/delayed list and place in the suspended list. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); - } - taskEXIT_CRITICAL(); - - if( ( void * ) pxTaskToSuspend == NULL ) - { - if( xSchedulerRunning != pdFALSE ) - { - /* We have just suspended the current task. */ - portYIELD_WITHIN_API(); - } - else - { - /* The scheduler is not running, but the task that was pointed - to by pxCurrentTCB has just been suspended and pxCurrentTCB - must be adjusted to point to a different task. */ - if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) - { - /* No other tasks are ready, so set pxCurrentTCB back to - NULL so when the next task is created pxCurrentTCB will - be set to point to it no matter what its relative priority - is. */ - pxCurrentTCB = NULL; - } - else - { - vTaskSwitchContext(); - } - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) - { - portBASE_TYPE xReturn = pdFALSE; - const tskTCB * const pxTCB = ( tskTCB * ) xTask; - - /* It does not make sense to check if the calling task is suspended. */ - configASSERT( xTask ); - - /* Is the task we are attempting to resume actually in the - suspended list? */ - if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - /* Has the task already been resumed from within an ISR? */ - if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) - { - /* Is it in the suspended list because it is in the - Suspended state? It is possible to be in the suspended - list because it is blocked on a task with no timeout - specified. */ - if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) - { - xReturn = pdTRUE; - } - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskResume( xTaskHandle pxTaskToResume ) - { - tskTCB *pxTCB; - - /* It does not make sense to resume the calling task. */ - configASSERT( pxTaskToResume ); - - /* Remove the task from whichever list it is currently in, and place - it in the ready list. */ - pxTCB = ( tskTCB * ) pxTaskToResume; - - /* The parameter cannot be NULL as it is impossible to resume the - currently executing task. */ - if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) - { - taskENTER_CRITICAL(); - { - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME( pxTCB ); - - /* As we are in a critical section we can access the ready - lists even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* We may have just resumed a higher priority task. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* This yield may not cause the task just resumed to run, but - will leave the lists in the correct state for the next yield. */ - portYIELD_WITHIN_API(); - } - } - } - taskEXIT_CRITICAL(); - } - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - tskTCB *pxTCB; - - configASSERT( pxTaskToResume ); - - pxTCB = ( tskTCB * ) pxTaskToResume; - - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME_FROM_ISR( pxTCB ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed, at which point a - yield will be performed if necessary. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); - } - } - - return xYieldRequired; - } - -#endif - - - - -/*----------------------------------------------------------- - * PUBLIC SCHEDULER CONTROL documented in task.h - *----------------------------------------------------------*/ - - -void vTaskStartScheduler( void ) -{ -portBASE_TYPE xReturn; - - /* Add the idle task at the lowest priority. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), ( xTaskHandle * ) NULL ); - - #if ( configUSE_TIMERS == 1 ) - { - if( xReturn == pdPASS ) - { - xReturn = xTimerCreateTimerTask(); - } - } - #endif - - if( xReturn == pdPASS ) - { - /* Interrupts are turned off here, to ensure a tick does not occur - before or during the call to xPortStartScheduler(). The stacks of - the created tasks contain a status word with interrupts switched on - so interrupts will automatically get re-enabled when the first task - starts to run. - - STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE - DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ - portDISABLE_INTERRUPTS(); - - xSchedulerRunning = pdTRUE; - xTickCount = ( portTickType ) 0; - - /* If configGENERATE_RUN_TIME_STATS is defined then the following - macro must be defined to configure the timer/counter used to generate - the run time counter time base. */ - portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); - - /* Setting up the timer tick is hardware specific and thus in the - portable interface. */ - if( xPortStartScheduler() ) - { - /* Should not reach here as if the scheduler is running the - function will not return. */ - } - else - { - /* Should only reach here if a task calls xTaskEndScheduler(). */ - } - } - - /* This line will only be reached if the kernel could not be started. */ - configASSERT( xReturn ); -} -/*-----------------------------------------------------------*/ - -void vTaskEndScheduler( void ) -{ - /* Stop the scheduler interrupts and call the portable scheduler end - routine so the original ISRs can be restored if necessary. The port - layer must ensure interrupts enable bit is left in the correct state. */ - portDISABLE_INTERRUPTS(); - xSchedulerRunning = pdFALSE; - vPortEndScheduler(); -} -/*----------------------------------------------------------*/ - -void vTaskSuspendAll( void ) -{ - /* A critical section is not required as the variable is of type - portBASE_TYPE. */ - ++uxSchedulerSuspended; -} -/*----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskResumeAll( void ) -{ -register tskTCB *pxTCB; -signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* If uxSchedulerSuspended is zero then this function does not match a - previous call to vTaskSuspendAll(). */ - configASSERT( uxSchedulerSuspended ); - - /* It is possible that an ISR caused a task to be removed from an event - list while the scheduler was suspended. If this was the case then the - removed task will have been added to the xPendingReadyList. Once the - scheduler has been resumed it is safe to move all the pending ready - tasks from this list into their appropriate ready list. */ - taskENTER_CRITICAL(); - { - --uxSchedulerSuspended; - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0 ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - - /* Move any readied tasks from the pending list into the - appropriate ready list. */ - while( listLIST_IS_EMPTY( ( xList * ) &xPendingReadyList ) == pdFALSE ) - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ); - vListRemove( &( pxTCB->xEventListItem ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* If we have moved a task that has a priority higher than - the current task then we should yield. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - xYieldRequired = pdTRUE; - } - } - - /* If any ticks occurred while the scheduler was suspended then - they should be processed now. This ensures the tick count does not - slip, and that any delayed tasks are resumed at the correct time. */ - if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) - { - while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) - { - vTaskIncrementTick(); - --uxMissedTicks; - } - - /* As we have processed some ticks it is appropriate to yield - to ensure the highest priority task that is ready to run is - the task actually running. */ - #if configUSE_PREEMPTION == 1 - { - xYieldRequired = pdTRUE; - } - #endif - } - - if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) - { - xAlreadyYielded = pdTRUE; - xMissedYield = pdFALSE; - portYIELD_WITHIN_API(); - } - } - } - } - taskEXIT_CRITICAL(); - - return xAlreadyYielded; -} - - - - - - -/*----------------------------------------------------------- - * PUBLIC TASK UTILITIES documented in task.h - *----------------------------------------------------------*/ - - - -portTickType xTaskGetTickCount( void ) -{ -portTickType xTicks; - - /* Critical section required if running on a 16 bit processor. */ - taskENTER_CRITICAL(); - { - xTicks = xTickCount; - } - taskEXIT_CRITICAL(); - - return xTicks; -} -/*-----------------------------------------------------------*/ - -portTickType xTaskGetTickCountFromISR( void ) -{ -portTickType xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - xReturn = xTickCount; - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) -{ - /* A critical section is not required because the variables are of type - portBASE_TYPE. */ - return uxCurrentNumberOfTasks; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskList( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB and - report the task name, state and stack high water mark. */ - - *pcWriteBuffer = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; - - do - { - uxQueue--; - - if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); - } - - if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); - } - - #if( INCLUDE_vTaskDelete == 1 ) - { - if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, tskDELETED_CHAR ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, tskSUSPENDED_CHAR ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - unsigned long ulTotalRunTime; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE - portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime ); - #else - ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); - #endif - - /* Divide ulTotalRunTime by 100 to make the percentage caluclations - simpler in the prvGenerateRunTimeStatsForTasksInList() function. */ - ulTotalRunTime /= 100UL; - - /* Run through all the lists that could potentially contain a TCB, - generating a table of run timer percentages in the provided - buffer. */ - - *pcWriteBuffer = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; - - do - { - uxQueue--; - - if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); - } - - if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); - } - - #if ( INCLUDE_vTaskDelete == 1 ) - { - if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, ulTotalRunTime ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, ulTotalRunTime ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) - { - configASSERT( pcBuffer ); - configASSERT( ulBufferSize ); - - taskENTER_CRITICAL(); - { - pcTraceBuffer = ( signed char * )pcBuffer; - pcTraceBufferStart = pcBuffer; - pcTraceBufferEnd = pcBuffer + ( ulBufferSize - tskSIZE_OF_EACH_TRACE_LINE ); - xTracing = pdTRUE; - } - taskEXIT_CRITICAL(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned long ulTaskEndTrace( void ) - { - unsigned long ulBufferLength; - - taskENTER_CRITICAL(); - xTracing = pdFALSE; - taskEXIT_CRITICAL(); - - ulBufferLength = ( unsigned long ) ( pcTraceBuffer - pcTraceBufferStart ); - - return ulBufferLength; - } - -#endif - - - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - * documented in task.h - *----------------------------------------------------------*/ - - -void vTaskIncrementTick( void ) -{ -tskTCB * pxTCB; - - /* Called by the portable layer each time a tick interrupt occurs. - Increments the tick then checks to see if the new tick value will cause any - tasks to be unblocked. */ - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - ++xTickCount; - if( xTickCount == ( portTickType ) 0 ) - { - xList *pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. - If there are any items in pxDelayedTaskList here then there is - an error! */ - configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) ); - - pxTemp = pxDelayedTaskList; - pxDelayedTaskList = pxOverflowDelayedTaskList; - pxOverflowDelayedTaskList = pxTemp; - xNumOfOverflows++; - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) - { - /* The new current delayed list is empty. Set - xNextTaskUnblockTime to the maximum possible value so it is - extremely unlikely that the - if( xTickCount >= xNextTaskUnblockTime ) test will pass until - there is an item in the delayed list. */ - xNextTaskUnblockTime = portMAX_DELAY; - } - else - { - /* The new current delayed list is not empty, get the value of - the item at the head of the delayed list. This is the time at - which the task at the head of the delayed list should be removed - from the Blocked state. */ - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); - xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); - } - } - - /* See if this tick has made a timeout expire. */ - prvCheckDelayedTasks(); - } - else - { - ++uxMissedTicks; - - /* The tick hook gets called at regular intervals, even if the - scheduler is locked. */ - #if ( configUSE_TICK_HOOK == 1 ) - { - vApplicationTickHook(); - } - #endif - } - - #if ( configUSE_TICK_HOOK == 1 ) - { - /* Guard against the tick hook being called when the missed tick - count is being unwound (when the scheduler is being unlocked. */ - if( uxMissedTicks == ( unsigned portBASE_TYPE ) 0U ) - { - vApplicationTickHook(); - } - } - #endif - - traceTASK_INCREMENT_TICK( xTickCount ); -} -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_vTaskCleanUpResources == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - void vTaskCleanUpResources( void ) - { - unsigned short usQueue; - volatile tskTCB *pxTCB; - - usQueue = ( unsigned short ) uxTopUsedPriority + ( unsigned short ) 1; - - /* Remove any TCB's from the ready queues. */ - do - { - usQueue--; - - while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ usQueue ] ) ) == pdFALSE ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &( pxReadyTasksLists[ usQueue ] ) ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - }while( usQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - /* Remove any TCB's from the delayed queue. */ - while( listLIST_IS_EMPTY( &xDelayedTaskList1 ) == pdFALSE ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList1 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - /* Remove any TCB's from the overflow delayed queue. */ - while( listLIST_IS_EMPTY( &xDelayedTaskList2 ) == pdFALSE ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList2 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - while( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xSuspendedTaskList ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) - { - tskTCB *xTCB; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - taskENTER_CRITICAL(); - xTCB->pxTaskTag = pxHookFunction; - taskEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) - { - tskTCB *xTCB; - pdTASK_HOOK_CODE xReturn; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - taskENTER_CRITICAL(); - xReturn = xTCB->pxTaskTag; - taskEXIT_CRITICAL(); - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) - { - tskTCB *xTCB; - portBASE_TYPE xReturn; - - /* If xTask is NULL then we are calling our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - if( xTCB->pxTaskTag != NULL ) - { - xReturn = xTCB->pxTaskTag( pvParameter ); - } - else - { - xReturn = pdFAIL; - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -void vTaskSwitchContext( void ) -{ - if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) - { - /* The scheduler is currently suspended - do not allow a context - switch. */ - xMissedYield = pdTRUE; - } - else - { - traceTASK_SWITCHED_OUT(); - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - unsigned long ulTempCounter; - - #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE - portALT_GET_RUN_TIME_COUNTER_VALUE( ulTempCounter ); - #else - ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); - #endif - - /* Add the amount of time the task has been running to the accumulated - time so far. The time the task started running was stored in - ulTaskSwitchedInTime. Note that there is no overflow protection here - so count values are only valid until the timer overflows. Generally - this will be about 1 hour assuming a 1uS timer increment. */ - pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); - ulTaskSwitchedInTime = ulTempCounter; - } - #endif - - taskFIRST_CHECK_FOR_STACK_OVERFLOW(); - taskSECOND_CHECK_FOR_STACK_OVERFLOW(); - - /* Find the highest priority queue that contains ready tasks. */ - while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) - { - configASSERT( uxTopReadyPriority ); - --uxTopReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the - same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); - - traceTASK_SWITCHED_IN(); - vWriteTraceToBuffer(); - } -} -/*-----------------------------------------------------------*/ - -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) -{ -portTickType xTimeToWake; - - configASSERT( pxEventList ); - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. */ - - /* Place the event list item of the TCB in the appropriate event list. - This is placed in the list in priority order so the highest priority task - is the first to be woken by the event. */ - vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove ourselves from the ready list before adding ourselves - to the blocked list as the same list item is used for both lists. We have - exclusive access to the ready lists as the scheduler is locked. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( xTicksToWait == portMAX_DELAY ) - { - /* Add ourselves to the suspended task list instead of a delayed task - list to ensure we are not woken by a timing event. We will block - indefinitely. */ - vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - } - #else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - #endif -} -/*-----------------------------------------------------------*/ - -#if configUSE_TIMERS == 1 - - void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) - { - portTickType xTimeToWake; - - configASSERT( pxEventList ); - - /* This function should not be called by application code hence the - 'Restricted' in its name. It is not part of the public API. It is - designed for use by kernel code, and has special calling requirements - - it should be called from a critical section. */ - - - /* Place the event list item of the TCB in the appropriate event list. - In this case it is assume that this is the only task that is going to - be waiting on this event list, so the faster vListInsertEnd() function - can be used in place of vListInsert. */ - vListInsertEnd( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove this task from the ready list before adding it to the - blocked list as the same list item is used for both lists. This - function is called form a critical section. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - -#endif /* configUSE_TIMERS */ -/*-----------------------------------------------------------*/ - -#include "assert.h" -extern volatile portBASE_TYPE xInterruptsEnabled; -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) -{ -tskTCB *pxUnblockedTCB; -portBASE_TYPE xReturn; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. It can also be called from within an ISR. */ - - assert( uxSchedulerSuspended || xInterruptsEnabled == pdFALSE); - - /* The event list is sorted in priority order, so we can remove the - first in the list, remove the TCB from the delayed list, and add - it to the ready list. - - If an event is for a queue that is locked then this function will never - get called - the lock count on the queue will get modified instead. This - means we can always expect exclusive access to the event list here. - - This function assumes that a check has already been made to ensure that - pxEventList is not empty. */ - pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - configASSERT( pxUnblockedTCB ); - vListRemove( &( pxUnblockedTCB->xEventListItem ) ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxUnblockedTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); - } - - if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* Return true if the task removed from the event list has - a higher priority than the calling task. This allows - the calling task to know if it should force a context - switch now. */ - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) -{ - configASSERT( pxTimeOut ); - pxTimeOut->xOverflowCount = xNumOfOverflows; - pxTimeOut->xTimeOnEntering = xTickCount; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) -{ -portBASE_TYPE xReturn; - - configASSERT( pxTimeOut ); - configASSERT( pxTicksToWait ); - - taskENTER_CRITICAL(); - { - #if ( INCLUDE_vTaskSuspend == 1 ) - /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is - the maximum block time then the task should block indefinitely, and - therefore never time out. */ - if( *pxTicksToWait == portMAX_DELAY ) - { - xReturn = pdFALSE; - } - else /* We are not blocking indefinitely, perform the checks below. */ - #endif - - if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) - { - /* The tick count is greater than the time at which vTaskSetTimeout() - was called, but has also overflowed since vTaskSetTimeOut() was called. - It must have wrapped all the way around and gone past us again. This - passed since vTaskSetTimeout() was called. */ - xReturn = pdTRUE; - } - else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) - { - /* Not a genuine timeout. Adjust parameters for time remaining. */ - *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); - vTaskSetTimeOutState( pxTimeOut ); - xReturn = pdFALSE; - } - else - { - xReturn = pdTRUE; - } - } - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskMissedYield( void ) -{ - xMissedYield = pdTRUE; -} - -/* - * ----------------------------------------------------------- - * The Idle task. - * ---------------------------------------------------------- - * - * The portTASK_FUNCTION() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION( prvIdleTask, pvParameters ) -{ - /* Stop warnings. */ - ( void ) pvParameters; - int last_idle_time = clock(); - for( ;; ) - { - /* See if any tasks have been deleted. */ - prvCheckTasksWaitingTermination(); - - #if ( configUSE_PREEMPTION == 0 ) - { - /* If we are not using preemption we keep forcing a task switch to - see if any other task has become available. If we are using - preemption we don't need to do this as any task becoming available - will automatically get the processor anyway. */ - taskYIELD(); - } - #endif - - #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) - { - /* When using preemption tasks of equal priority will be - timesliced. If a task that is sharing the idle priority is ready - to run then the idle task should yield before the end of the - timeslice. - - A critical region is not required here as we are just reading from - the list, and an occasional incorrect value will not matter. If - the ready list at the idle priority contains more than one task - then a task other than the idle task is ready to execute. */ - if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) - { - taskYIELD(); - } - } - #endif - - #if ( configUSE_IDLE_HOOK == 1 ) - { - extern void vApplicationIdleHook( void ); - - /* Call the user defined function from within the idle task. This - allows the application designer to add background functionality - without the overhead of a separate task. - NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, - CALL A FUNCTION THAT MIGHT BLOCK. */ - while(clock() < (last_idle_time + 1)) - sched_yield(); - last_idle_time = clock(); - vApplicationIdleHook(); - } - #endif - - - //usleep(5); - } -} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ - - - - - - - -/*----------------------------------------------------------- - * File private functions documented at the top of the file. - *----------------------------------------------------------*/ - - - -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) -{ - /* Store the function name in the TCB. */ - #if configMAX_TASK_NAME_LEN > 1 - { - /* Don't bring strncpy into the build unnecessarily. */ - strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); - } - #endif - pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = ( signed char ) '\0'; - - /* This is used as an array index so must ensure it's not too large. First - remove the privilege bit if one is present. */ - if( uxPriority >= configMAX_PRIORITIES ) - { - uxPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; - } - - pxTCB->uxPriority = uxPriority; - #if ( configUSE_MUTEXES == 1 ) - { - pxTCB->uxBasePriority = uxPriority; - } - #endif - - vListInitialiseItem( &( pxTCB->xGenericListItem ) ); - vListInitialiseItem( &( pxTCB->xEventListItem ) ); - - /* Set the pxTCB as a link back from the xListItem. This is so we can get - back to the containing TCB from a generic item in a list. */ - listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - { - pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0; - } - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - { - pxTCB->pxTaskTag = NULL; - } - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - pxTCB->ulRunTimeCounter = 0UL; - } - #endif - - #if ( portUSING_MPU_WRAPPERS == 1 ) - { - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); - } - #else - { - ( void ) xRegions; - ( void ) usStackDepth; - } - #endif -} -/*-----------------------------------------------------------*/ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - - void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) - { - tskTCB *pxTCB; - - if( xTaskToModify == pxCurrentTCB ) - { - xTaskToModify = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( xTaskToModify ); - - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); - } - /*-----------------------------------------------------------*/ -#endif - -static void prvInitialiseTaskLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = ( unsigned portBASE_TYPE ) 0U; uxPriority < configMAX_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedTaskList1 ); - vListInitialise( ( xList * ) &xDelayedTaskList2 ); - vListInitialise( ( xList * ) &xPendingReadyList ); - - #if ( INCLUDE_vTaskDelete == 1 ) - { - vListInitialise( ( xList * ) &xTasksWaitingTermination ); - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - vListInitialise( ( xList * ) &xSuspendedTaskList ); - } - #endif - - /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList - using list2. */ - pxDelayedTaskList = &xDelayedTaskList1; - pxOverflowDelayedTaskList = &xDelayedTaskList2; -} -/*-----------------------------------------------------------*/ - -static void prvCheckTasksWaitingTermination( void ) -{ - #if ( INCLUDE_vTaskDelete == 1 ) - { - portBASE_TYPE xListIsEmpty; - - /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called - too often in the idle task. */ - if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0 ) - { - vTaskSuspendAll(); - xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); - xTaskResumeAll(); - - if( xListIsEmpty == pdFALSE ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - --uxCurrentNumberOfTasks; - --uxTasksDeleted; - } - taskEXIT_CRITICAL(); - - prvDeleteTCB( pxTCB ); - } - } - } - #endif -} -/*-----------------------------------------------------------*/ - -static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) -{ - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* If the task entering the blocked state was placed at the head of the - list of blocked tasks then xNextTaskUnblockTime needs to be updated - too. */ - if( xTimeToWake < xNextTaskUnblockTime ) - { - xNextTaskUnblockTime = xTimeToWake; - } - } -} -/*-----------------------------------------------------------*/ - -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) -{ -tskTCB *pxNewTCB; - - /* Allocate space for the TCB. Where the memory comes from depends on - the implementation of the port malloc function. */ - pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); - - if( pxNewTCB != NULL ) - { - /* Allocate space for the stack used by the task being created. - The base of the stack memory stored in the TCB so the task can - be deleted later if required. */ - pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); - - if( pxNewTCB->pxStack == NULL ) - { - /* Could not allocate the stack. Delete the allocated TCB. */ - vPortFree( pxNewTCB ); - pxNewTCB = NULL; - } - else - { - /* Just to help debugging. */ - memset( pxNewTCB->pxStack, tskSTACK_FILL_BYTE, usStackDepth * sizeof( portSTACK_TYPE ) ); - } - } - - return pxNewTCB; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned short usStackRemaining; - - /* Write the details of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - #if ( portSTACK_GROWTH > 0 ) - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); - } - #else - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); - } - #endif - - sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned long ulStatsAsPercentage; - - /* Write the run time stats of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - /* Get next TCB in from the list. */ - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - - /* Divide by zero check. */ - if( ulTotalRunTime > 0UL ) - { - /* Has the task run at all? */ - if( pxNextTCB->ulRunTimeCounter == 0 ) - { - /* The task has used no CPU time at all. */ - sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); - } - else - { - /* What percentage of the total run time has the task used? - This will always be rounded down to the nearest integer. - ulTotalRunTime has already been divided by 100. */ - ulStatsAsPercentage = pxNextTCB->ulRunTimeCounter / ulTotalRunTime; - - if( ulStatsAsPercentage > 0UL ) - { - #ifdef portLU_PRINTF_SPECIFIER_REQUIRED - { - sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t%lu%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter, ulStatsAsPercentage ); - } - #else - { - /* sizeof( int ) == sizeof( long ) so a smaller - printf() library can be used. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); - } - #endif - } - else - { - /* If the percentage is zero here then the task has - consumed less than 1% of the total run time. */ - #ifdef portLU_PRINTF_SPECIFIER_REQUIRED - { - sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t<1%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter ); - } - #else - { - /* sizeof( int ) == sizeof( long ) so a smaller - printf() library can be used. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); - } - #endif - } - } - - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); - } - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetRunTime == 1 ) -unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) -{ - unsigned long runTime; - - tskTCB *pxTCB; - pxTCB = prvGetTCBFromHandle( xTask ); - runTime = pxTCB->ulRunTimeCounter; - pxTCB->ulRunTimeCounter = 0; - return runTime; -} - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) - { - register unsigned short usCount = 0; - - while( *pucStackByte == tskSTACK_FILL_BYTE ) - { - pucStackByte -= portSTACK_GROWTH; - usCount++; - } - - usCount /= sizeof( portSTACK_TYPE ); - - return usCount; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) - - unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) - { - tskTCB *pxTCB; - unsigned char *pcEndOfStack; - unsigned portBASE_TYPE uxReturn; - - pxTCB = prvGetTCBFromHandle( xTask ); - - #if portSTACK_GROWTH < 0 - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; - } - #else - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; - } - #endif - - uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) - - static void prvDeleteTCB( tskTCB *pxTCB ) - { - /* Free up the memory allocated by the scheduler for the task. It is up to - the task to free any memory allocated at the application level. */ - vPortFreeAligned( pxTCB->pxStack ); - vPortFree( pxTCB ); - } - -#endif - - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) - - xTaskHandle xTaskGetCurrentTaskHandle( void ) - { - xTaskHandle xReturn; - - /* A critical section is not required as this is not called from - an interrupt and the current TCB will always be the same for any - individual execution thread. */ - xReturn = pxCurrentTCB; - - return xReturn; - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) - - portBASE_TYPE xTaskGetSchedulerState( void ) - { - portBASE_TYPE xReturn; - - if( xSchedulerRunning == pdFALSE ) - { - xReturn = taskSCHEDULER_NOT_STARTED; - } - else - { - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xReturn = taskSCHEDULER_RUNNING; - } - else - { - xReturn = taskSCHEDULER_SUSPENDED; - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - configASSERT( pxMutexHolder ); - - if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) - { - /* Adjust the mutex holder state to account for its new priority. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); - - /* If the task being modified is in the ready state it will need to - be moved in to a new list. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Inherit the priority before being moved into the new list. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* Just inherit the priority. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxMutexHolder != NULL ) - { - if( pxTCB->uxPriority != pxTCB->uxBasePriority ) - { - /* We must be the running task to be able to give the mutex back. - Remove ourselves from the ready list we currently appear in. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Disinherit the priority before adding ourselves into the new - ready list. */ - pxTCB->uxPriority = pxTCB->uxBasePriority; - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); - prvAddTaskToReadyQueue( pxTCB ); - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - - void vTaskEnterCritical( void ) - { - portDISABLE_INTERRUPTS(); - - if( xSchedulerRunning != pdFALSE ) - { - ( pxCurrentTCB->uxCriticalNesting )++; - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - -void vTaskExitCritical( void ) -{ - if( xSchedulerRunning != pdFALSE ) - { - if( pxCurrentTCB->uxCriticalNesting > 0 ) - { - ( pxCurrentTCB->uxCriticalNesting )--; - - if( pxCurrentTCB->uxCriticalNesting == 0 ) - { - portENABLE_INTERRUPTS(); - } - } - } -} - -#endif -/*-----------------------------------------------------------*/ - -static void printNamesInList( const signed char *pcWriteBuffer, xList *pxList) -{ - volatile tskTCB *pxNextTCB, *pxFirstTCB; - char pcStatsString[100]; - /* Write the run time stats of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - /* Get next TCB in from the list. */ - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - if(pxNextTCB) { - sprintf( pcStatsString, ( char * ) "%s, ", pxNextTCB->pcTaskName); - - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); - } - - } while( pxNextTCB != pxFirstTCB ); -} - -void printTasks() -{ - signed char pcWriteBuffer[500]; - int uxQueue; - taskENTER_CRITICAL(); - { - /* Run through all the lists that could potentially contain a TCB, - generating a table of run timer percentages in the provided - buffer. */ - - pcWriteBuffer[ 0 ] = ( signed char ) 0x00; - - uxQueue = uxTopUsedPriority + 1; - - do - { - uxQueue--; - - if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) - { - char readyMessage[30]; - sprintf(readyMessage, "\r\nReady priority %d: ", uxQueue); - strcat( ( char * ) pcWriteBuffer,readyMessage); - printNamesInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] )); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) - { - strcat( ( char * ) pcWriteBuffer, "\r\nDelay: "); - printNamesInList( pcWriteBuffer, ( xList * ) &( pxDelayedTaskList)); - } - - if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) - { - strcat( ( char * ) pcWriteBuffer, "\r\nDelay Overflow: "); - printNamesInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList); - } - - if( !listLIST_IS_EMPTY( &xPendingReadyList ) ) - { - strcat( ( char * ) pcWriteBuffer, "\r\nPending ready: "); - printNamesInList( pcWriteBuffer, ( xList * ) &xPendingReadyList); - } - -#if ( INCLUDE_vTaskDelete == 1 ) - { - if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) - { - strcat( ( char * ) pcWriteBuffer, "\r\nWaiting termination: "); - printNamesInList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination); - } - } -#endif - -#if ( INCLUDE_vTaskSuspend == 1 ) - { - if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - strcat( ( char * ) pcWriteBuffer, "\r\nSuspended: "); - printNamesInList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList); - } - } -#endif - } - strcat( (char *) pcWriteBuffer, "\r\n\r\n"); - fprintf(stderr, "%s", ( char * ) pcWriteBuffer); - taskEXIT_CRITICAL(); - -} - - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#include +#include +#include +#include +#include +#include +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "timers.h" +#include "StackMacros.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* + * Macro to define the amount of stack available to the idle task. + */ +#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE + +/* + * Task control block. A task control block (TCB) is allocated to each task, + * and stores the context of the task. + */ +typedef struct tskTaskControlBlock +{ + volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ + + #if ( portUSING_MPU_WRAPPERS == 1 ) + xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ + #endif + + xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ + portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ + signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ + + #if ( portSTACK_GROWTH > 0 ) + portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ + #endif + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + unsigned portBASE_TYPE uxCriticalNesting; + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ + #endif + + #if ( configUSE_MUTEXES == 1 ) + unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + pdTASK_HOOK_CODE pxTaskTag; + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ + #endif + +} tskTCB; + + +/* + * Some kernel aware debuggers require data to be viewed to be global, rather + * than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + +/*lint -e956 */ +PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; + +/* Lists for ready and blocked tasks. --------------------*/ + +PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ +PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ +PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ +PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ +PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ +PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ + +#if ( INCLUDE_vTaskDelete == 1 ) + + PRIVILEGED_DATA static volatile xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ + PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0; + +#endif + +#if ( INCLUDE_vTaskSuspend == 1 ) + + PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ + +#endif + +/* File private variables. --------------------------------*/ +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0; +PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0; +PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; +PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0; +PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) portMAX_DELAY; + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + PRIVILEGED_DATA static char pcStatsString[ 50 ] ; + PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ + static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; + +#endif + +/* Debugging and trace facilities private variables and macros. ------------*/ + +/* + * The value used to fill the stack of a task when the task is created. This + * is used purely for checking the high water mark for tasks. + */ +#define tskSTACK_FILL_BYTE ( 0xa5U ) + +/* + * Macros used by vListTask to indicate which state a task is in. + */ +#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) +#define tskREADY_CHAR ( ( signed char ) 'R' ) +#define tskDELETED_CHAR ( ( signed char ) 'D' ) +#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) + +/* + * Macros and private variables used by the trace facility. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + #define tskSIZE_OF_EACH_TRACE_LINE ( ( unsigned long ) ( sizeof( unsigned long ) + sizeof( unsigned long ) ) ) + PRIVILEGED_DATA static volatile signed char * volatile pcTraceBuffer; + PRIVILEGED_DATA static signed char *pcTraceBufferStart; + PRIVILEGED_DATA static signed char *pcTraceBufferEnd; + PRIVILEGED_DATA static signed portBASE_TYPE xTracing = pdFALSE; + static unsigned portBASE_TYPE uxPreviousTask = 255U; + PRIVILEGED_DATA static char pcStatusString[ 50 ]; + +#endif + +/*-----------------------------------------------------------*/ + +/* + * Macro that writes a trace of scheduler activity to a buffer. This trace + * shows which task is running when and is very useful as a debugging tool. + * As this macro is called each context switch it is a good idea to undefine + * it if not using the facility. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + #define vWriteTraceToBuffer() \ + { \ + if( xTracing ) \ + { \ + if( uxPreviousTask != pxCurrentTCB->uxTCBNumber ) \ + { \ + if( ( pcTraceBuffer + tskSIZE_OF_EACH_TRACE_LINE ) < pcTraceBufferEnd ) \ + { \ + uxPreviousTask = pxCurrentTCB->uxTCBNumber; \ + *( unsigned long * ) pcTraceBuffer = ( unsigned long ) xTickCount; \ + pcTraceBuffer += sizeof( unsigned long ); \ + *( unsigned long * ) pcTraceBuffer = ( unsigned long ) uxPreviousTask; \ + pcTraceBuffer += sizeof( unsigned long ); \ + } \ + else \ + { \ + xTracing = pdFALSE; \ + } \ + } \ + } \ + } + +#else + + #define vWriteTraceToBuffer() + +#endif +/*-----------------------------------------------------------*/ + +/* + * Place the task represented by pxTCB into the appropriate ready queue for + * the task. It is inserted at the end of the list. One quirk of this is + * that if the task being inserted is at the same priority as the currently + * executing task, then it will only be rescheduled after the currently + * executing task has been rescheduled. + */ +#define prvAddTaskToReadyQueue( pxTCB ) \ + if( ( pxTCB )->uxPriority > uxTopReadyPriority ) \ + { \ + uxTopReadyPriority = ( pxTCB )->uxPriority; \ + } \ + vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xGenericListItem ) ) +/*-----------------------------------------------------------*/ + +/* + * Macro that looks at the list of tasks that are currently delayed to see if + * any require waking. + * + * Tasks are stored in the queue in the order of their wake time - meaning + * once one tasks has been found whose timer has not expired we need not look + * any further down the list. + */ +#define prvCheckDelayedTasks() \ +{ \ +portTickType xItemValue; \ + \ + /* Is the tick count greater than or equal to the wake time of the first \ + task referenced from the delayed tasks list? */ \ + if( xTickCount >= xNextTaskUnblockTime ) \ + { \ + for( ;; ) \ + { \ + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) \ + { \ + /* The delayed list is empty. Set xNextTaskUnblockTime to the \ + maximum possible value so it is extremely unlikely that the \ + if( xTickCount >= xNextTaskUnblockTime ) test will pass next \ + time through. */ \ + xNextTaskUnblockTime = portMAX_DELAY; \ + break; \ + } \ + else \ + { \ + /* The delayed list is not empty, get the value of the item at \ + the head of the delayed list. This is the time at which the \ + task at the head of the delayed list should be removed from \ + the Blocked state. */ \ + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); \ + xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); \ + \ + if( xTickCount < xItemValue ) \ + { \ + /* It is not time to unblock this item yet, but the item \ + value is the time at which the task at the head of the \ + blocked list should be removed from the Blocked state - \ + so record the item value in xNextTaskUnblockTime. */ \ + xNextTaskUnblockTime = xItemValue; \ + break; \ + } \ + \ + /* It is time to remove the item from the Blocked state. */ \ + vListRemove( &( pxTCB->xGenericListItem ) ); \ + \ + /* Is the task waiting on an event also? */ \ + if( pxTCB->xEventListItem.pvContainer ) \ + { \ + vListRemove( &( pxTCB->xEventListItem ) ); \ + } \ + prvAddTaskToReadyQueue( pxTCB ); \ + } \ + } \ + } \ +} +/*-----------------------------------------------------------*/ + +/* + * Several functions take an xTaskHandle parameter that can optionally be NULL, + * where NULL is used to indicate that the handle of the currently executing + * task should be used in place of the parameter. This macro simply checks to + * see if the parameter is NULL and returns a pointer to the appropriate TCB. + */ +#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) ( pxHandle ) ) + +/* Callback function prototypes. --------------------------*/ +extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); +extern void vApplicationTickHook( void ); + +/* File private functions. --------------------------------*/ + +/* + * Utility to ready a TCB for a given task. Mainly just copies the parameters + * into the TCB structure. + */ +static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first task. + */ +static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; + +/* + * The idle task, which as all tasks is implemented as a never ending loop. + * The idle task is automatically created and added to the ready lists upon + * creation of the first user task. + * + * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); + +/* + * Utility to free all memory allocated by the scheduler to hold a TCB, + * including the stack pointed to by the TCB. + * + * This does not free memory allocated by the task itself (i.e. memory + * allocated by calls to pvPortMalloc from within the tasks application code). + */ +#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) + + static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Used only by the idle task. This checks to see if anything has been placed + * in the list of tasks waiting to be deleted. If so the task is cleaned up + * and its TCB deleted. + */ +static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; + +/* + * The currently executing task is entering the Blocked state. Add the task to + * either the current or the overflow delayed task list. + */ +static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) PRIVILEGED_FUNCTION; + +/* + * Allocates memory from the heap for a TCB and associated stack. Checks the + * allocation was successful. + */ +static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; + +/* + * Called from vTaskList. vListTasks details all the tasks currently under + * control of the scheduler. The tasks may be in one of a number of lists. + * prvListTaskWithinSingleList accepts a list and details the tasks from + * within just that list. + * + * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM + * NORMAL APPLICATION CODE. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; + +#endif + +/* + * When a task is created, the stack of the task is filled with a known value. + * This function determines the 'high water mark' of the task stack by + * determining how much of the stack remains at the original preset value. + */ +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) + + static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; + +#endif + + +/*lint +e956 */ + + + +/*----------------------------------------------------------- + * TASK CREATION API documented in task.h + *----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) +{ +signed portBASE_TYPE xReturn; +tskTCB * pxNewTCB; + + configASSERT( pxTaskCode ); + configASSERT( ( uxPriority < configMAX_PRIORITIES ) ); + + /* Allocate the memory required by the TCB and stack for the new task, + checking that the allocation was successful. */ + pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); + + if( pxNewTCB != NULL ) + { + portSTACK_TYPE *pxTopOfStack; + + #if( portUSING_MPU_WRAPPERS == 1 ) + /* Should the task be created in privileged mode? */ + portBASE_TYPE xRunPrivileged; + if( ( uxPriority & portPRIVILEGE_BIT ) != 0x00 ) + { + xRunPrivileged = pdTRUE; + } + else + { + xRunPrivileged = pdFALSE; + } + uxPriority &= ~portPRIVILEGE_BIT; + #endif /* portUSING_MPU_WRAPPERS == 1 */ + + /* Calculate the top of stack address. This depends on whether the + stack grows from high memory to low (as per the 80x86) or visa versa. + portSTACK_GROWTH is used to make the result positive or negative as + required by the port. */ + #if( portSTACK_GROWTH < 0 ) + { + pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - ( unsigned short ) 1 ); + pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( unsigned long ) pxTopOfStack ) & ( ( unsigned long ) ~portBYTE_ALIGNMENT_MASK ) ); + + /* Check the alignment of the calculated top of stack is correct. */ + configASSERT( ( ( ( unsigned long ) pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + } + #else + { + pxTopOfStack = pxNewTCB->pxStack; + + /* Check the alignment of the stack buffer is correct. */ + configASSERT( ( ( ( unsigned long ) pxNewTCB->pxStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + /* If we want to use stack checking on architectures that use + a positive stack growth direction then we also need to store the + other extreme of the stack space. */ + pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); + } + #endif + + /* Setup the newly allocated TCB with the initial state of the task. */ + prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); + + /* Initialize the TCB stack to look as if the task was already running, + but had been interrupted by the scheduler. The return address is set + to the start of the task function. Once the stack has been initialised + the top of stack variable is updated. */ + #if( portUSING_MPU_WRAPPERS == 1 ) + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #else + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); + } + #endif + + /* Check the alignment of the initialised stack. */ + configASSERT( ( ( ( unsigned long ) pxNewTCB->pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + if( ( void * ) pxCreatedTask != NULL ) + { + /* Pass the TCB out - in an anonymous way. The calling function/ + task can use this as a handle to delete the task later if + required.*/ + *pxCreatedTask = ( xTaskHandle ) pxNewTCB; + } + + /* We are going to manipulate the task queues to add this task to a + ready list, so must make sure no interrupts occur. */ + taskENTER_CRITICAL(); + { + uxCurrentNumberOfTasks++; + if( pxCurrentTCB == NULL ) + { + /* There are no other tasks, or all the other tasks are in + the suspended state - make this the current task. */ + pxCurrentTCB = pxNewTCB; + + if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) + { + /* This is the first task to be created so do the preliminary + initialisation required. We will not recover if this call + fails, but we will report the failure. */ + prvInitialiseTaskLists(); + } + } + else + { + /* If the scheduler is not already running, make this task the + current task if it is the highest priority task to be created + so far. */ + if( xSchedulerRunning == pdFALSE ) + { + if( pxCurrentTCB->uxPriority <= uxPriority ) + { + pxCurrentTCB = pxNewTCB; + } + } + } + + /* Remember the top priority to make context switching faster. Use + the priority in pxNewTCB as this has been capped to a valid value. */ + if( pxNewTCB->uxPriority > uxTopUsedPriority ) + { + uxTopUsedPriority = pxNewTCB->uxPriority; + } + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + /* Add a counter into the TCB for tracing only. */ + pxNewTCB->uxTCBNumber = uxTaskNumber; + } + #endif + uxTaskNumber++; + + prvAddTaskToReadyQueue( pxNewTCB ); + + xReturn = pdPASS; + traceTASK_CREATE( pxNewTCB ); + } + taskEXIT_CRITICAL(); + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + traceTASK_CREATE_FAILED(); + } + + if( xReturn == pdPASS ) + { + if( xSchedulerRunning != pdFALSE ) + { + /* If the created task is of a higher priority than the current task + then it should run now. */ + if( pxCurrentTCB->uxPriority < uxPriority ) + { + portYIELD_WITHIN_API(); + } + } + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + void vTaskDelete( xTaskHandle pxTaskToDelete ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + /* Ensure a yield is performed if the current task is being + deleted. */ + if( pxTaskToDelete == pxCurrentTCB ) + { + pxTaskToDelete = NULL; + } + + /* If null is passed in here then we are deleting ourselves. */ + pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); + + /* Remove task from the ready list and place in the termination list. + This will stop the task from be scheduled. The idle task will check + the termination list and free up any memory allocated by the + scheduler for the TCB and stack. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Is the task waiting on an event also? */ + if( pxTCB->xEventListItem.pvContainer ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + } + + vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); + + /* Increment the ucTasksDeleted variable so the idle task knows + there is a task that has been deleted and that it should therefore + check the xTasksWaitingTermination list. */ + ++uxTasksDeleted; + + /* Increment the uxTaskNumberVariable also so kernel aware debuggers + can detect that the task lists need re-generating. */ + uxTaskNumber++; + + traceTASK_DELETE( pxTCB ); + } + taskEXIT_CRITICAL(); + + /* Force a reschedule if we have just deleted the current task. */ + if( xSchedulerRunning != pdFALSE ) + { + if( ( void * ) pxTaskToDelete == NULL ) + { + portYIELD_WITHIN_API(); + } + } + } + +#endif + + + + + + +/*----------------------------------------------------------- + * TASK CONTROL API documented in task.h + *----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelayUntil == 1 ) + + void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) + { + portTickType xTimeToWake; + portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; + + configASSERT( pxPreviousWakeTime ); + configASSERT( ( xTimeIncrement > 0 ) ); + + vTaskSuspendAll(); + { + /* Generate the tick time at which the task wants to wake. */ + xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; + + if( xTickCount < *pxPreviousWakeTime ) + { + /* The tick count has overflowed since this function was + lasted called. In this case the only time we should ever + actually delay is if the wake time has also overflowed, + and the wake time is greater than the tick time. When this + is the case it is as if neither time had overflowed. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) + { + xShouldDelay = pdTRUE; + } + } + else + { + /* The tick time has not overflowed. In this case we will + delay if either the wake time has overflowed, and/or the + tick time is less than the wake time. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) + { + xShouldDelay = pdTRUE; + } + } + + /* Update the wake time ready for the next call. */ + *pxPreviousWakeTime = xTimeToWake; + + if( xShouldDelay != pdFALSE ) + { + traceTASK_DELAY_UNTIL(); + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + } + xAlreadyYielded = xTaskResumeAll(); + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( !xAlreadyYielded ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelay == 1 ) + + void vTaskDelay( portTickType xTicksToDelay ) + { + portTickType xTimeToWake; + signed portBASE_TYPE xAlreadyYielded = pdFALSE; + + /* A delay time of zero just forces a reschedule. */ + if( xTicksToDelay > ( portTickType ) 0 ) + { + vTaskSuspendAll(); + { + traceTASK_DELAY(); + + /* A task that is removed from the event list while the + scheduler is suspended will not get placed in the ready + list or removed from the blocked list until the scheduler + is resumed. + + This task cannot be in an event list as it is the currently + executing task. */ + + /* Calculate the time to wake - this may overflow but this is + not a problem. */ + xTimeToWake = xTickCount + xTicksToDelay; + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + xAlreadyYielded = xTaskResumeAll(); + } + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( !xAlreadyYielded ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskPriorityGet == 1 ) + + unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) + { + tskTCB *pxTCB; + unsigned portBASE_TYPE uxReturn; + + taskENTER_CRITICAL(); + { + /* If null is passed in here then we are changing the + priority of the calling function. */ + pxTCB = prvGetTCBFromHandle( pxTask ); + uxReturn = pxTCB->uxPriority; + } + taskEXIT_CRITICAL(); + + return uxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskPrioritySet == 1 ) + + void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) + { + tskTCB *pxTCB; + unsigned portBASE_TYPE uxCurrentPriority; + portBASE_TYPE xYieldRequired = pdFALSE; + + configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) ); + + /* Ensure the new priority is valid. */ + if( uxNewPriority >= configMAX_PRIORITIES ) + { + uxNewPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; + } + + taskENTER_CRITICAL(); + { + if( pxTask == pxCurrentTCB ) + { + pxTask = NULL; + } + + /* If null is passed in here then we are changing the + priority of the calling function. */ + pxTCB = prvGetTCBFromHandle( pxTask ); + + traceTASK_PRIORITY_SET( pxTask, uxNewPriority ); + + #if ( configUSE_MUTEXES == 1 ) + { + uxCurrentPriority = pxTCB->uxBasePriority; + } + #else + { + uxCurrentPriority = pxTCB->uxPriority; + } + #endif + + if( uxCurrentPriority != uxNewPriority ) + { + /* The priority change may have readied a task of higher + priority than the calling task. */ + if( uxNewPriority > uxCurrentPriority ) + { + if( pxTask != NULL ) + { + /* The priority of another task is being raised. If we + were raising the priority of the currently running task + there would be no need to switch as it must have already + been the highest priority task. */ + xYieldRequired = pdTRUE; + } + } + else if( pxTask == NULL ) + { + /* Setting our own priority down means there may now be another + task of higher priority that is ready to execute. */ + xYieldRequired = pdTRUE; + } + + + + #if ( configUSE_MUTEXES == 1 ) + { + /* Only change the priority being used if the task is not + currently using an inherited priority. */ + if( pxTCB->uxBasePriority == pxTCB->uxPriority ) + { + pxTCB->uxPriority = uxNewPriority; + } + + /* The base priority gets set whatever. */ + pxTCB->uxBasePriority = uxNewPriority; + } + #else + { + pxTCB->uxPriority = uxNewPriority; + } + #endif + + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); + + /* If the task is in the blocked or suspended list we need do + nothing more than change it's priority variable. However, if + the task is in a ready list it needs to be removed and placed + in the queue appropriate to its new priority. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) + { + /* The task is currently in its ready list - remove before adding + it to it's new ready list. As we are in a critical section we + can do this even if the scheduler is suspended. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + + if( xYieldRequired == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + taskEXIT_CRITICAL(); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskSuspend( xTaskHandle pxTaskToSuspend ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + /* Ensure a yield is performed if the current task is being + suspended. */ + if( pxTaskToSuspend == pxCurrentTCB ) + { + pxTaskToSuspend = NULL; + } + + /* If null is passed in here then we are suspending ourselves. */ + pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); + + traceTASK_SUSPEND( pxTCB ); + + /* Remove task from the ready/delayed list and place in the suspended list. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Is the task waiting on an event also? */ + if( pxTCB->xEventListItem.pvContainer ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + } + + vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); + } + taskEXIT_CRITICAL(); + + if( ( void * ) pxTaskToSuspend == NULL ) + { + if( xSchedulerRunning != pdFALSE ) + { + /* We have just suspended the current task. */ + portYIELD_WITHIN_API(); + } + else + { + /* The scheduler is not running, but the task that was pointed + to by pxCurrentTCB has just been suspended and pxCurrentTCB + must be adjusted to point to a different task. */ + if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) + { + /* No other tasks are ready, so set pxCurrentTCB back to + NULL so when the next task is created pxCurrentTCB will + be set to point to it no matter what its relative priority + is. */ + pxCurrentTCB = NULL; + } + else + { + vTaskSwitchContext(); + } + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) + { + portBASE_TYPE xReturn = pdFALSE; + const tskTCB * const pxTCB = ( tskTCB * ) xTask; + + /* It does not make sense to check if the calling task is suspended. */ + configASSERT( xTask ); + + /* Is the task we are attempting to resume actually in the + suspended list? */ + if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) + { + /* Has the task already been resumed from within an ISR? */ + if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) + { + /* Is it in the suspended list because it is in the + Suspended state? It is possible to be in the suspended + list because it is blocked on a task with no timeout + specified. */ + if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) + { + xReturn = pdTRUE; + } + } + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskResume( xTaskHandle pxTaskToResume ) + { + tskTCB *pxTCB; + + /* It does not make sense to resume the calling task. */ + configASSERT( pxTaskToResume ); + + /* Remove the task from whichever list it is currently in, and place + it in the ready list. */ + pxTCB = ( tskTCB * ) pxTaskToResume; + + /* The parameter cannot be NULL as it is impossible to resume the + currently executing task. */ + if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) + { + taskENTER_CRITICAL(); + { + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME( pxTCB ); + + /* As we are in a critical section we can access the ready + lists even if the scheduler is suspended. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + + /* We may have just resumed a higher priority task. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* This yield may not cause the task just resumed to run, but + will leave the lists in the correct state for the next yield. */ + portYIELD_WITHIN_API(); + } + } + } + taskEXIT_CRITICAL(); + } + } + +#endif + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) + + portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) + { + portBASE_TYPE xYieldRequired = pdFALSE; + tskTCB *pxTCB; + + configASSERT( pxTaskToResume ); + + pxTCB = ( tskTCB * ) pxTaskToResume; + + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME_FROM_ISR( pxTCB ); + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed, at which point a + yield will be performed if necessary. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + } + + return xYieldRequired; + } + +#endif + + + + +/*----------------------------------------------------------- + * PUBLIC SCHEDULER CONTROL documented in task.h + *----------------------------------------------------------*/ + + +void vTaskStartScheduler( void ) +{ +portBASE_TYPE xReturn; + + /* Add the idle task at the lowest priority. */ + xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), ( xTaskHandle * ) NULL ); + + #if ( configUSE_TIMERS == 1 ) + { + if( xReturn == pdPASS ) + { + xReturn = xTimerCreateTimerTask(); + } + } + #endif + + if( xReturn == pdPASS ) + { + /* Interrupts are turned off here, to ensure a tick does not occur + before or during the call to xPortStartScheduler(). The stacks of + the created tasks contain a status word with interrupts switched on + so interrupts will automatically get re-enabled when the first task + starts to run. + + STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE + DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ + portDISABLE_INTERRUPTS(); + + xSchedulerRunning = pdTRUE; + xTickCount = ( portTickType ) 0; + + /* If configGENERATE_RUN_TIME_STATS is defined then the following + macro must be defined to configure the timer/counter used to generate + the run time counter time base. */ + portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); + + /* Setting up the timer tick is hardware specific and thus in the + portable interface. */ + if( xPortStartScheduler() ) + { + /* Should not reach here as if the scheduler is running the + function will not return. */ + } + else + { + /* Should only reach here if a task calls xTaskEndScheduler(). */ + } + } + + /* This line will only be reached if the kernel could not be started. */ + configASSERT( xReturn ); +} +/*-----------------------------------------------------------*/ + +void vTaskEndScheduler( void ) +{ + /* Stop the scheduler interrupts and call the portable scheduler end + routine so the original ISRs can be restored if necessary. The port + layer must ensure interrupts enable bit is left in the correct state. */ + portDISABLE_INTERRUPTS(); + xSchedulerRunning = pdFALSE; + vPortEndScheduler(); +} +/*----------------------------------------------------------*/ + +void vTaskSuspendAll( void ) +{ + /* A critical section is not required as the variable is of type + portBASE_TYPE. */ + ++uxSchedulerSuspended; +} +/*----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskResumeAll( void ) +{ +register tskTCB *pxTCB; +signed portBASE_TYPE xAlreadyYielded = pdFALSE; + + /* If uxSchedulerSuspended is zero then this function does not match a + previous call to vTaskSuspendAll(). */ + configASSERT( uxSchedulerSuspended ); + + /* It is possible that an ISR caused a task to be removed from an event + list while the scheduler was suspended. If this was the case then the + removed task will have been added to the xPendingReadyList. Once the + scheduler has been resumed it is safe to move all the pending ready + tasks from this list into their appropriate ready list. */ + taskENTER_CRITICAL(); + { + --uxSchedulerSuspended; + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0 ) + { + portBASE_TYPE xYieldRequired = pdFALSE; + + /* Move any readied tasks from the pending list into the + appropriate ready list. */ + while( listLIST_IS_EMPTY( ( xList * ) &xPendingReadyList ) == pdFALSE ) + { + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ); + vListRemove( &( pxTCB->xEventListItem ) ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + + /* If we have moved a task that has a priority higher than + the current task then we should yield. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xYieldRequired = pdTRUE; + } + } + + /* If any ticks occurred while the scheduler was suspended then + they should be processed now. This ensures the tick count does not + slip, and that any delayed tasks are resumed at the correct time. */ + if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) + { + while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) + { + vTaskIncrementTick(); + --uxMissedTicks; + } + + /* As we have processed some ticks it is appropriate to yield + to ensure the highest priority task that is ready to run is + the task actually running. */ + #if configUSE_PREEMPTION == 1 + { + xYieldRequired = pdTRUE; + } + #endif + } + + if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) + { + xAlreadyYielded = pdTRUE; + xMissedYield = pdFALSE; + portYIELD_WITHIN_API(); + } + } + } + } + taskEXIT_CRITICAL(); + + return xAlreadyYielded; +} + + + + + + +/*----------------------------------------------------------- + * PUBLIC TASK UTILITIES documented in task.h + *----------------------------------------------------------*/ + + + +portTickType xTaskGetTickCount( void ) +{ +portTickType xTicks; + + /* Critical section required if running on a 16 bit processor. */ + taskENTER_CRITICAL(); + { + xTicks = xTickCount; + } + taskEXIT_CRITICAL(); + + return xTicks; +} +/*-----------------------------------------------------------*/ + +portTickType xTaskGetTickCountFromISR( void ) +{ +portTickType xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + xReturn = xTickCount; + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) +{ + /* A critical section is not required because the variables are of type + portBASE_TYPE. */ + return uxCurrentNumberOfTasks; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTaskList( signed char *pcWriteBuffer ) + { + unsigned portBASE_TYPE uxQueue; + + /* This is a VERY costly function that should be used for debug only. + It leaves interrupts disabled for a LONG time. */ + + vTaskSuspendAll(); + { + /* Run through all the lists that could potentially contain a TCB and + report the task name, state and stack high water mark. */ + + *pcWriteBuffer = ( signed char ) 0x00; + strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); + + uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; + + do + { + uxQueue--; + + if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); + } + + if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); + } + + #if( INCLUDE_vTaskDelete == 1 ) + { + if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, tskDELETED_CHAR ); + } + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, tskSUSPENDED_CHAR ); + } + } + #endif + } + xTaskResumeAll(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) + { + unsigned portBASE_TYPE uxQueue; + unsigned long ulTotalRunTime; + + /* This is a VERY costly function that should be used for debug only. + It leaves interrupts disabled for a LONG time. */ + + vTaskSuspendAll(); + { + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime ); + #else + ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + + /* Divide ulTotalRunTime by 100 to make the percentage caluclations + simpler in the prvGenerateRunTimeStatsForTasksInList() function. */ + ulTotalRunTime /= 100UL; + + /* Run through all the lists that could potentially contain a TCB, + generating a table of run timer percentages in the provided + buffer. */ + + *pcWriteBuffer = ( signed char ) 0x00; + strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); + + uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; + + do + { + uxQueue--; + + if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); + } + + if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); + } + + #if ( INCLUDE_vTaskDelete == 1 ) + { + if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, ulTotalRunTime ); + } + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, ulTotalRunTime ); + } + } + #endif + } + xTaskResumeAll(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) + { + configASSERT( pcBuffer ); + configASSERT( ulBufferSize ); + + taskENTER_CRITICAL(); + { + pcTraceBuffer = ( signed char * )pcBuffer; + pcTraceBufferStart = pcBuffer; + pcTraceBufferEnd = pcBuffer + ( ulBufferSize - tskSIZE_OF_EACH_TRACE_LINE ); + xTracing = pdTRUE; + } + taskEXIT_CRITICAL(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + unsigned long ulTaskEndTrace( void ) + { + unsigned long ulBufferLength; + + taskENTER_CRITICAL(); + xTracing = pdFALSE; + taskEXIT_CRITICAL(); + + ulBufferLength = ( unsigned long ) ( pcTraceBuffer - pcTraceBufferStart ); + + return ulBufferLength; + } + +#endif + + + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + * documented in task.h + *----------------------------------------------------------*/ + + +void vTaskIncrementTick( void ) +{ +tskTCB * pxTCB; + + /* Called by the portable layer each time a tick interrupt occurs. + Increments the tick then checks to see if the new tick value will cause any + tasks to be unblocked. */ + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + ++xTickCount; + if( xTickCount == ( portTickType ) 0 ) + { + xList *pxTemp; + + /* Tick count has overflowed so we need to swap the delay lists. + If there are any items in pxDelayedTaskList here then there is + an error! */ + configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) ); + + pxTemp = pxDelayedTaskList; + pxDelayedTaskList = pxOverflowDelayedTaskList; + pxOverflowDelayedTaskList = pxTemp; + xNumOfOverflows++; + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) + { + /* The new current delayed list is empty. Set + xNextTaskUnblockTime to the maximum possible value so it is + extremely unlikely that the + if( xTickCount >= xNextTaskUnblockTime ) test will pass until + there is an item in the delayed list. */ + xNextTaskUnblockTime = portMAX_DELAY; + } + else + { + /* The new current delayed list is not empty, get the value of + the item at the head of the delayed list. This is the time at + which the task at the head of the delayed list should be removed + from the Blocked state. */ + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); + xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); + } + } + + /* See if this tick has made a timeout expire. */ + prvCheckDelayedTasks(); + } + else + { + ++uxMissedTicks; + + /* The tick hook gets called at regular intervals, even if the + scheduler is locked. */ + #if ( configUSE_TICK_HOOK == 1 ) + { + vApplicationTickHook(); + } + #endif + } + + #if ( configUSE_TICK_HOOK == 1 ) + { + /* Guard against the tick hook being called when the missed tick + count is being unwound (when the scheduler is being unlocked. */ + if( uxMissedTicks == ( unsigned portBASE_TYPE ) 0U ) + { + vApplicationTickHook(); + } + } + #endif + + traceTASK_INCREMENT_TICK( xTickCount ); +} +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_vTaskCleanUpResources == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) + + void vTaskCleanUpResources( void ) + { + unsigned short usQueue; + volatile tskTCB *pxTCB; + + usQueue = ( unsigned short ) uxTopUsedPriority + ( unsigned short ) 1; + + /* Remove any TCB's from the ready queues. */ + do + { + usQueue--; + + while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ usQueue ] ) ) == pdFALSE ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &( pxReadyTasksLists[ usQueue ] ) ); + vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); + + prvDeleteTCB( ( tskTCB * ) pxTCB ); + } + }while( usQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + /* Remove any TCB's from the delayed queue. */ + while( listLIST_IS_EMPTY( &xDelayedTaskList1 ) == pdFALSE ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList1 ); + vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); + + prvDeleteTCB( ( tskTCB * ) pxTCB ); + } + + /* Remove any TCB's from the overflow delayed queue. */ + while( listLIST_IS_EMPTY( &xDelayedTaskList2 ) == pdFALSE ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList2 ); + vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); + + prvDeleteTCB( ( tskTCB * ) pxTCB ); + } + + while( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xSuspendedTaskList ); + vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); + + prvDeleteTCB( ( tskTCB * ) pxTCB ); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) + { + tskTCB *xTCB; + + /* If xTask is NULL then we are setting our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + xTCB->pxTaskTag = pxHookFunction; + taskEXIT_CRITICAL(); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) + { + tskTCB *xTCB; + pdTASK_HOOK_CODE xReturn; + + /* If xTask is NULL then we are setting our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + xReturn = xTCB->pxTaskTag; + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) + { + tskTCB *xTCB; + portBASE_TYPE xReturn; + + /* If xTask is NULL then we are calling our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + if( xTCB->pxTaskTag != NULL ) + { + xReturn = xTCB->pxTaskTag( pvParameter ); + } + else + { + xReturn = pdFAIL; + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +void vTaskSwitchContext( void ) +{ + if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) + { + /* The scheduler is currently suspended - do not allow a context + switch. */ + xMissedYield = pdTRUE; + } + else + { + traceTASK_SWITCHED_OUT(); + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + unsigned long ulTempCounter; + + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ulTempCounter ); + #else + ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + + /* Add the amount of time the task has been running to the accumulated + time so far. The time the task started running was stored in + ulTaskSwitchedInTime. Note that there is no overflow protection here + so count values are only valid until the timer overflows. Generally + this will be about 1 hour assuming a 1uS timer increment. */ + pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); + ulTaskSwitchedInTime = ulTempCounter; + } + #endif + + taskFIRST_CHECK_FOR_STACK_OVERFLOW(); + taskSECOND_CHECK_FOR_STACK_OVERFLOW(); + + /* Find the highest priority queue that contains ready tasks. */ + while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) + { + configASSERT( uxTopReadyPriority ); + --uxTopReadyPriority; + } + + /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the + same priority get an equal share of the processor time. */ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); + + traceTASK_SWITCHED_IN(); + vWriteTraceToBuffer(); + } +} +/*-----------------------------------------------------------*/ + +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) +{ +portTickType xTimeToWake; + + configASSERT( pxEventList ); + + /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED. */ + + /* Place the event list item of the TCB in the appropriate event list. + This is placed in the list in priority order so the highest priority task + is the first to be woken by the event. */ + vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); + + /* We must remove ourselves from the ready list before adding ourselves + to the blocked list as the same list item is used for both lists. We have + exclusive access to the ready lists as the scheduler is locked. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( xTicksToWait == portMAX_DELAY ) + { + /* Add ourselves to the suspended task list instead of a delayed task + list to ensure we are not woken by a timing event. We will block + indefinitely. */ + vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + } + #else + { + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + #endif +} +/*-----------------------------------------------------------*/ + +#if configUSE_TIMERS == 1 + + void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) + { + portTickType xTimeToWake; + + configASSERT( pxEventList ); + + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements - + it should be called from a critical section. */ + + + /* Place the event list item of the TCB in the appropriate event list. + In this case it is assume that this is the only task that is going to + be waiting on this event list, so the faster vListInsertEnd() function + can be used in place of vListInsert. */ + vListInsertEnd( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); + + /* We must remove this task from the ready list before adding it to the + blocked list as the same list item is used for both lists. This + function is called form a critical section. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + +#endif /* configUSE_TIMERS */ +/*-----------------------------------------------------------*/ + +#include "assert.h" +extern volatile portBASE_TYPE xInterruptsEnabled; +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) +{ +tskTCB *pxUnblockedTCB; +portBASE_TYPE xReturn; + + /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED. It can also be called from within an ISR. */ + + assert( uxSchedulerSuspended || xInterruptsEnabled == pdFALSE); + + /* The event list is sorted in priority order, so we can remove the + first in the list, remove the TCB from the delayed list, and add + it to the ready list. + + If an event is for a queue that is locked then this function will never + get called - the lock count on the queue will get modified instead. This + means we can always expect exclusive access to the event list here. + + This function assumes that a check has already been made to ensure that + pxEventList is not empty. */ + pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); + configASSERT( pxUnblockedTCB ); + vListRemove( &( pxUnblockedTCB->xEventListItem ) ); + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxUnblockedTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); + } + + if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* Return true if the task removed from the event list has + a higher priority than the calling task. This allows + the calling task to know if it should force a context + switch now. */ + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) +{ + configASSERT( pxTimeOut ); + pxTimeOut->xOverflowCount = xNumOfOverflows; + pxTimeOut->xTimeOnEntering = xTickCount; +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) +{ +portBASE_TYPE xReturn; + + configASSERT( pxTimeOut ); + configASSERT( pxTicksToWait ); + + taskENTER_CRITICAL(); + { + #if ( INCLUDE_vTaskSuspend == 1 ) + /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is + the maximum block time then the task should block indefinitely, and + therefore never time out. */ + if( *pxTicksToWait == portMAX_DELAY ) + { + xReturn = pdFALSE; + } + else /* We are not blocking indefinitely, perform the checks below. */ + #endif + + if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) + { + /* The tick count is greater than the time at which vTaskSetTimeout() + was called, but has also overflowed since vTaskSetTimeOut() was called. + It must have wrapped all the way around and gone past us again. This + passed since vTaskSetTimeout() was called. */ + xReturn = pdTRUE; + } + else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) + { + /* Not a genuine timeout. Adjust parameters for time remaining. */ + *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); + vTaskSetTimeOutState( pxTimeOut ); + xReturn = pdFALSE; + } + else + { + xReturn = pdTRUE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskMissedYield( void ) +{ + xMissedYield = pdTRUE; +} + +/* + * ----------------------------------------------------------- + * The Idle task. + * ---------------------------------------------------------- + * + * The portTASK_FUNCTION() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION( prvIdleTask, pvParameters ) +{ + /* Stop warnings. */ + ( void ) pvParameters; + int last_idle_time = clock(); + for( ;; ) + { + /* See if any tasks have been deleted. */ + prvCheckTasksWaitingTermination(); + + #if ( configUSE_PREEMPTION == 0 ) + { + /* If we are not using preemption we keep forcing a task switch to + see if any other task has become available. If we are using + preemption we don't need to do this as any task becoming available + will automatically get the processor anyway. */ + taskYIELD(); + } + #endif + + #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) + { + /* When using preemption tasks of equal priority will be + timesliced. If a task that is sharing the idle priority is ready + to run then the idle task should yield before the end of the + timeslice. + + A critical region is not required here as we are just reading from + the list, and an occasional incorrect value will not matter. If + the ready list at the idle priority contains more than one task + then a task other than the idle task is ready to execute. */ + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) + { + taskYIELD(); + } + } + #endif + + #if ( configUSE_IDLE_HOOK == 1 ) + { + extern void vApplicationIdleHook( void ); + + /* Call the user defined function from within the idle task. This + allows the application designer to add background functionality + without the overhead of a separate task. + NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, + CALL A FUNCTION THAT MIGHT BLOCK. */ + while(clock() < (last_idle_time + 1)) + sched_yield(); + last_idle_time = clock(); + vApplicationIdleHook(); + } + #endif + + + //usleep(5); + } +} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ + + + + + + + +/*----------------------------------------------------------- + * File private functions documented at the top of the file. + *----------------------------------------------------------*/ + + + +static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) +{ + /* Store the function name in the TCB. */ + #if configMAX_TASK_NAME_LEN > 1 + { + /* Don't bring strncpy into the build unnecessarily. */ + strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); + } + #endif + pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = ( signed char ) '\0'; + + /* This is used as an array index so must ensure it's not too large. First + remove the privilege bit if one is present. */ + if( uxPriority >= configMAX_PRIORITIES ) + { + uxPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; + } + + pxTCB->uxPriority = uxPriority; + #if ( configUSE_MUTEXES == 1 ) + { + pxTCB->uxBasePriority = uxPriority; + } + #endif + + vListInitialiseItem( &( pxTCB->xGenericListItem ) ); + vListInitialiseItem( &( pxTCB->xEventListItem ) ); + + /* Set the pxTCB as a link back from the xListItem. This is so we can get + back to the containing TCB from a generic item in a list. */ + listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); + listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + { + pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0; + } + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + { + pxTCB->pxTaskTag = NULL; + } + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + pxTCB->ulRunTimeCounter = 0UL; + } + #endif + + #if ( portUSING_MPU_WRAPPERS == 1 ) + { + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); + } + #else + { + ( void ) xRegions; + ( void ) usStackDepth; + } + #endif +} +/*-----------------------------------------------------------*/ + +#if ( portUSING_MPU_WRAPPERS == 1 ) + + void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) + { + tskTCB *pxTCB; + + if( xTaskToModify == pxCurrentTCB ) + { + xTaskToModify = NULL; + } + + /* If null is passed in here then we are deleting ourselves. */ + pxTCB = prvGetTCBFromHandle( xTaskToModify ); + + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); + } + /*-----------------------------------------------------------*/ +#endif + +static void prvInitialiseTaskLists( void ) +{ +unsigned portBASE_TYPE uxPriority; + + for( uxPriority = ( unsigned portBASE_TYPE ) 0U; uxPriority < configMAX_PRIORITIES; uxPriority++ ) + { + vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); + } + + vListInitialise( ( xList * ) &xDelayedTaskList1 ); + vListInitialise( ( xList * ) &xDelayedTaskList2 ); + vListInitialise( ( xList * ) &xPendingReadyList ); + + #if ( INCLUDE_vTaskDelete == 1 ) + { + vListInitialise( ( xList * ) &xTasksWaitingTermination ); + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + vListInitialise( ( xList * ) &xSuspendedTaskList ); + } + #endif + + /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList + using list2. */ + pxDelayedTaskList = &xDelayedTaskList1; + pxOverflowDelayedTaskList = &xDelayedTaskList2; +} +/*-----------------------------------------------------------*/ + +static void prvCheckTasksWaitingTermination( void ) +{ + #if ( INCLUDE_vTaskDelete == 1 ) + { + portBASE_TYPE xListIsEmpty; + + /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called + too often in the idle task. */ + if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0 ) + { + vTaskSuspendAll(); + xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); + xTaskResumeAll(); + + if( xListIsEmpty == pdFALSE ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); + vListRemove( &( pxTCB->xGenericListItem ) ); + --uxCurrentNumberOfTasks; + --uxTasksDeleted; + } + taskEXIT_CRITICAL(); + + prvDeleteTCB( pxTCB ); + } + } + } + #endif +} +/*-----------------------------------------------------------*/ + +static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) +{ + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xTickCount ) + { + /* Wake time has overflowed. Place this item in the overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the current block list. */ + vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + /* If the task entering the blocked state was placed at the head of the + list of blocked tasks then xNextTaskUnblockTime needs to be updated + too. */ + if( xTimeToWake < xNextTaskUnblockTime ) + { + xNextTaskUnblockTime = xTimeToWake; + } + } +} +/*-----------------------------------------------------------*/ + +static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) +{ +tskTCB *pxNewTCB; + + /* Allocate space for the TCB. Where the memory comes from depends on + the implementation of the port malloc function. */ + pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); + + if( pxNewTCB != NULL ) + { + /* Allocate space for the stack used by the task being created. + The base of the stack memory stored in the TCB so the task can + be deleted later if required. */ + pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); + + if( pxNewTCB->pxStack == NULL ) + { + /* Could not allocate the stack. Delete the allocated TCB. */ + vPortFree( pxNewTCB ); + pxNewTCB = NULL; + } + else + { + /* Just to help debugging. */ + memset( pxNewTCB->pxStack, tskSTACK_FILL_BYTE, usStackDepth * sizeof( portSTACK_TYPE ) ); + } + } + + return pxNewTCB; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) + { + volatile tskTCB *pxNextTCB, *pxFirstTCB; + unsigned short usStackRemaining; + + /* Write the details of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + #if ( portSTACK_GROWTH > 0 ) + { + usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); + } + #else + { + usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); + } + #endif + + sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); + + } while( pxNextTCB != pxFirstTCB ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) + { + volatile tskTCB *pxNextTCB, *pxFirstTCB; + unsigned long ulStatsAsPercentage; + + /* Write the run time stats of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + /* Get next TCB in from the list. */ + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + + /* Divide by zero check. */ + if( ulTotalRunTime > 0UL ) + { + /* Has the task run at all? */ + if( pxNextTCB->ulRunTimeCounter == 0 ) + { + /* The task has used no CPU time at all. */ + sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); + } + else + { + /* What percentage of the total run time has the task used? + This will always be rounded down to the nearest integer. + ulTotalRunTime has already been divided by 100. */ + ulStatsAsPercentage = pxNextTCB->ulRunTimeCounter / ulTotalRunTime; + + if( ulStatsAsPercentage > 0UL ) + { + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t%lu%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter, ulStatsAsPercentage ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); + } + #endif + } + else + { + /* If the percentage is zero here then the task has + consumed less than 1% of the total run time. */ + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t<1%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); + } + #endif + } + } + + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); + } + + } while( pxNextTCB != pxFirstTCB ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetRunTime == 1 ) +unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) +{ + unsigned long runTime; + + tskTCB *pxTCB; + pxTCB = prvGetTCBFromHandle( xTask ); + runTime = pxTCB->ulRunTimeCounter; + pxTCB->ulRunTimeCounter = 0; + return runTime; +} + +#endif +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) + + static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) + { + register unsigned short usCount = 0; + + while( *pucStackByte == tskSTACK_FILL_BYTE ) + { + pucStackByte -= portSTACK_GROWTH; + usCount++; + } + + usCount /= sizeof( portSTACK_TYPE ); + + return usCount; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) + + unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) + { + tskTCB *pxTCB; + unsigned char *pcEndOfStack; + unsigned portBASE_TYPE uxReturn; + + pxTCB = prvGetTCBFromHandle( xTask ); + + #if portSTACK_GROWTH < 0 + { + pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; + } + #else + { + pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; + } + #endif + + uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); + + return uxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) + + static void prvDeleteTCB( tskTCB *pxTCB ) + { + /* Free up the memory allocated by the scheduler for the task. It is up to + the task to free any memory allocated at the application level. */ + vPortFreeAligned( pxTCB->pxStack ); + vPortFree( pxTCB ); + } + +#endif + + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) + + xTaskHandle xTaskGetCurrentTaskHandle( void ) + { + xTaskHandle xReturn; + + /* A critical section is not required as this is not called from + an interrupt and the current TCB will always be the same for any + individual execution thread. */ + xReturn = pxCurrentTCB; + + return xReturn; + } + +#endif + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + + portBASE_TYPE xTaskGetSchedulerState( void ) + { + portBASE_TYPE xReturn; + + if( xSchedulerRunning == pdFALSE ) + { + xReturn = taskSCHEDULER_NOT_STARTED; + } + else + { + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xReturn = taskSCHEDULER_RUNNING; + } + else + { + xReturn = taskSCHEDULER_SUSPENDED; + } + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) + { + tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; + + configASSERT( pxMutexHolder ); + + if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) + { + /* Adjust the mutex holder state to account for its new priority. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); + + /* If the task being modified is in the ready state it will need to + be moved in to a new list. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) ) + { + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Inherit the priority before being moved into the new list. */ + pxTCB->uxPriority = pxCurrentTCB->uxPriority; + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* Just inherit the priority. */ + pxTCB->uxPriority = pxCurrentTCB->uxPriority; + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) + { + tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; + + if( pxMutexHolder != NULL ) + { + if( pxTCB->uxPriority != pxTCB->uxBasePriority ) + { + /* We must be the running task to be able to give the mutex back. + Remove ourselves from the ready list we currently appear in. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Disinherit the priority before adding ourselves into the new + ready list. */ + pxTCB->uxPriority = pxTCB->uxBasePriority; + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); + prvAddTaskToReadyQueue( pxTCB ); + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + + void vTaskEnterCritical( void ) + { + portDISABLE_INTERRUPTS(); + + if( xSchedulerRunning != pdFALSE ) + { + ( pxCurrentTCB->uxCriticalNesting )++; + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + +void vTaskExitCritical( void ) +{ + if( xSchedulerRunning != pdFALSE ) + { + if( pxCurrentTCB->uxCriticalNesting > 0 ) + { + ( pxCurrentTCB->uxCriticalNesting )--; + + if( pxCurrentTCB->uxCriticalNesting == 0 ) + { + portENABLE_INTERRUPTS(); + } + } + } +} + +#endif +/*-----------------------------------------------------------*/ + +static void printNamesInList( const signed char *pcWriteBuffer, xList *pxList) +{ + volatile tskTCB *pxNextTCB, *pxFirstTCB; + char pcStatsString[100]; + /* Write the run time stats of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + /* Get next TCB in from the list. */ + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + if(pxNextTCB) { + sprintf( pcStatsString, ( char * ) "%s, ", pxNextTCB->pcTaskName); + + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); + } + + } while( pxNextTCB != pxFirstTCB ); +} + +void printTasks() +{ + signed char pcWriteBuffer[500]; + int uxQueue; + taskENTER_CRITICAL(); + { + /* Run through all the lists that could potentially contain a TCB, + generating a table of run timer percentages in the provided + buffer. */ + + pcWriteBuffer[ 0 ] = ( signed char ) 0x00; + + uxQueue = uxTopUsedPriority + 1; + + do + { + uxQueue--; + + if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) + { + char readyMessage[30]; + sprintf(readyMessage, "\r\nReady priority %d: ", uxQueue); + strcat( ( char * ) pcWriteBuffer,readyMessage); + printNamesInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] )); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) + { + strcat( ( char * ) pcWriteBuffer, "\r\nDelay: "); + printNamesInList( pcWriteBuffer, ( xList * ) &( pxDelayedTaskList)); + } + + if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) + { + strcat( ( char * ) pcWriteBuffer, "\r\nDelay Overflow: "); + printNamesInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList); + } + + if( !listLIST_IS_EMPTY( &xPendingReadyList ) ) + { + strcat( ( char * ) pcWriteBuffer, "\r\nPending ready: "); + printNamesInList( pcWriteBuffer, ( xList * ) &xPendingReadyList); + } + +#if ( INCLUDE_vTaskDelete == 1 ) + { + if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) + { + strcat( ( char * ) pcWriteBuffer, "\r\nWaiting termination: "); + printNamesInList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination); + } + } +#endif + +#if ( INCLUDE_vTaskSuspend == 1 ) + { + if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) + { + strcat( ( char * ) pcWriteBuffer, "\r\nSuspended: "); + printNamesInList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList); + } + } +#endif + } + strcat( (char *) pcWriteBuffer, "\r\n\r\n"); + fprintf(stderr, "%s", ( char * ) pcWriteBuffer); + taskEXIT_CRITICAL(); + +} + + diff --git a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/timers.c b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/timers.c index 7e5ef22ad..1dd7555a0 100644 --- a/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/timers.c +++ b/flight/PiOS.osx/osx/Libraries/FreeRTOS/Source/timers.c @@ -1,649 +1,649 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: - Atollic AB - Atollic provides professional embedded systems development - tools for C/C++ development, code analysis and test automation. - See http://www.atollic.com - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "queue.h" -#include "timers.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* This entire source file will be skipped if the application is not configured -to include software timer functionality. This #if is closed at the very bottom -of this file. If you want to include software timer functionality then ensure -configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ -#if ( configUSE_TIMERS == 1 ) - -/* Misc definitions. */ -#define tmrNO_DELAY ( portTickType ) 0U - -/* The definition of the timers themselves. */ -typedef struct tmrTimerControl -{ - const signed char *pcTimerName; /*<< Text name. This is not used by the kernel, it is included simply to make debugging easier. */ - xListItem xTimerListItem; /*<< Standard linked list item as used by all kernel features for event management. */ - portTickType xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */ - unsigned portBASE_TYPE uxAutoReload; /*<< Set to pdTRUE if the timer should be automatically restarted once expired. Set to pdFALSE if the timer is, in effect, a one shot timer. */ - void *pvTimerID; /*<< An ID to identify the timer. This allows the timer to be identified when the same callback is used for multiple timers. */ - tmrTIMER_CALLBACK pxCallbackFunction; /*<< The function that will be called when the timer expires. */ -} xTIMER; - -/* The definition of messages that can be sent and received on the timer -queue. */ -typedef struct tmrTimerQueueMessage -{ - portBASE_TYPE xMessageID; /*<< The command being sent to the timer service task. */ - portTickType xMessageValue; /*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */ - xTIMER * pxTimer; /*<< The timer to which the command will be applied. */ -} xTIMER_MESSAGE; - - -/* The list in which active timers are stored. Timers are referenced in expire -time order, with the nearest expiry time at the front of the list. Only the -timer service task is allowed to access xActiveTimerList. */ -PRIVILEGED_DATA static xList xActiveTimerList1; -PRIVILEGED_DATA static xList xActiveTimerList2; -PRIVILEGED_DATA static xList *pxCurrentTimerList; -PRIVILEGED_DATA static xList *pxOverflowTimerList; - -/* A queue that is used to send commands to the timer service task. */ -PRIVILEGED_DATA static xQueueHandle xTimerQueue = NULL; - -/*-----------------------------------------------------------*/ - -/* - * Initialise the infrastructure used by the timer service task if it has not - * been initialised already. - */ -static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION; - -/* - * The timer service task (daemon). Timer functionality is controlled by this - * task. Other tasks communicate with the timer service task using the - * xTimerQueue queue. - */ -static void prvTimerTask( void *pvParameters ) PRIVILEGED_FUNCTION; - -/* - * Called by the timer service task to interpret and process a command it - * received on the timer queue. - */ -static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION; - -/* - * Insert the timer into either xActiveTimerList1, or xActiveTimerList2, - * depending on if the expire time causes a timer counter overflow. - */ -static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) PRIVILEGED_FUNCTION; - -/* - * An active timer has reached its expire time. Reload the timer if it is an - * auto reload timer, then call its callback. - */ -static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) PRIVILEGED_FUNCTION; - -/* - * The tick count has overflowed. Switch the timer lists after ensuring the - * current timer list does not still reference some timers. - */ -static void prvSwitchTimerLists( portTickType xLastTime ) PRIVILEGED_FUNCTION; - -/* - * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE - * if a tick count overflow occurred since prvSampleTimeNow() was last called. - */ -static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION; - -/* - * If the timer list contains any active timers then return the expire time of - * the timer that will expire first and set *pxListWasEmpty to false. If the - * timer list does not contain any timers then return 0 and set *pxListWasEmpty - * to pdTRUE. - */ -static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) PRIVILEGED_FUNCTION; - -/* - * If a timer has expired, process it. Otherwise, block the timer service task - * until either a timer does expire or a command is received. - */ -static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) PRIVILEGED_FUNCTION; - -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerCreateTimerTask( void ) -{ -portBASE_TYPE xReturn = pdFAIL; - - /* This function is called when the scheduler is started if - configUSE_TIMERS is set to 1. Check that the infrastructure used by the - timer service task has been created/initialised. If timers have already - been created then the initialisation will already have been performed. */ - prvCheckForValidListAndQueue(); - - if( xTimerQueue != NULL ) - { - xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY, NULL); - } - - configASSERT( xReturn ); - return xReturn; -} -/*-----------------------------------------------------------*/ - -xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void *pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) -{ -xTIMER *pxNewTimer; - - /* Allocate the timer structure. */ - if( xTimerPeriodInTicks == ( portTickType ) 0U ) - { - pxNewTimer = NULL; - configASSERT( ( xTimerPeriodInTicks > 0 ) ); - } - else - { - pxNewTimer = ( xTIMER * ) pvPortMalloc( sizeof( xTIMER ) ); - if( pxNewTimer != NULL ) - { - /* Ensure the infrastructure used by the timer service task has been - created/initialised. */ - prvCheckForValidListAndQueue(); - - /* Initialise the timer structure members using the function parameters. */ - pxNewTimer->pcTimerName = pcTimerName; - pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks; - pxNewTimer->uxAutoReload = uxAutoReload; - pxNewTimer->pvTimerID = pvTimerID; - pxNewTimer->pxCallbackFunction = pxCallbackFunction; - vListInitialiseItem( &( pxNewTimer->xTimerListItem ) ); - - traceTIMER_CREATE( pxNewTimer ); - } - else - { - traceTIMER_CREATE_FAILED(); - } - } - - return ( xTimerHandle ) pxNewTimer; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) -{ -portBASE_TYPE xReturn = pdFAIL; -xTIMER_MESSAGE xMessage; - - /* Send a message to the timer service task to perform a particular action - on a particular timer definition. */ - if( xTimerQueue != NULL ) - { - /* Send a command to the timer service task to start the xTimer timer. */ - xMessage.xMessageID = xCommandID; - xMessage.xMessageValue = xOptionalValue; - xMessage.pxTimer = ( xTIMER * ) xTimer; - - if( pxHigherPriorityTaskWoken == NULL ) - { - if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING ) - { - xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xBlockTime ); - } - else - { - xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY ); - } - } - else - { - xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); - } - - traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn ); - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) -{ -xTIMER *pxTimer; -portBASE_TYPE xResult; - - /* Remove the timer from the list of active timers. A check has already - been performed to ensure the list is not empty. */ - pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); - vListRemove( &( pxTimer->xTimerListItem ) ); - traceTIMER_EXPIRED( pxTimer ); - - /* If the timer is an auto reload timer then calculate the next - expiry time and re-insert the timer in the list of active timers. */ - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - /* This is the only time a timer is inserted into a list using - a time relative to anything other than the current time. It - will therefore be inserted into the correct list relative to - the time this task thinks it is now, even if a command to - switch lists due to a tick count overflow is already waiting in - the timer queue. */ - if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) == pdTRUE ) - { - /* The timer expired before it was added to the active timer - list. Reload it now. */ - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - - /* Call the timer callback. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); -} -/*-----------------------------------------------------------*/ - -static void prvTimerTask( void *pvParameters ) -{ -portTickType xNextExpireTime; -portBASE_TYPE xListWasEmpty; - - /* Just to avoid compiler warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* Query the timers list to see if it contains any timers, and if so, - obtain the time at which the next timer will expire. */ - xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty ); - - /* If a timer has expired, process it. Otherwise, block this task - until either a timer does expire, or a command is received. */ - prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty ); - - /* Empty the command queue. */ - prvProcessReceivedCommands(); - } -} -/*-----------------------------------------------------------*/ - -static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) -{ -portTickType xTimeNow; -portBASE_TYPE xTimerListsWereSwitched; - - vTaskSuspendAll(); - { - /* Obtain the time now to make an assessment as to whether the timer - has expired or not. If obtaining the time causes the lists to switch - then don't process this timer as any timers that remained in the list - when the lists were switched will have been processed within the - prvSampelTimeNow() function. */ - xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); - if( xTimerListsWereSwitched == pdFALSE ) - { - /* The tick count has not overflowed, has the timer expired? */ - if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) ) - { - xTaskResumeAll(); - prvProcessExpiredTimer( xNextExpireTime, xTimeNow ); - } - else - { - /* The tick count has not overflowed, and the next expire - time has not been reached yet. This task should therefore - block to wait for the next expire time or a command to be - received - whichever comes first. The following line cannot - be reached unless xNextExpireTime > xTimeNow, except in the - case when the current timer list is empty. */ - vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ) ); - - if( xTaskResumeAll() == pdFALSE ) - { - /* Yield to wait for either a command to arrive, or the block time - to expire. If a command arrived between the critical section being - exited and this yield then the yield will not cause the task - to block. */ - portYIELD_WITHIN_API(); - } - } - } - else - { - xTaskResumeAll(); - } - } -} -/*-----------------------------------------------------------*/ - -static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) -{ -portTickType xNextExpireTime; - - /* Timers are listed in expiry time order, with the head of the list - referencing the task that will expire first. Obtain the time at which - the timer with the nearest expiry time will expire. If there are no - active timers then just set the next expire time to 0. That will cause - this task to unblock when the tick count overflows, at which point the - timer lists will be switched and the next expiry time can be - re-assessed. */ - *pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList ); - if( *pxListWasEmpty == pdFALSE ) - { - xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); - } - else - { - /* Ensure the task unblocks when the tick count rolls over. */ - xNextExpireTime = ( portTickType ) 0U; - } - - return xNextExpireTime; -} -/*-----------------------------------------------------------*/ - -static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) -{ -portTickType xTimeNow; -static portTickType xLastTime = ( portTickType ) 0U; - - xTimeNow = xTaskGetTickCount(); - - if( xTimeNow < xLastTime ) - { - prvSwitchTimerLists( xLastTime ); - *pxTimerListsWereSwitched = pdTRUE; - } - else - { - *pxTimerListsWereSwitched = pdFALSE; - } - - xLastTime = xTimeNow; - - return xTimeNow; -} -/*-----------------------------------------------------------*/ - -static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) -{ -portBASE_TYPE xProcessTimerNow = pdFALSE; - - listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime ); - listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); - - if( xNextExpiryTime <= xTimeNow ) - { - /* Has the expiry time elapsed between the command to start/reset a - timer was issued, and the time the command was processed? */ - if( ( ( portTickType ) ( xTimeNow - xCommandTime ) ) >= pxTimer->xTimerPeriodInTicks ) - { - /* The time between a command being issued and the command being - processed actually exceeds the timers period. */ - xProcessTimerNow = pdTRUE; - } - else - { - vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) ); - } - } - else - { - if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) ) - { - /* If, since the command was issued, the tick count has overflowed - but the expiry time has not, then the timer must have already passed - its expiry time and should be processed immediately. */ - xProcessTimerNow = pdTRUE; - } - else - { - vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); - } - } - - return xProcessTimerNow; -} -/*-----------------------------------------------------------*/ - -static void prvProcessReceivedCommands( void ) -{ -xTIMER_MESSAGE xMessage; -xTIMER *pxTimer; -portBASE_TYPE xTimerListsWereSwitched, xResult; -portTickType xTimeNow; - - /* In this case the xTimerListsWereSwitched parameter is not used, but it - must be present in the function call. */ - xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); - - while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) - { - pxTimer = xMessage.pxTimer; - - /* Is the timer already in a list of active timers? When the command - is trmCOMMAND_PROCESS_TIMER_OVERFLOW, the timer will be NULL as the - command is to the task rather than to an individual timer. */ - if( pxTimer != NULL ) - { - if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE ) - { - /* The timer is in a list, remove it. */ - vListRemove( &( pxTimer->xTimerListItem ) ); - } - } - - traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.xMessageValue ); - - switch( xMessage.xMessageID ) - { - case tmrCOMMAND_START : - /* Start or restart a timer. */ - if( prvInsertTimerInActiveList( pxTimer, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.xMessageValue ) == pdTRUE ) - { - /* The timer expired before it was added to the active timer - list. Process it now. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); - - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - break; - - case tmrCOMMAND_STOP : - /* The timer has already been removed from the active list. - There is nothing to do here. */ - break; - - case tmrCOMMAND_CHANGE_PERIOD : - pxTimer->xTimerPeriodInTicks = xMessage.xMessageValue; - configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) ); - prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow ); - break; - - case tmrCOMMAND_DELETE : - /* The timer has already been removed from the active list, - just free up the memory. */ - vPortFree( pxTimer ); - break; - - default : - /* Don't expect to get here. */ - break; - } - } -} -/*-----------------------------------------------------------*/ - -static void prvSwitchTimerLists( portTickType xLastTime ) -{ -portTickType xNextExpireTime, xReloadTime; -xList *pxTemp; -xTIMER *pxTimer; -portBASE_TYPE xResult; - - /* Remove compiler warnings if configASSERT() is not defined. */ - ( void ) xLastTime; - - /* The tick count has overflowed. The timer lists must be switched. - If there are any timers still referenced from the current timer list - then they must have expired and should be processed before the lists - are switched. */ - while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE ) - { - xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); - - /* Remove the timer from the list. */ - pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); - vListRemove( &( pxTimer->xTimerListItem ) ); - - /* Execute its callback, then send a command to restart the timer if - it is an auto-reload timer. It cannot be restarted here as the lists - have not yet been switched. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); - - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - /* Calculate the reload value, and if the reload value results in - the timer going into the same timer list then it has already expired - and the timer should be re-inserted into the current list so it is - processed again within this loop. Otherwise a command should be sent - to restart the timer to ensure it is only inserted into a list after - the lists have been swapped. */ - xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ); - if( xReloadTime > xNextExpireTime ) - { - listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime ); - listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); - vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); - } - else - { - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - } - - pxTemp = pxCurrentTimerList; - pxCurrentTimerList = pxOverflowTimerList; - pxOverflowTimerList = pxTemp; -} -/*-----------------------------------------------------------*/ - -static void prvCheckForValidListAndQueue( void ) -{ - /* Check that the list from which active timers are referenced, and the - queue used to communicate with the timer service, have been - initialised. */ - taskENTER_CRITICAL(); - { - if( xTimerQueue == NULL ) - { - vListInitialise( &xActiveTimerList1 ); - vListInitialise( &xActiveTimerList2 ); - pxCurrentTimerList = &xActiveTimerList1; - pxOverflowTimerList = &xActiveTimerList2; - xTimerQueue = xQueueCreate( ( unsigned portBASE_TYPE ) configTIMER_QUEUE_LENGTH, sizeof( xTIMER_MESSAGE ) ); - } - } - taskEXIT_CRITICAL(); -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) -{ -portBASE_TYPE xTimerIsInActiveList; -xTIMER *pxTimer = ( xTIMER * ) xTimer; - - /* Is the timer in the list of active timers? */ - taskENTER_CRITICAL(); - { - /* Checking to see if it is in the NULL list in effect checks to see if - it is referenced from either the current or the overflow timer lists in - one go, but the logic has to be reversed, hence the '!'. */ - xTimerIsInActiveList = !( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) ); - } - taskEXIT_CRITICAL(); - - return xTimerIsInActiveList; -} -/*-----------------------------------------------------------*/ - -void *pvTimerGetTimerID( xTimerHandle xTimer ) -{ -xTIMER *pxTimer = ( xTIMER * ) xTimer; - - return pxTimer->pvTimerID; -} -/*-----------------------------------------------------------*/ - -/* This entire source file will be skipped if the application is not configured -to include software timer functionality. If you want to include software timer -functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ -#endif /* configUSE_TIMERS == 1 */ +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + FreeRTOS supports many tools and architectures. V7.0.0 is sponsored by: + Atollic AB - Atollic provides professional embedded systems development + tools for C/C++ development, code analysis and test automation. + See http://www.atollic.com + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "timers.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. This #if is closed at the very bottom +of this file. If you want to include software timer functionality then ensure +configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#if ( configUSE_TIMERS == 1 ) + +/* Misc definitions. */ +#define tmrNO_DELAY ( portTickType ) 0U + +/* The definition of the timers themselves. */ +typedef struct tmrTimerControl +{ + const signed char *pcTimerName; /*<< Text name. This is not used by the kernel, it is included simply to make debugging easier. */ + xListItem xTimerListItem; /*<< Standard linked list item as used by all kernel features for event management. */ + portTickType xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */ + unsigned portBASE_TYPE uxAutoReload; /*<< Set to pdTRUE if the timer should be automatically restarted once expired. Set to pdFALSE if the timer is, in effect, a one shot timer. */ + void *pvTimerID; /*<< An ID to identify the timer. This allows the timer to be identified when the same callback is used for multiple timers. */ + tmrTIMER_CALLBACK pxCallbackFunction; /*<< The function that will be called when the timer expires. */ +} xTIMER; + +/* The definition of messages that can be sent and received on the timer +queue. */ +typedef struct tmrTimerQueueMessage +{ + portBASE_TYPE xMessageID; /*<< The command being sent to the timer service task. */ + portTickType xMessageValue; /*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */ + xTIMER * pxTimer; /*<< The timer to which the command will be applied. */ +} xTIMER_MESSAGE; + + +/* The list in which active timers are stored. Timers are referenced in expire +time order, with the nearest expiry time at the front of the list. Only the +timer service task is allowed to access xActiveTimerList. */ +PRIVILEGED_DATA static xList xActiveTimerList1; +PRIVILEGED_DATA static xList xActiveTimerList2; +PRIVILEGED_DATA static xList *pxCurrentTimerList; +PRIVILEGED_DATA static xList *pxOverflowTimerList; + +/* A queue that is used to send commands to the timer service task. */ +PRIVILEGED_DATA static xQueueHandle xTimerQueue = NULL; + +/*-----------------------------------------------------------*/ + +/* + * Initialise the infrastructure used by the timer service task if it has not + * been initialised already. + */ +static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION; + +/* + * The timer service task (daemon). Timer functionality is controlled by this + * task. Other tasks communicate with the timer service task using the + * xTimerQueue queue. + */ +static void prvTimerTask( void *pvParameters ) PRIVILEGED_FUNCTION; + +/* + * Called by the timer service task to interpret and process a command it + * received on the timer queue. + */ +static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION; + +/* + * Insert the timer into either xActiveTimerList1, or xActiveTimerList2, + * depending on if the expire time causes a timer counter overflow. + */ +static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) PRIVILEGED_FUNCTION; + +/* + * An active timer has reached its expire time. Reload the timer if it is an + * auto reload timer, then call its callback. + */ +static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) PRIVILEGED_FUNCTION; + +/* + * The tick count has overflowed. Switch the timer lists after ensuring the + * current timer list does not still reference some timers. + */ +static void prvSwitchTimerLists( portTickType xLastTime ) PRIVILEGED_FUNCTION; + +/* + * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE + * if a tick count overflow occurred since prvSampleTimeNow() was last called. + */ +static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION; + +/* + * If the timer list contains any active timers then return the expire time of + * the timer that will expire first and set *pxListWasEmpty to false. If the + * timer list does not contain any timers then return 0 and set *pxListWasEmpty + * to pdTRUE. + */ +static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) PRIVILEGED_FUNCTION; + +/* + * If a timer has expired, process it. Otherwise, block the timer service task + * until either a timer does expire or a command is received. + */ +static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) PRIVILEGED_FUNCTION; + +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerCreateTimerTask( void ) +{ +portBASE_TYPE xReturn = pdFAIL; + + /* This function is called when the scheduler is started if + configUSE_TIMERS is set to 1. Check that the infrastructure used by the + timer service task has been created/initialised. If timers have already + been created then the initialisation will already have been performed. */ + prvCheckForValidListAndQueue(); + + if( xTimerQueue != NULL ) + { + xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY, NULL); + } + + configASSERT( xReturn ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void *pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) +{ +xTIMER *pxNewTimer; + + /* Allocate the timer structure. */ + if( xTimerPeriodInTicks == ( portTickType ) 0U ) + { + pxNewTimer = NULL; + configASSERT( ( xTimerPeriodInTicks > 0 ) ); + } + else + { + pxNewTimer = ( xTIMER * ) pvPortMalloc( sizeof( xTIMER ) ); + if( pxNewTimer != NULL ) + { + /* Ensure the infrastructure used by the timer service task has been + created/initialised. */ + prvCheckForValidListAndQueue(); + + /* Initialise the timer structure members using the function parameters. */ + pxNewTimer->pcTimerName = pcTimerName; + pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks; + pxNewTimer->uxAutoReload = uxAutoReload; + pxNewTimer->pvTimerID = pvTimerID; + pxNewTimer->pxCallbackFunction = pxCallbackFunction; + vListInitialiseItem( &( pxNewTimer->xTimerListItem ) ); + + traceTIMER_CREATE( pxNewTimer ); + } + else + { + traceTIMER_CREATE_FAILED(); + } + } + + return ( xTimerHandle ) pxNewTimer; +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) +{ +portBASE_TYPE xReturn = pdFAIL; +xTIMER_MESSAGE xMessage; + + /* Send a message to the timer service task to perform a particular action + on a particular timer definition. */ + if( xTimerQueue != NULL ) + { + /* Send a command to the timer service task to start the xTimer timer. */ + xMessage.xMessageID = xCommandID; + xMessage.xMessageValue = xOptionalValue; + xMessage.pxTimer = ( xTIMER * ) xTimer; + + if( pxHigherPriorityTaskWoken == NULL ) + { + if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING ) + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xBlockTime ); + } + else + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY ); + } + } + else + { + xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); + } + + traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn ); + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) +{ +xTIMER *pxTimer; +portBASE_TYPE xResult; + + /* Remove the timer from the list of active timers. A check has already + been performed to ensure the list is not empty. */ + pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); + vListRemove( &( pxTimer->xTimerListItem ) ); + traceTIMER_EXPIRED( pxTimer ); + + /* If the timer is an auto reload timer then calculate the next + expiry time and re-insert the timer in the list of active timers. */ + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + /* This is the only time a timer is inserted into a list using + a time relative to anything other than the current time. It + will therefore be inserted into the correct list relative to + the time this task thinks it is now, even if a command to + switch lists due to a tick count overflow is already waiting in + the timer queue. */ + if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) == pdTRUE ) + { + /* The timer expired before it was added to the active timer + list. Reload it now. */ + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + + /* Call the timer callback. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); +} +/*-----------------------------------------------------------*/ + +static void prvTimerTask( void *pvParameters ) +{ +portTickType xNextExpireTime; +portBASE_TYPE xListWasEmpty; + + /* Just to avoid compiler warnings. */ + ( void ) pvParameters; + + for( ;; ) + { + /* Query the timers list to see if it contains any timers, and if so, + obtain the time at which the next timer will expire. */ + xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty ); + + /* If a timer has expired, process it. Otherwise, block this task + until either a timer does expire, or a command is received. */ + prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty ); + + /* Empty the command queue. */ + prvProcessReceivedCommands(); + } +} +/*-----------------------------------------------------------*/ + +static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) +{ +portTickType xTimeNow; +portBASE_TYPE xTimerListsWereSwitched; + + vTaskSuspendAll(); + { + /* Obtain the time now to make an assessment as to whether the timer + has expired or not. If obtaining the time causes the lists to switch + then don't process this timer as any timers that remained in the list + when the lists were switched will have been processed within the + prvSampelTimeNow() function. */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + if( xTimerListsWereSwitched == pdFALSE ) + { + /* The tick count has not overflowed, has the timer expired? */ + if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) ) + { + xTaskResumeAll(); + prvProcessExpiredTimer( xNextExpireTime, xTimeNow ); + } + else + { + /* The tick count has not overflowed, and the next expire + time has not been reached yet. This task should therefore + block to wait for the next expire time or a command to be + received - whichever comes first. The following line cannot + be reached unless xNextExpireTime > xTimeNow, except in the + case when the current timer list is empty. */ + vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ) ); + + if( xTaskResumeAll() == pdFALSE ) + { + /* Yield to wait for either a command to arrive, or the block time + to expire. If a command arrived between the critical section being + exited and this yield then the yield will not cause the task + to block. */ + portYIELD_WITHIN_API(); + } + } + } + else + { + xTaskResumeAll(); + } + } +} +/*-----------------------------------------------------------*/ + +static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) +{ +portTickType xNextExpireTime; + + /* Timers are listed in expiry time order, with the head of the list + referencing the task that will expire first. Obtain the time at which + the timer with the nearest expiry time will expire. If there are no + active timers then just set the next expire time to 0. That will cause + this task to unblock when the tick count overflows, at which point the + timer lists will be switched and the next expiry time can be + re-assessed. */ + *pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList ); + if( *pxListWasEmpty == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + } + else + { + /* Ensure the task unblocks when the tick count rolls over. */ + xNextExpireTime = ( portTickType ) 0U; + } + + return xNextExpireTime; +} +/*-----------------------------------------------------------*/ + +static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) +{ +portTickType xTimeNow; +static portTickType xLastTime = ( portTickType ) 0U; + + xTimeNow = xTaskGetTickCount(); + + if( xTimeNow < xLastTime ) + { + prvSwitchTimerLists( xLastTime ); + *pxTimerListsWereSwitched = pdTRUE; + } + else + { + *pxTimerListsWereSwitched = pdFALSE; + } + + xLastTime = xTimeNow; + + return xTimeNow; +} +/*-----------------------------------------------------------*/ + +static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) +{ +portBASE_TYPE xProcessTimerNow = pdFALSE; + + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + + if( xNextExpiryTime <= xTimeNow ) + { + /* Has the expiry time elapsed between the command to start/reset a + timer was issued, and the time the command was processed? */ + if( ( ( portTickType ) ( xTimeNow - xCommandTime ) ) >= pxTimer->xTimerPeriodInTicks ) + { + /* The time between a command being issued and the command being + processed actually exceeds the timers period. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) ); + } + } + else + { + if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) ) + { + /* If, since the command was issued, the tick count has overflowed + but the expiry time has not, then the timer must have already passed + its expiry time and should be processed immediately. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + } + + return xProcessTimerNow; +} +/*-----------------------------------------------------------*/ + +static void prvProcessReceivedCommands( void ) +{ +xTIMER_MESSAGE xMessage; +xTIMER *pxTimer; +portBASE_TYPE xTimerListsWereSwitched, xResult; +portTickType xTimeNow; + + /* In this case the xTimerListsWereSwitched parameter is not used, but it + must be present in the function call. */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + + while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) + { + pxTimer = xMessage.pxTimer; + + /* Is the timer already in a list of active timers? When the command + is trmCOMMAND_PROCESS_TIMER_OVERFLOW, the timer will be NULL as the + command is to the task rather than to an individual timer. */ + if( pxTimer != NULL ) + { + if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE ) + { + /* The timer is in a list, remove it. */ + vListRemove( &( pxTimer->xTimerListItem ) ); + } + } + + traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.xMessageValue ); + + switch( xMessage.xMessageID ) + { + case tmrCOMMAND_START : + /* Start or restart a timer. */ + if( prvInsertTimerInActiveList( pxTimer, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.xMessageValue ) == pdTRUE ) + { + /* The timer expired before it was added to the active timer + list. Process it now. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); + + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + break; + + case tmrCOMMAND_STOP : + /* The timer has already been removed from the active list. + There is nothing to do here. */ + break; + + case tmrCOMMAND_CHANGE_PERIOD : + pxTimer->xTimerPeriodInTicks = xMessage.xMessageValue; + configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) ); + prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow ); + break; + + case tmrCOMMAND_DELETE : + /* The timer has already been removed from the active list, + just free up the memory. */ + vPortFree( pxTimer ); + break; + + default : + /* Don't expect to get here. */ + break; + } + } +} +/*-----------------------------------------------------------*/ + +static void prvSwitchTimerLists( portTickType xLastTime ) +{ +portTickType xNextExpireTime, xReloadTime; +xList *pxTemp; +xTIMER *pxTimer; +portBASE_TYPE xResult; + + /* Remove compiler warnings if configASSERT() is not defined. */ + ( void ) xLastTime; + + /* The tick count has overflowed. The timer lists must be switched. + If there are any timers still referenced from the current timer list + then they must have expired and should be processed before the lists + are switched. */ + while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + + /* Remove the timer from the list. */ + pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); + vListRemove( &( pxTimer->xTimerListItem ) ); + + /* Execute its callback, then send a command to restart the timer if + it is an auto-reload timer. It cannot be restarted here as the lists + have not yet been switched. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); + + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + /* Calculate the reload value, and if the reload value results in + the timer going into the same timer list then it has already expired + and the timer should be re-inserted into the current list so it is + processed again within this loop. Otherwise a command should be sent + to restart the timer to ensure it is only inserted into a list after + the lists have been swapped. */ + xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ); + if( xReloadTime > xNextExpireTime ) + { + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + else + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + } + + pxTemp = pxCurrentTimerList; + pxCurrentTimerList = pxOverflowTimerList; + pxOverflowTimerList = pxTemp; +} +/*-----------------------------------------------------------*/ + +static void prvCheckForValidListAndQueue( void ) +{ + /* Check that the list from which active timers are referenced, and the + queue used to communicate with the timer service, have been + initialised. */ + taskENTER_CRITICAL(); + { + if( xTimerQueue == NULL ) + { + vListInitialise( &xActiveTimerList1 ); + vListInitialise( &xActiveTimerList2 ); + pxCurrentTimerList = &xActiveTimerList1; + pxOverflowTimerList = &xActiveTimerList2; + xTimerQueue = xQueueCreate( ( unsigned portBASE_TYPE ) configTIMER_QUEUE_LENGTH, sizeof( xTIMER_MESSAGE ) ); + } + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) +{ +portBASE_TYPE xTimerIsInActiveList; +xTIMER *pxTimer = ( xTIMER * ) xTimer; + + /* Is the timer in the list of active timers? */ + taskENTER_CRITICAL(); + { + /* Checking to see if it is in the NULL list in effect checks to see if + it is referenced from either the current or the overflow timer lists in + one go, but the logic has to be reversed, hence the '!'. */ + xTimerIsInActiveList = !( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) ); + } + taskEXIT_CRITICAL(); + + return xTimerIsInActiveList; +} +/*-----------------------------------------------------------*/ + +void *pvTimerGetTimerID( xTimerHandle xTimer ) +{ +xTIMER *pxTimer = ( xTIMER * ) xTimer; + + return pxTimer->pvTimerID; +} +/*-----------------------------------------------------------*/ + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. If you want to include software timer +functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#endif /* configUSE_TIMERS == 1 */ diff --git a/flight/PiOS.osx/osx/pios_delay.c b/flight/PiOS.osx/osx/pios_delay.c index 8d61eabb4..eb4082268 100644 --- a/flight/PiOS.osx/osx/pios_delay.c +++ b/flight/PiOS.osx/osx/pios_delay.c @@ -1,112 +1,112 @@ -/** - ****************************************************************************** - * - * @file pios_delay.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief Delay Functions - * - Provides a micro-second granular delay using a TIM - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_DELAY Delay Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" -#include "time.h" - -#if defined(PIOS_INCLUDE_DELAY) - -/** -* Initialises the Timer used by PIOS_DELAY functions
-* This is called from pios.c as part of the main() function -* at system start up. -* \return < 0 if initialisation failed -*/ -#include - -int32_t PIOS_DELAY_Init(void) -{ - // stub - - /* No error */ - return 0; -} - -/** -* Waits for a specific number of uS
-* Example:
-* \code -* // Wait for 500 uS -* PIOS_DELAY_Wait_uS(500); -* \endcode -* \param[in] uS delay (1..65535 microseconds) -* \return < 0 on errors -*/ -int32_t PIOS_DELAY_WaituS(uint32_t uS) -{ - struct timespec wait,rest; - wait.tv_sec=0; - wait.tv_nsec=1000*uS; - while (!nanosleep(&wait,&rest)) { - wait=rest; - } - - /* No error */ - return 0; -} - - -/** -* Waits for a specific number of mS
-* Example:
-* \code -* // Wait for 500 mS -* PIOS_DELAY_Wait_mS(500); -* \endcode -* \param[in] mS delay (1..65535 milliseconds) -* \return < 0 on errors -*/ -int32_t PIOS_DELAY_WaitmS(uint32_t mS) -{ - struct timespec wait,rest; - wait.tv_sec=mS/1000; - wait.tv_nsec=(mS%1000)*1000000; - while (!nanosleep(&wait,&rest)) { - wait=rest; - } - - /* No error */ - return 0; -} - -uint32_t PIOS_DELAY_GetRaw() -{ - uint32_t raw_us = clock(); - return raw_us; -} - -uint32_t PIOS_DELAY_DiffuS(uint32_t ref) -{ - uint32_t diff_clock = clock() - ref; - uint32_t diff_us = diff_clock; // (CLOCKS_PER_SEC / 1000); - return diff_us; -} -#endif +/** + ****************************************************************************** + * + * @file pios_delay.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Delay Functions + * - Provides a micro-second granular delay using a TIM + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_DELAY Delay Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" +#include "time.h" + +#if defined(PIOS_INCLUDE_DELAY) + +/** +* Initialises the Timer used by PIOS_DELAY functions
+* This is called from pios.c as part of the main() function +* at system start up. +* \return < 0 if initialisation failed +*/ +#include + +int32_t PIOS_DELAY_Init(void) +{ + // stub + + /* No error */ + return 0; +} + +/** +* Waits for a specific number of uS
+* Example:
+* \code +* // Wait for 500 uS +* PIOS_DELAY_Wait_uS(500); +* \endcode +* \param[in] uS delay (1..65535 microseconds) +* \return < 0 on errors +*/ +int32_t PIOS_DELAY_WaituS(uint32_t uS) +{ + struct timespec wait,rest; + wait.tv_sec=0; + wait.tv_nsec=1000*uS; + while (!nanosleep(&wait,&rest)) { + wait=rest; + } + + /* No error */ + return 0; +} + + +/** +* Waits for a specific number of mS
+* Example:
+* \code +* // Wait for 500 mS +* PIOS_DELAY_Wait_mS(500); +* \endcode +* \param[in] mS delay (1..65535 milliseconds) +* \return < 0 on errors +*/ +int32_t PIOS_DELAY_WaitmS(uint32_t mS) +{ + struct timespec wait,rest; + wait.tv_sec=mS/1000; + wait.tv_nsec=(mS%1000)*1000000; + while (!nanosleep(&wait,&rest)) { + wait=rest; + } + + /* No error */ + return 0; +} + +uint32_t PIOS_DELAY_GetRaw() +{ + uint32_t raw_us = clock(); + return raw_us; +} + +uint32_t PIOS_DELAY_DiffuS(uint32_t ref) +{ + uint32_t diff_clock = clock() - ref; + uint32_t diff_us = diff_clock; // (CLOCKS_PER_SEC / 1000); + return diff_us; +} +#endif diff --git a/flight/PiOS.osx/osx/pios_iap.c b/flight/PiOS.osx/osx/pios_iap.c index be5b19536..aef9f6c54 100644 --- a/flight/PiOS.osx/osx/pios_iap.c +++ b/flight/PiOS.osx/osx/pios_iap.c @@ -1,69 +1,69 @@ -/*! - * @File iap.c - * @Brief - * - * Created on: Sep 6, 2010 - * Author: joe - */ - - -/**************************************************************************************** - * Header files - ****************************************************************************************/ -#include - -/*! - * \brief PIOS_IAP_Init - performs required initializations for iap module. - * \param none. - * \return none. - * \retval none. - * - * Created: Sep 8, 2010 10:10:48 PM by joe - */ -void PIOS_IAP_Init( void ) -{ - -} - -/*! - * \brief Determines if an In-Application-Programming request has been made. - * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) - * \return TRUE - if correct sequence found, along with 'comm' updated. - * FALSE - Note that 'comm' will have an invalid comm identifier. - * \retval - * - */ -uint32_t PIOS_IAP_CheckRequest( void ) -{ - - return false; -} - - - -/*! - * \brief Sets the 1st word of the request sequence. - * \param n/a - * \return n/a - * \retval - */ -void PIOS_IAP_SetRequest1(void) -{ -} - -void PIOS_IAP_SetRequest2(void) -{ -} - -void PIOS_IAP_ClearRequest(void) -{ -} - -uint16_t PIOS_IAP_ReadBootCount(void) -{ - return 0; -} - -void PIOS_IAP_WriteBootCount (uint16_t boot_count) -{ -} +/*! + * @File iap.c + * @Brief + * + * Created on: Sep 6, 2010 + * Author: joe + */ + + +/**************************************************************************************** + * Header files + ****************************************************************************************/ +#include + +/*! + * \brief PIOS_IAP_Init - performs required initializations for iap module. + * \param none. + * \return none. + * \retval none. + * + * Created: Sep 8, 2010 10:10:48 PM by joe + */ +void PIOS_IAP_Init( void ) +{ + +} + +/*! + * \brief Determines if an In-Application-Programming request has been made. + * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) + * \return TRUE - if correct sequence found, along with 'comm' updated. + * FALSE - Note that 'comm' will have an invalid comm identifier. + * \retval + * + */ +uint32_t PIOS_IAP_CheckRequest( void ) +{ + + return false; +} + + + +/*! + * \brief Sets the 1st word of the request sequence. + * \param n/a + * \return n/a + * \retval + */ +void PIOS_IAP_SetRequest1(void) +{ +} + +void PIOS_IAP_SetRequest2(void) +{ +} + +void PIOS_IAP_ClearRequest(void) +{ +} + +uint16_t PIOS_IAP_ReadBootCount(void) +{ + return 0; +} + +void PIOS_IAP_WriteBootCount (uint16_t boot_count) +{ +} diff --git a/flight/PiOS.osx/osx/pios_led.c b/flight/PiOS.osx/osx/pios_led.c index 876f8f157..770e8b2c4 100644 --- a/flight/PiOS.osx/osx/pios_led.c +++ b/flight/PiOS.osx/osx/pios_led.c @@ -1,86 +1,86 @@ -/** - ****************************************************************************** - * - * @file pios_led.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief LED functions, init, toggle, on & off. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_LED LED Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_LED) - -/* Private Function Prototypes */ - - -/* Local Variables */ -static uint8_t LED_GPIO[PIOS_LED_NUM]; - - -static inline void PIOS_SetLED(uint32_t LED,uint8_t stat) { - //printf("PIOS: LED %i status %i\n",LED,stat); - LED_GPIO[LED]=stat; -} - -/** -* Initialises all the LED's -*/ -void PIOS_LED_Init(void) -{ - for(int LEDNum = 0; LEDNum < PIOS_LED_NUM; LEDNum++) { - LED_GPIO[LEDNum]=0; - } -} - - -/** -* Turn on LED -* \param[in] LED LED Name (LED1, LED2) -*/ -void PIOS_LED_On(uint32_t led) -{ - PIOS_SetLED(led,1); -} - - -/** -* Turn off LED -* \param[in] LED LED Name (LED1, LED2) -*/ -void PIOS_LED_Off(uint32_t led) -{ - PIOS_SetLED(led,0); -} - - -/** -* Toggle LED on/off -* \param[in] LED LED Name (LED1, LED2) -*/ -void PIOS_LED_Toggle(uint32_t led) -{ - PIOS_SetLED(led,LED_GPIO[led]?0:1); -} - -#endif +/** + ****************************************************************************** + * + * @file pios_led.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief LED functions, init, toggle, on & off. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_LED LED Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_LED) + +/* Private Function Prototypes */ + + +/* Local Variables */ +static uint8_t LED_GPIO[PIOS_LED_NUM]; + + +static inline void PIOS_SetLED(uint32_t LED,uint8_t stat) { + //printf("PIOS: LED %i status %i\n",LED,stat); + LED_GPIO[LED]=stat; +} + +/** +* Initialises all the LED's +*/ +void PIOS_LED_Init(void) +{ + for(int LEDNum = 0; LEDNum < PIOS_LED_NUM; LEDNum++) { + LED_GPIO[LEDNum]=0; + } +} + + +/** +* Turn on LED +* \param[in] LED LED Name (LED1, LED2) +*/ +void PIOS_LED_On(uint32_t led) +{ + PIOS_SetLED(led,1); +} + + +/** +* Turn off LED +* \param[in] LED LED Name (LED1, LED2) +*/ +void PIOS_LED_Off(uint32_t led) +{ + PIOS_SetLED(led,0); +} + + +/** +* Toggle LED on/off +* \param[in] LED LED Name (LED1, LED2) +*/ +void PIOS_LED_Toggle(uint32_t led) +{ + PIOS_SetLED(led,LED_GPIO[led]?0:1); +} + +#endif diff --git a/flight/PiOS.osx/osx/pios_sdcard.c b/flight/PiOS.osx/osx/pios_sdcard.c index 1e43c8086..78da48e46 100644 --- a/flight/PiOS.osx/osx/pios_sdcard.c +++ b/flight/PiOS.osx/osx/pios_sdcard.c @@ -1,300 +1,300 @@ -/** - ****************************************************************************** - * - * @file pios_sdcard.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief Sets up basic system hardware, functions are called from Main. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_SDCARD SDCard Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_SDCARD) - - -/** -* Initialises SPI pins and peripheral to access MMC/SD Card -* \param[in] mode currently only mode 0 supported -* \return < 0 if initialisation failed -*/ -int32_t PIOS_SDCARD_Init(void) -{ - /* No error */ - return 0; -} - - -/** -* Connects to SD Card -* \return < 0 if initialisation sequence failed -*/ -int32_t PIOS_SDCARD_PowerOn(void) -{ - return 0; /* Status should be 0 if nothing went wrong! */ -} - - -/** -* Disconnects from SD Card -* \return < 0 on errors -*/ -int32_t PIOS_SDCARD_PowerOff(void) -{ - return 0; // no error -} - - -/** -* If SD card was previously available: Checks if the SD Card is still -* available by sending the STATUS command.
-* This takes ca. 10 uS -* -* If SD card was previously not available: Checks if the SD Card is -* available by sending the IDLE command at low speed.
-* This takes ca. 500 uS!
-* Once we got a positive response, SDCARD_PowerOn() will be -* called by this function to initialize the card completely. -* -* Example for Connection/Disconnection detection: -* \code -* // this function is called each second from a low-priority task -* // If multiple tasks are accessing the SD card, add a semaphore/mutex -* // to avoid IO access collisions with other tasks! -* u8 sdcard_available; -* int32_t CheckSDCard(void) -* { -* // check if SD card is available -* // High speed access if the card was previously available -* u8 prev_sdcard_available = sdcard_available; -* sdcard_available = PIOS_SDCARD_CheckAvailable(prev_sdcard_available); -* -* if(sdcard_available && !prev_sdcard_available) { -* // SD Card has been connected -* -* // now it's possible to read/write sectors -* -* } else if( !sdcard_available && prev_sdcard_available ) { -* // SD Card has been disconnected -* -* // here you can notify your application about this state -* } -* -* return 0; // no error -* } -* \endcode -* \param[in] was_available should only be set if the SD card was previously available -* \return 0 if no response from SD Card -* \return 1 if SD card is accessible -*/ -int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available) -{ - return 1; /* 1 = available, 0 = not available. */ -} - - -/** -* Sends command to SD card -* \param[in] cmd SD card command -* \param[in] addr 32bit address -* \param[in] crc precalculated CRC -* \return >= 0x00 if command has been sent successfully (contains received byte) -* \return -1 if no response from SD Card (timeout) -*/ -int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc) -{ - return -1; -} - - -/** -* Reads 512 bytes from selected sector -* \param[in] sector 32bit sector -* \param[in] *buffer pointer to 512 byte buffer -* \return 0 if whole sector has been successfully read -* \return -error if error occured during read operation:
-*
    -*
  • Bit 0 - In idle state if 1 -*
  • Bit 1 - Erase Reset if 1 -*
  • Bit 2 - Illgal Command if 1 -*
  • Bit 3 - Com CRC Error if 1 -*
  • Bit 4 - Erase Sequence Error if 1 -*
  • Bit 5 - Address Error if 1 -*
  • Bit 6 - Parameter Error if 1 -*
  • Bit 7 - Not used, always '0' -*
-* \return -256 if timeout during command has been sent -* \return -257 if timeout while waiting for start token -*/ -int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer) -{ - return -256; -} - - -/** -* Writes 512 bytes into selected sector -* \param[in] sector 32bit sector -* \param[in] *buffer pointer to 512 byte buffer -* \return 0 if whole sector has been successfully read -* \return -error if error occured during read operation:
-*
    -*
  • Bit 0 - In idle state if 1 -*
  • Bit 1 - Erase Reset if 1 -*
  • Bit 2 - Illgal Command if 1 -*
  • Bit 3 - Com CRC Error if 1 -*
  • Bit 4 - Erase Sequence Error if 1 -*
  • Bit 5 - Address Error if 1 -*
  • Bit 6 - Parameter Error if 1 -*
  • Bit 7 - Not used, always '0' -*
-* \return -256 if timeout during command has been sent -* \return -257 if write operation not accepted -* \return -258 if timeout during write operation -*/ -int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer) -{ - return -256; -} - - -/** -* Reads the CID informations from SD Card -* \param[in] *cid pointer to buffer which holds the CID informations -* \return 0 if the informations haven been successfully read -* \return -error if error occured during read operation -* \return -256 if timeout during command has been sent -* \return -257 if timeout while waiting for start token -*/ -int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid) -{ - return -256; -} - -/** -* Reads the CSD informations from SD Card -* \param[in] *csd pointer to buffer which holds the CSD informations -* \return 0 if the informations haven been successfully read -* \return -error if error occured during read operation -* \return -256 if timeout during command has been sent -* \return -257 if timeout while waiting for start token -*/ -int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd) -{ - return -256; -} - -/** -* Attempts to write a startup log to the SDCard -* return 0 No errors -* return -1 Error deleting file -* return -2 Error opening file -* return -3 Error writing file -*/ -int32_t PIOS_SDCARD_StartupLog(void) -{ - return -3; -} - -/** - * Check if the SD card has been mounted - * @return 0 if no - * @return 1 if yes - */ -int32_t PIOS_SDCARD_IsMounted() -{ - return 1; -} - -/** -* Mounts the file system -* param[in] CreateStartupLog 1 = True, 0 = False -* return 0 No errors -* return -1 SDCard not available -* return -2 Cannot find first partition -* return -3 No volume information -* return -4 Error writing startup log file -*/ -int32_t PIOS_SDCARD_MountFS(uint32_t CreateStartupLog) -{ - return 0; -} - -/** -* Mounts the file system -* return Amount of free bytes -*/ -int32_t PIOS_SDCARD_GetFree(void) -{ - return 10240; -} - -/** -* Read from file -* return 0 No error -* return -1 DFS_ReadFile failed -* return -2 Less bytes read than expected -*/ -//int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len) -//{ - /* No error */ -// return -1; -//} - -/** -* Read a line from file -* returns Number of bytes read -*/ -//int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len) -//{ -// return -1; -//} - -/** -* Copy a file -* WARNING: This will overwrite the destination file even if it exists -* param[in] *Source Path to file to copy -* param[in] *Destination Path to destination file -* return 0 No errors -* return -1 Source file doesn't exist -* return -2 Failed to create destination file -* return -3 DFS_ReadFile failed -* return -4 DFS_WriteFile failed -*/ -int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination) -{ - return -2; -} - -/** -* Delete a file -* param[in] *Filename File to delete -* return 0 No errors -* return -1 Error deleting file -*/ -int32_t PIOS_SDCARD_FileDelete(char *Filename) -{ - return -1; -} - -#endif +/** + ****************************************************************************** + * + * @file pios_sdcard.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief Sets up basic system hardware, functions are called from Main. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_SDCARD SDCard Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_SDCARD) + + +/** +* Initialises SPI pins and peripheral to access MMC/SD Card +* \param[in] mode currently only mode 0 supported +* \return < 0 if initialisation failed +*/ +int32_t PIOS_SDCARD_Init(void) +{ + /* No error */ + return 0; +} + + +/** +* Connects to SD Card +* \return < 0 if initialisation sequence failed +*/ +int32_t PIOS_SDCARD_PowerOn(void) +{ + return 0; /* Status should be 0 if nothing went wrong! */ +} + + +/** +* Disconnects from SD Card +* \return < 0 on errors +*/ +int32_t PIOS_SDCARD_PowerOff(void) +{ + return 0; // no error +} + + +/** +* If SD card was previously available: Checks if the SD Card is still +* available by sending the STATUS command.
+* This takes ca. 10 uS +* +* If SD card was previously not available: Checks if the SD Card is +* available by sending the IDLE command at low speed.
+* This takes ca. 500 uS!
+* Once we got a positive response, SDCARD_PowerOn() will be +* called by this function to initialize the card completely. +* +* Example for Connection/Disconnection detection: +* \code +* // this function is called each second from a low-priority task +* // If multiple tasks are accessing the SD card, add a semaphore/mutex +* // to avoid IO access collisions with other tasks! +* u8 sdcard_available; +* int32_t CheckSDCard(void) +* { +* // check if SD card is available +* // High speed access if the card was previously available +* u8 prev_sdcard_available = sdcard_available; +* sdcard_available = PIOS_SDCARD_CheckAvailable(prev_sdcard_available); +* +* if(sdcard_available && !prev_sdcard_available) { +* // SD Card has been connected +* +* // now it's possible to read/write sectors +* +* } else if( !sdcard_available && prev_sdcard_available ) { +* // SD Card has been disconnected +* +* // here you can notify your application about this state +* } +* +* return 0; // no error +* } +* \endcode +* \param[in] was_available should only be set if the SD card was previously available +* \return 0 if no response from SD Card +* \return 1 if SD card is accessible +*/ +int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available) +{ + return 1; /* 1 = available, 0 = not available. */ +} + + +/** +* Sends command to SD card +* \param[in] cmd SD card command +* \param[in] addr 32bit address +* \param[in] crc precalculated CRC +* \return >= 0x00 if command has been sent successfully (contains received byte) +* \return -1 if no response from SD Card (timeout) +*/ +int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc) +{ + return -1; +} + + +/** +* Reads 512 bytes from selected sector +* \param[in] sector 32bit sector +* \param[in] *buffer pointer to 512 byte buffer +* \return 0 if whole sector has been successfully read +* \return -error if error occured during read operation:
+*
    +*
  • Bit 0 - In idle state if 1 +*
  • Bit 1 - Erase Reset if 1 +*
  • Bit 2 - Illgal Command if 1 +*
  • Bit 3 - Com CRC Error if 1 +*
  • Bit 4 - Erase Sequence Error if 1 +*
  • Bit 5 - Address Error if 1 +*
  • Bit 6 - Parameter Error if 1 +*
  • Bit 7 - Not used, always '0' +*
+* \return -256 if timeout during command has been sent +* \return -257 if timeout while waiting for start token +*/ +int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer) +{ + return -256; +} + + +/** +* Writes 512 bytes into selected sector +* \param[in] sector 32bit sector +* \param[in] *buffer pointer to 512 byte buffer +* \return 0 if whole sector has been successfully read +* \return -error if error occured during read operation:
+*
    +*
  • Bit 0 - In idle state if 1 +*
  • Bit 1 - Erase Reset if 1 +*
  • Bit 2 - Illgal Command if 1 +*
  • Bit 3 - Com CRC Error if 1 +*
  • Bit 4 - Erase Sequence Error if 1 +*
  • Bit 5 - Address Error if 1 +*
  • Bit 6 - Parameter Error if 1 +*
  • Bit 7 - Not used, always '0' +*
+* \return -256 if timeout during command has been sent +* \return -257 if write operation not accepted +* \return -258 if timeout during write operation +*/ +int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer) +{ + return -256; +} + + +/** +* Reads the CID informations from SD Card +* \param[in] *cid pointer to buffer which holds the CID informations +* \return 0 if the informations haven been successfully read +* \return -error if error occured during read operation +* \return -256 if timeout during command has been sent +* \return -257 if timeout while waiting for start token +*/ +int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid) +{ + return -256; +} + +/** +* Reads the CSD informations from SD Card +* \param[in] *csd pointer to buffer which holds the CSD informations +* \return 0 if the informations haven been successfully read +* \return -error if error occured during read operation +* \return -256 if timeout during command has been sent +* \return -257 if timeout while waiting for start token +*/ +int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd) +{ + return -256; +} + +/** +* Attempts to write a startup log to the SDCard +* return 0 No errors +* return -1 Error deleting file +* return -2 Error opening file +* return -3 Error writing file +*/ +int32_t PIOS_SDCARD_StartupLog(void) +{ + return -3; +} + +/** + * Check if the SD card has been mounted + * @return 0 if no + * @return 1 if yes + */ +int32_t PIOS_SDCARD_IsMounted() +{ + return 1; +} + +/** +* Mounts the file system +* param[in] CreateStartupLog 1 = True, 0 = False +* return 0 No errors +* return -1 SDCard not available +* return -2 Cannot find first partition +* return -3 No volume information +* return -4 Error writing startup log file +*/ +int32_t PIOS_SDCARD_MountFS(uint32_t CreateStartupLog) +{ + return 0; +} + +/** +* Mounts the file system +* return Amount of free bytes +*/ +int32_t PIOS_SDCARD_GetFree(void) +{ + return 10240; +} + +/** +* Read from file +* return 0 No error +* return -1 DFS_ReadFile failed +* return -2 Less bytes read than expected +*/ +//int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len) +//{ + /* No error */ +// return -1; +//} + +/** +* Read a line from file +* returns Number of bytes read +*/ +//int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len) +//{ +// return -1; +//} + +/** +* Copy a file +* WARNING: This will overwrite the destination file even if it exists +* param[in] *Source Path to file to copy +* param[in] *Destination Path to destination file +* return 0 No errors +* return -1 Source file doesn't exist +* return -2 Failed to create destination file +* return -3 DFS_ReadFile failed +* return -4 DFS_WriteFile failed +*/ +int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination) +{ + return -2; +} + +/** +* Delete a file +* param[in] *Filename File to delete +* return 0 No errors +* return -1 Error deleting file +*/ +int32_t PIOS_SDCARD_FileDelete(char *Filename) +{ + return -1; +} + +#endif diff --git a/flight/PiOS.osx/osx/pios_tcp.c b/flight/PiOS.osx/osx/pios_tcp.c index 234338f7e..3938cb2b7 100644 --- a/flight/PiOS.osx/osx/pios_tcp.c +++ b/flight/PiOS.osx/osx/pios_tcp.c @@ -1,286 +1,286 @@ -/** - ****************************************************************************** - * - * @file pios_tcp.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @brief TCP commands. Inits UDPs, controls UDPs & Interupt handlers. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_UDP UDP Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_TCP) - -#include -#include - -/* We need a list of TCP devices */ - -#define PIOS_TCP_MAX_DEV 16 -static int8_t pios_tcp_num_devices = 0; - -static pios_tcp_dev pios_tcp_devices[PIOS_TCP_MAX_DEV]; - - - -/* Provide a COM driver */ -static void PIOS_TCP_ChangeBaud(uint32_t udp_id, uint32_t baud); -static void PIOS_TCP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context); -static void PIOS_TCP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context); -static void PIOS_TCP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail); -static void PIOS_TCP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail); - -const struct pios_com_driver pios_tcp_com_driver = { - .set_baud = PIOS_TCP_ChangeBaud, - .tx_start = PIOS_TCP_TxStart, - .rx_start = PIOS_TCP_RxStart, - .bind_tx_cb = PIOS_TCP_RegisterTxCallback, - .bind_rx_cb = PIOS_TCP_RegisterRxCallback, -}; - - -static pios_tcp_dev * find_tcp_dev_by_id (uint8_t tcp) -{ - if (tcp >= pios_tcp_num_devices) { - /* Undefined UDP port for this board (see pios_board.c) */ - PIOS_Assert(0); - return NULL; - } - - /* Get a handle for the device configuration */ - return &(pios_tcp_devices[tcp]); -} - -/** - * RxThread - */ - -static void PIOS_TCP_RxTask(void *tcp_dev_n) -{ - bool rx_need_yield; - - pios_tcp_dev *tcp_dev = (pios_tcp_dev *) tcp_dev_n; - while(1) { - - if (tcp_dev->rx_in_cb) { - char buffer[PIOS_TCP_RX_BUFFER_SIZE]; - int received = fifoBuf_getData(&tcp_dev->rx_fifo, buffer, PIOS_TCP_RX_BUFFER_SIZE); - (void) (tcp_dev->rx_in_cb)(tcp_dev->rx_in_context, (uint8_t *) buffer, received, NULL, &rx_need_yield); - - //fprintf(stderr, "Received %d\n", received); -#if defined(PIOS_INCLUDE_FREERTOS) - // Not sure about this - if (rx_need_yield) { - vPortYieldFromISR(); - } -#endif /* PIOS_INCLUDE_FREERTOS */ - - } else - fifoBuf_clearData(&tcp_dev->rx_fifo); - - vTaskDelay(1); - } -} - -static void *PIOS_TCP_RxThread(void *tcp_dev_n) -{ - - /* needed because of FreeRTOS.posix scheduling */ - sigset_t set; - sigfillset(&set); - sigprocmask(SIG_BLOCK, &set, NULL); - - pios_tcp_dev *tcp_dev = (pios_tcp_dev*) tcp_dev_n; - - const int INCOMING_BUFFER_SIZE = 16; - char incoming_buffer[INCOMING_BUFFER_SIZE]; - /** - * com devices never get closed except by application "reboot" - * we also never give up our mutex except for waiting - */ - while(1) { - - tcp_dev->socket_connection = accept(tcp_dev->socket, NULL, NULL); - if (0 > tcp_dev->socket_connection) { - perror("Accept failed"); - close(tcp_dev->socket); - exit(EXIT_FAILURE); - } - - fprintf(stderr, "Connection accepted\n"); - - int received; - do { - // Received is used to track the scoket whereas the dev variable is only updated when it can be - received = read(tcp_dev->socket_connection, incoming_buffer, INCOMING_BUFFER_SIZE); - - //while(fifoBuf_getFree(&tcp_dev->rx_fifo) < received); - - fifoBuf_putData(&tcp_dev->rx_fifo, incoming_buffer, received); - } while(received > 0); - - if (-1 == shutdown(tcp_dev->socket_connection, SHUT_RDWR)) - { - //perror("can not shutdown socket"); - //close(tcp_dev->socket_connection); - //exit(EXIT_FAILURE); - } - close(tcp_dev->socket_connection); - tcp_dev->socket_connection = 0; - } -} - - -/** - * Open UDP socket - */ -xTaskHandle tcpRxTaskHandle; -int32_t PIOS_TCP_Init(uint32_t *tcp_id, const struct pios_tcp_cfg * cfg) -{ - - pios_tcp_dev *tcp_dev = &pios_tcp_devices[pios_tcp_num_devices]; - - pios_tcp_num_devices++; - - - /* initialize */ - tcp_dev->rx_in_cb = NULL; - tcp_dev->tx_out_cb = NULL; - tcp_dev->cfg=cfg; - - /* assign socket */ - tcp_dev->socket = socket(PF_INET, SOCK_STREAM, IPPROTO_TCP); - memset(&tcp_dev->server,0,sizeof(tcp_dev->server)); - memset(&tcp_dev->client,0,sizeof(tcp_dev->client)); - tcp_dev->server.sin_family = AF_INET; - tcp_dev->server.sin_addr.s_addr = INADDR_ANY; //inet_addr(tcp_dev->cfg->ip); - tcp_dev->server.sin_port = htons(tcp_dev->cfg->port); - int res= bind(tcp_dev->socket, (struct sockaddr *)&tcp_dev->server,sizeof(tcp_dev->server)); - if (res == -1) { - perror("Binding socket failed\n"); - exit(EXIT_FAILURE); - } - - res = listen(tcp_dev->socket, 10); - if (res == -1) { - perror("Socket listen failed\n"); - exit(EXIT_FAILURE); - } - - fifoBuf_init(&tcp_dev->rx_fifo, tcp_dev->rx_buffer, PIOS_TCP_RX_BUFFER_SIZE); - - pthread_create(&tcp_dev->rxThread, NULL, PIOS_TCP_RxThread, (void*)tcp_dev); - - xTaskCreate(PIOS_TCP_RxTask, (signed char *)"TcpRx", 1024, (void*)tcp_dev, 2, &tcpRxTaskHandle); - - printf("udp dev %i - socket %i opened - result %i\n",pios_tcp_num_devices-1,tcp_dev->socket,res); - - *tcp_id = pios_tcp_num_devices-1; - - return res; -} - - -void PIOS_TCP_ChangeBaud(uint32_t tcp_id, uint32_t baud) -{ - /** - * doesn't apply! - */ -} - - -static void PIOS_TCP_RxStart(uint32_t tp_id, uint16_t rx_bytes_avail) -{ - /** - * lazy! - */ -} - - -static void PIOS_TCP_TxStart(uint32_t tcp_id, uint16_t tx_bytes_avail) -{ - pios_tcp_dev *tcp_dev = find_tcp_dev_by_id(tcp_id); - - PIOS_Assert(tcp_dev); - - int32_t length,len,rem; - - /** - * we send everything directly whenever notified of data to send (lazy!) - */ - if (tcp_dev->tx_out_cb) { - while (tx_bytes_avail>0) { - bool tx_need_yield = false; - length = (tcp_dev->tx_out_cb)(tcp_dev->tx_out_context, tcp_dev->tx_buffer, PIOS_TCP_RX_BUFFER_SIZE, NULL, &tx_need_yield); - rem = length; - while (rem>0) { - if(tcp_dev->socket_connection != 0) { - len = write(tcp_dev->socket_connection, tcp_dev->tx_buffer, length); - } - if (len<=0) { - rem=0; - } else { - rem -= len; - } - } - tx_bytes_avail -= length; -#if defined(PIOS_INCLUDE_FREERTOS) - // Not sure about this - if (tx_need_yield) { - vPortYieldFromISR(); - } -#endif /* PIOS_INCLUDE_FREERTOS */ - } - } - -} - -static void PIOS_TCP_RegisterRxCallback(uint32_t tcp_id, pios_com_callback rx_in_cb, uint32_t context) -{ - pios_tcp_dev *tcp_dev = find_tcp_dev_by_id(tcp_id); - - PIOS_Assert(tcp_dev); - - /* - * Order is important in these assignments since ISR uses _cb - * field to determine if it's ok to dereference _cb and _context - */ - tcp_dev->rx_in_context = context; - tcp_dev->rx_in_cb = rx_in_cb; -} - -static void PIOS_TCP_RegisterTxCallback(uint32_t tcp_id, pios_com_callback tx_out_cb, uint32_t context) -{ - pios_tcp_dev *tcp_dev = find_tcp_dev_by_id(tcp_id); - - PIOS_Assert(tcp_dev); - - /* - * Order is important in these assignments since ISR uses _cb - * field to determine if it's ok to dereference _cb and _context - */ - tcp_dev->tx_out_context = context; - tcp_dev->tx_out_cb = tx_out_cb; -} - -#endif +/** + ****************************************************************************** + * + * @file pios_tcp.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief TCP commands. Inits UDPs, controls UDPs & Interupt handlers. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_UDP UDP Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_TCP) + +#include +#include + +/* We need a list of TCP devices */ + +#define PIOS_TCP_MAX_DEV 16 +static int8_t pios_tcp_num_devices = 0; + +static pios_tcp_dev pios_tcp_devices[PIOS_TCP_MAX_DEV]; + + + +/* Provide a COM driver */ +static void PIOS_TCP_ChangeBaud(uint32_t udp_id, uint32_t baud); +static void PIOS_TCP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context); +static void PIOS_TCP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context); +static void PIOS_TCP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail); +static void PIOS_TCP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail); + +const struct pios_com_driver pios_tcp_com_driver = { + .set_baud = PIOS_TCP_ChangeBaud, + .tx_start = PIOS_TCP_TxStart, + .rx_start = PIOS_TCP_RxStart, + .bind_tx_cb = PIOS_TCP_RegisterTxCallback, + .bind_rx_cb = PIOS_TCP_RegisterRxCallback, +}; + + +static pios_tcp_dev * find_tcp_dev_by_id (uint8_t tcp) +{ + if (tcp >= pios_tcp_num_devices) { + /* Undefined UDP port for this board (see pios_board.c) */ + PIOS_Assert(0); + return NULL; + } + + /* Get a handle for the device configuration */ + return &(pios_tcp_devices[tcp]); +} + +/** + * RxThread + */ + +static void PIOS_TCP_RxTask(void *tcp_dev_n) +{ + bool rx_need_yield; + + pios_tcp_dev *tcp_dev = (pios_tcp_dev *) tcp_dev_n; + while(1) { + + if (tcp_dev->rx_in_cb) { + char buffer[PIOS_TCP_RX_BUFFER_SIZE]; + int received = fifoBuf_getData(&tcp_dev->rx_fifo, buffer, PIOS_TCP_RX_BUFFER_SIZE); + (void) (tcp_dev->rx_in_cb)(tcp_dev->rx_in_context, (uint8_t *) buffer, received, NULL, &rx_need_yield); + + //fprintf(stderr, "Received %d\n", received); +#if defined(PIOS_INCLUDE_FREERTOS) + // Not sure about this + if (rx_need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ + + } else + fifoBuf_clearData(&tcp_dev->rx_fifo); + + vTaskDelay(1); + } +} + +static void *PIOS_TCP_RxThread(void *tcp_dev_n) +{ + + /* needed because of FreeRTOS.posix scheduling */ + sigset_t set; + sigfillset(&set); + sigprocmask(SIG_BLOCK, &set, NULL); + + pios_tcp_dev *tcp_dev = (pios_tcp_dev*) tcp_dev_n; + + const int INCOMING_BUFFER_SIZE = 16; + char incoming_buffer[INCOMING_BUFFER_SIZE]; + /** + * com devices never get closed except by application "reboot" + * we also never give up our mutex except for waiting + */ + while(1) { + + tcp_dev->socket_connection = accept(tcp_dev->socket, NULL, NULL); + if (0 > tcp_dev->socket_connection) { + perror("Accept failed"); + close(tcp_dev->socket); + exit(EXIT_FAILURE); + } + + fprintf(stderr, "Connection accepted\n"); + + int received; + do { + // Received is used to track the scoket whereas the dev variable is only updated when it can be + received = read(tcp_dev->socket_connection, incoming_buffer, INCOMING_BUFFER_SIZE); + + //while(fifoBuf_getFree(&tcp_dev->rx_fifo) < received); + + fifoBuf_putData(&tcp_dev->rx_fifo, incoming_buffer, received); + } while(received > 0); + + if (-1 == shutdown(tcp_dev->socket_connection, SHUT_RDWR)) + { + //perror("can not shutdown socket"); + //close(tcp_dev->socket_connection); + //exit(EXIT_FAILURE); + } + close(tcp_dev->socket_connection); + tcp_dev->socket_connection = 0; + } +} + + +/** + * Open UDP socket + */ +xTaskHandle tcpRxTaskHandle; +int32_t PIOS_TCP_Init(uint32_t *tcp_id, const struct pios_tcp_cfg * cfg) +{ + + pios_tcp_dev *tcp_dev = &pios_tcp_devices[pios_tcp_num_devices]; + + pios_tcp_num_devices++; + + + /* initialize */ + tcp_dev->rx_in_cb = NULL; + tcp_dev->tx_out_cb = NULL; + tcp_dev->cfg=cfg; + + /* assign socket */ + tcp_dev->socket = socket(PF_INET, SOCK_STREAM, IPPROTO_TCP); + memset(&tcp_dev->server,0,sizeof(tcp_dev->server)); + memset(&tcp_dev->client,0,sizeof(tcp_dev->client)); + tcp_dev->server.sin_family = AF_INET; + tcp_dev->server.sin_addr.s_addr = INADDR_ANY; //inet_addr(tcp_dev->cfg->ip); + tcp_dev->server.sin_port = htons(tcp_dev->cfg->port); + int res= bind(tcp_dev->socket, (struct sockaddr *)&tcp_dev->server,sizeof(tcp_dev->server)); + if (res == -1) { + perror("Binding socket failed\n"); + exit(EXIT_FAILURE); + } + + res = listen(tcp_dev->socket, 10); + if (res == -1) { + perror("Socket listen failed\n"); + exit(EXIT_FAILURE); + } + + fifoBuf_init(&tcp_dev->rx_fifo, tcp_dev->rx_buffer, PIOS_TCP_RX_BUFFER_SIZE); + + pthread_create(&tcp_dev->rxThread, NULL, PIOS_TCP_RxThread, (void*)tcp_dev); + + xTaskCreate(PIOS_TCP_RxTask, (signed char *)"TcpRx", 1024, (void*)tcp_dev, 2, &tcpRxTaskHandle); + + printf("udp dev %i - socket %i opened - result %i\n",pios_tcp_num_devices-1,tcp_dev->socket,res); + + *tcp_id = pios_tcp_num_devices-1; + + return res; +} + + +void PIOS_TCP_ChangeBaud(uint32_t tcp_id, uint32_t baud) +{ + /** + * doesn't apply! + */ +} + + +static void PIOS_TCP_RxStart(uint32_t tp_id, uint16_t rx_bytes_avail) +{ + /** + * lazy! + */ +} + + +static void PIOS_TCP_TxStart(uint32_t tcp_id, uint16_t tx_bytes_avail) +{ + pios_tcp_dev *tcp_dev = find_tcp_dev_by_id(tcp_id); + + PIOS_Assert(tcp_dev); + + int32_t length,len,rem; + + /** + * we send everything directly whenever notified of data to send (lazy!) + */ + if (tcp_dev->tx_out_cb) { + while (tx_bytes_avail>0) { + bool tx_need_yield = false; + length = (tcp_dev->tx_out_cb)(tcp_dev->tx_out_context, tcp_dev->tx_buffer, PIOS_TCP_RX_BUFFER_SIZE, NULL, &tx_need_yield); + rem = length; + while (rem>0) { + if(tcp_dev->socket_connection != 0) { + len = write(tcp_dev->socket_connection, tcp_dev->tx_buffer, length); + } + if (len<=0) { + rem=0; + } else { + rem -= len; + } + } + tx_bytes_avail -= length; +#if defined(PIOS_INCLUDE_FREERTOS) + // Not sure about this + if (tx_need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ + } + } + +} + +static void PIOS_TCP_RegisterRxCallback(uint32_t tcp_id, pios_com_callback rx_in_cb, uint32_t context) +{ + pios_tcp_dev *tcp_dev = find_tcp_dev_by_id(tcp_id); + + PIOS_Assert(tcp_dev); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + tcp_dev->rx_in_context = context; + tcp_dev->rx_in_cb = rx_in_cb; +} + +static void PIOS_TCP_RegisterTxCallback(uint32_t tcp_id, pios_com_callback tx_out_cb, uint32_t context) +{ + pios_tcp_dev *tcp_dev = find_tcp_dev_by_id(tcp_id); + + PIOS_Assert(tcp_dev); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + tcp_dev->tx_out_context = context; + tcp_dev->tx_out_cb = tx_out_cb; +} + +#endif diff --git a/flight/PiOS.osx/osx/pios_udp.c b/flight/PiOS.osx/osx/pios_udp.c index 4705dc3a2..a263116d4 100644 --- a/flight/PiOS.osx/osx/pios_udp.c +++ b/flight/PiOS.osx/osx/pios_udp.c @@ -1,244 +1,244 @@ -/** - ****************************************************************************** - * - * @file pios_udp.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief UDP commands. Inits UDPs, controls UDPs & Interupt handlers. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_UDP UDP Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_UDP) - -#include -#include - -/* We need a list of UDP devices */ - -#define PIOS_UDP_MAX_DEV 256 -static int8_t pios_udp_num_devices = 0; - -static pios_udp_dev pios_udp_devices[PIOS_UDP_MAX_DEV]; - - - -/* Provide a COM driver */ -static void PIOS_UDP_ChangeBaud(uint32_t udp_id, uint32_t baud); -static void PIOS_UDP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context); -static void PIOS_UDP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context); -static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail); -static void PIOS_UDP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail); - -const struct pios_com_driver pios_udp_com_driver = { - .set_baud = PIOS_UDP_ChangeBaud, - .tx_start = PIOS_UDP_TxStart, - .rx_start = PIOS_UDP_RxStart, - .bind_tx_cb = PIOS_UDP_RegisterTxCallback, - .bind_rx_cb = PIOS_UDP_RegisterRxCallback, -}; - - -static pios_udp_dev * find_udp_dev_by_id (uint8_t udp) -{ - if (udp >= pios_udp_num_devices) { - /* Undefined UDP port for this board (see pios_board.c) */ - PIOS_Assert(0); - return NULL; - } - - /* Get a handle for the device configuration */ - return &(pios_udp_devices[udp]); -} - -/** - * RxThread - */ -void PIOS_UDP_RxThread(void * udp_dev_n) -{ - - /* needed because of FreeRTOS.posix scheduling */ - sigset_t set; - sigfillset(&set); - sigprocmask(SIG_BLOCK, &set, NULL); - - pios_udp_dev * udp_dev = (pios_udp_dev*) udp_dev_n; - - /** - * com devices never get closed except by application "reboot" - * we also never give up our mutex except for waiting - */ - while(1) { - - /** - * receive - */ - int received; - udp_dev->clientLength=sizeof(udp_dev->client); - if ((received = recvfrom(udp_dev->socket, - &udp_dev->rx_buffer, - PIOS_UDP_RX_BUFFER_SIZE, - 0, - (struct sockaddr *) &udp_dev->client, - (socklen_t*)&udp_dev->clientLength)) >= 0) - { - - /* copy received data to buffer if possible */ - /* we do NOT buffer data locally. If the com buffer can't receive, data is discarded! */ - /* (thats what the USART driver does too!) */ - bool rx_need_yield = false; - if (udp_dev->rx_in_cb) { - (void) (udp_dev->rx_in_cb)(udp_dev->rx_in_context, udp_dev->rx_buffer, received, NULL, &rx_need_yield); - } - -#if defined(PIOS_INCLUDE_FREERTOS) - if (rx_need_yield) { - vPortYieldFromISR(); - } -#endif /* PIOS_INCLUDE_FREERTOS */ - - } - - - } -} - - -/** -* Open UDP socket -*/ -int32_t PIOS_UDP_Init(uint32_t * udp_id, const struct pios_udp_cfg * cfg) -{ - - pios_udp_dev * udp_dev = &pios_udp_devices[pios_udp_num_devices]; - - pios_udp_num_devices++; - - - /* initialize */ - udp_dev->rx_in_cb = NULL; - udp_dev->tx_out_cb = NULL; - udp_dev->cfg=cfg; - - /* assign socket */ - udp_dev->socket = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP); - memset(&udp_dev->server,0,sizeof(udp_dev->server)); - memset(&udp_dev->client,0,sizeof(udp_dev->client)); - udp_dev->server.sin_family = AF_INET; - udp_dev->server.sin_addr.s_addr = inet_addr(udp_dev->cfg->ip); - udp_dev->server.sin_port = htons(udp_dev->cfg->port); - int res= bind(udp_dev->socket, (struct sockaddr *)&udp_dev->server,sizeof(udp_dev->server)); - - /* Create transmit thread for this connection */ - xTaskCreate(PIOS_UDP_RxThread, (signed char *)"UdpRx", 1024, (void*)udp_dev, 2, &udp_dev->rxThread); - - printf("udp dev %i - socket %i opened - result %i\n",pios_udp_num_devices-1,udp_dev->socket,res); - - *udp_id = pios_udp_num_devices-1; - - return res; -} - - -void PIOS_UDP_ChangeBaud(uint32_t udp_id, uint32_t baud) -{ - /** - * doesn't apply! - */ -} - - -static void PIOS_UDP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail) -{ - /** - * lazy! - */ -} - - -static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail) -{ - pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); - - PIOS_Assert(udp_dev); - - int32_t length,len,rem; - - /** - * we send everything directly whenever notified of data to send (lazy!) - */ - if (udp_dev->tx_out_cb) { - while (tx_bytes_avail>0) { - bool tx_need_yield = false; - length = (udp_dev->tx_out_cb)(udp_dev->tx_out_context, udp_dev->tx_buffer, PIOS_UDP_RX_BUFFER_SIZE, NULL, &tx_need_yield); - rem = length; - while (rem>0) { - len = sendto(udp_dev->socket, udp_dev->tx_buffer, length, 0, - (struct sockaddr *) &udp_dev->client, - sizeof(udp_dev->client)); - if (len<=0) { - rem=0; - } else { - rem -= len; - } - } - tx_bytes_avail -= length; - } - } - -} - -static void PIOS_UDP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context) -{ - pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); - - PIOS_Assert(udp_dev); - - /* - * Order is important in these assignments since ISR uses _cb - * field to determine if it's ok to dereference _cb and _context - */ - udp_dev->rx_in_context = context; - udp_dev->rx_in_cb = rx_in_cb; -} - -static void PIOS_UDP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context) -{ - pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); - - PIOS_Assert(udp_dev); - - /* - * Order is important in these assignments since ISR uses _cb - * field to determine if it's ok to dereference _cb and _context - */ - udp_dev->tx_out_context = context; - udp_dev->tx_out_cb = tx_out_cb; -} - - - - - -#endif +/** + ****************************************************************************** + * + * @file pios_udp.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief UDP commands. Inits UDPs, controls UDPs & Interupt handlers. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_UDP UDP Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_UDP) + +#include +#include + +/* We need a list of UDP devices */ + +#define PIOS_UDP_MAX_DEV 256 +static int8_t pios_udp_num_devices = 0; + +static pios_udp_dev pios_udp_devices[PIOS_UDP_MAX_DEV]; + + + +/* Provide a COM driver */ +static void PIOS_UDP_ChangeBaud(uint32_t udp_id, uint32_t baud); +static void PIOS_UDP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context); +static void PIOS_UDP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context); +static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail); +static void PIOS_UDP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail); + +const struct pios_com_driver pios_udp_com_driver = { + .set_baud = PIOS_UDP_ChangeBaud, + .tx_start = PIOS_UDP_TxStart, + .rx_start = PIOS_UDP_RxStart, + .bind_tx_cb = PIOS_UDP_RegisterTxCallback, + .bind_rx_cb = PIOS_UDP_RegisterRxCallback, +}; + + +static pios_udp_dev * find_udp_dev_by_id (uint8_t udp) +{ + if (udp >= pios_udp_num_devices) { + /* Undefined UDP port for this board (see pios_board.c) */ + PIOS_Assert(0); + return NULL; + } + + /* Get a handle for the device configuration */ + return &(pios_udp_devices[udp]); +} + +/** + * RxThread + */ +void PIOS_UDP_RxThread(void * udp_dev_n) +{ + + /* needed because of FreeRTOS.posix scheduling */ + sigset_t set; + sigfillset(&set); + sigprocmask(SIG_BLOCK, &set, NULL); + + pios_udp_dev * udp_dev = (pios_udp_dev*) udp_dev_n; + + /** + * com devices never get closed except by application "reboot" + * we also never give up our mutex except for waiting + */ + while(1) { + + /** + * receive + */ + int received; + udp_dev->clientLength=sizeof(udp_dev->client); + if ((received = recvfrom(udp_dev->socket, + &udp_dev->rx_buffer, + PIOS_UDP_RX_BUFFER_SIZE, + 0, + (struct sockaddr *) &udp_dev->client, + (socklen_t*)&udp_dev->clientLength)) >= 0) + { + + /* copy received data to buffer if possible */ + /* we do NOT buffer data locally. If the com buffer can't receive, data is discarded! */ + /* (thats what the USART driver does too!) */ + bool rx_need_yield = false; + if (udp_dev->rx_in_cb) { + (void) (udp_dev->rx_in_cb)(udp_dev->rx_in_context, udp_dev->rx_buffer, received, NULL, &rx_need_yield); + } + +#if defined(PIOS_INCLUDE_FREERTOS) + if (rx_need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ + + } + + + } +} + + +/** +* Open UDP socket +*/ +int32_t PIOS_UDP_Init(uint32_t * udp_id, const struct pios_udp_cfg * cfg) +{ + + pios_udp_dev * udp_dev = &pios_udp_devices[pios_udp_num_devices]; + + pios_udp_num_devices++; + + + /* initialize */ + udp_dev->rx_in_cb = NULL; + udp_dev->tx_out_cb = NULL; + udp_dev->cfg=cfg; + + /* assign socket */ + udp_dev->socket = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP); + memset(&udp_dev->server,0,sizeof(udp_dev->server)); + memset(&udp_dev->client,0,sizeof(udp_dev->client)); + udp_dev->server.sin_family = AF_INET; + udp_dev->server.sin_addr.s_addr = inet_addr(udp_dev->cfg->ip); + udp_dev->server.sin_port = htons(udp_dev->cfg->port); + int res= bind(udp_dev->socket, (struct sockaddr *)&udp_dev->server,sizeof(udp_dev->server)); + + /* Create transmit thread for this connection */ + xTaskCreate(PIOS_UDP_RxThread, (signed char *)"UdpRx", 1024, (void*)udp_dev, 2, &udp_dev->rxThread); + + printf("udp dev %i - socket %i opened - result %i\n",pios_udp_num_devices-1,udp_dev->socket,res); + + *udp_id = pios_udp_num_devices-1; + + return res; +} + + +void PIOS_UDP_ChangeBaud(uint32_t udp_id, uint32_t baud) +{ + /** + * doesn't apply! + */ +} + + +static void PIOS_UDP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail) +{ + /** + * lazy! + */ +} + + +static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail) +{ + pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); + + PIOS_Assert(udp_dev); + + int32_t length,len,rem; + + /** + * we send everything directly whenever notified of data to send (lazy!) + */ + if (udp_dev->tx_out_cb) { + while (tx_bytes_avail>0) { + bool tx_need_yield = false; + length = (udp_dev->tx_out_cb)(udp_dev->tx_out_context, udp_dev->tx_buffer, PIOS_UDP_RX_BUFFER_SIZE, NULL, &tx_need_yield); + rem = length; + while (rem>0) { + len = sendto(udp_dev->socket, udp_dev->tx_buffer, length, 0, + (struct sockaddr *) &udp_dev->client, + sizeof(udp_dev->client)); + if (len<=0) { + rem=0; + } else { + rem -= len; + } + } + tx_bytes_avail -= length; + } + } + +} + +static void PIOS_UDP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context) +{ + pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); + + PIOS_Assert(udp_dev); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + udp_dev->rx_in_context = context; + udp_dev->rx_in_cb = rx_in_cb; +} + +static void PIOS_UDP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context) +{ + pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); + + PIOS_Assert(udp_dev); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + udp_dev->tx_out_context = context; + udp_dev->tx_out_cb = tx_out_cb; +} + + + + + +#endif diff --git a/flight/PiOS.osx/osx/pios_wdg.c b/flight/PiOS.osx/osx/pios_wdg.c index 6eb3cb39d..f2c35dac2 100644 --- a/flight/PiOS.osx/osx/pios_wdg.c +++ b/flight/PiOS.osx/osx/pios_wdg.c @@ -1,153 +1,153 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_WDG Watchdog Functions - * @brief PIOS Comamnds to initialize and clear watchdog timer - * @{ - * - * @file pios_spi.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief Hardware Abstraction Layer for SPI ports of STM32 - * @see The GNU Public License (GPL) Version 3 - * @notes - * - * The PIOS Watchdog provides a HAL to initialize a watchdog - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pios.h" - -unsigned int wdg_registered_flags; -unsigned int wdg_updated_flags; -unsigned int wdg_cleared_time; -unsigned int wdg_last_update_time; -bool wdg_expired; - -/** - * @brief Initialize the watchdog timer for a specified timeout - * - * It is important to note that this function returns the achieved timeout - * for this hardware. For hardware indendence this should be checked when - * scheduling updates. Other hardware dependent details may need to be - * considered such as a window time which sets a minimum update time, - * and this function should return a recommended delay for clearing. - * - * For the STM32 nominal clock rate is 32 khz, but for the maximum clock rate of - * 60 khz and a prescalar of 4 yields a clock rate of 15 khz. The delay that is - * set in the watchdog assumes the nominal clock rate, but the delay for FreeRTOS - * to use is 75% of the minimal delay. - * - * @param[in] delayMs The delay period in ms - * @returns Maximum recommended delay between updates - */ -void PIOS_WDG_Init() -{ - wdg_registered_flags = 0; - wdg_updated_flags = 0; -} - -/** - * @brief Register a module against the watchdog - * - * There are two ways to use PIOS WDG: this is for when - * multiple modules must be monitored. In this case they - * must first register against the watchdog system and - * only when all of the modules have been updated with the - * watchdog be cleared. Each module must have its own - * bit in the 16 bit - * - * @param[in] flag the bit this module wants to use - * @returns True if that bit is unregistered - */ -bool PIOS_WDG_RegisterFlag(uint16_t flag_requested) -{ - wdg_registered_flags |= flag_requested; - return true; -} - -/** - * @brief Function called by modules to indicate they are still running - * - * This function will set this flag in the active flags register (which is - * a backup regsiter) and if all the registered flags are set will clear - * the watchdog and set only this flag in the backup register - * - * @param[in] flag the flag to set - * @return true if the watchdog cleared, false if flags are pending - */ -bool PIOS_WDG_UpdateFlag(uint16_t flag) -{ - PIOS_WDG_Check(); - wdg_updated_flags |= flag; - if( wdg_updated_flags == wdg_registered_flags) { - wdg_last_update_time = PIOS_DELAY_DiffuS(wdg_cleared_time); - wdg_updated_flags = 0; - wdg_cleared_time = PIOS_DELAY_GetRaw(); - } - return true; -} - -/** - * @brief Returns the flags that were set at bootup - * - * This is used for diagnostics, if only one flag not set this - * was likely the module that wasn't running before reset - * - * @return The active flags register from bootup - */ -uint16_t PIOS_WDG_GetBootupFlags() -{ - return (uint16_t) 0xffff; -} - -/** - * @brief Returns the currently active flags - * - * For external monitoring - * - * @return The active flags register - */ -uint16_t PIOS_WDG_GetActiveFlags() -{ - return (uint16_t) 0xffff; -} - -/** - * @brief Clear the watchdog timer - * - * This function must be called at the appropriate delay to prevent a reset event occuring - */ -void PIOS_WDG_Clear(void) -{ -} - -/** - * @brief This function returns true if the watchdog would - * have expired - */ -bool PIOS_WDG_Check() -{ - if(PIOS_DELAY_DiffuS(wdg_cleared_time) > 250000) { - if(!wdg_expired) - fprintf(stderr, "Watchdog fired!\r\n"); - wdg_expired = true; - } - return wdg_expired; +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_WDG Watchdog Functions + * @brief PIOS Comamnds to initialize and clear watchdog timer + * @{ + * + * @file pios_spi.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Hardware Abstraction Layer for SPI ports of STM32 + * @see The GNU Public License (GPL) Version 3 + * @notes + * + * The PIOS Watchdog provides a HAL to initialize a watchdog + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios.h" + +unsigned int wdg_registered_flags; +unsigned int wdg_updated_flags; +unsigned int wdg_cleared_time; +unsigned int wdg_last_update_time; +bool wdg_expired; + +/** + * @brief Initialize the watchdog timer for a specified timeout + * + * It is important to note that this function returns the achieved timeout + * for this hardware. For hardware indendence this should be checked when + * scheduling updates. Other hardware dependent details may need to be + * considered such as a window time which sets a minimum update time, + * and this function should return a recommended delay for clearing. + * + * For the STM32 nominal clock rate is 32 khz, but for the maximum clock rate of + * 60 khz and a prescalar of 4 yields a clock rate of 15 khz. The delay that is + * set in the watchdog assumes the nominal clock rate, but the delay for FreeRTOS + * to use is 75% of the minimal delay. + * + * @param[in] delayMs The delay period in ms + * @returns Maximum recommended delay between updates + */ +void PIOS_WDG_Init() +{ + wdg_registered_flags = 0; + wdg_updated_flags = 0; +} + +/** + * @brief Register a module against the watchdog + * + * There are two ways to use PIOS WDG: this is for when + * multiple modules must be monitored. In this case they + * must first register against the watchdog system and + * only when all of the modules have been updated with the + * watchdog be cleared. Each module must have its own + * bit in the 16 bit + * + * @param[in] flag the bit this module wants to use + * @returns True if that bit is unregistered + */ +bool PIOS_WDG_RegisterFlag(uint16_t flag_requested) +{ + wdg_registered_flags |= flag_requested; + return true; +} + +/** + * @brief Function called by modules to indicate they are still running + * + * This function will set this flag in the active flags register (which is + * a backup regsiter) and if all the registered flags are set will clear + * the watchdog and set only this flag in the backup register + * + * @param[in] flag the flag to set + * @return true if the watchdog cleared, false if flags are pending + */ +bool PIOS_WDG_UpdateFlag(uint16_t flag) +{ + PIOS_WDG_Check(); + wdg_updated_flags |= flag; + if( wdg_updated_flags == wdg_registered_flags) { + wdg_last_update_time = PIOS_DELAY_DiffuS(wdg_cleared_time); + wdg_updated_flags = 0; + wdg_cleared_time = PIOS_DELAY_GetRaw(); + } + return true; +} + +/** + * @brief Returns the flags that were set at bootup + * + * This is used for diagnostics, if only one flag not set this + * was likely the module that wasn't running before reset + * + * @return The active flags register from bootup + */ +uint16_t PIOS_WDG_GetBootupFlags() +{ + return (uint16_t) 0xffff; +} + +/** + * @brief Returns the currently active flags + * + * For external monitoring + * + * @return The active flags register + */ +uint16_t PIOS_WDG_GetActiveFlags() +{ + return (uint16_t) 0xffff; +} + +/** + * @brief Clear the watchdog timer + * + * This function must be called at the appropriate delay to prevent a reset event occuring + */ +void PIOS_WDG_Clear(void) +{ +} + +/** + * @brief This function returns true if the watchdog would + * have expired + */ +bool PIOS_WDG_Check() +{ + if(PIOS_DELAY_DiffuS(wdg_cleared_time) > 250000) { + if(!wdg_expired) + fprintf(stderr, "Watchdog fired!\r\n"); + wdg_expired = true; + } + return wdg_expired; } \ No newline at end of file diff --git a/flight/PiOS.osx/pios.h b/flight/PiOS.osx/pios.h index debdef9b7..cc49e781e 100644 --- a/flight/PiOS.osx/pios.h +++ b/flight/PiOS.osx/pios.h @@ -1,84 +1,84 @@ -/** - ****************************************************************************** - * - * @file pios.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main PiOS header. - * - Central header for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_H -#define PIOS_H - -/* PIOS Feature Selection */ -#include "pios_config_sim.h" -#include - -#if defined(PIOS_INCLUDE_FREERTOS) -/* FreeRTOS Includes */ -#include "FreeRTOS.h" -#include "task.h" -#include "queue.h" -#include "semphr.h" - -#define vPortInitialiseBlocks(); -#endif - -/* C Lib Includes */ -#include -#include -#include -#include -#include -#include - -/* Generic initcall infrastructure */ -#include "pios_initcall.h" - -/* PIOS Board Specific Device Configuration */ -#include "pios_board_sim.h" - -/* PIOS Hardware Includes (posix) */ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#if defined(PIOS_INCLUDE_IAP) -#include -#endif -#if defined(PIOS_INCLUDE_BL_HELPER) -#include -#endif - -#define NELEMENTS(x) (sizeof(x) / sizeof(*(x))) - -#endif /* PIOS_H */ +/** + ****************************************************************************** + * + * @file pios.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main PiOS header. + * - Central header for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_H +#define PIOS_H + +/* PIOS Feature Selection */ +#include "pios_config_sim.h" +#include + +#if defined(PIOS_INCLUDE_FREERTOS) +/* FreeRTOS Includes */ +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "semphr.h" + +#define vPortInitialiseBlocks(); +#endif + +/* C Lib Includes */ +#include +#include +#include +#include +#include +#include + +/* Generic initcall infrastructure */ +#include "pios_initcall.h" + +/* PIOS Board Specific Device Configuration */ +#include "pios_board_sim.h" + +/* PIOS Hardware Includes (posix) */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined(PIOS_INCLUDE_IAP) +#include +#endif +#if defined(PIOS_INCLUDE_BL_HELPER) +#include +#endif + +#define NELEMENTS(x) (sizeof(x) / sizeof(*(x))) + +#endif /* PIOS_H */ diff --git a/flight/PiOS.win32/inc/FreeRTOSConfig.h b/flight/PiOS.win32/inc/FreeRTOSConfig.h index 8b8b51fed..063a843a1 100644 --- a/flight/PiOS.win32/inc/FreeRTOSConfig.h +++ b/flight/PiOS.win32/inc/FreeRTOSConfig.h @@ -1,76 +1,76 @@ - -#ifndef FREERTOS_CONFIG_H -#define FREERTOS_CONFIG_H - -/*----------------------------------------------------------- - * Application specific definitions. - * - * These definitions should be adjusted for your particular hardware and - * application requirements. - * - * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE - * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. - * - * See http://www.freertos.org/a00110.html. - *----------------------------------------------------------*/ - -/* Notes: We use 5 task priorities */ - -#define IDLE_SLEEPS - -#define configUSE_PREEMPTION 1 -#define configIDLE_SHOULD_YIELD 1 - -#define configUSE_IDLE_HOOK 1 -#define configUSE_TICK_HOOK 0 -#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) -#define configTICK_RATE_HZ ( ( portTickType ) 100 ) -#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) -#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 ) -#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 45 * 1024 ) ) -#define configMAX_TASK_NAME_LEN ( 16 ) -#define configUSE_TRACE_FACILITY 0 -#define configUSE_16_BIT_TICKS 0 -#define configUSE_MUTEXES 1 -#define configUSE_RECURSIVE_MUTEXES 1 -#define configUSE_COUNTING_SEMAPHORES 0 -#define configUSE_ALTERNATIVE_API 0 -#define configCHECK_FOR_STACK_OVERFLOW 2 -#define configQUEUE_REGISTRY_SIZE 10 - - -/* Co-routine definitions. */ -#define configUSE_CO_ROUTINES 0 -#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) - -/* Set the following definitions to 1 to include the API function, or zero -to exclude the API function. */ - -#define INCLUDE_vTaskPrioritySet 1 -#define INCLUDE_uxTaskPriorityGet 1 -#define INCLUDE_vTaskDelete 1 -#define INCLUDE_vTaskCleanUpResources 0 -#define INCLUDE_vTaskSuspend 1 -#define INCLUDE_vTaskDelayUntil 1 -#define INCLUDE_vTaskDelay 1 -#define INCLUDE_xTaskGetSchedulerState 1 -#define INCLUDE_xTaskGetCurrentTaskHandle 1 -#define INCLUDE_uxTaskGetStackHighWaterMark 0 - - - - -/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 -(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ -#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ -#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ - - -/* This is the value being used as per the ST library which permits 16 -priority values, 0 to 15. This must correspond to the -configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest -NVIC value of 255. */ -#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 - -#endif /* FREERTOS_CONFIG_H */ - + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html. + *----------------------------------------------------------*/ + +/* Notes: We use 5 task priorities */ + +#define IDLE_SLEEPS + +#define configUSE_PREEMPTION 1 +#define configIDLE_SHOULD_YIELD 1 + +#define configUSE_IDLE_HOOK 1 +#define configUSE_TICK_HOOK 0 +#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) +#define configTICK_RATE_HZ ( ( portTickType ) 100 ) +#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) +#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 ) +#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 45 * 1024 ) ) +#define configMAX_TASK_NAME_LEN ( 16 ) +#define configUSE_TRACE_FACILITY 0 +#define configUSE_16_BIT_TICKS 0 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 0 +#define configUSE_ALTERNATIVE_API 0 +#define configCHECK_FOR_STACK_OVERFLOW 2 +#define configQUEUE_REGISTRY_SIZE 10 + + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ + +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 0 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 1 +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 0 + + + + +/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 +(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ +#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ + + +/* This is the value being used as per the ST library which permits 16 +priority values, 0 to 15. This must correspond to the +configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest +NVIC value of 255. */ +#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 + +#endif /* FREERTOS_CONFIG_H */ + diff --git a/flight/PiOS.win32/inc/pios_com.h b/flight/PiOS.win32/inc/pios_com.h index 321f04112..b18cb3d52 100644 --- a/flight/PiOS.win32/inc/pios_com.h +++ b/flight/PiOS.win32/inc/pios_com.h @@ -1,56 +1,56 @@ -/** - ****************************************************************************** - * - * @file pios_com.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief COM layer functions header - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_COM_H -#define PIOS_COM_H - -/* Public Functions */ -extern int32_t PIOS_COM_Init(void); -extern int32_t PIOS_COM_Close(void); -extern int32_t PIOS_COM_ChangeBaud(uint8_t port, uint32_t baud); -extern int32_t PIOS_COM_SendCharNonBlocking(uint8_t port, char c); -extern int32_t PIOS_COM_SendChar(uint8_t port, char c); -extern int32_t PIOS_COM_SendBufferNonBlocking(uint8_t port, uint8_t *buffer, uint16_t len); -extern int32_t PIOS_COM_SendBuffer(uint8_t port, uint8_t *buffer, uint16_t len); -extern int32_t PIOS_COM_SendStringNonBlocking(uint8_t port, char *str); -extern int32_t PIOS_COM_SendString(uint8_t port, char *str); -extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint8_t port, char *format, ...); -extern int32_t PIOS_COM_SendFormattedString(uint8_t port, char *format, ...); -extern uint8_t PIOS_COM_ReceiveBuffer(uint8_t port); -extern int32_t PIOS_COM_ReceiveBufferUsed(uint8_t port); - -extern int32_t PIOS_COM_ReceiveHandler(void); - -struct pios_com_driver { - void (*init)(uint8_t id); - void (*set_baud)(uint8_t id, uint32_t baud); - int32_t (*tx_nb)(uint8_t id, char *buffer, uint16_t len); - int32_t (*tx)(uint8_t id, char *buffer, uint16_t len); - int32_t (*rx)(uint8_t id); - int32_t (*rx_avail)(uint8_t id); -}; - -#endif /* PIOS_COM_H */ +/** + ****************************************************************************** + * + * @file pios_com.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief COM layer functions header + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_COM_H +#define PIOS_COM_H + +/* Public Functions */ +extern int32_t PIOS_COM_Init(void); +extern int32_t PIOS_COM_Close(void); +extern int32_t PIOS_COM_ChangeBaud(uint8_t port, uint32_t baud); +extern int32_t PIOS_COM_SendCharNonBlocking(uint8_t port, char c); +extern int32_t PIOS_COM_SendChar(uint8_t port, char c); +extern int32_t PIOS_COM_SendBufferNonBlocking(uint8_t port, uint8_t *buffer, uint16_t len); +extern int32_t PIOS_COM_SendBuffer(uint8_t port, uint8_t *buffer, uint16_t len); +extern int32_t PIOS_COM_SendStringNonBlocking(uint8_t port, char *str); +extern int32_t PIOS_COM_SendString(uint8_t port, char *str); +extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint8_t port, char *format, ...); +extern int32_t PIOS_COM_SendFormattedString(uint8_t port, char *format, ...); +extern uint8_t PIOS_COM_ReceiveBuffer(uint8_t port); +extern int32_t PIOS_COM_ReceiveBufferUsed(uint8_t port); + +extern int32_t PIOS_COM_ReceiveHandler(void); + +struct pios_com_driver { + void (*init)(uint8_t id); + void (*set_baud)(uint8_t id, uint32_t baud); + int32_t (*tx_nb)(uint8_t id, char *buffer, uint16_t len); + int32_t (*tx)(uint8_t id, char *buffer, uint16_t len); + int32_t (*rx)(uint8_t id); + int32_t (*rx_avail)(uint8_t id); +}; + +#endif /* PIOS_COM_H */ diff --git a/flight/PiOS.win32/inc/pios_delay.h b/flight/PiOS.win32/inc/pios_delay.h index dcd9bb68d..8c49603c4 100644 --- a/flight/PiOS.win32/inc/pios_delay.h +++ b/flight/PiOS.win32/inc/pios_delay.h @@ -1,37 +1,37 @@ -/** - ****************************************************************************** - * - * @file pios_settings.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief Settings functions header - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_DELAY_H -#define PIOS_DELAY_H - - -/* Public Functions */ -extern int32_t PIOS_DELAY_Init(void); -extern int32_t PIOS_DELAY_WaituS(uint16_t uS); -extern int32_t PIOS_DELAY_WaitmS(uint16_t mS); - - -#endif /* PIOS_DELAY_H */ +/** + ****************************************************************************** + * + * @file pios_settings.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief Settings functions header + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_DELAY_H +#define PIOS_DELAY_H + + +/* Public Functions */ +extern int32_t PIOS_DELAY_Init(void); +extern int32_t PIOS_DELAY_WaituS(uint16_t uS); +extern int32_t PIOS_DELAY_WaitmS(uint16_t mS); + + +#endif /* PIOS_DELAY_H */ diff --git a/flight/PiOS.win32/inc/pios_initcall.h b/flight/PiOS.win32/inc/pios_initcall.h index bdb47cc8e..3805a88c6 100644 --- a/flight/PiOS.win32/inc/pios_initcall.h +++ b/flight/PiOS.win32/inc/pios_initcall.h @@ -1,58 +1,58 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Initcall infrastructure - * @{ - * @addtogroup PIOS_INITCALL Generic Initcall Macros - * @brief Initcall Macros - * @{ - * - * @file pios_initcall.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @brief Initcall header - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_INITCALL_H -#define PIOS_INITCALL_H - -/** - * Just a stub define to make things compile. - * Automatically link based initialization currently doesn't work - * since posix really runs on a multitude of architectures - * and we cannot define a linker script for each of them atm - */ - -#define MODULE_INITCALL(ifn, sfn) - -#define MODULE_TASKCREATE_ALL - -#define MODULE_INITIALISE_ALL { \ - /* Initialize modules */ \ - InitModules(); \ - /* Start the FreeRTOS scheduler which never returns.*/ \ - /* Initialize the system thread */ \ - SystemModInitialize();} - - -#endif /* PIOS_INITCALL_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Initcall infrastructure + * @{ + * @addtogroup PIOS_INITCALL Generic Initcall Macros + * @brief Initcall Macros + * @{ + * + * @file pios_initcall.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Initcall header + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_INITCALL_H +#define PIOS_INITCALL_H + +/** + * Just a stub define to make things compile. + * Automatically link based initialization currently doesn't work + * since posix really runs on a multitude of architectures + * and we cannot define a linker script for each of them atm + */ + +#define MODULE_INITCALL(ifn, sfn) + +#define MODULE_TASKCREATE_ALL + +#define MODULE_INITIALISE_ALL { \ + /* Initialize modules */ \ + InitModules(); \ + /* Start the FreeRTOS scheduler which never returns.*/ \ + /* Initialize the system thread */ \ + SystemModInitialize();} + + +#endif /* PIOS_INITCALL_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS.win32/inc/pios_led.h b/flight/PiOS.win32/inc/pios_led.h index 42b0d2443..94283e4b6 100644 --- a/flight/PiOS.win32/inc/pios_led.h +++ b/flight/PiOS.win32/inc/pios_led.h @@ -1,43 +1,43 @@ -/** - ****************************************************************************** - * - * @file pios_led.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief LED functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_LED_H -#define PIOS_LED_H - -/* Type Definitions */ - -#if (PIOS_LED_NUM == 1) -typedef enum {LED1 = 0} LedTypeDef; -#elif (PIOS_LED_NUM == 2) -typedef enum {LED1 = 0, LED2 = 1} LedTypeDef; -#endif - -/* Public Functions */ -extern void PIOS_LED_Init(void); -extern void PIOS_LED_On(LedTypeDef LED); -extern void PIOS_LED_Off(LedTypeDef LED); -extern void PIOS_LED_Toggle(LedTypeDef LED); - -#endif /* PIOS_LED_H */ +/** + ****************************************************************************** + * + * @file pios_led.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief LED functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_LED_H +#define PIOS_LED_H + +/* Type Definitions */ + +#if (PIOS_LED_NUM == 1) +typedef enum {LED1 = 0} LedTypeDef; +#elif (PIOS_LED_NUM == 2) +typedef enum {LED1 = 0, LED2 = 1} LedTypeDef; +#endif + +/* Public Functions */ +extern void PIOS_LED_Init(void); +extern void PIOS_LED_On(LedTypeDef LED); +extern void PIOS_LED_Off(LedTypeDef LED); +extern void PIOS_LED_Toggle(LedTypeDef LED); + +#endif /* PIOS_LED_H */ diff --git a/flight/PiOS.win32/inc/pios_sdcard.h b/flight/PiOS.win32/inc/pios_sdcard.h index 225d9de80..2927def2d 100644 --- a/flight/PiOS.win32/inc/pios_sdcard.h +++ b/flight/PiOS.win32/inc/pios_sdcard.h @@ -1,113 +1,113 @@ -/** - ****************************************************************************** - * - * @file pios_sdcard.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief System and hardware Init functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_SDCARD_H -#define PIOS_SDCARD_H - -#if defined(PIOS_INCLUDE_SDCARD) - -/* Public Functions */ -typedef struct { - uint8_t CSDStruct; /* CSD structure */ - uint8_t SysSpecVersion; /* System specification version */ - uint8_t Reserved1; /* Reserved */ - uint8_t TAAC; /* Data read access-time 1 */ - uint8_t NSAC; /* Data read access-time 2 in CLK cycles */ - uint8_t MaxBusClkFrec; /* Max. bus clock frequency */ - uint16_t CardComdClasses; /* Card command classes */ - uint8_t RdBlockLen; /* Max. read data block length */ - uint8_t PartBlockRead; /* Partial blocks for read allowed */ - uint8_t WrBlockMisalign; /* Write block misalignment */ - uint8_t RdBlockMisalign; /* Read block misalignment */ - uint8_t DSRImpl; /* DSR implemented */ - uint8_t Reserved2; /* Reserved */ - uint16_t DeviceSize; /* Device Size */ - uint8_t MaxRdCurrentVDDMin; /* Max. read current @ VDD min */ - uint8_t MaxRdCurrentVDDMax; /* Max. read current @ VDD max */ - uint8_t MaxWrCurrentVDDMin; /* Max. write current @ VDD min */ - uint8_t MaxWrCurrentVDDMax; /* Max. write current @ VDD max */ - uint8_t DeviceSizeMul; /* Device size multiplier */ - uint8_t EraseGrSize; /* Erase group size */ - uint8_t EraseGrMul; /* Erase group size multiplier */ - uint8_t WrProtectGrSize; /* Write protect group size */ - uint8_t WrProtectGrEnable; /* Write protect group enable */ - uint8_t ManDeflECC; /* Manufacturer default ECC */ - uint8_t WrSpeedFact; /* Write speed factor */ - uint8_t MaxWrBlockLen; /* Max. write data block length */ - uint8_t WriteBlockPaPartial; /* Partial blocks for write allowed */ - uint8_t Reserved3; /* Reserved */ - uint8_t ContentProtectAppli; /* Content protection application */ - uint8_t FileFormatGrouop; /* File format group */ - uint8_t CopyFlag; /* Copy flag (OTP) */ - uint8_t PermWrProtect; /* Permanent write protection */ - uint8_t TempWrProtect; /* Temporary write protection */ - uint8_t FileFormat; /* File Format */ - uint8_t ECC; /* ECC code */ - uint8_t msd_CRC; /* CRC */ - uint8_t Reserved4; /* always 1*/ -} SDCARDCsdTypeDef; - -/* Structure taken from Mass Storage Driver example provided by STM */ -typedef struct { - uint8_t ManufacturerID; /* ManufacturerID */ - uint16_t OEM_AppliID; /* OEM/Application ID */ - char ProdName[6]; /* Product Name */ - uint8_t ProdRev; /* Product Revision */ - uint32_t ProdSN; /* Product Serial Number */ - uint8_t Reserved1; /* Reserved1 */ - uint16_t ManufactDate; /* Manufacturing Date */ - uint8_t msd_CRC; /* CRC */ - uint8_t Reserved2; /* always 1*/ -} SDCARDCidTypeDef; - -/* Global Variables */ -//extern VOLINFO PIOS_SDCARD_VolInfo; -//extern uint8_t PIOS_SDCARD_Sector[SECTOR_SIZE]; - -/* Prototypes */ -extern int32_t PIOS_SDCARD_Init(void); -extern int32_t PIOS_SDCARD_PowerOn(void); -extern int32_t PIOS_SDCARD_PowerOff(void); -extern int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available); -extern int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc); -extern int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer); -extern int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer); -extern int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid); -extern int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd); - -extern int32_t PIOS_SDCARD_StartupLog(void); -extern int32_t PIOS_SDCARD_IsMounted(); -extern int32_t PIOS_SDCARD_MountFS(uint32_t StartupLog); -extern int32_t PIOS_SDCARD_GetFree(void); - -//extern int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len); -//extern int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len); -extern int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination); -extern int32_t PIOS_SDCARD_FileDelete(char *Filename); - -#endif - -#endif /* PIOS_SDCARD_H */ +/** + ****************************************************************************** + * + * @file pios_sdcard.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief System and hardware Init functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_SDCARD_H +#define PIOS_SDCARD_H + +#if defined(PIOS_INCLUDE_SDCARD) + +/* Public Functions */ +typedef struct { + uint8_t CSDStruct; /* CSD structure */ + uint8_t SysSpecVersion; /* System specification version */ + uint8_t Reserved1; /* Reserved */ + uint8_t TAAC; /* Data read access-time 1 */ + uint8_t NSAC; /* Data read access-time 2 in CLK cycles */ + uint8_t MaxBusClkFrec; /* Max. bus clock frequency */ + uint16_t CardComdClasses; /* Card command classes */ + uint8_t RdBlockLen; /* Max. read data block length */ + uint8_t PartBlockRead; /* Partial blocks for read allowed */ + uint8_t WrBlockMisalign; /* Write block misalignment */ + uint8_t RdBlockMisalign; /* Read block misalignment */ + uint8_t DSRImpl; /* DSR implemented */ + uint8_t Reserved2; /* Reserved */ + uint16_t DeviceSize; /* Device Size */ + uint8_t MaxRdCurrentVDDMin; /* Max. read current @ VDD min */ + uint8_t MaxRdCurrentVDDMax; /* Max. read current @ VDD max */ + uint8_t MaxWrCurrentVDDMin; /* Max. write current @ VDD min */ + uint8_t MaxWrCurrentVDDMax; /* Max. write current @ VDD max */ + uint8_t DeviceSizeMul; /* Device size multiplier */ + uint8_t EraseGrSize; /* Erase group size */ + uint8_t EraseGrMul; /* Erase group size multiplier */ + uint8_t WrProtectGrSize; /* Write protect group size */ + uint8_t WrProtectGrEnable; /* Write protect group enable */ + uint8_t ManDeflECC; /* Manufacturer default ECC */ + uint8_t WrSpeedFact; /* Write speed factor */ + uint8_t MaxWrBlockLen; /* Max. write data block length */ + uint8_t WriteBlockPaPartial; /* Partial blocks for write allowed */ + uint8_t Reserved3; /* Reserved */ + uint8_t ContentProtectAppli; /* Content protection application */ + uint8_t FileFormatGrouop; /* File format group */ + uint8_t CopyFlag; /* Copy flag (OTP) */ + uint8_t PermWrProtect; /* Permanent write protection */ + uint8_t TempWrProtect; /* Temporary write protection */ + uint8_t FileFormat; /* File Format */ + uint8_t ECC; /* ECC code */ + uint8_t msd_CRC; /* CRC */ + uint8_t Reserved4; /* always 1*/ +} SDCARDCsdTypeDef; + +/* Structure taken from Mass Storage Driver example provided by STM */ +typedef struct { + uint8_t ManufacturerID; /* ManufacturerID */ + uint16_t OEM_AppliID; /* OEM/Application ID */ + char ProdName[6]; /* Product Name */ + uint8_t ProdRev; /* Product Revision */ + uint32_t ProdSN; /* Product Serial Number */ + uint8_t Reserved1; /* Reserved1 */ + uint16_t ManufactDate; /* Manufacturing Date */ + uint8_t msd_CRC; /* CRC */ + uint8_t Reserved2; /* always 1*/ +} SDCARDCidTypeDef; + +/* Global Variables */ +//extern VOLINFO PIOS_SDCARD_VolInfo; +//extern uint8_t PIOS_SDCARD_Sector[SECTOR_SIZE]; + +/* Prototypes */ +extern int32_t PIOS_SDCARD_Init(void); +extern int32_t PIOS_SDCARD_PowerOn(void); +extern int32_t PIOS_SDCARD_PowerOff(void); +extern int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available); +extern int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc); +extern int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer); +extern int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer); +extern int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid); +extern int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd); + +extern int32_t PIOS_SDCARD_StartupLog(void); +extern int32_t PIOS_SDCARD_IsMounted(); +extern int32_t PIOS_SDCARD_MountFS(uint32_t StartupLog); +extern int32_t PIOS_SDCARD_GetFree(void); + +//extern int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len); +//extern int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len); +extern int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination); +extern int32_t PIOS_SDCARD_FileDelete(char *Filename); + +#endif + +#endif /* PIOS_SDCARD_H */ diff --git a/flight/PiOS.win32/inc/pios_sys.h b/flight/PiOS.win32/inc/pios_sys.h index 4e71b54a0..b99232649 100644 --- a/flight/PiOS.win32/inc/pios_sys.h +++ b/flight/PiOS.win32/inc/pios_sys.h @@ -1,35 +1,35 @@ -/** - ****************************************************************************** - * - * @file pios_sys.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief System and hardware Init functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_SYS_H -#define PIOS_SYS_H - -/* Public Functions */ -extern void PIOS_SYS_Init(void); -extern int32_t PIOS_SYS_Reset(void); -extern int32_t PIOS_SYS_SerialNumberGet(char *str); - -#endif /* PIOS_SYS_H */ +/** + ****************************************************************************** + * + * @file pios_sys.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief System and hardware Init functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_SYS_H +#define PIOS_SYS_H + +/* Public Functions */ +extern void PIOS_SYS_Init(void); +extern int32_t PIOS_SYS_Reset(void); +extern int32_t PIOS_SYS_SerialNumberGet(char *str); + +#endif /* PIOS_SYS_H */ diff --git a/flight/PiOS.win32/inc/pios_udp.h b/flight/PiOS.win32/inc/pios_udp.h index 218c10f42..f35fe903f 100644 --- a/flight/PiOS.win32/inc/pios_udp.h +++ b/flight/PiOS.win32/inc/pios_udp.h @@ -1,52 +1,52 @@ -/** - ****************************************************************************** - * - * @file pios_usart.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief UDP functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_UDP_H -#define PIOS_UDP_H - - -/* Global Types */ - -/* Public Functions */ -//extern void PIOS_UDP_Init(void); -void PIOS_UDP_Init(void); -void PIOS_UDP_Close(void); -extern void PIOS_UDP_ChangeBaud(uint8_t usart, uint32_t baud); - -extern int32_t PIOS_UDP_RxBufferFree(uint8_t usart); -extern int32_t PIOS_UDP_RxBufferUsed(uint8_t usart); -extern int32_t PIOS_UDP_RxBufferGet(uint8_t usart); -extern int32_t PIOS_UDP_RxBufferPeek(uint8_t usart); -extern int32_t PIOS_UDP_RxBufferPut(uint8_t usart, uint8_t b); - -extern int32_t PIOS_UDP_TxBufferFree(uint8_t usart); -extern int32_t PIOS_UDP_TxBufferGet(uint8_t usart); -extern int32_t PIOS_UDP_TxBufferPutMoreNonBlocking(uint8_t usart, char *buffer, uint16_t len); -extern int32_t PIOS_UDP_TxBufferPutMore(uint8_t usart, char *buffer, uint16_t len); -extern int32_t PIOS_UDP_TxBufferPutNonBlocking(uint8_t usart, char b); -extern int32_t PIOS_UDP_TxBufferPut(uint8_t usart, char b); - -#endif /* PIOS_UDP_H */ +/** + ****************************************************************************** + * + * @file pios_usart.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief UDP functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_UDP_H +#define PIOS_UDP_H + + +/* Global Types */ + +/* Public Functions */ +//extern void PIOS_UDP_Init(void); +void PIOS_UDP_Init(void); +void PIOS_UDP_Close(void); +extern void PIOS_UDP_ChangeBaud(uint8_t usart, uint32_t baud); + +extern int32_t PIOS_UDP_RxBufferFree(uint8_t usart); +extern int32_t PIOS_UDP_RxBufferUsed(uint8_t usart); +extern int32_t PIOS_UDP_RxBufferGet(uint8_t usart); +extern int32_t PIOS_UDP_RxBufferPeek(uint8_t usart); +extern int32_t PIOS_UDP_RxBufferPut(uint8_t usart, uint8_t b); + +extern int32_t PIOS_UDP_TxBufferFree(uint8_t usart); +extern int32_t PIOS_UDP_TxBufferGet(uint8_t usart); +extern int32_t PIOS_UDP_TxBufferPutMoreNonBlocking(uint8_t usart, char *buffer, uint16_t len); +extern int32_t PIOS_UDP_TxBufferPutMore(uint8_t usart, char *buffer, uint16_t len); +extern int32_t PIOS_UDP_TxBufferPutNonBlocking(uint8_t usart, char b); +extern int32_t PIOS_UDP_TxBufferPut(uint8_t usart, char b); + +#endif /* PIOS_UDP_H */ diff --git a/flight/PiOS.win32/pios.h b/flight/PiOS.win32/pios.h index a4600cee5..590c6a4df 100644 --- a/flight/PiOS.win32/pios.h +++ b/flight/PiOS.win32/pios.h @@ -1,70 +1,70 @@ -/** - ****************************************************************************** - * - * @file pios.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main PiOS header. - * - Central header for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_H -#define PIOS_H - -/* PIOS Feature Selection */ -#include "pios_config_posix.h" -#include - -#if defined(PIOS_INCLUDE_FREERTOS) -/* FreeRTOS Includes */ -#include "FreeRTOS.h" -#include "task.h" -#include "queue.h" -#include "semphr.h" -#endif - -/* C Lib Includes */ -#include -#include -#include -#include -#include -#include - -/* Generic initcall infrastructure */ -#include "pios_initcall.h" - -/* PIOS Board Specific Device Configuration */ -#include "pios_board_posix.h" - -/* PIOS Hardware Includes (win32) */ -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#define NELEMENTS(x) (sizeof(x) / sizeof(*(x))) - -#endif /* PIOS_H */ +/** + ****************************************************************************** + * + * @file pios.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main PiOS header. + * - Central header for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_H +#define PIOS_H + +/* PIOS Feature Selection */ +#include "pios_config_posix.h" +#include + +#if defined(PIOS_INCLUDE_FREERTOS) +/* FreeRTOS Includes */ +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "semphr.h" +#endif + +/* C Lib Includes */ +#include +#include +#include +#include +#include +#include + +/* Generic initcall infrastructure */ +#include "pios_initcall.h" + +/* PIOS Board Specific Device Configuration */ +#include "pios_board_posix.h" + +/* PIOS Hardware Includes (win32) */ +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define NELEMENTS(x) (sizeof(x) / sizeof(*(x))) + +#endif /* PIOS_H */ diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/croutine.c b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/croutine.c index d6f116262..1ef663f93 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/croutine.c +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/croutine.c @@ -1,371 +1,371 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#include "FreeRTOS.h" -#include "task.h" -#include "croutine.h" - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - - -/* Lists for ready and blocked co-routines. --------------------*/ -static xList pxReadyCoRoutineLists[ configMAX_CO_ROUTINE_PRIORITIES ]; /*< Prioritised ready co-routines. */ -static xList xDelayedCoRoutineList1; /*< Delayed co-routines. */ -static xList xDelayedCoRoutineList2; /*< Delayed co-routines (two lists are used - one for delays that have overflowed the current tick count. */ -static xList * pxDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used. */ -static xList * pxOverflowDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used to hold co-routines that have overflowed the current tick count. */ -static xList xPendingReadyCoRoutineList; /*< Holds co-routines that have been readied by an external event. They cannot be added directly to the ready lists as the ready lists cannot be accessed by interrupts. */ - -/* Other file private variables. --------------------------------*/ -corCRCB * pxCurrentCoRoutine = NULL; -static unsigned portBASE_TYPE uxTopCoRoutineReadyPriority = 0; -static portTickType xCoRoutineTickCount = 0, xLastTickCount = 0, xPassedTicks = 0; - -/* The initial state of the co-routine when it is created. */ -#define corINITIAL_STATE ( 0 ) - -/* - * Place the co-routine represented by pxCRCB into the appropriate ready queue - * for the priority. It is inserted at the end of the list. - * - * This macro accesses the co-routine ready lists and therefore must not be - * used from within an ISR. - */ -#define prvAddCoRoutineToReadyQueue( pxCRCB ) \ -{ \ - if( pxCRCB->uxPriority > uxTopCoRoutineReadyPriority ) \ - { \ - uxTopCoRoutineReadyPriority = pxCRCB->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyCoRoutineLists[ pxCRCB->uxPriority ] ), &( pxCRCB->xGenericListItem ) ); \ -} - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first co-routine. - */ -static void prvInitialiseCoRoutineLists( void ); - -/* - * Co-routines that are readied by an interrupt cannot be placed directly into - * the ready lists (there is no mutual exclusion). Instead they are placed in - * in the pending ready list in order that they can later be moved to the ready - * list by the co-routine scheduler. - */ -static void prvCheckPendingReadyList( void ); - -/* - * Macro that looks at the list of co-routines that are currently delayed to - * see if any require waking. - * - * Co-routines are stored in the queue in the order of their wake time - - * meaning once one co-routine has been found whose timer has not expired - * we need not look any further down the list. - */ -static void prvCheckDelayedList( void ); - -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ) -{ -signed portBASE_TYPE xReturn; -corCRCB *pxCoRoutine; - - /* Allocate the memory that will store the co-routine control block. */ - pxCoRoutine = ( corCRCB * ) pvPortMalloc( sizeof( corCRCB ) ); - if( pxCoRoutine ) - { - /* If pxCurrentCoRoutine is NULL then this is the first co-routine to - be created and the co-routine data structures need initialising. */ - if( pxCurrentCoRoutine == NULL ) - { - pxCurrentCoRoutine = pxCoRoutine; - prvInitialiseCoRoutineLists(); - } - - /* Check the priority is within limits. */ - if( uxPriority >= configMAX_CO_ROUTINE_PRIORITIES ) - { - uxPriority = configMAX_CO_ROUTINE_PRIORITIES - 1; - } - - /* Fill out the co-routine control block from the function parameters. */ - pxCoRoutine->uxState = corINITIAL_STATE; - pxCoRoutine->uxPriority = uxPriority; - pxCoRoutine->uxIndex = uxIndex; - pxCoRoutine->pxCoRoutineFunction = pxCoRoutineCode; - - /* Initialise all the other co-routine control block parameters. */ - vListInitialiseItem( &( pxCoRoutine->xGenericListItem ) ); - vListInitialiseItem( &( pxCoRoutine->xEventListItem ) ); - - /* Set the co-routine control block as a link back from the xListItem. - This is so we can get back to the containing CRCB from a generic item - in a list. */ - listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xGenericListItem ), pxCoRoutine ); - listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xEventListItem ), pxCoRoutine ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxCoRoutine->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - - /* Now the co-routine has been initialised it can be added to the ready - list at the correct priority. */ - prvAddCoRoutineToReadyQueue( pxCoRoutine ); - - xReturn = pdPASS; - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ) -{ -portTickType xTimeToWake; - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xCoRoutineTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentCoRoutine->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xCoRoutineTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - } - - if( pxEventList ) - { - /* Also add the co-routine to an event list. If this is done then the - function must be called with interrupts disabled. */ - vListInsert( pxEventList, &( pxCurrentCoRoutine->xEventListItem ) ); - } -} -/*-----------------------------------------------------------*/ - -static void prvCheckPendingReadyList( void ) -{ - /* Are there any co-routines waiting to get moved to the ready list? These - are co-routines that have been readied by an ISR. The ISR cannot access - the ready lists itself. */ - while( !listLIST_IS_EMPTY( &xPendingReadyCoRoutineList ) ) - { - corCRCB *pxUnblockedCRCB; - - /* The pending ready list can be accessed by an ISR. */ - portDISABLE_INTERRUPTS(); - { - pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( (&xPendingReadyCoRoutineList) ); - vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); - } - portENABLE_INTERRUPTS(); - - vListRemove( &( pxUnblockedCRCB->xGenericListItem ) ); - prvAddCoRoutineToReadyQueue( pxUnblockedCRCB ); - } -} -/*-----------------------------------------------------------*/ - -static void prvCheckDelayedList( void ) -{ -corCRCB *pxCRCB; - - xPassedTicks = xTaskGetTickCount() - xLastTickCount; - while( xPassedTicks ) - { - xCoRoutineTickCount++; - xPassedTicks--; - - /* If the tick count has overflowed we need to swap the ready lists. */ - if( xCoRoutineTickCount == 0 ) - { - xList * pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. If there are - any items in pxDelayedCoRoutineList here then there is an error! */ - pxTemp = pxDelayedCoRoutineList; - pxDelayedCoRoutineList = pxOverflowDelayedCoRoutineList; - pxOverflowDelayedCoRoutineList = pxTemp; - } - - /* See if this tick has made a timeout expire. */ - while( ( pxCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedCoRoutineList ) ) != NULL ) - { - if( xCoRoutineTickCount < listGET_LIST_ITEM_VALUE( &( pxCRCB->xGenericListItem ) ) ) - { - /* Timeout not yet expired. */ - break; - } - - portDISABLE_INTERRUPTS(); - { - /* The event could have occurred just before this critical - section. If this is the case then the generic list item will - have been moved to the pending ready list and the following - line is still valid. Also the pvContainer parameter will have - been set to NULL so the following lines are also valid. */ - vListRemove( &( pxCRCB->xGenericListItem ) ); - - /* Is the co-routine waiting on an event also? */ - if( pxCRCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxCRCB->xEventListItem ) ); - } - } - portENABLE_INTERRUPTS(); - - prvAddCoRoutineToReadyQueue( pxCRCB ); - } - } - - xLastTickCount = xCoRoutineTickCount; -} -/*-----------------------------------------------------------*/ - -void vCoRoutineSchedule( void ) -{ - /* See if any co-routines readied by events need moving to the ready lists. */ - prvCheckPendingReadyList(); - - /* See if any delayed co-routines have timed out. */ - prvCheckDelayedList(); - - /* Find the highest priority queue that contains ready co-routines. */ - while( listLIST_IS_EMPTY( &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ) ) - { - if( uxTopCoRoutineReadyPriority == 0 ) - { - /* No more co-routines to check. */ - return; - } - --uxTopCoRoutineReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the co-routines - of the same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentCoRoutine, &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ); - - /* Call the co-routine. */ - ( pxCurrentCoRoutine->pxCoRoutineFunction )( pxCurrentCoRoutine, pxCurrentCoRoutine->uxIndex ); - - return; -} -/*-----------------------------------------------------------*/ - -static void prvInitialiseCoRoutineLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = 0; uxPriority < configMAX_CO_ROUTINE_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyCoRoutineLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedCoRoutineList1 ); - vListInitialise( ( xList * ) &xDelayedCoRoutineList2 ); - vListInitialise( ( xList * ) &xPendingReadyCoRoutineList ); - - /* Start with pxDelayedCoRoutineList using list1 and the - pxOverflowDelayedCoRoutineList using list2. */ - pxDelayedCoRoutineList = &xDelayedCoRoutineList1; - pxOverflowDelayedCoRoutineList = &xDelayedCoRoutineList2; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ) -{ -corCRCB *pxUnblockedCRCB; -signed portBASE_TYPE xReturn; - - /* This function is called from within an interrupt. It can only access - event lists and the pending ready list. */ - pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); - vListInsertEnd( ( xList * ) &( xPendingReadyCoRoutineList ), &( pxUnblockedCRCB->xEventListItem ) ); - - if( pxUnblockedCRCB->uxPriority >= pxCurrentCoRoutine->uxPriority ) - { - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#include "FreeRTOS.h" +#include "task.h" +#include "croutine.h" + +/* + * Some kernel aware debuggers require data to be viewed to be global, rather + * than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + + +/* Lists for ready and blocked co-routines. --------------------*/ +static xList pxReadyCoRoutineLists[ configMAX_CO_ROUTINE_PRIORITIES ]; /*< Prioritised ready co-routines. */ +static xList xDelayedCoRoutineList1; /*< Delayed co-routines. */ +static xList xDelayedCoRoutineList2; /*< Delayed co-routines (two lists are used - one for delays that have overflowed the current tick count. */ +static xList * pxDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used. */ +static xList * pxOverflowDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used to hold co-routines that have overflowed the current tick count. */ +static xList xPendingReadyCoRoutineList; /*< Holds co-routines that have been readied by an external event. They cannot be added directly to the ready lists as the ready lists cannot be accessed by interrupts. */ + +/* Other file private variables. --------------------------------*/ +corCRCB * pxCurrentCoRoutine = NULL; +static unsigned portBASE_TYPE uxTopCoRoutineReadyPriority = 0; +static portTickType xCoRoutineTickCount = 0, xLastTickCount = 0, xPassedTicks = 0; + +/* The initial state of the co-routine when it is created. */ +#define corINITIAL_STATE ( 0 ) + +/* + * Place the co-routine represented by pxCRCB into the appropriate ready queue + * for the priority. It is inserted at the end of the list. + * + * This macro accesses the co-routine ready lists and therefore must not be + * used from within an ISR. + */ +#define prvAddCoRoutineToReadyQueue( pxCRCB ) \ +{ \ + if( pxCRCB->uxPriority > uxTopCoRoutineReadyPriority ) \ + { \ + uxTopCoRoutineReadyPriority = pxCRCB->uxPriority; \ + } \ + vListInsertEnd( ( xList * ) &( pxReadyCoRoutineLists[ pxCRCB->uxPriority ] ), &( pxCRCB->xGenericListItem ) ); \ +} + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first co-routine. + */ +static void prvInitialiseCoRoutineLists( void ); + +/* + * Co-routines that are readied by an interrupt cannot be placed directly into + * the ready lists (there is no mutual exclusion). Instead they are placed in + * in the pending ready list in order that they can later be moved to the ready + * list by the co-routine scheduler. + */ +static void prvCheckPendingReadyList( void ); + +/* + * Macro that looks at the list of co-routines that are currently delayed to + * see if any require waking. + * + * Co-routines are stored in the queue in the order of their wake time - + * meaning once one co-routine has been found whose timer has not expired + * we need not look any further down the list. + */ +static void prvCheckDelayedList( void ); + +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ) +{ +signed portBASE_TYPE xReturn; +corCRCB *pxCoRoutine; + + /* Allocate the memory that will store the co-routine control block. */ + pxCoRoutine = ( corCRCB * ) pvPortMalloc( sizeof( corCRCB ) ); + if( pxCoRoutine ) + { + /* If pxCurrentCoRoutine is NULL then this is the first co-routine to + be created and the co-routine data structures need initialising. */ + if( pxCurrentCoRoutine == NULL ) + { + pxCurrentCoRoutine = pxCoRoutine; + prvInitialiseCoRoutineLists(); + } + + /* Check the priority is within limits. */ + if( uxPriority >= configMAX_CO_ROUTINE_PRIORITIES ) + { + uxPriority = configMAX_CO_ROUTINE_PRIORITIES - 1; + } + + /* Fill out the co-routine control block from the function parameters. */ + pxCoRoutine->uxState = corINITIAL_STATE; + pxCoRoutine->uxPriority = uxPriority; + pxCoRoutine->uxIndex = uxIndex; + pxCoRoutine->pxCoRoutineFunction = pxCoRoutineCode; + + /* Initialise all the other co-routine control block parameters. */ + vListInitialiseItem( &( pxCoRoutine->xGenericListItem ) ); + vListInitialiseItem( &( pxCoRoutine->xEventListItem ) ); + + /* Set the co-routine control block as a link back from the xListItem. + This is so we can get back to the containing CRCB from a generic item + in a list. */ + listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xGenericListItem ), pxCoRoutine ); + listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xEventListItem ), pxCoRoutine ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxCoRoutine->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); + + /* Now the co-routine has been initialised it can be added to the ready + list at the correct priority. */ + prvAddCoRoutineToReadyQueue( pxCoRoutine ); + + xReturn = pdPASS; + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ) +{ +portTickType xTimeToWake; + + /* Calculate the time to wake - this may overflow but this is + not a problem. */ + xTimeToWake = xCoRoutineTickCount + xTicksToDelay; + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentCoRoutine->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xCoRoutineTickCount ) + { + /* Wake time has overflowed. Place this item in the + overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the + current block list. */ + vListInsert( ( xList * ) pxDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + } + + if( pxEventList ) + { + /* Also add the co-routine to an event list. If this is done then the + function must be called with interrupts disabled. */ + vListInsert( pxEventList, &( pxCurrentCoRoutine->xEventListItem ) ); + } +} +/*-----------------------------------------------------------*/ + +static void prvCheckPendingReadyList( void ) +{ + /* Are there any co-routines waiting to get moved to the ready list? These + are co-routines that have been readied by an ISR. The ISR cannot access + the ready lists itself. */ + while( !listLIST_IS_EMPTY( &xPendingReadyCoRoutineList ) ) + { + corCRCB *pxUnblockedCRCB; + + /* The pending ready list can be accessed by an ISR. */ + portDISABLE_INTERRUPTS(); + { + pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( (&xPendingReadyCoRoutineList) ); + vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); + } + portENABLE_INTERRUPTS(); + + vListRemove( &( pxUnblockedCRCB->xGenericListItem ) ); + prvAddCoRoutineToReadyQueue( pxUnblockedCRCB ); + } +} +/*-----------------------------------------------------------*/ + +static void prvCheckDelayedList( void ) +{ +corCRCB *pxCRCB; + + xPassedTicks = xTaskGetTickCount() - xLastTickCount; + while( xPassedTicks ) + { + xCoRoutineTickCount++; + xPassedTicks--; + + /* If the tick count has overflowed we need to swap the ready lists. */ + if( xCoRoutineTickCount == 0 ) + { + xList * pxTemp; + + /* Tick count has overflowed so we need to swap the delay lists. If there are + any items in pxDelayedCoRoutineList here then there is an error! */ + pxTemp = pxDelayedCoRoutineList; + pxDelayedCoRoutineList = pxOverflowDelayedCoRoutineList; + pxOverflowDelayedCoRoutineList = pxTemp; + } + + /* See if this tick has made a timeout expire. */ + while( ( pxCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedCoRoutineList ) ) != NULL ) + { + if( xCoRoutineTickCount < listGET_LIST_ITEM_VALUE( &( pxCRCB->xGenericListItem ) ) ) + { + /* Timeout not yet expired. */ + break; + } + + portDISABLE_INTERRUPTS(); + { + /* The event could have occurred just before this critical + section. If this is the case then the generic list item will + have been moved to the pending ready list and the following + line is still valid. Also the pvContainer parameter will have + been set to NULL so the following lines are also valid. */ + vListRemove( &( pxCRCB->xGenericListItem ) ); + + /* Is the co-routine waiting on an event also? */ + if( pxCRCB->xEventListItem.pvContainer ) + { + vListRemove( &( pxCRCB->xEventListItem ) ); + } + } + portENABLE_INTERRUPTS(); + + prvAddCoRoutineToReadyQueue( pxCRCB ); + } + } + + xLastTickCount = xCoRoutineTickCount; +} +/*-----------------------------------------------------------*/ + +void vCoRoutineSchedule( void ) +{ + /* See if any co-routines readied by events need moving to the ready lists. */ + prvCheckPendingReadyList(); + + /* See if any delayed co-routines have timed out. */ + prvCheckDelayedList(); + + /* Find the highest priority queue that contains ready co-routines. */ + while( listLIST_IS_EMPTY( &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ) ) + { + if( uxTopCoRoutineReadyPriority == 0 ) + { + /* No more co-routines to check. */ + return; + } + --uxTopCoRoutineReadyPriority; + } + + /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the co-routines + of the same priority get an equal share of the processor time. */ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentCoRoutine, &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ); + + /* Call the co-routine. */ + ( pxCurrentCoRoutine->pxCoRoutineFunction )( pxCurrentCoRoutine, pxCurrentCoRoutine->uxIndex ); + + return; +} +/*-----------------------------------------------------------*/ + +static void prvInitialiseCoRoutineLists( void ) +{ +unsigned portBASE_TYPE uxPriority; + + for( uxPriority = 0; uxPriority < configMAX_CO_ROUTINE_PRIORITIES; uxPriority++ ) + { + vListInitialise( ( xList * ) &( pxReadyCoRoutineLists[ uxPriority ] ) ); + } + + vListInitialise( ( xList * ) &xDelayedCoRoutineList1 ); + vListInitialise( ( xList * ) &xDelayedCoRoutineList2 ); + vListInitialise( ( xList * ) &xPendingReadyCoRoutineList ); + + /* Start with pxDelayedCoRoutineList using list1 and the + pxOverflowDelayedCoRoutineList using list2. */ + pxDelayedCoRoutineList = &xDelayedCoRoutineList1; + pxOverflowDelayedCoRoutineList = &xDelayedCoRoutineList2; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ) +{ +corCRCB *pxUnblockedCRCB; +signed portBASE_TYPE xReturn; + + /* This function is called from within an interrupt. It can only access + event lists and the pending ready list. */ + pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); + vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); + vListInsertEnd( ( xList * ) &( xPendingReadyCoRoutineList ), &( pxUnblockedCRCB->xEventListItem ) ); + + if( pxUnblockedCRCB->uxPriority >= pxCurrentCoRoutine->uxPriority ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/FreeRTOS.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/FreeRTOS.h index ee02592ae..13dbb70e5 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/FreeRTOS.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/FreeRTOS.h @@ -1,420 +1,420 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef INC_FREERTOS_H -#define INC_FREERTOS_H - - -/* - * Include the generic headers required for the FreeRTOS port being used. - */ -#include - -/* Basic FreeRTOS definitions. */ -#include "projdefs.h" - -/* Application specific configuration options. */ -#include "FreeRTOSConfig.h" - -/* Definitions specific to the port being used. */ -#include "portable.h" - - -/* Defines the prototype to which the application task hook function must -conform. */ -typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); - - - - - -/* - * Check all the required application specific macros have been defined. - * These macros are application specific and (as downloaded) are defined - * within FreeRTOSConfig.h. - */ - -#ifndef configUSE_PREEMPTION - #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_IDLE_HOOK - #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_TICK_HOOK - #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_CO_ROUTINES - #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskPrioritySet - #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_uxTaskPriorityGet - #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelete - #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskCleanUpResources - #error Missing definition: INCLUDE_vTaskCleanUpResources should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskSuspend - #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelayUntil - #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelay - #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_16_BIT_TICKS - #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_APPLICATION_TASK_TAG - #define configUSE_APPLICATION_TASK_TAG 0 -#endif - -#ifndef INCLUDE_uxTaskGetStackHighWaterMark - #define INCLUDE_uxTaskGetStackHighWaterMark 0 -#endif - -#ifndef configUSE_RECURSIVE_MUTEXES - #define configUSE_RECURSIVE_MUTEXES 0 -#endif - -#ifndef configUSE_MUTEXES - #define configUSE_MUTEXES 0 -#endif - -#ifndef configUSE_COUNTING_SEMAPHORES - #define configUSE_COUNTING_SEMAPHORES 0 -#endif - -#ifndef configUSE_ALTERNATIVE_API - #define configUSE_ALTERNATIVE_API 0 -#endif - -#ifndef portCRITICAL_NESTING_IN_TCB - #define portCRITICAL_NESTING_IN_TCB 0 -#endif - -#ifndef configMAX_TASK_NAME_LEN - #define configMAX_TASK_NAME_LEN 16 -#endif - -#ifndef configIDLE_SHOULD_YIELD - #define configIDLE_SHOULD_YIELD 1 -#endif - -#if configMAX_TASK_NAME_LEN < 1 - #undef configMAX_TASK_NAME_LEN - #define configMAX_TASK_NAME_LEN 1 -#endif - -#ifndef INCLUDE_xTaskResumeFromISR - #define INCLUDE_xTaskResumeFromISR 1 -#endif - -#ifndef INCLUDE_xTaskGetSchedulerState - #define INCLUDE_xTaskGetSchedulerState 0 -#endif - -#if ( configUSE_MUTEXES == 1 ) - /* xTaskGetCurrentTaskHandle is used by the priority inheritance mechanism - within the mutex implementation so must be available if mutexes are used. */ - #undef INCLUDE_xTaskGetCurrentTaskHandle - #define INCLUDE_xTaskGetCurrentTaskHandle 1 -#else - #ifndef INCLUDE_xTaskGetCurrentTaskHandle - #define INCLUDE_xTaskGetCurrentTaskHandle 0 - #endif -#endif - - -#ifndef portSET_INTERRUPT_MASK_FROM_ISR - #define portSET_INTERRUPT_MASK_FROM_ISR() 0 -#endif - -#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR - #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue -#endif - - -#ifndef configQUEUE_REGISTRY_SIZE - #define configQUEUE_REGISTRY_SIZE 0 -#endif - -#if configQUEUE_REGISTRY_SIZE < 1 - #define configQUEUE_REGISTRY_SIZE 0 - #define vQueueAddToRegistry( xQueue, pcName ) - #define vQueueUnregisterQueue( xQueue ) -#endif - - -/* Remove any unused trace macros. */ -#ifndef traceSTART - /* Used to perform any necessary initialisation - for example, open a file - into which trace is to be written. */ - #define traceSTART() -#endif - -#ifndef traceEND - /* Use to close a trace, for example close a file into which trace has been - written. */ - #define traceEND() -#endif - -#ifndef traceTASK_SWITCHED_IN - /* Called after a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the selected task. */ - #define traceTASK_SWITCHED_IN() -#endif - -#ifndef traceTASK_SWITCHED_OUT - /* Called before a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the task being switched out. */ - #define traceTASK_SWITCHED_OUT() -#endif - -#ifndef traceBLOCKING_ON_QUEUE_RECEIVE - /* Task is about to block because it cannot read from a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the read was attempted. pxCurrentTCB points to the TCB of the - task that attempted the read. */ - #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceBLOCKING_ON_QUEUE_SEND - /* Task is about to block because it cannot write to a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the write was attempted. pxCurrentTCB points to the TCB of the - task that attempted the write. */ - #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) -#endif - -#ifndef configCHECK_FOR_STACK_OVERFLOW - #define configCHECK_FOR_STACK_OVERFLOW 0 -#endif - -/* The following event macros are embedded in the kernel API calls. */ - -#ifndef traceQUEUE_CREATE - #define traceQUEUE_CREATE( pxNewQueue ) -#endif - -#ifndef traceQUEUE_CREATE_FAILED - #define traceQUEUE_CREATE_FAILED() -#endif - -#ifndef traceCREATE_MUTEX - #define traceCREATE_MUTEX( pxNewQueue ) -#endif - -#ifndef traceCREATE_MUTEX_FAILED - #define traceCREATE_MUTEX_FAILED() -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE - #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED - #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) -#endif - -#ifndef traceTAKE_MUTEX_RECURSIVE - #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE - #define traceCREATE_COUNTING_SEMAPHORE() -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED - #define traceCREATE_COUNTING_SEMAPHORE_FAILED() -#endif - -#ifndef traceQUEUE_SEND - #define traceQUEUE_SEND( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FAILED - #define traceQUEUE_SEND_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE - #define traceQUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceQUEUE_PEEK - #define traceQUEUE_PEEK( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FAILED - #define traceQUEUE_RECEIVE_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR - #define traceQUEUE_SEND_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR_FAILED - #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR - #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED - #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_DELETE - #define traceQUEUE_DELETE( pxQueue ) -#endif - -#ifndef traceTASK_CREATE - #define traceTASK_CREATE( pxNewTCB ) -#endif - -#ifndef traceTASK_CREATE_FAILED - #define traceTASK_CREATE_FAILED( pxNewTCB ) -#endif - -#ifndef traceTASK_DELETE - #define traceTASK_DELETE( pxTaskToDelete ) -#endif - -#ifndef traceTASK_DELAY_UNTIL - #define traceTASK_DELAY_UNTIL() -#endif - -#ifndef traceTASK_DELAY - #define traceTASK_DELAY() -#endif - -#ifndef traceTASK_PRIORITY_SET - #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) -#endif - -#ifndef traceTASK_SUSPEND - #define traceTASK_SUSPEND( pxTaskToSuspend ) -#endif - -#ifndef traceTASK_RESUME - #define traceTASK_RESUME( pxTaskToResume ) -#endif - -#ifndef traceTASK_RESUME_FROM_ISR - #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) -#endif - -#ifndef traceTASK_INCREMENT_TICK - #define traceTASK_INCREMENT_TICK( xTickCount ) -#endif - -#ifndef configGENERATE_RUN_TIME_STATS - #define configGENERATE_RUN_TIME_STATS 0 -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. - #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ - - #ifndef portGET_RUN_TIME_COUNTER_VALUE - #error If configGENERATE_RUN_TIME_STATS is defined then portGET_RUN_TIME_COUNTER_VALUE must also be defined. portGET_RUN_TIME_COUNTER_VALUE should evaluate to the counter value of the timer/counter peripheral used as the run time counter time base. - #endif /* portGET_RUN_TIME_COUNTER_VALUE */ - -#endif /* configGENERATE_RUN_TIME_STATS */ - -#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() -#endif - -#ifndef configUSE_MALLOC_FAILED_HOOK - #define configUSE_MALLOC_FAILED_HOOK 0 -#endif - -#ifndef portPRIVILEGE_BIT - #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) -#endif - -#ifndef portYIELD_WITHIN_API - #define portYIELD_WITHIN_API portYIELD -#endif - -#ifndef pvPortMallocAligned - #define pvPortMallocAligned( x, puxStackBuffer ) ( ( puxStackBuffer == NULL ) ? ( pvPortMalloc( x ) ) : ( puxStackBuffer ) ) -#endif - -#ifndef vPortFreeAligned - #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) -#endif - -#endif /* INC_FREERTOS_H */ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef INC_FREERTOS_H +#define INC_FREERTOS_H + + +/* + * Include the generic headers required for the FreeRTOS port being used. + */ +#include + +/* Basic FreeRTOS definitions. */ +#include "projdefs.h" + +/* Application specific configuration options. */ +#include "FreeRTOSConfig.h" + +/* Definitions specific to the port being used. */ +#include "portable.h" + + +/* Defines the prototype to which the application task hook function must +conform. */ +typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); + + + + + +/* + * Check all the required application specific macros have been defined. + * These macros are application specific and (as downloaded) are defined + * within FreeRTOSConfig.h. + */ + +#ifndef configUSE_PREEMPTION + #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_IDLE_HOOK + #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_TICK_HOOK + #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_CO_ROUTINES + #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskPrioritySet + #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_uxTaskPriorityGet + #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelete + #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskCleanUpResources + #error Missing definition: INCLUDE_vTaskCleanUpResources should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskSuspend + #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelayUntil + #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelay + #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_16_BIT_TICKS + #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_APPLICATION_TASK_TAG + #define configUSE_APPLICATION_TASK_TAG 0 +#endif + +#ifndef INCLUDE_uxTaskGetStackHighWaterMark + #define INCLUDE_uxTaskGetStackHighWaterMark 0 +#endif + +#ifndef configUSE_RECURSIVE_MUTEXES + #define configUSE_RECURSIVE_MUTEXES 0 +#endif + +#ifndef configUSE_MUTEXES + #define configUSE_MUTEXES 0 +#endif + +#ifndef configUSE_COUNTING_SEMAPHORES + #define configUSE_COUNTING_SEMAPHORES 0 +#endif + +#ifndef configUSE_ALTERNATIVE_API + #define configUSE_ALTERNATIVE_API 0 +#endif + +#ifndef portCRITICAL_NESTING_IN_TCB + #define portCRITICAL_NESTING_IN_TCB 0 +#endif + +#ifndef configMAX_TASK_NAME_LEN + #define configMAX_TASK_NAME_LEN 16 +#endif + +#ifndef configIDLE_SHOULD_YIELD + #define configIDLE_SHOULD_YIELD 1 +#endif + +#if configMAX_TASK_NAME_LEN < 1 + #undef configMAX_TASK_NAME_LEN + #define configMAX_TASK_NAME_LEN 1 +#endif + +#ifndef INCLUDE_xTaskResumeFromISR + #define INCLUDE_xTaskResumeFromISR 1 +#endif + +#ifndef INCLUDE_xTaskGetSchedulerState + #define INCLUDE_xTaskGetSchedulerState 0 +#endif + +#if ( configUSE_MUTEXES == 1 ) + /* xTaskGetCurrentTaskHandle is used by the priority inheritance mechanism + within the mutex implementation so must be available if mutexes are used. */ + #undef INCLUDE_xTaskGetCurrentTaskHandle + #define INCLUDE_xTaskGetCurrentTaskHandle 1 +#else + #ifndef INCLUDE_xTaskGetCurrentTaskHandle + #define INCLUDE_xTaskGetCurrentTaskHandle 0 + #endif +#endif + + +#ifndef portSET_INTERRUPT_MASK_FROM_ISR + #define portSET_INTERRUPT_MASK_FROM_ISR() 0 +#endif + +#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR + #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue +#endif + + +#ifndef configQUEUE_REGISTRY_SIZE + #define configQUEUE_REGISTRY_SIZE 0 +#endif + +#if configQUEUE_REGISTRY_SIZE < 1 + #define configQUEUE_REGISTRY_SIZE 0 + #define vQueueAddToRegistry( xQueue, pcName ) + #define vQueueUnregisterQueue( xQueue ) +#endif + + +/* Remove any unused trace macros. */ +#ifndef traceSTART + /* Used to perform any necessary initialisation - for example, open a file + into which trace is to be written. */ + #define traceSTART() +#endif + +#ifndef traceEND + /* Use to close a trace, for example close a file into which trace has been + written. */ + #define traceEND() +#endif + +#ifndef traceTASK_SWITCHED_IN + /* Called after a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the selected task. */ + #define traceTASK_SWITCHED_IN() +#endif + +#ifndef traceTASK_SWITCHED_OUT + /* Called before a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the task being switched out. */ + #define traceTASK_SWITCHED_OUT() +#endif + +#ifndef traceBLOCKING_ON_QUEUE_RECEIVE + /* Task is about to block because it cannot read from a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the read was attempted. pxCurrentTCB points to the TCB of the + task that attempted the read. */ + #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_SEND + /* Task is about to block because it cannot write to a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the write was attempted. pxCurrentTCB points to the TCB of the + task that attempted the write. */ + #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) +#endif + +#ifndef configCHECK_FOR_STACK_OVERFLOW + #define configCHECK_FOR_STACK_OVERFLOW 0 +#endif + +/* The following event macros are embedded in the kernel API calls. */ + +#ifndef traceQUEUE_CREATE + #define traceQUEUE_CREATE( pxNewQueue ) +#endif + +#ifndef traceQUEUE_CREATE_FAILED + #define traceQUEUE_CREATE_FAILED() +#endif + +#ifndef traceCREATE_MUTEX + #define traceCREATE_MUTEX( pxNewQueue ) +#endif + +#ifndef traceCREATE_MUTEX_FAILED + #define traceCREATE_MUTEX_FAILED() +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE + #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED + #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE + #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE + #define traceCREATE_COUNTING_SEMAPHORE() +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED + #define traceCREATE_COUNTING_SEMAPHORE_FAILED() +#endif + +#ifndef traceQUEUE_SEND + #define traceQUEUE_SEND( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FAILED + #define traceQUEUE_SEND_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE + #define traceQUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK + #define traceQUEUE_PEEK( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FAILED + #define traceQUEUE_RECEIVE_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR + #define traceQUEUE_SEND_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR_FAILED + #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR + #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED + #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_DELETE + #define traceQUEUE_DELETE( pxQueue ) +#endif + +#ifndef traceTASK_CREATE + #define traceTASK_CREATE( pxNewTCB ) +#endif + +#ifndef traceTASK_CREATE_FAILED + #define traceTASK_CREATE_FAILED( pxNewTCB ) +#endif + +#ifndef traceTASK_DELETE + #define traceTASK_DELETE( pxTaskToDelete ) +#endif + +#ifndef traceTASK_DELAY_UNTIL + #define traceTASK_DELAY_UNTIL() +#endif + +#ifndef traceTASK_DELAY + #define traceTASK_DELAY() +#endif + +#ifndef traceTASK_PRIORITY_SET + #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) +#endif + +#ifndef traceTASK_SUSPEND + #define traceTASK_SUSPEND( pxTaskToSuspend ) +#endif + +#ifndef traceTASK_RESUME + #define traceTASK_RESUME( pxTaskToResume ) +#endif + +#ifndef traceTASK_RESUME_FROM_ISR + #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) +#endif + +#ifndef traceTASK_INCREMENT_TICK + #define traceTASK_INCREMENT_TICK( xTickCount ) +#endif + +#ifndef configGENERATE_RUN_TIME_STATS + #define configGENERATE_RUN_TIME_STATS 0 +#endif + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. + #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ + + #ifndef portGET_RUN_TIME_COUNTER_VALUE + #error If configGENERATE_RUN_TIME_STATS is defined then portGET_RUN_TIME_COUNTER_VALUE must also be defined. portGET_RUN_TIME_COUNTER_VALUE should evaluate to the counter value of the timer/counter peripheral used as the run time counter time base. + #endif /* portGET_RUN_TIME_COUNTER_VALUE */ + +#endif /* configGENERATE_RUN_TIME_STATS */ + +#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() +#endif + +#ifndef configUSE_MALLOC_FAILED_HOOK + #define configUSE_MALLOC_FAILED_HOOK 0 +#endif + +#ifndef portPRIVILEGE_BIT + #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) +#endif + +#ifndef portYIELD_WITHIN_API + #define portYIELD_WITHIN_API portYIELD +#endif + +#ifndef pvPortMallocAligned + #define pvPortMallocAligned( x, puxStackBuffer ) ( ( puxStackBuffer == NULL ) ? ( pvPortMalloc( x ) ) : ( puxStackBuffer ) ) +#endif + +#ifndef vPortFreeAligned + #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) +#endif + +#endif /* INC_FREERTOS_H */ + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/StackMacros.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/StackMacros.h index a7514d790..baeb7bafa 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/StackMacros.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/StackMacros.h @@ -1,173 +1,173 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef STACK_MACROS_H -#define STACK_MACROS_H - -/* - * Call the stack overflow hook function if the stack of the task being swapped - * out is currently overflowed, or looks like it might have overflowed in the - * past. - * - * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check - * the current stack state only - comparing the current top of stack value to - * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 - * will also cause the last few stack bytes to be checked to ensure the value - * to which the bytes were set when the task was created have not been - * overwritten. Note this second test does not guarantee that an overflowed - * stack will always be recognised. - */ - -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) - - /* FreeRTOSConfig.h is not set to check for stack overflows. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) - - /* FreeRTOSConfig.h is only set to use the first method of - overflow checking. */ - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ - \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ - \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ - char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#endif /* STACK_MACROS_H */ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef STACK_MACROS_H +#define STACK_MACROS_H + +/* + * Call the stack overflow hook function if the stack of the task being swapped + * out is currently overflowed, or looks like it might have overflowed in the + * past. + * + * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check + * the current stack state only - comparing the current top of stack value to + * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 + * will also cause the last few stack bytes to be checked to ensure the value + * to which the bytes were set when the task was created have not been + * overwritten. Note this second test does not guarantee that an overflowed + * stack will always be recognised. + */ + +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) + + /* FreeRTOSConfig.h is not set to check for stack overflows. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) + + /* FreeRTOSConfig.h is only set to use the first method of + overflow checking. */ + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ + char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#endif /* STACK_MACROS_H */ + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/croutine.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/croutine.h index c189a1e87..32f19198f 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/croutine.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/croutine.h @@ -1,749 +1,749 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include croutine.h" -#endif - - - - -#ifndef CO_ROUTINE_H -#define CO_ROUTINE_H - -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* Used to hide the implementation of the co-routine control block. The -control block structure however has to be included in the header due to -the macro implementation of the co-routine functionality. */ -typedef void * xCoRoutineHandle; - -/* Defines the prototype to which co-routine functions must conform. */ -typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); - -typedef struct corCoRoutineControlBlock -{ - crCOROUTINE_CODE pxCoRoutineFunction; - xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ - unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ - unsigned short uxState; /*< Used internally by the co-routine implementation. */ -} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ - -/** - * croutine. h - *
- portBASE_TYPE xCoRoutineCreate(
-                                 crCOROUTINE_CODE pxCoRoutineCode,
-                                 unsigned portBASE_TYPE uxPriority,
-                                 unsigned portBASE_TYPE uxIndex
-                               );
- * - * Create a new co-routine and add it to the list of co-routines that are - * ready to run. - * - * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine - * functions require special syntax - see the co-routine section of the WEB - * documentation for more information. - * - * @param uxPriority The priority with respect to other co-routines at which - * the co-routine will run. - * - * @param uxIndex Used to distinguish between different co-routines that - * execute the same function. See the example below and the co-routine section - * of the WEB documentation for further information. - * - * @return pdPASS if the co-routine was successfully created and added to a ready - * list, otherwise an error code defined with ProjDefs.h. - * - * Example usage: -
- // Co-routine to be created.
- void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- static const char cLedToFlash[ 2 ] = { 5, 6 };
- static const portTickType xTimeToDelay[ 2 ] = { 200, 400 };
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // This co-routine just delays for a fixed period, then toggles
-         // an LED.  Two co-routines are created using this function, so
-         // the uxIndex parameter is used to tell the co-routine which
-         // LED to flash and how long to delay.  This assumes xQueue has
-         // already been created.
-         vParTestToggleLED( cLedToFlash[ uxIndex ] );
-         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
-
- // Function that creates two co-routines.
- void vOtherFunction( void )
- {
- unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-		
-     // Create two co-routines at priority 0.  The first is given index 0
-     // so (from the code above) toggles LED 5 every 200 ticks.  The second
-     // is given index 1 so toggles LED 6 every 400 ticks.
-     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
-     {
-         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
-     }
- }
-   
- * \defgroup xCoRoutineCreate xCoRoutineCreate - * \ingroup Tasks - */ -signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); - - -/** - * croutine. h - *
- void vCoRoutineSchedule( void );
- * - * Run a co-routine. - * - * vCoRoutineSchedule() executes the highest priority co-routine that is able - * to run. The co-routine will execute until it either blocks, yields or is - * preempted by a task. Co-routines execute cooperatively so one - * co-routine cannot be preempted by another, but can be preempted by a task. - * - * If an application comprises of both tasks and co-routines then - * vCoRoutineSchedule should be called from the idle task (in an idle task - * hook). - * - * Example usage: -
- // This idle task hook will schedule a co-routine each time it is called.
- // The rest of the idle task will execute between co-routine calls.
- void vApplicationIdleHook( void )
- {
-	vCoRoutineSchedule();
- }
-
- // Alternatively, if you do not require any other part of the idle task to
- // execute, the idle task hook can call vCoRoutineScheduler() within an
- // infinite loop.
- void vApplicationIdleHook( void )
- {
-    for( ;; )
-    {
-        vCoRoutineSchedule();
-    }
- }
- 
- * \defgroup vCoRoutineSchedule vCoRoutineSchedule - * \ingroup Tasks - */ -void vCoRoutineSchedule( void ); - -/** - * croutine. h - *
- crSTART( xCoRoutineHandle xHandle );
- * - * This macro MUST always be called at the start of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crSTART( pxCRCB ) switch( ( ( corCRCB * )pxCRCB )->uxState ) { case 0: - -/** - * croutine. h - *
- crEND();
- * - * This macro MUST always be called at the end of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crEND() } - -/* - * These macros are intended for internal use by the co-routine implementation - * only. The macros should not be used directly by application writers. - */ -#define crSET_STATE0( xHandle ) ( ( corCRCB * )xHandle)->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): -#define crSET_STATE1( xHandle ) ( ( corCRCB * )xHandle)->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): - -/** - * croutine. h - *
- crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
- * - * Delay a co-routine for a fixed period of time. - * - * crDELAY can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * @param xHandle The handle of the co-routine to delay. This is the xHandle - * parameter of the co-routine function. - * - * @param xTickToDelay The number of ticks that the co-routine should delay - * for. The actual amount of time this equates to is defined by - * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS - * can be used to convert ticks to milliseconds. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- // We are to delay for 200ms.
- static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-        // Delay for 200ms.
-        crDELAY( xHandle, xDelayTime );
-
-        // Do something here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crDELAY crDELAY - * \ingroup Tasks - */ -#define crDELAY( xHandle, xTicksToDelay ) \ - if( xTicksToDelay > 0 ) \ - { \ - vCoRoutineAddToDelayedList( xTicksToDelay, NULL ); \ - } \ - crSET_STATE0( xHandle ); - -/** - *
- crQUEUE_SEND(
-                  xCoRoutineHandle xHandle,
-                  xQueueHandle pxQueue,
-                  void *pvItemToQueue,
-                  portTickType xTicksToWait,
-                  portBASE_TYPE *pxResult
-             )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_SEND can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue on which the data will be posted. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvItemToQueue A pointer to the data being posted onto the queue. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied from pvItemToQueue into the queue - * itself. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for space to become available on the queue, should space not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example - * below). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully posted onto the queue, otherwise it will be set to an - * error defined within ProjDefs.h. - * - * Example usage: -
- // Co-routine function that blocks for a fixed period then posts a number onto
- // a queue.
- static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xNumberToPost = 0;
- static portBASE_TYPE xResult;
-
-    // Co-routines must begin with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // This assumes the queue has already been created.
-        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
-
-        if( xResult != pdPASS )
-        {
-            // The message was not posted!
-        }
-
-        // Increment the number to be posted onto the queue.
-        xNumberToPost++;
-
-        // Delay for 100 ticks.
-        crDELAY( xHandle, 100 );
-    }
-
-    // Co-routines must end with a call to crEND().
-    crEND();
- }
- * \defgroup crQUEUE_SEND crQUEUE_SEND - * \ingroup Tasks - */ -#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ -{ \ - *pxResult = xQueueCRSend( pxQueue, pvItemToQueue, xTicksToWait ); \ - if( *pxResult == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( xHandle ); \ - *pxResult = xQueueCRSend( pxQueue, pvItemToQueue, 0 ); \ - } \ - if( *pxResult == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( xHandle ); \ - *pxResult = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_RECEIVE(
-                     xCoRoutineHandle xHandle,
-                     xQueueHandle pxQueue,
-                     void *pvBuffer,
-                     portTickType xTicksToWait,
-                     portBASE_TYPE *pxResult
-                 )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_RECEIVE can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue from which the data will be received. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvBuffer The buffer into which the received item is to be copied. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied into pvBuffer. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for data to become available from the queue, should data not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the - * crQUEUE_SEND example). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully retrieved from the queue, otherwise it will be set to - * an error code as defined within ProjDefs.h. - * - * Example usage: -
- // A co-routine receives the number of an LED to flash from a queue.  It
- // blocks on the queue until the number is received.
- static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xResult;
- static unsigned portBASE_TYPE uxLEDToFlash;
-
-    // All co-routines must start with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // Wait for data to become available on the queue.
-        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-        if( xResult == pdPASS )
-        {
-            // We received the LED to flash - flash it!
-            vParTestToggleLED( uxLEDToFlash );
-        }
-    }
-
-    crEND();
- }
- * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ -{ \ - *pxResult = xQueueCRReceive( pxQueue, pvBuffer, xTicksToWait ); \ - if( *pxResult == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( xHandle ); \ - *pxResult = xQueueCRReceive( pxQueue, pvBuffer, 0 ); \ - } \ - if( *pxResult == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( xHandle ); \ - *pxResult = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvItemToQueue,
-                            portBASE_TYPE xCoRoutinePreviouslyWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue - * that is being used from within a co-routine. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto - * the same queue multiple times from a single interrupt. The first call - * should always pass in pdFALSE. Subsequent calls should pass in - * the value returned from the previous call. - * - * @return pdTRUE if a co-routine was woken by posting onto the queue. This is - * used by the ISR to determine if a context switch may be required following - * the ISR. - * - * Example usage: -
- // A co-routine that blocks on a queue waiting for characters to be received.
- static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- char cRxedChar;
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Wait for data to become available on the queue.  This assumes the
-         // queue xCommsRxQueue has already been created!
-         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-         // Was a character received?
-         if( xResult == pdPASS )
-         {
-             // Process the character here.
-         }
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to send characters received on a serial port to
- // a co-routine.
- void vUART_ISR( void )
- {
- char cRxedChar;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     // We loop around reading characters until there are none left in the UART.
-     while( UART_RX_REG_NOT_EMPTY() )
-     {
-         // Obtain the character from the UART.
-         cRxedChar = UART_RX_REG;
-
-         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
-         // the first time around the loop.  If the post causes a co-routine
-         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
-         // In this manner we can ensure that if more than one co-routine is
-         // blocked on the queue only one is woken by this ISR no matter how
-         // many characters are posted to the queue.
-         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
-     }
- }
- * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) - - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvBuffer,
-                            portBASE_TYPE * pxCoRoutineWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data - * from a queue that is being used from within a co-routine (a co-routine - * posted to the queue). - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvBuffer A pointer to a buffer into which the received item will be - * placed. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from the queue into - * pvBuffer. - * - * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become - * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a - * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise - * *pxCoRoutineWoken will remain unchanged. - * - * @return pdTRUE an item was successfully received from the queue, otherwise - * pdFALSE. - * - * Example usage: -
- // A co-routine that posts a character to a queue then blocks for a fixed
- // period.  The character is incremented each time.
- static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // cChar holds its value while this co-routine is blocked and must therefore
- // be declared static.
- static char cCharToTx = 'a';
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Send the next character to the queue.
-         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
-
-         if( xResult == pdPASS )
-         {
-             // The character was successfully posted to the queue.
-         }
-		 else
-		 {
-			// Could not post the character to the queue.
-		 }
-
-         // Enable the UART Tx interrupt to cause an interrupt in this
-		 // hypothetical UART.  The interrupt will obtain the character
-		 // from the queue and send it.
-		 ENABLE_RX_INTERRUPT();
-
-		 // Increment to the next character then block for a fixed period.
-		 // cCharToTx will maintain its value across the delay as it is
-		 // declared static.
-		 cCharToTx++;
-		 if( cCharToTx > 'x' )
-		 {
-			cCharToTx = 'a';
-		 }
-		 crDELAY( 100 );
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to receive characters to send on a UART.
- void vUART_ISR( void )
- {
- char cCharToTx;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     while( UART_TX_REG_EMPTY() )
-     {
-         // Are there any characters in the queue waiting to be sent?
-		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
-		 // is woken by the post - ensuring that only a single co-routine is
-		 // woken no matter how many times we go around this loop.
-         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
-		 {
-			 SEND_CHARACTER( cCharToTx );
-		 }
-     }
- }
- * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( pxQueue, pvBuffer, pxCoRoutineWoken ) - -/* - * This function is intended for internal use by the co-routine macros only. - * The macro nature of the co-routine implementation requires that the - * prototype appears here. The function should not be used by application - * writers. - * - * Removes the current co-routine from its ready list and places it in the - * appropriate delayed list. - */ -void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); - -/* - * This function is intended for internal use by the queue implementation only. - * The function should not be used by application writers. - * - * Removes the highest priority co-routine from the event list and places it in - * the pending ready list. - */ -signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); - -#ifdef __cplusplus -} -#endif - -#endif /* CO_ROUTINE_H */ +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include croutine.h" +#endif + + + + +#ifndef CO_ROUTINE_H +#define CO_ROUTINE_H + +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Used to hide the implementation of the co-routine control block. The +control block structure however has to be included in the header due to +the macro implementation of the co-routine functionality. */ +typedef void * xCoRoutineHandle; + +/* Defines the prototype to which co-routine functions must conform. */ +typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); + +typedef struct corCoRoutineControlBlock +{ + crCOROUTINE_CODE pxCoRoutineFunction; + xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ + unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ + unsigned short uxState; /*< Used internally by the co-routine implementation. */ +} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ + +/** + * croutine. h + *
+ portBASE_TYPE xCoRoutineCreate(
+                                 crCOROUTINE_CODE pxCoRoutineCode,
+                                 unsigned portBASE_TYPE uxPriority,
+                                 unsigned portBASE_TYPE uxIndex
+                               );
+ * + * Create a new co-routine and add it to the list of co-routines that are + * ready to run. + * + * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine + * functions require special syntax - see the co-routine section of the WEB + * documentation for more information. + * + * @param uxPriority The priority with respect to other co-routines at which + * the co-routine will run. + * + * @param uxIndex Used to distinguish between different co-routines that + * execute the same function. See the example below and the co-routine section + * of the WEB documentation for further information. + * + * @return pdPASS if the co-routine was successfully created and added to a ready + * list, otherwise an error code defined with ProjDefs.h. + * + * Example usage: +
+ // Co-routine to be created.
+ void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ static const char cLedToFlash[ 2 ] = { 5, 6 };
+ static const portTickType xTimeToDelay[ 2 ] = { 200, 400 };
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // This co-routine just delays for a fixed period, then toggles
+         // an LED.  Two co-routines are created using this function, so
+         // the uxIndex parameter is used to tell the co-routine which
+         // LED to flash and how long to delay.  This assumes xQueue has
+         // already been created.
+         vParTestToggleLED( cLedToFlash[ uxIndex ] );
+         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+
+ // Function that creates two co-routines.
+ void vOtherFunction( void )
+ {
+ unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+		
+     // Create two co-routines at priority 0.  The first is given index 0
+     // so (from the code above) toggles LED 5 every 200 ticks.  The second
+     // is given index 1 so toggles LED 6 every 400 ticks.
+     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
+     {
+         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
+     }
+ }
+   
+ * \defgroup xCoRoutineCreate xCoRoutineCreate + * \ingroup Tasks + */ +signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); + + +/** + * croutine. h + *
+ void vCoRoutineSchedule( void );
+ * + * Run a co-routine. + * + * vCoRoutineSchedule() executes the highest priority co-routine that is able + * to run. The co-routine will execute until it either blocks, yields or is + * preempted by a task. Co-routines execute cooperatively so one + * co-routine cannot be preempted by another, but can be preempted by a task. + * + * If an application comprises of both tasks and co-routines then + * vCoRoutineSchedule should be called from the idle task (in an idle task + * hook). + * + * Example usage: +
+ // This idle task hook will schedule a co-routine each time it is called.
+ // The rest of the idle task will execute between co-routine calls.
+ void vApplicationIdleHook( void )
+ {
+	vCoRoutineSchedule();
+ }
+
+ // Alternatively, if you do not require any other part of the idle task to
+ // execute, the idle task hook can call vCoRoutineScheduler() within an
+ // infinite loop.
+ void vApplicationIdleHook( void )
+ {
+    for( ;; )
+    {
+        vCoRoutineSchedule();
+    }
+ }
+ 
+ * \defgroup vCoRoutineSchedule vCoRoutineSchedule + * \ingroup Tasks + */ +void vCoRoutineSchedule( void ); + +/** + * croutine. h + *
+ crSTART( xCoRoutineHandle xHandle );
+ * + * This macro MUST always be called at the start of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crSTART( pxCRCB ) switch( ( ( corCRCB * )pxCRCB )->uxState ) { case 0: + +/** + * croutine. h + *
+ crEND();
+ * + * This macro MUST always be called at the end of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crEND() } + +/* + * These macros are intended for internal use by the co-routine implementation + * only. The macros should not be used directly by application writers. + */ +#define crSET_STATE0( xHandle ) ( ( corCRCB * )xHandle)->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): +#define crSET_STATE1( xHandle ) ( ( corCRCB * )xHandle)->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): + +/** + * croutine. h + *
+ crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
+ * + * Delay a co-routine for a fixed period of time. + * + * crDELAY can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * @param xHandle The handle of the co-routine to delay. This is the xHandle + * parameter of the co-routine function. + * + * @param xTickToDelay The number of ticks that the co-routine should delay + * for. The actual amount of time this equates to is defined by + * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS + * can be used to convert ticks to milliseconds. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ // We are to delay for 200ms.
+ static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+        // Delay for 200ms.
+        crDELAY( xHandle, xDelayTime );
+
+        // Do something here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crDELAY crDELAY + * \ingroup Tasks + */ +#define crDELAY( xHandle, xTicksToDelay ) \ + if( xTicksToDelay > 0 ) \ + { \ + vCoRoutineAddToDelayedList( xTicksToDelay, NULL ); \ + } \ + crSET_STATE0( xHandle ); + +/** + *
+ crQUEUE_SEND(
+                  xCoRoutineHandle xHandle,
+                  xQueueHandle pxQueue,
+                  void *pvItemToQueue,
+                  portTickType xTicksToWait,
+                  portBASE_TYPE *pxResult
+             )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_SEND can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue on which the data will be posted. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvItemToQueue A pointer to the data being posted onto the queue. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied from pvItemToQueue into the queue + * itself. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for space to become available on the queue, should space not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example + * below). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully posted onto the queue, otherwise it will be set to an + * error defined within ProjDefs.h. + * + * Example usage: +
+ // Co-routine function that blocks for a fixed period then posts a number onto
+ // a queue.
+ static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xNumberToPost = 0;
+ static portBASE_TYPE xResult;
+
+    // Co-routines must begin with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // This assumes the queue has already been created.
+        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
+
+        if( xResult != pdPASS )
+        {
+            // The message was not posted!
+        }
+
+        // Increment the number to be posted onto the queue.
+        xNumberToPost++;
+
+        // Delay for 100 ticks.
+        crDELAY( xHandle, 100 );
+    }
+
+    // Co-routines must end with a call to crEND().
+    crEND();
+ }
+ * \defgroup crQUEUE_SEND crQUEUE_SEND + * \ingroup Tasks + */ +#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ +{ \ + *pxResult = xQueueCRSend( pxQueue, pvItemToQueue, xTicksToWait ); \ + if( *pxResult == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( xHandle ); \ + *pxResult = xQueueCRSend( pxQueue, pvItemToQueue, 0 ); \ + } \ + if( *pxResult == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( xHandle ); \ + *pxResult = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_RECEIVE(
+                     xCoRoutineHandle xHandle,
+                     xQueueHandle pxQueue,
+                     void *pvBuffer,
+                     portTickType xTicksToWait,
+                     portBASE_TYPE *pxResult
+                 )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_RECEIVE can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue from which the data will be received. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvBuffer The buffer into which the received item is to be copied. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied into pvBuffer. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for data to become available from the queue, should data not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the + * crQUEUE_SEND example). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully retrieved from the queue, otherwise it will be set to + * an error code as defined within ProjDefs.h. + * + * Example usage: +
+ // A co-routine receives the number of an LED to flash from a queue.  It
+ // blocks on the queue until the number is received.
+ static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xResult;
+ static unsigned portBASE_TYPE uxLEDToFlash;
+
+    // All co-routines must start with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // Wait for data to become available on the queue.
+        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+        if( xResult == pdPASS )
+        {
+            // We received the LED to flash - flash it!
+            vParTestToggleLED( uxLEDToFlash );
+        }
+    }
+
+    crEND();
+ }
+ * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ +{ \ + *pxResult = xQueueCRReceive( pxQueue, pvBuffer, xTicksToWait ); \ + if( *pxResult == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( xHandle ); \ + *pxResult = xQueueCRReceive( pxQueue, pvBuffer, 0 ); \ + } \ + if( *pxResult == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( xHandle ); \ + *pxResult = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvItemToQueue,
+                            portBASE_TYPE xCoRoutinePreviouslyWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue + * that is being used from within a co-routine. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto + * the same queue multiple times from a single interrupt. The first call + * should always pass in pdFALSE. Subsequent calls should pass in + * the value returned from the previous call. + * + * @return pdTRUE if a co-routine was woken by posting onto the queue. This is + * used by the ISR to determine if a context switch may be required following + * the ISR. + * + * Example usage: +
+ // A co-routine that blocks on a queue waiting for characters to be received.
+ static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ char cRxedChar;
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Wait for data to become available on the queue.  This assumes the
+         // queue xCommsRxQueue has already been created!
+         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+         // Was a character received?
+         if( xResult == pdPASS )
+         {
+             // Process the character here.
+         }
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to send characters received on a serial port to
+ // a co-routine.
+ void vUART_ISR( void )
+ {
+ char cRxedChar;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     // We loop around reading characters until there are none left in the UART.
+     while( UART_RX_REG_NOT_EMPTY() )
+     {
+         // Obtain the character from the UART.
+         cRxedChar = UART_RX_REG;
+
+         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
+         // the first time around the loop.  If the post causes a co-routine
+         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
+         // In this manner we can ensure that if more than one co-routine is
+         // blocked on the queue only one is woken by this ISR no matter how
+         // many characters are posted to the queue.
+         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
+     }
+ }
+ * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) + + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvBuffer,
+                            portBASE_TYPE * pxCoRoutineWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data + * from a queue that is being used from within a co-routine (a co-routine + * posted to the queue). + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvBuffer A pointer to a buffer into which the received item will be + * placed. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from the queue into + * pvBuffer. + * + * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become + * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a + * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise + * *pxCoRoutineWoken will remain unchanged. + * + * @return pdTRUE an item was successfully received from the queue, otherwise + * pdFALSE. + * + * Example usage: +
+ // A co-routine that posts a character to a queue then blocks for a fixed
+ // period.  The character is incremented each time.
+ static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // cChar holds its value while this co-routine is blocked and must therefore
+ // be declared static.
+ static char cCharToTx = 'a';
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Send the next character to the queue.
+         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
+
+         if( xResult == pdPASS )
+         {
+             // The character was successfully posted to the queue.
+         }
+		 else
+		 {
+			// Could not post the character to the queue.
+		 }
+
+         // Enable the UART Tx interrupt to cause an interrupt in this
+		 // hypothetical UART.  The interrupt will obtain the character
+		 // from the queue and send it.
+		 ENABLE_RX_INTERRUPT();
+
+		 // Increment to the next character then block for a fixed period.
+		 // cCharToTx will maintain its value across the delay as it is
+		 // declared static.
+		 cCharToTx++;
+		 if( cCharToTx > 'x' )
+		 {
+			cCharToTx = 'a';
+		 }
+		 crDELAY( 100 );
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to receive characters to send on a UART.
+ void vUART_ISR( void )
+ {
+ char cCharToTx;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     while( UART_TX_REG_EMPTY() )
+     {
+         // Are there any characters in the queue waiting to be sent?
+		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
+		 // is woken by the post - ensuring that only a single co-routine is
+		 // woken no matter how many times we go around this loop.
+         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
+		 {
+			 SEND_CHARACTER( cCharToTx );
+		 }
+     }
+ }
+ * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( pxQueue, pvBuffer, pxCoRoutineWoken ) + +/* + * This function is intended for internal use by the co-routine macros only. + * The macro nature of the co-routine implementation requires that the + * prototype appears here. The function should not be used by application + * writers. + * + * Removes the current co-routine from its ready list and places it in the + * appropriate delayed list. + */ +void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); + +/* + * This function is intended for internal use by the queue implementation only. + * The function should not be used by application writers. + * + * Removes the highest priority co-routine from the event list and places it in + * the pending ready list. + */ +signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); + +#ifdef __cplusplus +} +#endif + +#endif /* CO_ROUTINE_H */ diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/list.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/list.h index 65712836e..6808fc323 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/list.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/list.h @@ -1,305 +1,305 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/* - * This is the list implementation used by the scheduler. While it is tailored - * heavily for the schedulers needs, it is also available for use by - * application code. - * - * xLists can only store pointers to xListItems. Each xListItem contains a - * numeric value (xItemValue). Most of the time the lists are sorted in - * descending item value order. - * - * Lists are created already containing one list item. The value of this - * item is the maximum possible that can be stored, it is therefore always at - * the end of the list and acts as a marker. The list member pxHead always - * points to this marker - even though it is at the tail of the list. This - * is because the tail contains a wrap back pointer to the true head of - * the list. - * - * In addition to it's value, each list item contains a pointer to the next - * item in the list (pxNext), a pointer to the list it is in (pxContainer) - * and a pointer to back to the object that contains it. These later two - * pointers are included for efficiency of list manipulation. There is - * effectively a two way link between the object containing the list item and - * the list item itself. - * - * - * \page ListIntroduction List Implementation - * \ingroup FreeRTOSIntro - */ - -/* - Changes from V4.3.1 - - + Included local const within listGET_OWNER_OF_NEXT_ENTRY() to assist - compiler with optimisation. Thanks B.R. -*/ - -#ifndef LIST_H -#define LIST_H - -#ifdef __cplusplus -extern "C" { -#endif -/* - * Definition of the only type of object that a list can contain. - */ -struct xLIST_ITEM -{ - portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ - volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ - volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ - void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ - void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ -}; -typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ - -struct xMINI_LIST_ITEM -{ - portTickType xItemValue; - volatile struct xLIST_ITEM *pxNext; - volatile struct xLIST_ITEM *pxPrevious; -}; -typedef struct xMINI_LIST_ITEM xMiniListItem; - -/* - * Definition of the type of queue used by the scheduler. - */ -typedef struct xLIST -{ - volatile unsigned portBASE_TYPE uxNumberOfItems; - volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ - volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ -} xList; - -/* - * Access macro to set the owner of a list item. The owner of a list item - * is the object (usually a TCB) that contains the list item. - * - * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) pxOwner - -/* - * Access macro to set the value of the list item. In most cases the value is - * used to sort the list in descending order. - * - * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = xValue - -/* - * Access macro the retrieve the value of the list item. The value can - * represent anything - for example a the priority of a task, or the time at - * which a task should be unblocked. - * - * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) - -/* - * Access macro to determine if a list contains any items. The macro will - * only have the value true if the list is empty. - * - * \page listLIST_IS_EMPTY listLIST_IS_EMPTY - * \ingroup LinkedList - */ -#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) - -/* - * Access macro to return the number of items in the list. - */ -#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) - -/* - * Access function to obtain the owner of the next entry in a list. - * - * The list member pxIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list - * and returns that entries pxOwner parameter. Using multiple calls to this - * function it is therefore possible to move through every item contained in - * a list. - * - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the next item owner is to be returned. - * - * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ -{ \ -xList * const pxConstList = pxList; \ - /* Increment the index to the next item and return the item, ensuring */ \ - /* we don't return the marker used at the end of the list. */ \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ - { \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - } \ - pxTCB = ( pxConstList )->pxIndex->pvOwner; \ -} - - -/* - * Access function to obtain the owner of the first entry in a list. Lists - * are normally sorted in ascending item value order. - * - * This function returns the pxOwner member of the first item in the list. - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the owner of the head item is to be - * returned. - * - * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( ( pxList->uxNumberOfItems != ( unsigned portBASE_TYPE ) 0 ) ? ( (&( pxList->xListEnd ))->pxNext->pvOwner ) : ( NULL ) ) - -/* - * Check to see if a list item is within a list. The list item maintains a - * "container" pointer that points to the list it is in. All this macro does - * is check to see if the container and the list match. - * - * @param pxList The list we want to know if the list item is within. - * @param pxListItem The list item we want to know if is in the list. - * @return pdTRUE is the list item is in the list, otherwise pdFALSE. - * pointer against - */ -#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) pxList ) - -/* - * Must be called before a list is used! This initialises all the members - * of the list structure and inserts the xListEnd item into the list as a - * marker to the back of the list. - * - * @param pxList Pointer to the list being initialised. - * - * \page vListInitialise vListInitialise - * \ingroup LinkedList - */ -void vListInitialise( xList *pxList ); - -/* - * Must be called before a list item is used. This sets the list container to - * null so the item does not think that it is already contained in a list. - * - * @param pxItem Pointer to the list item being initialised. - * - * \page vListInitialiseItem vListInitialiseItem - * \ingroup LinkedList - */ -void vListInitialiseItem( xListItem *pxItem ); - -/* - * Insert a list item into a list. The item will be inserted into the list in - * a position determined by its item value (descending item value order). - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The item to that is to be placed in the list. - * - * \page vListInsert vListInsert - * \ingroup LinkedList - */ -void vListInsert( xList *pxList, xListItem *pxNewListItem ); - -/* - * Insert a list item into a list. The item will be inserted in a position - * such that it will be the last item within the list returned by multiple - * calls to listGET_OWNER_OF_NEXT_ENTRY. - * - * The list member pvIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. - * Placing an item in a list using vListInsertEnd effectively places the item - * in the list position pointed to by pvIndex. This means that every other - * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before - * the pvIndex parameter again points to the item being inserted. - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The list item to be inserted into the list. - * - * \page vListInsertEnd vListInsertEnd - * \ingroup LinkedList - */ -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); - -/* - * Remove an item from a list. The list item has a pointer to the list that - * it is in, so only the list item need be passed into the function. - * - * @param vListRemove The item to be removed. The item will remove itself from - * the list pointed to by it's pxContainer parameter. - * - * \page vListRemove vListRemove - * \ingroup LinkedList - */ -void vListRemove( xListItem *pxItemToRemove ); - -#ifdef __cplusplus -} -#endif - -#endif - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/* + * This is the list implementation used by the scheduler. While it is tailored + * heavily for the schedulers needs, it is also available for use by + * application code. + * + * xLists can only store pointers to xListItems. Each xListItem contains a + * numeric value (xItemValue). Most of the time the lists are sorted in + * descending item value order. + * + * Lists are created already containing one list item. The value of this + * item is the maximum possible that can be stored, it is therefore always at + * the end of the list and acts as a marker. The list member pxHead always + * points to this marker - even though it is at the tail of the list. This + * is because the tail contains a wrap back pointer to the true head of + * the list. + * + * In addition to it's value, each list item contains a pointer to the next + * item in the list (pxNext), a pointer to the list it is in (pxContainer) + * and a pointer to back to the object that contains it. These later two + * pointers are included for efficiency of list manipulation. There is + * effectively a two way link between the object containing the list item and + * the list item itself. + * + * + * \page ListIntroduction List Implementation + * \ingroup FreeRTOSIntro + */ + +/* + Changes from V4.3.1 + + + Included local const within listGET_OWNER_OF_NEXT_ENTRY() to assist + compiler with optimisation. Thanks B.R. +*/ + +#ifndef LIST_H +#define LIST_H + +#ifdef __cplusplus +extern "C" { +#endif +/* + * Definition of the only type of object that a list can contain. + */ +struct xLIST_ITEM +{ + portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ + volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ + volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ + void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ + void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ +}; +typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ + +struct xMINI_LIST_ITEM +{ + portTickType xItemValue; + volatile struct xLIST_ITEM *pxNext; + volatile struct xLIST_ITEM *pxPrevious; +}; +typedef struct xMINI_LIST_ITEM xMiniListItem; + +/* + * Definition of the type of queue used by the scheduler. + */ +typedef struct xLIST +{ + volatile unsigned portBASE_TYPE uxNumberOfItems; + volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ + volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ +} xList; + +/* + * Access macro to set the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) pxOwner + +/* + * Access macro to set the value of the list item. In most cases the value is + * used to sort the list in descending order. + * + * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = xValue + +/* + * Access macro the retrieve the value of the list item. The value can + * represent anything - for example a the priority of a task, or the time at + * which a task should be unblocked. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) + +/* + * Access macro to determine if a list contains any items. The macro will + * only have the value true if the list is empty. + * + * \page listLIST_IS_EMPTY listLIST_IS_EMPTY + * \ingroup LinkedList + */ +#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) + +/* + * Access macro to return the number of items in the list. + */ +#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) + +/* + * Access function to obtain the owner of the next entry in a list. + * + * The list member pxIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list + * and returns that entries pxOwner parameter. Using multiple calls to this + * function it is therefore possible to move through every item contained in + * a list. + * + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the next item owner is to be returned. + * + * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ +{ \ +xList * const pxConstList = pxList; \ + /* Increment the index to the next item and return the item, ensuring */ \ + /* we don't return the marker used at the end of the list. */ \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ + { \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + } \ + pxTCB = ( pxConstList )->pxIndex->pvOwner; \ +} + + +/* + * Access function to obtain the owner of the first entry in a list. Lists + * are normally sorted in ascending item value order. + * + * This function returns the pxOwner member of the first item in the list. + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the owner of the head item is to be + * returned. + * + * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( ( pxList->uxNumberOfItems != ( unsigned portBASE_TYPE ) 0 ) ? ( (&( pxList->xListEnd ))->pxNext->pvOwner ) : ( NULL ) ) + +/* + * Check to see if a list item is within a list. The list item maintains a + * "container" pointer that points to the list it is in. All this macro does + * is check to see if the container and the list match. + * + * @param pxList The list we want to know if the list item is within. + * @param pxListItem The list item we want to know if is in the list. + * @return pdTRUE is the list item is in the list, otherwise pdFALSE. + * pointer against + */ +#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) pxList ) + +/* + * Must be called before a list is used! This initialises all the members + * of the list structure and inserts the xListEnd item into the list as a + * marker to the back of the list. + * + * @param pxList Pointer to the list being initialised. + * + * \page vListInitialise vListInitialise + * \ingroup LinkedList + */ +void vListInitialise( xList *pxList ); + +/* + * Must be called before a list item is used. This sets the list container to + * null so the item does not think that it is already contained in a list. + * + * @param pxItem Pointer to the list item being initialised. + * + * \page vListInitialiseItem vListInitialiseItem + * \ingroup LinkedList + */ +void vListInitialiseItem( xListItem *pxItem ); + +/* + * Insert a list item into a list. The item will be inserted into the list in + * a position determined by its item value (descending item value order). + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The item to that is to be placed in the list. + * + * \page vListInsert vListInsert + * \ingroup LinkedList + */ +void vListInsert( xList *pxList, xListItem *pxNewListItem ); + +/* + * Insert a list item into a list. The item will be inserted in a position + * such that it will be the last item within the list returned by multiple + * calls to listGET_OWNER_OF_NEXT_ENTRY. + * + * The list member pvIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. + * Placing an item in a list using vListInsertEnd effectively places the item + * in the list position pointed to by pvIndex. This means that every other + * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before + * the pvIndex parameter again points to the item being inserted. + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The list item to be inserted into the list. + * + * \page vListInsertEnd vListInsertEnd + * \ingroup LinkedList + */ +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); + +/* + * Remove an item from a list. The list item has a pointer to the list that + * it is in, so only the list item need be passed into the function. + * + * @param vListRemove The item to be removed. The item will remove itself from + * the list pointed to by it's pxContainer parameter. + * + * \page vListRemove vListRemove + * \ingroup LinkedList + */ +void vListRemove( xListItem *pxItemToRemove ); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/mpu_wrappers.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/mpu_wrappers.h index e197d5085..ecbe76147 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/mpu_wrappers.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/mpu_wrappers.h @@ -1,135 +1,135 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef MPU_WRAPPERS_H -#define MPU_WRAPPERS_H - -/* This file redefines API functions to be called through a wrapper macro, but -only for ports that are using the MPU. */ -#ifdef portUSING_MPU_WRAPPERS - - /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is - included from queue.c or task.c to prevent it from having an effect within - those files. */ - #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - - #define xTaskGenericCreate MPU_xTaskGenericCreate - #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions - #define vTaskDelete MPU_vTaskDelete - #define vTaskDelayUntil MPU_vTaskDelayUntil - #define vTaskDelay MPU_vTaskDelay - #define uxTaskPriorityGet MPU_uxTaskPriorityGet - #define vTaskPrioritySet MPU_vTaskPrioritySet - #define vTaskSuspend MPU_vTaskSuspend - #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended - #define vTaskResume MPU_vTaskResume - #define vTaskSuspendAll MPU_vTaskSuspendAll - #define xTaskResumeAll MPU_xTaskResumeAll - #define xTaskGetTickCount MPU_xTaskGetTickCount - #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks - #define vTaskList MPU_vTaskList - #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats - #define vTaskStartTrace MPU_vTaskStartTrace - #define ulTaskEndTrace MPU_ulTaskEndTrace - #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag - #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag - #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook - #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark - #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle - #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState - - #define xQueueCreate MPU_xQueueCreate - #define xQueueCreateMutex MPU_xQueueCreateMutex - #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive - #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive - #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore - #define xQueueGenericSend MPU_xQueueGenericSend - #define xQueueAltGenericSend MPU_xQueueAltGenericSend - #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive - #define xQueueGenericReceive MPU_xQueueGenericReceive - #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting - #define vQueueDelete MPU_vQueueDelete - - #define pvPortMalloc MPU_pvPortMalloc - #define vPortFree MPU_vPortFree - #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize - #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks - - #if configQUEUE_REGISTRY_SIZE > 0 - #define vQueueAddToRegistry MPU_vQueueAddToRegistry - #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue - #endif - - /* Remove the privileged function macro. */ - #define PRIVILEGED_FUNCTION - - #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - - /* Ensure API functions go in the privileged execution section. */ - #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) - #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) - //#define PRIVILEGED_DATA - - #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - -#else /* portUSING_MPU_WRAPPERS */ - - #define PRIVILEGED_FUNCTION - #define PRIVILEGED_DATA - #define portUSING_MPU_WRAPPERS 0 - -#endif /* portUSING_MPU_WRAPPERS */ - - -#endif /* MPU_WRAPPERS_H */ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef MPU_WRAPPERS_H +#define MPU_WRAPPERS_H + +/* This file redefines API functions to be called through a wrapper macro, but +only for ports that are using the MPU. */ +#ifdef portUSING_MPU_WRAPPERS + + /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is + included from queue.c or task.c to prevent it from having an effect within + those files. */ + #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + + #define xTaskGenericCreate MPU_xTaskGenericCreate + #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions + #define vTaskDelete MPU_vTaskDelete + #define vTaskDelayUntil MPU_vTaskDelayUntil + #define vTaskDelay MPU_vTaskDelay + #define uxTaskPriorityGet MPU_uxTaskPriorityGet + #define vTaskPrioritySet MPU_vTaskPrioritySet + #define vTaskSuspend MPU_vTaskSuspend + #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended + #define vTaskResume MPU_vTaskResume + #define vTaskSuspendAll MPU_vTaskSuspendAll + #define xTaskResumeAll MPU_xTaskResumeAll + #define xTaskGetTickCount MPU_xTaskGetTickCount + #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks + #define vTaskList MPU_vTaskList + #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats + #define vTaskStartTrace MPU_vTaskStartTrace + #define ulTaskEndTrace MPU_ulTaskEndTrace + #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag + #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag + #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook + #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark + #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle + #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState + + #define xQueueCreate MPU_xQueueCreate + #define xQueueCreateMutex MPU_xQueueCreateMutex + #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive + #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive + #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore + #define xQueueGenericSend MPU_xQueueGenericSend + #define xQueueAltGenericSend MPU_xQueueAltGenericSend + #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive + #define xQueueGenericReceive MPU_xQueueGenericReceive + #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting + #define vQueueDelete MPU_vQueueDelete + + #define pvPortMalloc MPU_pvPortMalloc + #define vPortFree MPU_vPortFree + #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize + #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks + + #if configQUEUE_REGISTRY_SIZE > 0 + #define vQueueAddToRegistry MPU_vQueueAddToRegistry + #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue + #endif + + /* Remove the privileged function macro. */ + #define PRIVILEGED_FUNCTION + + #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + + /* Ensure API functions go in the privileged execution section. */ + #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) + #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) + //#define PRIVILEGED_DATA + + #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + +#else /* portUSING_MPU_WRAPPERS */ + + #define PRIVILEGED_FUNCTION + #define PRIVILEGED_DATA + #define portUSING_MPU_WRAPPERS 0 + +#endif /* portUSING_MPU_WRAPPERS */ + + +#endif /* MPU_WRAPPERS_H */ + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/portable.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/portable.h index 058ac4352..0ba4771c1 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/portable.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/portable.h @@ -1,391 +1,391 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Portable layer API. Each function must be defined for each port. - *----------------------------------------------------------*/ - -#ifndef PORTABLE_H -#define PORTABLE_H - -/* Include the macro file relevant to the port being used. */ - -#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT - #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT - #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef GCC_MEGA_AVR - #include "../portable/GCC/ATMega323/portmacro.h" -#endif - -#ifdef IAR_MEGA_AVR - #include "../portable/IAR/ATMega323/portmacro.h" -#endif - -#ifdef MPLAB_PIC24_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_DSPIC_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_PIC18F_PORT - #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" -#endif - -#ifdef MPLAB_PIC32MX_PORT - #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" -#endif - -#ifdef _FEDPICC - #include "libFreeRTOS/Include/portmacro.h" -#endif - -#ifdef SDCC_CYGNAL - #include "../../Source/portable/SDCC/Cygnal/portmacro.h" -#endif - -#ifdef GCC_ARM7 - #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" -#endif - -#ifdef GCC_ARM7_ECLIPSE - #include "portmacro.h" -#endif - -#ifdef ROWLEY_LPC23xx - #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" -#endif - -#ifdef IAR_MSP430 - #include "..\..\Source\portable\IAR\MSP430\portmacro.h" -#endif - -#ifdef GCC_MSP430 - #include "../../Source/portable/GCC/MSP430F449/portmacro.h" -#endif - -#ifdef ROWLEY_MSP430 - #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" -#endif - -#ifdef ARM7_LPC21xx_KEIL_RVDS - #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" -#endif - -#ifdef SAM7_GCC - #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" -#endif - -#ifdef SAM7_IAR - #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" -#endif - -#ifdef SAM9XE_IAR - #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" -#endif - -#ifdef LPC2000_IAR - #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" -#endif - -#ifdef STR71X_IAR - #include "..\..\Source\portable\IAR\STR71x\portmacro.h" -#endif - -#ifdef STR75X_IAR - #include "..\..\Source\portable\IAR\STR75x\portmacro.h" -#endif - -#ifdef STR75X_GCC - #include "..\..\Source\portable\GCC\STR75x\portmacro.h" -#endif - -#ifdef STR91X_IAR - #include "..\..\Source\portable\IAR\STR91x\portmacro.h" -#endif - -#ifdef GCC_H8S - #include "../../Source/portable/GCC/H8S2329/portmacro.h" -#endif - -#ifdef GCC_AT91FR40008 - #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" -#endif - -#ifdef RVDS_ARMCM3_LM3S102 - #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3_LM3S102 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARM_CM3 - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARMCM3_LM - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef HCS12_CODE_WARRIOR - #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" -#endif - -#ifdef MICROBLAZE_GCC - #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" -#endif - -#ifdef TERN_EE - #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" -#endif - -#ifdef GCC_HCS12 - #include "../../Source/portable/GCC/HCS12/portmacro.h" -#endif - -#ifdef GCC_MCF5235 - #include "../../Source/portable/GCC/MCF5235/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_GCC - #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_CODEWARRIOR - #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" -#endif - -#ifdef GCC_PPC405 - #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" -#endif - -#ifdef GCC_PPC440 - #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" -#endif - -#ifdef _16FX_SOFTUNE - #include "..\..\Source\portable\Softune\MB96340\portmacro.h" -#endif - -#ifdef BCC_INDUSTRIAL_PC_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef BCC_FLASH_LITE_186_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef __GNUC__ - #ifdef __AVR32_AVR32A__ - #include "portmacro.h" - #endif -#endif - -#ifdef __ICCAVR32__ - #ifdef __CORE__ - #if __CORE__ == __AVR32A__ - #include "portmacro.h" - #endif - #endif -#endif - -#ifdef __91467D - #include "portmacro.h" -#endif - -#ifdef __96340 - #include "portmacro.h" -#endif - - -#ifdef __IAR_V850ES_Fx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3_L__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Hx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3L__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -/* Catch all to ensure portmacro.h is included in the build. Newer demos -have the path as part of the project options, rather than as relative from -the project location. If portENTER_CRITICAL() has not been defined then -portmacro.h has not yet been included - as every portmacro.h provides a -portENTER_CRITICAL() definition. Check the demo application for your demo -to find the path to the correct portmacro.h file. */ -#ifndef portENTER_CRITICAL - #include "../../Source/portable/GCC/Win32/portmacro.h" - //#include "portmacro.h" -#endif - -#if portBYTE_ALIGNMENT == 8 - #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) -#endif - -#if portBYTE_ALIGNMENT == 4 - #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) -#endif - -#if portBYTE_ALIGNMENT == 2 - #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) -#endif - -#if portBYTE_ALIGNMENT == 1 - #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) -#endif - -#ifndef portBYTE_ALIGNMENT_MASK - #error "Invalid portBYTE_ALIGNMENT definition" -#endif - -#ifndef portNUM_CONFIGURABLE_REGIONS - #define portNUM_CONFIGURABLE_REGIONS 1 -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -#include "mpu_wrappers.h" - -/* - * Setup the stack of a new task so it is ready to be placed under the - * scheduler control. The registers have to be placed on the stack in - * the order that the port expects to find them. - * - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; -#else - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ); -#endif - -/* - * Map to the memory management routines required for the port. - */ -void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; -void vPortFree( void *pv ) PRIVILEGED_FUNCTION; -void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; -size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; - -/* - * Setup the hardware ready for the scheduler to take control. This generally - * sets up a tick interrupt and sets timers for the correct tick frequency. - */ -portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so - * the hardware is left in its original condition after the scheduler stops - * executing. - */ -void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * The structures and methods of manipulating the MPU are contained within the - * port layer. - * - * Fills the xMPUSettings structure with the memory region information - * contained in xRegions. - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - struct xMEMORY_REGION; - void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* PORTABLE_H */ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/*----------------------------------------------------------- + * Portable layer API. Each function must be defined for each port. + *----------------------------------------------------------*/ + +#ifndef PORTABLE_H +#define PORTABLE_H + +/* Include the macro file relevant to the port being used. */ + +#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT + #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT + #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef GCC_MEGA_AVR + #include "../portable/GCC/ATMega323/portmacro.h" +#endif + +#ifdef IAR_MEGA_AVR + #include "../portable/IAR/ATMega323/portmacro.h" +#endif + +#ifdef MPLAB_PIC24_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_DSPIC_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_PIC18F_PORT + #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" +#endif + +#ifdef MPLAB_PIC32MX_PORT + #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" +#endif + +#ifdef _FEDPICC + #include "libFreeRTOS/Include/portmacro.h" +#endif + +#ifdef SDCC_CYGNAL + #include "../../Source/portable/SDCC/Cygnal/portmacro.h" +#endif + +#ifdef GCC_ARM7 + #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" +#endif + +#ifdef GCC_ARM7_ECLIPSE + #include "portmacro.h" +#endif + +#ifdef ROWLEY_LPC23xx + #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" +#endif + +#ifdef IAR_MSP430 + #include "..\..\Source\portable\IAR\MSP430\portmacro.h" +#endif + +#ifdef GCC_MSP430 + #include "../../Source/portable/GCC/MSP430F449/portmacro.h" +#endif + +#ifdef ROWLEY_MSP430 + #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" +#endif + +#ifdef ARM7_LPC21xx_KEIL_RVDS + #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" +#endif + +#ifdef SAM7_GCC + #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" +#endif + +#ifdef SAM7_IAR + #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" +#endif + +#ifdef SAM9XE_IAR + #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" +#endif + +#ifdef LPC2000_IAR + #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" +#endif + +#ifdef STR71X_IAR + #include "..\..\Source\portable\IAR\STR71x\portmacro.h" +#endif + +#ifdef STR75X_IAR + #include "..\..\Source\portable\IAR\STR75x\portmacro.h" +#endif + +#ifdef STR75X_GCC + #include "..\..\Source\portable\GCC\STR75x\portmacro.h" +#endif + +#ifdef STR91X_IAR + #include "..\..\Source\portable\IAR\STR91x\portmacro.h" +#endif + +#ifdef GCC_H8S + #include "../../Source/portable/GCC/H8S2329/portmacro.h" +#endif + +#ifdef GCC_AT91FR40008 + #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" +#endif + +#ifdef RVDS_ARMCM3_LM3S102 + #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3_LM3S102 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARM_CM3 + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARMCM3_LM + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef HCS12_CODE_WARRIOR + #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" +#endif + +#ifdef MICROBLAZE_GCC + #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" +#endif + +#ifdef TERN_EE + #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" +#endif + +#ifdef GCC_HCS12 + #include "../../Source/portable/GCC/HCS12/portmacro.h" +#endif + +#ifdef GCC_MCF5235 + #include "../../Source/portable/GCC/MCF5235/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_GCC + #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_CODEWARRIOR + #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" +#endif + +#ifdef GCC_PPC405 + #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" +#endif + +#ifdef GCC_PPC440 + #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" +#endif + +#ifdef _16FX_SOFTUNE + #include "..\..\Source\portable\Softune\MB96340\portmacro.h" +#endif + +#ifdef BCC_INDUSTRIAL_PC_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef BCC_FLASH_LITE_186_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef __GNUC__ + #ifdef __AVR32_AVR32A__ + #include "portmacro.h" + #endif +#endif + +#ifdef __ICCAVR32__ + #ifdef __CORE__ + #if __CORE__ == __AVR32A__ + #include "portmacro.h" + #endif + #endif +#endif + +#ifdef __91467D + #include "portmacro.h" +#endif + +#ifdef __96340 + #include "portmacro.h" +#endif + + +#ifdef __IAR_V850ES_Fx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3_L__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Hx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3L__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +/* Catch all to ensure portmacro.h is included in the build. Newer demos +have the path as part of the project options, rather than as relative from +the project location. If portENTER_CRITICAL() has not been defined then +portmacro.h has not yet been included - as every portmacro.h provides a +portENTER_CRITICAL() definition. Check the demo application for your demo +to find the path to the correct portmacro.h file. */ +#ifndef portENTER_CRITICAL + #include "../../Source/portable/GCC/Win32/portmacro.h" + //#include "portmacro.h" +#endif + +#if portBYTE_ALIGNMENT == 8 + #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) +#endif + +#if portBYTE_ALIGNMENT == 4 + #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) +#endif + +#if portBYTE_ALIGNMENT == 2 + #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) +#endif + +#if portBYTE_ALIGNMENT == 1 + #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) +#endif + +#ifndef portBYTE_ALIGNMENT_MASK + #error "Invalid portBYTE_ALIGNMENT definition" +#endif + +#ifndef portNUM_CONFIGURABLE_REGIONS + #define portNUM_CONFIGURABLE_REGIONS 1 +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#include "mpu_wrappers.h" + +/* + * Setup the stack of a new task so it is ready to be placed under the + * scheduler control. The registers have to be placed on the stack in + * the order that the port expects to find them. + * + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; +#else + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ); +#endif + +/* + * Map to the memory management routines required for the port. + */ +void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; +void vPortFree( void *pv ) PRIVILEGED_FUNCTION; +void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; +size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; + +/* + * Setup the hardware ready for the scheduler to take control. This generally + * sets up a tick interrupt and sets timers for the correct tick frequency. + */ +portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so + * the hardware is left in its original condition after the scheduler stops + * executing. + */ +void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * The structures and methods of manipulating the MPU are contained within the + * port layer. + * + * Fills the xMPUSettings structure with the memory region information + * contained in xRegions. + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + struct xMEMORY_REGION; + void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* PORTABLE_H */ + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/projdefs.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/projdefs.h index 25e9560ea..4ce410132 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/projdefs.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/projdefs.h @@ -1,77 +1,77 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef PROJDEFS_H -#define PROJDEFS_H - -/* Defines the prototype to which task functions must conform. */ -typedef void (*pdTASK_CODE)( void * ); - -#define pdTRUE ( 1 ) -#define pdFALSE ( 0 ) - -#define pdPASS ( 1 ) -#define pdFAIL ( 0 ) -#define errQUEUE_EMPTY ( 0 ) -#define errQUEUE_FULL ( 0 ) - -/* Error definitions. */ -#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) -#define errNO_TASK_TO_RUN ( -2 ) -#define errQUEUE_BLOCKED ( -4 ) -#define errQUEUE_YIELD ( -5 ) - -#endif /* PROJDEFS_H */ - - - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef PROJDEFS_H +#define PROJDEFS_H + +/* Defines the prototype to which task functions must conform. */ +typedef void (*pdTASK_CODE)( void * ); + +#define pdTRUE ( 1 ) +#define pdFALSE ( 0 ) + +#define pdPASS ( 1 ) +#define pdFAIL ( 0 ) +#define errQUEUE_EMPTY ( 0 ) +#define errQUEUE_FULL ( 0 ) + +/* Error definitions. */ +#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) +#define errNO_TASK_TO_RUN ( -2 ) +#define errQUEUE_BLOCKED ( -4 ) +#define errQUEUE_YIELD ( -5 ) + +#endif /* PROJDEFS_H */ + + + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/queue.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/queue.h index c26ccc7fe..055091624 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/queue.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/queue.h @@ -1,1261 +1,1261 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include queue.h" -#endif - - - - -#ifndef QUEUE_H -#define QUEUE_H - -#ifdef __cplusplus -extern "C" { -#endif - - -#include "mpu_wrappers.h" - - -typedef void * xQueueHandle; - - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - - -/** - * queue. h - *
- xQueueHandle xQueueCreate(
-							  unsigned portBASE_TYPE uxQueueLength,
-							  unsigned portBASE_TYPE uxItemSize
-						  );
- * 
- * - * Creates a new queue instance. This allocates the storage required by the - * new queue and returns a handle for the queue. - * - * @param uxQueueLength The maximum number of items that the queue can contain. - * - * @param uxItemSize The number of bytes each item in the queue will require. - * Items are queued by copy, not by reference, so this is the number of bytes - * that will be copied for each posted item. Each item on the queue must be - * the same size. - * - * @return If the queue is successfully create then a handle to the newly - * created queue is returned. If the queue cannot be created then 0 is - * returned. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- };
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-	if( xQueue1 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue2 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueCreate xQueueCreate - * \ingroup QueueManagement - */ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ); - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToToFront(
-								   xQueueHandle	xQueue,
-								   const	void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the front of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_FRONT ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBack(
-								   xQueueHandle	xQueue,
-								   const	void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the back of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the queue - * is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSend(
-							  xQueueHandle xQueue,
-							  const void * pvItemToQueue,
-							  portTickType xTicksToWait
-						 );
- * 
- * - * This is a macro that calls xQueueGenericSend(). It is included for - * backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToFront() and xQueueSendToBack() macros. It is - * equivalent to xQueueSendToBack(). - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSend(
-									xQueueHandle xQueue,
-									const void * pvItemToQueue,
-									portTickType xTicksToWait
-									portBASE_TYPE xCopyPosition
-								);
- * 
- * - * It is preferred that the macros xQueueSend(), xQueueSendToFront() and - * xQueueSendToBack() are used in place of calling this function directly. - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueuePeek(
-							 xQueueHandle xQueue,
-							 void *pvBuffer,
-							 portTickType xTicksToWait
-						 );
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue without removing the item from the queue. - * The item is received by copy so a buffer of adequate size must be - * provided. The number of bytes copied into the buffer was defined when - * the queue was created. - * - * Successfully received items remain on the queue so will be returned again - * by the next call, or a call to xQueueReceive(). - * - * This macro must not be used in an interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue - * is empty. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to peek the data from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Peek a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask, but the item still remains on the queue.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( xQueue, pvBuffer, xTicksToWait, pdTRUE ) - -/** - * queue. h - *
- portBASE_TYPE xQueueReceive(
-								 xQueueHandle xQueue,
-								 void *pvBuffer,
-								 portTickType xTicksToWait
-							);
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * Successfully received items are removed from the queue. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. xQueueReceive() will return immediately if xTicksToWait - * is zero and the queue is empty. The time is defined in tick periods so the - * constant portTICK_RATE_MS should be used to convert to real time if this is - * required. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( xQueue, pvBuffer, xTicksToWait, pdFALSE ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericReceive(
-									   xQueueHandle	xQueue,
-									   void	*pvBuffer,
-									   portTickType	xTicksToWait
-									   portBASE_TYPE	xJustPeek
-									);
- * - * It is preferred that the macro xQueueReceive() be used rather than calling - * this function directly. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueueGenericReceive() will return immediately if the queue is empty and - * xTicksToWait is 0. - * - * @param xJustPeek When set to true, the item received from the queue is not - * actually removed from the queue - meaning a subsequent call to - * xQueueReceive() will return the same item. When set to false, the item - * being received from the queue is also removed from the queue. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); - -/** - * queue. h - *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
- * - * Return the number of messages stored in a queue. - * - * @param xQueue A handle to the queue being queried. - * - * @return The number of messages available in the queue. - * - * \page uxQueueMessagesWaiting uxQueueMessagesWaiting - * \ingroup QueueManagement - */ -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); - -/** - * queue. h - *
void vQueueDelete( xQueueHandle xQueue );
- * - * Delete a queue - freeing all the memory allocated for storing of items - * placed on the queue. - * - * @param xQueue A handle to the queue to be deleted. - * - * \page vQueueDelete vQueueDelete - * \ingroup QueueManagement - */ -void vQueueDelete( xQueueHandle xQueue ); - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToFrontFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the front of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPrioritTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_FRONT ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBackFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the back of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendFromISR(
-									 xQueueHandle pxQueue,
-									 const void *pvItemToQueue,
-									 portBASE_TYPE *pxHigherPriorityTaskWoken
-								);
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). It is included - * for backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() - * macros. - * - * Post an item to the back of a queue. It is safe to use this function from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		// Actual macro used here is port specific.
-		taskYIELD_FROM_ISR ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSendFromISR(
-										   xQueueHandle	pxQueue,
-										   const	void	*pvItemToQueue,
-										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
-										   portBASE_TYPE	xCopyPosition
-									   );
- 
- * - * It is preferred that the macros xQueueSendFromISR(), - * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place - * of calling this function directly. - * - * Post an item on a queue. It is safe to use this function from within an - * interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWokenByPost;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWokenByPost = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post each byte.
-		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.  Note that the
-	// name of the yield function required is port specific.
-	if( xHigherPriorityTaskWokenByPost )
-	{
-		taskYIELD_YIELD_FROM_ISR();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueueReceiveFromISR(
-									   xQueueHandle	pxQueue,
-									   void	*pvBuffer,
-									   portBASE_TYPE	*pxTaskWoken
-								   );
- * 
- * - * Receive an item from a queue. It is safe to use this function from within an - * interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param pxTaskWoken A task may be blocked waiting for space to become - * available on the queue. If xQueueReceiveFromISR causes such a task to - * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will - * remain unchanged. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
-
- xQueueHandle xQueue;
-
- // Function to create a queue and post some values.
- void vAFunction( void *pvParameters )
- {
- char cValueToPost;
- const portTickType xBlockTime = ( portTickType )0xff;
-
-	// Create a queue capable of containing 10 characters.
-	xQueue = xQueueCreate( 10, sizeof( char ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Post some characters that will be used within an ISR.  If the queue
-	// is full then this task will block for xBlockTime ticks.
-	cValueToPost = 'a';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-	cValueToPost = 'b';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-
-	// ... keep posting characters ... this task may block when the queue
-	// becomes full.
-
-	cValueToPost = 'c';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
- }
-
- // ISR that outputs all the characters received on the queue.
- void vISR_Routine( void )
- {
- portBASE_TYPE xTaskWokenByReceive = pdFALSE;
- char cRxedChar;
-
-	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
-	{
-		// A character was received.  Output the character now.
-		vOutputCharacter( cRxedChar );
-
-		// If removing the character from the queue woke the task that was
-		// posting onto the queue cTaskWokenByReceive will have been set to
-		// pdTRUE.  No matter how many times this loop iterates only one
-		// task will be woken.
-	}
-
-	if( cTaskWokenByPost != ( char ) pdFALSE;
-	{
-		taskYIELD ();
-	}
- }
- 
- * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ); - -/* - * Utilities to query queue that are safe to use from an ISR. These utilities - * should be used only from witin an ISR, or within a critical section. - */ -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); - - -/* - * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). - * Likewise xQueueAltGenericReceive() is an alternative version of - * xQueueGenericReceive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); -#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_FRONT ) -#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) -#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( xQueue, pvBuffer, xTicksToWait, pdFALSE ) -#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( xQueue, pvBuffer, xTicksToWait, pdTRUE ) - -/* - * The functions defined above are for passing data to and from tasks. The - * functions below are the equivalents for passing data to and from - * co-routines. - * - * These functions are called from the co-routine macro implementation and - * should not be called directly from application code. Instead use the macro - * wrappers defined within croutine.h. - */ -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); - -/* - * For internal use only. Use xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting() instead of calling these functions directly. - */ -xQueueHandle xQueueCreateMutex( void ); -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); - -/* - * For internal use only. Use xSemaphoreTakeMutexRecursive() or - * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. - */ -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ); -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ); - -/* - * The registry is provided as a means for kernel aware debuggers to - * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add - * a queue, semaphore or mutex handle to the registry if you want the handle - * to be available to a kernel aware debugger. If you are not using a kernel - * aware debugger then this function can be ignored. - * - * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the - * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 - * within FreeRTOSConfig.h for the registry to be available. Its value - * does not effect the number of queues, semaphores and mutexes that can be - * created - just the number that the registry can hold. - * - * @param xQueue The handle of the queue being added to the registry. This - * is the handle returned by a call to xQueueCreate(). Semaphore and mutex - * handles can also be passed in here. - * - * @param pcName The name to be associated with the handle. This is the - * name that the kernel aware debugger will display. - */ -#if configQUEUE_REGISTRY_SIZE > 0 - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); -#endif - - - - -#ifdef __cplusplus -} -#endif - -#endif /* QUEUE_H */ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include queue.h" +#endif + + + + +#ifndef QUEUE_H +#define QUEUE_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "mpu_wrappers.h" + + +typedef void * xQueueHandle; + + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + + +/** + * queue. h + *
+ xQueueHandle xQueueCreate(
+							  unsigned portBASE_TYPE uxQueueLength,
+							  unsigned portBASE_TYPE uxItemSize
+						  );
+ * 
+ * + * Creates a new queue instance. This allocates the storage required by the + * new queue and returns a handle for the queue. + * + * @param uxQueueLength The maximum number of items that the queue can contain. + * + * @param uxItemSize The number of bytes each item in the queue will require. + * Items are queued by copy, not by reference, so this is the number of bytes + * that will be copied for each posted item. Each item on the queue must be + * the same size. + * + * @return If the queue is successfully create then a handle to the newly + * created queue is returned. If the queue cannot be created then 0 is + * returned. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+	if( xQueue1 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue2 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueCreate xQueueCreate + * \ingroup QueueManagement + */ +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToToFront(
+								   xQueueHandle	xQueue,
+								   const	void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the front of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_FRONT ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBack(
+								   xQueueHandle	xQueue,
+								   const	void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the back of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the queue + * is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSend(
+							  xQueueHandle xQueue,
+							  const void * pvItemToQueue,
+							  portTickType xTicksToWait
+						 );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). It is included for + * backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToFront() and xQueueSendToBack() macros. It is + * equivalent to xQueueSendToBack(). + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSend(
+									xQueueHandle xQueue,
+									const void * pvItemToQueue,
+									portTickType xTicksToWait
+									portBASE_TYPE xCopyPosition
+								);
+ * 
+ * + * It is preferred that the macros xQueueSend(), xQueueSendToFront() and + * xQueueSendToBack() are used in place of calling this function directly. + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueuePeek(
+							 xQueueHandle xQueue,
+							 void *pvBuffer,
+							 portTickType xTicksToWait
+						 );
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue without removing the item from the queue. + * The item is received by copy so a buffer of adequate size must be + * provided. The number of bytes copied into the buffer was defined when + * the queue was created. + * + * Successfully received items remain on the queue so will be returned again + * by the next call, or a call to xQueueReceive(). + * + * This macro must not be used in an interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue + * is empty. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to peek the data from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Peek a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask, but the item still remains on the queue.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( xQueue, pvBuffer, xTicksToWait, pdTRUE ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceive(
+								 xQueueHandle xQueue,
+								 void *pvBuffer,
+								 portTickType xTicksToWait
+							);
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * Successfully received items are removed from the queue. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. xQueueReceive() will return immediately if xTicksToWait + * is zero and the queue is empty. The time is defined in tick periods so the + * constant portTICK_RATE_MS should be used to convert to real time if this is + * required. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( xQueue, pvBuffer, xTicksToWait, pdFALSE ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericReceive(
+									   xQueueHandle	xQueue,
+									   void	*pvBuffer,
+									   portTickType	xTicksToWait
+									   portBASE_TYPE	xJustPeek
+									);
+ * + * It is preferred that the macro xQueueReceive() be used rather than calling + * this function directly. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueueGenericReceive() will return immediately if the queue is empty and + * xTicksToWait is 0. + * + * @param xJustPeek When set to true, the item received from the queue is not + * actually removed from the queue - meaning a subsequent call to + * xQueueReceive() will return the same item. When set to false, the item + * being received from the queue is also removed from the queue. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); + +/** + * queue. h + *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
+ * + * Return the number of messages stored in a queue. + * + * @param xQueue A handle to the queue being queried. + * + * @return The number of messages available in the queue. + * + * \page uxQueueMessagesWaiting uxQueueMessagesWaiting + * \ingroup QueueManagement + */ +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); + +/** + * queue. h + *
void vQueueDelete( xQueueHandle xQueue );
+ * + * Delete a queue - freeing all the memory allocated for storing of items + * placed on the queue. + * + * @param xQueue A handle to the queue to be deleted. + * + * \page vQueueDelete vQueueDelete + * \ingroup QueueManagement + */ +void vQueueDelete( xQueueHandle xQueue ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToFrontFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the front of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPrioritTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_FRONT ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBackFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the back of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendFromISR(
+									 xQueueHandle pxQueue,
+									 const void *pvItemToQueue,
+									 portBASE_TYPE *pxHigherPriorityTaskWoken
+								);
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). It is included + * for backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() + * macros. + * + * Post an item to the back of a queue. It is safe to use this function from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		// Actual macro used here is port specific.
+		taskYIELD_FROM_ISR ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSendFromISR(
+										   xQueueHandle	pxQueue,
+										   const	void	*pvItemToQueue,
+										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
+										   portBASE_TYPE	xCopyPosition
+									   );
+ 
+ * + * It is preferred that the macros xQueueSendFromISR(), + * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place + * of calling this function directly. + * + * Post an item on a queue. It is safe to use this function from within an + * interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWokenByPost;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWokenByPost = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post each byte.
+		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.  Note that the
+	// name of the yield function required is port specific.
+	if( xHigherPriorityTaskWokenByPost )
+	{
+		taskYIELD_YIELD_FROM_ISR();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceiveFromISR(
+									   xQueueHandle	pxQueue,
+									   void	*pvBuffer,
+									   portBASE_TYPE	*pxTaskWoken
+								   );
+ * 
+ * + * Receive an item from a queue. It is safe to use this function from within an + * interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param pxTaskWoken A task may be blocked waiting for space to become + * available on the queue. If xQueueReceiveFromISR causes such a task to + * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will + * remain unchanged. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+
+ xQueueHandle xQueue;
+
+ // Function to create a queue and post some values.
+ void vAFunction( void *pvParameters )
+ {
+ char cValueToPost;
+ const portTickType xBlockTime = ( portTickType )0xff;
+
+	// Create a queue capable of containing 10 characters.
+	xQueue = xQueueCreate( 10, sizeof( char ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Post some characters that will be used within an ISR.  If the queue
+	// is full then this task will block for xBlockTime ticks.
+	cValueToPost = 'a';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+	cValueToPost = 'b';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+
+	// ... keep posting characters ... this task may block when the queue
+	// becomes full.
+
+	cValueToPost = 'c';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+ }
+
+ // ISR that outputs all the characters received on the queue.
+ void vISR_Routine( void )
+ {
+ portBASE_TYPE xTaskWokenByReceive = pdFALSE;
+ char cRxedChar;
+
+	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
+	{
+		// A character was received.  Output the character now.
+		vOutputCharacter( cRxedChar );
+
+		// If removing the character from the queue woke the task that was
+		// posting onto the queue cTaskWokenByReceive will have been set to
+		// pdTRUE.  No matter how many times this loop iterates only one
+		// task will be woken.
+	}
+
+	if( cTaskWokenByPost != ( char ) pdFALSE;
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ); + +/* + * Utilities to query queue that are safe to use from an ISR. These utilities + * should be used only from witin an ISR, or within a critical section. + */ +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); + + +/* + * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). + * Likewise xQueueAltGenericReceive() is an alternative version of + * xQueueGenericReceive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); +#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_FRONT ) +#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) +#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( xQueue, pvBuffer, xTicksToWait, pdFALSE ) +#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( xQueue, pvBuffer, xTicksToWait, pdTRUE ) + +/* + * The functions defined above are for passing data to and from tasks. The + * functions below are the equivalents for passing data to and from + * co-routines. + * + * These functions are called from the co-routine macro implementation and + * should not be called directly from application code. Instead use the macro + * wrappers defined within croutine.h. + */ +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); + +/* + * For internal use only. Use xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting() instead of calling these functions directly. + */ +xQueueHandle xQueueCreateMutex( void ); +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); + +/* + * For internal use only. Use xSemaphoreTakeMutexRecursive() or + * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. + */ +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ); +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ); + +/* + * The registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add + * a queue, semaphore or mutex handle to the registry if you want the handle + * to be available to a kernel aware debugger. If you are not using a kernel + * aware debugger then this function can be ignored. + * + * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the + * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 + * within FreeRTOSConfig.h for the registry to be available. Its value + * does not effect the number of queues, semaphores and mutexes that can be + * created - just the number that the registry can hold. + * + * @param xQueue The handle of the queue being added to the registry. This + * is the handle returned by a call to xQueueCreate(). Semaphore and mutex + * handles can also be passed in here. + * + * @param pcName The name to be associated with the handle. This is the + * name that the kernel aware debugger will display. + */ +#if configQUEUE_REGISTRY_SIZE > 0 + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); +#endif + + + + +#ifdef __cplusplus +} +#endif + +#endif /* QUEUE_H */ + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/semphr.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/semphr.h index 3984e4bb9..1d6f34430 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/semphr.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/semphr.h @@ -1,711 +1,711 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include semphr.h" -#endif - -#ifndef SEMAPHORE_H -#define SEMAPHORE_H - -#include "queue.h" - -typedef xQueueHandle xSemaphoreHandle; - -#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1 ) -#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0 ) -#define semGIVE_BLOCK_TIME ( ( portTickType ) 0 ) - - -/** - * semphr. h - *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
- * - * Macro that implements a semaphore by using the existing queue mechanism. - * The queue length is 1 as this is a binary semaphore. The data size is 0 - * as we don't want to actually store any data - we just want to know if the - * queue is empty or full. - * - * This type of semaphore can be used for pure synchronisation between tasks or - * between an interrupt and a task. The semaphore need not be given back once - * obtained, so one task/interrupt can continuously 'give' the semaphore while - * another continuously 'takes' the semaphore. For this reason this type of - * semaphore does not use a priority inheritance mechanism. For an alternative - * that does use priority inheritance see xSemaphoreCreateMutex(). - * - * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
-    // This is a macro so pass the variable in directly.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary - * \ingroup Semaphores - */ -#define vSemaphoreCreateBinary( xSemaphore ) { \ - xSemaphore = xQueueCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH ); \ - if( xSemaphore != NULL ) \ - { \ - xSemaphoreGive( xSemaphore ); \ - } \ - } - -/** - * semphr. h - *
xSemaphoreTake( 
- *                   xSemaphoreHandle xSemaphore, 
- *                   portTickType xBlockTime 
- *               )
- * - * Macro to obtain a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). - * - * @param xSemaphore A handle to the semaphore being taken - obtained when - * the semaphore was created. - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. A block - * time of portMAX_DELAY can be used to block indefinitely (provided - * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). - * - * @return pdTRUE if the semaphore was obtained. pdFALSE - * if xBlockTime expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- // A task that creates a semaphore.
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
- }
-
- // A task that uses the semaphore.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xSemaphore != NULL )
-    {
-        // See if we can obtain the semaphore.  If the semaphore is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the semaphore and can now access the
-            // shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource.  Release the 
-            // semaphore.
-            xSemaphoreGive( xSemaphore );
-        }
-        else
-        {
-            // We could not obtain the semaphore and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTake xSemaphoreTake - * \ingroup Semaphores - */ -#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) xSemaphore, NULL, xBlockTime, pdFALSE ) - -/** - * semphr. h - * xSemaphoreTakeRecursive( - * xSemaphoreHandle xMutex, - * portTickType xBlockTime - * ) - * - * Macro to recursively obtain, or 'take', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being obtained. This is the - * handle returned by xSemaphoreCreateRecursiveMutex(); - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. If - * the task already owns the semaphore then xSemaphoreTakeRecursive() will - * return immediately no matter what the value of xBlockTime. - * - * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime - * expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, but instead buried in a more complex
-			// call structure.  This is just for illustrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive - * \ingroup Semaphores - */ -#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( xMutex, xBlockTime ) - - -/* - * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) xSemaphore, NULL, xBlockTime, pdFALSE ) - -/** - * semphr. h - *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). - * - * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for - * an alternative which can be used from an ISR. - * - * This macro must also not be used on semaphores created using - * xSemaphoreCreateRecursiveMutex(). - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. - * Semaphores are implemented using queues. An error can occur if there is - * no space on the queue to post a message - indicating that the - * semaphore was not first obtained correctly. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-        {
-            // We would expect this call to fail because we cannot give
-            // a semaphore without first "taking" it!
-        }
-
-        // Obtain the semaphore - don't block if the semaphore is not
-        // immediately available.
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
-        {
-            // We now have the semaphore and can access the shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource so can free the
-            // semaphore.
-            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-            {
-                // We would not expect this call to fail because we must have
-                // obtained the semaphore to get here.
-            }
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGive xSemaphoreGive - * \ingroup Semaphores - */ -#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) xSemaphore, NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
- * - * Macro to recursively release, or 'give', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being released, or 'given'. This is the - * handle returned by xSemaphoreCreateMutex(); - * - * @return pdTRUE if the semaphore was given. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, it would be more likely that the calls
-			// to xSemaphoreGiveRecursive() would be called as a call stack
-			// unwound.  This is just for demonstrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive - * \ingroup Semaphores - */ -#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( xMutex ) - -/* - * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) xSemaphore, NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
- xSemaphoreGiveFromISR( 
-                          xSemaphoreHandle xSemaphore, 
-                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
-                      )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). - * - * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) - * must not be used with this macro. - * - * This macro can be used from an ISR. - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. - * - * Example usage: -
- \#define LONG_TIME 0xffff
- \#define TICKS_TO_WAIT	10
- xSemaphoreHandle xSemaphore = NULL;
-
- // Repetitive task.
- void vATask( void * pvParameters )
- {
-    for( ;; )
-    {
-        // We want this task to run every 10 ticks of a timer.  The semaphore 
-        // was created before this task was started.
-
-        // Block waiting for the semaphore to become available.
-        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
-        {
-            // It is time to execute.
-
-            // ...
-
-            // We have finished our task.  Return to the top of the loop where
-            // we will block on the semaphore until it is time to execute 
-            // again.  Note when using the semaphore for synchronisation with an
-			// ISR in this manner there is no need to 'give' the semaphore back.
-        }
-    }
- }
-
- // Timer ISR
- void vTimerISR( void * pvParameters )
- {
- static unsigned char ucLocalTickCount = 0;
- static signed portBASE_TYPE xHigherPriorityTaskWoken;
-
-    // A timer tick has occurred.
-
-    // ... Do other time functions.
-
-    // Is it time for vATask () to run?
-	xHigherPriorityTaskWoken = pdFALSE;
-    ucLocalTickCount++;
-    if( ucLocalTickCount >= TICKS_TO_WAIT )
-    {
-        // Unblock the task by releasing the semaphore.
-        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
-
-        // Reset the count so we release the semaphore again in 10 ticks time.
-        ucLocalTickCount = 0;
-    }
-
-    if( xHigherPriorityTaskWoken != pdFALSE )
-    {
-        // We can force a context switch here.  Context switching from an
-        // ISR uses port specific syntax.  Check the demo task for your port
-        // to find the syntax required.
-    }
- }
- 
- * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR - * \ingroup Semaphores - */ -#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) xSemaphore, NULL, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateMutex( void )
- * - * Macro that implements a mutex semaphore by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the xSemaphoreTake() - * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and - * xSemaphoreGiveRecursive() macros should not be used. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateMutex() xQueueCreateMutex() - - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
- * - * Macro that implements a recursive mutex by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the - * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The - * xSemaphoreTake() and xSemaphoreGive() macros should not be used. - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateRecursiveMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex() - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
- * - * Macro that creates a counting semaphore by using the existing - * queue mechanism. - * - * Counting semaphores are typically used for two things: - * - * 1) Counting events. - * - * In this usage scenario an event handler will 'give' a semaphore each time - * an event occurs (incrementing the semaphore count value), and a handler - * task will 'take' a semaphore each time it processes an event - * (decrementing the semaphore count value). The count value is therefore - * the difference between the number of events that have occurred and the - * number that have been processed. In this case it is desirable for the - * initial count value to be zero. - * - * 2) Resource management. - * - * In this usage scenario the count value indicates the number of resources - * available. To obtain control of a resource a task must first obtain a - * semaphore - decrementing the semaphore count value. When the count value - * reaches zero there are no free resources. When a task finishes with the - * resource it 'gives' the semaphore back - incrementing the semaphore count - * value. In this case it is desirable for the initial count value to be - * equal to the maximum count value, indicating that all resources are free. - * - * @param uxMaxCount The maximum count value that can be reached. When the - * semaphore reaches this value it can no longer be 'given'. - * - * @param uxInitialCount The count value assigned to the semaphore when it is - * created. - * - * @return Handle to the created semaphore. Null if the semaphore could not be - * created. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
- xSemaphoreHandle xSemaphore = NULL;
-
-    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
-    // The max value to which the semaphore can count should be 10, and the
-    // initial value assigned to the count should be 0.
-    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting - * \ingroup Semaphores - */ -#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( uxMaxCount, uxInitialCount ) - - -#endif /* SEMAPHORE_H */ - - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include semphr.h" +#endif + +#ifndef SEMAPHORE_H +#define SEMAPHORE_H + +#include "queue.h" + +typedef xQueueHandle xSemaphoreHandle; + +#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1 ) +#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0 ) +#define semGIVE_BLOCK_TIME ( ( portTickType ) 0 ) + + +/** + * semphr. h + *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
+ * + * Macro that implements a semaphore by using the existing queue mechanism. + * The queue length is 1 as this is a binary semaphore. The data size is 0 + * as we don't want to actually store any data - we just want to know if the + * queue is empty or full. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
+    // This is a macro so pass the variable in directly.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary + * \ingroup Semaphores + */ +#define vSemaphoreCreateBinary( xSemaphore ) { \ + xSemaphore = xQueueCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH ); \ + if( xSemaphore != NULL ) \ + { \ + xSemaphoreGive( xSemaphore ); \ + } \ + } + +/** + * semphr. h + *
xSemaphoreTake( 
+ *                   xSemaphoreHandle xSemaphore, 
+ *                   portTickType xBlockTime 
+ *               )
+ * + * Macro to obtain a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). + * + * @param xSemaphore A handle to the semaphore being taken - obtained when + * the semaphore was created. + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. A block + * time of portMAX_DELAY can be used to block indefinitely (provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). + * + * @return pdTRUE if the semaphore was obtained. pdFALSE + * if xBlockTime expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // A task that creates a semaphore.
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+ }
+
+ // A task that uses the semaphore.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xSemaphore != NULL )
+    {
+        // See if we can obtain the semaphore.  If the semaphore is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the semaphore and can now access the
+            // shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource.  Release the 
+            // semaphore.
+            xSemaphoreGive( xSemaphore );
+        }
+        else
+        {
+            // We could not obtain the semaphore and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTake xSemaphoreTake + * \ingroup Semaphores + */ +#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) xSemaphore, NULL, xBlockTime, pdFALSE ) + +/** + * semphr. h + * xSemaphoreTakeRecursive( + * xSemaphoreHandle xMutex, + * portTickType xBlockTime + * ) + * + * Macro to recursively obtain, or 'take', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being obtained. This is the + * handle returned by xSemaphoreCreateRecursiveMutex(); + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. If + * the task already owns the semaphore then xSemaphoreTakeRecursive() will + * return immediately no matter what the value of xBlockTime. + * + * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime + * expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, but instead buried in a more complex
+			// call structure.  This is just for illustrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive + * \ingroup Semaphores + */ +#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( xMutex, xBlockTime ) + + +/* + * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) xSemaphore, NULL, xBlockTime, pdFALSE ) + +/** + * semphr. h + *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). + * + * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for + * an alternative which can be used from an ISR. + * + * This macro must also not be used on semaphores created using + * xSemaphoreCreateRecursiveMutex(). + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. + * Semaphores are implemented using queues. An error can occur if there is + * no space on the queue to post a message - indicating that the + * semaphore was not first obtained correctly. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+        {
+            // We would expect this call to fail because we cannot give
+            // a semaphore without first "taking" it!
+        }
+
+        // Obtain the semaphore - don't block if the semaphore is not
+        // immediately available.
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
+        {
+            // We now have the semaphore and can access the shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource so can free the
+            // semaphore.
+            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+            {
+                // We would not expect this call to fail because we must have
+                // obtained the semaphore to get here.
+            }
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGive xSemaphoreGive + * \ingroup Semaphores + */ +#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) xSemaphore, NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
+ * + * Macro to recursively release, or 'give', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being released, or 'given'. This is the + * handle returned by xSemaphoreCreateMutex(); + * + * @return pdTRUE if the semaphore was given. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, it would be more likely that the calls
+			// to xSemaphoreGiveRecursive() would be called as a call stack
+			// unwound.  This is just for demonstrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive + * \ingroup Semaphores + */ +#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( xMutex ) + +/* + * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) xSemaphore, NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
+ xSemaphoreGiveFromISR( 
+                          xSemaphoreHandle xSemaphore, 
+                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR. + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. + * + * Example usage: +
+ \#define LONG_TIME 0xffff
+ \#define TICKS_TO_WAIT	10
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // Repetitive task.
+ void vATask( void * pvParameters )
+ {
+    for( ;; )
+    {
+        // We want this task to run every 10 ticks of a timer.  The semaphore 
+        // was created before this task was started.
+
+        // Block waiting for the semaphore to become available.
+        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
+        {
+            // It is time to execute.
+
+            // ...
+
+            // We have finished our task.  Return to the top of the loop where
+            // we will block on the semaphore until it is time to execute 
+            // again.  Note when using the semaphore for synchronisation with an
+			// ISR in this manner there is no need to 'give' the semaphore back.
+        }
+    }
+ }
+
+ // Timer ISR
+ void vTimerISR( void * pvParameters )
+ {
+ static unsigned char ucLocalTickCount = 0;
+ static signed portBASE_TYPE xHigherPriorityTaskWoken;
+
+    // A timer tick has occurred.
+
+    // ... Do other time functions.
+
+    // Is it time for vATask () to run?
+	xHigherPriorityTaskWoken = pdFALSE;
+    ucLocalTickCount++;
+    if( ucLocalTickCount >= TICKS_TO_WAIT )
+    {
+        // Unblock the task by releasing the semaphore.
+        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
+
+        // Reset the count so we release the semaphore again in 10 ticks time.
+        ucLocalTickCount = 0;
+    }
+
+    if( xHigherPriorityTaskWoken != pdFALSE )
+    {
+        // We can force a context switch here.  Context switching from an
+        // ISR uses port specific syntax.  Check the demo task for your port
+        // to find the syntax required.
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR + * \ingroup Semaphores + */ +#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) xSemaphore, NULL, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateMutex( void )
+ * + * Macro that implements a mutex semaphore by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the xSemaphoreTake() + * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and + * xSemaphoreGiveRecursive() macros should not be used. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateMutex() xQueueCreateMutex() + + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
+ * + * Macro that implements a recursive mutex by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the + * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The + * xSemaphoreTake() and xSemaphoreGive() macros should not be used. + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateRecursiveMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex() + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
+ * + * Macro that creates a counting semaphore by using the existing + * queue mechanism. + * + * Counting semaphores are typically used for two things: + * + * 1) Counting events. + * + * In this usage scenario an event handler will 'give' a semaphore each time + * an event occurs (incrementing the semaphore count value), and a handler + * task will 'take' a semaphore each time it processes an event + * (decrementing the semaphore count value). The count value is therefore + * the difference between the number of events that have occurred and the + * number that have been processed. In this case it is desirable for the + * initial count value to be zero. + * + * 2) Resource management. + * + * In this usage scenario the count value indicates the number of resources + * available. To obtain control of a resource a task must first obtain a + * semaphore - decrementing the semaphore count value. When the count value + * reaches zero there are no free resources. When a task finishes with the + * resource it 'gives' the semaphore back - incrementing the semaphore count + * value. In this case it is desirable for the initial count value to be + * equal to the maximum count value, indicating that all resources are free. + * + * @param uxMaxCount The maximum count value that can be reached. When the + * semaphore reaches this value it can no longer be 'given'. + * + * @param uxInitialCount The count value assigned to the semaphore when it is + * created. + * + * @return Handle to the created semaphore. Null if the semaphore could not be + * created. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+ xSemaphoreHandle xSemaphore = NULL;
+
+    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
+    // The max value to which the semaphore can count should be 10, and the
+    // initial value assigned to the count should be 0.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting + * \ingroup Semaphores + */ +#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( uxMaxCount, uxInitialCount ) + + +#endif /* SEMAPHORE_H */ + + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/task.h index df059e001..6a0c53250 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/task.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/include/task.h @@ -1,1263 +1,1263 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include task.h" -#endif - - - -#ifndef TASK_H -#define TASK_H - -#include "portable.h" -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * MACROS AND DEFINITIONS - *----------------------------------------------------------*/ - -#define tskKERNEL_VERSION_NUMBER "V6.0.4" - -/** - * task. h - * - * Type by which tasks are referenced. For example, a call to xTaskCreate - * returns (via a pointer parameter) an xTaskHandle variable that can then - * be used as a parameter to vTaskDelete to delete the task. - * - * \page xTaskHandle xTaskHandle - * \ingroup Tasks - */ -typedef void * xTaskHandle; - -/* - * Used internally only. - */ -typedef struct xTIME_OUT -{ - portBASE_TYPE xOverflowCount; - portTickType xTimeOnEntering; -} xTimeOutType; - -/* - * Defines the memory ranges allocated to the task when an MPU is used. - */ -typedef struct xMEMORY_REGION -{ - void *pvBaseAddress; - unsigned long ulLengthInBytes; - unsigned long ulParameters; -} xMemoryRegion; - -/* - * Parameters required to create an MPU protected task. - */ -typedef struct xTASK_PARAMTERS -{ - pdTASK_CODE pvTaskCode; - const signed char * const pcName; - unsigned short usStackDepth; - void *pvParameters; - unsigned portBASE_TYPE uxPriority; - portSTACK_TYPE *puxStackBuffer; - xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; -} xTaskParameters; - -/* - * Defines the priority used by the idle task. This must not be modified. - * - * \ingroup TaskUtils - */ -#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0 ) - -/** - * task. h - * - * Macro for forcing a context switch. - * - * \page taskYIELD taskYIELD - * \ingroup SchedulerControl - */ -#define taskYIELD() portYIELD() - -/** - * task. h - * - * Macro to mark the start of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskENTER_CRITICAL taskENTER_CRITICAL - * \ingroup SchedulerControl - */ -#define taskENTER_CRITICAL() portENTER_CRITICAL() - -/** - * task. h - * - * Macro to mark the end of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskEXIT_CRITICAL taskEXIT_CRITICAL - * \ingroup SchedulerControl - */ -#define taskEXIT_CRITICAL() portEXIT_CRITICAL() - -/** - * task. h - * - * Macro to disable all maskable interrupts. - * - * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() - -/** - * task. h - * - * Macro to enable microcontroller interrupts. - * - * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() - -/* Definitions returned by xTaskGetSchedulerState(). */ -#define taskSCHEDULER_NOT_STARTED 0 -#define taskSCHEDULER_RUNNING 1 -#define taskSCHEDULER_SUSPENDED 2 - -/*----------------------------------------------------------- - * TASK CREATION API - *----------------------------------------------------------*/ - -/** - * task. h - *
- portBASE_TYPE xTaskCreate(
-							  pdTASK_CODE pvTaskCode,
-							  const char * const pcName,
-							  unsigned short usStackDepth,
-							  void *pvParameters,
-							  unsigned portBASE_TYPE uxPriority,
-							  xTaskHandle *pvCreatedTask
-						  );
- * - * Create a new task and add it to the list of tasks that are ready to run. - * - * xTaskCreate() can only be used to create a task that has unrestricted - * access to the entire microcontroller memory map. Systems that include MPU - * support can alternatively create an MPU constrained task using - * xTaskCreateRestricted(). - * - * @param pvTaskCode Pointer to the task entry function. Tasks - * must be implemented to never return (i.e. continuous loop). - * - * @param pcName A descriptive name for the task. This is mainly used to - * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default - * is 16. - * - * @param usStackDepth The size of the task stack specified as the number of - * variables the stack can hold - not the number of bytes. For example, if - * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes - * will be allocated for stack storage. - * - * @param pvParameters Pointer that will be used as the parameter for the task - * being created. - * - * @param uxPriority The priority at which the task should run. Systems that - * include MPU support can optionally create tasks in a privileged (system) - * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For - * example, to create a privileged task at priority 2 the uxPriority parameter - * should be set to ( 2 | portPRIVILEGE_BIT ). - * - * @param pvCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
- // Task to be created.
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-	 }
- }
-
- // Function that creates a task.
- void vOtherFunction( void )
- {
- static unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
-	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
-	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
-	 // the new task attempts to access it.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup xTaskCreate xTaskCreate - * \ingroup Tasks - */ -#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) - -/** - * task. h - *
- portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
- * - * xTaskCreateRestricted() should only be used in systems that include an MPU - * implementation. - * - * Create a new task and add it to the list of tasks that are ready to run. - * The function parameters define the memory regions and associated access - * permissions allocated to the task. - * - * @param pxTaskDefinition Pointer to a structure that contains a member - * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API - * documentation) plus an optional stack buffer and the memory region - * definitions. - * - * @param pxCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
-// Create an xTaskParameters structure that defines the task to be created.
-static const xTaskParameters xCheckTaskParameters =
-{
-	vATask,		// pvTaskCode - the function that implements the task.
-	"ATask",	// pcName - just a text name for the task to assist debugging.
-	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
-	NULL,		// pvParameters - passed into the task function as the function parameters.
-	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
-	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
-
-	// xRegions - Allocate up to three separate memory regions for access by
-	// the task, with appropriate access permissions.  Different processors have
-	// different memory alignment requirements - refer to the FreeRTOS documentation
-	// for full information.
-	{											
-		// Base address					Length	Parameters
-        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
-        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
-        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
-	}
-};
-
-int main( void )
-{
-xTaskHandle xHandle;
-
-	// Create a task from the const structure defined above.  The task handle
-	// is requested (the second parameter is not NULL) but in this case just for
-	// demonstration purposes as its not actually used.
-	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
-
-	// Start the scheduler.
-	vTaskStartScheduler();
-
-	// Will only get here if there was insufficient memory to create the idle
-	// task.
-	for( ;; );
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) - -/** - * task. h - *
- void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
- * - * Memory regions are assigned to a restricted task when the task is created by - * a call to xTaskCreateRestricted(). These regions can be redefined using - * vTaskAllocateMPURegions(). - * - * @param xTask The handle of the task being updated. - * - * @param xRegions A pointer to an xMemoryRegion structure that contains the - * new memory region definitions. - * - * Example usage: -
-// Define an array of xMemoryRegion structures that configures an MPU region
-// allowing read/write access for 1024 bytes starting at the beginning of the
-// ucOneKByte array.  The other two of the maximum 3 definable regions are
-// unused so set to zero.
-static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
-{											
-	// Base address		Length		Parameters
-	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
-	{ 0,				0,			0 },
-	{ 0,				0,			0 }
-};
-
-void vATask( void *pvParameters )
-{
-	// This task was created such that it has access to certain regions of
-	// memory as defined by the MPU configuration.  At some point it is 
-	// desired that these MPU regions are replaced with that defined in the
-	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
-	// for this purpose.  NULL is used as the task handle to indicate that this
-	// function should modify the MPU regions of the calling task.
-	vTaskAllocateMPURegions( NULL, xAltRegions );
-	
-	// Now the task can continue its function, but from this point on can only
-	// access its stack and the ucOneKByte array (unless any other statically
-	// defined or shared regions have been declared elsewhere).
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelete( xTaskHandle pxTask );
- * - * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Remove a task from the RTOS real time kernels management. The task being - * deleted will be removed from all ready, blocked, suspended and event lists. - * - * NOTE: The idle task is responsible for freeing the kernel allocated - * memory from tasks that have been deleted. It is therefore important that - * the idle task is not starved of microcontroller processing time if your - * application makes any calls to vTaskDelete (). Memory allocated by the - * task code is not automatically freed, and should be freed before the task - * is deleted. - * - * See the demo application file death.c for sample code that utilises - * vTaskDelete (). - * - * @param pxTask The handle of the task to be deleted. Passing NULL will - * cause the calling task to be deleted. - * - * Example usage: -
- void vOtherFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup vTaskDelete vTaskDelete - * \ingroup Tasks - */ -void vTaskDelete( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; - - -/*----------------------------------------------------------- - * TASK CONTROL API - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskDelay( portTickType xTicksToDelay );
- * - * Delay a task for a given number of ticks. The actual time that the - * task remains blocked depends on the tick rate. The constant - * portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * - * vTaskDelay() specifies a time at which the task wishes to unblock relative to - * the time at which vTaskDelay() is called. For example, specifying a block - * period of 100 ticks will cause the task to unblock 100 ticks after - * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method - * of controlling the frequency of a cyclical task as the path taken through the - * code, as well as other task and interrupt activity, will effect the frequency - * at which vTaskDelay() gets called and therefore the time at which the task - * next executes. See vTaskDelayUntil() for an alternative API function designed - * to facilitate fixed frequency execution. It does this by specifying an - * absolute time (rather than a relative time) at which the calling task should - * unblock. - * - * @param xTicksToDelay The amount of time, in tick periods, that - * the calling task should block. - * - * Example usage: - - void vTaskFunction( void * pvParameters ) - { - void vTaskFunction( void * pvParameters ) - { - // Block for 500ms. - const portTickType xDelay = 500 / portTICK_RATE_MS; - - for( ;; ) - { - // Simply toggle the LED every 500ms, blocking between each toggle. - vToggleLED(); - vTaskDelay( xDelay ); - } - } - - * \defgroup vTaskDelay vTaskDelay - * \ingroup TaskCtrl - */ -void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
- * - * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Delay a task until a specified time. This function can be used by cyclical - * tasks to ensure a constant execution frequency. - * - * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will - * cause a task to block for the specified number of ticks from the time vTaskDelay () is - * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed - * execution frequency as the time between a task starting to execute and that task - * calling vTaskDelay () may not be fixed [the task may take a different path though the - * code between calls, or may get interrupted or preempted a different number of times - * each time it executes]. - * - * Whereas vTaskDelay () specifies a wake time relative to the time at which the function - * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to - * unblock. - * - * The constant portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the - * task was last unblocked. The variable must be initialised with the current time - * prior to its first use (see the example below). Following this the variable is - * automatically updated within vTaskDelayUntil (). - * - * @param xTimeIncrement The cycle time period. The task will be unblocked at - * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the - * same xTimeIncrement parameter value will cause the task to execute with - * a fixed interface period. - * - * Example usage: -
- // Perform an action every 10 ticks.
- void vTaskFunction( void * pvParameters )
- {
- portTickType xLastWakeTime;
- const portTickType xFrequency = 10;
-
-	 // Initialise the xLastWakeTime variable with the current time.
-	 xLastWakeTime = xTaskGetTickCount ();
-	 for( ;; )
-	 {
-		 // Wait for the next cycle.
-		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
-
-		 // Perform action here.
-	 }
- }
-   
- * \defgroup vTaskDelayUntil vTaskDelayUntil - * \ingroup TaskCtrl - */ -void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
- * - * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Obtain the priority of any task. - * - * @param pxTask Handle of the task to be queried. Passing a NULL - * handle results in the priority of the calling task being returned. - * - * @return The priority of pxTask. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to obtain the priority of the created task.
-	 // It was created with tskIDLE_PRIORITY, but may have changed
-	 // it itself.
-	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
-	 {
-		 // The task has changed it's priority.
-	 }
-
-	 // ...
-
-	 // Is our priority higher than the created task?
-	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
-	 {
-		 // Our priority (obtained using NULL handle) is higher.
-	 }
- }
-   
- * \defgroup uxTaskPriorityGet uxTaskPriorityGet - * \ingroup TaskCtrl - */ -unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
- * - * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Set the priority of any task. - * - * A context switch will occur before the function returns if the priority - * being set is higher than the currently executing task. - * - * @param pxTask Handle to the task for which the priority is being set. - * Passing a NULL handle results in the priority of the calling task being set. - * - * @param uxNewPriority The priority to which the task will be set. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to raise the priority of the created task.
-	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
-
-	 // ...
-
-	 // Use a NULL handle to raise our priority to the same value.
-	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
- }
-   
- * \defgroup vTaskPrioritySet vTaskPrioritySet - * \ingroup TaskCtrl - */ -void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Suspend any task. When suspended a task will never get any microcontroller - * processing time, no matter what its priority. - * - * Calls to vTaskSuspend are not accumulative - - * i.e. calling vTaskSuspend () twice on the same task still only requires one - * call to vTaskResume () to ready the suspended task. - * - * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL - * handle will cause the calling task to be suspended. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Suspend ourselves.
-	 vTaskSuspend( NULL );
-
-	 // We cannot get here unless another task calls vTaskResume
-	 // with our handle as the parameter.
- }
-   
- * \defgroup vTaskSuspend vTaskSuspend - * \ingroup TaskCtrl - */ -void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskResume( xTaskHandle pxTaskToResume );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Resumes a suspended task. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * vTaskResume (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Resume the suspended task ourselves.
-	 vTaskResume( xHandle );
-
-	 // The created task will once again get microcontroller processing
-	 // time in accordance with it priority within the system.
- }
-   
- * \defgroup vTaskResume vTaskResume - * \ingroup TaskCtrl - */ -void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
- * - * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * An implementation of vTaskResume() that can be called from within an ISR. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * xTaskResumeFromISR (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * \defgroup vTaskResumeFromISR vTaskResumeFromISR - * \ingroup TaskCtrl - */ -portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * SCHEDULER CONTROL - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskStartScheduler( void );
- * - * Starts the real time kernel tick processing. After calling the kernel - * has control over which tasks are executed and when. This function - * does not return until an executing task calls vTaskEndScheduler (). - * - * At least one task should be created via a call to xTaskCreate () - * before calling vTaskStartScheduler (). The idle task is created - * automatically when the first application task is created. - * - * See the demo application file main.c for an example of creating - * tasks and starting the kernel. - * - * Example usage: -
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will not get here unless a task calls vTaskEndScheduler ()
- }
-   
- * - * \defgroup vTaskStartScheduler vTaskStartScheduler - * \ingroup SchedulerControl - */ -void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskEndScheduler( void );
- * - * Stops the real time kernel tick. All created tasks will be automatically - * deleted and multitasking (either preemptive or cooperative) will - * stop. Execution then resumes from the point where vTaskStartScheduler () - * was called, as if vTaskStartScheduler () had just returned. - * - * See the demo application file main. c in the demo/PC directory for an - * example that uses vTaskEndScheduler (). - * - * vTaskEndScheduler () requires an exit function to be defined within the - * portable layer (see vPortEndScheduler () in port. c for the PC port). This - * performs hardware specific operations such as stopping the kernel tick. - * - * vTaskEndScheduler () will cause all of the resources allocated by the - * kernel to be freed - but will not free resources allocated by application - * tasks. - * - * Example usage: -
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // At some point we want to end the real time kernel processing
-		 // so call ...
-		 vTaskEndScheduler ();
-	 }
- }
-
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will only get here when the vTaskCode () task has called
-	 // vTaskEndScheduler ().  When we get here we are back to single task
-	 // execution.
- }
-   
- * - * \defgroup vTaskEndScheduler vTaskEndScheduler - * \ingroup SchedulerControl - */ -void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspendAll( void );
- * - * Suspends all real time kernel activity while keeping interrupts (including the - * kernel tick) enabled. - * - * After calling vTaskSuspendAll () the calling task will continue to execute - * without risk of being swapped out until a call to xTaskResumeAll () has been - * made. - * - * API functions that have the potential to cause a context switch (for example, - * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler - * is suspended. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the kernel
-		 // tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.
-		 xTaskResumeAll ();
-	 }
- }
-   
- * \defgroup vTaskSuspendAll vTaskSuspendAll - * \ingroup SchedulerControl - */ -void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
char xTaskResumeAll( void );
- * - * Resumes real time kernel activity following a call to vTaskSuspendAll (). - * After a call to vTaskSuspendAll () the kernel will take control of which - * task is executing at any time. - * - * @return If resuming the scheduler caused a context switch then pdTRUE is - * returned, otherwise pdFALSE is returned. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the real
-		 // time kernel tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.  We want to force
-		 // a context switch - but there is no point if resuming the scheduler
-		 // caused a context switch already.
-		 if( !xTaskResumeAll () )
-		 {
-			  taskYIELD ();
-		 }
-	 }
- }
-   
- * \defgroup xTaskResumeAll xTaskResumeAll - * \ingroup SchedulerControl - */ -signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
- * - * Utility task that simply returns pdTRUE if the task referenced by xTask is - * currently in the Suspended state, or pdFALSE if the task referenced by xTask - * is in any other state. - * - */ -signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * TASK UTILITIES - *----------------------------------------------------------*/ - -/** - * task. h - *
volatile portTickType xTaskGetTickCount( void );
- * - * @return The count of ticks since vTaskStartScheduler was called. - * - * \page xTaskGetTickCount xTaskGetTickCount - * \ingroup TaskUtils - */ -portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned short uxTaskGetNumberOfTasks( void );
- * - * @return The number of tasks that the real time kernel is currently managing. - * This includes all ready, blocked and suspended tasks. A task that - * has been deleted but not yet freed by the idle task will also be - * included in the count. - * - * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks - * \ingroup TaskUtils - */ -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskList( char *pcWriteBuffer );
- * - * configUSE_TRACE_FACILITY must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Lists all the current tasks, along with their current state and stack - * usage high water mark. - * - * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or - * suspended ('S'). - * - * @param pcWriteBuffer A buffer into which the above mentioned details - * will be written, in ascii form. This buffer is assumed to be large - * enough to contain the generated report. Approximately 40 bytes per - * task should be sufficient. - * - * \page vTaskList vTaskList - * \ingroup TaskUtils - */ -void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
- * - * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function - * to be available. The application must also then provide definitions - * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and - * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter - * and return the timers current count value respectively. The counter - * should be at least 10 times the frequency of the tick count. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total - * accumulated execution time being stored for each task. The resolution - * of the accumulated time value depends on the frequency of the timer - * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. - * Calling vTaskGetRunTimeStats() writes the total execution time of each - * task into a buffer, both as an absolute count value and as a percentage - * of the total system execution time. - * - * @param pcWriteBuffer A buffer into which the execution times will be - * written, in ascii form. This buffer is assumed to be large enough to - * contain the generated report. Approximately 40 bytes per task should - * be sufficient. - * - * \page vTaskGetRunTimeStats vTaskGetRunTimeStats - * \ingroup TaskUtils - */ -void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskStartTrace( char * pcBuffer, unsigned portBASE_TYPE uxBufferSize );
- * - * Starts a real time kernel activity trace. The trace logs the identity of - * which task is running when. - * - * The trace file is stored in binary format. A separate DOS utility called - * convtrce.exe is used to convert this into a tab delimited text file which - * can be viewed and plotted in a spread sheet. - * - * @param pcBuffer The buffer into which the trace will be written. - * - * @param ulBufferSize The size of pcBuffer in bytes. The trace will continue - * until either the buffer in full, or ulTaskEndTrace () is called. - * - * \page vTaskStartTrace vTaskStartTrace - * \ingroup TaskUtils - */ -void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned long ulTaskEndTrace( void );
- * - * Stops a kernel activity trace. See vTaskStartTrace (). - * - * @return The number of bytes that have been written into the trace buffer. - * - * \page usTaskEndTrace usTaskEndTrace - * \ingroup TaskUtils - */ -unsigned long ulTaskEndTrace( void ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
- * - * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for - * this function to be available. - * - * Returns the high water mark of the stack associated with xTask. That is, - * the minimum free stack space there has been (in bytes) since the task - * started. The smaller the returned number the closer the task has come - * to overflowing its stack. - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The smallest amount of free stack space there has been (in bytes) - * since the task referenced by xTask was created. - */ -unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Sets pxHookFunction to be the task hook function used by the task xTask. - * Passing xTask as NULL has the effect of setting the calling tasks hook - * function. - */ -void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
- * - * Returns the pxHookFunction value assigned to the task xTask. - */ -pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Calls the hook function associated with xTask. Passing xTask as NULL has - * the effect of calling the Running tasks (the calling task) hook function. - * - * pvParameter is passed to the hook function for the task to interpret as it - * wants. - */ -portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; - - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - *----------------------------------------------------------*/ - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Called from the real time kernel tick (either preemptive or cooperative), - * this increments the tick count and checks if any tasks that are blocked - * for a finite period required removing from a blocked list and placing on - * a ready list. - */ -void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes the calling task from the ready list and places it both - * on the list of tasks waiting for a particular event, and the - * list of delayed tasks. The task will be removed from both lists - * and replaced on the ready list should either the event occur (and - * there be no higher priority tasks waiting on the same event) or - * the delay period expires. - * - * @param pxEventList The list containing tasks that are blocked waiting - * for the event to occur. - * - * @param xTicksToWait The maximum amount of time that the task should wait - * for the event to occur. This is specified in kernel ticks,the constant - * portTICK_RATE_MS can be used to convert kernel ticks into a real time - * period. - */ -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes a task from both the specified event list and the list of blocked - * tasks, and places it on a ready queue. - * - * xTaskRemoveFromEventList () will be called if either an event occurs to - * unblock a task, or the block timeout period expires. - * - * @return pdTRUE if the task being removed has a higher priority than the task - * making the call, otherwise pdFALSE. - */ -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * INCLUDE_vTaskCleanUpResources and INCLUDE_vTaskSuspend must be defined as 1 - * for this function to be available. - * See the configuration section for more information. - * - * Empties the ready and delayed queues of task control blocks, freeing the - * memory allocated for the task control block and task stacks as it goes. - */ -void vTaskCleanUpResources( void ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Sets the pointer to the current TCB to the TCB of the highest priority task - * that is ready to run. - */ -void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; - -/* - * Return the handle of the calling task. - */ -xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; - -/* - * Capture the current time status for future reference. - */ -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; - -/* - * Compare the time status now with that previously captured to see if the - * timeout has expired. - */ -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * Shortcut used by the queue implementation to prevent unnecessary call to - * taskYIELD(); - */ -void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; - -/* - * Returns the scheduler state as taskSCHEDULER_RUNNING, - * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. - */ -portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; - -/* - * Raises the priority of the mutex holder to that of the calling task should - * the mutex holder have a priority less than the calling task. - */ -void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Set the priority of a task back to its proper priority in the case that it - * inherited a higher priority while it was holding a semaphore. - */ -void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Generic version of the task creation function which is in turn called by the - * xTaskCreate() and xTaskCreateRestricted() macros. - */ -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pvTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; - -#ifdef __cplusplus -} -#endif -#endif /* TASK_H */ - - - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include task.h" +#endif + + + +#ifndef TASK_H +#define TASK_H + +#include "portable.h" +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + +#define tskKERNEL_VERSION_NUMBER "V6.0.4" + +/** + * task. h + * + * Type by which tasks are referenced. For example, a call to xTaskCreate + * returns (via a pointer parameter) an xTaskHandle variable that can then + * be used as a parameter to vTaskDelete to delete the task. + * + * \page xTaskHandle xTaskHandle + * \ingroup Tasks + */ +typedef void * xTaskHandle; + +/* + * Used internally only. + */ +typedef struct xTIME_OUT +{ + portBASE_TYPE xOverflowCount; + portTickType xTimeOnEntering; +} xTimeOutType; + +/* + * Defines the memory ranges allocated to the task when an MPU is used. + */ +typedef struct xMEMORY_REGION +{ + void *pvBaseAddress; + unsigned long ulLengthInBytes; + unsigned long ulParameters; +} xMemoryRegion; + +/* + * Parameters required to create an MPU protected task. + */ +typedef struct xTASK_PARAMTERS +{ + pdTASK_CODE pvTaskCode; + const signed char * const pcName; + unsigned short usStackDepth; + void *pvParameters; + unsigned portBASE_TYPE uxPriority; + portSTACK_TYPE *puxStackBuffer; + xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; +} xTaskParameters; + +/* + * Defines the priority used by the idle task. This must not be modified. + * + * \ingroup TaskUtils + */ +#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0 ) + +/** + * task. h + * + * Macro for forcing a context switch. + * + * \page taskYIELD taskYIELD + * \ingroup SchedulerControl + */ +#define taskYIELD() portYIELD() + +/** + * task. h + * + * Macro to mark the start of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskENTER_CRITICAL taskENTER_CRITICAL + * \ingroup SchedulerControl + */ +#define taskENTER_CRITICAL() portENTER_CRITICAL() + +/** + * task. h + * + * Macro to mark the end of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskEXIT_CRITICAL taskEXIT_CRITICAL + * \ingroup SchedulerControl + */ +#define taskEXIT_CRITICAL() portEXIT_CRITICAL() + +/** + * task. h + * + * Macro to disable all maskable interrupts. + * + * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() + +/** + * task. h + * + * Macro to enable microcontroller interrupts. + * + * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() + +/* Definitions returned by xTaskGetSchedulerState(). */ +#define taskSCHEDULER_NOT_STARTED 0 +#define taskSCHEDULER_RUNNING 1 +#define taskSCHEDULER_SUSPENDED 2 + +/*----------------------------------------------------------- + * TASK CREATION API + *----------------------------------------------------------*/ + +/** + * task. h + *
+ portBASE_TYPE xTaskCreate(
+							  pdTASK_CODE pvTaskCode,
+							  const char * const pcName,
+							  unsigned short usStackDepth,
+							  void *pvParameters,
+							  unsigned portBASE_TYPE uxPriority,
+							  xTaskHandle *pvCreatedTask
+						  );
+ * + * Create a new task and add it to the list of tasks that are ready to run. + * + * xTaskCreate() can only be used to create a task that has unrestricted + * access to the entire microcontroller memory map. Systems that include MPU + * support can alternatively create an MPU constrained task using + * xTaskCreateRestricted(). + * + * @param pvTaskCode Pointer to the task entry function. Tasks + * must be implemented to never return (i.e. continuous loop). + * + * @param pcName A descriptive name for the task. This is mainly used to + * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default + * is 16. + * + * @param usStackDepth The size of the task stack specified as the number of + * variables the stack can hold - not the number of bytes. For example, if + * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes + * will be allocated for stack storage. + * + * @param pvParameters Pointer that will be used as the parameter for the task + * being created. + * + * @param uxPriority The priority at which the task should run. Systems that + * include MPU support can optionally create tasks in a privileged (system) + * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For + * example, to create a privileged task at priority 2 the uxPriority parameter + * should be set to ( 2 | portPRIVILEGE_BIT ). + * + * @param pvCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+ // Task to be created.
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+	 }
+ }
+
+ // Function that creates a task.
+ void vOtherFunction( void )
+ {
+ static unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
+	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
+	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
+	 // the new task attempts to access it.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup xTaskCreate xTaskCreate + * \ingroup Tasks + */ +#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) + +/** + * task. h + *
+ portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
+ * + * xTaskCreateRestricted() should only be used in systems that include an MPU + * implementation. + * + * Create a new task and add it to the list of tasks that are ready to run. + * The function parameters define the memory regions and associated access + * permissions allocated to the task. + * + * @param pxTaskDefinition Pointer to a structure that contains a member + * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API + * documentation) plus an optional stack buffer and the memory region + * definitions. + * + * @param pxCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+// Create an xTaskParameters structure that defines the task to be created.
+static const xTaskParameters xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{											
+		// Base address					Length	Parameters
+        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+};
+
+int main( void )
+{
+xTaskHandle xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// task.
+	for( ;; );
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) + +/** + * task. h + *
+ void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
+ * + * Memory regions are assigned to a restricted task when the task is created by + * a call to xTaskCreateRestricted(). These regions can be redefined using + * vTaskAllocateMPURegions(). + * + * @param xTask The handle of the task being updated. + * + * @param xRegions A pointer to an xMemoryRegion structure that contains the + * new memory region definitions. + * + * Example usage: +
+// Define an array of xMemoryRegion structures that configures an MPU region
+// allowing read/write access for 1024 bytes starting at the beginning of the
+// ucOneKByte array.  The other two of the maximum 3 definable regions are
+// unused so set to zero.
+static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
+{											
+	// Base address		Length		Parameters
+	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
+	{ 0,				0,			0 },
+	{ 0,				0,			0 }
+};
+
+void vATask( void *pvParameters )
+{
+	// This task was created such that it has access to certain regions of
+	// memory as defined by the MPU configuration.  At some point it is 
+	// desired that these MPU regions are replaced with that defined in the
+	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
+	// for this purpose.  NULL is used as the task handle to indicate that this
+	// function should modify the MPU regions of the calling task.
+	vTaskAllocateMPURegions( NULL, xAltRegions );
+	
+	// Now the task can continue its function, but from this point on can only
+	// access its stack and the ucOneKByte array (unless any other statically
+	// defined or shared regions have been declared elsewhere).
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelete( xTaskHandle pxTask );
+ * + * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Remove a task from the RTOS real time kernels management. The task being + * deleted will be removed from all ready, blocked, suspended and event lists. + * + * NOTE: The idle task is responsible for freeing the kernel allocated + * memory from tasks that have been deleted. It is therefore important that + * the idle task is not starved of microcontroller processing time if your + * application makes any calls to vTaskDelete (). Memory allocated by the + * task code is not automatically freed, and should be freed before the task + * is deleted. + * + * See the demo application file death.c for sample code that utilises + * vTaskDelete (). + * + * @param pxTask The handle of the task to be deleted. Passing NULL will + * cause the calling task to be deleted. + * + * Example usage: +
+ void vOtherFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup vTaskDelete vTaskDelete + * \ingroup Tasks + */ +void vTaskDelete( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; + + +/*----------------------------------------------------------- + * TASK CONTROL API + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskDelay( portTickType xTicksToDelay );
+ * + * Delay a task for a given number of ticks. The actual time that the + * task remains blocked depends on the tick rate. The constant + * portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * + * vTaskDelay() specifies a time at which the task wishes to unblock relative to + * the time at which vTaskDelay() is called. For example, specifying a block + * period of 100 ticks will cause the task to unblock 100 ticks after + * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method + * of controlling the frequency of a cyclical task as the path taken through the + * code, as well as other task and interrupt activity, will effect the frequency + * at which vTaskDelay() gets called and therefore the time at which the task + * next executes. See vTaskDelayUntil() for an alternative API function designed + * to facilitate fixed frequency execution. It does this by specifying an + * absolute time (rather than a relative time) at which the calling task should + * unblock. + * + * @param xTicksToDelay The amount of time, in tick periods, that + * the calling task should block. + * + * Example usage: + + void vTaskFunction( void * pvParameters ) + { + void vTaskFunction( void * pvParameters ) + { + // Block for 500ms. + const portTickType xDelay = 500 / portTICK_RATE_MS; + + for( ;; ) + { + // Simply toggle the LED every 500ms, blocking between each toggle. + vToggleLED(); + vTaskDelay( xDelay ); + } + } + + * \defgroup vTaskDelay vTaskDelay + * \ingroup TaskCtrl + */ +void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
+ * + * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Delay a task until a specified time. This function can be used by cyclical + * tasks to ensure a constant execution frequency. + * + * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will + * cause a task to block for the specified number of ticks from the time vTaskDelay () is + * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed + * execution frequency as the time between a task starting to execute and that task + * calling vTaskDelay () may not be fixed [the task may take a different path though the + * code between calls, or may get interrupted or preempted a different number of times + * each time it executes]. + * + * Whereas vTaskDelay () specifies a wake time relative to the time at which the function + * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to + * unblock. + * + * The constant portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the + * task was last unblocked. The variable must be initialised with the current time + * prior to its first use (see the example below). Following this the variable is + * automatically updated within vTaskDelayUntil (). + * + * @param xTimeIncrement The cycle time period. The task will be unblocked at + * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the + * same xTimeIncrement parameter value will cause the task to execute with + * a fixed interface period. + * + * Example usage: +
+ // Perform an action every 10 ticks.
+ void vTaskFunction( void * pvParameters )
+ {
+ portTickType xLastWakeTime;
+ const portTickType xFrequency = 10;
+
+	 // Initialise the xLastWakeTime variable with the current time.
+	 xLastWakeTime = xTaskGetTickCount ();
+	 for( ;; )
+	 {
+		 // Wait for the next cycle.
+		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
+
+		 // Perform action here.
+	 }
+ }
+   
+ * \defgroup vTaskDelayUntil vTaskDelayUntil + * \ingroup TaskCtrl + */ +void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
+ * + * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Obtain the priority of any task. + * + * @param pxTask Handle of the task to be queried. Passing a NULL + * handle results in the priority of the calling task being returned. + * + * @return The priority of pxTask. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to obtain the priority of the created task.
+	 // It was created with tskIDLE_PRIORITY, but may have changed
+	 // it itself.
+	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
+	 {
+		 // The task has changed it's priority.
+	 }
+
+	 // ...
+
+	 // Is our priority higher than the created task?
+	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
+	 {
+		 // Our priority (obtained using NULL handle) is higher.
+	 }
+ }
+   
+ * \defgroup uxTaskPriorityGet uxTaskPriorityGet + * \ingroup TaskCtrl + */ +unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
+ * + * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Set the priority of any task. + * + * A context switch will occur before the function returns if the priority + * being set is higher than the currently executing task. + * + * @param pxTask Handle to the task for which the priority is being set. + * Passing a NULL handle results in the priority of the calling task being set. + * + * @param uxNewPriority The priority to which the task will be set. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to raise the priority of the created task.
+	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
+
+	 // ...
+
+	 // Use a NULL handle to raise our priority to the same value.
+	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
+ }
+   
+ * \defgroup vTaskPrioritySet vTaskPrioritySet + * \ingroup TaskCtrl + */ +void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Suspend any task. When suspended a task will never get any microcontroller + * processing time, no matter what its priority. + * + * Calls to vTaskSuspend are not accumulative - + * i.e. calling vTaskSuspend () twice on the same task still only requires one + * call to vTaskResume () to ready the suspended task. + * + * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL + * handle will cause the calling task to be suspended. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Suspend ourselves.
+	 vTaskSuspend( NULL );
+
+	 // We cannot get here unless another task calls vTaskResume
+	 // with our handle as the parameter.
+ }
+   
+ * \defgroup vTaskSuspend vTaskSuspend + * \ingroup TaskCtrl + */ +void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskResume( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Resumes a suspended task. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * vTaskResume (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Resume the suspended task ourselves.
+	 vTaskResume( xHandle );
+
+	 // The created task will once again get microcontroller processing
+	 // time in accordance with it priority within the system.
+ }
+   
+ * \defgroup vTaskResume vTaskResume + * \ingroup TaskCtrl + */ +void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * An implementation of vTaskResume() that can be called from within an ISR. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * xTaskResumeFromISR (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * \defgroup vTaskResumeFromISR vTaskResumeFromISR + * \ingroup TaskCtrl + */ +portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * SCHEDULER CONTROL + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskStartScheduler( void );
+ * + * Starts the real time kernel tick processing. After calling the kernel + * has control over which tasks are executed and when. This function + * does not return until an executing task calls vTaskEndScheduler (). + * + * At least one task should be created via a call to xTaskCreate () + * before calling vTaskStartScheduler (). The idle task is created + * automatically when the first application task is created. + * + * See the demo application file main.c for an example of creating + * tasks and starting the kernel. + * + * Example usage: +
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will not get here unless a task calls vTaskEndScheduler ()
+ }
+   
+ * + * \defgroup vTaskStartScheduler vTaskStartScheduler + * \ingroup SchedulerControl + */ +void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskEndScheduler( void );
+ * + * Stops the real time kernel tick. All created tasks will be automatically + * deleted and multitasking (either preemptive or cooperative) will + * stop. Execution then resumes from the point where vTaskStartScheduler () + * was called, as if vTaskStartScheduler () had just returned. + * + * See the demo application file main. c in the demo/PC directory for an + * example that uses vTaskEndScheduler (). + * + * vTaskEndScheduler () requires an exit function to be defined within the + * portable layer (see vPortEndScheduler () in port. c for the PC port). This + * performs hardware specific operations such as stopping the kernel tick. + * + * vTaskEndScheduler () will cause all of the resources allocated by the + * kernel to be freed - but will not free resources allocated by application + * tasks. + * + * Example usage: +
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // At some point we want to end the real time kernel processing
+		 // so call ...
+		 vTaskEndScheduler ();
+	 }
+ }
+
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will only get here when the vTaskCode () task has called
+	 // vTaskEndScheduler ().  When we get here we are back to single task
+	 // execution.
+ }
+   
+ * + * \defgroup vTaskEndScheduler vTaskEndScheduler + * \ingroup SchedulerControl + */ +void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspendAll( void );
+ * + * Suspends all real time kernel activity while keeping interrupts (including the + * kernel tick) enabled. + * + * After calling vTaskSuspendAll () the calling task will continue to execute + * without risk of being swapped out until a call to xTaskResumeAll () has been + * made. + * + * API functions that have the potential to cause a context switch (for example, + * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler + * is suspended. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the kernel
+		 // tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.
+		 xTaskResumeAll ();
+	 }
+ }
+   
+ * \defgroup vTaskSuspendAll vTaskSuspendAll + * \ingroup SchedulerControl + */ +void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
char xTaskResumeAll( void );
+ * + * Resumes real time kernel activity following a call to vTaskSuspendAll (). + * After a call to vTaskSuspendAll () the kernel will take control of which + * task is executing at any time. + * + * @return If resuming the scheduler caused a context switch then pdTRUE is + * returned, otherwise pdFALSE is returned. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the real
+		 // time kernel tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.  We want to force
+		 // a context switch - but there is no point if resuming the scheduler
+		 // caused a context switch already.
+		 if( !xTaskResumeAll () )
+		 {
+			  taskYIELD ();
+		 }
+	 }
+ }
+   
+ * \defgroup xTaskResumeAll xTaskResumeAll + * \ingroup SchedulerControl + */ +signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
+ * + * Utility task that simply returns pdTRUE if the task referenced by xTask is + * currently in the Suspended state, or pdFALSE if the task referenced by xTask + * is in any other state. + * + */ +signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK UTILITIES + *----------------------------------------------------------*/ + +/** + * task. h + *
volatile portTickType xTaskGetTickCount( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * \page xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned short uxTaskGetNumberOfTasks( void );
+ * + * @return The number of tasks that the real time kernel is currently managing. + * This includes all ready, blocked and suspended tasks. A task that + * has been deleted but not yet freed by the idle task will also be + * included in the count. + * + * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks + * \ingroup TaskUtils + */ +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskList( char *pcWriteBuffer );
+ * + * configUSE_TRACE_FACILITY must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Lists all the current tasks, along with their current state and stack + * usage high water mark. + * + * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or + * suspended ('S'). + * + * @param pcWriteBuffer A buffer into which the above mentioned details + * will be written, in ascii form. This buffer is assumed to be large + * enough to contain the generated report. Approximately 40 bytes per + * task should be sufficient. + * + * \page vTaskList vTaskList + * \ingroup TaskUtils + */ +void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
+ * + * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function + * to be available. The application must also then provide definitions + * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and + * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter + * and return the timers current count value respectively. The counter + * should be at least 10 times the frequency of the tick count. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total + * accumulated execution time being stored for each task. The resolution + * of the accumulated time value depends on the frequency of the timer + * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. + * Calling vTaskGetRunTimeStats() writes the total execution time of each + * task into a buffer, both as an absolute count value and as a percentage + * of the total system execution time. + * + * @param pcWriteBuffer A buffer into which the execution times will be + * written, in ascii form. This buffer is assumed to be large enough to + * contain the generated report. Approximately 40 bytes per task should + * be sufficient. + * + * \page vTaskGetRunTimeStats vTaskGetRunTimeStats + * \ingroup TaskUtils + */ +void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskStartTrace( char * pcBuffer, unsigned portBASE_TYPE uxBufferSize );
+ * + * Starts a real time kernel activity trace. The trace logs the identity of + * which task is running when. + * + * The trace file is stored in binary format. A separate DOS utility called + * convtrce.exe is used to convert this into a tab delimited text file which + * can be viewed and plotted in a spread sheet. + * + * @param pcBuffer The buffer into which the trace will be written. + * + * @param ulBufferSize The size of pcBuffer in bytes. The trace will continue + * until either the buffer in full, or ulTaskEndTrace () is called. + * + * \page vTaskStartTrace vTaskStartTrace + * \ingroup TaskUtils + */ +void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned long ulTaskEndTrace( void );
+ * + * Stops a kernel activity trace. See vTaskStartTrace (). + * + * @return The number of bytes that have been written into the trace buffer. + * + * \page usTaskEndTrace usTaskEndTrace + * \ingroup TaskUtils + */ +unsigned long ulTaskEndTrace( void ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
+ * + * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for + * this function to be available. + * + * Returns the high water mark of the stack associated with xTask. That is, + * the minimum free stack space there has been (in bytes) since the task + * started. The smaller the returned number the closer the task has come + * to overflowing its stack. + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The smallest amount of free stack space there has been (in bytes) + * since the task referenced by xTask was created. + */ +unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Sets pxHookFunction to be the task hook function used by the task xTask. + * Passing xTask as NULL has the effect of setting the calling tasks hook + * function. + */ +void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
+ * + * Returns the pxHookFunction value assigned to the task xTask. + */ +pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Calls the hook function associated with xTask. Passing xTask as NULL has + * the effect of calling the Running tasks (the calling task) hook function. + * + * pvParameter is passed to the hook function for the task to interpret as it + * wants. + */ +portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; + + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + *----------------------------------------------------------*/ + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Called from the real time kernel tick (either preemptive or cooperative), + * this increments the tick count and checks if any tasks that are blocked + * for a finite period required removing from a blocked list and placing on + * a ready list. + */ +void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes the calling task from the ready list and places it both + * on the list of tasks waiting for a particular event, and the + * list of delayed tasks. The task will be removed from both lists + * and replaced on the ready list should either the event occur (and + * there be no higher priority tasks waiting on the same event) or + * the delay period expires. + * + * @param pxEventList The list containing tasks that are blocked waiting + * for the event to occur. + * + * @param xTicksToWait The maximum amount of time that the task should wait + * for the event to occur. This is specified in kernel ticks,the constant + * portTICK_RATE_MS can be used to convert kernel ticks into a real time + * period. + */ +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes a task from both the specified event list and the list of blocked + * tasks, and places it on a ready queue. + * + * xTaskRemoveFromEventList () will be called if either an event occurs to + * unblock a task, or the block timeout period expires. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * INCLUDE_vTaskCleanUpResources and INCLUDE_vTaskSuspend must be defined as 1 + * for this function to be available. + * See the configuration section for more information. + * + * Empties the ready and delayed queues of task control blocks, freeing the + * memory allocated for the task control block and task stacks as it goes. + */ +void vTaskCleanUpResources( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Sets the pointer to the current TCB to the TCB of the highest priority task + * that is ready to run. + */ +void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; + +/* + * Return the handle of the calling task. + */ +xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; + +/* + * Capture the current time status for future reference. + */ +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; + +/* + * Compare the time status now with that previously captured to see if the + * timeout has expired. + */ +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * Shortcut used by the queue implementation to prevent unnecessary call to + * taskYIELD(); + */ +void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; + +/* + * Returns the scheduler state as taskSCHEDULER_RUNNING, + * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. + */ +portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; + +/* + * Raises the priority of the mutex holder to that of the calling task should + * the mutex holder have a priority less than the calling task. + */ +void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Set the priority of a task back to its proper priority in the case that it + * inherited a higher priority while it was holding a semaphore. + */ +void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Generic version of the task creation function which is in turn called by the + * xTaskCreate() and xTaskCreateRestricted() macros. + */ +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pvTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; + +#ifdef __cplusplus +} +#endif +#endif /* TASK_H */ + + + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/list.c b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/list.c index fe970ee1a..d7b76f918 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/list.c +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/list.c @@ -1,191 +1,191 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#include -#include "FreeRTOS.h" -#include "list.h" - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -void vListInitialise( xList *pxList ) -{ - /* The list structure contains a list item which is used to mark the - end of the list. To initialise the list the list end is inserted - as the only list entry. */ - pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); - - /* The list end value is the highest possible value in the list to - ensure it remains at the end of the list. */ - pxList->xListEnd.xItemValue = portMAX_DELAY; - - /* The list end next and previous pointers point to itself so we know - when the list is empty. */ - pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); - pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); - - pxList->uxNumberOfItems = 0; -} -/*-----------------------------------------------------------*/ - -void vListInitialiseItem( xListItem *pxItem ) -{ - /* Make sure the list item is not recorded as being on a list. */ - pxItem->pvContainer = NULL; -} -/*-----------------------------------------------------------*/ - -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) -{ -volatile xListItem * pxIndex; - - /* Insert a new list item into pxList, but rather than sort the list, - makes the new list item the last item to be removed by a call to - pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by - the pxIndex member. */ - pxIndex = pxList->pxIndex; - - pxNewListItem->pxNext = pxIndex->pxNext; - pxNewListItem->pxPrevious = pxList->pxIndex; - pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; - pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListInsert( xList *pxList, xListItem *pxNewListItem ) -{ -volatile xListItem *pxIterator; -portTickType xValueOfInsertion; - - /* Insert the new list item into the list, sorted in ulListItem order. */ - xValueOfInsertion = pxNewListItem->xItemValue; - - /* If the list already contains a list item with the same item value then - the new list item should be placed after it. This ensures that TCB's which - are stored in ready lists (all of which have the same ulListItem value) - get an equal share of the CPU. However, if the xItemValue is the same as - the back marker the iteration loop below will not end. This means we need - to guard against this by checking the value first and modifying the - algorithm slightly if necessary. */ - if( xValueOfInsertion == portMAX_DELAY ) - { - pxIterator = pxList->xListEnd.pxPrevious; - } - else - { - /* *** NOTE *********************************************************** - If you find your application is crashing here then likely causes are: - 1) Stack overflow - - see http://www.freertos.org/Stacks-and-stack-overflow-checking.html - 2) Incorrect interrupt priority assignment, especially on Cortex M3 - parts where numerically high priority values denote low actual - interrupt priories, which can seem counter intuitive. See - configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html - 3) Calling an API function from within a critical section or when - the scheduler is suspended. - 4) Using a queue or semaphore before it has been initialised or - before the scheduler has been started (are interrupts firing - before vTaskStartScheduler() has been called?). - See http://www.freertos.org/FAQHelp.html for more tips. - **********************************************************************/ - - for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) - { - /* There is nothing to do here, we are just iterating to the - wanted insertion position. */ - } - } - - pxNewListItem->pxNext = pxIterator->pxNext; - pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxNewListItem->pxPrevious = pxIterator; - pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. This allows fast removal of the - item later. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListRemove( xListItem *pxItemToRemove ) -{ -xList * pxList; - - pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; - pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; - - /* The list item knows which list it is in. Obtain the list from the list - item. */ - pxList = ( xList * ) pxItemToRemove->pvContainer; - - /* Make sure the index is left pointing to a valid item. */ - if( pxList->pxIndex == pxItemToRemove ) - { - pxList->pxIndex = pxItemToRemove->pxPrevious; - } - - pxItemToRemove->pvContainer = NULL; - ( pxList->uxNumberOfItems )--; -} -/*-----------------------------------------------------------*/ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#include +#include "FreeRTOS.h" +#include "list.h" + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +void vListInitialise( xList *pxList ) +{ + /* The list structure contains a list item which is used to mark the + end of the list. To initialise the list the list end is inserted + as the only list entry. */ + pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); + + /* The list end value is the highest possible value in the list to + ensure it remains at the end of the list. */ + pxList->xListEnd.xItemValue = portMAX_DELAY; + + /* The list end next and previous pointers point to itself so we know + when the list is empty. */ + pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); + pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); + + pxList->uxNumberOfItems = 0; +} +/*-----------------------------------------------------------*/ + +void vListInitialiseItem( xListItem *pxItem ) +{ + /* Make sure the list item is not recorded as being on a list. */ + pxItem->pvContainer = NULL; +} +/*-----------------------------------------------------------*/ + +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) +{ +volatile xListItem * pxIndex; + + /* Insert a new list item into pxList, but rather than sort the list, + makes the new list item the last item to be removed by a call to + pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by + the pxIndex member. */ + pxIndex = pxList->pxIndex; + + pxNewListItem->pxNext = pxIndex->pxNext; + pxNewListItem->pxPrevious = pxList->pxIndex; + pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; + pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListInsert( xList *pxList, xListItem *pxNewListItem ) +{ +volatile xListItem *pxIterator; +portTickType xValueOfInsertion; + + /* Insert the new list item into the list, sorted in ulListItem order. */ + xValueOfInsertion = pxNewListItem->xItemValue; + + /* If the list already contains a list item with the same item value then + the new list item should be placed after it. This ensures that TCB's which + are stored in ready lists (all of which have the same ulListItem value) + get an equal share of the CPU. However, if the xItemValue is the same as + the back marker the iteration loop below will not end. This means we need + to guard against this by checking the value first and modifying the + algorithm slightly if necessary. */ + if( xValueOfInsertion == portMAX_DELAY ) + { + pxIterator = pxList->xListEnd.pxPrevious; + } + else + { + /* *** NOTE *********************************************************** + If you find your application is crashing here then likely causes are: + 1) Stack overflow - + see http://www.freertos.org/Stacks-and-stack-overflow-checking.html + 2) Incorrect interrupt priority assignment, especially on Cortex M3 + parts where numerically high priority values denote low actual + interrupt priories, which can seem counter intuitive. See + configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html + 3) Calling an API function from within a critical section or when + the scheduler is suspended. + 4) Using a queue or semaphore before it has been initialised or + before the scheduler has been started (are interrupts firing + before vTaskStartScheduler() has been called?). + See http://www.freertos.org/FAQHelp.html for more tips. + **********************************************************************/ + + for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) + { + /* There is nothing to do here, we are just iterating to the + wanted insertion position. */ + } + } + + pxNewListItem->pxNext = pxIterator->pxNext; + pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxNewListItem->pxPrevious = pxIterator; + pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. This allows fast removal of the + item later. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListRemove( xListItem *pxItemToRemove ) +{ +xList * pxList; + + pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; + pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; + + /* The list item knows which list it is in. Obtain the list from the list + item. */ + pxList = ( xList * ) pxItemToRemove->pvContainer; + + /* Make sure the index is left pointing to a valid item. */ + if( pxList->pxIndex == pxItemToRemove ) + { + pxList->pxIndex = pxItemToRemove->pxPrevious; + } + + pxItemToRemove->pvContainer = NULL; + ( pxList->uxNumberOfItems )--; +} +/*-----------------------------------------------------------*/ + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/cpuemu.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/cpuemu.h index 69755698b..b453d4826 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/cpuemu.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/cpuemu.h @@ -1,86 +1,86 @@ -/* - FreeRTOS.org V4.2.1 (WIN32 port) - Copyright (C) 2007-2008 Dushara Jayasinghe. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation; either version 2 of the License, or - (at your option) any later version. - - FreeRTOS.org is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with FreeRTOS.org; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - - A special exception to the GPL can be applied should you wish to distribute - a combined work that includes FreeRTOS.org, without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details of how and when the exception - can be applied. - - *************************************************************************** - See http://www.FreeRTOS.org for documentation, latest information, license - and contact details. Please ensure to read the configuration and relevant - port sections of the online documentation. - - Also see http://www.SafeRTOS.com for an IEC 61508 compliant version along - with commercial development and support options. - *************************************************************************** -*/ - -#ifndef CPUEMU_H -#define CPUEMU_H - -/****************************************************************************** - Defines -******************************************************************************/ -#define CPU_INTR_SWI 0 // Software Interrupt (for yield) -#define CPU_INTR_USER1 1 -#define CPU_INTR_USER2 2 -#define CPU_INTR_USER3 3 -#define CPU_INTR_USER4 4 -#define CPU_INTR_USER5 5 -#define CPU_INTR_USER6 6 -#define CPU_INTR_USER7 7 -#define CPU_INTR_USER8 8 -#define CPU_INTR_USER9 9 -#define CPU_INTR_USER10 10 -#define CPU_INTR_USER11 11 -#define CPU_INTR_USER12 12 -#define CPU_INTR_USER13 13 -#define CPU_INTR_USER14 14 -#define CPU_INTR_USER15 15 -#define CPU_INTR_USER16 16 -#define CPU_INTR_USER17 17 -#define CPU_INTR_USER18 18 -#define CPU_INTR_USER19 19 -#define CPU_INTR_USER20 20 -#define CPU_INTR_USER21 21 -#define CPU_INTR_USER22 22 -#define CPU_INTR_USER23 23 -#define CPU_INTR_USER24 24 -#define CPU_INTR_USER25 25 -#define CPU_INTR_USER26 26 -#define CPU_INTR_USER27 27 -#define CPU_INTR_USER28 28 -#define CPU_INTR_USER29 29 -#define CPU_INTR_USER30 30 -#define CPU_INTR_TICK 31 // system tick (used by FreeRTOS) - -#define CPU_INTR_USER_START CPU_INTR_USER2 -#define CPU_INTR_USER_END CPU_INTR_USER30 -#define CPU_INTR_COUNT 32 - -/****************************************************************************** - Global variables -******************************************************************************/ -/****************************************************************************** - Global functions -******************************************************************************/ - -#endif +/* + FreeRTOS.org V4.2.1 (WIN32 port) - Copyright (C) 2007-2008 Dushara Jayasinghe. + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 2 of the License, or + (at your option) any later version. + + FreeRTOS.org is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with FreeRTOS.org; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + + A special exception to the GPL can be applied should you wish to distribute + a combined work that includes FreeRTOS.org, without being obliged to provide + the source code for any proprietary components. See the licensing section + of http://www.FreeRTOS.org for full details of how and when the exception + can be applied. + + *************************************************************************** + See http://www.FreeRTOS.org for documentation, latest information, license + and contact details. Please ensure to read the configuration and relevant + port sections of the online documentation. + + Also see http://www.SafeRTOS.com for an IEC 61508 compliant version along + with commercial development and support options. + *************************************************************************** +*/ + +#ifndef CPUEMU_H +#define CPUEMU_H + +/****************************************************************************** + Defines +******************************************************************************/ +#define CPU_INTR_SWI 0 // Software Interrupt (for yield) +#define CPU_INTR_USER1 1 +#define CPU_INTR_USER2 2 +#define CPU_INTR_USER3 3 +#define CPU_INTR_USER4 4 +#define CPU_INTR_USER5 5 +#define CPU_INTR_USER6 6 +#define CPU_INTR_USER7 7 +#define CPU_INTR_USER8 8 +#define CPU_INTR_USER9 9 +#define CPU_INTR_USER10 10 +#define CPU_INTR_USER11 11 +#define CPU_INTR_USER12 12 +#define CPU_INTR_USER13 13 +#define CPU_INTR_USER14 14 +#define CPU_INTR_USER15 15 +#define CPU_INTR_USER16 16 +#define CPU_INTR_USER17 17 +#define CPU_INTR_USER18 18 +#define CPU_INTR_USER19 19 +#define CPU_INTR_USER20 20 +#define CPU_INTR_USER21 21 +#define CPU_INTR_USER22 22 +#define CPU_INTR_USER23 23 +#define CPU_INTR_USER24 24 +#define CPU_INTR_USER25 25 +#define CPU_INTR_USER26 26 +#define CPU_INTR_USER27 27 +#define CPU_INTR_USER28 28 +#define CPU_INTR_USER29 29 +#define CPU_INTR_USER30 30 +#define CPU_INTR_TICK 31 // system tick (used by FreeRTOS) + +#define CPU_INTR_USER_START CPU_INTR_USER2 +#define CPU_INTR_USER_END CPU_INTR_USER30 +#define CPU_INTR_COUNT 32 + +/****************************************************************************** + Global variables +******************************************************************************/ +/****************************************************************************** + Global functions +******************************************************************************/ + +#endif diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/port.c b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/port.c index 94f09de91..b61adf724 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/port.c +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/port.c @@ -1,948 +1,948 @@ -/* - FreeRTOS.org V4.2.1 (WIN32 port) - Copyright (C) 2007-2008 Dushara Jayasinghe. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation; either version 2 of the License, or - (at your option) any later version. - - FreeRTOS.org is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with FreeRTOS.org; if not, write to the Free Software - Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - - A special exception to the GPL can be applied should you wish to distribute - a combined work that includes FreeRTOS.org, without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details of how and when the exception - can be applied. - - *************************************************************************** - See http://www.FreeRTOS.org for documentation, latest information, license - and contact details. Please ensure to read the configuration and relevant - port sections of the online documentation. - - Also see http://www.SafeRTOS.com for an IEC 61508 compliant version along - with commercial development and support options. - *************************************************************************** -*/ - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" -#include - -extern DWORD * pxCurrentTCB; - -/****************************************************************************** - Defines -******************************************************************************/ -#define NMI (1< 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ - #endif - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; - #endif - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ - #endif - - #if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ - #endif - -} tskTCB; - -tskTCB *debug_task_handle; - -//MinGW doesn't include MMCSS ... -//Bummer! - -typedef enum _AVRT_PRIORITY -{ - AVRT_PRIORITY_LOW = -1, - AVRT_PRIORITY_NORMAL, - AVRT_PRIORITY_HIGH, - AVRT_PRIORITY_CRITICAL -} AVRT_PRIORITY, *PAVRT_PRIORITY; - -typedef HANDLE WINAPI (*set_mm_thread_characteristics)(char *TaskName, LPDWORD TaskIndex); -typedef BOOL WINAPI (*set_mm_thread_priority)(HANDLE AvrtHandle, AVRT_PRIORITY priority); - -set_mm_thread_characteristics AvSetMmThreadCharacteristics; -set_mm_thread_priority AvSetMmThreadPriority; - -/* - Win32 simulator doesn't really use a stack. Instead It just - keep some task specific info in the pseudostack -*/ -typedef struct -{ - void (*entry)(void *pvParameters); /* Task Entry function */ - void *pvParameters; /* parameters to Entry function */ - portSTACK_TYPE ulCriticalNesting; /* Critical nesting count */ - HANDLE hThread; /* handle of thread associated with task */ - HANDLE hSemaphore; /* Semaphore thread (task) waits on at start and after yielding */ - portSTACK_TYPE dwGlobalIsr; /* mask used to enable/disable interrupts */ - BOOL yielded; /* Need to know how task went out of focus */ -}SSIM_T; - -#define portNO_CRITICAL_NESTING ( ( unsigned portLONG ) 0 ) - -//#define DEBUG_OUTPUT -//#define ERROR_OUTPUT - -#ifdef DEBUG_OUTPUT -/* #define debug_printf(...) ( (WaitForSingleObject(hPrintfMutex, INFINITE)|1)?( \ - ( \ - (NULL != (debug_task_handle = (tskTCB *) pxCurrentTCB ))? \ - (fprintf( stderr, "%20s\t%20s\t%i: ",debug_task_handle->pcTaskName,__func__,__LINE__)): \ - (fprintf( stderr, "%20s\t%20s\t%i: ","__unknown__",__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?ReleaseMutex( hPrintfMutex ):0) \ - ):0 ):0 ) */ -#define debug_printf(...) ( ( (NULL != (debug_task_handle = (tskTCB *) pxCurrentTCB ))? \ - (fprintf( stderr, "%20s\t%20s\t%i: ",debug_task_handle->pcTaskName,__func__,__LINE__)): \ - (fprintf( stderr, "%20s\t%20s\t%i: ","__unknown__",__func__,__LINE__)) \ - |1)? \ - fprintf( stderr, __VA_ARGS__ ) : 0 \ - ) - - #define debug_error debug_printf - -#else - #ifdef ERROR_OUTPUT -/* #define debug_error(...) ( (WaitForSingleObject(hPrintfMutex, INFINITE)|1)?( \ - ( \ - (NULL != (debug_task_handle = (tskTCB *) pxCurrentTCB ))? \ - (fprintf( stderr, "%20s\t%20s\t%i: ",debug_task_handle->pcTaskName,__func__,__LINE__)): \ - (fprintf( stderr, "%20s\t%20s\t%i: ","__unknown__",__func__,__LINE__)) \ - |1)?( \ - ((fprintf( stderr, __VA_ARGS__ )|1)?ReleaseMutex( hPrintfMutex ):0) \ - ):0 ):0 )*/ - -#define debug_error(...) ( ( (NULL != (debug_task_handle = (tskTCB *) pxCurrentTCB ))? \ - (fprintf( stderr, "%20s\t%20s\t%i: ",debug_task_handle->pcTaskName,__func__,__LINE__)): \ - (fprintf( stderr, "%20s\t%20s\t%i: ","__unknown__",__func__,__LINE__)) \ - |1)? \ - fprintf( stderr, __VA_ARGS__ ) : 0 \ - ) - - #define debug_printf(...) - #else - #define debug_printf(...) - #define debug_error(...) - #endif -#endif - -typedef BOOL (WINAPI *LPFN_ISWOW64PROCESS) (HANDLE, PBOOL); - -/****************************************************************************** - National prototypes -******************************************************************************/ -/****************************************************************************** - Global variables -******************************************************************************/ -volatile DWORD dwPendingIsr; // pending interrupts -HANDLE hIsrInvoke; // event to signal an interrupt -HANDLE hIsrMutex; // mutex to protect above 2 - -/****************************************************************************** - National variables -******************************************************************************/ -static HANDLE hIsrDispatcher; // handle of the main thread - -static volatile portSTACK_TYPE dwGlobalIsr = NMI; // interrupts disabled @ start -static volatile portSTACK_TYPE dwEnabledIsr = NMI; // mask of enabled ISRs (individual) - -static HANDLE hTickAck; // acknolwledge tick interrupt -static HANDLE hTermAck; // acknowledge termination - -volatile SSIM_T *taskToDelete; - -BOOL bIsWow64; -BOOL bUsingMMCSS; - -static enum -{ - SWI_ID_YIELD, - SWI_ID_TERMINATE, - SWI_ID_ENDTASK -} -ESWI_ID; - -unsigned portLONG ulCriticalNesting = ( unsigned portLONG ) 9999; -void (*vIsrHandler[CPU_INTR_COUNT])(void); -UINT msPerTick; //Returned from timeGetDevCaps() - -#if portDEBUG == 1 - -#define MAX_TRACE 1024 - -const char * TraceStr[MAX_TRACE]; -int TracePtr; - -#define TRACE_INFO(s) do { \ - if(TracePtr < MAX_TRACE) { \ - TraceStr[TracePtr++]=s; \ - } \ -}while(0) - -static char *TskName(DWORD *TCB) -{ - // HACK for debugging - return ((char*)TCB + 56); -} - -#else - -#define TRACE_INFO(s) - -#endif - -/****************************************************************************** - National functions -******************************************************************************/ -static DWORD WINAPI tick_generator(LPVOID lpParameter) -{ - HANDLE hTimer; - LARGE_INTEGER liDueTime; - HANDLE hObjList[2]; - float before, after; - - if(bUsingMMCSS) - { - DWORD taskIndex = 0; - HANDLE AvRtHandle = AvSetMmThreadCharacteristics(TEXT("FreeRTOS"), &taskIndex); - if(AvRtHandle == NULL) - { - printf("Error setting MMCSS on the tick generator."); - getchar(); - exit(1); - } - AvSetMmThreadPriority(AvRtHandle, AVRT_PRIORITY_CRITICAL); - } - - hTimer = CreateWaitableTimer(NULL, TRUE, NULL); - liDueTime.QuadPart = -100000; - - hObjList[0] = hIsrMutex; - hObjList[1] = hTimer; - - for(;;) - { - before = (float)clock()/CLOCKS_PER_SEC; - debug_printf("tick before, %f\n", before); - SetWaitableTimer(hTimer, &liDueTime, 0, NULL, NULL, FALSE); - if(WaitForMultipleObjects(2, hObjList, TRUE, 2000) == WAIT_TIMEOUT) - { - printf("Tick generator: timed out at WaitForMultipleObjects\n"); - return 0; - } - after = (float)clock()/CLOCKS_PER_SEC; - debug_printf("tick after, %f\n", after); - debug_printf("diff: %f\n", after - before); - - // generate the tick interrupt - dwPendingIsr |= (1<ulCriticalNesting; - - if(bUsingMMCSS) - { - DWORD taskIndex = 0; - HANDLE AvRtHandle = AvSetMmThreadCharacteristics("FreeRTOS", &taskIndex); - if(AvRtHandle == NULL) - { - printf("Error setting MMCSS on a task."); - getchar(); - exit(1); - } - } - - psSim->entry(psSim->pvParameters); - - return 0; -} - -void create_mmcss_registry_entry() -{ - HKEY hKey; - REGSAM flags = KEY_WRITE; - if(bIsWow64) - flags |= KEY_WOW64_64KEY; - - - if(RegCreateKeyEx(HKEY_LOCAL_MACHINE, - TEXT("SOFTWARE\\Microsoft\\Windows NT\\CurrentVersion\\Multimedia\\SystemProfile\\Tasks\\FreeRTOS"), - 0, NULL, 0, flags, NULL, - &hKey, NULL) != ERROR_SUCCESS) - { - printf("Internal error creating MMCSS registry key."); - getchar(); - exit(1); - } - - DWORD affinity = 0; - DWORD clock_rate = 10000; - DWORD gpu_priority = 8; - DWORD priority = 2; - - TCHAR *background_only = TEXT("True"); - TCHAR *scheduling_category = TEXT("High"); - TCHAR *sfio_priority = TEXT("Normal"); - - RegSetValueEx(hKey, TEXT("Affinity"), 0, REG_DWORD, - (BYTE *) &affinity, sizeof(DWORD)); - RegSetValueEx(hKey, TEXT("Clock Rate"), 0, REG_DWORD, - (BYTE *) &clock_rate, sizeof(DWORD)); - RegSetValueEx(hKey, TEXT("GPU Priority"), 0, REG_DWORD, - (BYTE *) &gpu_priority, sizeof(DWORD)); - RegSetValueEx(hKey, TEXT("Priority"), 0, REG_DWORD, - (BYTE *) &priority, sizeof(DWORD)); - - RegSetValueEx(hKey, TEXT("Background Only"), 0, REG_SZ, - (BYTE *) background_only, - (DWORD)(lstrlen(background_only)+1)*sizeof(TCHAR)); - RegSetValueEx(hKey, TEXT("Scheduling Category"), 0, REG_SZ, - (BYTE *) scheduling_category, - (DWORD)(lstrlen(scheduling_category)+1)*sizeof(TCHAR)); - RegSetValueEx(hKey, TEXT("SFIO Priority"), 0, REG_SZ, - (BYTE *) sfio_priority, - (DWORD)(lstrlen(sfio_priority)+1)*sizeof(TCHAR)); - - RegCloseKey(hKey); -} - - -//Boldly taken from MSDN -BOOL IsUserAdmin(VOID) -/*++ -Routine Description: This routine returns TRUE if the caller's -process is a member of the Administrators local group. Caller is NOT -expected to be impersonating anyone and is expected to be able to -open its own process and process token. -Arguments: None. -Return Value: - TRUE - Caller has Administrators local group. - FALSE - Caller does not have Administrators local group. -- -*/ -{ - BOOL b; - SID_IDENTIFIER_AUTHORITY NtAuthority = {SECURITY_NT_AUTHORITY}; - PSID AdministratorsGroup; - b = AllocateAndInitializeSid( - &NtAuthority, - 2, - SECURITY_BUILTIN_DOMAIN_RID, - DOMAIN_ALIAS_RID_ADMINS, - 0, 0, 0, 0, 0, 0, - &AdministratorsGroup); - if(b) - { - if (!CheckTokenMembership( NULL, AdministratorsGroup, &b)) - { - b = FALSE; - } - FreeSid(AdministratorsGroup); - } - - return b; -} - -//Also boldly taken from MSDN -void CheckIsWow64() -{ - LPFN_ISWOW64PROCESS fnIsWow64Process; - - bIsWow64 = FALSE; - - //IsWow64Process is not available on all supported versions of Windows. - //Use GetModuleHandle to get a handle to the DLL that contains the function - //and GetProcAddress to get a pointer to the function if available. - - fnIsWow64Process = (LPFN_ISWOW64PROCESS) GetProcAddress( - GetModuleHandle(TEXT("kernel32")),"IsWow64Process"); - - if(NULL != fnIsWow64Process) - { - if (!fnIsWow64Process(GetCurrentProcess(),&bIsWow64)) - { - printf("Error determining if FreeRTOS is running in WOW64 mode."); - getchar(); - exit(1); - } - } -} - -//Check whether we're an elevated process under UAC (only works with Vista and 7) -BOOL is_elevated_process() -{ - HANDLE tokenHandle; - TOKEN_ELEVATION isElevated; - DWORD returnLength; - - if(!OpenProcessToken(GetCurrentProcess(), TOKEN_QUERY, &tokenHandle)) - { - printf("Error opening process token while verifying elevated rights."); - getchar(); - exit(1); - } - - if(!GetTokenInformation(tokenHandle, - TokenElevation, - (void *) &isElevated, sizeof(isElevated), &returnLength)) - { - printf("Error getting token information while verifying elevated rights."); - CloseHandle(tokenHandle); - getchar(); - exit(1); - } - - CloseHandle(tokenHandle); - - return (isElevated.TokenIsElevated != 0); -} - -void check_mmcss_registry_entry() -{ - HKEY hKey; - DWORD numSubKeys; - TCHAR subKeyName[MAX_KEY_LENGTH]; - DWORD subKeyNameSize; - BOOL exists = FALSE; - REGSAM flags = KEY_READ; - LONG enumError; - if(bIsWow64) - flags |= KEY_WOW64_64KEY; - - //Check for the registry entry - - if(RegOpenKeyEx(HKEY_LOCAL_MACHINE, - TEXT("SOFTWARE\\Microsoft\\Windows NT\\CurrentVersion\\Multimedia\\SystemProfile\\Tasks"), - 0, flags, - &hKey) != ERROR_SUCCESS) - { - printf("Error opening MMCSS registry key."); - getchar(); - exit(1); - } - - //Enumerate through all subkeys - RegQueryInfoKey(hKey, NULL, NULL, NULL, - &numSubKeys, NULL, NULL, NULL, NULL, NULL, NULL, NULL); - //printf("Num subkeys: %d\n", (int) numSubKeys); - for(DWORD i = 0; i < numSubKeys; i++) - { - subKeyNameSize = MAX_KEY_LENGTH; - if((enumError = RegEnumKeyEx(hKey, i, subKeyName, &subKeyNameSize, - NULL, NULL, NULL, NULL)) == ERROR_SUCCESS) - { - //printf("Subkey name: %s\n", subKeyName); - if(lstrcmp(subKeyName, TEXT("FreeRTOS")) == 0) - { - exists = TRUE; - } - } - else - printf("Error enumerating subkeys: %d\n", (int) enumError); - } - - RegCloseKey(hKey); - - if(exists) - { - return; - } - - //it doesn't exist - //Create it - - //Check for sufficient privileges - if(!is_elevated_process()) - { - printf("Error: this program needs elevated privileges to run properly the first time only.\n"); - printf("Please click 'run as administrator'.\n"); - getchar(); - exit(1); - } - - create_mmcss_registry_entry(); -} - -void load_mmcss() -{ - HMODULE hAvrt = LoadLibrary(TEXT("Avrt.dll")); - if(hAvrt == NULL) - { - printf("Error: could not find avrt.dll."); - getchar(); - exit(1); - } - - AvSetMmThreadCharacteristics = (set_mm_thread_characteristics) - GetProcAddress(hAvrt, TEXT("AvSetMmThreadCharacteristicsA")); - AvSetMmThreadPriority = (set_mm_thread_priority) - GetProcAddress(hAvrt, TEXT("AvSetMmThreadPriority")); -} - -static void create_system_objects(void) -{ - OSVERSIONINFO version; - - version.dwOSVersionInfoSize = sizeof(version); - GetVersionEx(&version); - - //For operating systems up to XP, increase the clock rate - //and increase the priority as much as possible - if(version.dwMajorVersion < 6) - { - if(IsUserAdmin()) - SetPriorityClass(GetCurrentProcess(), REALTIME_PRIORITY_CLASS); - else - SetPriorityClass(GetCurrentProcess(), HIGH_PRIORITY_CLASS); - - //Set timer - - TIMECAPS tc; - timeGetDevCaps(&tc, sizeof(tc)); - msPerTick = tc.wPeriodMin; - debug_printf("Ms per tick: %i\n", msPerTick); - if(msPerTick > 2) - { - printf("Warning: your system timer has a low resolution.\n"); - printf("Either decrease the tick rate, or get a better PC!\n"); - } - timeBeginPeriod(tc.wPeriodMin); - bUsingMMCSS = FALSE; - } - else - { - //From Vista onward, use MMCSS - CheckIsWow64(); - check_mmcss_registry_entry(); - load_mmcss(); - bUsingMMCSS = TRUE; - } - - DuplicateHandle( - GetCurrentProcess(), - GetCurrentThread(), - GetCurrentProcess(), - &hIsrDispatcher, - 0, - FALSE, - DUPLICATE_SAME_ACCESS); - - if(bUsingMMCSS) - { - DWORD taskIndex = 0; - HANDLE AvRtHandle = AvSetMmThreadCharacteristics("FreeRTOS", &taskIndex); - if(AvRtHandle == NULL) - { - printf("Error setting MMCSS on the scheduler."); - getchar(); - exit(1); - } - AvSetMmThreadPriority(AvRtHandle, AVRT_PRIORITY_LOW); - } - else - SetThreadPriority(hIsrDispatcher, THREAD_PRIORITY_BELOW_NORMAL); - - hIsrMutex = CreateMutex(NULL, FALSE, NULL); - hIsrInvoke = CreateEvent(NULL, FALSE, FALSE, NULL); - hTickAck = CreateEvent(NULL, FALSE, FALSE, NULL); - hTermAck = CreateEvent(NULL, FALSE, FALSE, NULL); - - dwEnabledIsr |= (1<entry = ( void (*)(void *)) pxCode; - psSim->pvParameters=pvParameters; - psSim->ulCriticalNesting=portNO_CRITICAL_NESTING; - psSim->dwGlobalIsr = (DWORD)-1; - - // semaphore that's used to handle yielding - psSim->hSemaphore = CreateSemaphore(NULL, 0, 1, NULL); - psSim->yielded = FALSE; - psSim->hThread = CreateThread(NULL, 0, TaskSimThread, psSim, CREATE_SUSPENDED, NULL); - ok=SetThreadPriority(psSim->hThread, THREAD_PRIORITY_IDLE); - return (portSTACK_TYPE *) psSim; -} - -portBASE_TYPE xPortStartScheduler( void ) -{ - BOOL bSwitch, bTaskDelete; - SSIM_T *psSim; - DWORD dwIntr; - int i, iIsrCount; - HANDLE hObjList[2]; - - create_system_objects(); - - /* Start the first task. */ - psSim=(SSIM_T *)*pxCurrentTCB; - ulCriticalNesting = portNO_CRITICAL_NESTING; - ResumeThread(psSim->hThread); - - hObjList[0] = hIsrMutex; - hObjList[1] = hIsrInvoke; - - WaitForSingleObject(hIsrMutex, INFINITE); - dwGlobalIsr = psSim->dwGlobalIsr; - ReleaseMutex(hIsrMutex); - - for(;;) - { - if(WaitForMultipleObjects(2, hObjList, TRUE, 2000) == WAIT_TIMEOUT) - { - printf("vPortStartScheduler: timed out at WaitForMultipleObjects\n"); - exit(1); - } - - psSim=(SSIM_T *)*pxCurrentTCB; - - psSim->ulCriticalNesting = ulCriticalNesting ; - psSim->dwGlobalIsr = dwGlobalIsr; - - dwIntr = ((dwGlobalIsr & dwEnabledIsr) & dwPendingIsr); - - bSwitch = (dwIntr != 0); // switch only for a real interrupt - iIsrCount = 0; // no suspensions after handling first int - bTaskDelete = FALSE; - - for(i=0; dwIntr && ihThread, 0); - CloseHandle(taskToDelete->hSemaphore); - } - - psSim->yielded = TRUE; - iIsrCount++; - break; - - case CPU_INTR_TICK: - dwPendingIsr &= ~(1<hThread); - - vTaskIncrementTick(); - //debug_printf("Sending tick ack...\n"); - SetEvent(hTickAck); - break; - - default: - if(!iIsrCount++) - SuspendThread(psSim->hThread); - - vIsrHandler[i](); - break; - } - } - } - - if(bSwitch) - { - vTaskSwitchContext(); - debug_printf("switching context\n"); - psSim=(SSIM_T *)*pxCurrentTCB; - ulCriticalNesting = psSim->ulCriticalNesting; - dwGlobalIsr = psSim->dwGlobalIsr; - - if(psSim->yielded) { - psSim->yielded = FALSE; - ReleaseSemaphore(psSim->hSemaphore, 1, NULL); // awake next task - } else { - ResumeThread(psSim->hThread); - } - } - - if((dwGlobalIsr & dwEnabledIsr) & dwPendingIsr) - { - // we just enabled interrupts (by task switching in) and an interrupt is - // pending. Reinvoke ourselves - SetEvent(hIsrInvoke); - } - - ReleaseMutex(hIsrMutex); - } -} - -void vPortEndScheduler( void ) -{ - if(hIsrDispatcher) - { - WaitForSingleObject(hIsrMutex, INFINITE); - dwPendingIsr |= (1<hSemaphore, INFINITE, FALSE); - } -} - -void __delete_task(void *tcb) -{ - taskToDelete = *((SSIM_T **)tcb); - - if(hIsrDispatcher) - { - WaitForSingleObject(hIsrMutex, INFINITE); - dwPendingIsr |= (1< portNO_CRITICAL_NESTING ) - { - /* Decrement the nesting count as we are leaving a critical section. */ - ulCriticalNesting--; - - /* If the nesting level has reached zero then interrupts should be - re-enabled. */ - if( ulCriticalNesting == portNO_CRITICAL_NESTING ) - { - __enable_interrupt(); - } - } -} - -unsigned long ulPortGetTimerValue( void ) -{ - return (unsigned long) clock(); +/* + FreeRTOS.org V4.2.1 (WIN32 port) - Copyright (C) 2007-2008 Dushara Jayasinghe. + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 2 of the License, or + (at your option) any later version. + + FreeRTOS.org is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with FreeRTOS.org; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + + A special exception to the GPL can be applied should you wish to distribute + a combined work that includes FreeRTOS.org, without being obliged to provide + the source code for any proprietary components. See the licensing section + of http://www.FreeRTOS.org for full details of how and when the exception + can be applied. + + *************************************************************************** + See http://www.FreeRTOS.org for documentation, latest information, license + and contact details. Please ensure to read the configuration and relevant + port sections of the online documentation. + + Also see http://www.SafeRTOS.com for an IEC 61508 compliant version along + with commercial development and support options. + *************************************************************************** +*/ + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" +#include + +extern DWORD * pxCurrentTCB; + +/****************************************************************************** + Defines +******************************************************************************/ +#define NMI (1< 0 ) + portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ + #endif + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + unsigned portBASE_TYPE uxCriticalNesting; + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ + #endif + + #if ( configUSE_MUTEXES == 1 ) + unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + pdTASK_HOOK_CODE pxTaskTag; + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ + #endif + +} tskTCB; + +tskTCB *debug_task_handle; + +//MinGW doesn't include MMCSS ... +//Bummer! + +typedef enum _AVRT_PRIORITY +{ + AVRT_PRIORITY_LOW = -1, + AVRT_PRIORITY_NORMAL, + AVRT_PRIORITY_HIGH, + AVRT_PRIORITY_CRITICAL +} AVRT_PRIORITY, *PAVRT_PRIORITY; + +typedef HANDLE WINAPI (*set_mm_thread_characteristics)(char *TaskName, LPDWORD TaskIndex); +typedef BOOL WINAPI (*set_mm_thread_priority)(HANDLE AvrtHandle, AVRT_PRIORITY priority); + +set_mm_thread_characteristics AvSetMmThreadCharacteristics; +set_mm_thread_priority AvSetMmThreadPriority; + +/* + Win32 simulator doesn't really use a stack. Instead It just + keep some task specific info in the pseudostack +*/ +typedef struct +{ + void (*entry)(void *pvParameters); /* Task Entry function */ + void *pvParameters; /* parameters to Entry function */ + portSTACK_TYPE ulCriticalNesting; /* Critical nesting count */ + HANDLE hThread; /* handle of thread associated with task */ + HANDLE hSemaphore; /* Semaphore thread (task) waits on at start and after yielding */ + portSTACK_TYPE dwGlobalIsr; /* mask used to enable/disable interrupts */ + BOOL yielded; /* Need to know how task went out of focus */ +}SSIM_T; + +#define portNO_CRITICAL_NESTING ( ( unsigned portLONG ) 0 ) + +//#define DEBUG_OUTPUT +//#define ERROR_OUTPUT + +#ifdef DEBUG_OUTPUT +/* #define debug_printf(...) ( (WaitForSingleObject(hPrintfMutex, INFINITE)|1)?( \ + ( \ + (NULL != (debug_task_handle = (tskTCB *) pxCurrentTCB ))? \ + (fprintf( stderr, "%20s\t%20s\t%i: ",debug_task_handle->pcTaskName,__func__,__LINE__)): \ + (fprintf( stderr, "%20s\t%20s\t%i: ","__unknown__",__func__,__LINE__)) \ + |1)?( \ + ((fprintf( stderr, __VA_ARGS__ )|1)?ReleaseMutex( hPrintfMutex ):0) \ + ):0 ):0 ) */ +#define debug_printf(...) ( ( (NULL != (debug_task_handle = (tskTCB *) pxCurrentTCB ))? \ + (fprintf( stderr, "%20s\t%20s\t%i: ",debug_task_handle->pcTaskName,__func__,__LINE__)): \ + (fprintf( stderr, "%20s\t%20s\t%i: ","__unknown__",__func__,__LINE__)) \ + |1)? \ + fprintf( stderr, __VA_ARGS__ ) : 0 \ + ) + + #define debug_error debug_printf + +#else + #ifdef ERROR_OUTPUT +/* #define debug_error(...) ( (WaitForSingleObject(hPrintfMutex, INFINITE)|1)?( \ + ( \ + (NULL != (debug_task_handle = (tskTCB *) pxCurrentTCB ))? \ + (fprintf( stderr, "%20s\t%20s\t%i: ",debug_task_handle->pcTaskName,__func__,__LINE__)): \ + (fprintf( stderr, "%20s\t%20s\t%i: ","__unknown__",__func__,__LINE__)) \ + |1)?( \ + ((fprintf( stderr, __VA_ARGS__ )|1)?ReleaseMutex( hPrintfMutex ):0) \ + ):0 ):0 )*/ + +#define debug_error(...) ( ( (NULL != (debug_task_handle = (tskTCB *) pxCurrentTCB ))? \ + (fprintf( stderr, "%20s\t%20s\t%i: ",debug_task_handle->pcTaskName,__func__,__LINE__)): \ + (fprintf( stderr, "%20s\t%20s\t%i: ","__unknown__",__func__,__LINE__)) \ + |1)? \ + fprintf( stderr, __VA_ARGS__ ) : 0 \ + ) + + #define debug_printf(...) + #else + #define debug_printf(...) + #define debug_error(...) + #endif +#endif + +typedef BOOL (WINAPI *LPFN_ISWOW64PROCESS) (HANDLE, PBOOL); + +/****************************************************************************** + National prototypes +******************************************************************************/ +/****************************************************************************** + Global variables +******************************************************************************/ +volatile DWORD dwPendingIsr; // pending interrupts +HANDLE hIsrInvoke; // event to signal an interrupt +HANDLE hIsrMutex; // mutex to protect above 2 + +/****************************************************************************** + National variables +******************************************************************************/ +static HANDLE hIsrDispatcher; // handle of the main thread + +static volatile portSTACK_TYPE dwGlobalIsr = NMI; // interrupts disabled @ start +static volatile portSTACK_TYPE dwEnabledIsr = NMI; // mask of enabled ISRs (individual) + +static HANDLE hTickAck; // acknolwledge tick interrupt +static HANDLE hTermAck; // acknowledge termination + +volatile SSIM_T *taskToDelete; + +BOOL bIsWow64; +BOOL bUsingMMCSS; + +static enum +{ + SWI_ID_YIELD, + SWI_ID_TERMINATE, + SWI_ID_ENDTASK +} +ESWI_ID; + +unsigned portLONG ulCriticalNesting = ( unsigned portLONG ) 9999; +void (*vIsrHandler[CPU_INTR_COUNT])(void); +UINT msPerTick; //Returned from timeGetDevCaps() + +#if portDEBUG == 1 + +#define MAX_TRACE 1024 + +const char * TraceStr[MAX_TRACE]; +int TracePtr; + +#define TRACE_INFO(s) do { \ + if(TracePtr < MAX_TRACE) { \ + TraceStr[TracePtr++]=s; \ + } \ +}while(0) + +static char *TskName(DWORD *TCB) +{ + // HACK for debugging + return ((char*)TCB + 56); +} + +#else + +#define TRACE_INFO(s) + +#endif + +/****************************************************************************** + National functions +******************************************************************************/ +static DWORD WINAPI tick_generator(LPVOID lpParameter) +{ + HANDLE hTimer; + LARGE_INTEGER liDueTime; + HANDLE hObjList[2]; + float before, after; + + if(bUsingMMCSS) + { + DWORD taskIndex = 0; + HANDLE AvRtHandle = AvSetMmThreadCharacteristics(TEXT("FreeRTOS"), &taskIndex); + if(AvRtHandle == NULL) + { + printf("Error setting MMCSS on the tick generator."); + getchar(); + exit(1); + } + AvSetMmThreadPriority(AvRtHandle, AVRT_PRIORITY_CRITICAL); + } + + hTimer = CreateWaitableTimer(NULL, TRUE, NULL); + liDueTime.QuadPart = -100000; + + hObjList[0] = hIsrMutex; + hObjList[1] = hTimer; + + for(;;) + { + before = (float)clock()/CLOCKS_PER_SEC; + debug_printf("tick before, %f\n", before); + SetWaitableTimer(hTimer, &liDueTime, 0, NULL, NULL, FALSE); + if(WaitForMultipleObjects(2, hObjList, TRUE, 2000) == WAIT_TIMEOUT) + { + printf("Tick generator: timed out at WaitForMultipleObjects\n"); + return 0; + } + after = (float)clock()/CLOCKS_PER_SEC; + debug_printf("tick after, %f\n", after); + debug_printf("diff: %f\n", after - before); + + // generate the tick interrupt + dwPendingIsr |= (1<ulCriticalNesting; + + if(bUsingMMCSS) + { + DWORD taskIndex = 0; + HANDLE AvRtHandle = AvSetMmThreadCharacteristics("FreeRTOS", &taskIndex); + if(AvRtHandle == NULL) + { + printf("Error setting MMCSS on a task."); + getchar(); + exit(1); + } + } + + psSim->entry(psSim->pvParameters); + + return 0; +} + +void create_mmcss_registry_entry() +{ + HKEY hKey; + REGSAM flags = KEY_WRITE; + if(bIsWow64) + flags |= KEY_WOW64_64KEY; + + + if(RegCreateKeyEx(HKEY_LOCAL_MACHINE, + TEXT("SOFTWARE\\Microsoft\\Windows NT\\CurrentVersion\\Multimedia\\SystemProfile\\Tasks\\FreeRTOS"), + 0, NULL, 0, flags, NULL, + &hKey, NULL) != ERROR_SUCCESS) + { + printf("Internal error creating MMCSS registry key."); + getchar(); + exit(1); + } + + DWORD affinity = 0; + DWORD clock_rate = 10000; + DWORD gpu_priority = 8; + DWORD priority = 2; + + TCHAR *background_only = TEXT("True"); + TCHAR *scheduling_category = TEXT("High"); + TCHAR *sfio_priority = TEXT("Normal"); + + RegSetValueEx(hKey, TEXT("Affinity"), 0, REG_DWORD, + (BYTE *) &affinity, sizeof(DWORD)); + RegSetValueEx(hKey, TEXT("Clock Rate"), 0, REG_DWORD, + (BYTE *) &clock_rate, sizeof(DWORD)); + RegSetValueEx(hKey, TEXT("GPU Priority"), 0, REG_DWORD, + (BYTE *) &gpu_priority, sizeof(DWORD)); + RegSetValueEx(hKey, TEXT("Priority"), 0, REG_DWORD, + (BYTE *) &priority, sizeof(DWORD)); + + RegSetValueEx(hKey, TEXT("Background Only"), 0, REG_SZ, + (BYTE *) background_only, + (DWORD)(lstrlen(background_only)+1)*sizeof(TCHAR)); + RegSetValueEx(hKey, TEXT("Scheduling Category"), 0, REG_SZ, + (BYTE *) scheduling_category, + (DWORD)(lstrlen(scheduling_category)+1)*sizeof(TCHAR)); + RegSetValueEx(hKey, TEXT("SFIO Priority"), 0, REG_SZ, + (BYTE *) sfio_priority, + (DWORD)(lstrlen(sfio_priority)+1)*sizeof(TCHAR)); + + RegCloseKey(hKey); +} + + +//Boldly taken from MSDN +BOOL IsUserAdmin(VOID) +/*++ +Routine Description: This routine returns TRUE if the caller's +process is a member of the Administrators local group. Caller is NOT +expected to be impersonating anyone and is expected to be able to +open its own process and process token. +Arguments: None. +Return Value: + TRUE - Caller has Administrators local group. + FALSE - Caller does not have Administrators local group. -- +*/ +{ + BOOL b; + SID_IDENTIFIER_AUTHORITY NtAuthority = {SECURITY_NT_AUTHORITY}; + PSID AdministratorsGroup; + b = AllocateAndInitializeSid( + &NtAuthority, + 2, + SECURITY_BUILTIN_DOMAIN_RID, + DOMAIN_ALIAS_RID_ADMINS, + 0, 0, 0, 0, 0, 0, + &AdministratorsGroup); + if(b) + { + if (!CheckTokenMembership( NULL, AdministratorsGroup, &b)) + { + b = FALSE; + } + FreeSid(AdministratorsGroup); + } + + return b; +} + +//Also boldly taken from MSDN +void CheckIsWow64() +{ + LPFN_ISWOW64PROCESS fnIsWow64Process; + + bIsWow64 = FALSE; + + //IsWow64Process is not available on all supported versions of Windows. + //Use GetModuleHandle to get a handle to the DLL that contains the function + //and GetProcAddress to get a pointer to the function if available. + + fnIsWow64Process = (LPFN_ISWOW64PROCESS) GetProcAddress( + GetModuleHandle(TEXT("kernel32")),"IsWow64Process"); + + if(NULL != fnIsWow64Process) + { + if (!fnIsWow64Process(GetCurrentProcess(),&bIsWow64)) + { + printf("Error determining if FreeRTOS is running in WOW64 mode."); + getchar(); + exit(1); + } + } +} + +//Check whether we're an elevated process under UAC (only works with Vista and 7) +BOOL is_elevated_process() +{ + HANDLE tokenHandle; + TOKEN_ELEVATION isElevated; + DWORD returnLength; + + if(!OpenProcessToken(GetCurrentProcess(), TOKEN_QUERY, &tokenHandle)) + { + printf("Error opening process token while verifying elevated rights."); + getchar(); + exit(1); + } + + if(!GetTokenInformation(tokenHandle, + TokenElevation, + (void *) &isElevated, sizeof(isElevated), &returnLength)) + { + printf("Error getting token information while verifying elevated rights."); + CloseHandle(tokenHandle); + getchar(); + exit(1); + } + + CloseHandle(tokenHandle); + + return (isElevated.TokenIsElevated != 0); +} + +void check_mmcss_registry_entry() +{ + HKEY hKey; + DWORD numSubKeys; + TCHAR subKeyName[MAX_KEY_LENGTH]; + DWORD subKeyNameSize; + BOOL exists = FALSE; + REGSAM flags = KEY_READ; + LONG enumError; + if(bIsWow64) + flags |= KEY_WOW64_64KEY; + + //Check for the registry entry + + if(RegOpenKeyEx(HKEY_LOCAL_MACHINE, + TEXT("SOFTWARE\\Microsoft\\Windows NT\\CurrentVersion\\Multimedia\\SystemProfile\\Tasks"), + 0, flags, + &hKey) != ERROR_SUCCESS) + { + printf("Error opening MMCSS registry key."); + getchar(); + exit(1); + } + + //Enumerate through all subkeys + RegQueryInfoKey(hKey, NULL, NULL, NULL, + &numSubKeys, NULL, NULL, NULL, NULL, NULL, NULL, NULL); + //printf("Num subkeys: %d\n", (int) numSubKeys); + for(DWORD i = 0; i < numSubKeys; i++) + { + subKeyNameSize = MAX_KEY_LENGTH; + if((enumError = RegEnumKeyEx(hKey, i, subKeyName, &subKeyNameSize, + NULL, NULL, NULL, NULL)) == ERROR_SUCCESS) + { + //printf("Subkey name: %s\n", subKeyName); + if(lstrcmp(subKeyName, TEXT("FreeRTOS")) == 0) + { + exists = TRUE; + } + } + else + printf("Error enumerating subkeys: %d\n", (int) enumError); + } + + RegCloseKey(hKey); + + if(exists) + { + return; + } + + //it doesn't exist + //Create it + + //Check for sufficient privileges + if(!is_elevated_process()) + { + printf("Error: this program needs elevated privileges to run properly the first time only.\n"); + printf("Please click 'run as administrator'.\n"); + getchar(); + exit(1); + } + + create_mmcss_registry_entry(); +} + +void load_mmcss() +{ + HMODULE hAvrt = LoadLibrary(TEXT("Avrt.dll")); + if(hAvrt == NULL) + { + printf("Error: could not find avrt.dll."); + getchar(); + exit(1); + } + + AvSetMmThreadCharacteristics = (set_mm_thread_characteristics) + GetProcAddress(hAvrt, TEXT("AvSetMmThreadCharacteristicsA")); + AvSetMmThreadPriority = (set_mm_thread_priority) + GetProcAddress(hAvrt, TEXT("AvSetMmThreadPriority")); +} + +static void create_system_objects(void) +{ + OSVERSIONINFO version; + + version.dwOSVersionInfoSize = sizeof(version); + GetVersionEx(&version); + + //For operating systems up to XP, increase the clock rate + //and increase the priority as much as possible + if(version.dwMajorVersion < 6) + { + if(IsUserAdmin()) + SetPriorityClass(GetCurrentProcess(), REALTIME_PRIORITY_CLASS); + else + SetPriorityClass(GetCurrentProcess(), HIGH_PRIORITY_CLASS); + + //Set timer + + TIMECAPS tc; + timeGetDevCaps(&tc, sizeof(tc)); + msPerTick = tc.wPeriodMin; + debug_printf("Ms per tick: %i\n", msPerTick); + if(msPerTick > 2) + { + printf("Warning: your system timer has a low resolution.\n"); + printf("Either decrease the tick rate, or get a better PC!\n"); + } + timeBeginPeriod(tc.wPeriodMin); + bUsingMMCSS = FALSE; + } + else + { + //From Vista onward, use MMCSS + CheckIsWow64(); + check_mmcss_registry_entry(); + load_mmcss(); + bUsingMMCSS = TRUE; + } + + DuplicateHandle( + GetCurrentProcess(), + GetCurrentThread(), + GetCurrentProcess(), + &hIsrDispatcher, + 0, + FALSE, + DUPLICATE_SAME_ACCESS); + + if(bUsingMMCSS) + { + DWORD taskIndex = 0; + HANDLE AvRtHandle = AvSetMmThreadCharacteristics("FreeRTOS", &taskIndex); + if(AvRtHandle == NULL) + { + printf("Error setting MMCSS on the scheduler."); + getchar(); + exit(1); + } + AvSetMmThreadPriority(AvRtHandle, AVRT_PRIORITY_LOW); + } + else + SetThreadPriority(hIsrDispatcher, THREAD_PRIORITY_BELOW_NORMAL); + + hIsrMutex = CreateMutex(NULL, FALSE, NULL); + hIsrInvoke = CreateEvent(NULL, FALSE, FALSE, NULL); + hTickAck = CreateEvent(NULL, FALSE, FALSE, NULL); + hTermAck = CreateEvent(NULL, FALSE, FALSE, NULL); + + dwEnabledIsr |= (1<entry = ( void (*)(void *)) pxCode; + psSim->pvParameters=pvParameters; + psSim->ulCriticalNesting=portNO_CRITICAL_NESTING; + psSim->dwGlobalIsr = (DWORD)-1; + + // semaphore that's used to handle yielding + psSim->hSemaphore = CreateSemaphore(NULL, 0, 1, NULL); + psSim->yielded = FALSE; + psSim->hThread = CreateThread(NULL, 0, TaskSimThread, psSim, CREATE_SUSPENDED, NULL); + ok=SetThreadPriority(psSim->hThread, THREAD_PRIORITY_IDLE); + return (portSTACK_TYPE *) psSim; +} + +portBASE_TYPE xPortStartScheduler( void ) +{ + BOOL bSwitch, bTaskDelete; + SSIM_T *psSim; + DWORD dwIntr; + int i, iIsrCount; + HANDLE hObjList[2]; + + create_system_objects(); + + /* Start the first task. */ + psSim=(SSIM_T *)*pxCurrentTCB; + ulCriticalNesting = portNO_CRITICAL_NESTING; + ResumeThread(psSim->hThread); + + hObjList[0] = hIsrMutex; + hObjList[1] = hIsrInvoke; + + WaitForSingleObject(hIsrMutex, INFINITE); + dwGlobalIsr = psSim->dwGlobalIsr; + ReleaseMutex(hIsrMutex); + + for(;;) + { + if(WaitForMultipleObjects(2, hObjList, TRUE, 2000) == WAIT_TIMEOUT) + { + printf("vPortStartScheduler: timed out at WaitForMultipleObjects\n"); + exit(1); + } + + psSim=(SSIM_T *)*pxCurrentTCB; + + psSim->ulCriticalNesting = ulCriticalNesting ; + psSim->dwGlobalIsr = dwGlobalIsr; + + dwIntr = ((dwGlobalIsr & dwEnabledIsr) & dwPendingIsr); + + bSwitch = (dwIntr != 0); // switch only for a real interrupt + iIsrCount = 0; // no suspensions after handling first int + bTaskDelete = FALSE; + + for(i=0; dwIntr && ihThread, 0); + CloseHandle(taskToDelete->hSemaphore); + } + + psSim->yielded = TRUE; + iIsrCount++; + break; + + case CPU_INTR_TICK: + dwPendingIsr &= ~(1<hThread); + + vTaskIncrementTick(); + //debug_printf("Sending tick ack...\n"); + SetEvent(hTickAck); + break; + + default: + if(!iIsrCount++) + SuspendThread(psSim->hThread); + + vIsrHandler[i](); + break; + } + } + } + + if(bSwitch) + { + vTaskSwitchContext(); + debug_printf("switching context\n"); + psSim=(SSIM_T *)*pxCurrentTCB; + ulCriticalNesting = psSim->ulCriticalNesting; + dwGlobalIsr = psSim->dwGlobalIsr; + + if(psSim->yielded) { + psSim->yielded = FALSE; + ReleaseSemaphore(psSim->hSemaphore, 1, NULL); // awake next task + } else { + ResumeThread(psSim->hThread); + } + } + + if((dwGlobalIsr & dwEnabledIsr) & dwPendingIsr) + { + // we just enabled interrupts (by task switching in) and an interrupt is + // pending. Reinvoke ourselves + SetEvent(hIsrInvoke); + } + + ReleaseMutex(hIsrMutex); + } +} + +void vPortEndScheduler( void ) +{ + if(hIsrDispatcher) + { + WaitForSingleObject(hIsrMutex, INFINITE); + dwPendingIsr |= (1<hSemaphore, INFINITE, FALSE); + } +} + +void __delete_task(void *tcb) +{ + taskToDelete = *((SSIM_T **)tcb); + + if(hIsrDispatcher) + { + WaitForSingleObject(hIsrMutex, INFINITE); + dwPendingIsr |= (1< portNO_CRITICAL_NESTING ) + { + /* Decrement the nesting count as we are leaving a critical section. */ + ulCriticalNesting--; + + /* If the nesting level has reached zero then interrupts should be + re-enabled. */ + if( ulCriticalNesting == portNO_CRITICAL_NESTING ) + { + __enable_interrupt(); + } + } +} + +unsigned long ulPortGetTimerValue( void ) +{ + return (unsigned long) clock(); } \ No newline at end of file diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/portmacro.h b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/portmacro.h index f9b6441fb..8a06614c4 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/portmacro.h +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/GCC/Win32/portmacro.h @@ -1,177 +1,177 @@ -/* - FreeRTOS.org V5.2.0 - Copyright (C) 2003-2009 Richard Barry. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. - - You should have received a copy of the GNU General Public License along - with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef PORTMACRO_H -#define PORTMACRO_H - -#define _WIN32_WINNT 0x600 - -#include -#include -#include -#include -#include "cpuemu.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * Port specific definitions. - * - * The settings in this file configure FreeRTOS correctly for the - * given hardware and compiler. - * - * These settings should not be altered. - *----------------------------------------------------------- - */ - -/* Type definitions. */ -#define portCHAR char -#define portFLOAT float -#define portDOUBLE double -#define portLONG int -#define portSHORT short -#define portSTACK_TYPE unsigned long -#define portBASE_TYPE long - -#if( configUSE_16_BIT_TICKS == 1 ) - typedef unsigned portSHORT portTickType; - #define portMAX_DELAY ( portTickType ) 0xffff -#else - typedef unsigned portLONG portTickType; - #define portMAX_DELAY ( portTickType ) 0xffffffff -#endif -/*-----------------------------------------------------------*/ - -/* Hardware specifics. */ -#define portSTACK_GROWTH ( -1 ) -#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) -#define portTICK_RATE_MICROSECONDS ( ( portTickType ) 1000000 / configTICK_RATE_HZ ) -#define portBYTE_ALIGNMENT 4 - -#define portYIELD() __swi(); -#define portDISABLE_INTERRUPTS() __disable_interrupt() -#define portENABLE_INTERRUPTS() __enable_interrupt() - -/* Critical section handling. */ -#define portENTER_CRITICAL() vPortEnterCritical() -#define portEXIT_CRITICAL() vPortExitCritical() - -/* Task utilities. */ -#define portEND_SWITCHING_ISR( xSwitchRequired ) \ -{ \ -extern void vTaskSwitchContext( void ); \ - \ - if( xSwitchRequired ) \ - { \ - vTaskSwitchContext(); \ - } \ -} - -/* Task function macros as described on the FreeRTOS.org WEB site. */ -#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) -#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) - -#define portNOP() - -#define portOUTPUT_BYTE( a, b ) - -#define traceTASK_DELETE( pxTaskToDelete ) __delete_task( pxTaskToDelete ) - -#define traceTASK_CREATE( pxNewTCB ) - -/* Make use of times(man 2) to gather run-time statistics on the tasks. */ -extern void vPortFindTicksPerSecond( void ); -#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vPortFindTicksPerSecond() /* Nothing to do because the timer is already present. */ -extern unsigned long ulPortGetTimerValue( void ); -#define portGET_RUN_TIME_COUNTER_VALUE() ulPortGetTimerValue() /* Query the System time stats for this process. */ - -/* Assign a handler to an interrupt no */ -int iPortSetIsrHandler(int iNo, void (*handler)(void)); - -/* enable specified interrupt no */ -void vPortEnableInt(int iNo); - -/* disable specified interrupt no */ -void vPortDisableInt(int iNo); - -/* query interrupt enabled status */ -BOOL bPortIsEnabledInt(int iNo); - -/* global interrupt disable */ -void __disable_interrupt(void); - -/* global interrupt enable */ -void __enable_interrupt(void); - -/* generate software interrupt - non - maskable */ -void __swi(void); - -/* generate an interrupt which causes the scheduler to delete the task */ -void __delete_task(void *tcb); - -/* To be used by interrupt generation threads. e.g. Create a thread that -monitors console events and generate an interrupt whenever a key is pressed. -See also implimentation of tick_generator. -*/ -void __generate_interrupt(int iNo); - -void vPortEnterCritical( void ); -void vPortExitCritical( void ); - -#ifdef __cplusplus -} -#endif - -#endif /* PORTMACRO_H */ - +/* + FreeRTOS.org V5.2.0 - Copyright (C) 2003-2009 Richard Barry. + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify it + under the terms of the GNU General Public License (version 2) as published + by the Free Software Foundation and modified by the FreeRTOS exception. + + FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. + + You should have received a copy of the GNU General Public License along + with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 + Temple Place, Suite 330, Boston, MA 02111-1307 USA. + + A special exception to the GPL is included to allow you to distribute a + combined work that includes FreeRTOS.org without being obliged to provide + the source code for any proprietary components. See the licensing section + of http://www.FreeRTOS.org for full details. + + + *************************************************************************** + * * + * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * + * * + * This is a concise, step by step, 'hands on' guide that describes both * + * general multitasking concepts and FreeRTOS specifics. It presents and * + * explains numerous examples that are written using the FreeRTOS API. * + * Full source code for all the examples is provided in an accompanying * + * .zip file. * + * * + *************************************************************************** + + 1 tab == 4 spaces! + + Please ensure to read the configuration and relevant port sections of the + online documentation. + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef PORTMACRO_H +#define PORTMACRO_H + +#define _WIN32_WINNT 0x600 + +#include +#include +#include +#include +#include "cpuemu.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * Port specific definitions. + * + * The settings in this file configure FreeRTOS correctly for the + * given hardware and compiler. + * + * These settings should not be altered. + *----------------------------------------------------------- + */ + +/* Type definitions. */ +#define portCHAR char +#define portFLOAT float +#define portDOUBLE double +#define portLONG int +#define portSHORT short +#define portSTACK_TYPE unsigned long +#define portBASE_TYPE long + +#if( configUSE_16_BIT_TICKS == 1 ) + typedef unsigned portSHORT portTickType; + #define portMAX_DELAY ( portTickType ) 0xffff +#else + typedef unsigned portLONG portTickType; + #define portMAX_DELAY ( portTickType ) 0xffffffff +#endif +/*-----------------------------------------------------------*/ + +/* Hardware specifics. */ +#define portSTACK_GROWTH ( -1 ) +#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) +#define portTICK_RATE_MICROSECONDS ( ( portTickType ) 1000000 / configTICK_RATE_HZ ) +#define portBYTE_ALIGNMENT 4 + +#define portYIELD() __swi(); +#define portDISABLE_INTERRUPTS() __disable_interrupt() +#define portENABLE_INTERRUPTS() __enable_interrupt() + +/* Critical section handling. */ +#define portENTER_CRITICAL() vPortEnterCritical() +#define portEXIT_CRITICAL() vPortExitCritical() + +/* Task utilities. */ +#define portEND_SWITCHING_ISR( xSwitchRequired ) \ +{ \ +extern void vTaskSwitchContext( void ); \ + \ + if( xSwitchRequired ) \ + { \ + vTaskSwitchContext(); \ + } \ +} + +/* Task function macros as described on the FreeRTOS.org WEB site. */ +#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) +#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) + +#define portNOP() + +#define portOUTPUT_BYTE( a, b ) + +#define traceTASK_DELETE( pxTaskToDelete ) __delete_task( pxTaskToDelete ) + +#define traceTASK_CREATE( pxNewTCB ) + +/* Make use of times(man 2) to gather run-time statistics on the tasks. */ +extern void vPortFindTicksPerSecond( void ); +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vPortFindTicksPerSecond() /* Nothing to do because the timer is already present. */ +extern unsigned long ulPortGetTimerValue( void ); +#define portGET_RUN_TIME_COUNTER_VALUE() ulPortGetTimerValue() /* Query the System time stats for this process. */ + +/* Assign a handler to an interrupt no */ +int iPortSetIsrHandler(int iNo, void (*handler)(void)); + +/* enable specified interrupt no */ +void vPortEnableInt(int iNo); + +/* disable specified interrupt no */ +void vPortDisableInt(int iNo); + +/* query interrupt enabled status */ +BOOL bPortIsEnabledInt(int iNo); + +/* global interrupt disable */ +void __disable_interrupt(void); + +/* global interrupt enable */ +void __enable_interrupt(void); + +/* generate software interrupt - non - maskable */ +void __swi(void); + +/* generate an interrupt which causes the scheduler to delete the task */ +void __delete_task(void *tcb); + +/* To be used by interrupt generation threads. e.g. Create a thread that +monitors console events and generate an interrupt whenever a key is pressed. +See also implimentation of tick_generator. +*/ +void __generate_interrupt(int iNo); + +void vPortEnterCritical( void ); +void vPortExitCritical( void ); + +#ifdef __cplusplus +} +#endif + +#endif /* PORTMACRO_H */ + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c index e4fd22f8a..190b8d58c 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c @@ -1,117 +1,117 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -/* - * Implementation of pvPortMalloc() and vPortFree() that relies on the - * compilers own malloc() and free() implementations. - * - * This file can only be used if the linker is configured to to generate - * a heap memory area. - * - * See heap_2.c and heap_1.c for alternative implementations, and the memory - * management pages of http://www.FreeRTOS.org for more information. - */ - -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/*-----------------------------------------------------------*/ - -void *pvPortMalloc( size_t xWantedSize ) -{ -void *pvReturn; - - vTaskSuspendAll(); - { - pvReturn = malloc( xWantedSize ); - } - xTaskResumeAll(); - - #if( configUSE_MALLOC_FAILED_HOOK == 1 ) - { - if( pvReturn == NULL ) - { - extern void vApplicationMallocFailedHook( void ); - vApplicationMallocFailedHook(); - } - } - #endif - - return pvReturn; -} -/*-----------------------------------------------------------*/ - -void vPortFree( void *pv ) -{ - if( pv ) - { - vTaskSuspendAll(); - { - free( pv ); - } - xTaskResumeAll(); - } -} - - - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +/* + * Implementation of pvPortMalloc() and vPortFree() that relies on the + * compilers own malloc() and free() implementations. + * + * This file can only be used if the linker is configured to to generate + * a heap memory area. + * + * See heap_2.c and heap_1.c for alternative implementations, and the memory + * management pages of http://www.FreeRTOS.org for more information. + */ + +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +void *pvReturn; + + vTaskSuspendAll(); + { + pvReturn = malloc( xWantedSize ); + } + xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ + if( pv ) + { + vTaskSuspendAll(); + { + free( pv ); + } + xTaskResumeAll(); + } +} + + + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/queue.c b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/queue.c index 7258f7a3e..3827ca65f 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/queue.c +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/queue.c @@ -1,1465 +1,1465 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "croutine.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -/* Constants used with the cRxLock and cTxLock structure members. */ -#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) -#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) - -#define queueERRONEOUS_UNBLOCK ( -1 ) - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - -/* Effectively make a union out of the xQUEUE structure. */ -#define pxMutexHolder pcTail -#define uxQueueType pcHead -#define uxRecursiveCallCount pcReadFrom -#define queueQUEUE_IS_MUTEX NULL - -/* Semaphores do not actually store or copy data, so have an items size of -zero. */ -#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( 0 ) -#define queueDONT_BLOCK ( ( portTickType ) 0 ) -#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0 ) - -/* - * Definition of the queue used by the scheduler. - * Items are queued by copy, not reference. - */ -typedef struct QueueDefinition -{ - signed char *pcHead; /*< Points to the beginning of the queue storage area. */ - signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ - - signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ - signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ - - xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ - xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ - - volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ - unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ - unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ - - signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - -} xQUEUE; -/*-----------------------------------------------------------*/ - -/* - * Inside this file xQueueHandle is a pointer to a xQUEUE structure. - * To keep the definition private the API header file defines it as a - * pointer to void. - */ -typedef xQUEUE * xQueueHandle; - -/* - * Prototypes for public functions are included here so we don't have to - * include the API header file (as it defines xQueueHandle differently). These - * functions are documented in the API header file. - */ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateMutex( void ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Co-routine queue functions differ from task queue functions. Co-routines are - * an optional component. - */ -#if configUSE_CO_ROUTINES == 1 - signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; -#endif - -/* - * The queue registry is just a means for kernel aware debuggers to locate - * queue structures. It has no other purpose so is an optional component. - */ -#if configQUEUE_REGISTRY_SIZE > 0 - - /* The type stored within the queue registry array. This allows a name - to be assigned to each queue making kernel aware debugging a little - more user friendly. */ - typedef struct QUEUE_REGISTRY_ITEM - { - signed char *pcQueueName; - xQueueHandle xHandle; - } xQueueRegistryItem; - - /* The queue registry is simply an array of xQueueRegistryItem structures. - The pcQueueName member of a structure being NULL is indicative of the - array position being vacant. */ - xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; - - /* Removes a queue from the registry by simply setting the pcQueueName - member to NULL. */ - static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; -#endif - -/* - * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not - * prevent an ISR from adding or removing items to the queue, but does prevent - * an ISR from removing tasks from the queue event lists. If an ISR finds a - * queue is locked it will instead increment the appropriate queue lock count - * to indicate that a task may require unblocking. When the queue in unlocked - * these lock counts are inspected, and the appropriate action taken. - */ -static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any data in a queue. - * - * @return pdTRUE if the queue contains no items, otherwise pdFALSE. - */ -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any space in a queue. - * - * @return pdTRUE if there is no space, otherwise pdFALSE; - */ -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Copies an item into the queue, either at the front of the queue or the - * back of the queue. - */ -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; - -/* - * Copies an item out of a queue. - */ -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; -/*-----------------------------------------------------------*/ - -/* - * Macro to mark a queue as locked. Locking a queue prevents an ISR from - * accessing the queue event lists. - */ -#define prvLockQueue( pxQueue ) \ -{ \ - taskENTER_CRITICAL(); \ - { \ - if( pxQueue->xRxLock == queueUNLOCKED ) \ - { \ - pxQueue->xRxLock = queueLOCKED_UNMODIFIED; \ - } \ - if( pxQueue->xTxLock == queueUNLOCKED ) \ - { \ - pxQueue->xTxLock = queueLOCKED_UNMODIFIED; \ - } \ - } \ - taskEXIT_CRITICAL(); \ -} -/*-----------------------------------------------------------*/ - - -/*----------------------------------------------------------- - * PUBLIC QUEUE MANAGEMENT API documented in queue.h - *----------------------------------------------------------*/ - -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) -{ -xQUEUE *pxNewQueue; -size_t xQueueSizeInBytes; - - /* Allocate the new queue structure. */ - if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) - { - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Create the list of pointers to queue items. The queue is one byte - longer than asked for to make wrap checking easier/faster. */ - xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; - - pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); - if( pxNewQueue->pcHead != NULL ) - { - /* Initialise the queue members as described above where the - queue type is defined. */ - pxNewQueue->pcTail = pxNewQueue->pcHead + ( uxQueueLength * uxItemSize ); - pxNewQueue->uxMessagesWaiting = 0; - pxNewQueue->pcWriteTo = pxNewQueue->pcHead; - pxNewQueue->pcReadFrom = pxNewQueue->pcHead + ( ( uxQueueLength - 1 ) * uxItemSize ); - pxNewQueue->uxLength = uxQueueLength; - pxNewQueue->uxItemSize = uxItemSize; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - /* Likewise ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); - - traceQUEUE_CREATE( pxNewQueue ); - return pxNewQueue; - } - else - { - traceQUEUE_CREATE_FAILED(); - vPortFree( pxNewQueue ); - } - } - } - - /* Will only reach here if we could not allocate enough memory or no memory - was required. */ - return NULL; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - xQueueHandle xQueueCreateMutex( void ) - { - xQUEUE *pxNewQueue; - - /* Allocate the new queue structure. */ - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Information required for priority inheritance. */ - pxNewQueue->pxMutexHolder = NULL; - pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; - - /* Queues used as a mutex no data is actually copied into or out - of the queue. */ - pxNewQueue->pcWriteTo = NULL; - pxNewQueue->pcReadFrom = NULL; - - /* Each mutex has a length of 1 (like a binary semaphore) and - an item size of 0 as nothing is actually copied into or out - of the mutex. */ - pxNewQueue->uxMessagesWaiting = 0; - pxNewQueue->uxLength = 1; - pxNewQueue->uxItemSize = 0; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - /* Ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); - - /* Start with the semaphore in the expected state. */ - xQueueGenericSend( pxNewQueue, NULL, 0, queueSEND_TO_BACK ); - - traceCREATE_MUTEX( pxNewQueue ); - } - else - { - traceCREATE_MUTEX_FAILED(); - } - - return pxNewQueue; - } - -#endif /* configUSE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_RECURSIVE_MUTEXES == 1 - - portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) - { - portBASE_TYPE xReturn; - - /* If this is the task that holds the mutex then pxMutexHolder will not - change outside of this task. If this task does not hold the mutex then - pxMutexHolder can never coincidentally equal the tasks handle, and as - this is the only condition we are interested in it does not matter if - pxMutexHolder is accessed simultaneously by another task. Therefore no - mutual exclusion is required to test the pxMutexHolder variable. */ - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - traceGIVE_MUTEX_RECURSIVE( pxMutex ); - - /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to - the task handle, therefore no underflow check is required. Also, - uxRecursiveCallCount is only modified by the mutex holder, and as - there can only be one, no mutual exclusion is required to modify the - uxRecursiveCallCount member. */ - ( pxMutex->uxRecursiveCallCount )--; - - /* Have we unwound the call count? */ - if( pxMutex->uxRecursiveCallCount == 0 ) - { - /* Return the mutex. This will automatically unblock any other - task that might be waiting to access the mutex. */ - xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); - } - - xReturn = pdPASS; - } - else - { - /* We cannot give the mutex because we are not the holder. */ - xReturn = pdFAIL; - - traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_RECURSIVE_MUTEXES == 1 - - portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) - { - portBASE_TYPE xReturn; - - /* Comments regarding mutual exclusion as per those within - xQueueGiveMutexRecursive(). */ - - traceTAKE_MUTEX_RECURSIVE( pxMutex ); - - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - ( pxMutex->uxRecursiveCallCount )++; - xReturn = pdPASS; - } - else - { - xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); - - /* pdPASS will only be returned if we successfully obtained the mutex, - we may have blocked to reach here. */ - if( xReturn == pdPASS ) - { - ( pxMutex->uxRecursiveCallCount )++; - } - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_COUNTING_SEMAPHORES == 1 - - xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) - { - xQueueHandle pxHandle; - - pxHandle = xQueueCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH ); - - if( pxHandle != NULL ) - { - pxHandle->uxMessagesWaiting = uxInitialCount; - - traceCREATE_COUNTING_SEMAPHORE(); - } - else - { - traceCREATE_COUNTING_SEMAPHORE_FAILED(); - } - - return pxHandle; - } - -#endif /* configUSE_COUNTING_SEMAPHORES */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. Yes it is ok to do - this from within the critical section - the kernel - takes care of that. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting the - function. */ - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was full and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting - the function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was full and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - - /* Unlocking the queue means queue events can effect the - event list. It is possible that interrupts occurring now - remove this task from the event list again - but as the - scheduler is suspended the task will go onto the pending - ready last instead of the actual ready list. */ - prvUnlockQueue( pxQueue ); - - /* Resuming the scheduler will move tasks from the pending - ready list into the ready list - so it is feasible that this - task is already in a ready list before it yields - in which - case the yield will not cause a context switch unless there - is also a higher priority task in the pending ready list. */ - if( !xTaskResumeAll() ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - /* The timeout has expired. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - - /* Return to the original privilege level before exiting the - function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } -} -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } - taskEXIT_CRITICAL(); - } - } - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - signed char *pcOriginalReadPosition; - - for( ;; ) - { - taskENTER_CRITICAL(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } - taskEXIT_CRITICAL(); - } - } - - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - /* Similar to xQueueGenericSend, except we don't block if there is no room - in the queue. Also we don't directly wake a task that was blocked on a - queue read, instead we return a flag to say whether a context switch is - required or not (i.e. has a task with a higher priority than us been woken - by this post). */ - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND_FROM_ISR( pxQueue ); - - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If the queue is locked we do not alter the event list. This will - be done when the queue is unlocked later. */ - if( pxQueue->xTxLock == queueUNLOCKED ) - { - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - *pxHigherPriorityTaskWoken = pdTRUE; - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was posted while it was locked. */ - ++( pxQueue->xTxLock ); - } - - xReturn = pdPASS; - } - else - { - traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); - xReturn = errQUEUE_FULL; - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; -signed char *pcOriginalReadPosition; - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there data in the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was empty and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was empty and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - { - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - } - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - prvUnlockQueue( pxQueue ); - if( !xTaskResumeAll() ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - /* We cannot block from an ISR, so check there is data available. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - --( pxQueue->uxMessagesWaiting ); - - /* If the queue is locked we will not modify the event list. Instead - we update the lock count so the task that unlocks the queue will know - that an ISR has removed data while the queue was locked. */ - if( pxQueue->xRxLock == queueUNLOCKED ) - { - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than us so - force a context switch. */ - *pxTaskWoken = pdTRUE; - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was removed while it was locked. */ - ++( pxQueue->xRxLock ); - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - taskENTER_CRITICAL(); - uxReturn = pxQueue->uxMessagesWaiting; - taskEXIT_CRITICAL(); - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - uxReturn = pxQueue->uxMessagesWaiting; - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -void vQueueDelete( xQueueHandle pxQueue ) -{ - traceQUEUE_DELETE( pxQueue ); - vQueueUnregisterQueue( pxQueue ); - vPortFree( pxQueue->pcHead ); - vPortFree( pxQueue ); -} -/*-----------------------------------------------------------*/ - -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) -{ - if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) - { - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* The mutex is no longer being held. */ - vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); - pxQueue->pxMutexHolder = NULL; - } - } - #endif - } - else if( xPosition == queueSEND_TO_BACK ) - { - memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcWriteTo += pxQueue->uxItemSize; - if( pxQueue->pcWriteTo >= pxQueue->pcTail ) - { - pxQueue->pcWriteTo = pxQueue->pcHead; - } - } - else - { - memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcReadFrom -= pxQueue->uxItemSize; - if( pxQueue->pcReadFrom < pxQueue->pcHead ) - { - pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); - } - } - - ++( pxQueue->uxMessagesWaiting ); -} -/*-----------------------------------------------------------*/ - -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) -{ - if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) - { - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - } -} -/*-----------------------------------------------------------*/ - -static void prvUnlockQueue( xQueueHandle pxQueue ) -{ - /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ - - /* The lock counts contains the number of extra data items placed or - removed from the queue while the queue was locked. When a queue is - locked items can be added or removed, but the event lists cannot be - updated. */ - taskENTER_CRITICAL(); - { - /* See if data was added to the queue while it was locked. */ - while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) - { - /* Data was posted while the queue was locked. Are any tasks - blocked waiting for data to become available? */ - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - vTaskMissedYield(); - } - - --( pxQueue->xTxLock ); - } - else - { - break; - } - } - - pxQueue->xTxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); - - /* Do the same for the Rx lock. */ - taskENTER_CRITICAL(); - { - while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) - { - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - vTaskMissedYield(); - } - - --( pxQueue->xRxLock ); - } - else - { - break; - } - } - - pxQueue->xRxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already full we may have to block. A critical section - is required to prevent an interrupt removing something from the queue - between the check to see if the queue is full and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( prvIsQueueFull( pxQueue ) ) - { - /* The queue is full - do we want to block or just leave without - posting? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is called from a coroutine we cannot block directly, but - return indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - /* There is room in the queue, copy the data into the queue. */ - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - xReturn = pdPASS; - - /* Were any co-routines waiting for data to become available? */ - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The co-routine waiting has a higher priority so record - that a yield might be appropriate. */ - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = errQUEUE_FULL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already empty we may have to block. A critical section - is required to prevent an interrupt adding something to the queue - between the check to see if the queue is empty and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) - { - /* There are no messages in the queue, do we want to block or just - leave with nothing? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is a co-routine we cannot block directly, but return - indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Data is available from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - xReturn = pdPASS; - - /* Were any co-routines waiting for space to become available? */ - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = pdFAIL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - - - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) -{ - /* Cannot block within an ISR so if there is no space on the queue then - exit without doing anything. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - - /* We only want to wake one co-routine per ISR, so check that a - co-routine has not already been woken. */ - if( !xCoRoutinePreviouslyWoken ) - { - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - return pdTRUE; - } - } - } - } - - return xCoRoutinePreviouslyWoken; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) -{ -signed portBASE_TYPE xReturn; - - /* We cannot block from an ISR, so check there is data available. If - not then just leave without doing anything. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Copy the data from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - if( !( *pxCoRoutineWoken ) ) - { - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - *pxCoRoutineWoken = pdTRUE; - } - } - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - } - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) - { - unsigned portBASE_TYPE ux; - - /* See if there is an empty space in the registry. A NULL name denotes - a free slot. */ - for( ux = 0; ux < configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].pcQueueName == NULL ) - { - /* Store the information on this queue. */ - xQueueRegistry[ ux ].pcQueueName = pcQueueName; - xQueueRegistry[ ux ].xHandle = xQueue; - break; - } - } - } - -#endif - /*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - static void vQueueUnregisterQueue( xQueueHandle xQueue ) - { - unsigned portBASE_TYPE ux; - - /* See if the handle of the queue being unregistered in actually in the - registry. */ - for( ux = 0; ux < configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].xHandle == xQueue ) - { - /* Set the name to NULL to show that this slot if free again. */ - xQueueRegistry[ ux ].pcQueueName = NULL; - break; - } - } - - } - -#endif - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "croutine.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +/* Constants used with the cRxLock and cTxLock structure members. */ +#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) +#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) + +#define queueERRONEOUS_UNBLOCK ( -1 ) + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + +/* Effectively make a union out of the xQUEUE structure. */ +#define pxMutexHolder pcTail +#define uxQueueType pcHead +#define uxRecursiveCallCount pcReadFrom +#define queueQUEUE_IS_MUTEX NULL + +/* Semaphores do not actually store or copy data, so have an items size of +zero. */ +#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( 0 ) +#define queueDONT_BLOCK ( ( portTickType ) 0 ) +#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0 ) + +/* + * Definition of the queue used by the scheduler. + * Items are queued by copy, not reference. + */ +typedef struct QueueDefinition +{ + signed char *pcHead; /*< Points to the beginning of the queue storage area. */ + signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ + + signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ + signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ + + xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ + xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ + + volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ + unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ + unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ + + signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + +} xQUEUE; +/*-----------------------------------------------------------*/ + +/* + * Inside this file xQueueHandle is a pointer to a xQUEUE structure. + * To keep the definition private the API header file defines it as a + * pointer to void. + */ +typedef xQUEUE * xQueueHandle; + +/* + * Prototypes for public functions are included here so we don't have to + * include the API header file (as it defines xQueueHandle differently). These + * functions are documented in the API header file. + */ +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateMutex( void ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Co-routine queue functions differ from task queue functions. Co-routines are + * an optional component. + */ +#if configUSE_CO_ROUTINES == 1 + signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; +#endif + +/* + * The queue registry is just a means for kernel aware debuggers to locate + * queue structures. It has no other purpose so is an optional component. + */ +#if configQUEUE_REGISTRY_SIZE > 0 + + /* The type stored within the queue registry array. This allows a name + to be assigned to each queue making kernel aware debugging a little + more user friendly. */ + typedef struct QUEUE_REGISTRY_ITEM + { + signed char *pcQueueName; + xQueueHandle xHandle; + } xQueueRegistryItem; + + /* The queue registry is simply an array of xQueueRegistryItem structures. + The pcQueueName member of a structure being NULL is indicative of the + array position being vacant. */ + xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; + + /* Removes a queue from the registry by simply setting the pcQueueName + member to NULL. */ + static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; +#endif + +/* + * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not + * prevent an ISR from adding or removing items to the queue, but does prevent + * an ISR from removing tasks from the queue event lists. If an ISR finds a + * queue is locked it will instead increment the appropriate queue lock count + * to indicate that a task may require unblocking. When the queue in unlocked + * these lock counts are inspected, and the appropriate action taken. + */ +static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any data in a queue. + * + * @return pdTRUE if the queue contains no items, otherwise pdFALSE. + */ +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any space in a queue. + * + * @return pdTRUE if there is no space, otherwise pdFALSE; + */ +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Copies an item into the queue, either at the front of the queue or the + * back of the queue. + */ +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; + +/* + * Copies an item out of a queue. + */ +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; +/*-----------------------------------------------------------*/ + +/* + * Macro to mark a queue as locked. Locking a queue prevents an ISR from + * accessing the queue event lists. + */ +#define prvLockQueue( pxQueue ) \ +{ \ + taskENTER_CRITICAL(); \ + { \ + if( pxQueue->xRxLock == queueUNLOCKED ) \ + { \ + pxQueue->xRxLock = queueLOCKED_UNMODIFIED; \ + } \ + if( pxQueue->xTxLock == queueUNLOCKED ) \ + { \ + pxQueue->xTxLock = queueLOCKED_UNMODIFIED; \ + } \ + } \ + taskEXIT_CRITICAL(); \ +} +/*-----------------------------------------------------------*/ + + +/*----------------------------------------------------------- + * PUBLIC QUEUE MANAGEMENT API documented in queue.h + *----------------------------------------------------------*/ + +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) +{ +xQUEUE *pxNewQueue; +size_t xQueueSizeInBytes; + + /* Allocate the new queue structure. */ + if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) + { + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Create the list of pointers to queue items. The queue is one byte + longer than asked for to make wrap checking easier/faster. */ + xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; + + pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); + if( pxNewQueue->pcHead != NULL ) + { + /* Initialise the queue members as described above where the + queue type is defined. */ + pxNewQueue->pcTail = pxNewQueue->pcHead + ( uxQueueLength * uxItemSize ); + pxNewQueue->uxMessagesWaiting = 0; + pxNewQueue->pcWriteTo = pxNewQueue->pcHead; + pxNewQueue->pcReadFrom = pxNewQueue->pcHead + ( ( uxQueueLength - 1 ) * uxItemSize ); + pxNewQueue->uxLength = uxQueueLength; + pxNewQueue->uxItemSize = uxItemSize; + pxNewQueue->xRxLock = queueUNLOCKED; + pxNewQueue->xTxLock = queueUNLOCKED; + + /* Likewise ensure the event queues start with the correct state. */ + vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + + traceQUEUE_CREATE( pxNewQueue ); + return pxNewQueue; + } + else + { + traceQUEUE_CREATE_FAILED(); + vPortFree( pxNewQueue ); + } + } + } + + /* Will only reach here if we could not allocate enough memory or no memory + was required. */ + return NULL; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + xQueueHandle xQueueCreateMutex( void ) + { + xQUEUE *pxNewQueue; + + /* Allocate the new queue structure. */ + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Information required for priority inheritance. */ + pxNewQueue->pxMutexHolder = NULL; + pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; + + /* Queues used as a mutex no data is actually copied into or out + of the queue. */ + pxNewQueue->pcWriteTo = NULL; + pxNewQueue->pcReadFrom = NULL; + + /* Each mutex has a length of 1 (like a binary semaphore) and + an item size of 0 as nothing is actually copied into or out + of the mutex. */ + pxNewQueue->uxMessagesWaiting = 0; + pxNewQueue->uxLength = 1; + pxNewQueue->uxItemSize = 0; + pxNewQueue->xRxLock = queueUNLOCKED; + pxNewQueue->xTxLock = queueUNLOCKED; + + /* Ensure the event queues start with the correct state. */ + vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + + /* Start with the semaphore in the expected state. */ + xQueueGenericSend( pxNewQueue, NULL, 0, queueSEND_TO_BACK ); + + traceCREATE_MUTEX( pxNewQueue ); + } + else + { + traceCREATE_MUTEX_FAILED(); + } + + return pxNewQueue; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_RECURSIVE_MUTEXES == 1 + + portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) + { + portBASE_TYPE xReturn; + + /* If this is the task that holds the mutex then pxMutexHolder will not + change outside of this task. If this task does not hold the mutex then + pxMutexHolder can never coincidentally equal the tasks handle, and as + this is the only condition we are interested in it does not matter if + pxMutexHolder is accessed simultaneously by another task. Therefore no + mutual exclusion is required to test the pxMutexHolder variable. */ + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + traceGIVE_MUTEX_RECURSIVE( pxMutex ); + + /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to + the task handle, therefore no underflow check is required. Also, + uxRecursiveCallCount is only modified by the mutex holder, and as + there can only be one, no mutual exclusion is required to modify the + uxRecursiveCallCount member. */ + ( pxMutex->uxRecursiveCallCount )--; + + /* Have we unwound the call count? */ + if( pxMutex->uxRecursiveCallCount == 0 ) + { + /* Return the mutex. This will automatically unblock any other + task that might be waiting to access the mutex. */ + xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); + } + + xReturn = pdPASS; + } + else + { + /* We cannot give the mutex because we are not the holder. */ + xReturn = pdFAIL; + + traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_RECURSIVE_MUTEXES == 1 + + portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) + { + portBASE_TYPE xReturn; + + /* Comments regarding mutual exclusion as per those within + xQueueGiveMutexRecursive(). */ + + traceTAKE_MUTEX_RECURSIVE( pxMutex ); + + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + ( pxMutex->uxRecursiveCallCount )++; + xReturn = pdPASS; + } + else + { + xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); + + /* pdPASS will only be returned if we successfully obtained the mutex, + we may have blocked to reach here. */ + if( xReturn == pdPASS ) + { + ( pxMutex->uxRecursiveCallCount )++; + } + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_COUNTING_SEMAPHORES == 1 + + xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) + { + xQueueHandle pxHandle; + + pxHandle = xQueueCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH ); + + if( pxHandle != NULL ) + { + pxHandle->uxMessagesWaiting = uxInitialCount; + + traceCREATE_COUNTING_SEMAPHORE(); + } + else + { + traceCREATE_COUNTING_SEMAPHORE_FAILED(); + } + + return pxHandle; + } + +#endif /* configUSE_COUNTING_SEMAPHORES */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. Yes it is ok to do + this from within the critical section - the kernel + takes care of that. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting the + function. */ + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was full and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting + the function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was full and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + + /* Unlocking the queue means queue events can effect the + event list. It is possible that interrupts occurring now + remove this task from the event list again - but as the + scheduler is suspended the task will go onto the pending + ready last instead of the actual ready list. */ + prvUnlockQueue( pxQueue ); + + /* Resuming the scheduler will move tasks from the pending + ready list into the ready list - so it is feasible that this + task is already in a ready list before it yields - in which + case the yield will not cause a context switch unless there + is also a higher priority task in the pending ready list. */ + if( !xTaskResumeAll() ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* The timeout has expired. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + /* Return to the original privilege level before exiting the + function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } +} +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } + taskEXIT_CRITICAL(); + } + } + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + signed char *pcOriginalReadPosition; + + for( ;; ) + { + taskENTER_CRITICAL(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } + taskEXIT_CRITICAL(); + } + } + + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + /* Similar to xQueueGenericSend, except we don't block if there is no room + in the queue. Also we don't directly wake a task that was blocked on a + queue read, instead we return a flag to say whether a context switch is + required or not (i.e. has a task with a higher priority than us been woken + by this post). */ + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND_FROM_ISR( pxQueue ); + + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If the queue is locked we do not alter the event list. This will + be done when the queue is unlocked later. */ + if( pxQueue->xTxLock == queueUNLOCKED ) + { + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + *pxHigherPriorityTaskWoken = pdTRUE; + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was posted while it was locked. */ + ++( pxQueue->xTxLock ); + } + + xReturn = pdPASS; + } + else + { + traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); + xReturn = errQUEUE_FULL; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; +signed char *pcOriginalReadPosition; + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there data in the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was empty and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was empty and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + { + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + } + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( !xTaskResumeAll() ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* We cannot block from an ISR, so check there is data available. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + --( pxQueue->uxMessagesWaiting ); + + /* If the queue is locked we will not modify the event list. Instead + we update the lock count so the task that unlocks the queue will know + that an ISR has removed data while the queue was locked. */ + if( pxQueue->xRxLock == queueUNLOCKED ) + { + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than us so + force a context switch. */ + *pxTaskWoken = pdTRUE; + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was removed while it was locked. */ + ++( pxQueue->xRxLock ); + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + taskENTER_CRITICAL(); + uxReturn = pxQueue->uxMessagesWaiting; + taskEXIT_CRITICAL(); + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + uxReturn = pxQueue->uxMessagesWaiting; + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +void vQueueDelete( xQueueHandle pxQueue ) +{ + traceQUEUE_DELETE( pxQueue ); + vQueueUnregisterQueue( pxQueue ); + vPortFree( pxQueue->pcHead ); + vPortFree( pxQueue ); +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) +{ + if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) + { + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* The mutex is no longer being held. */ + vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); + pxQueue->pxMutexHolder = NULL; + } + } + #endif + } + else if( xPosition == queueSEND_TO_BACK ) + { + memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcWriteTo += pxQueue->uxItemSize; + if( pxQueue->pcWriteTo >= pxQueue->pcTail ) + { + pxQueue->pcWriteTo = pxQueue->pcHead; + } + } + else + { + memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcReadFrom -= pxQueue->uxItemSize; + if( pxQueue->pcReadFrom < pxQueue->pcHead ) + { + pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); + } + } + + ++( pxQueue->uxMessagesWaiting ); +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) +{ + if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) + { + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + } +} +/*-----------------------------------------------------------*/ + +static void prvUnlockQueue( xQueueHandle pxQueue ) +{ + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ + + /* The lock counts contains the number of extra data items placed or + removed from the queue while the queue was locked. When a queue is + locked items can be added or removed, but the event lists cannot be + updated. */ + taskENTER_CRITICAL(); + { + /* See if data was added to the queue while it was locked. */ + while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) + { + /* Data was posted while the queue was locked. Are any tasks + blocked waiting for data to become available? */ + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + vTaskMissedYield(); + } + + --( pxQueue->xTxLock ); + } + else + { + break; + } + } + + pxQueue->xTxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); + + /* Do the same for the Rx lock. */ + taskENTER_CRITICAL(); + { + while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) + { + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + vTaskMissedYield(); + } + + --( pxQueue->xRxLock ); + } + else + { + break; + } + } + + pxQueue->xRxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already full we may have to block. A critical section + is required to prevent an interrupt removing something from the queue + between the check to see if the queue is full and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( prvIsQueueFull( pxQueue ) ) + { + /* The queue is full - do we want to block or just leave without + posting? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is called from a coroutine we cannot block directly, but + return indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + /* There is room in the queue, copy the data into the queue. */ + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + xReturn = pdPASS; + + /* Were any co-routines waiting for data to become available? */ + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The co-routine waiting has a higher priority so record + that a yield might be appropriate. */ + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = errQUEUE_FULL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already empty we may have to block. A critical section + is required to prevent an interrupt adding something to the queue + between the check to see if the queue is empty and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) + { + /* There are no messages in the queue, do we want to block or just + leave with nothing? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is a co-routine we cannot block directly, but return + indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Data is available from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + xReturn = pdPASS; + + /* Were any co-routines waiting for space to become available? */ + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = pdFAIL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + + + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) +{ + /* Cannot block within an ISR so if there is no space on the queue then + exit without doing anything. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + + /* We only want to wake one co-routine per ISR, so check that a + co-routine has not already been woken. */ + if( !xCoRoutinePreviouslyWoken ) + { + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + return pdTRUE; + } + } + } + } + + return xCoRoutinePreviouslyWoken; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) +{ +signed portBASE_TYPE xReturn; + + /* We cannot block from an ISR, so check there is data available. If + not then just leave without doing anything. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Copy the data from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + if( !( *pxCoRoutineWoken ) ) + { + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + *pxCoRoutineWoken = pdTRUE; + } + } + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) + { + unsigned portBASE_TYPE ux; + + /* See if there is an empty space in the registry. A NULL name denotes + a free slot. */ + for( ux = 0; ux < configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].pcQueueName == NULL ) + { + /* Store the information on this queue. */ + xQueueRegistry[ ux ].pcQueueName = pcQueueName; + xQueueRegistry[ ux ].xHandle = xQueue; + break; + } + } + } + +#endif + /*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + static void vQueueUnregisterQueue( xQueueHandle xQueue ) + { + unsigned portBASE_TYPE ux; + + /* See if the handle of the queue being unregistered in actually in the + registry. */ + for( ux = 0; ux < configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].xHandle == xQueue ) + { + /* Set the name to NULL to show that this slot if free again. */ + xQueueRegistry[ ux ].pcQueueName = NULL; + break; + } + } + + } + +#endif + diff --git a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/tasks.c b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/tasks.c index ec5699485..b21004818 100644 --- a/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/tasks.c +++ b/flight/PiOS.win32/win32/Libraries/FreeRTOS/Source/tasks.c @@ -1,2318 +1,2318 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#include -#include -#include -#include -#include "portable/GCC/Win32/portmacro.h" - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "StackMacros.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* - * Macro to define the amount of stack available to the idle task. - */ -#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE - -/* - * Task control block. A task control block (TCB) is allocated to each task, - * and stores the context of the task. - */ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - - #if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ - #endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - - #if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ - #endif - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; - #endif - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ - #endif - - #if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ - #endif - -} tskTCB; - - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - -/*lint -e956 */ -PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; - -/* Lists for ready and blocked tasks. --------------------*/ - -PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ -PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ - -#if ( INCLUDE_vTaskDelete == 1 ) - - PRIVILEGED_DATA static volatile xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ - PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0; - -#endif - -#if ( INCLUDE_vTaskSuspend == 1 ) - - PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ - -#endif - -/* File private variables. --------------------------------*/ -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0; -PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0; - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - PRIVILEGED_DATA static char pcStatsString[ 50 ] ; - PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; - -#endif - -/* Debugging and trace facilities private variables and macros. ------------*/ - -/* - * The value used to fill the stack of a task when the task is created. This - * is used purely for checking the high water mark for tasks. - */ -#define tskSTACK_FILL_BYTE ( 0xa5 ) - -/* - * Macros used by vListTask to indicate which state a task is in. - */ -#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) -#define tskREADY_CHAR ( ( signed char ) 'R' ) -#define tskDELETED_CHAR ( ( signed char ) 'D' ) -#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) - -/* - * Macros and private variables used by the trace facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define tskSIZE_OF_EACH_TRACE_LINE ( ( unsigned long ) ( sizeof( unsigned long ) + sizeof( unsigned long ) ) ) - PRIVILEGED_DATA static volatile signed char * volatile pcTraceBuffer; - PRIVILEGED_DATA static signed char *pcTraceBufferStart; - PRIVILEGED_DATA static signed char *pcTraceBufferEnd; - PRIVILEGED_DATA static signed portBASE_TYPE xTracing = pdFALSE; - static unsigned portBASE_TYPE uxPreviousTask = 255; - PRIVILEGED_DATA static char pcStatusString[ 50 ]; - -#endif - -/*-----------------------------------------------------------*/ - -/* - * Macro that writes a trace of scheduler activity to a buffer. This trace - * shows which task is running when and is very useful as a debugging tool. - * As this macro is called each context switch it is a good idea to undefine - * it if not using the facility. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - #define vWriteTraceToBuffer() \ - { \ - if( xTracing ) \ - { \ - if( uxPreviousTask != pxCurrentTCB->uxTCBNumber ) \ - { \ - if( ( pcTraceBuffer + tskSIZE_OF_EACH_TRACE_LINE ) < pcTraceBufferEnd ) \ - { \ - uxPreviousTask = pxCurrentTCB->uxTCBNumber; \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) xTickCount; \ - pcTraceBuffer += sizeof( unsigned long ); \ - *( unsigned long * ) pcTraceBuffer = ( unsigned long ) uxPreviousTask; \ - pcTraceBuffer += sizeof( unsigned long ); \ - } \ - else \ - { \ - xTracing = pdFALSE; \ - } \ - } \ - } \ - } - -#else - - #define vWriteTraceToBuffer() - -#endif -/*-----------------------------------------------------------*/ - -/* - * Place the task represented by pxTCB into the appropriate ready queue for - * the task. It is inserted at the end of the list. One quirk of this is - * that if the task being inserted is at the same priority as the currently - * executing task, then it will only be rescheduled after the currently - * executing task has been rescheduled. - */ -#define prvAddTaskToReadyQueue( pxTCB ) \ -{ \ - if( pxTCB->uxPriority > uxTopReadyPriority ) \ - { \ - uxTopReadyPriority = pxTCB->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ); \ -} -/*-----------------------------------------------------------*/ - -/* - * Macro that looks at the list of tasks that are currently delayed to see if - * any require waking. - * - * Tasks are stored in the queue in the order of their wake time - meaning - * once one tasks has been found whose timer has not expired we need not look - * any further down the list. - */ -#define prvCheckDelayedTasks() \ -{ \ -register tskTCB *pxTCB; \ - \ - while( ( pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ) ) != NULL ) \ - { \ - if( xTickCount < listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ) ) \ - { \ - break; \ - } \ - vListRemove( &( pxTCB->xGenericListItem ) ); \ - /* Is the task waiting on an event also? */ \ - if( pxTCB->xEventListItem.pvContainer ) \ - { \ - vListRemove( &( pxTCB->xEventListItem ) ); \ - } \ - prvAddTaskToReadyQueue( pxTCB ); \ - } \ -} -/*-----------------------------------------------------------*/ - -/* - * Several functions take an xTaskHandle parameter that can optionally be NULL, - * where NULL is used to indicate that the handle of the currently executing - * task should be used in place of the parameter. This macro simply checks to - * see if the parameter is NULL and returns a pointer to the appropriate TCB. - */ -#define prvGetTCBFromHandle( pxHandle ) ( ( pxHandle == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) pxHandle ) - - -/* File private functions. --------------------------------*/ - -/* - * Utility to ready a TCB for a given task. Mainly just copies the parameters - * into the TCB structure. - */ -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first task. - */ -static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; - -/* - * The idle task, which as all tasks is implemented as a never ending loop. - * The idle task is automatically created and added to the ready lists upon - * creation of the first user task. - * - * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); - -/* - * Utility to free all memory allocated by the scheduler to hold a TCB, - * including the stack pointed to by the TCB. - * - * This does not free memory allocated by the task itself (i.e. memory - * allocated by calls to pvPortMalloc from within the tasks application code). - */ -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) - - static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; - -#endif - -/* - * Used only by the idle task. This checks to see if anything has been placed - * in the list of tasks waiting to be deleted. If so the task is cleaned up - * and its TCB deleted. - */ -static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; - -/* - * Allocates memory from the heap for a TCB and associated stack. Checks the - * allocation was successful. - */ -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; - -/* - * Called from vTaskList. vListTasks details all the tasks currently under - * control of the scheduler. The tasks may be in one of a number of lists. - * prvListTaskWithinSingleList accepts a list and details the tasks from - * within just that list. - * - * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM - * NORMAL APPLICATION CODE. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; - -#endif - -/* - * When a task is created, the stack of the task is filled with a known value. - * This function determines the 'high water mark' of the task stack by - * determining how much of the stack remains at the original preset value. - */ -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; - -#endif - - -/*lint +e956 */ - - - -/*----------------------------------------------------------- - * TASK CREATION API documented in task.h - *----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) -{ -signed portBASE_TYPE xReturn; -tskTCB * pxNewTCB; - - /* Allocate the memory required by the TCB and stack for the new task, - checking that the allocation was successful. */ - pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); - - if( pxNewTCB != NULL ) - { - portSTACK_TYPE *pxTopOfStack; - - #if( portUSING_MPU_WRAPPERS == 1 ) - /* Should the task be created in privileged mode? */ - portBASE_TYPE xRunPrivileged; - if( ( uxPriority & portPRIVILEGE_BIT ) != 0x00 ) - { - xRunPrivileged = pdTRUE; - } - else - { - xRunPrivileged = pdFALSE; - } - uxPriority &= ~portPRIVILEGE_BIT; - #endif /* portUSING_MPU_WRAPPERS == 1 */ - - /* Calculate the top of stack address. This depends on whether the - stack grows from high memory to low (as per the 80x86) or visa versa. - portSTACK_GROWTH is used to make the result positive or negative as - required by the port. */ - #if( portSTACK_GROWTH < 0 ) - { - pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( unsigned long ) pxTopOfStack ) & ( ( unsigned long ) ~portBYTE_ALIGNMENT_MASK ) ); - } - #else - { - pxTopOfStack = pxNewTCB->pxStack; - - /* If we want to use stack checking on architectures that use - a positive stack growth direction then we also need to store the - other extreme of the stack space. */ - pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - } - #endif - - /* Setup the newly allocated TCB with the initial state of the task. */ - prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); - - /* Initialize the TCB stack to look as if the task was already running, - but had been interrupted by the scheduler. The return address is set - to the start of the task function. Once the stack has been initialised - the top of stack variable is updated. */ - #if( portUSING_MPU_WRAPPERS == 1 ) - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); - } - #else - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); - } - #endif - - /* We are going to manipulate the task queues to add this task to a - ready list, so must make sure no interrupts occur. */ - portENTER_CRITICAL(); - { - uxCurrentNumberOfTasks++; - if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) - { - /* As this is the first task it must also be the current task. */ - pxCurrentTCB = pxNewTCB; - - /* This is the first task to be created so do the preliminary - initialisation required. We will not recover if this call - fails, but we will report the failure. */ - prvInitialiseTaskLists(); - } - else - { - /* If the scheduler is not already running, make this task the - current task if it is the highest priority task to be created - so far. */ - if( xSchedulerRunning == pdFALSE ) - { - if( pxCurrentTCB->uxPriority <= uxPriority ) - { - pxCurrentTCB = pxNewTCB; - } - } - } - - /* Remember the top priority to make context switching faster. Use - the priority in pxNewTCB as this has been capped to a valid value. */ - if( pxNewTCB->uxPriority > uxTopUsedPriority ) - { - uxTopUsedPriority = pxNewTCB->uxPriority; - } - - #if ( configUSE_TRACE_FACILITY == 1 ) - { - /* Add a counter into the TCB for tracing only. */ - pxNewTCB->uxTCBNumber = uxTaskNumber; - } - #endif - uxTaskNumber++; - - prvAddTaskToReadyQueue( pxNewTCB ); - - xReturn = pdPASS; - traceTASK_CREATE( pxNewTCB ); - } - portEXIT_CRITICAL(); - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - traceTASK_CREATE_FAILED( pxNewTCB ); - } - - if( xReturn == pdPASS ) - { - if( ( void * ) pxCreatedTask != NULL ) - { - /* Pass the TCB out - in an anonymous way. The calling function/ - task can use this as a handle to delete the task later if - required.*/ - *pxCreatedTask = ( xTaskHandle ) pxNewTCB; - } - - if( xSchedulerRunning != pdFALSE ) - { - /* If the created task is of a higher priority than the current task - then it should run now. */ - if( pxCurrentTCB->uxPriority < uxPriority ) - { - portYIELD_WITHIN_API(); - } - } - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - void vTaskDelete( xTaskHandle pxTaskToDelete ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - deleted. */ - if( pxTaskToDelete == pxCurrentTCB ) - { - pxTaskToDelete = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); - - /* Remove task from the ready list and place in the termination list. - This will stop the task from be scheduled. The idle task will check - the termination list and free up any memory allocated by the - scheduler for the TCB and stack. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); - - /* Increment the ucTasksDeleted variable so the idle task knows - there is a task that has been deleted and that it should therefore - check the xTasksWaitingTermination list. */ - ++uxTasksDeleted; - - /* Increment the uxTaskNumberVariable also so kernel aware debuggers - can detect that the task lists need re-generating. */ - uxTaskNumber++; - - traceTASK_DELETE( pxTCB ); - } - portEXIT_CRITICAL(); - - /* Force a reschedule if we have just deleted the current task. */ - if( xSchedulerRunning != pdFALSE ) - { - if( ( void * ) pxTaskToDelete == NULL ) - { - portYIELD_WITHIN_API(); - } - } - } - -#endif - - - - - - -/*----------------------------------------------------------- - * TASK CONTROL API documented in task.h - *----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelayUntil == 1 ) - - void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) - { - portTickType xTimeToWake; - portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; - - vTaskSuspendAll(); - { - /* Generate the tick time at which the task wants to wake. */ - xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; - - if( xTickCount < *pxPreviousWakeTime ) - { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - else - { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - - /* Update the wake time ready for the next call. */ - *pxPreviousWakeTime = xTimeToWake; - - if( xShouldDelay ) - { - traceTASK_DELAY_UNTIL(); - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - } - xAlreadyYielded = xTaskResumeAll(); - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( !xAlreadyYielded ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelay == 1 ) - - void vTaskDelay( portTickType xTicksToDelay ) - { - portTickType xTimeToWake; - signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* A delay time of zero just forces a reschedule. */ - if( xTicksToDelay > ( portTickType ) 0 ) - { - vTaskSuspendAll(); - { - traceTASK_DELAY(); - - /* A task that is removed from the event list while the - scheduler is suspended will not get placed in the ready - list or removed from the blocked list until the scheduler - is resumed. - - This task cannot be in an event list as it is the currently - executing task. */ - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - xAlreadyYielded = xTaskResumeAll(); - } - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( !xAlreadyYielded ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskPriorityGet == 1 ) - - unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxReturn; - - portENTER_CRITICAL(); - { - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - uxReturn = pxTCB->uxPriority; - } - portEXIT_CRITICAL(); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskPrioritySet == 1 ) - - void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxCurrentPriority, xYieldRequired = pdFALSE; - - /* Ensure the new priority is valid. */ - if( uxNewPriority >= configMAX_PRIORITIES ) - { - uxNewPriority = configMAX_PRIORITIES - 1; - } - - portENTER_CRITICAL(); - { - if( pxTask == pxCurrentTCB ) - { - pxTask = NULL; - } - - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - - traceTASK_PRIORITY_SET( pxTask, uxNewPriority ); - - #if ( configUSE_MUTEXES == 1 ) - { - uxCurrentPriority = pxTCB->uxBasePriority; - } - #else - { - uxCurrentPriority = pxTCB->uxPriority; - } - #endif - - if( uxCurrentPriority != uxNewPriority ) - { - /* The priority change may have readied a task of higher - priority than the calling task. */ - if( uxNewPriority > uxCurrentPriority ) - { - if( pxTask != NULL ) - { - /* The priority of another task is being raised. If we - were raising the priority of the currently running task - there would be no need to switch as it must have already - been the highest priority task. */ - xYieldRequired = pdTRUE; - } - } - else if( pxTask == NULL ) - { - /* Setting our own priority down means there may now be another - task of higher priority that is ready to execute. */ - xYieldRequired = pdTRUE; - } - - - - #if ( configUSE_MUTEXES == 1 ) - { - /* Only change the priority being used if the task is not - currently using an inherited priority. */ - if( pxTCB->uxBasePriority == pxTCB->uxPriority ) - { - pxTCB->uxPriority = uxNewPriority; - } - - /* The base priority gets set whatever. */ - pxTCB->uxBasePriority = uxNewPriority; - } - #else - { - pxTCB->uxPriority = uxNewPriority; - } - #endif - - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); - - /* If the task is in the blocked or suspended list we need do - nothing more than change it's priority variable. However, if - the task is in a ready list it needs to be removed and placed - in the queue appropriate to its new priority. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - /* The task is currently in its ready list - remove before adding - it to it's new ready list. As we are in a critical section we - can do this even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - - if( xYieldRequired == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - portEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskSuspend( xTaskHandle pxTaskToSuspend ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - suspended. */ - if( pxTaskToSuspend == pxCurrentTCB ) - { - pxTaskToSuspend = NULL; - } - - /* If null is passed in here then we are suspending ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); - - traceTASK_SUSPEND( pxTCB ); - - /* Remove task from the ready/delayed list and place in the suspended list. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); - } - portEXIT_CRITICAL(); - - /* We may have just suspended the current task. */ - if( ( void * ) pxTaskToSuspend == NULL ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) - { - portBASE_TYPE xReturn = pdFALSE; - const tskTCB * const pxTCB = ( tskTCB * ) xTask; - - /* Is the task we are attempting to resume actually in the - suspended list? */ - if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - /* Has the task already been resumed from within an ISR? */ - if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) - { - /* Is it in the suspended list because it is in the - Suspended state? It is possible to be in the suspended - list because it is blocked on a task with no timeout - specified. */ - if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) - { - xReturn = pdTRUE; - } - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskResume( xTaskHandle pxTaskToResume ) - { - tskTCB *pxTCB; - - /* Remove the task from whichever list it is currently in, and place - it in the ready list. */ - pxTCB = ( tskTCB * ) pxTaskToResume; - - /* The parameter cannot be NULL as it is impossible to resume the - currently executing task. */ - if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) - { - portENTER_CRITICAL(); - { - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME( pxTCB ); - - /* As we are in a critical section we can access the ready - lists even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* We may have just resumed a higher priority task. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* This yield may not cause the task just resumed to run, but - will leave the lists in the correct state for the next yield. */ - portYIELD_WITHIN_API(); - } - } - } - portEXIT_CRITICAL(); - } - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - tskTCB *pxTCB; - - pxTCB = ( tskTCB * ) pxTaskToResume; - - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME_FROM_ISR( pxTCB ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed, at which point a - yield will be performed if necessary. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); - } - } - - return xYieldRequired; - } - -#endif - - - - -/*----------------------------------------------------------- - * PUBLIC SCHEDULER CONTROL documented in task.h - *----------------------------------------------------------*/ - - -void vTaskStartScheduler( void ) -{ -portBASE_TYPE xReturn; - - /* Add the idle task at the lowest priority. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), ( xTaskHandle * ) NULL ); - - if( xReturn == pdPASS ) - { - /* Interrupts are turned off here, to ensure a tick does not occur - before or during the call to xPortStartScheduler(). The stacks of - the created tasks contain a status word with interrupts switched on - so interrupts will automatically get re-enabled when the first task - starts to run. - - STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE - DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ - portDISABLE_INTERRUPTS(); - - xSchedulerRunning = pdTRUE; - xTickCount = ( portTickType ) 0; - - /* Setting up the timer tick is hardware specific and thus in the - portable interface. */ - if( xPortStartScheduler() ) - { - /* Should not reach here as if the scheduler is running the - function will not return. */ - } - else - { - /* Should only reach here if a task calls xTaskEndScheduler(). */ - } - } -} -/*-----------------------------------------------------------*/ - -void vTaskEndScheduler( void ) -{ - /* Stop the scheduler interrupts and call the portable scheduler end - routine so the original ISRs can be restored if necessary. The port - layer must ensure interrupts enable bit is left in the correct state. */ - portDISABLE_INTERRUPTS(); - xSchedulerRunning = pdFALSE; - vPortEndScheduler(); -} -/*----------------------------------------------------------*/ - -void vTaskSuspendAll( void ) -{ - /* A critical section is not required as the variable is of type - portBASE_TYPE. */ - ++uxSchedulerSuspended; -} -/*----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskResumeAll( void ) -{ -register tskTCB *pxTCB; -signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* It is possible that an ISR caused a task to be removed from an event - list while the scheduler was suspended. If this was the case then the - removed task will have been added to the xPendingReadyList. Once the - scheduler has been resumed it is safe to move all the pending ready - tasks from this list into their appropriate ready list. */ - portENTER_CRITICAL(); - { - --uxSchedulerSuspended; - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0 ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - - /* Move any readied tasks from the pending list into the - appropriate ready list. */ - while( ( pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ) ) != NULL ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* If we have moved a task that has a priority higher than - the current task then we should yield. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - xYieldRequired = pdTRUE; - } - } - - /* If any ticks occurred while the scheduler was suspended then - they should be processed now. This ensures the tick count does not - slip, and that any delayed tasks are resumed at the correct time. */ - if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) - { - while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) - { - vTaskIncrementTick(); - --uxMissedTicks; - } - - /* As we have processed some ticks it is appropriate to yield - to ensure the highest priority task that is ready to run is - the task actually running. */ - #if configUSE_PREEMPTION == 1 - { - xYieldRequired = pdTRUE; - } - #endif - } - - if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) - { - xAlreadyYielded = pdTRUE; - xMissedYield = pdFALSE; - portYIELD_WITHIN_API(); - } - } - } - } - portEXIT_CRITICAL(); - - return xAlreadyYielded; -} - - - - - - -/*----------------------------------------------------------- - * PUBLIC TASK UTILITIES documented in task.h - *----------------------------------------------------------*/ - - - -portTickType xTaskGetTickCount( void ) -{ -portTickType xTicks; - - /* Critical section required if running on a 16 bit processor. */ - portENTER_CRITICAL(); - { - xTicks = xTickCount; - } - portEXIT_CRITICAL(); - - return xTicks; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) -{ - /* A critical section is not required because the variables are of type - portBASE_TYPE. */ - return uxCurrentNumberOfTasks; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskList( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB and - report the task name, state and stack high water mark. */ - - pcWriteBuffer[ 0 ] = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + 1; - - do - { - uxQueue--; - - if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); - } - - if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); - } - - #if( INCLUDE_vTaskDelete == 1 ) - { - if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, tskDELETED_CHAR ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, tskSUSPENDED_CHAR ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - unsigned long ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB, - generating a table of run timer percentages in the provided - buffer. */ - - pcWriteBuffer[ 0 ] = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + 1; - - do - { - uxQueue--; - - if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); - } - - if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); - } - - #if ( INCLUDE_vTaskDelete == 1 ) - { - if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, ulTotalRunTime ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, ulTotalRunTime ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) - { - portENTER_CRITICAL(); - { - pcTraceBuffer = ( signed char * )pcBuffer; - pcTraceBufferStart = pcBuffer; - pcTraceBufferEnd = pcBuffer + ( ulBufferSize - tskSIZE_OF_EACH_TRACE_LINE ); - xTracing = pdTRUE; - } - portEXIT_CRITICAL(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned long ulTaskEndTrace( void ) - { - unsigned long ulBufferLength; - - portENTER_CRITICAL(); - xTracing = pdFALSE; - portEXIT_CRITICAL(); - - ulBufferLength = ( unsigned long ) ( pcTraceBuffer - pcTraceBufferStart ); - - return ulBufferLength; - } - -#endif - - - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - * documented in task.h - *----------------------------------------------------------*/ - - -void vTaskIncrementTick( void ) -{ - /* Called by the portable layer each time a tick interrupt occurs. - Increments the tick then checks to see if the new tick value will cause any - tasks to be unblocked. */ - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - ++xTickCount; - if( xTickCount == ( portTickType ) 0 ) - { - xList *pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. - If there are any items in pxDelayedTaskList here then there is - an error! */ - pxTemp = pxDelayedTaskList; - pxDelayedTaskList = pxOverflowDelayedTaskList; - pxOverflowDelayedTaskList = pxTemp; - xNumOfOverflows++; - } - - /* See if this tick has made a timeout expire. */ - prvCheckDelayedTasks(); - } - else - { - ++uxMissedTicks; - - /* The tick hook gets called at regular intervals, even if the - scheduler is locked. */ - #if ( configUSE_TICK_HOOK == 1 ) - { - extern void vApplicationTickHook( void ); - - vApplicationTickHook(); - } - #endif - } - - #if ( configUSE_TICK_HOOK == 1 ) - { - extern void vApplicationTickHook( void ); - - /* Guard against the tick hook being called when the missed tick - count is being unwound (when the scheduler is being unlocked. */ - if( uxMissedTicks == 0 ) - { - vApplicationTickHook(); - } - } - #endif - - traceTASK_INCREMENT_TICK( xTickCount ); -} -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_vTaskCleanUpResources == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - void vTaskCleanUpResources( void ) - { - unsigned short usQueue; - volatile tskTCB *pxTCB; - - usQueue = ( unsigned short ) uxTopUsedPriority + ( unsigned short ) 1; - - /* Remove any TCB's from the ready queues. */ - do - { - usQueue--; - - while( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ usQueue ] ) ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &( pxReadyTasksLists[ usQueue ] ) ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - }while( usQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - /* Remove any TCB's from the delayed queue. */ - while( !listLIST_IS_EMPTY( &xDelayedTaskList1 ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList1 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - /* Remove any TCB's from the overflow delayed queue. */ - while( !listLIST_IS_EMPTY( &xDelayedTaskList2 ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList2 ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - - while( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) - { - listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xSuspendedTaskList ); - vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); - - prvDeleteTCB( ( tskTCB * ) pxTCB ); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxTagValue ) - { - tskTCB *xTCB; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - portENTER_CRITICAL(); - xTCB->pxTaskTag = pxTagValue; - portEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) - { - tskTCB *xTCB; - pdTASK_HOOK_CODE xReturn; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - portENTER_CRITICAL(); - xReturn = xTCB->pxTaskTag; - portEXIT_CRITICAL(); - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) - { - tskTCB *xTCB; - portBASE_TYPE xReturn; - - /* If xTask is NULL then we are calling our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - if( xTCB->pxTaskTag != NULL ) - { - xReturn = xTCB->pxTaskTag( pvParameter ); - } - else - { - xReturn = pdFAIL; - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -void vTaskSwitchContext( void ) -{ - if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) - { - /* The scheduler is currently suspended - do not allow a context - switch. */ - xMissedYield = pdTRUE; - return; - } - - traceTASK_SWITCHED_OUT(); - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - unsigned long ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); - - /* Add the amount of time the task has been running to the accumulated - time so far. The time the task started running was stored in - ulTaskSwitchedInTime. Note that there is no overflow protection here - so count values are only valid until the timer overflows. Generally - this will be about 1 hour assuming a 1uS timer increment. */ - pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); - ulTaskSwitchedInTime = ulTempCounter; - } - #endif - - taskFIRST_CHECK_FOR_STACK_OVERFLOW(); - taskSECOND_CHECK_FOR_STACK_OVERFLOW(); - - /* Find the highest priority queue that contains ready tasks. */ - while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) - { - --uxTopReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the - same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); - - traceTASK_SWITCHED_IN(); - vWriteTraceToBuffer(); -} -/*-----------------------------------------------------------*/ - -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) -{ -portTickType xTimeToWake; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. */ - - /* Place the event list item of the TCB in the appropriate event list. - This is placed in the list in priority order so the highest priority task - is the first to be woken by the event. */ - vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove ourselves from the ready list before adding ourselves - to the blocked list as the same list item is used for both lists. We have - exclusive access to the ready lists as the scheduler is locked. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( xTicksToWait == portMAX_DELAY ) - { - /* Add ourselves to the suspended task list instead of a delayed task - list to ensure we are not woken by a timing event. We will block - indefinitely. */ - vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - } - #else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - } - #endif -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) -{ -tskTCB *pxUnblockedTCB; -portBASE_TYPE xReturn; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. It can also be called from within an ISR. */ - - /* The event list is sorted in priority order, so we can remove the - first in the list, remove the TCB from the delayed list, and add - it to the ready list. - - If an event is for a queue that is locked then this function will never - get called - the lock count on the queue will get modified instead. This - means we can always expect exclusive access to the event list here. */ - pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - vListRemove( &( pxUnblockedTCB->xEventListItem ) ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxUnblockedTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); - } - - if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* Return true if the task removed from the event list has - a higher priority than the calling task. This allows - the calling task to know if it should force a context - switch now. */ - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) -{ - pxTimeOut->xOverflowCount = xNumOfOverflows; - pxTimeOut->xTimeOnEntering = xTickCount; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) -{ -portBASE_TYPE xReturn; - - portENTER_CRITICAL(); - { - #if ( INCLUDE_vTaskSuspend == 1 ) - /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is - the maximum block time then the task should block indefinitely, and - therefore never time out. */ - if( *pxTicksToWait == portMAX_DELAY ) - { - xReturn = pdFALSE; - } - else /* We are not blocking indefinitely, perform the checks below. */ - #endif - - if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) - { - /* The tick count is greater than the time at which vTaskSetTimeout() - was called, but has also overflowed since vTaskSetTimeOut() was called. - It must have wrapped all the way around and gone past us again. This - passed since vTaskSetTimeout() was called. */ - xReturn = pdTRUE; - } - else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) - { - /* Not a genuine timeout. Adjust parameters for time remaining. */ - *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); - vTaskSetTimeOutState( pxTimeOut ); - xReturn = pdFALSE; - } - else - { - xReturn = pdTRUE; - } - } - portEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskMissedYield( void ) -{ - xMissedYield = pdTRUE; -} - -/* - * ----------------------------------------------------------- - * The Idle task. - * ---------------------------------------------------------- - * - * The portTASK_FUNCTION() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION( prvIdleTask, pvParameters ) -{ - /* Stop warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* See if any tasks have been deleted. */ - prvCheckTasksWaitingTermination(); - - #if ( configUSE_PREEMPTION == 0 ) - { - /* If we are not using preemption we keep forcing a task switch to - see if any other task has become available. If we are using - preemption we don't need to do this as any task becoming available - will automatically get the processor anyway. */ - taskYIELD(); - } - #endif - - #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) - { - /* When using preemption tasks of equal priority will be - timesliced. If a task that is sharing the idle priority is ready - to run then the idle task should yield before the end of the - timeslice. - - A critical region is not required here as we are just reading from - the list, and an occasional incorrect value will not matter. If - the ready list at the idle priority contains more than one task - then a task other than the idle task is ready to execute. */ - if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) - { - taskYIELD(); - } - } - #endif - - #if ( configUSE_IDLE_HOOK == 1 ) - { - extern void vApplicationIdleHook( void ); - - /* Call the user defined function from within the idle task. This - allows the application designer to add background functionality - without the overhead of a separate task. - NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, - CALL A FUNCTION THAT MIGHT BLOCK. */ - vApplicationIdleHook(); - } - #endif - // call Sleep for smalles sleep time possible - // (depending on kernel settings - around 100 microseconds) - // decreases idle thread CPU load from 100 to practically 0 -#ifdef IDLE_SLEEPS - Sleep(5); -#endif - } -} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ - - - - - - - -/*----------------------------------------------------------- - * File private functions documented at the top of the file. - *----------------------------------------------------------*/ - - - -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) -{ - /* Store the function name in the TCB. */ - #if configMAX_TASK_NAME_LEN > 1 - { - /* Don't bring strncpy into the build unnecessarily. */ - strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); - } - #endif - pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = '\0'; - - /* This is used as an array index so must ensure it's not too large. First - remove the privilege bit if one is present. */ - if( uxPriority >= configMAX_PRIORITIES ) - { - uxPriority = configMAX_PRIORITIES - 1; - } - - pxTCB->uxPriority = uxPriority; - #if ( configUSE_MUTEXES == 1 ) - { - pxTCB->uxBasePriority = uxPriority; - } - #endif - - vListInitialiseItem( &( pxTCB->xGenericListItem ) ); - vListInitialiseItem( &( pxTCB->xEventListItem ) ); - - /* Set the pxTCB as a link back from the xListItem. This is so we can get - back to the containing TCB from a generic item in a list. */ - listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - { - pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0; - } - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - { - pxTCB->pxTaskTag = NULL; - } - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - pxTCB->ulRunTimeCounter = 0UL; - } - #endif - - #if ( portUSING_MPU_WRAPPERS == 1 ) - { - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); - } - #else - { - ( void ) xRegions; - ( void ) usStackDepth; - } - #endif -} -/*-----------------------------------------------------------*/ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - - void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) - { - tskTCB *pxTCB; - - if( xTaskToModify == pxCurrentTCB ) - { - xTaskToModify = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( xTaskToModify ); - - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); - } - /*-----------------------------------------------------------*/ -#endif - -static void prvInitialiseTaskLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = 0; uxPriority < configMAX_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedTaskList1 ); - vListInitialise( ( xList * ) &xDelayedTaskList2 ); - vListInitialise( ( xList * ) &xPendingReadyList ); - - #if ( INCLUDE_vTaskDelete == 1 ) - { - vListInitialise( ( xList * ) &xTasksWaitingTermination ); - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - vListInitialise( ( xList * ) &xSuspendedTaskList ); - } - #endif - - /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList - using list2. */ - pxDelayedTaskList = &xDelayedTaskList1; - pxOverflowDelayedTaskList = &xDelayedTaskList2; -} -/*-----------------------------------------------------------*/ - -static void prvCheckTasksWaitingTermination( void ) -{ - #if ( INCLUDE_vTaskDelete == 1 ) - { - portBASE_TYPE xListIsEmpty; - - /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called - too often in the idle task. */ - if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0 ) - { - vTaskSuspendAll(); - xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); - xTaskResumeAll(); - - if( !xListIsEmpty ) - { - tskTCB *pxTCB; - - portENTER_CRITICAL(); - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - --uxCurrentNumberOfTasks; - --uxTasksDeleted; - } - portEXIT_CRITICAL(); - - prvDeleteTCB( pxTCB ); - } - } - } - #endif -} -/*-----------------------------------------------------------*/ - -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) -{ -tskTCB *pxNewTCB; - - /* Allocate space for the TCB. Where the memory comes from depends on - the implementation of the port malloc function. */ - pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); - - if( pxNewTCB != NULL ) - { - /* Allocate space for the stack used by the task being created. - The base of the stack memory stored in the TCB so the task can - be deleted later if required. */ - pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); - - if( pxNewTCB->pxStack == NULL ) - { - /* Could not allocate the stack. Delete the allocated TCB. */ - vPortFree( pxNewTCB ); - pxNewTCB = NULL; - } - else - { - /* Just to help debugging. */ - memset( pxNewTCB->pxStack, tskSTACK_FILL_BYTE, usStackDepth * sizeof( portSTACK_TYPE ) ); - } - } - - return pxNewTCB; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned short usStackRemaining; - - /* Write the details of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - #if ( portSTACK_GROWTH > 0 ) - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); - } - #else - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); - } - #endif - - sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned long ulStatsAsPercentage; - - /* Write the run time stats of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - /* Get next TCB in from the list. */ - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - - /* Divide by zero check. */ - if( ulTotalRunTime > 0UL ) - { - /* Has the task run at all? */ - if( pxNextTCB->ulRunTimeCounter == 0 ) - { - /* The task has used no CPU time at all. */ - sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); - } - else - { - /* What percentage of the total run time as the task used? - This will always be rounded down to the nearest integer. */ - ulStatsAsPercentage = ( 100UL * pxNextTCB->ulRunTimeCounter ) / ulTotalRunTime; - - if( ulStatsAsPercentage > 0UL ) - { - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); - } - else - { - /* If the percentage is zero here then the task has - consumed less than 1% of the total run time. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); - } - } - - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); - } - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) - { - register unsigned short usCount = 0; - - while( *pucStackByte == tskSTACK_FILL_BYTE ) - { - pucStackByte -= portSTACK_GROWTH; - usCount++; - } - - usCount /= sizeof( portSTACK_TYPE ); - - return usCount; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) - - unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) - { - tskTCB *pxTCB; - unsigned char *pcEndOfStack; - unsigned portBASE_TYPE uxReturn; - - pxTCB = prvGetTCBFromHandle( xTask ); - - #if portSTACK_GROWTH < 0 - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; - } - #else - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; - } - #endif - - uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) - - static void prvDeleteTCB( tskTCB *pxTCB ) - { - /* Free up the memory allocated by the scheduler for the task. It is up to - the task to free any memory allocated at the application level. */ - vPortFreeAligned( pxTCB->pxStack ); - vPortFree( pxTCB ); - } - -#endif - - -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) - - xTaskHandle xTaskGetCurrentTaskHandle( void ) - { - xTaskHandle xReturn; - - /* A critical section is not required as this is not called from - an interrupt and the current TCB will always be the same for any - individual execution thread. */ - xReturn = pxCurrentTCB; - - return xReturn; - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetSchedulerState == 1 ) - - portBASE_TYPE xTaskGetSchedulerState( void ) - { - portBASE_TYPE xReturn; - - if( xSchedulerRunning == pdFALSE ) - { - xReturn = taskSCHEDULER_NOT_STARTED; - } - else - { - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xReturn = taskSCHEDULER_RUNNING; - } - else - { - xReturn = taskSCHEDULER_SUSPENDED; - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) - { - /* Adjust the mutex holder state to account for its new priority. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); - - /* If the task being modified is in the ready state it will need to - be moved in to a new list. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Inherit the priority before being moved into the new list. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* Just inherit the priority. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxMutexHolder != NULL ) - { - if( pxTCB->uxPriority != pxTCB->uxBasePriority ) - { - /* We must be the running task to be able to give the mutex back. - Remove ourselves from the ready list we currently appear in. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Disinherit the priority before adding ourselves into the new - ready list. */ - pxTCB->uxPriority = pxTCB->uxBasePriority; - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); - prvAddTaskToReadyQueue( pxTCB ); - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - - void vTaskEnterCritical( void ) - { - portDISABLE_INTERRUPTS(); - - if( xSchedulerRunning != pdFALSE ) - { - pxCurrentTCB->uxCriticalNesting++; - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - -void vTaskExitCritical( void ) -{ - if( xSchedulerRunning != pdFALSE ) - { - if( pxCurrentTCB->uxCriticalNesting > 0 ) - { - pxCurrentTCB->uxCriticalNesting--; - - if( pxCurrentTCB->uxCriticalNesting == 0 ) - { - portENABLE_INTERRUPTS(); - } - } - } -} - -#endif -/*-----------------------------------------------------------*/ - - - - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#include +#include +#include +#include +#include "portable/GCC/Win32/portmacro.h" + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "StackMacros.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* + * Macro to define the amount of stack available to the idle task. + */ +#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE + +/* + * Task control block. A task control block (TCB) is allocated to each task, + * and stores the context of the task. + */ +typedef struct tskTaskControlBlock +{ + volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ + + #if ( portUSING_MPU_WRAPPERS == 1 ) + xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ + #endif + + xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ + portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ + signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ + + #if ( portSTACK_GROWTH > 0 ) + portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ + #endif + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + unsigned portBASE_TYPE uxCriticalNesting; + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + unsigned portBASE_TYPE uxTCBNumber; /*< This is used for tracing the scheduler and making debugging easier only. */ + #endif + + #if ( configUSE_MUTEXES == 1 ) + unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + pdTASK_HOOK_CODE pxTaskTag; + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ + #endif + +} tskTCB; + + +/* + * Some kernel aware debuggers require data to be viewed to be global, rather + * than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + +/*lint -e956 */ +PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; + +/* Lists for ready and blocked tasks. --------------------*/ + +PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ +PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ +PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ +PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ +PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ +PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ + +#if ( INCLUDE_vTaskDelete == 1 ) + + PRIVILEGED_DATA static volatile xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ + PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0; + +#endif + +#if ( INCLUDE_vTaskSuspend == 1 ) + + PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ + +#endif + +/* File private variables. --------------------------------*/ +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0; +PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0; +PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; +PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0; + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + PRIVILEGED_DATA static char pcStatsString[ 50 ] ; + PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ + static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; + +#endif + +/* Debugging and trace facilities private variables and macros. ------------*/ + +/* + * The value used to fill the stack of a task when the task is created. This + * is used purely for checking the high water mark for tasks. + */ +#define tskSTACK_FILL_BYTE ( 0xa5 ) + +/* + * Macros used by vListTask to indicate which state a task is in. + */ +#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) +#define tskREADY_CHAR ( ( signed char ) 'R' ) +#define tskDELETED_CHAR ( ( signed char ) 'D' ) +#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) + +/* + * Macros and private variables used by the trace facility. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + #define tskSIZE_OF_EACH_TRACE_LINE ( ( unsigned long ) ( sizeof( unsigned long ) + sizeof( unsigned long ) ) ) + PRIVILEGED_DATA static volatile signed char * volatile pcTraceBuffer; + PRIVILEGED_DATA static signed char *pcTraceBufferStart; + PRIVILEGED_DATA static signed char *pcTraceBufferEnd; + PRIVILEGED_DATA static signed portBASE_TYPE xTracing = pdFALSE; + static unsigned portBASE_TYPE uxPreviousTask = 255; + PRIVILEGED_DATA static char pcStatusString[ 50 ]; + +#endif + +/*-----------------------------------------------------------*/ + +/* + * Macro that writes a trace of scheduler activity to a buffer. This trace + * shows which task is running when and is very useful as a debugging tool. + * As this macro is called each context switch it is a good idea to undefine + * it if not using the facility. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + #define vWriteTraceToBuffer() \ + { \ + if( xTracing ) \ + { \ + if( uxPreviousTask != pxCurrentTCB->uxTCBNumber ) \ + { \ + if( ( pcTraceBuffer + tskSIZE_OF_EACH_TRACE_LINE ) < pcTraceBufferEnd ) \ + { \ + uxPreviousTask = pxCurrentTCB->uxTCBNumber; \ + *( unsigned long * ) pcTraceBuffer = ( unsigned long ) xTickCount; \ + pcTraceBuffer += sizeof( unsigned long ); \ + *( unsigned long * ) pcTraceBuffer = ( unsigned long ) uxPreviousTask; \ + pcTraceBuffer += sizeof( unsigned long ); \ + } \ + else \ + { \ + xTracing = pdFALSE; \ + } \ + } \ + } \ + } + +#else + + #define vWriteTraceToBuffer() + +#endif +/*-----------------------------------------------------------*/ + +/* + * Place the task represented by pxTCB into the appropriate ready queue for + * the task. It is inserted at the end of the list. One quirk of this is + * that if the task being inserted is at the same priority as the currently + * executing task, then it will only be rescheduled after the currently + * executing task has been rescheduled. + */ +#define prvAddTaskToReadyQueue( pxTCB ) \ +{ \ + if( pxTCB->uxPriority > uxTopReadyPriority ) \ + { \ + uxTopReadyPriority = pxTCB->uxPriority; \ + } \ + vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ); \ +} +/*-----------------------------------------------------------*/ + +/* + * Macro that looks at the list of tasks that are currently delayed to see if + * any require waking. + * + * Tasks are stored in the queue in the order of their wake time - meaning + * once one tasks has been found whose timer has not expired we need not look + * any further down the list. + */ +#define prvCheckDelayedTasks() \ +{ \ +register tskTCB *pxTCB; \ + \ + while( ( pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ) ) != NULL ) \ + { \ + if( xTickCount < listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ) ) \ + { \ + break; \ + } \ + vListRemove( &( pxTCB->xGenericListItem ) ); \ + /* Is the task waiting on an event also? */ \ + if( pxTCB->xEventListItem.pvContainer ) \ + { \ + vListRemove( &( pxTCB->xEventListItem ) ); \ + } \ + prvAddTaskToReadyQueue( pxTCB ); \ + } \ +} +/*-----------------------------------------------------------*/ + +/* + * Several functions take an xTaskHandle parameter that can optionally be NULL, + * where NULL is used to indicate that the handle of the currently executing + * task should be used in place of the parameter. This macro simply checks to + * see if the parameter is NULL and returns a pointer to the appropriate TCB. + */ +#define prvGetTCBFromHandle( pxHandle ) ( ( pxHandle == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) pxHandle ) + + +/* File private functions. --------------------------------*/ + +/* + * Utility to ready a TCB for a given task. Mainly just copies the parameters + * into the TCB structure. + */ +static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first task. + */ +static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; + +/* + * The idle task, which as all tasks is implemented as a never ending loop. + * The idle task is automatically created and added to the ready lists upon + * creation of the first user task. + * + * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); + +/* + * Utility to free all memory allocated by the scheduler to hold a TCB, + * including the stack pointed to by the TCB. + * + * This does not free memory allocated by the task itself (i.e. memory + * allocated by calls to pvPortMalloc from within the tasks application code). + */ +#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) + + static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Used only by the idle task. This checks to see if anything has been placed + * in the list of tasks waiting to be deleted. If so the task is cleaned up + * and its TCB deleted. + */ +static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; + +/* + * Allocates memory from the heap for a TCB and associated stack. Checks the + * allocation was successful. + */ +static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; + +/* + * Called from vTaskList. vListTasks details all the tasks currently under + * control of the scheduler. The tasks may be in one of a number of lists. + * prvListTaskWithinSingleList accepts a list and details the tasks from + * within just that list. + * + * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM + * NORMAL APPLICATION CODE. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; + +#endif + +/* + * When a task is created, the stack of the task is filled with a known value. + * This function determines the 'high water mark' of the task stack by + * determining how much of the stack remains at the original preset value. + */ +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) + + static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; + +#endif + + +/*lint +e956 */ + + + +/*----------------------------------------------------------- + * TASK CREATION API documented in task.h + *----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) +{ +signed portBASE_TYPE xReturn; +tskTCB * pxNewTCB; + + /* Allocate the memory required by the TCB and stack for the new task, + checking that the allocation was successful. */ + pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); + + if( pxNewTCB != NULL ) + { + portSTACK_TYPE *pxTopOfStack; + + #if( portUSING_MPU_WRAPPERS == 1 ) + /* Should the task be created in privileged mode? */ + portBASE_TYPE xRunPrivileged; + if( ( uxPriority & portPRIVILEGE_BIT ) != 0x00 ) + { + xRunPrivileged = pdTRUE; + } + else + { + xRunPrivileged = pdFALSE; + } + uxPriority &= ~portPRIVILEGE_BIT; + #endif /* portUSING_MPU_WRAPPERS == 1 */ + + /* Calculate the top of stack address. This depends on whether the + stack grows from high memory to low (as per the 80x86) or visa versa. + portSTACK_GROWTH is used to make the result positive or negative as + required by the port. */ + #if( portSTACK_GROWTH < 0 ) + { + pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); + pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( unsigned long ) pxTopOfStack ) & ( ( unsigned long ) ~portBYTE_ALIGNMENT_MASK ) ); + } + #else + { + pxTopOfStack = pxNewTCB->pxStack; + + /* If we want to use stack checking on architectures that use + a positive stack growth direction then we also need to store the + other extreme of the stack space. */ + pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); + } + #endif + + /* Setup the newly allocated TCB with the initial state of the task. */ + prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); + + /* Initialize the TCB stack to look as if the task was already running, + but had been interrupted by the scheduler. The return address is set + to the start of the task function. Once the stack has been initialised + the top of stack variable is updated. */ + #if( portUSING_MPU_WRAPPERS == 1 ) + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #else + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); + } + #endif + + /* We are going to manipulate the task queues to add this task to a + ready list, so must make sure no interrupts occur. */ + portENTER_CRITICAL(); + { + uxCurrentNumberOfTasks++; + if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) + { + /* As this is the first task it must also be the current task. */ + pxCurrentTCB = pxNewTCB; + + /* This is the first task to be created so do the preliminary + initialisation required. We will not recover if this call + fails, but we will report the failure. */ + prvInitialiseTaskLists(); + } + else + { + /* If the scheduler is not already running, make this task the + current task if it is the highest priority task to be created + so far. */ + if( xSchedulerRunning == pdFALSE ) + { + if( pxCurrentTCB->uxPriority <= uxPriority ) + { + pxCurrentTCB = pxNewTCB; + } + } + } + + /* Remember the top priority to make context switching faster. Use + the priority in pxNewTCB as this has been capped to a valid value. */ + if( pxNewTCB->uxPriority > uxTopUsedPriority ) + { + uxTopUsedPriority = pxNewTCB->uxPriority; + } + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + /* Add a counter into the TCB for tracing only. */ + pxNewTCB->uxTCBNumber = uxTaskNumber; + } + #endif + uxTaskNumber++; + + prvAddTaskToReadyQueue( pxNewTCB ); + + xReturn = pdPASS; + traceTASK_CREATE( pxNewTCB ); + } + portEXIT_CRITICAL(); + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + traceTASK_CREATE_FAILED( pxNewTCB ); + } + + if( xReturn == pdPASS ) + { + if( ( void * ) pxCreatedTask != NULL ) + { + /* Pass the TCB out - in an anonymous way. The calling function/ + task can use this as a handle to delete the task later if + required.*/ + *pxCreatedTask = ( xTaskHandle ) pxNewTCB; + } + + if( xSchedulerRunning != pdFALSE ) + { + /* If the created task is of a higher priority than the current task + then it should run now. */ + if( pxCurrentTCB->uxPriority < uxPriority ) + { + portYIELD_WITHIN_API(); + } + } + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + void vTaskDelete( xTaskHandle pxTaskToDelete ) + { + tskTCB *pxTCB; + + portENTER_CRITICAL(); + { + /* Ensure a yield is performed if the current task is being + deleted. */ + if( pxTaskToDelete == pxCurrentTCB ) + { + pxTaskToDelete = NULL; + } + + /* If null is passed in here then we are deleting ourselves. */ + pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); + + /* Remove task from the ready list and place in the termination list. + This will stop the task from be scheduled. The idle task will check + the termination list and free up any memory allocated by the + scheduler for the TCB and stack. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Is the task waiting on an event also? */ + if( pxTCB->xEventListItem.pvContainer ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + } + + vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); + + /* Increment the ucTasksDeleted variable so the idle task knows + there is a task that has been deleted and that it should therefore + check the xTasksWaitingTermination list. */ + ++uxTasksDeleted; + + /* Increment the uxTaskNumberVariable also so kernel aware debuggers + can detect that the task lists need re-generating. */ + uxTaskNumber++; + + traceTASK_DELETE( pxTCB ); + } + portEXIT_CRITICAL(); + + /* Force a reschedule if we have just deleted the current task. */ + if( xSchedulerRunning != pdFALSE ) + { + if( ( void * ) pxTaskToDelete == NULL ) + { + portYIELD_WITHIN_API(); + } + } + } + +#endif + + + + + + +/*----------------------------------------------------------- + * TASK CONTROL API documented in task.h + *----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelayUntil == 1 ) + + void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) + { + portTickType xTimeToWake; + portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; + + vTaskSuspendAll(); + { + /* Generate the tick time at which the task wants to wake. */ + xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; + + if( xTickCount < *pxPreviousWakeTime ) + { + /* The tick count has overflowed since this function was + lasted called. In this case the only time we should ever + actually delay is if the wake time has also overflowed, + and the wake time is greater than the tick time. When this + is the case it is as if neither time had overflowed. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) + { + xShouldDelay = pdTRUE; + } + } + else + { + /* The tick time has not overflowed. In this case we will + delay if either the wake time has overflowed, and/or the + tick time is less than the wake time. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) + { + xShouldDelay = pdTRUE; + } + } + + /* Update the wake time ready for the next call. */ + *pxPreviousWakeTime = xTimeToWake; + + if( xShouldDelay ) + { + traceTASK_DELAY_UNTIL(); + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xTickCount ) + { + /* Wake time has overflowed. Place this item in the + overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the + current block list. */ + vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + } + } + xAlreadyYielded = xTaskResumeAll(); + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( !xAlreadyYielded ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelay == 1 ) + + void vTaskDelay( portTickType xTicksToDelay ) + { + portTickType xTimeToWake; + signed portBASE_TYPE xAlreadyYielded = pdFALSE; + + /* A delay time of zero just forces a reschedule. */ + if( xTicksToDelay > ( portTickType ) 0 ) + { + vTaskSuspendAll(); + { + traceTASK_DELAY(); + + /* A task that is removed from the event list while the + scheduler is suspended will not get placed in the ready + list or removed from the blocked list until the scheduler + is resumed. + + This task cannot be in an event list as it is the currently + executing task. */ + + /* Calculate the time to wake - this may overflow but this is + not a problem. */ + xTimeToWake = xTickCount + xTicksToDelay; + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xTickCount ) + { + /* Wake time has overflowed. Place this item in the + overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the + current block list. */ + vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + } + xAlreadyYielded = xTaskResumeAll(); + } + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( !xAlreadyYielded ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskPriorityGet == 1 ) + + unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) + { + tskTCB *pxTCB; + unsigned portBASE_TYPE uxReturn; + + portENTER_CRITICAL(); + { + /* If null is passed in here then we are changing the + priority of the calling function. */ + pxTCB = prvGetTCBFromHandle( pxTask ); + uxReturn = pxTCB->uxPriority; + } + portEXIT_CRITICAL(); + + return uxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskPrioritySet == 1 ) + + void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) + { + tskTCB *pxTCB; + unsigned portBASE_TYPE uxCurrentPriority, xYieldRequired = pdFALSE; + + /* Ensure the new priority is valid. */ + if( uxNewPriority >= configMAX_PRIORITIES ) + { + uxNewPriority = configMAX_PRIORITIES - 1; + } + + portENTER_CRITICAL(); + { + if( pxTask == pxCurrentTCB ) + { + pxTask = NULL; + } + + /* If null is passed in here then we are changing the + priority of the calling function. */ + pxTCB = prvGetTCBFromHandle( pxTask ); + + traceTASK_PRIORITY_SET( pxTask, uxNewPriority ); + + #if ( configUSE_MUTEXES == 1 ) + { + uxCurrentPriority = pxTCB->uxBasePriority; + } + #else + { + uxCurrentPriority = pxTCB->uxPriority; + } + #endif + + if( uxCurrentPriority != uxNewPriority ) + { + /* The priority change may have readied a task of higher + priority than the calling task. */ + if( uxNewPriority > uxCurrentPriority ) + { + if( pxTask != NULL ) + { + /* The priority of another task is being raised. If we + were raising the priority of the currently running task + there would be no need to switch as it must have already + been the highest priority task. */ + xYieldRequired = pdTRUE; + } + } + else if( pxTask == NULL ) + { + /* Setting our own priority down means there may now be another + task of higher priority that is ready to execute. */ + xYieldRequired = pdTRUE; + } + + + + #if ( configUSE_MUTEXES == 1 ) + { + /* Only change the priority being used if the task is not + currently using an inherited priority. */ + if( pxTCB->uxBasePriority == pxTCB->uxPriority ) + { + pxTCB->uxPriority = uxNewPriority; + } + + /* The base priority gets set whatever. */ + pxTCB->uxBasePriority = uxNewPriority; + } + #else + { + pxTCB->uxPriority = uxNewPriority; + } + #endif + + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); + + /* If the task is in the blocked or suspended list we need do + nothing more than change it's priority variable. However, if + the task is in a ready list it needs to be removed and placed + in the queue appropriate to its new priority. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) + { + /* The task is currently in its ready list - remove before adding + it to it's new ready list. As we are in a critical section we + can do this even if the scheduler is suspended. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + + if( xYieldRequired == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + portEXIT_CRITICAL(); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskSuspend( xTaskHandle pxTaskToSuspend ) + { + tskTCB *pxTCB; + + portENTER_CRITICAL(); + { + /* Ensure a yield is performed if the current task is being + suspended. */ + if( pxTaskToSuspend == pxCurrentTCB ) + { + pxTaskToSuspend = NULL; + } + + /* If null is passed in here then we are suspending ourselves. */ + pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); + + traceTASK_SUSPEND( pxTCB ); + + /* Remove task from the ready/delayed list and place in the suspended list. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Is the task waiting on an event also? */ + if( pxTCB->xEventListItem.pvContainer ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + } + + vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); + } + portEXIT_CRITICAL(); + + /* We may have just suspended the current task. */ + if( ( void * ) pxTaskToSuspend == NULL ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) + { + portBASE_TYPE xReturn = pdFALSE; + const tskTCB * const pxTCB = ( tskTCB * ) xTask; + + /* Is the task we are attempting to resume actually in the + suspended list? */ + if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) + { + /* Has the task already been resumed from within an ISR? */ + if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) + { + /* Is it in the suspended list because it is in the + Suspended state? It is possible to be in the suspended + list because it is blocked on a task with no timeout + specified. */ + if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) + { + xReturn = pdTRUE; + } + } + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskResume( xTaskHandle pxTaskToResume ) + { + tskTCB *pxTCB; + + /* Remove the task from whichever list it is currently in, and place + it in the ready list. */ + pxTCB = ( tskTCB * ) pxTaskToResume; + + /* The parameter cannot be NULL as it is impossible to resume the + currently executing task. */ + if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) + { + portENTER_CRITICAL(); + { + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME( pxTCB ); + + /* As we are in a critical section we can access the ready + lists even if the scheduler is suspended. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + + /* We may have just resumed a higher priority task. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* This yield may not cause the task just resumed to run, but + will leave the lists in the correct state for the next yield. */ + portYIELD_WITHIN_API(); + } + } + } + portEXIT_CRITICAL(); + } + } + +#endif + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) + + portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) + { + portBASE_TYPE xYieldRequired = pdFALSE; + tskTCB *pxTCB; + + pxTCB = ( tskTCB * ) pxTaskToResume; + + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME_FROM_ISR( pxTCB ); + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed, at which point a + yield will be performed if necessary. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + } + + return xYieldRequired; + } + +#endif + + + + +/*----------------------------------------------------------- + * PUBLIC SCHEDULER CONTROL documented in task.h + *----------------------------------------------------------*/ + + +void vTaskStartScheduler( void ) +{ +portBASE_TYPE xReturn; + + /* Add the idle task at the lowest priority. */ + xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), ( xTaskHandle * ) NULL ); + + if( xReturn == pdPASS ) + { + /* Interrupts are turned off here, to ensure a tick does not occur + before or during the call to xPortStartScheduler(). The stacks of + the created tasks contain a status word with interrupts switched on + so interrupts will automatically get re-enabled when the first task + starts to run. + + STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE + DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ + portDISABLE_INTERRUPTS(); + + xSchedulerRunning = pdTRUE; + xTickCount = ( portTickType ) 0; + + /* Setting up the timer tick is hardware specific and thus in the + portable interface. */ + if( xPortStartScheduler() ) + { + /* Should not reach here as if the scheduler is running the + function will not return. */ + } + else + { + /* Should only reach here if a task calls xTaskEndScheduler(). */ + } + } +} +/*-----------------------------------------------------------*/ + +void vTaskEndScheduler( void ) +{ + /* Stop the scheduler interrupts and call the portable scheduler end + routine so the original ISRs can be restored if necessary. The port + layer must ensure interrupts enable bit is left in the correct state. */ + portDISABLE_INTERRUPTS(); + xSchedulerRunning = pdFALSE; + vPortEndScheduler(); +} +/*----------------------------------------------------------*/ + +void vTaskSuspendAll( void ) +{ + /* A critical section is not required as the variable is of type + portBASE_TYPE. */ + ++uxSchedulerSuspended; +} +/*----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskResumeAll( void ) +{ +register tskTCB *pxTCB; +signed portBASE_TYPE xAlreadyYielded = pdFALSE; + + /* It is possible that an ISR caused a task to be removed from an event + list while the scheduler was suspended. If this was the case then the + removed task will have been added to the xPendingReadyList. Once the + scheduler has been resumed it is safe to move all the pending ready + tasks from this list into their appropriate ready list. */ + portENTER_CRITICAL(); + { + --uxSchedulerSuspended; + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0 ) + { + portBASE_TYPE xYieldRequired = pdFALSE; + + /* Move any readied tasks from the pending list into the + appropriate ready list. */ + while( ( pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ) ) != NULL ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + + /* If we have moved a task that has a priority higher than + the current task then we should yield. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xYieldRequired = pdTRUE; + } + } + + /* If any ticks occurred while the scheduler was suspended then + they should be processed now. This ensures the tick count does not + slip, and that any delayed tasks are resumed at the correct time. */ + if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) + { + while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0 ) + { + vTaskIncrementTick(); + --uxMissedTicks; + } + + /* As we have processed some ticks it is appropriate to yield + to ensure the highest priority task that is ready to run is + the task actually running. */ + #if configUSE_PREEMPTION == 1 + { + xYieldRequired = pdTRUE; + } + #endif + } + + if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) + { + xAlreadyYielded = pdTRUE; + xMissedYield = pdFALSE; + portYIELD_WITHIN_API(); + } + } + } + } + portEXIT_CRITICAL(); + + return xAlreadyYielded; +} + + + + + + +/*----------------------------------------------------------- + * PUBLIC TASK UTILITIES documented in task.h + *----------------------------------------------------------*/ + + + +portTickType xTaskGetTickCount( void ) +{ +portTickType xTicks; + + /* Critical section required if running on a 16 bit processor. */ + portENTER_CRITICAL(); + { + xTicks = xTickCount; + } + portEXIT_CRITICAL(); + + return xTicks; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) +{ + /* A critical section is not required because the variables are of type + portBASE_TYPE. */ + return uxCurrentNumberOfTasks; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTaskList( signed char *pcWriteBuffer ) + { + unsigned portBASE_TYPE uxQueue; + + /* This is a VERY costly function that should be used for debug only. + It leaves interrupts disabled for a LONG time. */ + + vTaskSuspendAll(); + { + /* Run through all the lists that could potentially contain a TCB and + report the task name, state and stack high water mark. */ + + pcWriteBuffer[ 0 ] = ( signed char ) 0x00; + strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); + + uxQueue = uxTopUsedPriority + 1; + + do + { + uxQueue--; + + if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); + } + + if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); + } + + #if( INCLUDE_vTaskDelete == 1 ) + { + if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, tskDELETED_CHAR ); + } + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, tskSUSPENDED_CHAR ); + } + } + #endif + } + xTaskResumeAll(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) + { + unsigned portBASE_TYPE uxQueue; + unsigned long ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); + + /* This is a VERY costly function that should be used for debug only. + It leaves interrupts disabled for a LONG time. */ + + vTaskSuspendAll(); + { + /* Run through all the lists that could potentially contain a TCB, + generating a table of run timer percentages in the provided + buffer. */ + + pcWriteBuffer[ 0 ] = ( signed char ) 0x00; + strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); + + uxQueue = uxTopUsedPriority + 1; + + do + { + uxQueue--; + + if( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( !listLIST_IS_EMPTY( pxDelayedTaskList ) ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); + } + + if( !listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); + } + + #if ( INCLUDE_vTaskDelete == 1 ) + { + if( !listLIST_IS_EMPTY( &xTasksWaitingTermination ) ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xTasksWaitingTermination, ulTotalRunTime ); + } + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &xSuspendedTaskList, ulTotalRunTime ); + } + } + #endif + } + xTaskResumeAll(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) + { + portENTER_CRITICAL(); + { + pcTraceBuffer = ( signed char * )pcBuffer; + pcTraceBufferStart = pcBuffer; + pcTraceBufferEnd = pcBuffer + ( ulBufferSize - tskSIZE_OF_EACH_TRACE_LINE ); + xTracing = pdTRUE; + } + portEXIT_CRITICAL(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + unsigned long ulTaskEndTrace( void ) + { + unsigned long ulBufferLength; + + portENTER_CRITICAL(); + xTracing = pdFALSE; + portEXIT_CRITICAL(); + + ulBufferLength = ( unsigned long ) ( pcTraceBuffer - pcTraceBufferStart ); + + return ulBufferLength; + } + +#endif + + + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + * documented in task.h + *----------------------------------------------------------*/ + + +void vTaskIncrementTick( void ) +{ + /* Called by the portable layer each time a tick interrupt occurs. + Increments the tick then checks to see if the new tick value will cause any + tasks to be unblocked. */ + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + ++xTickCount; + if( xTickCount == ( portTickType ) 0 ) + { + xList *pxTemp; + + /* Tick count has overflowed so we need to swap the delay lists. + If there are any items in pxDelayedTaskList here then there is + an error! */ + pxTemp = pxDelayedTaskList; + pxDelayedTaskList = pxOverflowDelayedTaskList; + pxOverflowDelayedTaskList = pxTemp; + xNumOfOverflows++; + } + + /* See if this tick has made a timeout expire. */ + prvCheckDelayedTasks(); + } + else + { + ++uxMissedTicks; + + /* The tick hook gets called at regular intervals, even if the + scheduler is locked. */ + #if ( configUSE_TICK_HOOK == 1 ) + { + extern void vApplicationTickHook( void ); + + vApplicationTickHook(); + } + #endif + } + + #if ( configUSE_TICK_HOOK == 1 ) + { + extern void vApplicationTickHook( void ); + + /* Guard against the tick hook being called when the missed tick + count is being unwound (when the scheduler is being unlocked. */ + if( uxMissedTicks == 0 ) + { + vApplicationTickHook(); + } + } + #endif + + traceTASK_INCREMENT_TICK( xTickCount ); +} +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_vTaskCleanUpResources == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) + + void vTaskCleanUpResources( void ) + { + unsigned short usQueue; + volatile tskTCB *pxTCB; + + usQueue = ( unsigned short ) uxTopUsedPriority + ( unsigned short ) 1; + + /* Remove any TCB's from the ready queues. */ + do + { + usQueue--; + + while( !listLIST_IS_EMPTY( &( pxReadyTasksLists[ usQueue ] ) ) ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &( pxReadyTasksLists[ usQueue ] ) ); + vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); + + prvDeleteTCB( ( tskTCB * ) pxTCB ); + } + }while( usQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + /* Remove any TCB's from the delayed queue. */ + while( !listLIST_IS_EMPTY( &xDelayedTaskList1 ) ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList1 ); + vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); + + prvDeleteTCB( ( tskTCB * ) pxTCB ); + } + + /* Remove any TCB's from the overflow delayed queue. */ + while( !listLIST_IS_EMPTY( &xDelayedTaskList2 ) ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xDelayedTaskList2 ); + vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); + + prvDeleteTCB( ( tskTCB * ) pxTCB ); + } + + while( !listLIST_IS_EMPTY( &xSuspendedTaskList ) ) + { + listGET_OWNER_OF_NEXT_ENTRY( pxTCB, &xSuspendedTaskList ); + vListRemove( ( xListItem * ) &( pxTCB->xGenericListItem ) ); + + prvDeleteTCB( ( tskTCB * ) pxTCB ); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxTagValue ) + { + tskTCB *xTCB; + + /* If xTask is NULL then we are setting our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + portENTER_CRITICAL(); + xTCB->pxTaskTag = pxTagValue; + portEXIT_CRITICAL(); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) + { + tskTCB *xTCB; + pdTASK_HOOK_CODE xReturn; + + /* If xTask is NULL then we are setting our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + portENTER_CRITICAL(); + xReturn = xTCB->pxTaskTag; + portEXIT_CRITICAL(); + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) + { + tskTCB *xTCB; + portBASE_TYPE xReturn; + + /* If xTask is NULL then we are calling our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + if( xTCB->pxTaskTag != NULL ) + { + xReturn = xTCB->pxTaskTag( pvParameter ); + } + else + { + xReturn = pdFAIL; + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +void vTaskSwitchContext( void ) +{ + if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) + { + /* The scheduler is currently suspended - do not allow a context + switch. */ + xMissedYield = pdTRUE; + return; + } + + traceTASK_SWITCHED_OUT(); + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + unsigned long ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); + + /* Add the amount of time the task has been running to the accumulated + time so far. The time the task started running was stored in + ulTaskSwitchedInTime. Note that there is no overflow protection here + so count values are only valid until the timer overflows. Generally + this will be about 1 hour assuming a 1uS timer increment. */ + pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); + ulTaskSwitchedInTime = ulTempCounter; + } + #endif + + taskFIRST_CHECK_FOR_STACK_OVERFLOW(); + taskSECOND_CHECK_FOR_STACK_OVERFLOW(); + + /* Find the highest priority queue that contains ready tasks. */ + while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) + { + --uxTopReadyPriority; + } + + /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the + same priority get an equal share of the processor time. */ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); + + traceTASK_SWITCHED_IN(); + vWriteTraceToBuffer(); +} +/*-----------------------------------------------------------*/ + +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) +{ +portTickType xTimeToWake; + + /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED. */ + + /* Place the event list item of the TCB in the appropriate event list. + This is placed in the list in priority order so the highest priority task + is the first to be woken by the event. */ + vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); + + /* We must remove ourselves from the ready list before adding ourselves + to the blocked list as the same list item is used for both lists. We have + exclusive access to the ready lists as the scheduler is locked. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( xTicksToWait == portMAX_DELAY ) + { + /* Add ourselves to the suspended task list instead of a delayed task + list to ensure we are not woken by a timing event. We will block + indefinitely. */ + vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xTickCount ) + { + /* Wake time has overflowed. Place this item in the overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the current block list. */ + vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + } + } + #else + { + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xTickCount ) + { + /* Wake time has overflowed. Place this item in the overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the current block list. */ + vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + } + #endif +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) +{ +tskTCB *pxUnblockedTCB; +portBASE_TYPE xReturn; + + /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED. It can also be called from within an ISR. */ + + /* The event list is sorted in priority order, so we can remove the + first in the list, remove the TCB from the delayed list, and add + it to the ready list. + + If an event is for a queue that is locked then this function will never + get called - the lock count on the queue will get modified instead. This + means we can always expect exclusive access to the event list here. */ + pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); + vListRemove( &( pxUnblockedTCB->xEventListItem ) ); + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxUnblockedTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); + } + + if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* Return true if the task removed from the event list has + a higher priority than the calling task. This allows + the calling task to know if it should force a context + switch now. */ + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) +{ + pxTimeOut->xOverflowCount = xNumOfOverflows; + pxTimeOut->xTimeOnEntering = xTickCount; +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) +{ +portBASE_TYPE xReturn; + + portENTER_CRITICAL(); + { + #if ( INCLUDE_vTaskSuspend == 1 ) + /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is + the maximum block time then the task should block indefinitely, and + therefore never time out. */ + if( *pxTicksToWait == portMAX_DELAY ) + { + xReturn = pdFALSE; + } + else /* We are not blocking indefinitely, perform the checks below. */ + #endif + + if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) + { + /* The tick count is greater than the time at which vTaskSetTimeout() + was called, but has also overflowed since vTaskSetTimeOut() was called. + It must have wrapped all the way around and gone past us again. This + passed since vTaskSetTimeout() was called. */ + xReturn = pdTRUE; + } + else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) + { + /* Not a genuine timeout. Adjust parameters for time remaining. */ + *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); + vTaskSetTimeOutState( pxTimeOut ); + xReturn = pdFALSE; + } + else + { + xReturn = pdTRUE; + } + } + portEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskMissedYield( void ) +{ + xMissedYield = pdTRUE; +} + +/* + * ----------------------------------------------------------- + * The Idle task. + * ---------------------------------------------------------- + * + * The portTASK_FUNCTION() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION( prvIdleTask, pvParameters ) +{ + /* Stop warnings. */ + ( void ) pvParameters; + + for( ;; ) + { + /* See if any tasks have been deleted. */ + prvCheckTasksWaitingTermination(); + + #if ( configUSE_PREEMPTION == 0 ) + { + /* If we are not using preemption we keep forcing a task switch to + see if any other task has become available. If we are using + preemption we don't need to do this as any task becoming available + will automatically get the processor anyway. */ + taskYIELD(); + } + #endif + + #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) + { + /* When using preemption tasks of equal priority will be + timesliced. If a task that is sharing the idle priority is ready + to run then the idle task should yield before the end of the + timeslice. + + A critical region is not required here as we are just reading from + the list, and an occasional incorrect value will not matter. If + the ready list at the idle priority contains more than one task + then a task other than the idle task is ready to execute. */ + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) + { + taskYIELD(); + } + } + #endif + + #if ( configUSE_IDLE_HOOK == 1 ) + { + extern void vApplicationIdleHook( void ); + + /* Call the user defined function from within the idle task. This + allows the application designer to add background functionality + without the overhead of a separate task. + NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, + CALL A FUNCTION THAT MIGHT BLOCK. */ + vApplicationIdleHook(); + } + #endif + // call Sleep for smalles sleep time possible + // (depending on kernel settings - around 100 microseconds) + // decreases idle thread CPU load from 100 to practically 0 +#ifdef IDLE_SLEEPS + Sleep(5); +#endif + } +} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ + + + + + + + +/*----------------------------------------------------------- + * File private functions documented at the top of the file. + *----------------------------------------------------------*/ + + + +static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) +{ + /* Store the function name in the TCB. */ + #if configMAX_TASK_NAME_LEN > 1 + { + /* Don't bring strncpy into the build unnecessarily. */ + strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); + } + #endif + pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = '\0'; + + /* This is used as an array index so must ensure it's not too large. First + remove the privilege bit if one is present. */ + if( uxPriority >= configMAX_PRIORITIES ) + { + uxPriority = configMAX_PRIORITIES - 1; + } + + pxTCB->uxPriority = uxPriority; + #if ( configUSE_MUTEXES == 1 ) + { + pxTCB->uxBasePriority = uxPriority; + } + #endif + + vListInitialiseItem( &( pxTCB->xGenericListItem ) ); + vListInitialiseItem( &( pxTCB->xEventListItem ) ); + + /* Set the pxTCB as a link back from the xListItem. This is so we can get + back to the containing TCB from a generic item in a list. */ + listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); + listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + { + pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0; + } + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + { + pxTCB->pxTaskTag = NULL; + } + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + pxTCB->ulRunTimeCounter = 0UL; + } + #endif + + #if ( portUSING_MPU_WRAPPERS == 1 ) + { + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); + } + #else + { + ( void ) xRegions; + ( void ) usStackDepth; + } + #endif +} +/*-----------------------------------------------------------*/ + +#if ( portUSING_MPU_WRAPPERS == 1 ) + + void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) + { + tskTCB *pxTCB; + + if( xTaskToModify == pxCurrentTCB ) + { + xTaskToModify = NULL; + } + + /* If null is passed in here then we are deleting ourselves. */ + pxTCB = prvGetTCBFromHandle( xTaskToModify ); + + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); + } + /*-----------------------------------------------------------*/ +#endif + +static void prvInitialiseTaskLists( void ) +{ +unsigned portBASE_TYPE uxPriority; + + for( uxPriority = 0; uxPriority < configMAX_PRIORITIES; uxPriority++ ) + { + vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); + } + + vListInitialise( ( xList * ) &xDelayedTaskList1 ); + vListInitialise( ( xList * ) &xDelayedTaskList2 ); + vListInitialise( ( xList * ) &xPendingReadyList ); + + #if ( INCLUDE_vTaskDelete == 1 ) + { + vListInitialise( ( xList * ) &xTasksWaitingTermination ); + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + vListInitialise( ( xList * ) &xSuspendedTaskList ); + } + #endif + + /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList + using list2. */ + pxDelayedTaskList = &xDelayedTaskList1; + pxOverflowDelayedTaskList = &xDelayedTaskList2; +} +/*-----------------------------------------------------------*/ + +static void prvCheckTasksWaitingTermination( void ) +{ + #if ( INCLUDE_vTaskDelete == 1 ) + { + portBASE_TYPE xListIsEmpty; + + /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called + too often in the idle task. */ + if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0 ) + { + vTaskSuspendAll(); + xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); + xTaskResumeAll(); + + if( !xListIsEmpty ) + { + tskTCB *pxTCB; + + portENTER_CRITICAL(); + { + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); + vListRemove( &( pxTCB->xGenericListItem ) ); + --uxCurrentNumberOfTasks; + --uxTasksDeleted; + } + portEXIT_CRITICAL(); + + prvDeleteTCB( pxTCB ); + } + } + } + #endif +} +/*-----------------------------------------------------------*/ + +static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) +{ +tskTCB *pxNewTCB; + + /* Allocate space for the TCB. Where the memory comes from depends on + the implementation of the port malloc function. */ + pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); + + if( pxNewTCB != NULL ) + { + /* Allocate space for the stack used by the task being created. + The base of the stack memory stored in the TCB so the task can + be deleted later if required. */ + pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); + + if( pxNewTCB->pxStack == NULL ) + { + /* Could not allocate the stack. Delete the allocated TCB. */ + vPortFree( pxNewTCB ); + pxNewTCB = NULL; + } + else + { + /* Just to help debugging. */ + memset( pxNewTCB->pxStack, tskSTACK_FILL_BYTE, usStackDepth * sizeof( portSTACK_TYPE ) ); + } + } + + return pxNewTCB; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) + { + volatile tskTCB *pxNextTCB, *pxFirstTCB; + unsigned short usStackRemaining; + + /* Write the details of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + #if ( portSTACK_GROWTH > 0 ) + { + usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); + } + #else + { + usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); + } + #endif + + sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); + + } while( pxNextTCB != pxFirstTCB ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) + { + volatile tskTCB *pxNextTCB, *pxFirstTCB; + unsigned long ulStatsAsPercentage; + + /* Write the run time stats of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + /* Get next TCB in from the list. */ + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + + /* Divide by zero check. */ + if( ulTotalRunTime > 0UL ) + { + /* Has the task run at all? */ + if( pxNextTCB->ulRunTimeCounter == 0 ) + { + /* The task has used no CPU time at all. */ + sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); + } + else + { + /* What percentage of the total run time as the task used? + This will always be rounded down to the nearest integer. */ + ulStatsAsPercentage = ( 100UL * pxNextTCB->ulRunTimeCounter ) / ulTotalRunTime; + + if( ulStatsAsPercentage > 0UL ) + { + sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); + } + else + { + /* If the percentage is zero here then the task has + consumed less than 1% of the total run time. */ + sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); + } + } + + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); + } + + } while( pxNextTCB != pxFirstTCB ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) + + static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) + { + register unsigned short usCount = 0; + + while( *pucStackByte == tskSTACK_FILL_BYTE ) + { + pucStackByte -= portSTACK_GROWTH; + usCount++; + } + + usCount /= sizeof( portSTACK_TYPE ); + + return usCount; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) + + unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) + { + tskTCB *pxTCB; + unsigned char *pcEndOfStack; + unsigned portBASE_TYPE uxReturn; + + pxTCB = prvGetTCBFromHandle( xTask ); + + #if portSTACK_GROWTH < 0 + { + pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; + } + #else + { + pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; + } + #endif + + uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); + + return uxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_vTaskDelete == 1 ) || ( INCLUDE_vTaskCleanUpResources == 1 ) ) + + static void prvDeleteTCB( tskTCB *pxTCB ) + { + /* Free up the memory allocated by the scheduler for the task. It is up to + the task to free any memory allocated at the application level. */ + vPortFreeAligned( pxTCB->pxStack ); + vPortFree( pxTCB ); + } + +#endif + + +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) + + xTaskHandle xTaskGetCurrentTaskHandle( void ) + { + xTaskHandle xReturn; + + /* A critical section is not required as this is not called from + an interrupt and the current TCB will always be the same for any + individual execution thread. */ + xReturn = pxCurrentTCB; + + return xReturn; + } + +#endif + +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetSchedulerState == 1 ) + + portBASE_TYPE xTaskGetSchedulerState( void ) + { + portBASE_TYPE xReturn; + + if( xSchedulerRunning == pdFALSE ) + { + xReturn = taskSCHEDULER_NOT_STARTED; + } + else + { + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xReturn = taskSCHEDULER_RUNNING; + } + else + { + xReturn = taskSCHEDULER_SUSPENDED; + } + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) + { + tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; + + if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) + { + /* Adjust the mutex holder state to account for its new priority. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); + + /* If the task being modified is in the ready state it will need to + be moved in to a new list. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) ) + { + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Inherit the priority before being moved into the new list. */ + pxTCB->uxPriority = pxCurrentTCB->uxPriority; + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* Just inherit the priority. */ + pxTCB->uxPriority = pxCurrentTCB->uxPriority; + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) + { + tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; + + if( pxMutexHolder != NULL ) + { + if( pxTCB->uxPriority != pxTCB->uxBasePriority ) + { + /* We must be the running task to be able to give the mutex back. + Remove ourselves from the ready list we currently appear in. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Disinherit the priority before adding ourselves into the new + ready list. */ + pxTCB->uxPriority = pxTCB->uxBasePriority; + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); + prvAddTaskToReadyQueue( pxTCB ); + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + + void vTaskEnterCritical( void ) + { + portDISABLE_INTERRUPTS(); + + if( xSchedulerRunning != pdFALSE ) + { + pxCurrentTCB->uxCriticalNesting++; + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + +void vTaskExitCritical( void ) +{ + if( xSchedulerRunning != pdFALSE ) + { + if( pxCurrentTCB->uxCriticalNesting > 0 ) + { + pxCurrentTCB->uxCriticalNesting--; + + if( pxCurrentTCB->uxCriticalNesting == 0 ) + { + portENABLE_INTERRUPTS(); + } + } + } +} + +#endif +/*-----------------------------------------------------------*/ + + + + diff --git a/flight/PiOS.win32/win32/pios_com.c b/flight/PiOS.win32/win32/pios_com.c index 3dc2c5f35..749a0bc38 100644 --- a/flight/PiOS.win32/win32/pios_com.c +++ b/flight/PiOS.win32/win32/pios_com.c @@ -1,33 +1,33 @@ -/** - ****************************************************************************** - * - * @file pios_com.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief COM layer functions - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_COM COM layer functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ +/** + ****************************************************************************** + * + * @file pios_com.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief COM layer functions + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_COM COM layer functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ #include "pios.h" #if defined(PIOS_INCLUDE_COM) @@ -45,45 +45,45 @@ static struct pios_com_dev * find_com_dev_by_id (uint8_t port) return &(pios_com_devs[port]); } -/** -* Initialises COM layer -* \param[in] mode currently only mode 0 supported -* \return < 0 if initialisation failed -*/ -int32_t PIOS_COM_Init(void) -{ - int32_t ret = 0; - - /* If any COM assignment: */ -#if defined(PIOS_INCLUDE_SERIAL) - PIOS_SERIAL_Init(); -#endif - -#if defined(PIOS_INCLUDE_UDP) - PIOS_UDP_Init(); -#endif - - return ret; -} - -int32_t PIOS_COM_Close(void) -{ - int32_t ret = 0; - -#if defined(PIOS_INCLUDE_UDP) - PIOS_UDP_Close(); -#endif - - return ret; -} - -/** -* Change the port speed without re-initializing -* \param[in] port COM port -* \param[in] baud Requested baud rate -* \return -1 if port not available -* \return 0 on success -*/ +/** +* Initialises COM layer +* \param[in] mode currently only mode 0 supported +* \return < 0 if initialisation failed +*/ +int32_t PIOS_COM_Init(void) +{ + int32_t ret = 0; + + /* If any COM assignment: */ +#if defined(PIOS_INCLUDE_SERIAL) + PIOS_SERIAL_Init(); +#endif + +#if defined(PIOS_INCLUDE_UDP) + PIOS_UDP_Init(); +#endif + + return ret; +} + +int32_t PIOS_COM_Close(void) +{ + int32_t ret = 0; + +#if defined(PIOS_INCLUDE_UDP) + PIOS_UDP_Close(); +#endif + + return ret; +} + +/** +* Change the port speed without re-initializing +* \param[in] port COM port +* \param[in] baud Requested baud rate +* \return -1 if port not available +* \return 0 on success +*/ int32_t PIOS_COM_ChangeBaud(uint8_t port, uint32_t baud) { struct pios_com_dev * com_dev; @@ -102,17 +102,17 @@ int32_t PIOS_COM_ChangeBaud(uint8_t port, uint32_t baud) return 0; } - -/** -* Sends a package over given port -* \param[in] port COM port -* \param[in] buffer character buffer -* \param[in] len buffer length -* \return -1 if port not available -* \return -2 if non-blocking mode activated: buffer is full -* caller should retry until buffer is free again -* \return 0 on success -*/ + +/** +* Sends a package over given port +* \param[in] port COM port +* \param[in] buffer character buffer +* \param[in] len buffer length +* \return -1 if port not available +* \return -2 if non-blocking mode activated: buffer is full +* caller should retry until buffer is free again +* \return 0 on success +*/ int32_t PIOS_COM_SendBufferNonBlocking(uint8_t port, uint8_t *buffer, uint16_t len) { struct pios_com_dev * com_dev; @@ -132,15 +132,15 @@ int32_t PIOS_COM_SendBufferNonBlocking(uint8_t port, uint8_t *buffer, uint16_t l return 0; } -/** -* Sends a package over given port -* (blocking function) -* \param[in] port COM port -* \param[in] buffer character buffer -* \param[in] len buffer length -* \return -1 if port not available -* \return 0 on success -*/ +/** +* Sends a package over given port +* (blocking function) +* \param[in] port COM port +* \param[in] buffer character buffer +* \param[in] len buffer length +* \return -1 if port not available +* \return 0 on success +*/ int32_t PIOS_COM_SendBuffer(uint8_t port, uint8_t *buffer, uint16_t len) { struct pios_com_dev * com_dev; @@ -160,107 +160,107 @@ int32_t PIOS_COM_SendBuffer(uint8_t port, uint8_t *buffer, uint16_t len) return 0; } -/** -* Sends a single character over given port -* \param[in] port COM port -* \param[in] c character -* \return -1 if port not available -* \return -2 buffer is full -* caller should retry until buffer is free again -* \return 0 on success -*/ -int32_t PIOS_COM_SendCharNonBlocking(uint8_t port, char c) -{ - return PIOS_COM_SendBufferNonBlocking(port, (uint8_t *)&c, 1); -} - -/** -* Sends a single character over given port -* (blocking function) -* \param[in] port COM port -* \param[in] c character -* \return -1 if port not available -* \return 0 on success -*/ -int32_t PIOS_COM_SendChar(uint8_t port, char c) -{ - return PIOS_COM_SendBuffer(port, (uint8_t *)&c, 1); -} - -/** -* Sends a string over given port -* \param[in] port COM port -* \param[in] str zero-terminated string -* \return -1 if port not available -* \return -2 buffer is full -* caller should retry until buffer is free again -* \return 0 on success -*/ -int32_t PIOS_COM_SendStringNonBlocking(uint8_t port, char *str) -{ - return PIOS_COM_SendBufferNonBlocking(port, (uint8_t *)str, (uint16_t)strlen(str)); -} - -/** -* Sends a string over given port -* (blocking function) -* \param[in] port COM port -* \param[in] str zero-terminated string -* \return -1 if port not available -* \return 0 on success -*/ -int32_t PIOS_COM_SendString(uint8_t port, char *str) -{ - return PIOS_COM_SendBuffer(port, (uint8_t *)str, strlen(str)); -} - -/** -* Sends a formatted string (-> printf) over given port -* \param[in] port COM port -* \param[in] *format zero-terminated format string - 128 characters supported maximum! -* \param[in] ... optional arguments, -* 128 characters supported maximum! -* \return -2 if non-blocking mode activated: buffer is full -* caller should retry until buffer is free again -* \return 0 on success -*/ -int32_t PIOS_COM_SendFormattedStringNonBlocking(uint8_t port, char *format, ...) -{ - uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later! - - va_list args; - - va_start(args, format); - vsprintf((char *)buffer, format, args); - return PIOS_COM_SendBufferNonBlocking(port, buffer, (uint16_t)strlen((char *)buffer)); -} - -/** -* Sends a formatted string (-> printf) over given port -* (blocking function) -* \param[in] port COM port -* \param[in] *format zero-terminated format string - 128 characters supported maximum! -* \param[in] ... optional arguments, -* \return -1 if port not available -* \return 0 on success -*/ -int32_t PIOS_COM_SendFormattedString(uint8_t port, char *format, ...) -{ - uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later! - va_list args; - - va_start(args, format); - vsprintf((char *)buffer, format, args); - return PIOS_COM_SendBuffer(port, buffer, (uint16_t)strlen((char *)buffer)); -} - -/** -* Transfer bytes from port buffers into another buffer -* \param[in] port COM port +/** +* Sends a single character over given port +* \param[in] port COM port +* \param[in] c character +* \return -1 if port not available +* \return -2 buffer is full +* caller should retry until buffer is free again +* \return 0 on success +*/ +int32_t PIOS_COM_SendCharNonBlocking(uint8_t port, char c) +{ + return PIOS_COM_SendBufferNonBlocking(port, (uint8_t *)&c, 1); +} + +/** +* Sends a single character over given port +* (blocking function) +* \param[in] port COM port +* \param[in] c character +* \return -1 if port not available +* \return 0 on success +*/ +int32_t PIOS_COM_SendChar(uint8_t port, char c) +{ + return PIOS_COM_SendBuffer(port, (uint8_t *)&c, 1); +} + +/** +* Sends a string over given port +* \param[in] port COM port +* \param[in] str zero-terminated string +* \return -1 if port not available +* \return -2 buffer is full +* caller should retry until buffer is free again +* \return 0 on success +*/ +int32_t PIOS_COM_SendStringNonBlocking(uint8_t port, char *str) +{ + return PIOS_COM_SendBufferNonBlocking(port, (uint8_t *)str, (uint16_t)strlen(str)); +} + +/** +* Sends a string over given port +* (blocking function) +* \param[in] port COM port +* \param[in] str zero-terminated string +* \return -1 if port not available +* \return 0 on success +*/ +int32_t PIOS_COM_SendString(uint8_t port, char *str) +{ + return PIOS_COM_SendBuffer(port, (uint8_t *)str, strlen(str)); +} + +/** +* Sends a formatted string (-> printf) over given port +* \param[in] port COM port +* \param[in] *format zero-terminated format string - 128 characters supported maximum! +* \param[in] ... optional arguments, +* 128 characters supported maximum! +* \return -2 if non-blocking mode activated: buffer is full +* caller should retry until buffer is free again +* \return 0 on success +*/ +int32_t PIOS_COM_SendFormattedStringNonBlocking(uint8_t port, char *format, ...) +{ + uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later! + + va_list args; + + va_start(args, format); + vsprintf((char *)buffer, format, args); + return PIOS_COM_SendBufferNonBlocking(port, buffer, (uint16_t)strlen((char *)buffer)); +} + +/** +* Sends a formatted string (-> printf) over given port +* (blocking function) +* \param[in] port COM port +* \param[in] *format zero-terminated format string - 128 characters supported maximum! +* \param[in] ... optional arguments, +* \return -1 if port not available +* \return 0 on success +*/ +int32_t PIOS_COM_SendFormattedString(uint8_t port, char *format, ...) +{ + uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later! + va_list args; + + va_start(args, format); + vsprintf((char *)buffer, format, args); + return PIOS_COM_SendBuffer(port, buffer, (uint16_t)strlen((char *)buffer)); +} + +/** +* Transfer bytes from port buffers into another buffer +* \param[in] port COM port * \returns Byte from buffer -*/ -uint8_t PIOS_COM_ReceiveBuffer(uint8_t port) -{ +*/ +uint8_t PIOS_COM_ReceiveBuffer(uint8_t port) +{ struct pios_com_dev * com_dev; com_dev = find_com_dev_by_id (port); @@ -270,11 +270,11 @@ uint8_t PIOS_COM_ReceiveBuffer(uint8_t port) return com_dev->driver->rx(com_dev->id); } -/** -* Get the number of bytes waiting in the buffer -* \param[in] port COM port -* \return Number of bytes used in buffer -*/ +/** +* Get the number of bytes waiting in the buffer +* \param[in] port COM port +* \return Number of bytes used in buffer +*/ int32_t PIOS_COM_ReceiveBufferUsed(uint8_t port) { struct pios_com_dev * com_dev; @@ -292,5 +292,5 @@ int32_t PIOS_COM_ReceiveBufferUsed(uint8_t port) return com_dev->driver->rx_avail(com_dev->id); } - -#endif + +#endif diff --git a/flight/PiOS.win32/win32/pios_delay.c b/flight/PiOS.win32/win32/pios_delay.c index a8d892601..37a430462 100644 --- a/flight/PiOS.win32/win32/pios_delay.c +++ b/flight/PiOS.win32/win32/pios_delay.c @@ -1,88 +1,88 @@ -/** - ****************************************************************************** - * - * @file pios_delay.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief Delay Functions - * - Provides a micro-second granular delay using a TIM - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_DELAY Delay Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_DELAY) - -/** -* Initialises the Timer used by PIOS_DELAY functions
-* This is called from pios.c as part of the main() function -* at system start up. -* \return < 0 if initialisation failed -*/ -#include - -int32_t PIOS_DELAY_Init(void) -{ - // stub - - /* No error */ - return 0; -} - -/** -* Waits for a specific number of uS
-* Example:
-* \code -* // Wait for 500 uS -* PIOS_DELAY_Wait_uS(500); -* \endcode -* \param[in] uS delay (1..65535 microseconds) -* \return < 0 on errors -*/ -int32_t PIOS_DELAY_WaituS(uint16_t uS) -{ - Sleep(uS/1000); - - return 0; -} - - -/** -* Waits for a specific number of mS
-* Example:
-* \code -* // Wait for 500 mS -* PIOS_DELAY_Wait_mS(500); -* \endcode -* \param[in] mS delay (1..65535 milliseconds) -* \return < 0 on errors -*/ -int32_t PIOS_DELAY_WaitmS(uint16_t mS) -{ - Sleep(mS); - - /* No error */ - return 0; -} - -#endif +/** + ****************************************************************************** + * + * @file pios_delay.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Delay Functions + * - Provides a micro-second granular delay using a TIM + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_DELAY Delay Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_DELAY) + +/** +* Initialises the Timer used by PIOS_DELAY functions
+* This is called from pios.c as part of the main() function +* at system start up. +* \return < 0 if initialisation failed +*/ +#include + +int32_t PIOS_DELAY_Init(void) +{ + // stub + + /* No error */ + return 0; +} + +/** +* Waits for a specific number of uS
+* Example:
+* \code +* // Wait for 500 uS +* PIOS_DELAY_Wait_uS(500); +* \endcode +* \param[in] uS delay (1..65535 microseconds) +* \return < 0 on errors +*/ +int32_t PIOS_DELAY_WaituS(uint16_t uS) +{ + Sleep(uS/1000); + + return 0; +} + + +/** +* Waits for a specific number of mS
+* Example:
+* \code +* // Wait for 500 mS +* PIOS_DELAY_Wait_mS(500); +* \endcode +* \param[in] mS delay (1..65535 milliseconds) +* \return < 0 on errors +*/ +int32_t PIOS_DELAY_WaitmS(uint16_t mS) +{ + Sleep(mS); + + /* No error */ + return 0; +} + +#endif diff --git a/flight/PiOS.win32/win32/pios_led.c b/flight/PiOS.win32/win32/pios_led.c index b35477d45..4ac23cb2c 100644 --- a/flight/PiOS.win32/win32/pios_led.c +++ b/flight/PiOS.win32/win32/pios_led.c @@ -1,102 +1,102 @@ -/** - ****************************************************************************** - * - * @file pios_led.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief LED functions, init, toggle, on & off. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_LED LED Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_LED) - -/* Private Function Prototypes */ - - -/* Local Variables */ -//static GPIO_TypeDef* LED_GPIO_PORT[PIOS_LED_NUM] = PIOS_LED_PORTS; -//static const uint32_t LED_GPIO_PIN[PIOS_LED_NUM] = PIOS_LED_PINS; -//static const uint32_t LED_GPIO_CLK[PIOS_LED_NUM] = PIOS_LED_CLKS; -static uint8_t LED_GPIO[PIOS_LED_NUM]; - - -static inline void PIOS_SetLED(LedTypeDef LED,uint8_t stat) { - printf("PIOS: LED %i status %i\n",LED,stat); - LED_GPIO[LED]=stat; -} - -/** -* Initialises all the LED's -*/ -void PIOS_LED_Init(void) -{ - //GPIO_InitTypeDef GPIO_InitStructure; - //GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; - //GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - - for(int LEDNum = 0; LEDNum < PIOS_LED_NUM; LEDNum++) { - //RCC_APB2PeriphClockCmd(LED_GPIO_CLK[LEDNum], ENABLE); - //GPIO_InitStructure.GPIO_Pin = LED_GPIO_PIN[LEDNum]; - //GPIO_Init(LED_GPIO_PORT[LEDNum], &GPIO_InitStructure); - - /* LED's Off */ - //LED_GPIO_PORT[LEDNum]->BSRR = LED_GPIO_PIN[LEDNum]; - LED_GPIO[LEDNum]=0; - } -} - - -/** -* Turn on LED -* \param[in] LED LED Name (LED1, LED2) -*/ -void PIOS_LED_On(LedTypeDef LED) -{ - //LED_GPIO_PORT[LED]->BRR = LED_GPIO_PIN[LED]; - PIOS_SetLED(LED,1); -} - - -/** -* Turn off LED -* \param[in] LED LED Name (LED1, LED2) -*/ -void PIOS_LED_Off(LedTypeDef LED) -{ - //LED_GPIO_PORT[LED]->BSRR = LED_GPIO_PIN[LED]; - PIOS_SetLED(LED,0); -} - - -/** -* Toggle LED on/off -* \param[in] LED LED Name (LED1, LED2) -*/ -void PIOS_LED_Toggle(LedTypeDef LED) -{ - //LED_GPIO_PORT[LED]->ODR ^= LED_GPIO_PIN[LED]; - PIOS_SetLED(LED,LED_GPIO[LED]?0:1); -} - -#endif +/** + ****************************************************************************** + * + * @file pios_led.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief LED functions, init, toggle, on & off. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_LED LED Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_LED) + +/* Private Function Prototypes */ + + +/* Local Variables */ +//static GPIO_TypeDef* LED_GPIO_PORT[PIOS_LED_NUM] = PIOS_LED_PORTS; +//static const uint32_t LED_GPIO_PIN[PIOS_LED_NUM] = PIOS_LED_PINS; +//static const uint32_t LED_GPIO_CLK[PIOS_LED_NUM] = PIOS_LED_CLKS; +static uint8_t LED_GPIO[PIOS_LED_NUM]; + + +static inline void PIOS_SetLED(LedTypeDef LED,uint8_t stat) { + printf("PIOS: LED %i status %i\n",LED,stat); + LED_GPIO[LED]=stat; +} + +/** +* Initialises all the LED's +*/ +void PIOS_LED_Init(void) +{ + //GPIO_InitTypeDef GPIO_InitStructure; + //GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + //GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + + for(int LEDNum = 0; LEDNum < PIOS_LED_NUM; LEDNum++) { + //RCC_APB2PeriphClockCmd(LED_GPIO_CLK[LEDNum], ENABLE); + //GPIO_InitStructure.GPIO_Pin = LED_GPIO_PIN[LEDNum]; + //GPIO_Init(LED_GPIO_PORT[LEDNum], &GPIO_InitStructure); + + /* LED's Off */ + //LED_GPIO_PORT[LEDNum]->BSRR = LED_GPIO_PIN[LEDNum]; + LED_GPIO[LEDNum]=0; + } +} + + +/** +* Turn on LED +* \param[in] LED LED Name (LED1, LED2) +*/ +void PIOS_LED_On(LedTypeDef LED) +{ + //LED_GPIO_PORT[LED]->BRR = LED_GPIO_PIN[LED]; + PIOS_SetLED(LED,1); +} + + +/** +* Turn off LED +* \param[in] LED LED Name (LED1, LED2) +*/ +void PIOS_LED_Off(LedTypeDef LED) +{ + //LED_GPIO_PORT[LED]->BSRR = LED_GPIO_PIN[LED]; + PIOS_SetLED(LED,0); +} + + +/** +* Toggle LED on/off +* \param[in] LED LED Name (LED1, LED2) +*/ +void PIOS_LED_Toggle(LedTypeDef LED) +{ + //LED_GPIO_PORT[LED]->ODR ^= LED_GPIO_PIN[LED]; + PIOS_SetLED(LED,LED_GPIO[LED]?0:1); +} + +#endif diff --git a/flight/PiOS.win32/win32/pios_sdcard.c b/flight/PiOS.win32/win32/pios_sdcard.c index 1e43c8086..78da48e46 100644 --- a/flight/PiOS.win32/win32/pios_sdcard.c +++ b/flight/PiOS.win32/win32/pios_sdcard.c @@ -1,300 +1,300 @@ -/** - ****************************************************************************** - * - * @file pios_sdcard.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief Sets up basic system hardware, functions are called from Main. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_SDCARD SDCard Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_SDCARD) - - -/** -* Initialises SPI pins and peripheral to access MMC/SD Card -* \param[in] mode currently only mode 0 supported -* \return < 0 if initialisation failed -*/ -int32_t PIOS_SDCARD_Init(void) -{ - /* No error */ - return 0; -} - - -/** -* Connects to SD Card -* \return < 0 if initialisation sequence failed -*/ -int32_t PIOS_SDCARD_PowerOn(void) -{ - return 0; /* Status should be 0 if nothing went wrong! */ -} - - -/** -* Disconnects from SD Card -* \return < 0 on errors -*/ -int32_t PIOS_SDCARD_PowerOff(void) -{ - return 0; // no error -} - - -/** -* If SD card was previously available: Checks if the SD Card is still -* available by sending the STATUS command.
-* This takes ca. 10 uS -* -* If SD card was previously not available: Checks if the SD Card is -* available by sending the IDLE command at low speed.
-* This takes ca. 500 uS!
-* Once we got a positive response, SDCARD_PowerOn() will be -* called by this function to initialize the card completely. -* -* Example for Connection/Disconnection detection: -* \code -* // this function is called each second from a low-priority task -* // If multiple tasks are accessing the SD card, add a semaphore/mutex -* // to avoid IO access collisions with other tasks! -* u8 sdcard_available; -* int32_t CheckSDCard(void) -* { -* // check if SD card is available -* // High speed access if the card was previously available -* u8 prev_sdcard_available = sdcard_available; -* sdcard_available = PIOS_SDCARD_CheckAvailable(prev_sdcard_available); -* -* if(sdcard_available && !prev_sdcard_available) { -* // SD Card has been connected -* -* // now it's possible to read/write sectors -* -* } else if( !sdcard_available && prev_sdcard_available ) { -* // SD Card has been disconnected -* -* // here you can notify your application about this state -* } -* -* return 0; // no error -* } -* \endcode -* \param[in] was_available should only be set if the SD card was previously available -* \return 0 if no response from SD Card -* \return 1 if SD card is accessible -*/ -int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available) -{ - return 1; /* 1 = available, 0 = not available. */ -} - - -/** -* Sends command to SD card -* \param[in] cmd SD card command -* \param[in] addr 32bit address -* \param[in] crc precalculated CRC -* \return >= 0x00 if command has been sent successfully (contains received byte) -* \return -1 if no response from SD Card (timeout) -*/ -int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc) -{ - return -1; -} - - -/** -* Reads 512 bytes from selected sector -* \param[in] sector 32bit sector -* \param[in] *buffer pointer to 512 byte buffer -* \return 0 if whole sector has been successfully read -* \return -error if error occured during read operation:
-*
    -*
  • Bit 0 - In idle state if 1 -*
  • Bit 1 - Erase Reset if 1 -*
  • Bit 2 - Illgal Command if 1 -*
  • Bit 3 - Com CRC Error if 1 -*
  • Bit 4 - Erase Sequence Error if 1 -*
  • Bit 5 - Address Error if 1 -*
  • Bit 6 - Parameter Error if 1 -*
  • Bit 7 - Not used, always '0' -*
-* \return -256 if timeout during command has been sent -* \return -257 if timeout while waiting for start token -*/ -int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer) -{ - return -256; -} - - -/** -* Writes 512 bytes into selected sector -* \param[in] sector 32bit sector -* \param[in] *buffer pointer to 512 byte buffer -* \return 0 if whole sector has been successfully read -* \return -error if error occured during read operation:
-*
    -*
  • Bit 0 - In idle state if 1 -*
  • Bit 1 - Erase Reset if 1 -*
  • Bit 2 - Illgal Command if 1 -*
  • Bit 3 - Com CRC Error if 1 -*
  • Bit 4 - Erase Sequence Error if 1 -*
  • Bit 5 - Address Error if 1 -*
  • Bit 6 - Parameter Error if 1 -*
  • Bit 7 - Not used, always '0' -*
-* \return -256 if timeout during command has been sent -* \return -257 if write operation not accepted -* \return -258 if timeout during write operation -*/ -int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer) -{ - return -256; -} - - -/** -* Reads the CID informations from SD Card -* \param[in] *cid pointer to buffer which holds the CID informations -* \return 0 if the informations haven been successfully read -* \return -error if error occured during read operation -* \return -256 if timeout during command has been sent -* \return -257 if timeout while waiting for start token -*/ -int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid) -{ - return -256; -} - -/** -* Reads the CSD informations from SD Card -* \param[in] *csd pointer to buffer which holds the CSD informations -* \return 0 if the informations haven been successfully read -* \return -error if error occured during read operation -* \return -256 if timeout during command has been sent -* \return -257 if timeout while waiting for start token -*/ -int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd) -{ - return -256; -} - -/** -* Attempts to write a startup log to the SDCard -* return 0 No errors -* return -1 Error deleting file -* return -2 Error opening file -* return -3 Error writing file -*/ -int32_t PIOS_SDCARD_StartupLog(void) -{ - return -3; -} - -/** - * Check if the SD card has been mounted - * @return 0 if no - * @return 1 if yes - */ -int32_t PIOS_SDCARD_IsMounted() -{ - return 1; -} - -/** -* Mounts the file system -* param[in] CreateStartupLog 1 = True, 0 = False -* return 0 No errors -* return -1 SDCard not available -* return -2 Cannot find first partition -* return -3 No volume information -* return -4 Error writing startup log file -*/ -int32_t PIOS_SDCARD_MountFS(uint32_t CreateStartupLog) -{ - return 0; -} - -/** -* Mounts the file system -* return Amount of free bytes -*/ -int32_t PIOS_SDCARD_GetFree(void) -{ - return 10240; -} - -/** -* Read from file -* return 0 No error -* return -1 DFS_ReadFile failed -* return -2 Less bytes read than expected -*/ -//int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len) -//{ - /* No error */ -// return -1; -//} - -/** -* Read a line from file -* returns Number of bytes read -*/ -//int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len) -//{ -// return -1; -//} - -/** -* Copy a file -* WARNING: This will overwrite the destination file even if it exists -* param[in] *Source Path to file to copy -* param[in] *Destination Path to destination file -* return 0 No errors -* return -1 Source file doesn't exist -* return -2 Failed to create destination file -* return -3 DFS_ReadFile failed -* return -4 DFS_WriteFile failed -*/ -int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination) -{ - return -2; -} - -/** -* Delete a file -* param[in] *Filename File to delete -* return 0 No errors -* return -1 Error deleting file -*/ -int32_t PIOS_SDCARD_FileDelete(char *Filename) -{ - return -1; -} - -#endif +/** + ****************************************************************************** + * + * @file pios_sdcard.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief Sets up basic system hardware, functions are called from Main. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_SDCARD SDCard Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_SDCARD) + + +/** +* Initialises SPI pins and peripheral to access MMC/SD Card +* \param[in] mode currently only mode 0 supported +* \return < 0 if initialisation failed +*/ +int32_t PIOS_SDCARD_Init(void) +{ + /* No error */ + return 0; +} + + +/** +* Connects to SD Card +* \return < 0 if initialisation sequence failed +*/ +int32_t PIOS_SDCARD_PowerOn(void) +{ + return 0; /* Status should be 0 if nothing went wrong! */ +} + + +/** +* Disconnects from SD Card +* \return < 0 on errors +*/ +int32_t PIOS_SDCARD_PowerOff(void) +{ + return 0; // no error +} + + +/** +* If SD card was previously available: Checks if the SD Card is still +* available by sending the STATUS command.
+* This takes ca. 10 uS +* +* If SD card was previously not available: Checks if the SD Card is +* available by sending the IDLE command at low speed.
+* This takes ca. 500 uS!
+* Once we got a positive response, SDCARD_PowerOn() will be +* called by this function to initialize the card completely. +* +* Example for Connection/Disconnection detection: +* \code +* // this function is called each second from a low-priority task +* // If multiple tasks are accessing the SD card, add a semaphore/mutex +* // to avoid IO access collisions with other tasks! +* u8 sdcard_available; +* int32_t CheckSDCard(void) +* { +* // check if SD card is available +* // High speed access if the card was previously available +* u8 prev_sdcard_available = sdcard_available; +* sdcard_available = PIOS_SDCARD_CheckAvailable(prev_sdcard_available); +* +* if(sdcard_available && !prev_sdcard_available) { +* // SD Card has been connected +* +* // now it's possible to read/write sectors +* +* } else if( !sdcard_available && prev_sdcard_available ) { +* // SD Card has been disconnected +* +* // here you can notify your application about this state +* } +* +* return 0; // no error +* } +* \endcode +* \param[in] was_available should only be set if the SD card was previously available +* \return 0 if no response from SD Card +* \return 1 if SD card is accessible +*/ +int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available) +{ + return 1; /* 1 = available, 0 = not available. */ +} + + +/** +* Sends command to SD card +* \param[in] cmd SD card command +* \param[in] addr 32bit address +* \param[in] crc precalculated CRC +* \return >= 0x00 if command has been sent successfully (contains received byte) +* \return -1 if no response from SD Card (timeout) +*/ +int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc) +{ + return -1; +} + + +/** +* Reads 512 bytes from selected sector +* \param[in] sector 32bit sector +* \param[in] *buffer pointer to 512 byte buffer +* \return 0 if whole sector has been successfully read +* \return -error if error occured during read operation:
+*
    +*
  • Bit 0 - In idle state if 1 +*
  • Bit 1 - Erase Reset if 1 +*
  • Bit 2 - Illgal Command if 1 +*
  • Bit 3 - Com CRC Error if 1 +*
  • Bit 4 - Erase Sequence Error if 1 +*
  • Bit 5 - Address Error if 1 +*
  • Bit 6 - Parameter Error if 1 +*
  • Bit 7 - Not used, always '0' +*
+* \return -256 if timeout during command has been sent +* \return -257 if timeout while waiting for start token +*/ +int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer) +{ + return -256; +} + + +/** +* Writes 512 bytes into selected sector +* \param[in] sector 32bit sector +* \param[in] *buffer pointer to 512 byte buffer +* \return 0 if whole sector has been successfully read +* \return -error if error occured during read operation:
+*
    +*
  • Bit 0 - In idle state if 1 +*
  • Bit 1 - Erase Reset if 1 +*
  • Bit 2 - Illgal Command if 1 +*
  • Bit 3 - Com CRC Error if 1 +*
  • Bit 4 - Erase Sequence Error if 1 +*
  • Bit 5 - Address Error if 1 +*
  • Bit 6 - Parameter Error if 1 +*
  • Bit 7 - Not used, always '0' +*
+* \return -256 if timeout during command has been sent +* \return -257 if write operation not accepted +* \return -258 if timeout during write operation +*/ +int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer) +{ + return -256; +} + + +/** +* Reads the CID informations from SD Card +* \param[in] *cid pointer to buffer which holds the CID informations +* \return 0 if the informations haven been successfully read +* \return -error if error occured during read operation +* \return -256 if timeout during command has been sent +* \return -257 if timeout while waiting for start token +*/ +int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid) +{ + return -256; +} + +/** +* Reads the CSD informations from SD Card +* \param[in] *csd pointer to buffer which holds the CSD informations +* \return 0 if the informations haven been successfully read +* \return -error if error occured during read operation +* \return -256 if timeout during command has been sent +* \return -257 if timeout while waiting for start token +*/ +int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd) +{ + return -256; +} + +/** +* Attempts to write a startup log to the SDCard +* return 0 No errors +* return -1 Error deleting file +* return -2 Error opening file +* return -3 Error writing file +*/ +int32_t PIOS_SDCARD_StartupLog(void) +{ + return -3; +} + +/** + * Check if the SD card has been mounted + * @return 0 if no + * @return 1 if yes + */ +int32_t PIOS_SDCARD_IsMounted() +{ + return 1; +} + +/** +* Mounts the file system +* param[in] CreateStartupLog 1 = True, 0 = False +* return 0 No errors +* return -1 SDCard not available +* return -2 Cannot find first partition +* return -3 No volume information +* return -4 Error writing startup log file +*/ +int32_t PIOS_SDCARD_MountFS(uint32_t CreateStartupLog) +{ + return 0; +} + +/** +* Mounts the file system +* return Amount of free bytes +*/ +int32_t PIOS_SDCARD_GetFree(void) +{ + return 10240; +} + +/** +* Read from file +* return 0 No error +* return -1 DFS_ReadFile failed +* return -2 Less bytes read than expected +*/ +//int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len) +//{ + /* No error */ +// return -1; +//} + +/** +* Read a line from file +* returns Number of bytes read +*/ +//int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len) +//{ +// return -1; +//} + +/** +* Copy a file +* WARNING: This will overwrite the destination file even if it exists +* param[in] *Source Path to file to copy +* param[in] *Destination Path to destination file +* return 0 No errors +* return -1 Source file doesn't exist +* return -2 Failed to create destination file +* return -3 DFS_ReadFile failed +* return -4 DFS_WriteFile failed +*/ +int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination) +{ + return -2; +} + +/** +* Delete a file +* param[in] *Filename File to delete +* return 0 No errors +* return -1 Error deleting file +*/ +int32_t PIOS_SDCARD_FileDelete(char *Filename) +{ + return -1; +} + +#endif diff --git a/flight/PiOS.win32/win32/pios_sys.c b/flight/PiOS.win32/win32/pios_sys.c index 85cdc9727..999796407 100644 --- a/flight/PiOS.win32/win32/pios_sys.c +++ b/flight/PiOS.win32/win32/pios_sys.c @@ -1,186 +1,186 @@ -/** - ****************************************************************************** - * - * @file pios_sys.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief Sets up basic system hardware, functions are called from Main. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_SYS System Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_SYS) - - -/* Private Function Prototypes */ -void NVIC_Configuration(void); -void SysTick_Handler(void); - -/* Local Macros */ -#define MEM8(addr) (*((volatile uint8_t *)(addr))) - -/** -* Initialises all system peripherals -*/ -void PIOS_SYS_Init(void) -{ - - /** - * stub - */ - printf("PIOS_SYS_Init\n"); - - /* Initialise Basic NVIC */ - NVIC_Configuration(); - -#if defined(PIOS_INCLUDE_LED) - /* Initialise LEDs */ - PIOS_LED_Init(); -#endif -} - -/** -* Shutdown PIOS and reset the microcontroller:
-*
    -*
  • Disable all RTOS tasks -*
  • Disable all interrupts -*
  • Turn off all board LEDs -*
  • Reset STM32 -*
-* \return < 0 if reset failed -*/ -int32_t PIOS_SYS_Reset(void) -{ - /** - * stub - */ - printf("PIOS_SYS_Reset\n"); - /* Disable all RTOS tasks */ -#if defined(PIOS_INCLUDE_FREERTOS) - /* port specific FreeRTOS function to disable tasks (nested) */ - portENTER_CRITICAL(); -#endif - - // disable all interrupts - //PIOS_IRQ_Disable(); - - // turn off all board LEDs - #if (PIOS_LED_NUM == 1) - PIOS_LED_Off(LED1); - #elif (PIOS_LED_NUM == 2) - PIOS_LED_Off(LED1); - PIOS_LED_Off(LED2); - #endif - - - - /* Reset STM32 */ - //RCC_APB2PeriphResetCmd(0xfffffff8, ENABLE); /* MBHP_CORE_STM32: don't reset GPIOA/AF due to USB pins */ - //RCC_APB1PeriphResetCmd(0xff7fffff, ENABLE); /* don't reset USB, so that the connection can survive! */ - - //RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); - //RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); - //SCB->AIRCR = NVIC_AIRCR_VECTKEY | (1 << NVIC_VECTRESET); - exit(1); - - while(1); - - /* We will never reach this point */ - return -1; -} - -/** -* Returns the serial number as a string -* param[out] str pointer to a string which can store at least 32 digits + zero terminator! -* (24 digits returned for STM32) -* return < 0 if feature not supported -*/ -int32_t PIOS_SYS_SerialNumberGet(char *str) -{ - int i; - - /* Stored in the so called "electronic signature" */ - for(i=0; i<24; ++i) { - //uint8_t b = MEM8(0x1ffff7e8 + (i/2)); - //if( !(i & 1) ) - //b >>= 4; - //b &= 0x0f; - - //str[i] = ((b > 9) ? ('A'-10) : '0') + b; - str[i]='6'; - } - str[i] = 0; - - /* No error */ - return 0; -} - -/** -* Configures Vector Table base location and SysTick -*/ -void NVIC_Configuration(void) -{ - /** - * stub - */ - printf("NVIC_Configuration\n"); - /* Set the Vector Table base address as specified in .ld file */ - //NVIC_SetVectorTable(PIOS_NVIC_VECTTAB_FLASH, 0x0); - - /* 4 bits for Interrupt priorities so no sub priorities */ - //NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4); - - /* Configure HCLK clock as SysTick clock source. */ - //SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK); -} - -#ifdef USE_FULL_ASSERT -/** -* Reports the name of the source file and the source line number -* where the assert_param error has occurred. -* \param[in] file pointer to the source file name -* \param[in] line assert_param error line source number -* \retval None -*/ -void assert_failed(uint8_t* file, uint32_t line) -{ - /* When serial debugging is implemented, use something like this. */ - /* printf("Wrong parameters value: file %s on line %d\r\n", file, line); */ - printf("Wrong parameters value: file %s on line %d\r\n", file, line); - - /* Setup the LEDs to Alternate */ - PIOS_LED_On(LED1); - PIOS_LED_Off(LED2); - - /* Infinite loop */ - while (1) - { - PIOS_LED_Toggle(LED1); - PIOS_LED_Toggle(LED2); - for(int i = 0; i < 1000000; i++); - } -} -#endif - -#endif +/** + ****************************************************************************** + * + * @file pios_sys.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Sets up basic system hardware, functions are called from Main. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_SYS System Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_SYS) + + +/* Private Function Prototypes */ +void NVIC_Configuration(void); +void SysTick_Handler(void); + +/* Local Macros */ +#define MEM8(addr) (*((volatile uint8_t *)(addr))) + +/** +* Initialises all system peripherals +*/ +void PIOS_SYS_Init(void) +{ + + /** + * stub + */ + printf("PIOS_SYS_Init\n"); + + /* Initialise Basic NVIC */ + NVIC_Configuration(); + +#if defined(PIOS_INCLUDE_LED) + /* Initialise LEDs */ + PIOS_LED_Init(); +#endif +} + +/** +* Shutdown PIOS and reset the microcontroller:
+*
    +*
  • Disable all RTOS tasks +*
  • Disable all interrupts +*
  • Turn off all board LEDs +*
  • Reset STM32 +*
+* \return < 0 if reset failed +*/ +int32_t PIOS_SYS_Reset(void) +{ + /** + * stub + */ + printf("PIOS_SYS_Reset\n"); + /* Disable all RTOS tasks */ +#if defined(PIOS_INCLUDE_FREERTOS) + /* port specific FreeRTOS function to disable tasks (nested) */ + portENTER_CRITICAL(); +#endif + + // disable all interrupts + //PIOS_IRQ_Disable(); + + // turn off all board LEDs + #if (PIOS_LED_NUM == 1) + PIOS_LED_Off(LED1); + #elif (PIOS_LED_NUM == 2) + PIOS_LED_Off(LED1); + PIOS_LED_Off(LED2); + #endif + + + + /* Reset STM32 */ + //RCC_APB2PeriphResetCmd(0xfffffff8, ENABLE); /* MBHP_CORE_STM32: don't reset GPIOA/AF due to USB pins */ + //RCC_APB1PeriphResetCmd(0xff7fffff, ENABLE); /* don't reset USB, so that the connection can survive! */ + + //RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); + //RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); + //SCB->AIRCR = NVIC_AIRCR_VECTKEY | (1 << NVIC_VECTRESET); + exit(1); + + while(1); + + /* We will never reach this point */ + return -1; +} + +/** +* Returns the serial number as a string +* param[out] str pointer to a string which can store at least 32 digits + zero terminator! +* (24 digits returned for STM32) +* return < 0 if feature not supported +*/ +int32_t PIOS_SYS_SerialNumberGet(char *str) +{ + int i; + + /* Stored in the so called "electronic signature" */ + for(i=0; i<24; ++i) { + //uint8_t b = MEM8(0x1ffff7e8 + (i/2)); + //if( !(i & 1) ) + //b >>= 4; + //b &= 0x0f; + + //str[i] = ((b > 9) ? ('A'-10) : '0') + b; + str[i]='6'; + } + str[i] = 0; + + /* No error */ + return 0; +} + +/** +* Configures Vector Table base location and SysTick +*/ +void NVIC_Configuration(void) +{ + /** + * stub + */ + printf("NVIC_Configuration\n"); + /* Set the Vector Table base address as specified in .ld file */ + //NVIC_SetVectorTable(PIOS_NVIC_VECTTAB_FLASH, 0x0); + + /* 4 bits for Interrupt priorities so no sub priorities */ + //NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4); + + /* Configure HCLK clock as SysTick clock source. */ + //SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK); +} + +#ifdef USE_FULL_ASSERT +/** +* Reports the name of the source file and the source line number +* where the assert_param error has occurred. +* \param[in] file pointer to the source file name +* \param[in] line assert_param error line source number +* \retval None +*/ +void assert_failed(uint8_t* file, uint32_t line) +{ + /* When serial debugging is implemented, use something like this. */ + /* printf("Wrong parameters value: file %s on line %d\r\n", file, line); */ + printf("Wrong parameters value: file %s on line %d\r\n", file, line); + + /* Setup the LEDs to Alternate */ + PIOS_LED_On(LED1); + PIOS_LED_Off(LED2); + + /* Infinite loop */ + while (1) + { + PIOS_LED_Toggle(LED1); + PIOS_LED_Toggle(LED2); + for(int i = 0; i < 1000000; i++); + } +} +#endif + +#endif diff --git a/flight/PiOS.win32/win32/pios_udp.c b/flight/PiOS.win32/win32/pios_udp.c index 278b64db6..ed4342e4c 100644 --- a/flight/PiOS.win32/win32/pios_udp.c +++ b/flight/PiOS.win32/win32/pios_udp.c @@ -1,478 +1,478 @@ -/** - ****************************************************************************** - * - * @file pios_udp.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief UDP commands. Inits UDPs, controls UDPs & Interupt handlers. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_UDP UDP Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_UDP) - -#include - -/* Provide a COM driver */ -const struct pios_com_driver pios_udp_com_driver = { - .set_baud = PIOS_UDP_ChangeBaud, - .tx_nb = PIOS_UDP_TxBufferPutMoreNonBlocking, - .tx = PIOS_UDP_TxBufferPutMore, - .rx = PIOS_UDP_RxBufferGet, - .rx_avail = PIOS_UDP_RxBufferUsed, -}; - -WSADATA wsaData; - -static struct pios_udp_dev * find_udp_dev_by_id (uint8_t udp) -{ - if (udp >= pios_udp_num_devices) { - /* Undefined UDP port for this board (see pios_board.c) */ - return NULL; - } - - /* Get a handle for the device configuration */ - return &(pios_udp_devs[udp]); -} - -/** -* Open some UDP sockets -*/ -void PIOS_UDP_Init(void) -{ - struct pios_udp_dev * udp_dev; - uint8_t i; - - WSAStartup(MAKEWORD(2, 0), &wsaData); - - for (i = 0; i < pios_udp_num_devices; i++) { - /* Get a handle for the device configuration */ - udp_dev = find_udp_dev_by_id(i); - //PIOS_DEBUG_Assert(udp_dev); - - /* Clear buffer counters */ - udp_dev->rx.head = udp_dev->rx.tail = udp_dev->rx.size = 0; - - /* assign socket */ - udp_dev->socket = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP); - memset(&udp_dev->server,0,sizeof(udp_dev->server)); - memset(&udp_dev->client,0,sizeof(udp_dev->client)); - udp_dev->server.sin_family = AF_INET; - udp_dev->server.sin_addr.s_addr = inet_addr(udp_dev->cfg->ip); - udp_dev->server.sin_port = htons(udp_dev->cfg->port); - BOOL tmp = TRUE; - setsockopt(udp_dev->socket, SOL_SOCKET, SO_BROADCAST, (char *)&tmp, sizeof(tmp)); - int res= bind(udp_dev->socket, (struct sockaddr *)&udp_dev->server,sizeof(udp_dev->server)); - /* use nonblocking IO */ - u_long argp = 1; - ioctlsocket(udp_dev->socket, FIONBIO, &argp); - printf("udp dev %i - socket %i opened - result %i\n",i,udp_dev->socket,res); - - /* TODO do some error handling - wait no, we can't - we are void anyway ;) */ - } -} - -/** +/** + ****************************************************************************** + * + * @file pios_udp.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief UDP commands. Inits UDPs, controls UDPs & Interupt handlers. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_UDP UDP Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_UDP) + +#include + +/* Provide a COM driver */ +const struct pios_com_driver pios_udp_com_driver = { + .set_baud = PIOS_UDP_ChangeBaud, + .tx_nb = PIOS_UDP_TxBufferPutMoreNonBlocking, + .tx = PIOS_UDP_TxBufferPutMore, + .rx = PIOS_UDP_RxBufferGet, + .rx_avail = PIOS_UDP_RxBufferUsed, +}; + +WSADATA wsaData; + +static struct pios_udp_dev * find_udp_dev_by_id (uint8_t udp) +{ + if (udp >= pios_udp_num_devices) { + /* Undefined UDP port for this board (see pios_board.c) */ + return NULL; + } + + /* Get a handle for the device configuration */ + return &(pios_udp_devs[udp]); +} + +/** +* Open some UDP sockets +*/ +void PIOS_UDP_Init(void) +{ + struct pios_udp_dev * udp_dev; + uint8_t i; + + WSAStartup(MAKEWORD(2, 0), &wsaData); + + for (i = 0; i < pios_udp_num_devices; i++) { + /* Get a handle for the device configuration */ + udp_dev = find_udp_dev_by_id(i); + //PIOS_DEBUG_Assert(udp_dev); + + /* Clear buffer counters */ + udp_dev->rx.head = udp_dev->rx.tail = udp_dev->rx.size = 0; + + /* assign socket */ + udp_dev->socket = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP); + memset(&udp_dev->server,0,sizeof(udp_dev->server)); + memset(&udp_dev->client,0,sizeof(udp_dev->client)); + udp_dev->server.sin_family = AF_INET; + udp_dev->server.sin_addr.s_addr = inet_addr(udp_dev->cfg->ip); + udp_dev->server.sin_port = htons(udp_dev->cfg->port); + BOOL tmp = TRUE; + setsockopt(udp_dev->socket, SOL_SOCKET, SO_BROADCAST, (char *)&tmp, sizeof(tmp)); + int res= bind(udp_dev->socket, (struct sockaddr *)&udp_dev->server,sizeof(udp_dev->server)); + /* use nonblocking IO */ + u_long argp = 1; + ioctlsocket(udp_dev->socket, FIONBIO, &argp); + printf("udp dev %i - socket %i opened - result %i\n",i,udp_dev->socket,res); + + /* TODO do some error handling - wait no, we can't - we are void anyway ;) */ + } +} + +/** * Clean up Winsock - */ -void PIOS_UDP_Close(void) -{ - WSACleanup(); -} - -/** -* Changes the baud rate of the UDP peripheral without re-initialising. -* \param[in] udp UDP name (GPS, TELEM, AUX) -* \param[in] baud Requested baud rate -*/ -void PIOS_UDP_ChangeBaud(uint8_t udp, uint32_t baud) -{ -} - - -/** -* puts a byte onto the receive buffer -* \param[in] UDP UDP name -* \param[in] b byte which should be put into Rx buffer -* \return 0 if no error -* \return -1 if UDP not available -* \return -2 if buffer full (retry) -* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions -*/ -int32_t PIOS_UDP_RxBufferPut(uint8_t udp, uint8_t b) -{ - struct pios_udp_dev * udp_dev; - - /* Get a handle for the device configuration */ - udp_dev = find_udp_dev_by_id(udp); - - if (!udp_dev) { - /* Undefined UDP port for this board (see pios_board.c) */ - return -1; - } - - if (udp_dev->rx.size >= sizeof(udp_dev->rx.buf)) { - /* Buffer full (retry) */ - return -2; - } - - /* Copy received byte into receive buffer */ - udp_dev->rx.buf[udp_dev->rx.head++] = b; - if (udp_dev->rx.head >= sizeof(udp_dev->rx.buf)) { - udp_dev->rx.head = 0; - } - udp_dev->rx.size++; - - /* No error */ - return 0; -} - -/** - * attempt to receive - */ -void PIOS_UDP_RECV(uint8_t udp) { - - struct pios_udp_dev * udp_dev; - char localbuffer[PIOS_UDP_RX_BUFFER_SIZE]; - - /* Get a handle for the device configuration */ - udp_dev = find_udp_dev_by_id(udp); - - if (!udp_dev) { - /* Undefined UDP port for this board (see pios_board.c) */ - return; - } - - /* use nonblocking IO */ - u_long argp = 1; - ioctlsocket(udp_dev->socket, FIONBIO, &argp); - - /* receive data */ - int received; - udp_dev->clientLength=sizeof(udp_dev->client); - if ((received = recvfrom(udp_dev->socket, - localbuffer, - (PIOS_UDP_RX_BUFFER_SIZE - udp_dev->rx.size), - 0, - (struct sockaddr *) &udp_dev->client, - (int*)&udp_dev->clientLength)) == SOCKET_ERROR) { - - return; - } - /* copy received data to buffer */ - int t; - for (t=0;trx.buf) - udp_dev->rx.size); -} - -/** -* Returns number of used bytes in receive buffer -* \param[in] UDP UDP name -* \return > 0: number of used bytes -* \return 0 if UDP not available -* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions -*/ -int32_t PIOS_UDP_RxBufferUsed(uint8_t udp) -{ - struct pios_udp_dev * udp_dev; - - /* Get a handle for the device configuration */ - udp_dev = find_udp_dev_by_id(udp); - - if (!udp_dev) { - /* Undefined UDP port for this board (see pios_board.c) */ - return -2; - } - - /* fill buffer */ - PIOS_UDP_RECV(udp); - - return (udp_dev->rx.size); -} - -/** -* Gets a byte from the receive buffer -* \param[in] UDP UDP name -* \return -1 if UDP not available -* \return -2 if no new byte available -* \return >= 0: number of received bytes -* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions -*/ -int32_t PIOS_UDP_RxBufferGet(uint8_t udp) -{ - struct pios_udp_dev * udp_dev; - - /* Get a handle for the device configuration */ - udp_dev = find_udp_dev_by_id(udp); - - if (!udp_dev) { - /* Undefined UDP port for this board (see pios_board.c) */ - return -2; - } - - /* fill buffer */ - PIOS_UDP_RECV(udp); - - if (!udp_dev->rx.size) { - /* Nothing new in the buffer */ - //printf("PIOS_UDP: nothing new in the buffer\n"); - return -1; - } - - /* get byte */ - uint8_t b = udp_dev->rx.buf[udp_dev->rx.tail++]; - if (udp_dev->rx.tail >= sizeof(udp_dev->rx.buf)) { - udp_dev->rx.tail = 0; - } - udp_dev->rx.size--; - - //printf("PIOS_UDP: received byte: %c\n", (char) b); - - /* Return received byte */ - return b; -} - -/** -* Returns the next byte of the receive buffer without taking it -* \param[in] UDP UDP name -* \return -1 if UDP not available -* \return -2 if no new byte available -* \return >= 0: number of received bytes -* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions -*/ -int32_t PIOS_UDP_RxBufferPeek(uint8_t udp) -{ - struct pios_udp_dev * udp_dev; - - /* Get a handle for the device configuration */ - udp_dev = find_udp_dev_by_id(udp); - - if (!udp_dev) { - /* Undefined UDP port for this board (see pios_board.c) */ - return -2; - } - - /* fill buffer */ - PIOS_UDP_RECV(udp); - - if (!udp_dev->rx.size) { - /* Nothing new in the buffer */ - return -1; - } - - /* get byte */ - uint8_t b = udp_dev->rx.buf[udp_dev->rx.tail]; - - /* Return received byte */ - return b; -} - -/** -* returns number of free bytes in transmit buffer -* \param[in] UDP UDP name -* \return number of free bytes -* \return 0 if UDP not available -* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions -*/ -int32_t PIOS_UDP_TxBufferFree(uint8_t udp) -{ - struct pios_udp_dev * udp_dev; - - /* Get a handle for the device configuration */ - udp_dev = find_udp_dev_by_id(udp); - - if (!udp_dev) { - /* Undefined UDP port for this board (see pios_board.c) */ - return 0; - } - - return PIOS_UDP_RX_BUFFER_SIZE; -} - -/** -* returns number of used bytes in transmit buffer -* \param[in] UDP UDP name -* \return number of used bytes -* \return 0 if UDP not available -* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions -*/ -int32_t PIOS_UDP_TxBufferUsed(uint8_t udp) -{ - struct pios_udp_dev * udp_dev; - - /* Get a handle for the device configuration */ - udp_dev = find_udp_dev_by_id(udp); - - if (!udp_dev) { - /* Undefined UDP port for this board (see pios_board.c) */ - return 0; - } - - return 0; -} - - -/** -* puts more than one byte onto the transmit buffer (used for atomic sends) -* \param[in] UDP UDP name -* \param[in] *buffer pointer to buffer to be sent -* \param[in] len number of bytes to be sent -* \return 0 if no error -* \return -1 if UDP not available -* \return -2 if buffer full or cannot get all requested bytes (retry) -* \return -3 if UDP not supported by UDPTxBufferPut Routine -* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions -*/ -int32_t PIOS_UDP_TxBufferPutMoreNonBlocking(uint8_t udp, char *buffer, uint16_t len) -{ - struct pios_udp_dev * udp_dev; - - /* Get a handle for the device configuration */ - udp_dev = find_udp_dev_by_id(udp); - - if (!udp_dev) { - /* Undefined UDP port for this board (see pios_board.c) */ - return -1; - } - - if (len >= PIOS_UDP_RX_BUFFER_SIZE) { - /* Buffer cannot accept all requested bytes (retry) */ - return -2; - } - /* send data to client - non blocking*/ - - /* use nonblocking IO */ - u_long argp = 1; - ioctlsocket(udp_dev->socket, FIONBIO, &argp); - sendto(udp_dev->socket, buffer, len, 0, - (struct sockaddr *) &udp_dev->client, - (int)sizeof(udp_dev->client)); - - - /* No error */ - return 0; -} - -/** -* puts more than one byte onto the transmit buffer (used for atomic sends)
-* (blocking function) -* \param[in] UDP UDP name -* \param[in] *buffer pointer to buffer to be sent -* \param[in] len number of bytes to be sent -* \return 0 if no error -* \return -1 if UDP not available -* \return -3 if UDP not supported by UDPTxBufferPut Routine -* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions -*/ -int32_t PIOS_UDP_TxBufferPutMore(uint8_t udp, char *buffer, uint16_t len) -{ - struct pios_udp_dev * udp_dev; - - /* Get a handle for the device configuration */ - udp_dev = find_udp_dev_by_id(udp); - - if (!udp_dev) { - /* Undefined UDP port for this board (see pios_board.c) */ - return -1; - } - - if (len >= PIOS_UDP_RX_BUFFER_SIZE) { - /* Buffer cannot accept all requested bytes (retry) */ - return -2; - } - - /* send data to client - blocking*/ - /* use blocking IO */ - u_long argp = 1; - ioctlsocket(udp_dev->socket, FIONBIO, &argp); - sendto(udp_dev->socket, buffer, len, 0, - (struct sockaddr *) &udp_dev->client, - sizeof(udp_dev->client)); - - //printf("PIOS_UDP: sent data\n"); - - /* No error */ - return 0; -} - -/** -* puts a byte onto the transmit buffer -* \param[in] UDP UDP name -* \param[in] b byte which should be put into Tx buffer -* \return 0 if no error -* \return -1 if UDP not available -* \return -2 if buffer full (retry) -* \return -3 if UDP not supported by UDPTxBufferPut Routine -* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions -*/ -int32_t PIOS_UDP_TxBufferPut_NonBlocking(uint8_t udp, char b) -{ - return PIOS_UDP_TxBufferPutMoreNonBlocking(udp, &b, 1); -} - -/** -* puts a byte onto the transmit buffer
-* (blocking function) -* \param[in] UDP UDP name -* \param[in] b byte which should be put into Tx buffer -* \return 0 if no error -* \return -1 if UDP not available -* \return -3 if UDP not supported by UDPTxBufferPut Routine -* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions -*/ -int32_t PIOS_UDP_TxBufferPut(uint8_t udp, char b) -{ - return PIOS_UDP_TxBufferPutMore(udp, &b, 1); -} - - -#endif + */ +void PIOS_UDP_Close(void) +{ + WSACleanup(); +} + +/** +* Changes the baud rate of the UDP peripheral without re-initialising. +* \param[in] udp UDP name (GPS, TELEM, AUX) +* \param[in] baud Requested baud rate +*/ +void PIOS_UDP_ChangeBaud(uint8_t udp, uint32_t baud) +{ +} + + +/** +* puts a byte onto the receive buffer +* \param[in] UDP UDP name +* \param[in] b byte which should be put into Rx buffer +* \return 0 if no error +* \return -1 if UDP not available +* \return -2 if buffer full (retry) +* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions +*/ +int32_t PIOS_UDP_RxBufferPut(uint8_t udp, uint8_t b) +{ + struct pios_udp_dev * udp_dev; + + /* Get a handle for the device configuration */ + udp_dev = find_udp_dev_by_id(udp); + + if (!udp_dev) { + /* Undefined UDP port for this board (see pios_board.c) */ + return -1; + } + + if (udp_dev->rx.size >= sizeof(udp_dev->rx.buf)) { + /* Buffer full (retry) */ + return -2; + } + + /* Copy received byte into receive buffer */ + udp_dev->rx.buf[udp_dev->rx.head++] = b; + if (udp_dev->rx.head >= sizeof(udp_dev->rx.buf)) { + udp_dev->rx.head = 0; + } + udp_dev->rx.size++; + + /* No error */ + return 0; +} + +/** + * attempt to receive + */ +void PIOS_UDP_RECV(uint8_t udp) { + + struct pios_udp_dev * udp_dev; + char localbuffer[PIOS_UDP_RX_BUFFER_SIZE]; + + /* Get a handle for the device configuration */ + udp_dev = find_udp_dev_by_id(udp); + + if (!udp_dev) { + /* Undefined UDP port for this board (see pios_board.c) */ + return; + } + + /* use nonblocking IO */ + u_long argp = 1; + ioctlsocket(udp_dev->socket, FIONBIO, &argp); + + /* receive data */ + int received; + udp_dev->clientLength=sizeof(udp_dev->client); + if ((received = recvfrom(udp_dev->socket, + localbuffer, + (PIOS_UDP_RX_BUFFER_SIZE - udp_dev->rx.size), + 0, + (struct sockaddr *) &udp_dev->client, + (int*)&udp_dev->clientLength)) == SOCKET_ERROR) { + + return; + } + /* copy received data to buffer */ + int t; + for (t=0;trx.buf) - udp_dev->rx.size); +} + +/** +* Returns number of used bytes in receive buffer +* \param[in] UDP UDP name +* \return > 0: number of used bytes +* \return 0 if UDP not available +* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions +*/ +int32_t PIOS_UDP_RxBufferUsed(uint8_t udp) +{ + struct pios_udp_dev * udp_dev; + + /* Get a handle for the device configuration */ + udp_dev = find_udp_dev_by_id(udp); + + if (!udp_dev) { + /* Undefined UDP port for this board (see pios_board.c) */ + return -2; + } + + /* fill buffer */ + PIOS_UDP_RECV(udp); + + return (udp_dev->rx.size); +} + +/** +* Gets a byte from the receive buffer +* \param[in] UDP UDP name +* \return -1 if UDP not available +* \return -2 if no new byte available +* \return >= 0: number of received bytes +* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions +*/ +int32_t PIOS_UDP_RxBufferGet(uint8_t udp) +{ + struct pios_udp_dev * udp_dev; + + /* Get a handle for the device configuration */ + udp_dev = find_udp_dev_by_id(udp); + + if (!udp_dev) { + /* Undefined UDP port for this board (see pios_board.c) */ + return -2; + } + + /* fill buffer */ + PIOS_UDP_RECV(udp); + + if (!udp_dev->rx.size) { + /* Nothing new in the buffer */ + //printf("PIOS_UDP: nothing new in the buffer\n"); + return -1; + } + + /* get byte */ + uint8_t b = udp_dev->rx.buf[udp_dev->rx.tail++]; + if (udp_dev->rx.tail >= sizeof(udp_dev->rx.buf)) { + udp_dev->rx.tail = 0; + } + udp_dev->rx.size--; + + //printf("PIOS_UDP: received byte: %c\n", (char) b); + + /* Return received byte */ + return b; +} + +/** +* Returns the next byte of the receive buffer without taking it +* \param[in] UDP UDP name +* \return -1 if UDP not available +* \return -2 if no new byte available +* \return >= 0: number of received bytes +* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions +*/ +int32_t PIOS_UDP_RxBufferPeek(uint8_t udp) +{ + struct pios_udp_dev * udp_dev; + + /* Get a handle for the device configuration */ + udp_dev = find_udp_dev_by_id(udp); + + if (!udp_dev) { + /* Undefined UDP port for this board (see pios_board.c) */ + return -2; + } + + /* fill buffer */ + PIOS_UDP_RECV(udp); + + if (!udp_dev->rx.size) { + /* Nothing new in the buffer */ + return -1; + } + + /* get byte */ + uint8_t b = udp_dev->rx.buf[udp_dev->rx.tail]; + + /* Return received byte */ + return b; +} + +/** +* returns number of free bytes in transmit buffer +* \param[in] UDP UDP name +* \return number of free bytes +* \return 0 if UDP not available +* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions +*/ +int32_t PIOS_UDP_TxBufferFree(uint8_t udp) +{ + struct pios_udp_dev * udp_dev; + + /* Get a handle for the device configuration */ + udp_dev = find_udp_dev_by_id(udp); + + if (!udp_dev) { + /* Undefined UDP port for this board (see pios_board.c) */ + return 0; + } + + return PIOS_UDP_RX_BUFFER_SIZE; +} + +/** +* returns number of used bytes in transmit buffer +* \param[in] UDP UDP name +* \return number of used bytes +* \return 0 if UDP not available +* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions +*/ +int32_t PIOS_UDP_TxBufferUsed(uint8_t udp) +{ + struct pios_udp_dev * udp_dev; + + /* Get a handle for the device configuration */ + udp_dev = find_udp_dev_by_id(udp); + + if (!udp_dev) { + /* Undefined UDP port for this board (see pios_board.c) */ + return 0; + } + + return 0; +} + + +/** +* puts more than one byte onto the transmit buffer (used for atomic sends) +* \param[in] UDP UDP name +* \param[in] *buffer pointer to buffer to be sent +* \param[in] len number of bytes to be sent +* \return 0 if no error +* \return -1 if UDP not available +* \return -2 if buffer full or cannot get all requested bytes (retry) +* \return -3 if UDP not supported by UDPTxBufferPut Routine +* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions +*/ +int32_t PIOS_UDP_TxBufferPutMoreNonBlocking(uint8_t udp, char *buffer, uint16_t len) +{ + struct pios_udp_dev * udp_dev; + + /* Get a handle for the device configuration */ + udp_dev = find_udp_dev_by_id(udp); + + if (!udp_dev) { + /* Undefined UDP port for this board (see pios_board.c) */ + return -1; + } + + if (len >= PIOS_UDP_RX_BUFFER_SIZE) { + /* Buffer cannot accept all requested bytes (retry) */ + return -2; + } + /* send data to client - non blocking*/ + + /* use nonblocking IO */ + u_long argp = 1; + ioctlsocket(udp_dev->socket, FIONBIO, &argp); + sendto(udp_dev->socket, buffer, len, 0, + (struct sockaddr *) &udp_dev->client, + (int)sizeof(udp_dev->client)); + + + /* No error */ + return 0; +} + +/** +* puts more than one byte onto the transmit buffer (used for atomic sends)
+* (blocking function) +* \param[in] UDP UDP name +* \param[in] *buffer pointer to buffer to be sent +* \param[in] len number of bytes to be sent +* \return 0 if no error +* \return -1 if UDP not available +* \return -3 if UDP not supported by UDPTxBufferPut Routine +* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions +*/ +int32_t PIOS_UDP_TxBufferPutMore(uint8_t udp, char *buffer, uint16_t len) +{ + struct pios_udp_dev * udp_dev; + + /* Get a handle for the device configuration */ + udp_dev = find_udp_dev_by_id(udp); + + if (!udp_dev) { + /* Undefined UDP port for this board (see pios_board.c) */ + return -1; + } + + if (len >= PIOS_UDP_RX_BUFFER_SIZE) { + /* Buffer cannot accept all requested bytes (retry) */ + return -2; + } + + /* send data to client - blocking*/ + /* use blocking IO */ + u_long argp = 1; + ioctlsocket(udp_dev->socket, FIONBIO, &argp); + sendto(udp_dev->socket, buffer, len, 0, + (struct sockaddr *) &udp_dev->client, + sizeof(udp_dev->client)); + + //printf("PIOS_UDP: sent data\n"); + + /* No error */ + return 0; +} + +/** +* puts a byte onto the transmit buffer +* \param[in] UDP UDP name +* \param[in] b byte which should be put into Tx buffer +* \return 0 if no error +* \return -1 if UDP not available +* \return -2 if buffer full (retry) +* \return -3 if UDP not supported by UDPTxBufferPut Routine +* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions +*/ +int32_t PIOS_UDP_TxBufferPut_NonBlocking(uint8_t udp, char b) +{ + return PIOS_UDP_TxBufferPutMoreNonBlocking(udp, &b, 1); +} + +/** +* puts a byte onto the transmit buffer
+* (blocking function) +* \param[in] UDP UDP name +* \param[in] b byte which should be put into Tx buffer +* \return 0 if no error +* \return -1 if UDP not available +* \return -3 if UDP not supported by UDPTxBufferPut Routine +* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions +*/ +int32_t PIOS_UDP_TxBufferPut(uint8_t udp, char b) +{ + return PIOS_UDP_TxBufferPutMore(udp, &b, 1); +} + + +#endif diff --git a/flight/PiOS.win32/win32/pios_wdg.c b/flight/PiOS.win32/win32/pios_wdg.c index 93568247f..e3b7701d4 100644 --- a/flight/PiOS.win32/win32/pios_wdg.c +++ b/flight/PiOS.win32/win32/pios_wdg.c @@ -1,123 +1,123 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_WDG Watchdog Functions - * @brief PIOS Comamnds to initialize and clear watchdog timer - * @{ - * - * @file pios_spi.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief Hardware Abstraction Layer for SPI ports of STM32 - * @see The GNU Public License (GPL) Version 3 - * @notes - * - * The PIOS Watchdog provides a HAL to initialize a watchdog - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pios.h" - -/** - * @brief Initialize the watchdog timer for a specified timeout - * - * It is important to note that this function returns the achieved timeout - * for this hardware. For hardware indendence this should be checked when - * scheduling updates. Other hardware dependent details may need to be - * considered such as a window time which sets a minimum update time, - * and this function should return a recommended delay for clearing. - * - * For the STM32 nominal clock rate is 32 khz, but for the maximum clock rate of - * 60 khz and a prescalar of 4 yields a clock rate of 15 khz. The delay that is - * set in the watchdog assumes the nominal clock rate, but the delay for FreeRTOS - * to use is 75% of the minimal delay. - * - * @param[in] delayMs The delay period in ms - * @returns Maximum recommended delay between updates - */ -void PIOS_WDG_Init() -{ -} - -/** - * @brief Register a module against the watchdog - * - * There are two ways to use PIOS WDG: this is for when - * multiple modules must be monitored. In this case they - * must first register against the watchdog system and - * only when all of the modules have been updated with the - * watchdog be cleared. Each module must have its own - * bit in the 16 bit - * - * @param[in] flag the bit this module wants to use - * @returns True if that bit is unregistered - */ -bool PIOS_WDG_RegisterFlag(uint16_t flag_requested) -{ - return true; -} - -/** - * @brief Function called by modules to indicate they are still running - * - * This function will set this flag in the active flags register (which is - * a backup regsiter) and if all the registered flags are set will clear - * the watchdog and set only this flag in the backup register - * - * @param[in] flag the flag to set - * @return true if the watchdog cleared, false if flags are pending - */ -bool PIOS_WDG_UpdateFlag(uint16_t flag) -{ - return true; -} - -/** - * @brief Returns the flags that were set at bootup - * - * This is used for diagnostics, if only one flag not set this - * was likely the module that wasn't running before reset - * - * @return The active flags register from bootup - */ -uint16_t PIOS_WDG_GetBootupFlags() -{ - return (uint16_t) 0xffff; -} - -/** - * @brief Returns the currently active flags - * - * For external monitoring - * - * @return The active flags register - */ -uint16_t PIOS_WDG_GetActiveFlags() -{ - return (uint16_t) 0xffff; -} - -/** - * @brief Clear the watchdog timer - * - * This function must be called at the appropriate delay to prevent a reset event occuring - */ -void PIOS_WDG_Clear(void) -{ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_WDG Watchdog Functions + * @brief PIOS Comamnds to initialize and clear watchdog timer + * @{ + * + * @file pios_spi.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Hardware Abstraction Layer for SPI ports of STM32 + * @see The GNU Public License (GPL) Version 3 + * @notes + * + * The PIOS Watchdog provides a HAL to initialize a watchdog + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios.h" + +/** + * @brief Initialize the watchdog timer for a specified timeout + * + * It is important to note that this function returns the achieved timeout + * for this hardware. For hardware indendence this should be checked when + * scheduling updates. Other hardware dependent details may need to be + * considered such as a window time which sets a minimum update time, + * and this function should return a recommended delay for clearing. + * + * For the STM32 nominal clock rate is 32 khz, but for the maximum clock rate of + * 60 khz and a prescalar of 4 yields a clock rate of 15 khz. The delay that is + * set in the watchdog assumes the nominal clock rate, but the delay for FreeRTOS + * to use is 75% of the minimal delay. + * + * @param[in] delayMs The delay period in ms + * @returns Maximum recommended delay between updates + */ +void PIOS_WDG_Init() +{ +} + +/** + * @brief Register a module against the watchdog + * + * There are two ways to use PIOS WDG: this is for when + * multiple modules must be monitored. In this case they + * must first register against the watchdog system and + * only when all of the modules have been updated with the + * watchdog be cleared. Each module must have its own + * bit in the 16 bit + * + * @param[in] flag the bit this module wants to use + * @returns True if that bit is unregistered + */ +bool PIOS_WDG_RegisterFlag(uint16_t flag_requested) +{ + return true; +} + +/** + * @brief Function called by modules to indicate they are still running + * + * This function will set this flag in the active flags register (which is + * a backup regsiter) and if all the registered flags are set will clear + * the watchdog and set only this flag in the backup register + * + * @param[in] flag the flag to set + * @return true if the watchdog cleared, false if flags are pending + */ +bool PIOS_WDG_UpdateFlag(uint16_t flag) +{ + return true; +} + +/** + * @brief Returns the flags that were set at bootup + * + * This is used for diagnostics, if only one flag not set this + * was likely the module that wasn't running before reset + * + * @return The active flags register from bootup + */ +uint16_t PIOS_WDG_GetBootupFlags() +{ + return (uint16_t) 0xffff; +} + +/** + * @brief Returns the currently active flags + * + * For external monitoring + * + * @return The active flags register + */ +uint16_t PIOS_WDG_GetActiveFlags() +{ + return (uint16_t) 0xffff; +} + +/** + * @brief Clear the watchdog timer + * + * This function must be called at the appropriate delay to prevent a reset event occuring + */ +void PIOS_WDG_Clear(void) +{ } \ No newline at end of file diff --git a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h index caa3683e4..ac4be841c 100644 --- a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h @@ -1,282 +1,282 @@ - /** - ****************************************************************************** - * - * @file pios_board.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef STM32103CB_CC_H_ -#define STM32103CB_CC_H_ - -//------------------------ -// Timers and Channels Used -//------------------------ -/* -Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 -------+-----------+-----------+-----------+---------- -TIM1 | Servo 4 | | | -TIM2 | RC In 5 | RC In 6 | Servo 6 | -TIM3 | Servo 5 | RC In 2 | RC In 3 | RC In 4 -TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1 -------+-----------+-----------+-----------+---------- -*/ - -//------------------------ -// DMA Channels Used -//------------------------ -/* Channel 1 - */ -/* Channel 2 - */ -/* Channel 3 - */ -/* Channel 4 - */ -/* Channel 5 - */ -/* Channel 6 - */ -/* Channel 7 - */ -/* Channel 8 - */ -/* Channel 9 - */ -/* Channel 10 - */ -/* Channel 11 - */ -/* Channel 12 - */ - - -//------------------------ -// BOOTLOADER_SETTINGS -//------------------------ -#define BOARD_READABLE TRUE -#define BOARD_WRITABLE TRUE -#define MAX_DEL_RETRYS 3 - - -//------------------------ -// WATCHDOG_SETTINGS -//------------------------ -#define PIOS_WATCHDOG_TIMEOUT 250 -#define PIOS_WDG_REGISTER BKP_DR4 -#define PIOS_WDG_ACTUATOR 0x0001 -#define PIOS_WDG_STABILIZATION 0x0002 -#define PIOS_WDG_ATTITUDE 0x0004 -#define PIOS_WDG_MANUAL 0x0008 -#define PIOS_WDG_AUTOTUNE 0x0010 - -//------------------------ -// TELEMETRY -//------------------------ -#define TELEM_QUEUE_SIZE 20 - -//------------------------ -// PIOS_LED -//------------------------ -#define PIOS_LED_HEARTBEAT 0 - -//------------------------- -// System Settings -//------------------------- -#define PIOS_MASTER_CLOCK 72000000 -#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) - -//------------------------- -// Interrupt Priorities -//------------------------- -#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS -#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS -#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... -#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... - -//------------------------ -// PIOS_I2C -// See also pios_board.c -//------------------------ -#define PIOS_I2C_MAX_DEVS 1 -extern uint32_t pios_i2c_flexi_adapter_id; -#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexi_adapter_id) -#define PIOS_I2C_ESC_ADAPTER (pios_i2c_flexi_adapter_id) -#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_flexi_adapter_id) - -//------------------------ -// PIOS_BMP085 -//------------------------ -#define PIOS_BMP085_OVERSAMPLING 3 - -//------------------------- -// SPI -// -// See also pios_board.c -//------------------------- -#define PIOS_SPI_MAX_DEVS 2 - -//------------------------- -// PIOS_USART -//------------------------- -#define PIOS_USART_MAX_DEVS 2 - -//------------------------- -// PIOS_COM -// -// See also pios_board.c -//------------------------- -#define PIOS_COM_MAX_DEVS 3 - -extern uint32_t pios_com_telem_rf_id; -#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) - -#if defined(PIOS_INCLUDE_GPS) -extern uint32_t pios_com_gps_id; -#define PIOS_COM_GPS (pios_com_gps_id) -#endif /* PIOS_INCLUDE_GPS */ - -extern uint32_t pios_com_bridge_id; -#define PIOS_COM_BRIDGE (pios_com_bridge_id) - -extern uint32_t pios_com_vcp_id; -#define PIOS_COM_VCP (pios_com_vcp_id) - -extern uint32_t pios_com_telem_usb_id; -#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) - -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) -extern uint32_t pios_com_debug_id; -#define PIOS_COM_DEBUG (pios_com_debug_id) -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - -extern uint32_t pios_com_hkosd_id; -#define PIOS_COM_OSDHK (pios_com_hkosd_id) - - -//------------------------- -// ADC -// PIOS_ADC_PinGet(0) = Gyro Z -// PIOS_ADC_PinGet(1) = Gyro Y -// PIOS_ADC_PinGet(2) = Gyro X -//------------------------- -//#define PIOS_ADC_OVERSAMPLING_RATE 1 -#define PIOS_ADC_USE_TEMP_SENSOR 1 -#define PIOS_ADC_TEMP_SENSOR_ADC ADC1 -#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1 - -#define PIOS_ADC_PIN1_GPIO_PORT GPIOA // PA4 (Gyro X) -#define PIOS_ADC_PIN1_GPIO_PIN GPIO_Pin_4 // ADC12_IN4 -#define PIOS_ADC_PIN1_GPIO_CHANNEL ADC_Channel_4 -#define PIOS_ADC_PIN1_ADC ADC2 -#define PIOS_ADC_PIN1_ADC_NUMBER 1 - -#define PIOS_ADC_PIN2_GPIO_PORT GPIOA // PA5 (Gyro Y) -#define PIOS_ADC_PIN2_GPIO_PIN GPIO_Pin_5 // ADC123_IN5 -#define PIOS_ADC_PIN2_GPIO_CHANNEL ADC_Channel_5 -#define PIOS_ADC_PIN2_ADC ADC1 -#define PIOS_ADC_PIN2_ADC_NUMBER 2 - -#define PIOS_ADC_PIN3_GPIO_PORT GPIOA // PA3 (Gyro Z) -#define PIOS_ADC_PIN3_GPIO_PIN GPIO_Pin_3 // ADC12_IN3 -#define PIOS_ADC_PIN3_GPIO_CHANNEL ADC_Channel_3 -#define PIOS_ADC_PIN3_ADC ADC2 -#define PIOS_ADC_PIN3_ADC_NUMBER 2 - -#define PIOS_ADC_NUM_PINS 3 - -#define PIOS_ADC_PORTS { PIOS_ADC_PIN1_GPIO_PORT, PIOS_ADC_PIN2_GPIO_PORT, PIOS_ADC_PIN3_GPIO_PORT } -#define PIOS_ADC_PINS { PIOS_ADC_PIN1_GPIO_PIN, PIOS_ADC_PIN2_GPIO_PIN, PIOS_ADC_PIN3_GPIO_PIN } -#define PIOS_ADC_CHANNELS { PIOS_ADC_PIN1_GPIO_CHANNEL, PIOS_ADC_PIN2_GPIO_CHANNEL, PIOS_ADC_PIN3_GPIO_CHANNEL } -#define PIOS_ADC_MAPPING { PIOS_ADC_PIN1_ADC, PIOS_ADC_PIN2_ADC, PIOS_ADC_PIN3_ADC } -#define PIOS_ADC_CHANNEL_MAPPING { PIOS_ADC_PIN1_ADC_NUMBER, PIOS_ADC_PIN2_ADC_NUMBER, PIOS_ADC_PIN3_ADC_NUMBER } -#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR) -#define PIOS_ADC_NUM_ADC_CHANNELS 2 -#define PIOS_ADC_USE_ADC2 1 -#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE) -#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8 -/* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */ -/* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */ -/* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */ -/* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */ -#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5 -/* Sample time: */ -/* With an ADCCLK = 14 MHz and a sampling time of 239.5 cycles: */ -/* Tconv = 239.5 + 12.5 = 252 cycles = 18�s */ -/* (1 / (ADCCLK / CYCLES)) = Sample Time (�S) */ -#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW - -// Currently analog acquistion hard coded at 480 Hz -// PCKL2 = HCLK / 16 -// ADCCLK = PCLK2 / 2 -#define PIOS_ADC_RATE (72.0e6 / 1.0 / 8.0 / 252.0 / (PIOS_ADC_NUM_CHANNELS >> PIOS_ADC_USE_ADC2)) -#define PIOS_ADC_MAX_OVERSAMPLING 36 - -//------------------------ -// PIOS_RCVR -// See also pios_board.c -//------------------------ -#define PIOS_RCVR_MAX_DEVS 3 -#define PIOS_RCVR_MAX_CHANNELS 12 -#define PIOS_GCSRCVR_TIMEOUT_MS 100 - -//------------------------- -// Receiver PPM input -//------------------------- -#define PIOS_PPM_MAX_DEVS 1 -#define PIOS_PPM_NUM_INPUTS 12 - -//------------------------- -// Receiver PWM input -//------------------------- -#define PIOS_PWM_MAX_DEVS 1 -#define PIOS_PWM_NUM_INPUTS 6 - -//------------------------- -// Receiver DSM input -//------------------------- -#define PIOS_DSM_MAX_DEVS 2 -#define PIOS_DSM_NUM_INPUTS 12 - -//------------------------- -// Receiver S.Bus input -//------------------------- -#define PIOS_SBUS_MAX_DEVS 1 -#define PIOS_SBUS_NUM_INPUTS (16+2) - -//------------------------- -// Servo outputs -//------------------------- -#define PIOS_SERVO_UPDATE_HZ 50 -#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ - -//-------------------------- -// Timer controller settings -//-------------------------- -#define PIOS_TIM_MAX_DEVS 3 - -//------------------------- -// GPIO -//------------------------- -#define PIOS_GPIO_PORTS { } -#define PIOS_GPIO_PINS { } -#define PIOS_GPIO_CLKS { } -#define PIOS_GPIO_NUM 0 - - -//------------------------- -// USB -//------------------------- -#define PIOS_USB_HID_MAX_DEVS 1 - -#define PIOS_USB_ENABLED 1 -#define PIOS_USB_DETECT_GPIO_PORT GPIOC -#define PIOS_USB_MAX_DEVS 1 -#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15 -#endif /* STM32103CB_CC_H_ */ + /** + ****************************************************************************** + * + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef STM32103CB_CC_H_ +#define STM32103CB_CC_H_ + +//------------------------ +// Timers and Channels Used +//------------------------ +/* +Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 +------+-----------+-----------+-----------+---------- +TIM1 | Servo 4 | | | +TIM2 | RC In 5 | RC In 6 | Servo 6 | +TIM3 | Servo 5 | RC In 2 | RC In 3 | RC In 4 +TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1 +------+-----------+-----------+-----------+---------- +*/ + +//------------------------ +// DMA Channels Used +//------------------------ +/* Channel 1 - */ +/* Channel 2 - */ +/* Channel 3 - */ +/* Channel 4 - */ +/* Channel 5 - */ +/* Channel 6 - */ +/* Channel 7 - */ +/* Channel 8 - */ +/* Channel 9 - */ +/* Channel 10 - */ +/* Channel 11 - */ +/* Channel 12 - */ + + +//------------------------ +// BOOTLOADER_SETTINGS +//------------------------ +#define BOARD_READABLE TRUE +#define BOARD_WRITABLE TRUE +#define MAX_DEL_RETRYS 3 + + +//------------------------ +// WATCHDOG_SETTINGS +//------------------------ +#define PIOS_WATCHDOG_TIMEOUT 250 +#define PIOS_WDG_REGISTER BKP_DR4 +#define PIOS_WDG_ACTUATOR 0x0001 +#define PIOS_WDG_STABILIZATION 0x0002 +#define PIOS_WDG_ATTITUDE 0x0004 +#define PIOS_WDG_MANUAL 0x0008 +#define PIOS_WDG_AUTOTUNE 0x0010 + +//------------------------ +// TELEMETRY +//------------------------ +#define TELEM_QUEUE_SIZE 20 + +//------------------------ +// PIOS_LED +//------------------------ +#define PIOS_LED_HEARTBEAT 0 + +//------------------------- +// System Settings +//------------------------- +#define PIOS_MASTER_CLOCK 72000000 +#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) + +//------------------------- +// Interrupt Priorities +//------------------------- +#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS +#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS +#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... +#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... + +//------------------------ +// PIOS_I2C +// See also pios_board.c +//------------------------ +#define PIOS_I2C_MAX_DEVS 1 +extern uint32_t pios_i2c_flexi_adapter_id; +#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexi_adapter_id) +#define PIOS_I2C_ESC_ADAPTER (pios_i2c_flexi_adapter_id) +#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_flexi_adapter_id) + +//------------------------ +// PIOS_BMP085 +//------------------------ +#define PIOS_BMP085_OVERSAMPLING 3 + +//------------------------- +// SPI +// +// See also pios_board.c +//------------------------- +#define PIOS_SPI_MAX_DEVS 2 + +//------------------------- +// PIOS_USART +//------------------------- +#define PIOS_USART_MAX_DEVS 2 + +//------------------------- +// PIOS_COM +// +// See also pios_board.c +//------------------------- +#define PIOS_COM_MAX_DEVS 3 + +extern uint32_t pios_com_telem_rf_id; +#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) + +#if defined(PIOS_INCLUDE_GPS) +extern uint32_t pios_com_gps_id; +#define PIOS_COM_GPS (pios_com_gps_id) +#endif /* PIOS_INCLUDE_GPS */ + +extern uint32_t pios_com_bridge_id; +#define PIOS_COM_BRIDGE (pios_com_bridge_id) + +extern uint32_t pios_com_vcp_id; +#define PIOS_COM_VCP (pios_com_vcp_id) + +extern uint32_t pios_com_telem_usb_id; +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) + +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) +extern uint32_t pios_com_debug_id; +#define PIOS_COM_DEBUG (pios_com_debug_id) +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + +extern uint32_t pios_com_hkosd_id; +#define PIOS_COM_OSDHK (pios_com_hkosd_id) + + +//------------------------- +// ADC +// PIOS_ADC_PinGet(0) = Gyro Z +// PIOS_ADC_PinGet(1) = Gyro Y +// PIOS_ADC_PinGet(2) = Gyro X +//------------------------- +//#define PIOS_ADC_OVERSAMPLING_RATE 1 +#define PIOS_ADC_USE_TEMP_SENSOR 1 +#define PIOS_ADC_TEMP_SENSOR_ADC ADC1 +#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1 + +#define PIOS_ADC_PIN1_GPIO_PORT GPIOA // PA4 (Gyro X) +#define PIOS_ADC_PIN1_GPIO_PIN GPIO_Pin_4 // ADC12_IN4 +#define PIOS_ADC_PIN1_GPIO_CHANNEL ADC_Channel_4 +#define PIOS_ADC_PIN1_ADC ADC2 +#define PIOS_ADC_PIN1_ADC_NUMBER 1 + +#define PIOS_ADC_PIN2_GPIO_PORT GPIOA // PA5 (Gyro Y) +#define PIOS_ADC_PIN2_GPIO_PIN GPIO_Pin_5 // ADC123_IN5 +#define PIOS_ADC_PIN2_GPIO_CHANNEL ADC_Channel_5 +#define PIOS_ADC_PIN2_ADC ADC1 +#define PIOS_ADC_PIN2_ADC_NUMBER 2 + +#define PIOS_ADC_PIN3_GPIO_PORT GPIOA // PA3 (Gyro Z) +#define PIOS_ADC_PIN3_GPIO_PIN GPIO_Pin_3 // ADC12_IN3 +#define PIOS_ADC_PIN3_GPIO_CHANNEL ADC_Channel_3 +#define PIOS_ADC_PIN3_ADC ADC2 +#define PIOS_ADC_PIN3_ADC_NUMBER 2 + +#define PIOS_ADC_NUM_PINS 3 + +#define PIOS_ADC_PORTS { PIOS_ADC_PIN1_GPIO_PORT, PIOS_ADC_PIN2_GPIO_PORT, PIOS_ADC_PIN3_GPIO_PORT } +#define PIOS_ADC_PINS { PIOS_ADC_PIN1_GPIO_PIN, PIOS_ADC_PIN2_GPIO_PIN, PIOS_ADC_PIN3_GPIO_PIN } +#define PIOS_ADC_CHANNELS { PIOS_ADC_PIN1_GPIO_CHANNEL, PIOS_ADC_PIN2_GPIO_CHANNEL, PIOS_ADC_PIN3_GPIO_CHANNEL } +#define PIOS_ADC_MAPPING { PIOS_ADC_PIN1_ADC, PIOS_ADC_PIN2_ADC, PIOS_ADC_PIN3_ADC } +#define PIOS_ADC_CHANNEL_MAPPING { PIOS_ADC_PIN1_ADC_NUMBER, PIOS_ADC_PIN2_ADC_NUMBER, PIOS_ADC_PIN3_ADC_NUMBER } +#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR) +#define PIOS_ADC_NUM_ADC_CHANNELS 2 +#define PIOS_ADC_USE_ADC2 1 +#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE) +#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8 +/* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */ +/* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */ +/* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */ +/* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */ +#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5 +/* Sample time: */ +/* With an ADCCLK = 14 MHz and a sampling time of 239.5 cycles: */ +/* Tconv = 239.5 + 12.5 = 252 cycles = 18�s */ +/* (1 / (ADCCLK / CYCLES)) = Sample Time (�S) */ +#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW + +// Currently analog acquistion hard coded at 480 Hz +// PCKL2 = HCLK / 16 +// ADCCLK = PCLK2 / 2 +#define PIOS_ADC_RATE (72.0e6 / 1.0 / 8.0 / 252.0 / (PIOS_ADC_NUM_CHANNELS >> PIOS_ADC_USE_ADC2)) +#define PIOS_ADC_MAX_OVERSAMPLING 36 + +//------------------------ +// PIOS_RCVR +// See also pios_board.c +//------------------------ +#define PIOS_RCVR_MAX_DEVS 3 +#define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_GCSRCVR_TIMEOUT_MS 100 + +//------------------------- +// Receiver PPM input +//------------------------- +#define PIOS_PPM_MAX_DEVS 1 +#define PIOS_PPM_NUM_INPUTS 12 + +//------------------------- +// Receiver PWM input +//------------------------- +#define PIOS_PWM_MAX_DEVS 1 +#define PIOS_PWM_NUM_INPUTS 6 + +//------------------------- +// Receiver DSM input +//------------------------- +#define PIOS_DSM_MAX_DEVS 2 +#define PIOS_DSM_NUM_INPUTS 12 + +//------------------------- +// Receiver S.Bus input +//------------------------- +#define PIOS_SBUS_MAX_DEVS 1 +#define PIOS_SBUS_NUM_INPUTS (16+2) + +//------------------------- +// Servo outputs +//------------------------- +#define PIOS_SERVO_UPDATE_HZ 50 +#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ + +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 3 + +//------------------------- +// GPIO +//------------------------- +#define PIOS_GPIO_PORTS { } +#define PIOS_GPIO_PINS { } +#define PIOS_GPIO_CLKS { } +#define PIOS_GPIO_NUM 0 + + +//------------------------- +// USB +//------------------------- +#define PIOS_USB_HID_MAX_DEVS 1 + +#define PIOS_USB_ENABLED 1 +#define PIOS_USB_DETECT_GPIO_PORT GPIOC +#define PIOS_USB_MAX_DEVS 1 +#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15 +#endif /* STM32103CB_CC_H_ */ diff --git a/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h b/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h index d2a901bfb..2d3588ec4 100755 --- a/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h @@ -1,314 +1,314 @@ - /** - ****************************************************************************** - * - * @file pios_board.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef STM32103CB_PIPXTREME_H_ -#define STM32103CB_PIPXTREME_H_ - -#define ADD_ONE_ADC - -//------------------------ -// Timers and Channels Used -//------------------------ -/* -Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 -------+-----------+-----------+-----------+---------- -TIM1 | Servo 4 | | | -TIM2 | RC In 5 | RC In 6 | Servo 6 | -TIM3 | Servo 5 | RC In 2 | RC In 3 | RC In 4 -TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1 -------+-----------+-----------+-----------+---------- -*/ - -//------------------------ -// DMA Channels Used -//------------------------ -/* Channel 1 - */ -/* Channel 2 - */ -/* Channel 3 - */ -/* Channel 4 - */ -/* Channel 5 - */ -/* Channel 6 - */ -/* Channel 7 - */ -/* Channel 8 - */ -/* Channel 9 - */ -/* Channel 10 - */ -/* Channel 11 - */ -/* Channel 12 - */ - - -//------------------------ -// BOOTLOADER_SETTINGS -//------------------------ -#define BOARD_READABLE TRUE -#define BOARD_WRITABLE TRUE -#define MAX_DEL_RETRYS 3 - - -//------------------------ -// WATCHDOG_SETTINGS -//------------------------ -#define PIOS_WATCHDOG_TIMEOUT 500 -#define PIOS_WDG_REGISTER BKP_DR4 -#define PIOS_WDG_TELEMETRY 0x0001 -#define PIOS_WDG_RADIORX 0x0002 -#define PIOS_WDG_RADIOTX 0x0004 -#define PIOS_WDG_RFM22B 0x0008 - -//------------------------ -// TELEMETRY -//------------------------ -#define TELEM_QUEUE_SIZE 20 - -//------------------------ -// PIOS_LED -//------------------------ -#define PIOS_LED_USB 0 -#define PIOS_LED_LINK 1 -#define PIOS_LED_RX 2 -#define PIOS_LED_TX 3 -#ifdef PIOS_RFM22B_DEBUG_ON_TELEM -#define PIOS_LED_D1 4 -#define PIOS_LED_D2 5 -#define PIOS_LED_D3 6 -#define PIOS_LED_D4 7 -#endif - -#define PIOS_LED_HEARTBEAT PIOS_LED_LINK -#define PIOS_LED_ALARM PIOS_LED_TX - -#define USB_LED_ON PIOS_LED_On(PIOS_LED_USB) -#define USB_LED_OFF PIOS_LED_Off(PIOS_LED_USB) -#define USB_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_USB) - -#define LINK_LED_ON PIOS_LED_On(PIOS_LED_LINK) -#define LINK_LED_OFF PIOS_LED_Off(PIOS_LED_LINK) -#define LINK_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_LINK) - -#define RX_LED_ON PIOS_LED_On(PIOS_LED_RX) -#define RX_LED_OFF PIOS_LED_Off(PIOS_LED_RX) -#define RX_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_RX) - -#define TX_LED_ON PIOS_LED_On(PIOS_LED_TX) -#define TX_LED_OFF PIOS_LED_Off(PIOS_LED_TX) -#define TX_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_TX) - -#ifdef PIOS_RFM22B_DEBUG_ON_TELEM -#define D1_LED_ON PIOS_LED_On(PIOS_LED_D1) -#define D1_LED_OFF PIOS_LED_Off(PIOS_LED_D1) -#define D1_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D1) - -#define D2_LED_ON PIOS_LED_On(PIOS_LED_D2) -#define D2_LED_OFF PIOS_LED_Off(PIOS_LED_D2) -#define D2_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D2) - -#define D3_LED_ON PIOS_LED_On(PIOS_LED_D3) -#define D3_LED_OFF PIOS_LED_Off(PIOS_LED_D3) -#define D3_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D3) - -#define D4_LED_ON PIOS_LED_On(PIOS_LED_D4) -#define D4_LED_OFF PIOS_LED_Off(PIOS_LED_D4) -#define D4_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D4) -#endif - -//------------------------- -// System Settings -//------------------------- -#define PIOS_MASTER_CLOCK 72000000 -#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) - -//------------------------- -// Interrupt Priorities -//------------------------- -#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS -#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS -#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... -#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... - -//------------------------ -// PIOS_I2C -// See also pios_board.c -//------------------------ -#define PIOS_I2C_MAX_DEVS 1 -extern uint32_t pios_i2c_flexi_adapter_id; -#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexi_adapter_id) - -//------------------------ -// PIOS_SPI -// See also pios_board.c -//------------------------ -#define PIOS_SPI_MAX_DEVS 1 - -//------------------------- -// PIOS_USART -//------------------------- -#define PIOS_USART_MAX_DEVS 3 - -//------------------------- -// PIOS_COM -// -// See also pios_board.c -//------------------------- -#define PIOS_COM_MAX_DEVS 5 - -extern uint32_t pios_com_telem_usb_id; -extern uint32_t pios_com_telem_vcp_id; -extern uint32_t pios_com_telem_uart_telem_id; -extern uint32_t pios_com_telem_uart_flexi_id; -extern uint32_t pios_com_telemetry_id; -extern uint32_t pios_com_rfm22b_id; -extern uint32_t pios_com_radio_id; -extern uint32_t pios_ppm_rcvr_id; -extern uint32_t pios_ppm_out_id; -#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#define PIOS_COM_TELEM_VCP (pios_com_telem_vcp_id) -#define PIOS_COM_TELEM_UART_FLEXI (pios_com_telem_uart_flexi_id) -#define PIOS_COM_TELEM_UART_TELEM (pios_com_telem_uart_telem_id) -#define PIOS_COM_TELEMETRY (pios_com_telemetry_id) -#define PIOS_COM_RFM22B (pios_com_rfm22b_id) -#define PIOS_COM_RADIO (pios_com_radio_id) -#define PIOS_PPM_RECEIVER (pios_ppm_rcvr_id) -#define PIOS_PPM_OUTPUT (pios_ppm_out_id) - -#define RFM22_DEBUG 1 - -//------------------------- -// ADC -// None -//------------------------- -//#define PIOS_ADC_OVERSAMPLING_RATE 1 -#define PIOS_ADC_USE_TEMP_SENSOR 0 -#define PIOS_ADC_TEMP_SENSOR_ADC ADC1 -#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1 - -#define PIOS_ADC_NUM_PINS 0 - -#define PIOS_ADC_PORTS { } -#define PIOS_ADC_PINS { } -#define PIOS_ADC_CHANNELS { } -#define PIOS_ADC_MAPPING { } -#define PIOS_ADC_CHANNEL_MAPPING { } -#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR) -#define PIOS_ADC_NUM_ADC_CHANNELS 0 -#define PIOS_ADC_USE_ADC2 0 -#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE) -#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8 -/* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */ -/* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */ -/* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */ -/* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */ -#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5 -/* Sample time: */ -/* With an ADCCLK = 14 MHz and a sampling time of 239.5 cycles: */ -/* Tconv = 239.5 + 12.5 = 252 cycles = 18�s */ -/* (1 / (ADCCLK / CYCLES)) = Sample Time (�S) */ -#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW - -// Currently analog acquistion hard coded at 480 Hz -// PCKL2 = HCLK / 16 -// ADCCLK = PCLK2 / 2 -#define PIOS_ADC_RATE (72.0e6 / 1.0 / 8.0 / 252.0 / (PIOS_ADC_NUM_CHANNELS >> PIOS_ADC_USE_ADC2)) -#define PIOS_ADC_MAX_OVERSAMPLING 36 - -//------------------------ -// PIOS_RCVR -// See also pios_board.c -//------------------------ -#define PIOS_RCVR_MAX_DEVS 3 -#define PIOS_RCVR_MAX_CHANNELS 12 -#define PIOS_GCSRCVR_TIMEOUT_MS 100 - -//------------------------- -// Receiver PPM input -//------------------------- -#define PIOS_PPM_MAX_DEVS 1 -#define PIOS_PPM_NUM_INPUTS 8 - -//------------------------- -// Servo outputs -//------------------------- -#define PIOS_SERVO_UPDATE_HZ 50 -#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ - -//-------------------------- -// Timer controller settings -//-------------------------- -#define PIOS_TIM_MAX_DEVS 3 - -//------------------------- -// GPIO -//------------------------- -#define PIOS_GPIO_PORTS { } -#define PIOS_GPIO_PINS { } -#define PIOS_GPIO_CLKS { } -#define PIOS_GPIO_NUM 0 - -//------------------------- -// USB -//------------------------- -#define PIOS_USB_HID_MAX_DEVS 1 -#define PIOS_USB_ENABLED 1 -#define PIOS_USB_HID_MAX_DEVS 1 -#define PIOS_USB_MAX_DEVS 1 -#define PIOS_USB_DETECT_GPIO_PORT GPIOC -#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15 -#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line15 - -//------------------------- -// RFM22 -//------------------------- - -#if defined(PIOS_INCLUDE_RFM22B) -extern uint32_t pios_spi_rfm22b_id; -#define PIOS_RFM22_SPI_PORT (pios_spi_rfm22b_id) -extern uint32_t pios_rfm22b_id; -#endif /* PIOS_INCLUDE_RFM22B */ - -//------------------------- -// Packet Handler -//------------------------- -extern uint32_t pios_packet_handler; -#define PIOS_PACKET_HANDLER (pios_packet_handler) -#define PIOS_PH_MAX_PACKET 255 -#define PIOS_PH_WIN_SIZE 3 -#define PIOS_PH_MAX_CONNECTIONS 1 -#define RS_ECC_NPARITY 4 - -//------------------------- -// Reed-Solomon ECC -//------------------------- - -#define RS_ECC_NPARITY 4 - -//------------------------- -// Flash EEPROM Emulation -//------------------------- - -#define PIOS_FLASH_SIZE 0x20000 -#define PIOS_FLASH_EEPROM_START_ADDR 0x08000000 -#define PIOS_FLASH_PAGE_SIZE 1024 -#define PIOS_FLASH_EEPROM_ADDR (PIOS_FLASH_EEPROM_START_ADDR + PIOS_FLASH_SIZE - PIOS_FLASH_PAGE_SIZE) -#define PIOS_FLASH_EEPROM_LEN PIOS_FLASH_PAGE_SIZE - -#endif /* STM32103CB_PIPXTREME_H_ */ + /** + ****************************************************************************** + * + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef STM32103CB_PIPXTREME_H_ +#define STM32103CB_PIPXTREME_H_ + +#define ADD_ONE_ADC + +//------------------------ +// Timers and Channels Used +//------------------------ +/* +Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 +------+-----------+-----------+-----------+---------- +TIM1 | Servo 4 | | | +TIM2 | RC In 5 | RC In 6 | Servo 6 | +TIM3 | Servo 5 | RC In 2 | RC In 3 | RC In 4 +TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1 +------+-----------+-----------+-----------+---------- +*/ + +//------------------------ +// DMA Channels Used +//------------------------ +/* Channel 1 - */ +/* Channel 2 - */ +/* Channel 3 - */ +/* Channel 4 - */ +/* Channel 5 - */ +/* Channel 6 - */ +/* Channel 7 - */ +/* Channel 8 - */ +/* Channel 9 - */ +/* Channel 10 - */ +/* Channel 11 - */ +/* Channel 12 - */ + + +//------------------------ +// BOOTLOADER_SETTINGS +//------------------------ +#define BOARD_READABLE TRUE +#define BOARD_WRITABLE TRUE +#define MAX_DEL_RETRYS 3 + + +//------------------------ +// WATCHDOG_SETTINGS +//------------------------ +#define PIOS_WATCHDOG_TIMEOUT 500 +#define PIOS_WDG_REGISTER BKP_DR4 +#define PIOS_WDG_TELEMETRY 0x0001 +#define PIOS_WDG_RADIORX 0x0002 +#define PIOS_WDG_RADIOTX 0x0004 +#define PIOS_WDG_RFM22B 0x0008 + +//------------------------ +// TELEMETRY +//------------------------ +#define TELEM_QUEUE_SIZE 20 + +//------------------------ +// PIOS_LED +//------------------------ +#define PIOS_LED_USB 0 +#define PIOS_LED_LINK 1 +#define PIOS_LED_RX 2 +#define PIOS_LED_TX 3 +#ifdef PIOS_RFM22B_DEBUG_ON_TELEM +#define PIOS_LED_D1 4 +#define PIOS_LED_D2 5 +#define PIOS_LED_D3 6 +#define PIOS_LED_D4 7 +#endif + +#define PIOS_LED_HEARTBEAT PIOS_LED_LINK +#define PIOS_LED_ALARM PIOS_LED_TX + +#define USB_LED_ON PIOS_LED_On(PIOS_LED_USB) +#define USB_LED_OFF PIOS_LED_Off(PIOS_LED_USB) +#define USB_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_USB) + +#define LINK_LED_ON PIOS_LED_On(PIOS_LED_LINK) +#define LINK_LED_OFF PIOS_LED_Off(PIOS_LED_LINK) +#define LINK_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_LINK) + +#define RX_LED_ON PIOS_LED_On(PIOS_LED_RX) +#define RX_LED_OFF PIOS_LED_Off(PIOS_LED_RX) +#define RX_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_RX) + +#define TX_LED_ON PIOS_LED_On(PIOS_LED_TX) +#define TX_LED_OFF PIOS_LED_Off(PIOS_LED_TX) +#define TX_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_TX) + +#ifdef PIOS_RFM22B_DEBUG_ON_TELEM +#define D1_LED_ON PIOS_LED_On(PIOS_LED_D1) +#define D1_LED_OFF PIOS_LED_Off(PIOS_LED_D1) +#define D1_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D1) + +#define D2_LED_ON PIOS_LED_On(PIOS_LED_D2) +#define D2_LED_OFF PIOS_LED_Off(PIOS_LED_D2) +#define D2_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D2) + +#define D3_LED_ON PIOS_LED_On(PIOS_LED_D3) +#define D3_LED_OFF PIOS_LED_Off(PIOS_LED_D3) +#define D3_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D3) + +#define D4_LED_ON PIOS_LED_On(PIOS_LED_D4) +#define D4_LED_OFF PIOS_LED_Off(PIOS_LED_D4) +#define D4_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_D4) +#endif + +//------------------------- +// System Settings +//------------------------- +#define PIOS_MASTER_CLOCK 72000000 +#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) + +//------------------------- +// Interrupt Priorities +//------------------------- +#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS +#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS +#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... +#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... + +//------------------------ +// PIOS_I2C +// See also pios_board.c +//------------------------ +#define PIOS_I2C_MAX_DEVS 1 +extern uint32_t pios_i2c_flexi_adapter_id; +#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexi_adapter_id) + +//------------------------ +// PIOS_SPI +// See also pios_board.c +//------------------------ +#define PIOS_SPI_MAX_DEVS 1 + +//------------------------- +// PIOS_USART +//------------------------- +#define PIOS_USART_MAX_DEVS 3 + +//------------------------- +// PIOS_COM +// +// See also pios_board.c +//------------------------- +#define PIOS_COM_MAX_DEVS 5 + +extern uint32_t pios_com_telem_usb_id; +extern uint32_t pios_com_telem_vcp_id; +extern uint32_t pios_com_telem_uart_telem_id; +extern uint32_t pios_com_telem_uart_flexi_id; +extern uint32_t pios_com_telemetry_id; +extern uint32_t pios_com_rfm22b_id; +extern uint32_t pios_com_radio_id; +extern uint32_t pios_ppm_rcvr_id; +extern uint32_t pios_ppm_out_id; +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) +#define PIOS_COM_TELEM_VCP (pios_com_telem_vcp_id) +#define PIOS_COM_TELEM_UART_FLEXI (pios_com_telem_uart_flexi_id) +#define PIOS_COM_TELEM_UART_TELEM (pios_com_telem_uart_telem_id) +#define PIOS_COM_TELEMETRY (pios_com_telemetry_id) +#define PIOS_COM_RFM22B (pios_com_rfm22b_id) +#define PIOS_COM_RADIO (pios_com_radio_id) +#define PIOS_PPM_RECEIVER (pios_ppm_rcvr_id) +#define PIOS_PPM_OUTPUT (pios_ppm_out_id) + +#define RFM22_DEBUG 1 + +//------------------------- +// ADC +// None +//------------------------- +//#define PIOS_ADC_OVERSAMPLING_RATE 1 +#define PIOS_ADC_USE_TEMP_SENSOR 0 +#define PIOS_ADC_TEMP_SENSOR_ADC ADC1 +#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1 + +#define PIOS_ADC_NUM_PINS 0 + +#define PIOS_ADC_PORTS { } +#define PIOS_ADC_PINS { } +#define PIOS_ADC_CHANNELS { } +#define PIOS_ADC_MAPPING { } +#define PIOS_ADC_CHANNEL_MAPPING { } +#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR) +#define PIOS_ADC_NUM_ADC_CHANNELS 0 +#define PIOS_ADC_USE_ADC2 0 +#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE) +#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8 +/* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */ +/* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */ +/* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */ +/* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */ +#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5 +/* Sample time: */ +/* With an ADCCLK = 14 MHz and a sampling time of 239.5 cycles: */ +/* Tconv = 239.5 + 12.5 = 252 cycles = 18�s */ +/* (1 / (ADCCLK / CYCLES)) = Sample Time (�S) */ +#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW + +// Currently analog acquistion hard coded at 480 Hz +// PCKL2 = HCLK / 16 +// ADCCLK = PCLK2 / 2 +#define PIOS_ADC_RATE (72.0e6 / 1.0 / 8.0 / 252.0 / (PIOS_ADC_NUM_CHANNELS >> PIOS_ADC_USE_ADC2)) +#define PIOS_ADC_MAX_OVERSAMPLING 36 + +//------------------------ +// PIOS_RCVR +// See also pios_board.c +//------------------------ +#define PIOS_RCVR_MAX_DEVS 3 +#define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_GCSRCVR_TIMEOUT_MS 100 + +//------------------------- +// Receiver PPM input +//------------------------- +#define PIOS_PPM_MAX_DEVS 1 +#define PIOS_PPM_NUM_INPUTS 8 + +//------------------------- +// Servo outputs +//------------------------- +#define PIOS_SERVO_UPDATE_HZ 50 +#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ + +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 3 + +//------------------------- +// GPIO +//------------------------- +#define PIOS_GPIO_PORTS { } +#define PIOS_GPIO_PINS { } +#define PIOS_GPIO_CLKS { } +#define PIOS_GPIO_NUM 0 + +//------------------------- +// USB +//------------------------- +#define PIOS_USB_HID_MAX_DEVS 1 +#define PIOS_USB_ENABLED 1 +#define PIOS_USB_HID_MAX_DEVS 1 +#define PIOS_USB_MAX_DEVS 1 +#define PIOS_USB_DETECT_GPIO_PORT GPIOC +#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15 +#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line15 + +//------------------------- +// RFM22 +//------------------------- + +#if defined(PIOS_INCLUDE_RFM22B) +extern uint32_t pios_spi_rfm22b_id; +#define PIOS_RFM22_SPI_PORT (pios_spi_rfm22b_id) +extern uint32_t pios_rfm22b_id; +#endif /* PIOS_INCLUDE_RFM22B */ + +//------------------------- +// Packet Handler +//------------------------- +extern uint32_t pios_packet_handler; +#define PIOS_PACKET_HANDLER (pios_packet_handler) +#define PIOS_PH_MAX_PACKET 255 +#define PIOS_PH_WIN_SIZE 3 +#define PIOS_PH_MAX_CONNECTIONS 1 +#define RS_ECC_NPARITY 4 + +//------------------------- +// Reed-Solomon ECC +//------------------------- + +#define RS_ECC_NPARITY 4 + +//------------------------- +// Flash EEPROM Emulation +//------------------------- + +#define PIOS_FLASH_SIZE 0x20000 +#define PIOS_FLASH_EEPROM_START_ADDR 0x08000000 +#define PIOS_FLASH_PAGE_SIZE 1024 +#define PIOS_FLASH_EEPROM_ADDR (PIOS_FLASH_EEPROM_START_ADDR + PIOS_FLASH_SIZE - PIOS_FLASH_PAGE_SIZE) +#define PIOS_FLASH_EEPROM_LEN PIOS_FLASH_PAGE_SIZE + +#endif /* STM32103CB_PIPXTREME_H_ */ diff --git a/flight/PiOS/Boards/STM3210E_OP.h b/flight/PiOS/Boards/STM3210E_OP.h index 5cb6ce591..5ffb75d6e 100644 --- a/flight/PiOS/Boards/STM3210E_OP.h +++ b/flight/PiOS/Boards/STM3210E_OP.h @@ -1,334 +1,334 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file pios_board.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef STM3210E_OP_H_ -#define STM3210E_OP_H_ - - - -//------------------------ -// Timers and Channels Used -//------------------------ -/* -Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 -------+-----------+-----------+-----------+---------- -TIM1 | RC In 3 | RC In 6 | RC In 5 | -TIM2 | --------------- PIOS_DELAY ----------------- -TIM3 | RC In 7 | RC In 8 | RC In 1 | RC In 2 -TIM4 | Servo 1 | Servo 2 | Servo 3 | Servo 4 -TIM5 | RC In 4 | | | -TIM6 | ----------- PIOS_PWM (Supervisor) ---------- -TIM7 | | | | -TIM8 | Servo 5 | Servo 6 | Servo 7 | Servo 8 -------+-----------+-----------+-----------+---------- -*/ - -//------------------------ -// DMA Channels Used -//------------------------ -/* Channel 1 - ADC */ -/* Channel 2 - SPI1 RX */ -/* Channel 3 - SPI1 TX */ -/* Channel 4 - SPI2 RX */ -/* Channel 5 - SPI2 TX */ -/* Channel 6 - */ -/* Channel 7 - */ -/* Channel 8 - */ -/* Channel 9 - */ -/* Channel 10 - */ -/* Channel 11 - */ -/* Channel 12 - */ - -//------------------------ -// BOOTLOADER_SETTINGS -//------------------------ -#define BOARD_READABLE TRUE -#define BOARD_WRITABLE TRUE -#define MAX_DEL_RETRYS 3 - -//------------------------ -// WATCHDOG_SETTINGS -//------------------------ -#define PIOS_WATCHDOG_TIMEOUT 250 -#define PIOS_WDG_REGISTER BKP_DR4 -#define PIOS_WDG_ACTUATOR 0x0001 -#define PIOS_WDG_STABILIZATION 0x0002 -#define PIOS_WDG_AHRS 0x0004 -#define PIOS_WDG_MANUAL 0x0008 - -//------------------------ -// TELEMETRY -//------------------------ -#define TELEM_QUEUE_SIZE 20 -#define PIOS_TELEM_STACK_SIZE 624 - -//------------------------ -// PIOS_LED -//------------------------ -#define PIOS_LED_HEARTBEAT 0 -#define PIOS_LED_ALARM 1 - -//------------------------ -// PIOS_SPI -// See also pios_board.c -//------------------------ -#define PIOS_SPI_MAX_DEVS 2 - -//------------------------ -// PIOS_I2C -// See also pios_board.c -//------------------------ -#define PIOS_I2C_MAX_DEVS 1 -extern uint32_t pios_i2c_main_adapter_id; -#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_main_adapter_id) -#define PIOS_I2C_ESC_ADAPTER (pios_i2c_main_adapter_id) -#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_main_adapter_id) - -//------------------------ -// PIOS_BMP085 -//------------------------ -#define PIOS_BMP085_HAS_GPIOS -#define PIOS_BMP085_EOC_GPIO_PORT GPIOC -#define PIOS_BMP085_EOC_GPIO_PIN GPIO_Pin_15 -#define PIOS_BMP085_EOC_PORT_SOURCE GPIO_PortSourceGPIOC -#define PIOS_BMP085_EOC_PIN_SOURCE GPIO_PinSource15 -#define PIOS_BMP085_EOC_CLK RCC_APB2Periph_GPIOC -#define PIOS_BMP085_EOC_EXTI_LINE EXTI_Line15 -#define PIOS_BMP085_EOC_IRQn EXTI15_10_IRQn -#define PIOS_BMP085_EOC_PRIO PIOS_IRQ_PRIO_LOW -#define PIOS_BMP085_XCLR_GPIO_PORT GPIOC // Not actually connected on OP mainboard -#define PIOS_BMP085_XCLR_GPIO_PIN GPIO_Pin_14 // Not actually connected on OP mainboard -//#define PIOS_BMP085_OVERSAMPLING 2 -#define PIOS_BMP085_OVERSAMPLING 3 - -//------------------------- -// PIOS_USART -// -// See also pios_board.c -//------------------------- -#define PIOS_USART_MAX_DEVS 3 - -//------------------------- -// PIOS_COM -// -// See also pios_board.c -//------------------------- -#define PIOS_COM_MAX_DEVS 4 - -extern uint32_t pios_com_telem_rf_id; -#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) - -extern uint32_t pios_com_gps_id; -#define PIOS_COM_GPS (pios_com_gps_id) - -extern uint32_t pios_com_telem_usb_id; -#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) - -#ifdef PIOS_ENABLE_AUX_UART -extern uint32_t pios_com_aux_id; -#define PIOS_COM_AUX (pios_com_aux_id) -#define PIOS_COM_DEBUG PIOS_COM_AUX -#endif - -//------------------------- -// System Settings -//------------------------- -#define PIOS_MASTER_CLOCK 72000000 -#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) - -//------------------------- -// Interrupt Priorities -//------------------------- -#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS -#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS -#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... -#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... - -//------------------------ -// PIOS_RCVR -// See also pios_board.c -//------------------------ -#define PIOS_RCVR_MAX_DEVS 1 -#define PIOS_RCVR_MAX_CHANNELS 12 - -//------------------------- -// Receiver PPM input -//------------------------- -#define PIOS_PPM_MAX_DEVS 1 -#define PIOS_PPM_NUM_INPUTS 12 - -//------------------------- -// Receiver PWM input -//------------------------- -#define PIOS_PWM_MAX_DEVS 1 -#define PIOS_PWM_NUM_INPUTS 8 - -//------------------------- -// Receiver DSM input -//------------------------- -#define PIOS_DSM_MAX_DEVS 1 -#define PIOS_DSM_NUM_INPUTS 12 - -//------------------------- -// Receiver S.Bus input -//------------------------- -#define PIOS_SBUS_MAX_DEVS 0 -#define PIOS_SBUS_NUM_INPUTS (16+2) - -//------------------------- -// Servo outputs -//------------------------- -#define PIOS_SERVO_UPDATE_HZ 50 -#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ - -//-------------------------- -// Timer controller settings -//-------------------------- -#define PIOS_TIM_MAX_DEVS 3 - -//------------------------- -// ADC -// PIOS_ADC_PinGet(0) = Temperature Sensor (On-board) -// PIOS_ADC_PinGet(1) = Power Sensor (Current) -// PIOS_ADC_PinGet(2) = Power Sensor (Voltage) -// PIOS_ADC_PinGet(3) = On-board 5v Rail Sensor -// PIOS_ADC_PinGet(4) = Auxiliary Input 1 -// PIOS_ADC_PinGet(5) = Auxiliary Input 2 -// PIOS_ADC_PinGet(6) = Auxiliary Input 3 -//------------------------- -//#define PIOS_ADC_OVERSAMPLING_RATE 1 -#define PIOS_ADC_USE_TEMP_SENSOR 1 -#define PIOS_ADC_TEMP_SENSOR_ADC ADC1 -#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1 -#define PIOS_ADC_PIN1_GPIO_PORT GPIOA // PA1 (Power Sense - Voltage) -#define PIOS_ADC_PIN1_GPIO_PIN GPIO_Pin_1 // ADC123_IN1 -#define PIOS_ADC_PIN1_GPIO_CHANNEL ADC_Channel_1 -#define PIOS_ADC_PIN1_ADC ADC1 -#define PIOS_ADC_PIN1_ADC_NUMBER 2 -#define PIOS_ADC_PIN2_GPIO_PORT GPIOC // PC3 (Power Sense - Current) -#define PIOS_ADC_PIN2_GPIO_PIN GPIO_Pin_3 // ADC123_IN13 -#define PIOS_ADC_PIN2_GPIO_CHANNEL ADC_Channel_13 -#define PIOS_ADC_PIN2_ADC ADC2 -#define PIOS_ADC_PIN2_ADC_NUMBER 1 -#define PIOS_ADC_PIN3_GPIO_PORT GPIOC // PC5 (Onboard 5v Sensor) PC5 -#define PIOS_ADC_PIN3_GPIO_PIN GPIO_Pin_5 // ADC12_IN15 -#define PIOS_ADC_PIN3_GPIO_CHANNEL ADC_Channel_15 -#define PIOS_ADC_PIN3_ADC ADC2 -#define PIOS_ADC_PIN3_ADC_NUMBER 2 -#define PIOS_ADC_PIN4_GPIO_PORT GPIOC // PC0 (AUX 1) -#define PIOS_ADC_PIN4_GPIO_PIN GPIO_Pin_0 // ADC123_IN10 -#define PIOS_ADC_PIN4_GPIO_CHANNEL ADC_Channel_10 -#define PIOS_ADC_PIN4_ADC ADC1 -#define PIOS_ADC_PIN4_ADC_NUMBER 3 -#define PIOS_ADC_PIN5_GPIO_PORT GPIOC // PC1 (AUX 2) -#define PIOS_ADC_PIN5_GPIO_PIN GPIO_Pin_1 // ADC123_IN11 -#define PIOS_ADC_PIN5_GPIO_CHANNEL ADC_Channel_11 -#define PIOS_ADC_PIN5_ADC ADC2 -#define PIOS_ADC_PIN5_ADC_NUMBER 3 -#define PIOS_ADC_PIN6_GPIO_PORT GPIOC // PC2 (AUX 3) -#define PIOS_ADC_PIN6_GPIO_PIN GPIO_Pin_2 // ADC123_IN12 -#define PIOS_ADC_PIN6_GPIO_CHANNEL ADC_Channel_12 -#define PIOS_ADC_PIN6_ADC ADC1 -#define PIOS_ADC_PIN6_ADC_NUMBER 4 -#define PIOS_ADC_NUM_PINS 6 -#define PIOS_ADC_PORTS { PIOS_ADC_PIN1_GPIO_PORT, PIOS_ADC_PIN2_GPIO_PORT, PIOS_ADC_PIN3_GPIO_PORT, PIOS_ADC_PIN4_GPIO_PORT, PIOS_ADC_PIN5_GPIO_PORT, PIOS_ADC_PIN6_GPIO_PORT } -#define PIOS_ADC_PINS { PIOS_ADC_PIN1_GPIO_PIN, PIOS_ADC_PIN2_GPIO_PIN, PIOS_ADC_PIN3_GPIO_PIN, PIOS_ADC_PIN4_GPIO_PIN, PIOS_ADC_PIN5_GPIO_PIN, PIOS_ADC_PIN6_GPIO_PIN } -#define PIOS_ADC_CHANNELS { PIOS_ADC_PIN1_GPIO_CHANNEL, PIOS_ADC_PIN2_GPIO_CHANNEL, PIOS_ADC_PIN3_GPIO_CHANNEL, PIOS_ADC_PIN4_GPIO_CHANNEL, PIOS_ADC_PIN5_GPIO_CHANNEL, PIOS_ADC_PIN6_GPIO_CHANNEL } -#define PIOS_ADC_MAPPING { PIOS_ADC_PIN1_ADC, PIOS_ADC_PIN2_ADC, PIOS_ADC_PIN3_ADC, PIOS_ADC_PIN4_ADC, PIOS_ADC_PIN5_ADC, PIOS_ADC_PIN6_ADC } -#define PIOS_ADC_CHANNEL_MAPPING { PIOS_ADC_PIN1_ADC_NUMBER, PIOS_ADC_PIN2_ADC_NUMBER, PIOS_ADC_PIN3_ADC_NUMBER, PIOS_ADC_PIN4_ADC_NUMBER, PIOS_ADC_PIN5_ADC_NUMBER, PIOS_ADC_PIN6_ADC_NUMBER } -#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR) -#define PIOS_ADC_NUM_ADC_CHANNELS 2 -#define PIOS_ADC_USE_ADC2 1 -#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE) -#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8 - /* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */ - /* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */ - /* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */ - /* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */ -#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5 - /* Sample time: */ - /* With an ADCCLK = 14 MHz and a sampling time of 293.5 cycles: */ - /* Tconv = 239.5 + 12.5 = 252 cycles = 18?s */ - /* (1 / (ADCCLK / CYCLES)) = Sample Time (?S) */ -#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW -#define PIOS_ADC_MAX_OVERSAMPLING 10 -#define PIOS_ADC_RATE (72.0e6 / 1 / 8 / 252 / (PIOS_ADC_NUM_ADC_CHANNELS >> PIOS_ADC_USE_ADC2)) - -//------------------------- -// GPIO -//------------------------- -#define PIOS_GPIO_1_PORT GPIOC -#define PIOS_GPIO_1_PIN GPIO_Pin_0 -#define PIOS_GPIO_1_GPIO_CLK RCC_APB2Periph_GPIOC -#define PIOS_GPIO_2_PORT GPIOC -#define PIOS_GPIO_2_PIN GPIO_Pin_1 -#define PIOS_GPIO_2_GPIO_CLK RCC_APB2Periph_GPIOC -#define PIOS_GPIO_3_PORT GPIOC -#define PIOS_GPIO_3_PIN GPIO_Pin_2 -#define PIOS_GPIO_3_GPIO_CLK RCC_APB2Periph_GPIOC -#define PIOS_GPIO_4_PORT GPIOD -#define PIOS_GPIO_4_PIN GPIO_Pin_2 -#define PIOS_GPIO_4_GPIO_CLK RCC_APB2Periph_GPIOD -#define PIOS_GPIO_PORTS { PIOS_GPIO_1_PORT, PIOS_GPIO_2_PORT, PIOS_GPIO_3_PORT, PIOS_GPIO_4_PORT } -#define PIOS_GPIO_PINS { PIOS_GPIO_1_PIN, PIOS_GPIO_2_PIN, PIOS_GPIO_3_PIN, PIOS_GPIO_4_PIN } -#define PIOS_GPIO_CLKS { PIOS_GPIO_1_GPIO_CLK, PIOS_GPIO_2_GPIO_CLK, PIOS_GPIO_3_GPIO_CLK, PIOS_GPIO_4_GPIO_CLK } -#define PIOS_GPIO_NUM 4 - -//------------------------- -// USB -//------------------------- -#define PIOS_USB_ENABLED 1 -#define PIOS_USB_DETECT_GPIO_PORT GPIOC -#define PIOS_USB_MAX_DEVS 1 -#define PIOS_USB_HID_MAX_DEVS 1 -#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_4 - -/** - * glue macros for file IO - * STM32 uses DOSFS for file IO - */ -#define PIOS_FOPEN_READ(filename,file) DFS_OpenFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, DFS_READ, PIOS_SDCARD_Sector, &file) != DFS_OK - -#define PIOS_FOPEN_WRITE(filename,file) DFS_OpenFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, DFS_WRITE, PIOS_SDCARD_Sector, &file) != DFS_OK - -#define PIOS_FREAD(file,bufferadr,length,resultadr) DFS_ReadFile(file, PIOS_SDCARD_Sector, (uint8_t*)bufferadr, resultadr, length) != DFS_OK - -#define PIOS_FWRITE(file,bufferadr,length,resultadr) DFS_WriteFile(file, PIOS_SDCARD_Sector, (uint8_t*)bufferadr, resultadr, length) - -#define PIOS_FCLOSE(file) DFS_Close(&file) - -#define PIOS_FUNLINK(filename) DFS_UnlinkFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, PIOS_SDCARD_Sector) - - - -#endif /* STM3210E_OP_H_ */ -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef STM3210E_OP_H_ +#define STM3210E_OP_H_ + + + +//------------------------ +// Timers and Channels Used +//------------------------ +/* +Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 +------+-----------+-----------+-----------+---------- +TIM1 | RC In 3 | RC In 6 | RC In 5 | +TIM2 | --------------- PIOS_DELAY ----------------- +TIM3 | RC In 7 | RC In 8 | RC In 1 | RC In 2 +TIM4 | Servo 1 | Servo 2 | Servo 3 | Servo 4 +TIM5 | RC In 4 | | | +TIM6 | ----------- PIOS_PWM (Supervisor) ---------- +TIM7 | | | | +TIM8 | Servo 5 | Servo 6 | Servo 7 | Servo 8 +------+-----------+-----------+-----------+---------- +*/ + +//------------------------ +// DMA Channels Used +//------------------------ +/* Channel 1 - ADC */ +/* Channel 2 - SPI1 RX */ +/* Channel 3 - SPI1 TX */ +/* Channel 4 - SPI2 RX */ +/* Channel 5 - SPI2 TX */ +/* Channel 6 - */ +/* Channel 7 - */ +/* Channel 8 - */ +/* Channel 9 - */ +/* Channel 10 - */ +/* Channel 11 - */ +/* Channel 12 - */ + +//------------------------ +// BOOTLOADER_SETTINGS +//------------------------ +#define BOARD_READABLE TRUE +#define BOARD_WRITABLE TRUE +#define MAX_DEL_RETRYS 3 + +//------------------------ +// WATCHDOG_SETTINGS +//------------------------ +#define PIOS_WATCHDOG_TIMEOUT 250 +#define PIOS_WDG_REGISTER BKP_DR4 +#define PIOS_WDG_ACTUATOR 0x0001 +#define PIOS_WDG_STABILIZATION 0x0002 +#define PIOS_WDG_AHRS 0x0004 +#define PIOS_WDG_MANUAL 0x0008 + +//------------------------ +// TELEMETRY +//------------------------ +#define TELEM_QUEUE_SIZE 20 +#define PIOS_TELEM_STACK_SIZE 624 + +//------------------------ +// PIOS_LED +//------------------------ +#define PIOS_LED_HEARTBEAT 0 +#define PIOS_LED_ALARM 1 + +//------------------------ +// PIOS_SPI +// See also pios_board.c +//------------------------ +#define PIOS_SPI_MAX_DEVS 2 + +//------------------------ +// PIOS_I2C +// See also pios_board.c +//------------------------ +#define PIOS_I2C_MAX_DEVS 1 +extern uint32_t pios_i2c_main_adapter_id; +#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_main_adapter_id) +#define PIOS_I2C_ESC_ADAPTER (pios_i2c_main_adapter_id) +#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_main_adapter_id) + +//------------------------ +// PIOS_BMP085 +//------------------------ +#define PIOS_BMP085_HAS_GPIOS +#define PIOS_BMP085_EOC_GPIO_PORT GPIOC +#define PIOS_BMP085_EOC_GPIO_PIN GPIO_Pin_15 +#define PIOS_BMP085_EOC_PORT_SOURCE GPIO_PortSourceGPIOC +#define PIOS_BMP085_EOC_PIN_SOURCE GPIO_PinSource15 +#define PIOS_BMP085_EOC_CLK RCC_APB2Periph_GPIOC +#define PIOS_BMP085_EOC_EXTI_LINE EXTI_Line15 +#define PIOS_BMP085_EOC_IRQn EXTI15_10_IRQn +#define PIOS_BMP085_EOC_PRIO PIOS_IRQ_PRIO_LOW +#define PIOS_BMP085_XCLR_GPIO_PORT GPIOC // Not actually connected on OP mainboard +#define PIOS_BMP085_XCLR_GPIO_PIN GPIO_Pin_14 // Not actually connected on OP mainboard +//#define PIOS_BMP085_OVERSAMPLING 2 +#define PIOS_BMP085_OVERSAMPLING 3 + +//------------------------- +// PIOS_USART +// +// See also pios_board.c +//------------------------- +#define PIOS_USART_MAX_DEVS 3 + +//------------------------- +// PIOS_COM +// +// See also pios_board.c +//------------------------- +#define PIOS_COM_MAX_DEVS 4 + +extern uint32_t pios_com_telem_rf_id; +#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) + +extern uint32_t pios_com_gps_id; +#define PIOS_COM_GPS (pios_com_gps_id) + +extern uint32_t pios_com_telem_usb_id; +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) + +#ifdef PIOS_ENABLE_AUX_UART +extern uint32_t pios_com_aux_id; +#define PIOS_COM_AUX (pios_com_aux_id) +#define PIOS_COM_DEBUG PIOS_COM_AUX +#endif + +//------------------------- +// System Settings +//------------------------- +#define PIOS_MASTER_CLOCK 72000000 +#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2) + +//------------------------- +// Interrupt Priorities +//------------------------- +#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS +#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS +#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... +#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... + +//------------------------ +// PIOS_RCVR +// See also pios_board.c +//------------------------ +#define PIOS_RCVR_MAX_DEVS 1 +#define PIOS_RCVR_MAX_CHANNELS 12 + +//------------------------- +// Receiver PPM input +//------------------------- +#define PIOS_PPM_MAX_DEVS 1 +#define PIOS_PPM_NUM_INPUTS 12 + +//------------------------- +// Receiver PWM input +//------------------------- +#define PIOS_PWM_MAX_DEVS 1 +#define PIOS_PWM_NUM_INPUTS 8 + +//------------------------- +// Receiver DSM input +//------------------------- +#define PIOS_DSM_MAX_DEVS 1 +#define PIOS_DSM_NUM_INPUTS 12 + +//------------------------- +// Receiver S.Bus input +//------------------------- +#define PIOS_SBUS_MAX_DEVS 0 +#define PIOS_SBUS_NUM_INPUTS (16+2) + +//------------------------- +// Servo outputs +//------------------------- +#define PIOS_SERVO_UPDATE_HZ 50 +#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ + +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 3 + +//------------------------- +// ADC +// PIOS_ADC_PinGet(0) = Temperature Sensor (On-board) +// PIOS_ADC_PinGet(1) = Power Sensor (Current) +// PIOS_ADC_PinGet(2) = Power Sensor (Voltage) +// PIOS_ADC_PinGet(3) = On-board 5v Rail Sensor +// PIOS_ADC_PinGet(4) = Auxiliary Input 1 +// PIOS_ADC_PinGet(5) = Auxiliary Input 2 +// PIOS_ADC_PinGet(6) = Auxiliary Input 3 +//------------------------- +//#define PIOS_ADC_OVERSAMPLING_RATE 1 +#define PIOS_ADC_USE_TEMP_SENSOR 1 +#define PIOS_ADC_TEMP_SENSOR_ADC ADC1 +#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1 +#define PIOS_ADC_PIN1_GPIO_PORT GPIOA // PA1 (Power Sense - Voltage) +#define PIOS_ADC_PIN1_GPIO_PIN GPIO_Pin_1 // ADC123_IN1 +#define PIOS_ADC_PIN1_GPIO_CHANNEL ADC_Channel_1 +#define PIOS_ADC_PIN1_ADC ADC1 +#define PIOS_ADC_PIN1_ADC_NUMBER 2 +#define PIOS_ADC_PIN2_GPIO_PORT GPIOC // PC3 (Power Sense - Current) +#define PIOS_ADC_PIN2_GPIO_PIN GPIO_Pin_3 // ADC123_IN13 +#define PIOS_ADC_PIN2_GPIO_CHANNEL ADC_Channel_13 +#define PIOS_ADC_PIN2_ADC ADC2 +#define PIOS_ADC_PIN2_ADC_NUMBER 1 +#define PIOS_ADC_PIN3_GPIO_PORT GPIOC // PC5 (Onboard 5v Sensor) PC5 +#define PIOS_ADC_PIN3_GPIO_PIN GPIO_Pin_5 // ADC12_IN15 +#define PIOS_ADC_PIN3_GPIO_CHANNEL ADC_Channel_15 +#define PIOS_ADC_PIN3_ADC ADC2 +#define PIOS_ADC_PIN3_ADC_NUMBER 2 +#define PIOS_ADC_PIN4_GPIO_PORT GPIOC // PC0 (AUX 1) +#define PIOS_ADC_PIN4_GPIO_PIN GPIO_Pin_0 // ADC123_IN10 +#define PIOS_ADC_PIN4_GPIO_CHANNEL ADC_Channel_10 +#define PIOS_ADC_PIN4_ADC ADC1 +#define PIOS_ADC_PIN4_ADC_NUMBER 3 +#define PIOS_ADC_PIN5_GPIO_PORT GPIOC // PC1 (AUX 2) +#define PIOS_ADC_PIN5_GPIO_PIN GPIO_Pin_1 // ADC123_IN11 +#define PIOS_ADC_PIN5_GPIO_CHANNEL ADC_Channel_11 +#define PIOS_ADC_PIN5_ADC ADC2 +#define PIOS_ADC_PIN5_ADC_NUMBER 3 +#define PIOS_ADC_PIN6_GPIO_PORT GPIOC // PC2 (AUX 3) +#define PIOS_ADC_PIN6_GPIO_PIN GPIO_Pin_2 // ADC123_IN12 +#define PIOS_ADC_PIN6_GPIO_CHANNEL ADC_Channel_12 +#define PIOS_ADC_PIN6_ADC ADC1 +#define PIOS_ADC_PIN6_ADC_NUMBER 4 +#define PIOS_ADC_NUM_PINS 6 +#define PIOS_ADC_PORTS { PIOS_ADC_PIN1_GPIO_PORT, PIOS_ADC_PIN2_GPIO_PORT, PIOS_ADC_PIN3_GPIO_PORT, PIOS_ADC_PIN4_GPIO_PORT, PIOS_ADC_PIN5_GPIO_PORT, PIOS_ADC_PIN6_GPIO_PORT } +#define PIOS_ADC_PINS { PIOS_ADC_PIN1_GPIO_PIN, PIOS_ADC_PIN2_GPIO_PIN, PIOS_ADC_PIN3_GPIO_PIN, PIOS_ADC_PIN4_GPIO_PIN, PIOS_ADC_PIN5_GPIO_PIN, PIOS_ADC_PIN6_GPIO_PIN } +#define PIOS_ADC_CHANNELS { PIOS_ADC_PIN1_GPIO_CHANNEL, PIOS_ADC_PIN2_GPIO_CHANNEL, PIOS_ADC_PIN3_GPIO_CHANNEL, PIOS_ADC_PIN4_GPIO_CHANNEL, PIOS_ADC_PIN5_GPIO_CHANNEL, PIOS_ADC_PIN6_GPIO_CHANNEL } +#define PIOS_ADC_MAPPING { PIOS_ADC_PIN1_ADC, PIOS_ADC_PIN2_ADC, PIOS_ADC_PIN3_ADC, PIOS_ADC_PIN4_ADC, PIOS_ADC_PIN5_ADC, PIOS_ADC_PIN6_ADC } +#define PIOS_ADC_CHANNEL_MAPPING { PIOS_ADC_PIN1_ADC_NUMBER, PIOS_ADC_PIN2_ADC_NUMBER, PIOS_ADC_PIN3_ADC_NUMBER, PIOS_ADC_PIN4_ADC_NUMBER, PIOS_ADC_PIN5_ADC_NUMBER, PIOS_ADC_PIN6_ADC_NUMBER } +#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR) +#define PIOS_ADC_NUM_ADC_CHANNELS 2 +#define PIOS_ADC_USE_ADC2 1 +#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE) +#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8 + /* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */ + /* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */ + /* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */ + /* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */ +#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5 + /* Sample time: */ + /* With an ADCCLK = 14 MHz and a sampling time of 293.5 cycles: */ + /* Tconv = 239.5 + 12.5 = 252 cycles = 18?s */ + /* (1 / (ADCCLK / CYCLES)) = Sample Time (?S) */ +#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW +#define PIOS_ADC_MAX_OVERSAMPLING 10 +#define PIOS_ADC_RATE (72.0e6 / 1 / 8 / 252 / (PIOS_ADC_NUM_ADC_CHANNELS >> PIOS_ADC_USE_ADC2)) + +//------------------------- +// GPIO +//------------------------- +#define PIOS_GPIO_1_PORT GPIOC +#define PIOS_GPIO_1_PIN GPIO_Pin_0 +#define PIOS_GPIO_1_GPIO_CLK RCC_APB2Periph_GPIOC +#define PIOS_GPIO_2_PORT GPIOC +#define PIOS_GPIO_2_PIN GPIO_Pin_1 +#define PIOS_GPIO_2_GPIO_CLK RCC_APB2Periph_GPIOC +#define PIOS_GPIO_3_PORT GPIOC +#define PIOS_GPIO_3_PIN GPIO_Pin_2 +#define PIOS_GPIO_3_GPIO_CLK RCC_APB2Periph_GPIOC +#define PIOS_GPIO_4_PORT GPIOD +#define PIOS_GPIO_4_PIN GPIO_Pin_2 +#define PIOS_GPIO_4_GPIO_CLK RCC_APB2Periph_GPIOD +#define PIOS_GPIO_PORTS { PIOS_GPIO_1_PORT, PIOS_GPIO_2_PORT, PIOS_GPIO_3_PORT, PIOS_GPIO_4_PORT } +#define PIOS_GPIO_PINS { PIOS_GPIO_1_PIN, PIOS_GPIO_2_PIN, PIOS_GPIO_3_PIN, PIOS_GPIO_4_PIN } +#define PIOS_GPIO_CLKS { PIOS_GPIO_1_GPIO_CLK, PIOS_GPIO_2_GPIO_CLK, PIOS_GPIO_3_GPIO_CLK, PIOS_GPIO_4_GPIO_CLK } +#define PIOS_GPIO_NUM 4 + +//------------------------- +// USB +//------------------------- +#define PIOS_USB_ENABLED 1 +#define PIOS_USB_DETECT_GPIO_PORT GPIOC +#define PIOS_USB_MAX_DEVS 1 +#define PIOS_USB_HID_MAX_DEVS 1 +#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_4 + +/** + * glue macros for file IO + * STM32 uses DOSFS for file IO + */ +#define PIOS_FOPEN_READ(filename,file) DFS_OpenFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, DFS_READ, PIOS_SDCARD_Sector, &file) != DFS_OK + +#define PIOS_FOPEN_WRITE(filename,file) DFS_OpenFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, DFS_WRITE, PIOS_SDCARD_Sector, &file) != DFS_OK + +#define PIOS_FREAD(file,bufferadr,length,resultadr) DFS_ReadFile(file, PIOS_SDCARD_Sector, (uint8_t*)bufferadr, resultadr, length) != DFS_OK + +#define PIOS_FWRITE(file,bufferadr,length,resultadr) DFS_WriteFile(file, PIOS_SDCARD_Sector, (uint8_t*)bufferadr, resultadr, length) + +#define PIOS_FCLOSE(file) DFS_Close(&file) + +#define PIOS_FUNLINK(filename) DFS_UnlinkFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, PIOS_SDCARD_Sector) + + + +#endif /* STM3210E_OP_H_ */ +/** + * @} + * @} + */ diff --git a/flight/PiOS/Boards/STM32F4xx_OSD.h b/flight/PiOS/Boards/STM32F4xx_OSD.h index 2126acb8d..baf17a9c8 100644 --- a/flight/PiOS/Boards/STM32F4xx_OSD.h +++ b/flight/PiOS/Boards/STM32F4xx_OSD.h @@ -1,292 +1,292 @@ - /** - ****************************************************************************** - * - * @file pios_board.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_BOARD_H -#define PIOS_BOARD_H - - -#include - -// ***************************************************************** -// Timers and Channels Used - -/* -Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 -------+------------+------------+------------+------------ -TIM1 | DELAY | -TIM2 | | PPM Output | PPM Input | -TIM3 | TIMER INTERRUPT | -TIM4 | STOPWATCH | -------+------------+------------+------------+------------ -*/ - -//------------------------ -// DMA Channels Used -//------------------------ -/* Channel 1 - */ -/* Channel 2 - */ -/* Channel 3 - */ -/* Channel 4 - */ -/* Channel 5 - */ -/* Channel 6 - */ -/* Channel 7 - */ -/* Channel 8 - */ -/* Channel 9 - */ -/* Channel 10 - */ -/* Channel 11 - */ -/* Channel 12 - */ - -//------------------------ -// BOOTLOADER_SETTINGS -//------------------------ -#define BOARD_READABLE true -#define BOARD_WRITABLE true -#define MAX_DEL_RETRYS 3 - -//------------------------- -// System Settings -// -// See also System_stm32f4xx.c -//------------------------- -//These macros are deprecated -//please use PIOS_PERIPHERAL_APBx_CLOCK According to the table below -//#define PIOS_MASTER_CLOCK -//#define PIOS_PERIPHERAL_CLOCK -//#define PIOS_PERIPHERAL_CLOCK - -#define PIOS_SYSCLK 168000000 -// Peripherals that belongs to APB1 are: -// DAC |PWR |CAN1,2 -// I2C1,2,3 |UART4,5 |USART3,2 -// I2S3Ext |SPI3/I2S3 |SPI2/I2S2 -// I2S2Ext |IWDG |WWDG -// RTC/BKP reg -// TIM2,3,4,5,6,7,12,13,14 - -// Calculated as SYSCLK / APBPresc * (APBPre == 1 ? 1 : 2) -// Default APB1 Prescaler = 4 -#define PIOS_PERIPHERAL_APB1_CLOCK (PIOS_SYSCLK / 2) - -// Peripherals belonging to APB2 -// SDIO |EXTI |SYSCFG |SPI1 -// ADC1,2,3 -// USART1,6 -// TIM1,8,9,10,11 -// -// Default APB2 Prescaler = 2 -// -#define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK - - -//------------------------ -// TELEMETRY -//------------------------ -#define TELEM_QUEUE_SIZE 20 -#define PIOS_TELEM_STACK_SIZE 624 - -// ***************************************************************** -// Interrupt Priorities - -#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS -#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS -#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... -#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... - - -//------------------------ -// WATCHDOG_SETTINGS -//------------------------ -#define PIOS_WATCHDOG_TIMEOUT 250 -#define PIOS_WDG_REGISTER RTC_BKP_DR4 -#define PIOS_WDG_ACTUATOR 0x0001 -#define PIOS_WDG_STABILIZATION 0x0002 -#define PIOS_WDG_ATTITUDE 0x0004 -#define PIOS_WDG_MANUAL 0x0008 - - -// ***************************************************************** -// PIOS_LED -#define PIOS_LED_HEARTBEAT 0 -#define PIOS_LED_ALARM 1 - -// ***************************************************************** -// Delay Timer - -//#define PIOS_DELAY_TIMER TIM2 -//#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE) -#define PIOS_DELAY_TIMER TIM1 -#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE) - -// ***************************************************************** -// Timer interrupt - -/*#define TIMER_INT_TIMER TIM3 -#define TIMER_INT_FUNC TIM3_IRQHandler -#define TIMER_INT_PRIORITY 2 - -// ***************************************************************** -// Stop watch timer - -#define STOPWATCH_TIMER TIM4*/ - -//------------------------ -// PIOS_SPI -// See also pios_board.c -//------------------------ -#define PIOS_SPI_MAX_DEVS 1 -extern uint32_t pios_spi_port_id; -#define PIOS_SPI_PORT (pios_spi_port_id) - -//------------------------- -// PIOS_USART -// -// See also pios_board.c -//------------------------- -#define PIOS_USART_MAX_DEVS 5 - -//------------------------- -// PIOS_COM -// -// See also pios_board.c -//------------------------- -#define PIOS_COM_MAX_DEVS 5 -extern uint32_t pios_com_telem_rf_id; -extern uint32_t pios_com_gps_id; -extern uint32_t pios_com_aux_id; -extern uint32_t pios_com_telem_usb_id; -#define PIOS_COM_AUX (pios_com_aux_id) -#define PIOS_COM_GPS (pios_com_gps_id) -#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) -#define PIOS_COM_DEBUG (PIOS_COM_AUX) -#define PIOS_COM_OSD (pios_com_aux_id) - -//extern uint32_t pios_com_serial_id; -//#define PIOS_COM_SERIAL (pios_com_serial_id) -//#define PIOS_COM_DEBUG PIOS_COM_SERIAL // uncomment this to send debug info out the serial port - -//extern uint32_t pios_com_gps_id; -//#define PIOS_COM_GPS (pios_com_gps_id) - - -#if defined(PIOS_INCLUDE_USB_HID) -extern uint32_t pios_com_telem_usb_id; -#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#endif - -// ***************************************************************** -// ADC - -//------------------------- -// ADC -// PIOS_ADC_PinGet(0) = Current -// PIOS_ADC_PinGet(1) = Voltage -// PIOS_ADC_PinGet(2) = Flight -// PIOS_ADC_PinGet(3) = Temperature sensor -// PIOS_ADC_PinGet(4) = Video -// PIOS_ADC_PinGet(5) = RSSI -// PIOS_ADC_PinGet(6) = VREF -//------------------------- - -#define PIOS_DMA_PIN_CONFIG \ -{ \ -{GPIOC, GPIO_Pin_0, ADC_Channel_10}, \ -{GPIOC, GPIO_Pin_1, ADC_Channel_11}, \ -{GPIOC, GPIO_Pin_2, ADC_Channel_12}, \ -{NULL, 0, ADC_Channel_TempSensor}, /* Temperature sensor */\ -{GPIOC, GPIO_Pin_3, ADC_Channel_13}, \ -{GPIOA, GPIO_Pin_7, ADC_Channel_7}, \ -{NULL, 0, ADC_Channel_Vrefint} /* Voltage reference */\ -} - -/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */ -/* which is annoying because this then determines the rate at which we generate buffer turnover events */ -/* the objective here is to get enough buffer space to support 100Hz averaging rate */ -#define PIOS_ADC_NUM_CHANNELS 7 -#define PIOS_ADC_MAX_OVERSAMPLING 10 -#define PIOS_ADC_USE_ADC2 0 -#define PIOS_ADC_USE_TEMP_SENSOR 1 - -// ***************************************************************** -// USB - -#if defined(PIOS_INCLUDE_USB_HID) - #define PIOS_USB_ENABLED 1 - #define PIOS_USB_DETECT_GPIO_PORT GPIO_IN_2_PORT - #define PIOS_USB_DETECT_GPIO_PIN GPIO_IN_2_PIN - #define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4 - #define PIOS_IRQ_USB_PRIORITY 8 - #define PIOS_USB_RX_BUFFER_SIZE 512 - #define PIOS_USB_TX_BUFFER_SIZE 512 -#endif - - -// ***************************************************************** -//-------------------------- -// Timer controller settings -//-------------------------- -#define PIOS_TIM_MAX_DEVS 6 - -//------------------------- -// USB -//------------------------- -#define PIOS_USB_MAX_DEVS 1 -#define PIOS_USB_ENABLED 1 /* Should remove all references to this */ -#define PIOS_USB_HID_MAX_DEVS 1 - -//------------------------ -// PIOS_I2C -// See also pios_board.c -//------------------------ -#define PIOS_I2C_MAX_DEVS 1 -extern uint32_t pios_i2c_flexiport_adapter_id; -#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexiport_adapter_id) -#define PIOS_I2C_ESC_ADAPTER (pios_i2c_flexiport_adapter_id) -#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_flexiport_adapter_id) - -//------------------------ -// PIOS_BMP085 -//------------------------ -#define PIOS_BMP085_OVERSAMPLING 3 - - -/** - * glue macros for file IO - * STM32 uses DOSFS for file IO - */ -#define PIOS_FOPEN_READ(filename,file) DFS_OpenFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, DFS_READ, PIOS_SDCARD_Sector, &file) != DFS_OK - -#define PIOS_FOPEN_WRITE(filename,file) DFS_OpenFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, DFS_WRITE, PIOS_SDCARD_Sector, &file) != DFS_OK - -#define PIOS_FREAD(file,bufferadr,length,resultadr) DFS_ReadFile(file, PIOS_SDCARD_Sector, (uint8_t*)bufferadr, resultadr, length) != DFS_OK - -#define PIOS_FWRITE(file,bufferadr,length,resultadr) DFS_WriteFile(file, PIOS_SDCARD_Sector, (uint8_t*)bufferadr, resultadr, length) - -#define PIOS_FCLOSE(file) DFS_Close(&file) - -#define PIOS_FUNLINK(filename) DFS_UnlinkFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, PIOS_SDCARD_Sector) - - -#endif /* PIOS_BOARD_H */ + /** + ****************************************************************************** + * + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_BOARD_H +#define PIOS_BOARD_H + + +#include + +// ***************************************************************** +// Timers and Channels Used + +/* +Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 +------+------------+------------+------------+------------ +TIM1 | DELAY | +TIM2 | | PPM Output | PPM Input | +TIM3 | TIMER INTERRUPT | +TIM4 | STOPWATCH | +------+------------+------------+------------+------------ +*/ + +//------------------------ +// DMA Channels Used +//------------------------ +/* Channel 1 - */ +/* Channel 2 - */ +/* Channel 3 - */ +/* Channel 4 - */ +/* Channel 5 - */ +/* Channel 6 - */ +/* Channel 7 - */ +/* Channel 8 - */ +/* Channel 9 - */ +/* Channel 10 - */ +/* Channel 11 - */ +/* Channel 12 - */ + +//------------------------ +// BOOTLOADER_SETTINGS +//------------------------ +#define BOARD_READABLE true +#define BOARD_WRITABLE true +#define MAX_DEL_RETRYS 3 + +//------------------------- +// System Settings +// +// See also System_stm32f4xx.c +//------------------------- +//These macros are deprecated +//please use PIOS_PERIPHERAL_APBx_CLOCK According to the table below +//#define PIOS_MASTER_CLOCK +//#define PIOS_PERIPHERAL_CLOCK +//#define PIOS_PERIPHERAL_CLOCK + +#define PIOS_SYSCLK 168000000 +// Peripherals that belongs to APB1 are: +// DAC |PWR |CAN1,2 +// I2C1,2,3 |UART4,5 |USART3,2 +// I2S3Ext |SPI3/I2S3 |SPI2/I2S2 +// I2S2Ext |IWDG |WWDG +// RTC/BKP reg +// TIM2,3,4,5,6,7,12,13,14 + +// Calculated as SYSCLK / APBPresc * (APBPre == 1 ? 1 : 2) +// Default APB1 Prescaler = 4 +#define PIOS_PERIPHERAL_APB1_CLOCK (PIOS_SYSCLK / 2) + +// Peripherals belonging to APB2 +// SDIO |EXTI |SYSCFG |SPI1 +// ADC1,2,3 +// USART1,6 +// TIM1,8,9,10,11 +// +// Default APB2 Prescaler = 2 +// +#define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK + + +//------------------------ +// TELEMETRY +//------------------------ +#define TELEM_QUEUE_SIZE 20 +#define PIOS_TELEM_STACK_SIZE 624 + +// ***************************************************************** +// Interrupt Priorities + +#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS +#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS +#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... +#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... + + +//------------------------ +// WATCHDOG_SETTINGS +//------------------------ +#define PIOS_WATCHDOG_TIMEOUT 250 +#define PIOS_WDG_REGISTER RTC_BKP_DR4 +#define PIOS_WDG_ACTUATOR 0x0001 +#define PIOS_WDG_STABILIZATION 0x0002 +#define PIOS_WDG_ATTITUDE 0x0004 +#define PIOS_WDG_MANUAL 0x0008 + + +// ***************************************************************** +// PIOS_LED +#define PIOS_LED_HEARTBEAT 0 +#define PIOS_LED_ALARM 1 + +// ***************************************************************** +// Delay Timer + +//#define PIOS_DELAY_TIMER TIM2 +//#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE) +#define PIOS_DELAY_TIMER TIM1 +#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE) + +// ***************************************************************** +// Timer interrupt + +/*#define TIMER_INT_TIMER TIM3 +#define TIMER_INT_FUNC TIM3_IRQHandler +#define TIMER_INT_PRIORITY 2 + +// ***************************************************************** +// Stop watch timer + +#define STOPWATCH_TIMER TIM4*/ + +//------------------------ +// PIOS_SPI +// See also pios_board.c +//------------------------ +#define PIOS_SPI_MAX_DEVS 1 +extern uint32_t pios_spi_port_id; +#define PIOS_SPI_PORT (pios_spi_port_id) + +//------------------------- +// PIOS_USART +// +// See also pios_board.c +//------------------------- +#define PIOS_USART_MAX_DEVS 5 + +//------------------------- +// PIOS_COM +// +// See also pios_board.c +//------------------------- +#define PIOS_COM_MAX_DEVS 5 +extern uint32_t pios_com_telem_rf_id; +extern uint32_t pios_com_gps_id; +extern uint32_t pios_com_aux_id; +extern uint32_t pios_com_telem_usb_id; +#define PIOS_COM_AUX (pios_com_aux_id) +#define PIOS_COM_GPS (pios_com_gps_id) +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) +#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) +#define PIOS_COM_DEBUG (PIOS_COM_AUX) +#define PIOS_COM_OSD (pios_com_aux_id) + +//extern uint32_t pios_com_serial_id; +//#define PIOS_COM_SERIAL (pios_com_serial_id) +//#define PIOS_COM_DEBUG PIOS_COM_SERIAL // uncomment this to send debug info out the serial port + +//extern uint32_t pios_com_gps_id; +//#define PIOS_COM_GPS (pios_com_gps_id) + + +#if defined(PIOS_INCLUDE_USB_HID) +extern uint32_t pios_com_telem_usb_id; +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) +#endif + +// ***************************************************************** +// ADC + +//------------------------- +// ADC +// PIOS_ADC_PinGet(0) = Current +// PIOS_ADC_PinGet(1) = Voltage +// PIOS_ADC_PinGet(2) = Flight +// PIOS_ADC_PinGet(3) = Temperature sensor +// PIOS_ADC_PinGet(4) = Video +// PIOS_ADC_PinGet(5) = RSSI +// PIOS_ADC_PinGet(6) = VREF +//------------------------- + +#define PIOS_DMA_PIN_CONFIG \ +{ \ +{GPIOC, GPIO_Pin_0, ADC_Channel_10}, \ +{GPIOC, GPIO_Pin_1, ADC_Channel_11}, \ +{GPIOC, GPIO_Pin_2, ADC_Channel_12}, \ +{NULL, 0, ADC_Channel_TempSensor}, /* Temperature sensor */\ +{GPIOC, GPIO_Pin_3, ADC_Channel_13}, \ +{GPIOA, GPIO_Pin_7, ADC_Channel_7}, \ +{NULL, 0, ADC_Channel_Vrefint} /* Voltage reference */\ +} + +/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */ +/* which is annoying because this then determines the rate at which we generate buffer turnover events */ +/* the objective here is to get enough buffer space to support 100Hz averaging rate */ +#define PIOS_ADC_NUM_CHANNELS 7 +#define PIOS_ADC_MAX_OVERSAMPLING 10 +#define PIOS_ADC_USE_ADC2 0 +#define PIOS_ADC_USE_TEMP_SENSOR 1 + +// ***************************************************************** +// USB + +#if defined(PIOS_INCLUDE_USB_HID) + #define PIOS_USB_ENABLED 1 + #define PIOS_USB_DETECT_GPIO_PORT GPIO_IN_2_PORT + #define PIOS_USB_DETECT_GPIO_PIN GPIO_IN_2_PIN + #define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4 + #define PIOS_IRQ_USB_PRIORITY 8 + #define PIOS_USB_RX_BUFFER_SIZE 512 + #define PIOS_USB_TX_BUFFER_SIZE 512 +#endif + + +// ***************************************************************** +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 6 + +//------------------------- +// USB +//------------------------- +#define PIOS_USB_MAX_DEVS 1 +#define PIOS_USB_ENABLED 1 /* Should remove all references to this */ +#define PIOS_USB_HID_MAX_DEVS 1 + +//------------------------ +// PIOS_I2C +// See also pios_board.c +//------------------------ +#define PIOS_I2C_MAX_DEVS 1 +extern uint32_t pios_i2c_flexiport_adapter_id; +#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexiport_adapter_id) +#define PIOS_I2C_ESC_ADAPTER (pios_i2c_flexiport_adapter_id) +#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_flexiport_adapter_id) + +//------------------------ +// PIOS_BMP085 +//------------------------ +#define PIOS_BMP085_OVERSAMPLING 3 + + +/** + * glue macros for file IO + * STM32 uses DOSFS for file IO + */ +#define PIOS_FOPEN_READ(filename,file) DFS_OpenFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, DFS_READ, PIOS_SDCARD_Sector, &file) != DFS_OK + +#define PIOS_FOPEN_WRITE(filename,file) DFS_OpenFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, DFS_WRITE, PIOS_SDCARD_Sector, &file) != DFS_OK + +#define PIOS_FREAD(file,bufferadr,length,resultadr) DFS_ReadFile(file, PIOS_SDCARD_Sector, (uint8_t*)bufferadr, resultadr, length) != DFS_OK + +#define PIOS_FWRITE(file,bufferadr,length,resultadr) DFS_WriteFile(file, PIOS_SDCARD_Sector, (uint8_t*)bufferadr, resultadr, length) + +#define PIOS_FCLOSE(file) DFS_Close(&file) + +#define PIOS_FUNLINK(filename) DFS_UnlinkFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, PIOS_SDCARD_Sector) + + +#endif /* PIOS_BOARD_H */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_f32.c index 958fe541c..2b6bd5389 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_f32.c @@ -1,122 +1,122 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_abs_f32.c -* -* Description: Vector absolute value. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" -#include - -/** - * @ingroup groupMath - */ - -/** - * @defgroup BasicAbs Vector Absolute Value - * - * Computes the absolute value of a vector on an element-by-element basis. - * - *
   
- *     pDst[n] = abs(pSrcA[n]),   0 <= n < blockSize.   
- * 
- * - * The operation can be done in-place by setting the input and output pointers to the same buffer. - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup BasicAbs - * @{ - */ - -/** - * @brief Floating-point vector absolute value. - * @param[in] *pSrc points to the input buffer - * @param[out] *pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - * @return none. - */ - -void arm_abs_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = |A| */ - /* Calculate absolute and then store the results in the destination buffer. */ - *pDst++ = fabsf(*pSrc++); - *pDst++ = fabsf(*pSrc++); - *pDst++ = fabsf(*pSrc++); - *pDst++ = fabsf(*pSrc++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Calculate absolute and then store the results in the destination buffer. */ - *pDst++ = fabsf(*pSrc++); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of BasicAbs group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_abs_f32.c +* +* Description: Vector absolute value. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" +#include + +/** + * @ingroup groupMath + */ + +/** + * @defgroup BasicAbs Vector Absolute Value + * + * Computes the absolute value of a vector on an element-by-element basis. + * + *
   
+ *     pDst[n] = abs(pSrcA[n]),   0 <= n < blockSize.   
+ * 
+ * + * The operation can be done in-place by setting the input and output pointers to the same buffer. + * There are separate functions for floating-point, Q7, Q15, and Q31 data types. + */ + +/** + * @addtogroup BasicAbs + * @{ + */ + +/** + * @brief Floating-point vector absolute value. + * @param[in] *pSrc points to the input buffer + * @param[out] *pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + * @return none. + */ + +void arm_abs_f32( + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = |A| */ + /* Calculate absolute and then store the results in the destination buffer. */ + *pDst++ = fabsf(*pSrc++); + *pDst++ = fabsf(*pSrc++); + *pDst++ = fabsf(*pSrc++); + *pDst++ = fabsf(*pSrc++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = |A| */ + /* Calculate absolute and then store the results in the destination buffer. */ + *pDst++ = fabsf(*pSrc++); + + /* Decrement the loop counter */ + blkCnt--; + } + +} + +/** + * @} end of BasicAbs group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q15.c index 5d346fff3..0a3941bef 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q15.c @@ -1,170 +1,170 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_abs_q15.c -* -* Description: Q15 vector absolute value. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAbs - * @{ - */ - -/** - * @brief Q15 vector absolute value. - * @param[in] *pSrc points to the input buffer - * @param[out] *pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q15 value -1 (0x8000) will be saturated to the maximum allowable positive value 0x7FFF. - */ - -void arm_abs_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t in1; /* Input value1 */ - q15_t in2; /* Input value2 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read two inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - - - /* Store the Absolute result in the destination buffer by packing the two values, in a single cycle */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = - __PKHBT(((in1 > 0) ? in1 : __SSAT(-in1, 16)), - ((in2 > 0) ? in2 : __SSAT(-in2, 16)), 16); - -#else - - - *__SIMD32(pDst)++ = - __PKHBT(((in2 > 0) ? in2 : __SSAT(-in2, 16)), - ((in1 > 0) ? in1 : __SSAT(-in1, 16)), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - in1 = *pSrc++; - in2 = *pSrc++; - - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = - __PKHBT(((in1 > 0) ? in1 : __SSAT(-in1, 16)), - ((in2 > 0) ? in2 : __SSAT(-in2, 16)), 16); - - -#else - - *__SIMD32(pDst)++ = - __PKHBT(((in2 > 0) ? in2 : __SSAT(-in2, 16)), - ((in1 > 0) ? in1 : __SSAT(-in1, 16)), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read the input */ - in1 = *pSrc++; - - /* Calculate absolute value of input and then store the result in the destination buffer. */ - *pDst++ = (in1 > 0) ? in1 : __SSAT(-in1, 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t in; /* Temporary input variable */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read the input */ - in = *pSrc++; - - /* Calculate absolute value of input and then store the result in the destination buffer. */ - *pDst++ = (in > 0) ? in : __SSAT(-in, 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of BasicAbs group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_abs_q15.c +* +* Description: Q15 vector absolute value. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicAbs + * @{ + */ + +/** + * @brief Q15 vector absolute value. + * @param[in] *pSrc points to the input buffer + * @param[out] *pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * The Q15 value -1 (0x8000) will be saturated to the maximum allowable positive value 0x7FFF. + */ + +void arm_abs_q15( + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t in1; /* Input value1 */ + q15_t in2; /* Input value2 */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = |A| */ + /* Read two inputs */ + in1 = *pSrc++; + in2 = *pSrc++; + + + /* Store the Absolute result in the destination buffer by packing the two values, in a single cycle */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = + __PKHBT(((in1 > 0) ? in1 : __SSAT(-in1, 16)), + ((in2 > 0) ? in2 : __SSAT(-in2, 16)), 16); + +#else + + + *__SIMD32(pDst)++ = + __PKHBT(((in2 > 0) ? in2 : __SSAT(-in2, 16)), + ((in1 > 0) ? in1 : __SSAT(-in1, 16)), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + in1 = *pSrc++; + in2 = *pSrc++; + + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = + __PKHBT(((in1 > 0) ? in1 : __SSAT(-in1, 16)), + ((in2 > 0) ? in2 : __SSAT(-in2, 16)), 16); + + +#else + + *__SIMD32(pDst)++ = + __PKHBT(((in2 > 0) ? in2 : __SSAT(-in2, 16)), + ((in1 > 0) ? in1 : __SSAT(-in1, 16)), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = |A| */ + /* Read the input */ + in1 = *pSrc++; + + /* Calculate absolute value of input and then store the result in the destination buffer. */ + *pDst++ = (in1 > 0) ? in1 : __SSAT(-in1, 16); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q15_t in; /* Temporary input variable */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = |A| */ + /* Read the input */ + in = *pSrc++; + + /* Calculate absolute value of input and then store the result in the destination buffer. */ + *pDst++ = (in > 0) ? in : __SSAT(-in, 16); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of BasicAbs group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q31.c index 86a0b55b9..52d7d3d33 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q31.c @@ -1,120 +1,120 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_abs_q31.c -* -* Description: Q31 vector absolute value. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAbs - * @{ - */ - - -/** - * @brief Q31 vector absolute value. - * @param[in] *pSrc points to the input buffer - * @param[out] *pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q31 value -1 (0x80000000) will be saturated to the maximum allowable positive value 0x7FFFFFFF. - */ - -void arm_abs_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - q31_t in; /* Input value */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = |A| */ - /* Calculate absolute of input (if -1 then saturated to 0x7fffffff) and then store the results in the destination buffer. */ - in = *pSrc++; - *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); - in = *pSrc++; - *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); - in = *pSrc++; - *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); - in = *pSrc++; - *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Calculate absolute value of the input (if -1 then saturated to 0x7fffffff) and then store the results in the destination buffer. */ - in = *pSrc++; - *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of BasicAbs group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_abs_q31.c +* +* Description: Q31 vector absolute value. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicAbs + * @{ + */ + + +/** + * @brief Q31 vector absolute value. + * @param[in] *pSrc points to the input buffer + * @param[out] *pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * The Q31 value -1 (0x80000000) will be saturated to the maximum allowable positive value 0x7FFFFFFF. + */ + +void arm_abs_q31( + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + q31_t in; /* Input value */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = |A| */ + /* Calculate absolute of input (if -1 then saturated to 0x7fffffff) and then store the results in the destination buffer. */ + in = *pSrc++; + *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); + in = *pSrc++; + *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); + in = *pSrc++; + *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); + in = *pSrc++; + *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = |A| */ + /* Calculate absolute value of the input (if -1 then saturated to 0x7fffffff) and then store the results in the destination buffer. */ + in = *pSrc++; + *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); + + /* Decrement the loop counter */ + blkCnt--; + } + +} + +/** + * @} end of BasicAbs group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q7.c index f1dd27b34..81019fd90 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_abs_q7.c @@ -1,143 +1,143 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_abs_q7.c -* -* Description: Q7 vector absolute value. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAbs - * @{ - */ - -/** - * @brief Q7 vector absolute value. - * @param[in] *pSrc points to the input buffer - * @param[out] *pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q7 value -1 (0x80) will be saturated to the maximum allowable positive value 0x7F. - */ - -void arm_abs_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q7_t in1; /* Input value1 */ - q7_t in2; /* Input value2 */ - q7_t in3; /* Input value3 */ - q7_t in4; /* Input value4 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read 4 inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - /* Store the Absolute result in the destination buffer by packing the 4 values in single cycle */ - *__SIMD32(pDst)++ = - __PACKq7(((in1 > 0) ? in1 : __SSAT(-in1, 8)), - ((in2 > 0) ? in2 : __SSAT(-in2, 8)), - ((in3 > 0) ? in3 : __SSAT(-in3, 8)), - ((in4 > 0) ? in4 : __SSAT(-in4, 8))); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read the input */ - in1 = *pSrc++; - - /* Store the Absolute result in the destination buffer */ - *pDst++ = (in1 > 0) ? in1 : __SSAT(-in1, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q7_t in; /* Temporary input varible */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read the input */ - in = *pSrc++; - - /* Store the Absolute result in the destination buffer */ - *pDst++ = (in > 0) ? in : __SSAT(-in, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of BasicAbs group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_abs_q7.c +* +* Description: Q7 vector absolute value. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicAbs + * @{ + */ + +/** + * @brief Q7 vector absolute value. + * @param[in] *pSrc points to the input buffer + * @param[out] *pDst points to the output buffer + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * The Q7 value -1 (0x80) will be saturated to the maximum allowable positive value 0x7F. + */ + +void arm_abs_q7( + q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + q7_t in1; /* Input value1 */ + q7_t in2; /* Input value2 */ + q7_t in3; /* Input value3 */ + q7_t in4; /* Input value4 */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = |A| */ + /* Read 4 inputs */ + in1 = *pSrc++; + in2 = *pSrc++; + in3 = *pSrc++; + in4 = *pSrc++; + + /* Store the Absolute result in the destination buffer by packing the 4 values in single cycle */ + *__SIMD32(pDst)++ = + __PACKq7(((in1 > 0) ? in1 : __SSAT(-in1, 8)), + ((in2 > 0) ? in2 : __SSAT(-in2, 8)), + ((in3 > 0) ? in3 : __SSAT(-in3, 8)), + ((in4 > 0) ? in4 : __SSAT(-in4, 8))); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = |A| */ + /* Read the input */ + in1 = *pSrc++; + + /* Store the Absolute result in the destination buffer */ + *pDst++ = (in1 > 0) ? in1 : __SSAT(-in1, 8); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q7_t in; /* Temporary input varible */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = |A| */ + /* Read the input */ + in = *pSrc++; + + /* Store the Absolute result in the destination buffer */ + *pDst++ = (in > 0) ? in : __SSAT(-in, 8); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of BasicAbs group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_f32.c index 1d7c6ad52..d73a6ef68 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_f32.c @@ -1,121 +1,121 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_add_f32.c -* -* Description: Floating-point vector addition. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup BasicAdd Vector Addition - * - * Element-by-element addition of two vectors. - * - *
   
- *     pDst[n] = pSrcA[n] + pSrcB[n],   0 <= n < blockSize.   
- * 
- * - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup BasicAdd - * @{ - */ - -/** - * @brief Floating-point vector addition. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - */ - -void arm_add_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (*pSrcA++) + (*pSrcB++); - *pDst++ = (*pSrcA++) + (*pSrcB++); - *pDst++ = (*pSrcA++) + (*pSrcB++); - *pDst++ = (*pSrcA++) + (*pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (*pSrcA++) + (*pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicAdd group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_add_f32.c +* +* Description: Floating-point vector addition. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @defgroup BasicAdd Vector Addition + * + * Element-by-element addition of two vectors. + * + *
   
+ *     pDst[n] = pSrcA[n] + pSrcB[n],   0 <= n < blockSize.   
+ * 
+ * + * There are separate functions for floating-point, Q7, Q15, and Q31 data types. + */ + +/** + * @addtogroup BasicAdd + * @{ + */ + +/** + * @brief Floating-point vector addition. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + +void arm_add_f32( + float32_t * pSrcA, + float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *pDst++ = (*pSrcA++) + (*pSrcB++); + *pDst++ = (*pSrcA++) + (*pSrcB++); + *pDst++ = (*pSrcA++) + (*pSrcB++); + *pDst++ = (*pSrcA++) + (*pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *pDst++ = (*pSrcA++) + (*pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of BasicAdd group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q15.c index e3a281200..f4ede5325 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q15.c @@ -1,127 +1,127 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_add_q15.c -* -* Description: Q15 vector addition -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAdd - * @{ - */ - -/** - * @brief Q15 vector addition. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -void arm_add_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *__SIMD32(pDst)++ = __QADD16(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); - *__SIMD32(pDst)++ = __QADD16(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (q15_t) __QADD16(*pSrcA++, *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (q15_t) __SSAT(((q31_t) * pSrcA++ + *pSrcB++), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - -} - -/** - * @} end of BasicAdd group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_add_q15.c +* +* Description: Q15 vector addition +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicAdd + * @{ + */ + +/** + * @brief Q15 vector addition. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. + */ + +void arm_add_q15( + q15_t * pSrcA, + q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *__SIMD32(pDst)++ = __QADD16(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); + *__SIMD32(pDst)++ = __QADD16(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *pDst++ = (q15_t) __QADD16(*pSrcA++, *pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *pDst++ = (q15_t) __SSAT(((q31_t) * pSrcA++ + *pSrcB++), 16); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + +} + +/** + * @} end of BasicAdd group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q31.c index 58f99d9a2..e33b9e2fd 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q31.c @@ -1,129 +1,129 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_add_q31.c -* -* Description: Q31 vector addition. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAdd - * @{ - */ - - -/** - * @brief Q31 vector addition. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated. - */ - -void arm_add_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = __QADD(*pSrcA++, *pSrcB++); - *pDst++ = __QADD(*pSrcA++, *pSrcB++); - *pDst++ = __QADD(*pSrcA++, *pSrcB++); - *pDst++ = __QADD(*pSrcA++, *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = __QADD(*pSrcA++, *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (q31_t) clip_q63_to_q31((q63_t) * pSrcA++ + *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of BasicAdd group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_add_q31.c +* +* Description: Q31 vector addition. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicAdd + * @{ + */ + + +/** + * @brief Q31 vector addition. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated. + */ + +void arm_add_q31( + q31_t * pSrcA, + q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *pDst++ = __QADD(*pSrcA++, *pSrcB++); + *pDst++ = __QADD(*pSrcA++, *pSrcB++); + *pDst++ = __QADD(*pSrcA++, *pSrcB++); + *pDst++ = __QADD(*pSrcA++, *pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *pDst++ = __QADD(*pSrcA++, *pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *pDst++ = (q31_t) clip_q63_to_q31((q63_t) * pSrcA++ + *pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of BasicAdd group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q7.c index c6f4f92fb..08199c31b 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_add_q7.c @@ -1,126 +1,126 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_add_q7.c -* -* Description: Q7 vector addition. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAdd - * @{ - */ - -/** - * @brief Q7 vector addition. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. - */ - -void arm_add_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *__SIMD32(pDst)++ = __QADD8(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (q7_t) __SSAT(*pSrcA++ + *pSrcB++, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (q7_t) __SSAT((q15_t) * pSrcA++ + *pSrcB++, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - -} - -/** - * @} end of BasicAdd group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_add_q7.c +* +* Description: Q7 vector addition. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicAdd + * @{ + */ + +/** + * @brief Q7 vector addition. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. + */ + +void arm_add_q7( + q7_t * pSrcA, + q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *__SIMD32(pDst)++ = __QADD8(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *pDst++ = (q7_t) __SSAT(*pSrcA++ + *pSrcB++, 8); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A + B */ + /* Add and then store the results in the destination buffer. */ + *pDst++ = (q7_t) __SSAT((q15_t) * pSrcA++ + *pSrcB++, 8); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + +} + +/** + * @} end of BasicAdd group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_f32.c index ea82aa375..bc7516e5a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_f32.c @@ -1,122 +1,122 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_dot_prod_f32.c -* -* Description: Floating-point dot product. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup dot_prod Vector Dot Product - * - * Computes the dot product of two vectors. - * The vectors are multiplied element-by-element and then summed. - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup dot_prod - * @{ - */ - -/** - * @brief Dot product of floating-point vectors. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] *result output result returned here - * @return none. - */ - - -void arm_dot_prod_f32( - float32_t * pSrcA, - float32_t * pSrcB, - uint32_t blockSize, - float32_t * result) -{ - float32_t sum = 0.0f; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the result in a temporary buffer */ - sum += (*pSrcA++) * (*pSrcB++); - sum += (*pSrcA++) * (*pSrcB++); - sum += (*pSrcA++) * (*pSrcB++); - sum += (*pSrcA++) * (*pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the result in a temporary buffer. */ - sum += (*pSrcA++) * (*pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - /* Store the result back in the destination buffer */ - *result = sum; -} - -/** - * @} end of dot_prod group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_dot_prod_f32.c +* +* Description: Floating-point dot product. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @defgroup dot_prod Vector Dot Product + * + * Computes the dot product of two vectors. + * The vectors are multiplied element-by-element and then summed. + * There are separate functions for floating-point, Q7, Q15, and Q31 data types. + */ + +/** + * @addtogroup dot_prod + * @{ + */ + +/** + * @brief Dot product of floating-point vectors. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] *result output result returned here + * @return none. + */ + + +void arm_dot_prod_f32( + float32_t * pSrcA, + float32_t * pSrcB, + uint32_t blockSize, + float32_t * result) +{ + float32_t sum = 0.0f; /* Temporary result storage */ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Calculate dot product and then store the result in a temporary buffer */ + sum += (*pSrcA++) * (*pSrcB++); + sum += (*pSrcA++) * (*pSrcB++); + sum += (*pSrcA++) * (*pSrcB++); + sum += (*pSrcA++) * (*pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Calculate dot product and then store the result in a temporary buffer. */ + sum += (*pSrcA++) * (*pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + /* Store the result back in the destination buffer */ + *result = sum; +} + +/** + * @} end of dot_prod group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q15.c index 32bfdbc1a..50be68cf9 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q15.c @@ -1,132 +1,132 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_dot_prod_q15.c -* -* Description: Q15 dot product. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup dot_prod - * @{ - */ - -/** - * @brief Dot product of Q15 vectors. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] *result output result returned here - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The intermediate multiplications are in 1.15 x 1.15 = 2.30 format and these - * results are added to a 64-bit accumulator in 34.30 format. - * Nonsaturating additions are used and given that there are 33 guard bits in the accumulator - * there is no risk of overflow. - * The return result is in 34.30 format. - */ - -void arm_dot_prod_q15( - q15_t * pSrcA, - q15_t * pSrcB, - uint32_t blockSize, - q63_t * result) -{ - q63_t sum = 0; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the result in a temporary buffer. */ - sum = __SMLALD(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++, sum); - sum = __SMLALD(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the results in a temporary buffer. */ - sum = __SMLALD(*pSrcA++, *pSrcB++, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the results in a temporary buffer. */ - sum += (q63_t) ((q31_t) * pSrcA++ * *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Store the result in the destination buffer in 34.30 format */ - *result = sum; - -} - -/** - * @} end of dot_prod group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_dot_prod_q15.c +* +* Description: Q15 dot product. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup dot_prod + * @{ + */ + +/** + * @brief Dot product of Q15 vectors. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] *result output result returned here + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The intermediate multiplications are in 1.15 x 1.15 = 2.30 format and these + * results are added to a 64-bit accumulator in 34.30 format. + * Nonsaturating additions are used and given that there are 33 guard bits in the accumulator + * there is no risk of overflow. + * The return result is in 34.30 format. + */ + +void arm_dot_prod_q15( + q15_t * pSrcA, + q15_t * pSrcB, + uint32_t blockSize, + q63_t * result) +{ + q63_t sum = 0; /* Temporary result storage */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Calculate dot product and then store the result in a temporary buffer. */ + sum = __SMLALD(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++, sum); + sum = __SMLALD(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Calculate dot product and then store the results in a temporary buffer. */ + sum = __SMLALD(*pSrcA++, *pSrcB++, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Calculate dot product and then store the results in a temporary buffer. */ + sum += (q63_t) ((q31_t) * pSrcA++ * *pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Store the result in the destination buffer in 34.30 format */ + *result = sum; + +} + +/** + * @} end of dot_prod group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q31.c index eb674c359..eb5f674a7 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q31.c @@ -1,124 +1,124 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_dot_prod_q31.c -* -* Description: Q31 dot product. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup dot_prod - * @{ - */ - -/** - * @brief Dot product of Q31 vectors. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] *result output result returned here - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The intermediate multiplications are in 1.31 x 1.31 = 2.62 format and these - * are truncated to 2.48 format by discarding the lower 14 bits. - * The 2.48 result is then added without saturation to a 64-bit accumulator in 16.48 format. - * There are 15 guard bits in the accumulator and there is no risk of overflow as long as - * the length of the vectors is less than 2^16 elements. - * The return result is in 16.48 format. - */ - -void arm_dot_prod_q31( - q31_t * pSrcA, - q31_t * pSrcB, - uint32_t blockSize, - q63_t * result) -{ - q63_t sum = 0; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the result in a temporary buffer. */ - sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; - sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; - sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; - sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the result in a temporary buffer. */ - sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the result in the destination buffer in 16.48 format */ - *result = sum; -} - -/** - * @} end of dot_prod group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_dot_prod_q31.c +* +* Description: Q31 dot product. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup dot_prod + * @{ + */ + +/** + * @brief Dot product of Q31 vectors. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] *result output result returned here + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The intermediate multiplications are in 1.31 x 1.31 = 2.62 format and these + * are truncated to 2.48 format by discarding the lower 14 bits. + * The 2.48 result is then added without saturation to a 64-bit accumulator in 16.48 format. + * There are 15 guard bits in the accumulator and there is no risk of overflow as long as + * the length of the vectors is less than 2^16 elements. + * The return result is in 16.48 format. + */ + +void arm_dot_prod_q31( + q31_t * pSrcA, + q31_t * pSrcB, + uint32_t blockSize, + q63_t * result) +{ + q63_t sum = 0; /* Temporary result storage */ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Calculate dot product and then store the result in a temporary buffer. */ + sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; + sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; + sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; + sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Calculate dot product and then store the result in a temporary buffer. */ + sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Store the result in the destination buffer in 16.48 format */ + *result = sum; +} + +/** + * @} end of dot_prod group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q7.c index 089273218..cfea032ff 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q7.c @@ -1,163 +1,163 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_dot_prod_q7.c -* -* Description: Q7 dot product. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup dot_prod - * @{ - */ - -/** - * @brief Dot product of Q7 vectors. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] *result output result returned here - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The intermediate multiplications are in 1.7 x 1.7 = 2.14 format and these - * results are added to an accumulator in 18.14 format. - * Nonsaturating additions are used and there is no danger of wrap around as long as - * the vectors are less than 2^18 elements long. - * The return result is in 18.14 format. - */ - -void arm_dot_prod_q7( - q7_t * pSrcA, - q7_t * pSrcB, - uint32_t blockSize, - q31_t * result) -{ - uint32_t blkCnt; /* loop counter */ - - q31_t sum = 0; /* Temporary variables to store output */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t input1, input2; /* Temporary variables to store input */ - q15_t in1, in2; /* Temporary variables to store input */ - - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * pSrcA++; - in2 = (q15_t) * pSrcA++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * pSrcB++; - in2 = (q15_t) * pSrcB++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Perform Dot product of 2 packed inputs using SMLALD and store the result in a temporary variable. */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * pSrcA++; - in2 = (q15_t) * pSrcA++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * pSrcB++; - in2 = (q15_t) * pSrcB++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Perform Dot product of 2 packed inputs using SMLALD and store the result in a temporary variable. */ - sum = __SMLAD(input1, input2, sum); - - - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Dot product and then store the results in a temporary buffer. */ - sum = __SMLAD(*pSrcA++, *pSrcB++, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Dot product and then store the results in a temporary buffer. */ - sum += (q31_t) ((q15_t) * pSrcA++ * *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - - /* Store the result in the destination buffer in 18.14 format */ - *result = sum; -} - -/** - * @} end of dot_prod group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_dot_prod_q7.c +* +* Description: Q7 dot product. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup dot_prod + * @{ + */ + +/** + * @brief Dot product of Q7 vectors. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[in] blockSize number of samples in each vector + * @param[out] *result output result returned here + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The intermediate multiplications are in 1.7 x 1.7 = 2.14 format and these + * results are added to an accumulator in 18.14 format. + * Nonsaturating additions are used and there is no danger of wrap around as long as + * the vectors are less than 2^18 elements long. + * The return result is in 18.14 format. + */ + +void arm_dot_prod_q7( + q7_t * pSrcA, + q7_t * pSrcB, + uint32_t blockSize, + q31_t * result) +{ + uint32_t blkCnt; /* loop counter */ + + q31_t sum = 0; /* Temporary variables to store output */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t input1, input2; /* Temporary variables to store input */ + q15_t in1, in2; /* Temporary variables to store input */ + + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Reading two inputs of SrcA buffer and packing */ + in1 = (q15_t) * pSrcA++; + in2 = (q15_t) * pSrcA++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Reading two inputs of SrcB buffer and packing */ + in1 = (q15_t) * pSrcB++; + in2 = (q15_t) * pSrcB++; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Perform Dot product of 2 packed inputs using SMLALD and store the result in a temporary variable. */ + sum = __SMLAD(input1, input2, sum); + + /* Reading two inputs of SrcA buffer and packing */ + in1 = (q15_t) * pSrcA++; + in2 = (q15_t) * pSrcA++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Reading two inputs of SrcB buffer and packing */ + in1 = (q15_t) * pSrcB++; + in2 = (q15_t) * pSrcB++; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Perform Dot product of 2 packed inputs using SMLALD and store the result in a temporary variable. */ + sum = __SMLAD(input1, input2, sum); + + + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Dot product and then store the results in a temporary buffer. */ + sum = __SMLAD(*pSrcA++, *pSrcB++, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ + /* Dot product and then store the results in a temporary buffer. */ + sum += (q31_t) ((q15_t) * pSrcA++ * *pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + + /* Store the result in the destination buffer in 18.14 format */ + *result = sum; +} + +/** + * @} end of dot_prod group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_f32.c index 7b555638b..5c2dac070 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_f32.c @@ -1,126 +1,126 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mult_f32.c -* -* Description: Floating-point vector multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup BasicMult Vector Multiplication - * - * Element-by-element multiplication of two vectors. - * - *
   
- *     pDst[n] = pSrcA[n] * pSrcB[n],   0 <= n < blockSize.   
- * 
- * - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup BasicMult - * @{ - */ - -/** - * @brief Floating-point vector multiplication. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - */ - -void arm_mult_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counters */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the results in output buffer */ - *pDst++ = (*pSrcA++) * (*pSrcB++); - *pDst++ = (*pSrcA++) * (*pSrcB++); - *pDst++ = (*pSrcA++) * (*pSrcB++); - *pDst++ = (*pSrcA++) * (*pSrcB++); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the results in output buffer */ - *pDst++ = (*pSrcA++) * (*pSrcB++); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - -} - -/** - * @} end of BasicMult group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mult_f32.c +* +* Description: Floating-point vector multiplication. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @defgroup BasicMult Vector Multiplication + * + * Element-by-element multiplication of two vectors. + * + *
   
+ *     pDst[n] = pSrcA[n] * pSrcB[n],   0 <= n < blockSize.   
+ * 
+ * + * There are separate functions for floating-point, Q7, Q15, and Q31 data types. + */ + +/** + * @addtogroup BasicMult + * @{ + */ + +/** + * @brief Floating-point vector multiplication. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + +void arm_mult_f32( + float32_t * pSrcA, + float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counters */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A * B */ + /* Multiply the inputs and store the results in output buffer */ + *pDst++ = (*pSrcA++) * (*pSrcB++); + *pDst++ = (*pSrcA++) * (*pSrcB++); + *pDst++ = (*pSrcA++) * (*pSrcB++); + *pDst++ = (*pSrcA++) * (*pSrcB++); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = A * B */ + /* Multiply the inputs and store the results in output buffer */ + *pDst++ = (*pSrcA++) * (*pSrcB++); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } + +} + +/** + * @} end of BasicMult group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q15.c index e9728f847..76a3843c4 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q15.c @@ -1,119 +1,119 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mult_q15.c -* -* Description: Q15 vector multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicMult - * @{ - */ - - -/** - * @brief Q15 vector multiplication - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -void arm_mult_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counters */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the result in the destination buffer */ - *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); - *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); - *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); - *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the result in the destination buffer */ - *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicMult group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mult_q15.c +* +* Description: Q15 vector multiplication. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicMult + * @{ + */ + + +/** + * @brief Q15 vector multiplication + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. + */ + +void arm_mult_q15( + q15_t * pSrcA, + q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counters */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A * B */ + /* Multiply the inputs and store the result in the destination buffer */ + *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); + *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); + *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); + *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = A * B */ + /* Multiply the inputs and store the result in the destination buffer */ + *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } +} + +/** + * @} end of BasicMult group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q31.c index 8259a129d..c682c1123 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q31.c @@ -1,121 +1,121 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mult_q31.c -* -* Description: Q31 vector multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicMult - * @{ - */ - -/** - * @brief Q31 vector multiplication. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated. - */ - -void arm_mult_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counters */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and then store the results in the destination buffer. */ - *pDst++ = - (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); - *pDst++ = - (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); - *pDst++ = - (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); - *pDst++ = - (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and then store the results in the destination buffer. */ - *pDst++ = - (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicMult group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mult_q31.c +* +* Description: Q31 vector multiplication. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicMult + * @{ + */ + +/** + * @brief Q31 vector multiplication. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated. + */ + +void arm_mult_q31( + q31_t * pSrcA, + q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counters */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + /* loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A * B */ + /* Multiply the inputs and then store the results in the destination buffer. */ + *pDst++ = + (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); + *pDst++ = + (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); + *pDst++ = + (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); + *pDst++ = + (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A * B */ + /* Multiply the inputs and then store the results in the destination buffer. */ + *pDst++ = + (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } +} + +/** + * @} end of BasicMult group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q7.c index 75f075a1f..285fc04af 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_mult_q7.c @@ -1,125 +1,125 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mult_q7.c -* -* Description: Q7 vector multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 DP -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicMult - * @{ - */ - -/** - * @brief Q7 vector multiplication - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. - */ - -void arm_mult_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counters */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q7_t out1, out2, out3, out4; /* Temporary variables to store the product */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the results in temporary variables */ - out1 = (q7_t) (((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7); - out2 = (q7_t) (((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7); - out3 = (q7_t) (((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7); - out4 = (q7_t) (((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7); - - /* Store the results of 4 inputs in the destination buffer in single cycle by packing */ - *__SIMD32(pDst)++ = __PACKq7(out1, out2, out3, out4); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the result in the destination buffer */ - *pDst++ = (q7_t) (((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicMult group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mult_q7.c +* +* Description: Q7 vector multiplication. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 DP +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicMult + * @{ + */ + +/** + * @brief Q7 vector multiplication + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. + */ + +void arm_mult_q7( + q7_t * pSrcA, + q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counters */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + q7_t out1, out2, out3, out4; /* Temporary variables to store the product */ + + /* loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A * B */ + /* Multiply the inputs and store the results in temporary variables */ + out1 = (q7_t) (((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7); + out2 = (q7_t) (((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7); + out3 = (q7_t) (((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7); + out4 = (q7_t) (((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7); + + /* Store the results of 4 inputs in the destination buffer in single cycle by packing */ + *__SIMD32(pDst)++ = __PACKq7(out1, out2, out3, out4); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = A * B */ + /* Multiply the inputs and store the result in the destination buffer */ + *pDst++ = (q7_t) (((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } +} + +/** + * @} end of BasicMult group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_f32.c index 265f50ffd..13deaa919 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_f32.c @@ -1,117 +1,117 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_negate_f32.c -* -* Description: Negates floating-point vectors. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup negate Vector Negate - * - * Negates the elements of a vector. - * - *
   
- *     pDst[n] = -pSrc[n],   0 <= n < blockSize.   
- * 
- */ - -/** - * @addtogroup negate - * @{ - */ - -/** - * @brief Negates the elements of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - */ - -void arm_negate_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the results in the destination buffer. */ - *pDst++ = -*pSrc++; - *pDst++ = -*pSrc++; - *pDst++ = -*pSrc++; - *pDst++ = -*pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the results in the destination buffer. */ - *pDst++ = -*pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of negate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_negate_f32.c +* +* Description: Negates floating-point vectors. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @defgroup negate Vector Negate + * + * Negates the elements of a vector. + * + *
   
+ *     pDst[n] = -pSrc[n],   0 <= n < blockSize.   
+ * 
+ */ + +/** + * @addtogroup negate + * @{ + */ + +/** + * @brief Negates the elements of a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + +void arm_negate_f32( + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = -A */ + /* Negate and then store the results in the destination buffer. */ + *pDst++ = -*pSrc++; + *pDst++ = -*pSrc++; + *pDst++ = -*pSrc++; + *pDst++ = -*pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = -A */ + /* Negate and then store the results in the destination buffer. */ + *pDst++ = -*pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of negate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q15.c index 21122488e..705143191 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q15.c @@ -1,140 +1,140 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_negate_q15.c -* -* Description: Negates Q15 vectors. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup negate - * @{ - */ - -/** - * @brief Negates the elements of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q15 value -1 (0x8000) will be saturated to the maximum allowable positive value 0x7FFF. - */ - -void arm_negate_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t in1, in2; /* Temporary variables */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = -A */ - /* Read two inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - /* Negate and then store the results in the destination buffer by packing. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT(__SSAT(-in1, 16), __SSAT(-in2, 16), 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT(__SSAT(-in2, 16), __SSAT(-in1, 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - in1 = *pSrc++; - in2 = *pSrc++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT(__SSAT(-in1, 16), __SSAT(-in2, 16), 16); - -#else - - - *__SIMD32(pDst)++ = __PKHBT(__SSAT(-in2, 16), __SSAT(-in1, 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the result in the destination buffer. */ - *pDst++ = __SSAT(-*pSrc++, 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of negate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_negate_q15.c +* +* Description: Negates Q15 vectors. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup negate + * @{ + */ + +/** + * @brief Negates the elements of a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * The Q15 value -1 (0x8000) will be saturated to the maximum allowable positive value 0x7FFF. + */ + +void arm_negate_q15( + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t in1, in2; /* Temporary variables */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = -A */ + /* Read two inputs */ + in1 = *pSrc++; + in2 = *pSrc++; + /* Negate and then store the results in the destination buffer by packing. */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = __PKHBT(__SSAT(-in1, 16), __SSAT(-in2, 16), 16); + +#else + + *__SIMD32(pDst)++ = __PKHBT(__SSAT(-in2, 16), __SSAT(-in1, 16), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + in1 = *pSrc++; + in2 = *pSrc++; + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = __PKHBT(__SSAT(-in1, 16), __SSAT(-in2, 16), 16); + +#else + + + *__SIMD32(pDst)++ = __PKHBT(__SSAT(-in2, 16), __SSAT(-in1, 16), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = -A */ + /* Negate and then store the result in the destination buffer. */ + *pDst++ = __SSAT(-*pSrc++, 16); + + /* Decrement the loop counter */ + blkCnt--; + } + +} + +/** + * @} end of negate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q31.c index f7de456e5..c917a84df 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q31.c @@ -1,119 +1,119 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_negate_q31.c -* -* Description: Negates Q31 vectors. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup negate - * @{ - */ - -/** - * @brief Negates the elements of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q31 value -1 (0x80000000) will be saturated to the maximum allowable positive value 0x7FFFFFFF. - */ - -void arm_negate_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t in; /* Temporary variable */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the results in the destination buffer. */ - in = *pSrc++; - *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; - in = *pSrc++; - *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; - in = *pSrc++; - *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; - in = *pSrc++; - *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the result in the destination buffer. */ - in = *pSrc++; - *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of negate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_negate_q31.c +* +* Description: Negates Q31 vectors. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup negate + * @{ + */ + +/** + * @brief Negates the elements of a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * The Q31 value -1 (0x80000000) will be saturated to the maximum allowable positive value 0x7FFFFFFF. + */ + +void arm_negate_q31( + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t in; /* Temporary variable */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = -A */ + /* Negate and then store the results in the destination buffer. */ + in = *pSrc++; + *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; + in = *pSrc++; + *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; + in = *pSrc++; + *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; + in = *pSrc++; + *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = -A */ + /* Negate and then store the result in the destination buffer. */ + in = *pSrc++; + *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of negate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q7.c index 795b047ff..ec991bd45 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_negate_q7.c @@ -1,122 +1,122 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_negate_q7.c -* -* Description: Negates Q7 vectors. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup negate - * @{ - */ - -/** - * @brief Negates the elements of a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q7 value -1 (0x80) will be saturated to the maximum allowable positive value 0x7F. - */ - -void arm_negate_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q7_t in1; /* Input value1 */ - q7_t in2; /* Input value2 */ - q7_t in3; /* Input value3 */ - q7_t in4; /* Input value4 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = -A */ - /* Read four inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - /* Store the Negated results in the destination buffer in a single cycle by packing the results */ - *__SIMD32(pDst)++ = - __PACKq7(__SSAT(-in1, 8), __SSAT(-in2, 8), __SSAT(-in3, 8), - __SSAT(-in4, 8)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the results in the destination buffer. */ - *pDst++ = __SSAT(-*pSrc++, 8); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of negate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_negate_q7.c +* +* Description: Negates Q7 vectors. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup negate + * @{ + */ + +/** + * @brief Negates the elements of a Q7 vector. + * @param[in] *pSrc points to the input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * The Q7 value -1 (0x80) will be saturated to the maximum allowable positive value 0x7F. + */ + +void arm_negate_q7( + q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + q7_t in1; /* Input value1 */ + q7_t in2; /* Input value2 */ + q7_t in3; /* Input value3 */ + q7_t in4; /* Input value4 */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = -A */ + /* Read four inputs */ + in1 = *pSrc++; + in2 = *pSrc++; + in3 = *pSrc++; + in4 = *pSrc++; + + /* Store the Negated results in the destination buffer in a single cycle by packing the results */ + *__SIMD32(pDst)++ = + __PACKq7(__SSAT(-in1, 8), __SSAT(-in2, 8), __SSAT(-in3, 8), + __SSAT(-in4, 8)); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = -A */ + /* Negate and then store the results in the destination buffer. */ + *pDst++ = __SSAT(-*pSrc++, 8); + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of negate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_f32.c index 04ec1fac7..4fcbbbe94 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_f32.c @@ -1,122 +1,122 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_offset_f32.c -* -* Description: Floating-point vector offset. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup offset Vector Offset - * - * Adds a constant offset to each element of a vector. - * - *
   
- *     pDst[n] = pSrc[n] + offset,   0 <= n < blockSize.   
- * 
- * - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup offset - * @{ - */ - -/** - * @brief Adds a constant offset to a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - */ - - -void arm_offset_f32( - float32_t * pSrc, - float32_t offset, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination buffer. */ - *pDst++ = (*pSrc++) + offset; - *pDst++ = (*pSrc++) + offset; - *pDst++ = (*pSrc++) + offset; - *pDst++ = (*pSrc++) + offset; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the result in the destination buffer. */ - *pDst++ = (*pSrc++) + offset; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of offset group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_offset_f32.c +* +* Description: Floating-point vector offset. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @defgroup offset Vector Offset + * + * Adds a constant offset to each element of a vector. + * + *
   
+ *     pDst[n] = pSrc[n] + offset,   0 <= n < blockSize.   
+ * 
+ * + * There are separate functions for floating-point, Q7, Q15, and Q31 data types. + */ + +/** + * @addtogroup offset + * @{ + */ + +/** + * @brief Adds a constant offset to a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + +void arm_offset_f32( + float32_t * pSrc, + float32_t offset, + float32_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the results in the destination buffer. */ + *pDst++ = (*pSrc++) + offset; + *pDst++ = (*pSrc++) + offset; + *pDst++ = (*pSrc++) + offset; + *pDst++ = (*pSrc++) + offset; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the result in the destination buffer. */ + *pDst++ = (*pSrc++) + offset; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of offset group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q15.c index e9106f322..a6eaa86ed 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q15.c @@ -1,128 +1,128 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_offset_q15.c -* -* Description: Q15 vector offset. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup offset - * @{ - */ - -/** - * @brief Adds a constant offset to a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] are saturated. - */ - -void arm_offset_q15( - q15_t * pSrc, - q15_t offset, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t offset_packed; /* Offset packed to 32 bit */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Offset is packed to 32 bit in order to use SIMD32 for addition */ - offset_packed = __PKHBT(offset, offset, 16); - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination buffer, 2 samples at a time. */ - *__SIMD32(pDst)++ = __QADD16(*__SIMD32(pSrc)++, offset_packed); - *__SIMD32(pDst)++ = __QADD16(*__SIMD32(pSrc)++, offset_packed); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination buffer. */ - *pDst++ = (q15_t) __QADD16(*pSrc++, offset); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination buffer. */ - *pDst++ = (q15_t) __SSAT(((q31_t) * pSrc++ + offset), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of offset group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_offset_q15.c +* +* Description: Q15 vector offset. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup offset + * @{ + */ + +/** + * @brief Adds a constant offset to a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q15 range [0x8000 0x7FFF] are saturated. + */ + +void arm_offset_q15( + q15_t * pSrc, + q15_t offset, + q15_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + q31_t offset_packed; /* Offset packed to 32 bit */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Offset is packed to 32 bit in order to use SIMD32 for addition */ + offset_packed = __PKHBT(offset, offset, 16); + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the results in the destination buffer, 2 samples at a time. */ + *__SIMD32(pDst)++ = __QADD16(*__SIMD32(pSrc)++, offset_packed); + *__SIMD32(pDst)++ = __QADD16(*__SIMD32(pSrc)++, offset_packed); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the results in the destination buffer. */ + *pDst++ = (q15_t) __QADD16(*pSrc++, offset); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the results in the destination buffer. */ + *pDst++ = (q15_t) __SSAT(((q31_t) * pSrc++ + offset), 16); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of offset group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q31.c index ff0f6f786..dab3a774f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q31.c @@ -1,126 +1,126 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_offset_q31.c -* -* Description: Q31 vector offset. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup offset - * @{ - */ - -/** - * @brief Adds a constant offset to a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] are saturated. - */ - -void arm_offset_q31( - q31_t * pSrc, - q31_t offset, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination buffer. */ - *pDst++ = __QADD(*pSrc++, offset); - *pDst++ = __QADD(*pSrc++, offset); - *pDst++ = __QADD(*pSrc++, offset); - *pDst++ = __QADD(*pSrc++, offset); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the result in the destination buffer. */ - *pDst++ = __QADD(*pSrc++, offset); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the result in the destination buffer. */ - *pDst++ = (q31_t) clip_q63_to_q31((q63_t) * pSrc++ + offset); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of offset group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_offset_q31.c +* +* Description: Q31 vector offset. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup offset + * @{ + */ + +/** + * @brief Adds a constant offset to a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] are saturated. + */ + +void arm_offset_q31( + q31_t * pSrc, + q31_t offset, + q31_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the results in the destination buffer. */ + *pDst++ = __QADD(*pSrc++, offset); + *pDst++ = __QADD(*pSrc++, offset); + *pDst++ = __QADD(*pSrc++, offset); + *pDst++ = __QADD(*pSrc++, offset); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the result in the destination buffer. */ + *pDst++ = __QADD(*pSrc++, offset); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the result in the destination buffer. */ + *pDst++ = (q31_t) clip_q63_to_q31((q63_t) * pSrc++ + offset); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of offset group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q7.c index 7526648a2..8ed8ddd7f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_offset_q7.c @@ -1,127 +1,127 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_offset_q7.c -* -* Description: Q7 vector offset. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup offset - * @{ - */ - -/** - * @brief Adds a constant offset to a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x80 0x7F] are saturated. - */ - -void arm_offset_q7( - q7_t * pSrc, - q7_t offset, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t offset_packed; /* Offset packed to 32 bit */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Offset is packed to 32 bit in order to use SIMD32 for addition */ - offset_packed = __PACKq7(offset, offset, offset, offset); - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination bufferfor 4 samples at a time. */ - *__SIMD32(pDst)++ = __QADD8(*__SIMD32(pSrc)++, offset_packed); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the result in the destination buffer. */ - *pDst++ = (q7_t) __SSAT(*pSrc++ + offset, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the result in the destination buffer. */ - *pDst++ = (q7_t) __SSAT((q15_t) * pSrc++ + offset, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of offset group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_offset_q7.c +* +* Description: Q7 vector offset. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup offset + * @{ + */ + +/** + * @brief Adds a constant offset to a Q7 vector. + * @param[in] *pSrc points to the input vector + * @param[in] offset is the offset to be added + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q7 range [0x80 0x7F] are saturated. + */ + +void arm_offset_q7( + q7_t * pSrc, + q7_t offset, + q7_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + q31_t offset_packed; /* Offset packed to 32 bit */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Offset is packed to 32 bit in order to use SIMD32 for addition */ + offset_packed = __PACKq7(offset, offset, offset, offset); + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the results in the destination bufferfor 4 samples at a time. */ + *__SIMD32(pDst)++ = __QADD8(*__SIMD32(pSrc)++, offset_packed); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the result in the destination buffer. */ + *pDst++ = (q7_t) __SSAT(*pSrc++ + offset, 8); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A + offset */ + /* Add offset and then store the result in the destination buffer. */ + *pDst++ = (q7_t) __SSAT((q15_t) * pSrc++ + offset, 8); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of offset group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_f32.c index cf516ad7c..f51f78e84 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_f32.c @@ -1,133 +1,133 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_scale_f32.c -* -* Description: Multiplies a floating-point vector by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup scale Vector Scale - * - * Multiply a vector by a scalar value. For floating-point data, the algorithm used is: - * - *
   
- *     pDst[n] = pSrc[n] * scale,   0 <= n < blockSize.   
- * 
- * - * In the fixed-point Q7, Q15, and Q31 functions, scale is represented by - * a fractional multiplication scaleFract and an arithmetic shift shift. - * The shift allows the gain of the scaling operation to exceed 1.0. - * The algorithm used with fixed-point data is: - * - *
   
- *     pDst[n] = (pSrc[n] * scaleFract) << shift,   0 <= n < blockSize.   
- * 
- * - * The overall scale factor applied to the fixed-point data is - *
   
- *     scale = scaleFract * 2^shift.   
- * 
- */ - -/** - * @addtogroup scale - * @{ - */ - -/** - * @brief Multiplies a floating-point vector by a scalar. - * @param[in] *pSrc points to the input vector - * @param[in] scale scale factor to be applied - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - */ - - -void arm_scale_f32( - float32_t * pSrc, - float32_t scale, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the results in the destination buffer. */ - *pDst++ = (*pSrc++) * scale; - *pDst++ = (*pSrc++) * scale; - *pDst++ = (*pSrc++) * scale; - *pDst++ = (*pSrc++) * scale; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = (*pSrc++) * scale; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of scale group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_scale_f32.c +* +* Description: Multiplies a floating-point vector by a scalar. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @defgroup scale Vector Scale + * + * Multiply a vector by a scalar value. For floating-point data, the algorithm used is: + * + *
   
+ *     pDst[n] = pSrc[n] * scale,   0 <= n < blockSize.   
+ * 
+ * + * In the fixed-point Q7, Q15, and Q31 functions, scale is represented by + * a fractional multiplication scaleFract and an arithmetic shift shift. + * The shift allows the gain of the scaling operation to exceed 1.0. + * The algorithm used with fixed-point data is: + * + *
   
+ *     pDst[n] = (pSrc[n] * scaleFract) << shift,   0 <= n < blockSize.   
+ * 
+ * + * The overall scale factor applied to the fixed-point data is + *
   
+ *     scale = scaleFract * 2^shift.   
+ * 
+ */ + +/** + * @addtogroup scale + * @{ + */ + +/** + * @brief Multiplies a floating-point vector by a scalar. + * @param[in] *pSrc points to the input vector + * @param[in] scale scale factor to be applied + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + */ + + +void arm_scale_f32( + float32_t * pSrc, + float32_t scale, + float32_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A * scale */ + /* Scale the input and then store the results in the destination buffer. */ + *pDst++ = (*pSrc++) * scale; + *pDst++ = (*pSrc++) * scale; + *pDst++ = (*pSrc++) * scale; + *pDst++ = (*pSrc++) * scale; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A * scale */ + /* Scale the input and then store the result in the destination buffer. */ + *pDst++ = (*pSrc++) * scale; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of scale group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q15.c index ac3f5bb8f..5e4615f31 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q15.c @@ -1,162 +1,162 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_scale_q15.c -* -* Description: Multiplies a Q15 vector by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup scale - * @{ - */ - -/** - * @brief Multiplies a Q15 vector by a scalar. - * @param[in] *pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The input data *pSrc and scaleFract are in 1.15 format. - * These are multiplied to yield a 2.30 intermediate result and this is shifted with saturation to 1.15 format. - */ - - -void arm_scale_q15( - q15_t * pSrc, - q15_t scaleFract, - int8_t shift, - q15_t * pDst, - uint32_t blockSize) -{ - int8_t kShift = 15 - shift; /* shift to apply after scaling */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t in1, in2; /* Temporary variables */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Reading 2 inputs from memory */ - in1 = *pSrc++; - in2 = *pSrc++; - /* C = A * scale */ - /* Scale the inputs and then store the 2 results in the destination buffer - * in single cycle by packing the outputs */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((in1 * scaleFract) >> kShift, 16), - __SSAT((in2 * scaleFract) >> kShift, 16), 16); - -#else - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((in2 * scaleFract) >> kShift, 16), - __SSAT((in1 * scaleFract) >> kShift, 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - in1 = *pSrc++; - in2 = *pSrc++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((in1 * scaleFract) >> kShift, 16), - __SSAT((in2 * scaleFract) >> kShift, 16), 16); - -#else - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((in2 * scaleFract) >> kShift, 16), - __SSAT((in1 * scaleFract) >> kShift, 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = (q15_t) (__SSAT(((*pSrc++) * scaleFract) >> kShift, 16)); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = (q15_t) (__SSAT(((q31_t) * pSrc++ * scaleFract) >> kShift, 16)); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of scale group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_scale_q15.c +* +* Description: Multiplies a Q15 vector by a scalar. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup scale + * @{ + */ + +/** + * @brief Multiplies a Q15 vector by a scalar. + * @param[in] *pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The input data *pSrc and scaleFract are in 1.15 format. + * These are multiplied to yield a 2.30 intermediate result and this is shifted with saturation to 1.15 format. + */ + + +void arm_scale_q15( + q15_t * pSrc, + q15_t scaleFract, + int8_t shift, + q15_t * pDst, + uint32_t blockSize) +{ + int8_t kShift = 15 - shift; /* shift to apply after scaling */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t in1, in2; /* Temporary variables */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Reading 2 inputs from memory */ + in1 = *pSrc++; + in2 = *pSrc++; + /* C = A * scale */ + /* Scale the inputs and then store the 2 results in the destination buffer + * in single cycle by packing the outputs */ +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = + __PKHBT(__SSAT((in1 * scaleFract) >> kShift, 16), + __SSAT((in2 * scaleFract) >> kShift, 16), 16); + +#else + + *__SIMD32(pDst)++ = + __PKHBT(__SSAT((in2 * scaleFract) >> kShift, 16), + __SSAT((in1 * scaleFract) >> kShift, 16), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + in1 = *pSrc++; + in2 = *pSrc++; + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = + __PKHBT(__SSAT((in1 * scaleFract) >> kShift, 16), + __SSAT((in2 * scaleFract) >> kShift, 16), 16); + +#else + + *__SIMD32(pDst)++ = + __PKHBT(__SSAT((in2 * scaleFract) >> kShift, 16), + __SSAT((in1 * scaleFract) >> kShift, 16), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A * scale */ + /* Scale the input and then store the result in the destination buffer. */ + *pDst++ = (q15_t) (__SSAT(((*pSrc++) * scaleFract) >> kShift, 16)); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A * scale */ + /* Scale the input and then store the result in the destination buffer. */ + *pDst++ = (q15_t) (__SSAT(((q31_t) * pSrc++ * scaleFract) >> kShift, 16)); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of scale group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q31.c index c265eedd7..1b2b7de7f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q31.c @@ -1,117 +1,117 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_scale_q31.c -* -* Description: Multiplies a Q31 vector by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup scale - * @{ - */ - -/** - * @brief Multiplies a Q31 vector by a scalar. - * @param[in] *pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The input data *pSrc and scaleFract are in 1.31 format. - * These are multiplied to yield a 2.62 intermediate result and this is shifted with saturation to 1.31 format. - */ - -void arm_scale_q31( - q31_t * pSrc, - q31_t scaleFract, - int8_t shift, - q31_t * pDst, - uint32_t blockSize) -{ - int8_t kShift = 31 - shift; /* Shift to apply after scaling */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the results in the destination buffer. */ - *pDst++ = clip_q63_to_q31(((q63_t) * pSrc++ * scaleFract) >> kShift); - *pDst++ = clip_q63_to_q31(((q63_t) * pSrc++ * scaleFract) >> kShift); - *pDst++ = clip_q63_to_q31(((q63_t) * pSrc++ * scaleFract) >> kShift); - *pDst++ = clip_q63_to_q31(((q63_t) * pSrc++ * scaleFract) >> kShift); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = clip_q63_to_q31(((q63_t) * pSrc++ * scaleFract) >> kShift); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of scale group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_scale_q31.c +* +* Description: Multiplies a Q31 vector by a scalar. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup scale + * @{ + */ + +/** + * @brief Multiplies a Q31 vector by a scalar. + * @param[in] *pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The input data *pSrc and scaleFract are in 1.31 format. + * These are multiplied to yield a 2.62 intermediate result and this is shifted with saturation to 1.31 format. + */ + +void arm_scale_q31( + q31_t * pSrc, + q31_t scaleFract, + int8_t shift, + q31_t * pDst, + uint32_t blockSize) +{ + int8_t kShift = 31 - shift; /* Shift to apply after scaling */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A * scale */ + /* Scale the input and then store the results in the destination buffer. */ + *pDst++ = clip_q63_to_q31(((q63_t) * pSrc++ * scaleFract) >> kShift); + *pDst++ = clip_q63_to_q31(((q63_t) * pSrc++ * scaleFract) >> kShift); + *pDst++ = clip_q63_to_q31(((q63_t) * pSrc++ * scaleFract) >> kShift); + *pDst++ = clip_q63_to_q31(((q63_t) * pSrc++ * scaleFract) >> kShift); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A * scale */ + /* Scale the input and then store the result in the destination buffer. */ + *pDst++ = clip_q63_to_q31(((q63_t) * pSrc++ * scaleFract) >> kShift); + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of scale group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q7.c index 743d20507..f058b0e9c 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_scale_q7.c @@ -1,141 +1,141 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_scale_q7.c -* -* Description: Multiplies a Q7 vector by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup scale - * @{ - */ - -/** - * @brief Multiplies a Q7 vector by a scalar. - * @param[in] *pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The input data *pSrc and scaleFract are in 1.7 format. - * These are multiplied to yield a 2.14 intermediate result and this is shifted with saturation to 1.7 format. - */ - -void arm_scale_q7( - q7_t * pSrc, - q7_t scaleFract, - int8_t shift, - q7_t * pDst, - uint32_t blockSize) -{ - int8_t kShift = 7 - shift; /* shift to apply after scaling */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q7_t in1, in2, in3, in4, out1, out2, out3, out4; /* Temporary variables to store input & output */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Reading 4 inputs from memory */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - /* C = A * scale */ - /* Scale the inputs and then store the results in the temporary variables. */ - out1 = (q7_t) (__SSAT(((in1) * scaleFract) >> kShift, 8)); - out2 = (q7_t) (__SSAT(((in2) * scaleFract) >> kShift, 8)); - out3 = (q7_t) (__SSAT(((in3) * scaleFract) >> kShift, 8)); - out4 = (q7_t) (__SSAT(((in4) * scaleFract) >> kShift, 8)); - - /* Packing the individual outputs into 32bit and storing in - * destination buffer in single write */ - *__SIMD32(pDst)++ = __PACKq7(out1, out2, out3, out4); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = (q7_t) (__SSAT(((*pSrc++) * scaleFract) >> kShift, 8)); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = (q7_t) (__SSAT((((q15_t) * pSrc++ * scaleFract) >> kShift), 8)); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of scale group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_scale_q7.c +* +* Description: Multiplies a Q7 vector by a scalar. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup scale + * @{ + */ + +/** + * @brief Multiplies a Q7 vector by a scalar. + * @param[in] *pSrc points to the input vector + * @param[in] scaleFract fractional portion of the scale value + * @param[in] shift number of bits to shift the result by + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The input data *pSrc and scaleFract are in 1.7 format. + * These are multiplied to yield a 2.14 intermediate result and this is shifted with saturation to 1.7 format. + */ + +void arm_scale_q7( + q7_t * pSrc, + q7_t scaleFract, + int8_t shift, + q7_t * pDst, + uint32_t blockSize) +{ + int8_t kShift = 7 - shift; /* shift to apply after scaling */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + q7_t in1, in2, in3, in4, out1, out2, out3, out4; /* Temporary variables to store input & output */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Reading 4 inputs from memory */ + in1 = *pSrc++; + in2 = *pSrc++; + in3 = *pSrc++; + in4 = *pSrc++; + + /* C = A * scale */ + /* Scale the inputs and then store the results in the temporary variables. */ + out1 = (q7_t) (__SSAT(((in1) * scaleFract) >> kShift, 8)); + out2 = (q7_t) (__SSAT(((in2) * scaleFract) >> kShift, 8)); + out3 = (q7_t) (__SSAT(((in3) * scaleFract) >> kShift, 8)); + out4 = (q7_t) (__SSAT(((in4) * scaleFract) >> kShift, 8)); + + /* Packing the individual outputs into 32bit and storing in + * destination buffer in single write */ + *__SIMD32(pDst)++ = __PACKq7(out1, out2, out3, out4); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A * scale */ + /* Scale the input and then store the result in the destination buffer. */ + *pDst++ = (q7_t) (__SSAT(((*pSrc++) * scaleFract) >> kShift, 8)); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A * scale */ + /* Scale the input and then store the result in the destination buffer. */ + *pDst++ = (q7_t) (__SSAT((((q15_t) * pSrc++ * scaleFract) >> kShift), 8)); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of scale group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q15.c index 3dc6ac534..70a80c2f7 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q15.c @@ -1,239 +1,239 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_shift_q15.c -* -* Description: Shifts the elements of a Q15 vector by a specified number of bits. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup shift - * @{ - */ - -/** - * @brief Shifts the elements of a Q15 vector a specified number of bits. - * @param[in] *pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -void arm_shift_q15( - q15_t * pSrc, - int8_t shiftBits, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - uint8_t sign; /* Sign of shiftBits */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t in1, in2; /* Temporary variables */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Getting the sign of shiftBits */ - sign = (shiftBits & 0x80); - - /* If the shift value is positive then do right shift else left shift */ - if(sign == 0u) - { - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Read 2 inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - /* C = A << shiftBits */ - /* Shift the inputs and then store the results in the destination buffer. */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT(__SSAT((in1 << shiftBits), 16), - __SSAT((in2 << shiftBits), 16), 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT(__SSAT((in2 << shiftBits), 16), - __SSAT((in1 << shiftBits), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - in1 = *pSrc++; - in2 = *pSrc++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT(__SSAT((in1 << shiftBits), 16), - __SSAT((in2 << shiftBits), 16), 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT(__SSAT((in2 << shiftBits), 16), - __SSAT((in1 << shiftBits), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Shift and then store the results in the destination buffer. */ - *pDst++ = __SSAT((*pSrc++ << shiftBits), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Read 2 inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - /* C = A >> shiftBits */ - /* Shift the inputs and then store the results in the destination buffer. */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT((in1 >> -shiftBits), - (in2 >> -shiftBits), 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT((in2 >> -shiftBits), - (in1 >> -shiftBits), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - in1 = *pSrc++; - in2 = *pSrc++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT((in1 >> -shiftBits), - (in2 >> -shiftBits), 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT((in2 >> -shiftBits), - (in1 >> -shiftBits), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Shift the inputs and then store the results in the destination buffer. */ - *pDst++ = (*pSrc++ >> -shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Getting the sign of shiftBits */ - sign = (shiftBits & 0x80); - - /* If the shift value is positive then do right shift else left shift */ - if(sign == 0u) - { - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Shift and then store the results in the destination buffer. */ - *pDst++ = __SSAT(((q31_t) * pSrc++ << shiftBits), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Shift the inputs and then store the results in the destination buffer. */ - *pDst++ = (*pSrc++ >> -shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of shift group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_shift_q15.c +* +* Description: Shifts the elements of a Q15 vector by a specified number of bits. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup shift + * @{ + */ + +/** + * @brief Shifts the elements of a Q15 vector a specified number of bits. + * @param[in] *pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. + */ + +void arm_shift_q15( + q15_t * pSrc, + int8_t shiftBits, + q15_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + uint8_t sign; /* Sign of shiftBits */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t in1, in2; /* Temporary variables */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Getting the sign of shiftBits */ + sign = (shiftBits & 0x80); + + /* If the shift value is positive then do right shift else left shift */ + if(sign == 0u) + { + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Read 2 inputs */ + in1 = *pSrc++; + in2 = *pSrc++; + /* C = A << shiftBits */ + /* Shift the inputs and then store the results in the destination buffer. */ +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = __PKHBT(__SSAT((in1 << shiftBits), 16), + __SSAT((in2 << shiftBits), 16), 16); + +#else + + *__SIMD32(pDst)++ = __PKHBT(__SSAT((in2 << shiftBits), 16), + __SSAT((in1 << shiftBits), 16), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + in1 = *pSrc++; + in2 = *pSrc++; + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = __PKHBT(__SSAT((in1 << shiftBits), 16), + __SSAT((in2 << shiftBits), 16), 16); + +#else + + *__SIMD32(pDst)++ = __PKHBT(__SSAT((in2 << shiftBits), 16), + __SSAT((in1 << shiftBits), 16), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A << shiftBits */ + /* Shift and then store the results in the destination buffer. */ + *pDst++ = __SSAT((*pSrc++ << shiftBits), 16); + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Read 2 inputs */ + in1 = *pSrc++; + in2 = *pSrc++; + /* C = A >> shiftBits */ + /* Shift the inputs and then store the results in the destination buffer. */ +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = __PKHBT((in1 >> -shiftBits), + (in2 >> -shiftBits), 16); + +#else + + *__SIMD32(pDst)++ = __PKHBT((in2 >> -shiftBits), + (in1 >> -shiftBits), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + in1 = *pSrc++; + in2 = *pSrc++; + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = __PKHBT((in1 >> -shiftBits), + (in2 >> -shiftBits), 16); + +#else + + *__SIMD32(pDst)++ = __PKHBT((in2 >> -shiftBits), + (in1 >> -shiftBits), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A >> shiftBits */ + /* Shift the inputs and then store the results in the destination buffer. */ + *pDst++ = (*pSrc++ >> -shiftBits); + + /* Decrement the loop counter */ + blkCnt--; + } + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Getting the sign of shiftBits */ + sign = (shiftBits & 0x80); + + /* If the shift value is positive then do right shift else left shift */ + if(sign == 0u) + { + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A << shiftBits */ + /* Shift and then store the results in the destination buffer. */ + *pDst++ = __SSAT(((q31_t) * pSrc++ << shiftBits), 16); + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A >> shiftBits */ + /* Shift the inputs and then store the results in the destination buffer. */ + *pDst++ = (*pSrc++ >> -shiftBits); + + /* Decrement the loop counter */ + blkCnt--; + } + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of shift group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q31.c index 8fb989c78..81f45bd1a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q31.c @@ -1,141 +1,141 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_shift_q31.c -* -* Description: Shifts the elements of a Q31 vector by a specified number of bits. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ -/** - * @defgroup shift Vector Shift - * - * Shifts the elements of a fixed-point vector by a specified number of bits. - * There are separate functions for Q7, Q15, and Q31 data types. - * The underlying algorithm used is: - * - *
   
- *     pDst[n] = pSrc[n] << shift,   0 <= n < blockSize.   
- * 
- * - * If shift is positive then the elements of the vector are shifted to the left. - * If shift is negative then the elements of the vector are shifted to the right. - */ - -/** - * @addtogroup shift - * @{ - */ - -/** - * @brief Shifts the elements of a Q31 vector a specified number of bits. - * @param[in] *pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. - */ - -void arm_shift_q31( - q31_t * pSrc, - int8_t shiftBits, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - uint8_t sign; /* Sign of shiftBits */ - /* Getting the sign of shiftBits */ - sign = (shiftBits & 0x80); - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A (>> or <<) shiftBits */ - /* Shift the input and then store the results in the destination buffer. */ - *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : - (*pSrc++ >> -shiftBits); - *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : - (*pSrc++ >> -shiftBits); - *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : - (*pSrc++ >> -shiftBits); - *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : - (*pSrc++ >> -shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A (>> or <<) shiftBits */ - /* Shift the input and then store the result in the destination buffer. */ - *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : - (*pSrc++ >> -shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of shift group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_shift_q31.c +* +* Description: Shifts the elements of a Q31 vector by a specified number of bits. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ +/** + * @defgroup shift Vector Shift + * + * Shifts the elements of a fixed-point vector by a specified number of bits. + * There are separate functions for Q7, Q15, and Q31 data types. + * The underlying algorithm used is: + * + *
   
+ *     pDst[n] = pSrc[n] << shift,   0 <= n < blockSize.   
+ * 
+ * + * If shift is positive then the elements of the vector are shifted to the left. + * If shift is negative then the elements of the vector are shifted to the right. + */ + +/** + * @addtogroup shift + * @{ + */ + +/** + * @brief Shifts the elements of a Q31 vector a specified number of bits. + * @param[in] *pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. + */ + +void arm_shift_q31( + q31_t * pSrc, + int8_t shiftBits, + q31_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + uint8_t sign; /* Sign of shiftBits */ + /* Getting the sign of shiftBits */ + sign = (shiftBits & 0x80); + + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A (>> or <<) shiftBits */ + /* Shift the input and then store the results in the destination buffer. */ + *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : + (*pSrc++ >> -shiftBits); + *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : + (*pSrc++ >> -shiftBits); + *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : + (*pSrc++ >> -shiftBits); + *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : + (*pSrc++ >> -shiftBits); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = A (>> or <<) shiftBits */ + /* Shift the input and then store the result in the destination buffer. */ + *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : + (*pSrc++ >> -shiftBits); + + /* Decrement the loop counter */ + blkCnt--; + } + +} + +/** + * @} end of shift group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q7.c index f65e244cf..cf13ef3ab 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_shift_q7.c @@ -1,202 +1,202 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_shift_q7.c -* -* Description: Processing function for the Q7 Shifting -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup shift - * @{ - */ - - -/** - * @brief Shifts the elements of a Q7 vector a specified number of bits. - * @param[in] *pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x8 0x7F] will be saturated. - */ - -void arm_shift_q7( - q7_t * pSrc, - int8_t shiftBits, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - uint8_t sign; /* Sign of shiftBits */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q7_t in1; /* Input value1 */ - q7_t in2; /* Input value2 */ - q7_t in3; /* Input value3 */ - q7_t in4; /* Input value4 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Getting the sign of shiftBits */ - sign = (shiftBits & 0x80); - - /* If the shift value is positive then do right shift else left shift */ - if(sign == 0u) - { - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Read 4 inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - /* Store the Shifted result in the destination buffer in single cycle by packing the outputs */ - *__SIMD32(pDst)++ = __PACKq7(__SSAT((in1 << shiftBits), 8), - __SSAT((in2 << shiftBits), 8), - __SSAT((in3 << shiftBits), 8), - __SSAT((in4 << shiftBits), 8)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Shift the input and then store the result in the destination buffer. */ - *pDst++ = (q7_t) __SSAT((*pSrc++ << shiftBits), 8); - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Read 4 inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - /* Store the Shifted result in the destination buffer in single cycle by packing the outputs */ - *__SIMD32(pDst)++ = __PACKq7((in1 >> -shiftBits), (in2 >> -shiftBits), - (in3 >> -shiftBits), (in4 >> -shiftBits)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Shift the input and then store the result in the destination buffer. */ - *pDst++ = (*pSrc++ >> -shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Getting the sign of shiftBits */ - sign = (shiftBits & 0x80); - - /* If the shift value is positive then do right shift else left shift */ - if(sign == 0u) - { - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Shift the input and then store the result in the destination buffer. */ - *pDst++ = (q7_t) __SSAT(((q15_t) * pSrc++ << shiftBits), 8); - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Shift the input and then store the result in the destination buffer. */ - *pDst++ = (*pSrc++ >> -shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of shift group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_shift_q7.c +* +* Description: Processing function for the Q7 Shifting +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup shift + * @{ + */ + + +/** + * @brief Shifts the elements of a Q7 vector a specified number of bits. + * @param[in] *pSrc points to the input vector + * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in the vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q7 range [0x8 0x7F] will be saturated. + */ + +void arm_shift_q7( + q7_t * pSrc, + int8_t shiftBits, + q7_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + uint8_t sign; /* Sign of shiftBits */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + q7_t in1; /* Input value1 */ + q7_t in2; /* Input value2 */ + q7_t in3; /* Input value3 */ + q7_t in4; /* Input value4 */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Getting the sign of shiftBits */ + sign = (shiftBits & 0x80); + + /* If the shift value is positive then do right shift else left shift */ + if(sign == 0u) + { + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A << shiftBits */ + /* Read 4 inputs */ + in1 = *pSrc++; + in2 = *pSrc++; + in3 = *pSrc++; + in4 = *pSrc++; + + /* Store the Shifted result in the destination buffer in single cycle by packing the outputs */ + *__SIMD32(pDst)++ = __PACKq7(__SSAT((in1 << shiftBits), 8), + __SSAT((in2 << shiftBits), 8), + __SSAT((in3 << shiftBits), 8), + __SSAT((in4 << shiftBits), 8)); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A << shiftBits */ + /* Shift the input and then store the result in the destination buffer. */ + *pDst++ = (q7_t) __SSAT((*pSrc++ << shiftBits), 8); + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A >> shiftBits */ + /* Read 4 inputs */ + in1 = *pSrc++; + in2 = *pSrc++; + in3 = *pSrc++; + in4 = *pSrc++; + + /* Store the Shifted result in the destination buffer in single cycle by packing the outputs */ + *__SIMD32(pDst)++ = __PACKq7((in1 >> -shiftBits), (in2 >> -shiftBits), + (in3 >> -shiftBits), (in4 >> -shiftBits)); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A >> shiftBits */ + /* Shift the input and then store the result in the destination buffer. */ + *pDst++ = (*pSrc++ >> -shiftBits); + + /* Decrement the loop counter */ + blkCnt--; + } + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Getting the sign of shiftBits */ + sign = (shiftBits & 0x80); + + /* If the shift value is positive then do right shift else left shift */ + if(sign == 0u) + { + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A << shiftBits */ + /* Shift the input and then store the result in the destination buffer. */ + *pDst++ = (q7_t) __SSAT(((q15_t) * pSrc++ << shiftBits), 8); + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A >> shiftBits */ + /* Shift the input and then store the result in the destination buffer. */ + *pDst++ = (*pSrc++ >> -shiftBits); + + /* Decrement the loop counter */ + blkCnt--; + } + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of shift group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_f32.c index b09e7d440..3ec5c7431 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_f32.c @@ -1,122 +1,122 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_sub_f32.c -* -* Description: Floating-point vector subtraction. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup BasicSub Vector Subtraction - * - * Element-by-element subtraction of two vectors. - * - *
   
- *     pDst[n] = pSrcA[n] - pSrcB[n],   0 <= n < blockSize.   
- * 
- * - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup BasicSub - * @{ - */ - - -/** - * @brief Floating-point vector subtraction. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - */ - -void arm_sub_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the results in the destination buffer. */ - *pDst++ = (*pSrcA++) - (*pSrcB++); - *pDst++ = (*pSrcA++) - (*pSrcB++); - *pDst++ = (*pSrcA++) - (*pSrcB++); - *pDst++ = (*pSrcA++) - (*pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the results in the destination buffer. */ - *pDst++ = (*pSrcA++) - (*pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicSub group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sub_f32.c +* +* Description: Floating-point vector subtraction. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @defgroup BasicSub Vector Subtraction + * + * Element-by-element subtraction of two vectors. + * + *
   
+ *     pDst[n] = pSrcA[n] - pSrcB[n],   0 <= n < blockSize.   
+ * 
+ * + * There are separate functions for floating-point, Q7, Q15, and Q31 data types. + */ + +/** + * @addtogroup BasicSub + * @{ + */ + + +/** + * @brief Floating-point vector subtraction. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + */ + +void arm_sub_f32( + float32_t * pSrcA, + float32_t * pSrcB, + float32_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the results in the destination buffer. */ + *pDst++ = (*pSrcA++) - (*pSrcB++); + *pDst++ = (*pSrcA++) - (*pSrcB++); + *pDst++ = (*pSrcA++) - (*pSrcB++); + *pDst++ = (*pSrcA++) - (*pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the results in the destination buffer. */ + *pDst++ = (*pSrcA++) - (*pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of BasicSub group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q15.c index 2844951b4..6d170e25d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q15.c @@ -1,124 +1,124 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_sub_q15.c -* -* Description: Q15 vector subtraction. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicSub - * @{ - */ - -/** - * @brief Q15 vector subtraction. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -void arm_sub_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the results in the destination buffer two samples at a time. */ - *__SIMD32(pDst)++ = __QSUB16(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); - *__SIMD32(pDst)++ = __QSUB16(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = (q15_t) __QSUB16(*pSrcA++, *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = (q15_t) __SSAT(((q31_t) * pSrcA++ - *pSrcB++), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - -} - -/** - * @} end of BasicSub group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sub_q15.c +* +* Description: Q15 vector subtraction. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicSub + * @{ + */ + +/** + * @brief Q15 vector subtraction. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. + */ + +void arm_sub_q15( + q15_t * pSrcA, + q15_t * pSrcB, + q15_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the results in the destination buffer two samples at a time. */ + *__SIMD32(pDst)++ = __QSUB16(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); + *__SIMD32(pDst)++ = __QSUB16(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the result in the destination buffer. */ + *pDst++ = (q15_t) __QSUB16(*pSrcA++, *pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the result in the destination buffer. */ + *pDst++ = (q15_t) __SSAT(((q31_t) * pSrcA++ - *pSrcB++), 16); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + +} + +/** + * @} end of BasicSub group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q31.c index 5ce8a106f..489a28f3a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q31.c @@ -1,125 +1,125 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_sub_q31.c -* -* Description: Q31 vector subtraction. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicSub - * @{ - */ - -/** - * @brief Q31 vector subtraction. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. - */ - -void arm_sub_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the results in the destination buffer. */ - *pDst++ = __QSUB(*pSrcA++, *pSrcB++); - *pDst++ = __QSUB(*pSrcA++, *pSrcB++); - *pDst++ = __QSUB(*pSrcA++, *pSrcB++); - *pDst++ = __QSUB(*pSrcA++, *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = __QSUB(*pSrcA++, *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = (q31_t) clip_q63_to_q31((q63_t) * pSrcA++ - *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of BasicSub group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sub_q31.c +* +* Description: Q31 vector subtraction. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicSub + * @{ + */ + +/** + * @brief Q31 vector subtraction. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. + */ + +void arm_sub_q31( + q31_t * pSrcA, + q31_t * pSrcB, + q31_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the results in the destination buffer. */ + *pDst++ = __QSUB(*pSrcA++, *pSrcB++); + *pDst++ = __QSUB(*pSrcA++, *pSrcB++); + *pDst++ = __QSUB(*pSrcA++, *pSrcB++); + *pDst++ = __QSUB(*pSrcA++, *pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the result in the destination buffer. */ + *pDst++ = __QSUB(*pSrcA++, *pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the result in the destination buffer. */ + *pDst++ = (q31_t) clip_q63_to_q31((q63_t) * pSrcA++ - *pSrcB++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of BasicSub group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q7.c index 5497c5a30..f1bb2c6fa 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/BasicMathFunctions/arm_sub_q7.c @@ -1,123 +1,123 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_sub_q7.c -* -* Description: Q7 vector subtraction. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicSub - * @{ - */ - -/** - * @brief Q7 vector subtraction. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. - */ - -void arm_sub_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the results in the destination buffer 4 samples at a time. */ - *__SIMD32(pDst)++ = __QSUB8(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = __SSAT(*pSrcA++ - *pSrcB++, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = (q7_t) __SSAT((q15_t) * pSrcA++ - *pSrcB++, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - -} - -/** - * @} end of BasicSub group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sub_q7.c +* +* Description: Q7 vector subtraction. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMath + */ + +/** + * @addtogroup BasicSub + * @{ + */ + +/** + * @brief Q7 vector subtraction. + * @param[in] *pSrcA points to the first input vector + * @param[in] *pSrcB points to the second input vector + * @param[out] *pDst points to the output vector + * @param[in] blockSize number of samples in each vector + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. + */ + +void arm_sub_q7( + q7_t * pSrcA, + q7_t * pSrcB, + q7_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + +/* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the results in the destination buffer 4 samples at a time. */ + *__SIMD32(pDst)++ = __QSUB8(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the result in the destination buffer. */ + *pDst++ = __SSAT(*pSrcA++ - *pSrcB++, 8); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A - B */ + /* Subtract and then store the result in the destination buffer. */ + *pDst++ = (q7_t) __SSAT((q15_t) * pSrcA++ - *pSrcB++, 8); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + +} + +/** + * @} end of BasicSub group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/CommonTables/arm_common_tables.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/CommonTables/arm_common_tables.c index c1f1491f2..22ffea16b 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/CommonTables/arm_common_tables.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/CommonTables/arm_common_tables.c @@ -1,144 +1,144 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_common_tables.c -* -* Description: This file has common tables like Bitreverse, reciprocal etc which are used across different functions -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup CFFT_CIFFT - * @{ - */ - -/** -* \par -* Pseudo code for Generation of Bit reversal Table is -* \par -*
for(l=1;l <= N/4;l++)   
-* {   
-*   for(i=0;i> 1;   
-*  } 
-* \par -* where N = 1024 logN2 = 10 -* \par -* N is the maximum FFT Size supported -*/ - -/* -* @brief Table for bit reversal process -*/ -const uint16_t armBitRevTable[256] = { - 0x100, 0x80, 0x180, 0x40, 0x140, 0xc0, 0x1c0, - 0x20, 0x120, 0xa0, 0x1a0, 0x60, 0x160, 0xe0, - 0x1e0, 0x10, 0x110, 0x90, 0x190, 0x50, 0x150, - 0xd0, 0x1d0, 0x30, 0x130, 0xb0, 0x1b0, 0x70, - 0x170, 0xf0, 0x1f0, 0x8, 0x108, 0x88, 0x188, - 0x48, 0x148, 0xc8, 0x1c8, 0x28, 0x128, 0xa8, - 0x1a8, 0x68, 0x168, 0xe8, 0x1e8, 0x18, 0x118, - 0x98, 0x198, 0x58, 0x158, 0xd8, 0x1d8, 0x38, - 0x138, 0xb8, 0x1b8, 0x78, 0x178, 0xf8, 0x1f8, - 0x4, 0x104, 0x84, 0x184, 0x44, 0x144, 0xc4, - 0x1c4, 0x24, 0x124, 0xa4, 0x1a4, 0x64, 0x164, - 0xe4, 0x1e4, 0x14, 0x114, 0x94, 0x194, 0x54, - 0x154, 0xd4, 0x1d4, 0x34, 0x134, 0xb4, 0x1b4, - 0x74, 0x174, 0xf4, 0x1f4, 0xc, 0x10c, 0x8c, - 0x18c, 0x4c, 0x14c, 0xcc, 0x1cc, 0x2c, 0x12c, - 0xac, 0x1ac, 0x6c, 0x16c, 0xec, 0x1ec, 0x1c, - 0x11c, 0x9c, 0x19c, 0x5c, 0x15c, 0xdc, 0x1dc, - 0x3c, 0x13c, 0xbc, 0x1bc, 0x7c, 0x17c, 0xfc, - 0x1fc, 0x2, 0x102, 0x82, 0x182, 0x42, 0x142, - 0xc2, 0x1c2, 0x22, 0x122, 0xa2, 0x1a2, 0x62, - 0x162, 0xe2, 0x1e2, 0x12, 0x112, 0x92, 0x192, - 0x52, 0x152, 0xd2, 0x1d2, 0x32, 0x132, 0xb2, - 0x1b2, 0x72, 0x172, 0xf2, 0x1f2, 0xa, 0x10a, - 0x8a, 0x18a, 0x4a, 0x14a, 0xca, 0x1ca, 0x2a, - 0x12a, 0xaa, 0x1aa, 0x6a, 0x16a, 0xea, 0x1ea, - 0x1a, 0x11a, 0x9a, 0x19a, 0x5a, 0x15a, 0xda, - 0x1da, 0x3a, 0x13a, 0xba, 0x1ba, 0x7a, 0x17a, - 0xfa, 0x1fa, 0x6, 0x106, 0x86, 0x186, 0x46, - 0x146, 0xc6, 0x1c6, 0x26, 0x126, 0xa6, 0x1a6, - 0x66, 0x166, 0xe6, 0x1e6, 0x16, 0x116, 0x96, - 0x196, 0x56, 0x156, 0xd6, 0x1d6, 0x36, 0x136, - 0xb6, 0x1b6, 0x76, 0x176, 0xf6, 0x1f6, 0xe, - 0x10e, 0x8e, 0x18e, 0x4e, 0x14e, 0xce, 0x1ce, - 0x2e, 0x12e, 0xae, 0x1ae, 0x6e, 0x16e, 0xee, - 0x1ee, 0x1e, 0x11e, 0x9e, 0x19e, 0x5e, 0x15e, - 0xde, 0x1de, 0x3e, 0x13e, 0xbe, 0x1be, 0x7e, - 0x17e, 0xfe, 0x1fe, 0x1 -}; - -/** - * @} end of CFFT_CIFFT group - */ - -/* -* @brief Q15 table for reciprocal -*/ -const q15_t armRecipTableQ15[64] = { - 0x7F03, 0x7D13, 0x7B31, 0x795E, 0x7798, 0x75E0, - 0x7434, 0x7294, 0x70FF, 0x6F76, 0x6DF6, 0x6C82, - 0x6B16, 0x69B5, 0x685C, 0x670C, 0x65C4, 0x6484, - 0x634C, 0x621C, 0x60F3, 0x5FD0, 0x5EB5, 0x5DA0, - 0x5C91, 0x5B88, 0x5A85, 0x5988, 0x5890, 0x579E, - 0x56B0, 0x55C8, 0x54E4, 0x5405, 0x532B, 0x5255, - 0x5183, 0x50B6, 0x4FEC, 0x4F26, 0x4E64, 0x4DA6, - 0x4CEC, 0x4C34, 0x4B81, 0x4AD0, 0x4A23, 0x4978, - 0x48D1, 0x482D, 0x478C, 0x46ED, 0x4651, 0x45B8, - 0x4521, 0x448D, 0x43FC, 0x436C, 0x42DF, 0x4255, - 0x41CC, 0x4146, 0x40C2, 0x4040 -}; - -/* -* @brief Q31 table for reciprocal -*/ -const q31_t armRecipTableQ31[64] = { - 0x7F03F03F, 0x7D137420, 0x7B31E739, 0x795E9F94, 0x7798FD29, 0x75E06928, - 0x7434554D, 0x72943B4B, 0x70FF9C40, 0x6F760031, 0x6DF6F593, 0x6C8210E3, - 0x6B16EC3A, 0x69B526F6, 0x685C655F, 0x670C505D, 0x65C4952D, 0x6484E519, - 0x634CF53E, 0x621C7E4F, 0x60F33C61, 0x5FD0EEB3, 0x5EB55785, 0x5DA03BEB, - 0x5C9163A1, 0x5B8898E6, 0x5A85A85A, 0x598860DF, 0x58909373, 0x579E1318, - 0x56B0B4B8, 0x55C84F0B, 0x54E4BA80, 0x5405D124, 0x532B6E8F, 0x52556FD0, - 0x5183B35A, 0x50B618F3, 0x4FEC81A2, 0x4F26CFA2, 0x4E64E64E, 0x4DA6AA1D, - 0x4CEC008B, 0x4C34D010, 0x4B810016, 0x4AD078EF, 0x4A2323C4, 0x4978EA96, - 0x48D1B827, 0x482D77FE, 0x478C1657, 0x46ED801D, 0x4651A2E5, 0x45B86CE2, - 0x4521CCE1, 0x448DB244, 0x43FC0CFA, 0x436CCD78, 0x42DFE4B4, 0x42554426, - 0x41CCDDB6, 0x4146A3C6, 0x40C28923, 0x40408102 -}; +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_common_tables.c +* +* Description: This file has common tables like Bitreverse, reciprocal etc which are used across different functions +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup CFFT_CIFFT + * @{ + */ + +/** +* \par +* Pseudo code for Generation of Bit reversal Table is +* \par +*
for(l=1;l <= N/4;l++)   
+* {   
+*   for(i=0;i> 1;   
+*  } 
+* \par +* where N = 1024 logN2 = 10 +* \par +* N is the maximum FFT Size supported +*/ + +/* +* @brief Table for bit reversal process +*/ +const uint16_t armBitRevTable[256] = { + 0x100, 0x80, 0x180, 0x40, 0x140, 0xc0, 0x1c0, + 0x20, 0x120, 0xa0, 0x1a0, 0x60, 0x160, 0xe0, + 0x1e0, 0x10, 0x110, 0x90, 0x190, 0x50, 0x150, + 0xd0, 0x1d0, 0x30, 0x130, 0xb0, 0x1b0, 0x70, + 0x170, 0xf0, 0x1f0, 0x8, 0x108, 0x88, 0x188, + 0x48, 0x148, 0xc8, 0x1c8, 0x28, 0x128, 0xa8, + 0x1a8, 0x68, 0x168, 0xe8, 0x1e8, 0x18, 0x118, + 0x98, 0x198, 0x58, 0x158, 0xd8, 0x1d8, 0x38, + 0x138, 0xb8, 0x1b8, 0x78, 0x178, 0xf8, 0x1f8, + 0x4, 0x104, 0x84, 0x184, 0x44, 0x144, 0xc4, + 0x1c4, 0x24, 0x124, 0xa4, 0x1a4, 0x64, 0x164, + 0xe4, 0x1e4, 0x14, 0x114, 0x94, 0x194, 0x54, + 0x154, 0xd4, 0x1d4, 0x34, 0x134, 0xb4, 0x1b4, + 0x74, 0x174, 0xf4, 0x1f4, 0xc, 0x10c, 0x8c, + 0x18c, 0x4c, 0x14c, 0xcc, 0x1cc, 0x2c, 0x12c, + 0xac, 0x1ac, 0x6c, 0x16c, 0xec, 0x1ec, 0x1c, + 0x11c, 0x9c, 0x19c, 0x5c, 0x15c, 0xdc, 0x1dc, + 0x3c, 0x13c, 0xbc, 0x1bc, 0x7c, 0x17c, 0xfc, + 0x1fc, 0x2, 0x102, 0x82, 0x182, 0x42, 0x142, + 0xc2, 0x1c2, 0x22, 0x122, 0xa2, 0x1a2, 0x62, + 0x162, 0xe2, 0x1e2, 0x12, 0x112, 0x92, 0x192, + 0x52, 0x152, 0xd2, 0x1d2, 0x32, 0x132, 0xb2, + 0x1b2, 0x72, 0x172, 0xf2, 0x1f2, 0xa, 0x10a, + 0x8a, 0x18a, 0x4a, 0x14a, 0xca, 0x1ca, 0x2a, + 0x12a, 0xaa, 0x1aa, 0x6a, 0x16a, 0xea, 0x1ea, + 0x1a, 0x11a, 0x9a, 0x19a, 0x5a, 0x15a, 0xda, + 0x1da, 0x3a, 0x13a, 0xba, 0x1ba, 0x7a, 0x17a, + 0xfa, 0x1fa, 0x6, 0x106, 0x86, 0x186, 0x46, + 0x146, 0xc6, 0x1c6, 0x26, 0x126, 0xa6, 0x1a6, + 0x66, 0x166, 0xe6, 0x1e6, 0x16, 0x116, 0x96, + 0x196, 0x56, 0x156, 0xd6, 0x1d6, 0x36, 0x136, + 0xb6, 0x1b6, 0x76, 0x176, 0xf6, 0x1f6, 0xe, + 0x10e, 0x8e, 0x18e, 0x4e, 0x14e, 0xce, 0x1ce, + 0x2e, 0x12e, 0xae, 0x1ae, 0x6e, 0x16e, 0xee, + 0x1ee, 0x1e, 0x11e, 0x9e, 0x19e, 0x5e, 0x15e, + 0xde, 0x1de, 0x3e, 0x13e, 0xbe, 0x1be, 0x7e, + 0x17e, 0xfe, 0x1fe, 0x1 +}; + +/** + * @} end of CFFT_CIFFT group + */ + +/* +* @brief Q15 table for reciprocal +*/ +const q15_t armRecipTableQ15[64] = { + 0x7F03, 0x7D13, 0x7B31, 0x795E, 0x7798, 0x75E0, + 0x7434, 0x7294, 0x70FF, 0x6F76, 0x6DF6, 0x6C82, + 0x6B16, 0x69B5, 0x685C, 0x670C, 0x65C4, 0x6484, + 0x634C, 0x621C, 0x60F3, 0x5FD0, 0x5EB5, 0x5DA0, + 0x5C91, 0x5B88, 0x5A85, 0x5988, 0x5890, 0x579E, + 0x56B0, 0x55C8, 0x54E4, 0x5405, 0x532B, 0x5255, + 0x5183, 0x50B6, 0x4FEC, 0x4F26, 0x4E64, 0x4DA6, + 0x4CEC, 0x4C34, 0x4B81, 0x4AD0, 0x4A23, 0x4978, + 0x48D1, 0x482D, 0x478C, 0x46ED, 0x4651, 0x45B8, + 0x4521, 0x448D, 0x43FC, 0x436C, 0x42DF, 0x4255, + 0x41CC, 0x4146, 0x40C2, 0x4040 +}; + +/* +* @brief Q31 table for reciprocal +*/ +const q31_t armRecipTableQ31[64] = { + 0x7F03F03F, 0x7D137420, 0x7B31E739, 0x795E9F94, 0x7798FD29, 0x75E06928, + 0x7434554D, 0x72943B4B, 0x70FF9C40, 0x6F760031, 0x6DF6F593, 0x6C8210E3, + 0x6B16EC3A, 0x69B526F6, 0x685C655F, 0x670C505D, 0x65C4952D, 0x6484E519, + 0x634CF53E, 0x621C7E4F, 0x60F33C61, 0x5FD0EEB3, 0x5EB55785, 0x5DA03BEB, + 0x5C9163A1, 0x5B8898E6, 0x5A85A85A, 0x598860DF, 0x58909373, 0x579E1318, + 0x56B0B4B8, 0x55C84F0B, 0x54E4BA80, 0x5405D124, 0x532B6E8F, 0x52556FD0, + 0x5183B35A, 0x50B618F3, 0x4FEC81A2, 0x4F26CFA2, 0x4E64E64E, 0x4DA6AA1D, + 0x4CEC008B, 0x4C34D010, 0x4B810016, 0x4AD078EF, 0x4A2323C4, 0x4978EA96, + 0x48D1B827, 0x482D77FE, 0x478C1657, 0x46ED801D, 0x4651A2E5, 0x45B86CE2, + 0x4521CCE1, 0x448DB244, 0x43FC0CFA, 0x436CCD78, 0x42DFE4B4, 0x42554426, + 0x41CCDDB6, 0x4146A3C6, 0x40C28923, 0x40408102 +}; diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_f32.c index 71cbc45f2..4623357b7 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_f32.c @@ -1,141 +1,141 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_cmplx_conj_f32.c -* -* Description: Floating-point complex conjugate. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupCmplxMath - */ - -/** - * @defgroup cmplx_conj Complex Conjugate - * - * Conjugates the elements of a complex data vector. - * - * The pSrc points to the source data and - * pDst points to the where the result should be written. - * numSamples specifies the number of complex samples - * and the data in each array is stored in an interleaved fashion - * (real, imag, real, imag, ...). - * Each array has a total of 2*numSamples values. - * The underlying algorithm is used: - * - *
   
- * for(n=0; n   
- *   
- * There are separate functions for floating-point, Q15, and Q31 data types.   
- */
-
-/**   
- * @addtogroup cmplx_conj   
- * @{   
- */
-
-/**   
- * @brief  Floating-point complex conjugate.   
- * @param  *pSrc points to the input vector   
- * @param  *pDst points to the output vector   
- * @param  numSamples number of complex samples in each vector   
- * @return none.   
- */
-
-void arm_cmplx_conj_f32(
-  float32_t * pSrc,
-  float32_t * pDst,
-  uint32_t numSamples)
-{
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    *pDst++ = *pSrc++;
-    *pDst++ = -*pSrc++;
-    *pDst++ = *pSrc++;
-    *pDst++ = -*pSrc++;
-    *pDst++ = *pSrc++;
-    *pDst++ = -*pSrc++;
-    *pDst++ = *pSrc++;
-    *pDst++ = -*pSrc++;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    *pDst++ = *pSrc++;
-    *pDst++ = -*pSrc++;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* realOut + j (imagOut) = realIn + j (-1) imagIn */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    *pDst++ = *pSrc++;
-    *pDst++ = -*pSrc++;
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of cmplx_conj group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_conj_f32.c   
+*   
+* Description:	Floating-point complex conjugate.   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ---------------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @defgroup cmplx_conj Complex Conjugate   
+ *   
+ * Conjugates the elements of a complex data vector.   
+ *  
+ * The pSrc points to the source data and   
+ * pDst points to the where the result should be written.   
+ * numSamples specifies the number of complex samples   
+ * and the data in each array is stored in an interleaved fashion   
+ * (real, imag, real, imag, ...).   
+ * Each array has a total of 2*numSamples values.   
+ * The underlying algorithm is used:   
+ *   
+ * 
   
+ * for(n=0; n   
+ *   
+ * There are separate functions for floating-point, Q15, and Q31 data types.   
+ */
+
+/**   
+ * @addtogroup cmplx_conj   
+ * @{   
+ */
+
+/**   
+ * @brief  Floating-point complex conjugate.   
+ * @param  *pSrc points to the input vector   
+ * @param  *pDst points to the output vector   
+ * @param  numSamples number of complex samples in each vector   
+ * @return none.   
+ */
+
+void arm_cmplx_conj_f32(
+  float32_t * pSrc,
+  float32_t * pDst,
+  uint32_t numSamples)
+{
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
+    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
+    *pDst++ = *pSrc++;
+    *pDst++ = -*pSrc++;
+    *pDst++ = *pSrc++;
+    *pDst++ = -*pSrc++;
+    *pDst++ = *pSrc++;
+    *pDst++ = -*pSrc++;
+    *pDst++ = *pSrc++;
+    *pDst++ = -*pSrc++;
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
+    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
+    *pDst++ = *pSrc++;
+    *pDst++ = -*pSrc++;
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* realOut + j (imagOut) = realIn + j (-1) imagIn */
+    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
+    *pDst++ = *pSrc++;
+    *pDst++ = -*pSrc++;
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of cmplx_conj group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q15.c
index 0a1897f75..5c4c389f1 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q15.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q15.c
@@ -1,123 +1,123 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_conj_q15.c   
-*   
-* Description:	Q15 complex conjugate.   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup cmplx_conj   
- * @{   
- */
-
-/**   
- * @brief  Q15 complex conjugate.   
- * @param  *pSrc points to the input vector   
- * @param  *pDst points to the output vector   
- * @param  numSamples number of complex samples in each vector   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function uses saturating arithmetic.   
- * The Q15 value -1 (0x8000) will be saturated to the maximum allowable positive value 0x7FFF.   
- */
-
-void arm_cmplx_conj_q15(
-  q15_t * pSrc,
-  q15_t * pDst,
-  uint32_t numSamples)
-{
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    *pDst++ = *pSrc++;
-    *pDst++ = __SSAT(-*pSrc++, 16);
-    *pDst++ = *pSrc++;
-    *pDst++ = __SSAT(-*pSrc++, 16);
-    *pDst++ = *pSrc++;
-    *pDst++ = __SSAT(-*pSrc++, 16);
-    *pDst++ = *pSrc++;
-    *pDst++ = __SSAT(-*pSrc++, 16);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    *pDst++ = *pSrc++;
-    *pDst++ = __SSAT(-*pSrc++, 16);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* realOut + j (imagOut) = realIn+ j (-1) imagIn */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    *pDst++ = *pSrc++;
-    *pDst++ = -*pSrc++;
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of cmplx_conj group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_conj_q15.c   
+*   
+* Description:	Q15 complex conjugate.   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ---------------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup cmplx_conj   
+ * @{   
+ */
+
+/**   
+ * @brief  Q15 complex conjugate.   
+ * @param  *pSrc points to the input vector   
+ * @param  *pDst points to the output vector   
+ * @param  numSamples number of complex samples in each vector   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function uses saturating arithmetic.   
+ * The Q15 value -1 (0x8000) will be saturated to the maximum allowable positive value 0x7FFF.   
+ */
+
+void arm_cmplx_conj_q15(
+  q15_t * pSrc,
+  q15_t * pDst,
+  uint32_t numSamples)
+{
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
+    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
+    *pDst++ = *pSrc++;
+    *pDst++ = __SSAT(-*pSrc++, 16);
+    *pDst++ = *pSrc++;
+    *pDst++ = __SSAT(-*pSrc++, 16);
+    *pDst++ = *pSrc++;
+    *pDst++ = __SSAT(-*pSrc++, 16);
+    *pDst++ = *pSrc++;
+    *pDst++ = __SSAT(-*pSrc++, 16);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
+    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
+    *pDst++ = *pSrc++;
+    *pDst++ = __SSAT(-*pSrc++, 16);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* realOut + j (imagOut) = realIn+ j (-1) imagIn */
+    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
+    *pDst++ = *pSrc++;
+    *pDst++ = -*pSrc++;
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of cmplx_conj group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q31.c
index 3eaa44e0c..b139ea25f 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q31.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q31.c
@@ -1,131 +1,131 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_conj_q31.c   
-*   
-* Description:	Q31 complex conjugate.   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup cmplx_conj   
- * @{   
- */
-
-/**   
- * @brief  Q31 complex conjugate.   
- * @param  *pSrc points to the input vector   
- * @param  *pDst points to the output vector   
- * @param  numSamples number of complex samples in each vector   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function uses saturating arithmetic.   
- * The Q31 value -1 (0x80000000) will be saturated to the maximum allowable positive value 0x7FFFFFFF.   
- */
-
-void arm_cmplx_conj_q31(
-  q31_t * pSrc,
-  q31_t * pDst,
-  uint32_t numSamples)
-{
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-  q31_t in;                                      /* Input value */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    /* Saturated to 0x7fffffff if the input is -1(0x80000000) */
-    *pDst++ = *pSrc++;
-    in = *pSrc++;
-    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
-    *pDst++ = *pSrc++;
-    in = *pSrc++;
-    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
-    *pDst++ = *pSrc++;
-    in = *pSrc++;
-    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
-    *pDst++ = *pSrc++;
-    in = *pSrc++;
-    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    /* Saturated to 0x7fffffff if the input is -1(0x80000000) */
-    *pDst++ = *pSrc++;
-    in = *pSrc++;
-    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* realOut + j (imagOut) = realIn+ j (-1) imagIn */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    *pDst++ = *pSrc++;
-    *pDst++ = -*pSrc++;
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of cmplx_conj group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_conj_q31.c   
+*   
+* Description:	Q31 complex conjugate.   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ---------------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup cmplx_conj   
+ * @{   
+ */
+
+/**   
+ * @brief  Q31 complex conjugate.   
+ * @param  *pSrc points to the input vector   
+ * @param  *pDst points to the output vector   
+ * @param  numSamples number of complex samples in each vector   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function uses saturating arithmetic.   
+ * The Q31 value -1 (0x80000000) will be saturated to the maximum allowable positive value 0x7FFFFFFF.   
+ */
+
+void arm_cmplx_conj_q31(
+  q31_t * pSrc,
+  q31_t * pDst,
+  uint32_t numSamples)
+{
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+  q31_t in;                                      /* Input value */
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
+    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
+    /* Saturated to 0x7fffffff if the input is -1(0x80000000) */
+    *pDst++ = *pSrc++;
+    in = *pSrc++;
+    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
+    *pDst++ = *pSrc++;
+    in = *pSrc++;
+    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
+    *pDst++ = *pSrc++;
+    in = *pSrc++;
+    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
+    *pDst++ = *pSrc++;
+    in = *pSrc++;
+    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
+    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
+    /* Saturated to 0x7fffffff if the input is -1(0x80000000) */
+    *pDst++ = *pSrc++;
+    in = *pSrc++;
+    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* realOut + j (imagOut) = realIn+ j (-1) imagIn */
+    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
+    *pDst++ = *pSrc++;
+    *pDst++ = -*pSrc++;
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of cmplx_conj group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_f32.c
index 15ab18b17..90b8a8b34 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_f32.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_f32.c
@@ -1,157 +1,157 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_dot_prod_f32.c   
-*   
-* Description:	Floating-point complex dot product   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @defgroup cmplx_dot_prod Complex Dot Product   
- *   
- * Computes the dot product of two complex vectors.   
- * The vectors are multiplied element-by-element and then summed.   
- *  
- * The pSrcA points to the first complex input vector and   
- * pSrcB points to the second complex input vector.   
- * numSamples specifies the number of complex samples   
- * and the data in each array is stored in an interleaved fashion   
- * (real, imag, real, imag, ...).   
- * Each array has a total of 2*numSamples values.   
- *   
- * The underlying algorithm is used:   
- * 
   
- * realResult=0;   
- * imagResult=0;   
- * for(n=0; n   
- *   
- * There are separate functions for floating-point, Q15, and Q31 data types.   
- */
-
-/**   
- * @addtogroup cmplx_dot_prod   
- * @{   
- */
-
-/**   
- * @brief  Floating-point complex dot product   
- * @param  *pSrcA points to the first input vector   
- * @param  *pSrcB points to the second input vector   
- * @param  numSamples number of complex samples in each vector   
- * @param  *realResult real part of the result returned here   
- * @param  *imagResult imaginary part of the result returned here   
- * @return none.   
- */
-
-void arm_cmplx_dot_prod_f32(
-  float32_t * pSrcA,
-  float32_t * pSrcB,
-  uint32_t numSamples,
-  float32_t * realResult,
-  float32_t * imagResult)
-{
-  float32_t real_sum = 0.0f, imag_sum = 0.0f;    /* Temporary result storage */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  /* Store the real and imaginary results in the destination buffers */
-  *realResult = real_sum;
-  *imagResult = imag_sum;
-}
-
-/**   
- * @} end of cmplx_dot_prod group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_dot_prod_f32.c   
+*   
+* Description:	Floating-point complex dot product   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ---------------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @defgroup cmplx_dot_prod Complex Dot Product   
+ *   
+ * Computes the dot product of two complex vectors.   
+ * The vectors are multiplied element-by-element and then summed.   
+ *  
+ * The pSrcA points to the first complex input vector and   
+ * pSrcB points to the second complex input vector.   
+ * numSamples specifies the number of complex samples   
+ * and the data in each array is stored in an interleaved fashion   
+ * (real, imag, real, imag, ...).   
+ * Each array has a total of 2*numSamples values.   
+ *   
+ * The underlying algorithm is used:   
+ * 
   
+ * realResult=0;   
+ * imagResult=0;   
+ * for(n=0; n   
+ *   
+ * There are separate functions for floating-point, Q15, and Q31 data types.   
+ */
+
+/**   
+ * @addtogroup cmplx_dot_prod   
+ * @{   
+ */
+
+/**   
+ * @brief  Floating-point complex dot product   
+ * @param  *pSrcA points to the first input vector   
+ * @param  *pSrcB points to the second input vector   
+ * @param  numSamples number of complex samples in each vector   
+ * @param  *realResult real part of the result returned here   
+ * @param  *imagResult imaginary part of the result returned here   
+ * @return none.   
+ */
+
+void arm_cmplx_dot_prod_f32(
+  float32_t * pSrcA,
+  float32_t * pSrcB,
+  uint32_t numSamples,
+  float32_t * realResult,
+  float32_t * imagResult)
+{
+  float32_t real_sum = 0.0f, imag_sum = 0.0f;    /* Temporary result storage */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
+    real_sum += (*pSrcA++) * (*pSrcB++);
+    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
+    imag_sum += (*pSrcA++) * (*pSrcB++);
+
+    real_sum += (*pSrcA++) * (*pSrcB++);
+    imag_sum += (*pSrcA++) * (*pSrcB++);
+
+    real_sum += (*pSrcA++) * (*pSrcB++);
+    imag_sum += (*pSrcA++) * (*pSrcB++);
+
+    real_sum += (*pSrcA++) * (*pSrcB++);
+    imag_sum += (*pSrcA++) * (*pSrcB++);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
+    real_sum += (*pSrcA++) * (*pSrcB++);
+    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
+    imag_sum += (*pSrcA++) * (*pSrcB++);
+
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
+    real_sum += (*pSrcA++) * (*pSrcB++);
+    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
+    imag_sum += (*pSrcA++) * (*pSrcB++);
+
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+  /* Store the real and imaginary results in the destination buffers */
+  *realResult = real_sum;
+  *imagResult = imag_sum;
+}
+
+/**   
+ * @} end of cmplx_dot_prod group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q15.c
index 4194ed6f0..2e341bffd 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q15.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q15.c
@@ -1,141 +1,141 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_dot_prod_q15.c   
-*   
-* Description:	Processing function for the Q15 Complex Dot product   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup cmplx_dot_prod   
- * @{   
- */
-
-/**   
- * @brief  Q15 complex dot product   
- * @param  *pSrcA points to the first input vector   
- * @param  *pSrcB points to the second input vector   
- * @param  numSamples number of complex samples in each vector   
- * @param  *realResult real part of the result returned here   
- * @param  *imagResult imaginary part of the result returned here   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function is implemented using an internal 64-bit accumulator.   
- * The intermediate 1.15 by 1.15 multiplications are performed with full precision and yield a 2.30 result.   
- * These are accumulated in a 64-bit accumulator with 34.30 precision.   
- * As a final step, the accumulators are converted to 8.24 format.   
- * The return results realResult and imagResult are in 8.24 format.   
- */
-
-void arm_cmplx_dot_prod_q15(
-  q15_t * pSrcA,
-  q15_t * pSrcB,
-  uint32_t numSamples,
-  q31_t * realResult,
-  q31_t * imagResult)
-{
-  q63_t real_sum = 0, imag_sum = 0;              /* Temporary result storage */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  /* Store the real and imaginary results in 8.24 format  */
-  /* Convert real data in 34.30 to 8.24 by 6 right shifts */
-  *realResult = (q31_t) (real_sum) >> 6;
-  /* Convert imaginary data in 34.30 to 8.24 by 6 right shifts */
-  *imagResult = (q31_t) (imag_sum) >> 6;
-}
-
-/**   
- * @} end of cmplx_dot_prod group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_dot_prod_q15.c   
+*   
+* Description:	Processing function for the Q15 Complex Dot product   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* -------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup cmplx_dot_prod   
+ * @{   
+ */
+
+/**   
+ * @brief  Q15 complex dot product   
+ * @param  *pSrcA points to the first input vector   
+ * @param  *pSrcB points to the second input vector   
+ * @param  numSamples number of complex samples in each vector   
+ * @param  *realResult real part of the result returned here   
+ * @param  *imagResult imaginary part of the result returned here   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function is implemented using an internal 64-bit accumulator.   
+ * The intermediate 1.15 by 1.15 multiplications are performed with full precision and yield a 2.30 result.   
+ * These are accumulated in a 64-bit accumulator with 34.30 precision.   
+ * As a final step, the accumulators are converted to 8.24 format.   
+ * The return results realResult and imagResult are in 8.24 format.   
+ */
+
+void arm_cmplx_dot_prod_q15(
+  q15_t * pSrcA,
+  q15_t * pSrcB,
+  uint32_t numSamples,
+  q31_t * realResult,
+  q31_t * imagResult)
+{
+  q63_t real_sum = 0, imag_sum = 0;              /* Temporary result storage */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
+    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+
+    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
+    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+
+    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+
+    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+
+    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
+    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
+    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
+    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
+    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+  /* Store the real and imaginary results in 8.24 format  */
+  /* Convert real data in 34.30 to 8.24 by 6 right shifts */
+  *realResult = (q31_t) (real_sum) >> 6;
+  /* Convert imaginary data in 34.30 to 8.24 by 6 right shifts */
+  *imagResult = (q31_t) (imag_sum) >> 6;
+}
+
+/**   
+ * @} end of cmplx_dot_prod group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q31.c
index f6ad992cf..30ee59c7e 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q31.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q31.c
@@ -1,142 +1,142 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_dot_prod_q31.c   
-*   
-* Description:	Q31 complex dot product   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup cmplx_dot_prod   
- * @{   
- */
-
-/**   
- * @brief  Q31 complex dot product   
- * @param  *pSrcA points to the first input vector   
- * @param  *pSrcB points to the second input vector   
- * @param  numSamples number of complex samples in each vector   
- * @param  *realResult real part of the result returned here   
- * @param  *imagResult imaginary part of the result returned here   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function is implemented using an internal 64-bit accumulator.   
- * The intermediate 1.31 by 1.31 multiplications are performed with 64-bit precision and then shifted to 16.48 format.   
- * The internal real and imaginary accumulators are in 16.48 format and provide 15 guard bits.   
- * Additions are nonsaturating and no overflow will occur as long as numSamples is less than 32768.   
- * The return results realResult and imagResult are in 16.48 format.   
- * Input down scaling is not required.   
- */
-
-void arm_cmplx_dot_prod_q31(
-  q31_t * pSrcA,
-  q31_t * pSrcB,
-  uint32_t numSamples,
-  q63_t * realResult,
-  q63_t * imagResult)
-{
-  q63_t real_sum = 0, imag_sum = 0;              /* Temporary result storage */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    /* Convert real data in 2.62 to 16.48 by 14 right shifts */
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    /* Convert imag data in 2.62 to 16.48 by 14 right shifts */
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples  is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* outReal = realA[0]* realB[0] + realA[2]* realB[2] + realA[4]* realB[4] + .....+ realA[numSamples-2]* realB[numSamples-2] */
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    /* outImag = imagA[1]* imagB[1] + imagA[3]* imagB[3] + imagA[5]* imagB[5] + .....+ imagA[numSamples-1]* imagB[numSamples-1] */
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  /* Store the real and imaginary results in 16.48 format  */
-  *realResult = real_sum;
-  *imagResult = imag_sum;
-}
-
-/**   
- * @} end of cmplx_dot_prod group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_dot_prod_q31.c   
+*   
+* Description:	Q31 complex dot product   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* -------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup cmplx_dot_prod   
+ * @{   
+ */
+
+/**   
+ * @brief  Q31 complex dot product   
+ * @param  *pSrcA points to the first input vector   
+ * @param  *pSrcB points to the second input vector   
+ * @param  numSamples number of complex samples in each vector   
+ * @param  *realResult real part of the result returned here   
+ * @param  *imagResult imaginary part of the result returned here   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function is implemented using an internal 64-bit accumulator.   
+ * The intermediate 1.31 by 1.31 multiplications are performed with 64-bit precision and then shifted to 16.48 format.   
+ * The internal real and imaginary accumulators are in 16.48 format and provide 15 guard bits.   
+ * Additions are nonsaturating and no overflow will occur as long as numSamples is less than 32768.   
+ * The return results realResult and imagResult are in 16.48 format.   
+ * Input down scaling is not required.   
+ */
+
+void arm_cmplx_dot_prod_q31(
+  q31_t * pSrcA,
+  q31_t * pSrcB,
+  uint32_t numSamples,
+  q63_t * realResult,
+  q63_t * imagResult)
+{
+  q63_t real_sum = 0, imag_sum = 0;              /* Temporary result storage */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
+    /* Convert real data in 2.62 to 16.48 by 14 right shifts */
+    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
+    /* Convert imag data in 2.62 to 16.48 by 14 right shifts */
+    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+
+    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+
+    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+
+    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples  is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
+    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
+    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* outReal = realA[0]* realB[0] + realA[2]* realB[2] + realA[4]* realB[4] + .....+ realA[numSamples-2]* realB[numSamples-2] */
+    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+    /* outImag = imagA[1]* imagB[1] + imagA[3]* imagB[3] + imagA[5]* imagB[5] + .....+ imagA[numSamples-1]* imagB[numSamples-1] */
+    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+  /* Store the real and imaginary results in 16.48 format  */
+  *realResult = real_sum;
+  *imagResult = imag_sum;
+}
+
+/**   
+ * @} end of cmplx_dot_prod group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c
index 309ad6f09..e84195ec1 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c
@@ -1,154 +1,154 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_mag_f32.c   
-*   
-* Description:	Floating-point complex magnitude.   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @defgroup cmplx_mag Complex Magnitude   
- *   
- * Computes the magnitude of the elements of a complex data vector.   
- *  
- * The pSrc points to the source data and   
- * pDst points to the where the result should be written.   
- * numSamples specifies the number of complex samples   
- * in the input array and the data is stored in an interleaved fashion   
- * (real, imag, real, imag, ...).   
- * The input array has a total of 2*numSamples values;   
- * the output array has a total of numSamples values.   
- * The underlying algorithm is used:   
- *   
- * 
   
- * for(n=0; n   
- *   
- * There are separate functions for floating-point, Q15, and Q31 data types.   
- */
-
-/**   
- * @addtogroup cmplx_mag   
- * @{   
- */
-/**   
- * @brief Floating-point complex magnitude.   
- * @param[in]       *pSrc points to complex input buffer   
- * @param[out]      *pDst points to real output buffer   
- * @param[in]       numSamples number of complex samples in the input vector   
- * @return none.   
- *   
- */
-
-
-void arm_cmplx_mag_f32(
-  float32_t * pSrc,
-  float32_t * pDst,
-  uint32_t numSamples)
-{
-  float32_t realIn, imagIn;                      /* Temporary variables to hold input values */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    /* store the result in the destination buffer. */
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    /* store the result in the destination buffer. */
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* out = sqrt((real * real) + (imag * imag)) */
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    /* store the result in the destination buffer. */
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of cmplx_mag group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_mag_f32.c   
+*   
+* Description:	Floating-point complex magnitude.   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ---------------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @defgroup cmplx_mag Complex Magnitude   
+ *   
+ * Computes the magnitude of the elements of a complex data vector.   
+ *  
+ * The pSrc points to the source data and   
+ * pDst points to the where the result should be written.   
+ * numSamples specifies the number of complex samples   
+ * in the input array and the data is stored in an interleaved fashion   
+ * (real, imag, real, imag, ...).   
+ * The input array has a total of 2*numSamples values;   
+ * the output array has a total of numSamples values.   
+ * The underlying algorithm is used:   
+ *   
+ * 
   
+ * for(n=0; n   
+ *   
+ * There are separate functions for floating-point, Q15, and Q31 data types.   
+ */
+
+/**   
+ * @addtogroup cmplx_mag   
+ * @{   
+ */
+/**   
+ * @brief Floating-point complex magnitude.   
+ * @param[in]       *pSrc points to complex input buffer   
+ * @param[out]      *pDst points to real output buffer   
+ * @param[in]       numSamples number of complex samples in the input vector   
+ * @return none.   
+ *   
+ */
+
+
+void arm_cmplx_mag_f32(
+  float32_t * pSrc,
+  float32_t * pDst,
+  uint32_t numSamples)
+{
+  float32_t realIn, imagIn;                      /* Temporary variables to hold input values */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+
+    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
+    realIn = *pSrc++;
+    imagIn = *pSrc++;
+    /* store the result in the destination buffer. */
+    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
+
+    realIn = *pSrc++;
+    imagIn = *pSrc++;
+    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
+
+    realIn = *pSrc++;
+    imagIn = *pSrc++;
+    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
+
+    realIn = *pSrc++;
+    imagIn = *pSrc++;
+    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
+
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
+    realIn = *pSrc++;
+    imagIn = *pSrc++;
+    /* store the result in the destination buffer. */
+    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* out = sqrt((real * real) + (imag * imag)) */
+    realIn = *pSrc++;
+    imagIn = *pSrc++;
+    /* store the result in the destination buffer. */
+    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of cmplx_mag group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q15.c
index ef5a455d3..6f5f7e041 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q15.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q15.c
@@ -1,153 +1,153 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_mag_q15.c   
-*   
-* Description:	Q15 complex magnitude.   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup cmplx_mag   
- * @{   
- */
-
-
-/**   
- * @brief  Q15 complex magnitude   
- * @param  *pSrc points to the complex input vector   
- * @param  *pDst points to the real output vector   
- * @param  numSamples number of complex samples in the input vector   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function implements 1.15 by 1.15 multiplications and finally output is converted into 2.14 format.   
- */
-
-void arm_cmplx_mag_q15(
-  q15_t * pSrc,
-  q15_t * pDst,
-  uint32_t numSamples)
-{
-  q15_t real, imag;                              /* Temporary variables to hold input values */
-  q31_t acc0, acc1;                              /* Accumulators */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = __SMUAD(real, real);
-    acc1 = __SMUAD(imag, imag);
-    /* store the result in 2.14 format in the destination buffer. */
-    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = __SMUAD(real, real);
-    acc1 = __SMUAD(imag, imag);
-    /* store the result in 2.14 format in the destination buffer. */
-    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = __SMUAD(real, real);
-    acc1 = __SMUAD(imag, imag);
-    /* store the result in 2.14 format in the destination buffer. */
-    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = __SMUAD(real, real);
-    acc1 = __SMUAD(imag, imag);
-    /* store the result in 2.14 format in the destination buffer. */
-    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = __SMUAD(real, real);
-    acc1 = __SMUAD(imag, imag);
-    /* store the result in 2.14 format in the destination buffer. */
-    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* out = sqrt(real * real + imag * imag) */
-    real = *pSrc++;
-    imag = *pSrc++;
-
-    acc0 = (real * real);
-    acc1 = (imag * imag);
-
-    /* store the result in 2.14 format in the destination buffer. */
-    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of cmplx_mag group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_mag_q15.c   
+*   
+* Description:	Q15 complex magnitude.   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ---------------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup cmplx_mag   
+ * @{   
+ */
+
+
+/**   
+ * @brief  Q15 complex magnitude   
+ * @param  *pSrc points to the complex input vector   
+ * @param  *pDst points to the real output vector   
+ * @param  numSamples number of complex samples in the input vector   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function implements 1.15 by 1.15 multiplications and finally output is converted into 2.14 format.   
+ */
+
+void arm_cmplx_mag_q15(
+  q15_t * pSrc,
+  q15_t * pDst,
+  uint32_t numSamples)
+{
+  q15_t real, imag;                              /* Temporary variables to hold input values */
+  q31_t acc0, acc1;                              /* Accumulators */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+
+    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = __SMUAD(real, real);
+    acc1 = __SMUAD(imag, imag);
+    /* store the result in 2.14 format in the destination buffer. */
+    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = __SMUAD(real, real);
+    acc1 = __SMUAD(imag, imag);
+    /* store the result in 2.14 format in the destination buffer. */
+    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = __SMUAD(real, real);
+    acc1 = __SMUAD(imag, imag);
+    /* store the result in 2.14 format in the destination buffer. */
+    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = __SMUAD(real, real);
+    acc1 = __SMUAD(imag, imag);
+    /* store the result in 2.14 format in the destination buffer. */
+    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = __SMUAD(real, real);
+    acc1 = __SMUAD(imag, imag);
+    /* store the result in 2.14 format in the destination buffer. */
+    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* out = sqrt(real * real + imag * imag) */
+    real = *pSrc++;
+    imag = *pSrc++;
+
+    acc0 = (real * real);
+    acc1 = (imag * imag);
+
+    /* store the result in 2.14 format in the destination buffer. */
+    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of cmplx_mag group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q31.c
index ab56304b1..07b683dc6 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q31.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q31.c
@@ -1,151 +1,151 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_mag_q31.c   
-*   
-* Description:	Q31 complex magnitude   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup cmplx_mag   
- * @{   
- */
-
-/**   
- * @brief  Q31 complex magnitude   
- * @param  *pSrc points to the complex input vector   
- * @param  *pDst points to the real output vector   
- * @param  numSamples number of complex samples in the input vector   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function implements 1.31 by 1.31 multiplications and finally output is converted into 2.30 format.   
- * Input down scaling is not required.   
- */
-
-void arm_cmplx_mag_q31(
-  q31_t * pSrc,
-  q31_t * pDst,
-  uint32_t numSamples)
-{
-  q31_t real, imag;                              /* Temporary variables to hold input values */
-  q31_t acc0, acc1;                              /* Accumulators */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 2.30 format in the destination buffer. */
-    arm_sqrt_q31(acc0 + acc1, pDst++);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 2.30 format in the destination buffer. */
-    arm_sqrt_q31(acc0 + acc1, pDst++);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 2.30 format in the destination buffer. */
-    arm_sqrt_q31(acc0 + acc1, pDst++);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 2.30 format in the destination buffer. */
-    arm_sqrt_q31(acc0 + acc1, pDst++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 2.30 format in the destination buffer. */
-    arm_sqrt_q31(acc0 + acc1, pDst++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* out = sqrt((real * real) + (imag * imag)) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 2.30 format in the destination buffer. */
-    arm_sqrt_q31(acc0 + acc1, pDst++);
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of cmplx_mag group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_mag_q31.c   
+*   
+* Description:	Q31 complex magnitude   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ---------------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup cmplx_mag   
+ * @{   
+ */
+
+/**   
+ * @brief  Q31 complex magnitude   
+ * @param  *pSrc points to the complex input vector   
+ * @param  *pDst points to the real output vector   
+ * @param  numSamples number of complex samples in the input vector   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function implements 1.31 by 1.31 multiplications and finally output is converted into 2.30 format.   
+ * Input down scaling is not required.   
+ */
+
+void arm_cmplx_mag_q31(
+  q31_t * pSrc,
+  q31_t * pDst,
+  uint32_t numSamples)
+{
+  q31_t real, imag;                              /* Temporary variables to hold input values */
+  q31_t acc0, acc1;                              /* Accumulators */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+
+    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 2.30 format in the destination buffer. */
+    arm_sqrt_q31(acc0 + acc1, pDst++);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 2.30 format in the destination buffer. */
+    arm_sqrt_q31(acc0 + acc1, pDst++);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 2.30 format in the destination buffer. */
+    arm_sqrt_q31(acc0 + acc1, pDst++);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 2.30 format in the destination buffer. */
+    arm_sqrt_q31(acc0 + acc1, pDst++);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 2.30 format in the destination buffer. */
+    arm_sqrt_q31(acc0 + acc1, pDst++);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* out = sqrt((real * real) + (imag * imag)) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 2.30 format in the destination buffer. */
+    arm_sqrt_q31(acc0 + acc1, pDst++);
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of cmplx_mag group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_f32.c
index eb6c1baf8..87b89dea1 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_f32.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_f32.c
@@ -1,155 +1,155 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_mag_squared_f32.c   
-*   
-* Description:	Floating-point complex magnitude squared.   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @defgroup cmplx_mag_squared Complex Magnitude Squared   
- *   
- * Computes the magnitude squared of the elements of a complex data vector.   
- *  
- * The pSrc points to the source data and   
- * pDst points to the where the result should be written.   
- * numSamples specifies the number of complex samples   
- * in the input array and the data is stored in an interleaved fashion   
- * (real, imag, real, imag, ...).   
- * The input array has a total of 2*numSamples values;   
- * the output array has a total of numSamples values.   
- *   
- * The underlying algorithm is used:   
- *   
- * 
   
- * for(n=0; n   
- *   
- * There are separate functions for floating-point, Q15, and Q31 data types.   
- */
-
-/**   
- * @addtogroup cmplx_mag_squared   
- * @{   
- */
-
-
-/**   
- * @brief  Floating-point complex magnitude squared   
- * @param[in]  *pSrc points to the complex input vector   
- * @param[out]  *pDst points to the real output vector   
- * @param[in]  numSamples number of complex samples in the input vector   
- * @return none.   
- */
-
-void arm_cmplx_mag_squared_f32(
-  float32_t * pSrc,
-  float32_t * pDst,
-  uint32_t numSamples)
-{
-  float32_t real, imag;                          /* Temporary variables to store real and imaginary values */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    /* store the result in the destination buffer. */
-    *pDst++ = (real * real) + (imag * imag);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    *pDst++ = (real * real) + (imag * imag);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    *pDst++ = (real * real) + (imag * imag);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    *pDst++ = (real * real) + (imag * imag);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    /* store the result in the destination buffer. */
-    *pDst++ = (real * real) + (imag * imag);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* reading real and imaginary values */
-    real = *pSrc++;
-    imag = *pSrc++;
-
-    /* out = (real * real) + (imag * imag) */
-    /* store the result in the destination buffer. */
-    *pDst++ = (real * real) + (imag * imag);
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of cmplx_mag_squared group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_mag_squared_f32.c   
+*   
+* Description:	Floating-point complex magnitude squared.   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ---------------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @defgroup cmplx_mag_squared Complex Magnitude Squared   
+ *   
+ * Computes the magnitude squared of the elements of a complex data vector.   
+ *  
+ * The pSrc points to the source data and   
+ * pDst points to the where the result should be written.   
+ * numSamples specifies the number of complex samples   
+ * in the input array and the data is stored in an interleaved fashion   
+ * (real, imag, real, imag, ...).   
+ * The input array has a total of 2*numSamples values;   
+ * the output array has a total of numSamples values.   
+ *   
+ * The underlying algorithm is used:   
+ *   
+ * 
   
+ * for(n=0; n   
+ *   
+ * There are separate functions for floating-point, Q15, and Q31 data types.   
+ */
+
+/**   
+ * @addtogroup cmplx_mag_squared   
+ * @{   
+ */
+
+
+/**   
+ * @brief  Floating-point complex magnitude squared   
+ * @param[in]  *pSrc points to the complex input vector   
+ * @param[out]  *pDst points to the real output vector   
+ * @param[in]  numSamples number of complex samples in the input vector   
+ * @return none.   
+ */
+
+void arm_cmplx_mag_squared_f32(
+  float32_t * pSrc,
+  float32_t * pDst,
+  uint32_t numSamples)
+{
+  float32_t real, imag;                          /* Temporary variables to store real and imaginary values */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    /* store the result in the destination buffer. */
+    *pDst++ = (real * real) + (imag * imag);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    *pDst++ = (real * real) + (imag * imag);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    *pDst++ = (real * real) + (imag * imag);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    *pDst++ = (real * real) + (imag * imag);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    /* store the result in the destination buffer. */
+    *pDst++ = (real * real) + (imag * imag);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* reading real and imaginary values */
+    real = *pSrc++;
+    imag = *pSrc++;
+
+    /* out = (real * real) + (imag * imag) */
+    /* store the result in the destination buffer. */
+    *pDst++ = (real * real) + (imag * imag);
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of cmplx_mag_squared group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q15.c
index 236199ee5..31fb79dfc 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q15.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q15.c
@@ -1,148 +1,148 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_mag_squared_q15.c   
-*   
-* Description:	Q15 complex magnitude squared.   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup cmplx_mag_squared   
- * @{   
- */
-
-/**   
- * @brief  Q15 complex magnitude squared   
- * @param  *pSrc points to the complex input vector   
- * @param  *pDst points to the real output vector   
- * @param  numSamples number of complex samples in the input vector   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function implements 1.15 by 1.15 multiplications and finally output is converted into 3.13 format.   
- */
-
-void arm_cmplx_mag_squared_q15(
-  q15_t * pSrc,
-  q15_t * pDst,
-  uint32_t numSamples)
-{
-  q15_t real, imag;                              /* Temporary variables to store real and imaginary values */
-  q31_t acc0, acc1;                              /* Accumulators */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = __SMUAD(real, real);
-    acc1 = __SMUAD(imag, imag);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = __SMUAD(real, real);
-    acc1 = __SMUAD(imag, imag);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = __SMUAD(real, real);
-    acc1 = __SMUAD(imag, imag);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = __SMUAD(real, real);
-    acc1 = __SMUAD(imag, imag);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = __SMUAD(real, real);
-    acc1 = __SMUAD(imag, imag);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* out = ((real * real) + (imag * imag)) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (real * real);
-    acc1 = (imag * imag);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of cmplx_mag_squared group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_mag_squared_q15.c   
+*   
+* Description:	Q15 complex magnitude squared.   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ---------------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup cmplx_mag_squared   
+ * @{   
+ */
+
+/**   
+ * @brief  Q15 complex magnitude squared   
+ * @param  *pSrc points to the complex input vector   
+ * @param  *pDst points to the real output vector   
+ * @param  numSamples number of complex samples in the input vector   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function implements 1.15 by 1.15 multiplications and finally output is converted into 3.13 format.   
+ */
+
+void arm_cmplx_mag_squared_q15(
+  q15_t * pSrc,
+  q15_t * pDst,
+  uint32_t numSamples)
+{
+  q15_t real, imag;                              /* Temporary variables to store real and imaginary values */
+  q31_t acc0, acc1;                              /* Accumulators */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+  /*loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = __SMUAD(real, real);
+    acc1 = __SMUAD(imag, imag);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = __SMUAD(real, real);
+    acc1 = __SMUAD(imag, imag);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = __SMUAD(real, real);
+    acc1 = __SMUAD(imag, imag);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = __SMUAD(real, real);
+    acc1 = __SMUAD(imag, imag);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = __SMUAD(real, real);
+    acc1 = __SMUAD(imag, imag);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* out = ((real * real) + (imag * imag)) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (real * real);
+    acc1 = (imag * imag);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of cmplx_mag_squared group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q31.c
index 2ebb98c1f..807632e3f 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q31.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q31.c
@@ -1,150 +1,150 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_cmplx_mag_squared_q31.c   
-*   
-* Description:	Q31 complex magnitude squared.   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup cmplx_mag_squared   
- * @{   
- */
-
-
-/**   
- * @brief  Q31 complex magnitude squared   
- * @param  *pSrc points to the complex input vector   
- * @param  *pDst points to the real output vector   
- * @param  numSamples number of complex samples in the input vector   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function implements 1.31 by 1.31 multiplications and finally output is converted into 3.29 format.   
- * Input down scaling is not required.   
- */
-
-void arm_cmplx_mag_squared_q31(
-  q31_t * pSrc,
-  q31_t * pDst,
-  uint32_t numSamples)
-{
-  q31_t real, imag;                              /* Temporary variables to store real and imaginary values */
-  q31_t acc0, acc1;                              /* Accumulators */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* out = ((real * real) + (imag * imag)) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of cmplx_mag_squared group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:		arm_cmplx_mag_squared_q31.c   
+*   
+* Description:	Q31 complex magnitude squared.   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ---------------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup cmplx_mag_squared   
+ * @{   
+ */
+
+
+/**   
+ * @brief  Q31 complex magnitude squared   
+ * @param  *pSrc points to the complex input vector   
+ * @param  *pDst points to the real output vector   
+ * @param  numSamples number of complex samples in the input vector   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function implements 1.31 by 1.31 multiplications and finally output is converted into 3.29 format.   
+ * Input down scaling is not required.   
+ */
+
+void arm_cmplx_mag_squared_q31(
+  q31_t * pSrc,
+  q31_t * pDst,
+  uint32_t numSamples)
+{
+  q31_t real, imag;                              /* Temporary variables to store real and imaginary values */
+  q31_t acc0, acc1;                              /* Accumulators */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counter */
+
+  /* loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = acc0 + acc1;
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = acc0 + acc1;
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = acc0 + acc1;
+
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = acc0 + acc1;
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = acc0 + acc1;
+
+    /* Decrement the loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* out = ((real * real) + (imag * imag)) */
+    real = *pSrc++;
+    imag = *pSrc++;
+    acc0 = (q31_t) (((q63_t) real * real) >> 33);
+    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = acc0 + acc1;
+
+    /* Decrement the loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of cmplx_mag_squared group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_f32.c
index 24b56f69c..4cdda3273 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_f32.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_f32.c
@@ -1,180 +1,180 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_cmplx_mult_cmplx_f32.c   
-*   
-* Description:	Floating-point complex-by-complex multiplication   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @defgroup CmplxByCmplxMult Complex-by-Complex Multiplication   
- *   
- * Multiplies a complex vector by another complex vector and generates a complex result.   
- * The data in the complex arrays is stored in an interleaved fashion   
- * (real, imag, real, imag, ...).   
- * The parameter numSamples represents the number of complex   
- * samples processed.  The complex arrays have a total of 2*numSamples   
- * real values.   
- *   
- * The underlying algorithm is used:   
- *   
- * 
   
- * for(n=0; n   
- *   
- * There are separate functions for floating-point, Q15, and Q31 data types.   
- */
-
-/**   
- * @addtogroup CmplxByCmplxMult   
- * @{   
- */
-
-
-/**   
- * @brief  Floating-point complex-by-complex multiplication   
- * @param[in]  *pSrcA points to the first input vector   
- * @param[in]  *pSrcB points to the second input vector   
- * @param[out]  *pDst  points to the output vector   
- * @param[in]  numSamples number of complex samples in each vector   
- * @return none.   
- */
-
-void arm_cmplx_mult_cmplx_f32(
-  float32_t * pSrcA,
-  float32_t * pSrcB,
-  float32_t * pDst,
-  uint32_t numSamples)
-{
-  float32_t a, b, c, d;                          /* Temporary variables to store real and imaginary values */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counters */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in the destination buffer. */
-    *pDst++ = (a * c) - (b * d);
-    *pDst++ = (a * d) + (b * c);
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    *pDst++ = (a * c) - (b * d);
-    *pDst++ = (a * d) + (b * c);
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    *pDst++ = (a * c) - (b * d);
-    *pDst++ = (a * d) + (b * c);
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    *pDst++ = (a * c) - (b * d);
-    *pDst++ = (a * d) + (b * c);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in the destination buffer. */
-    *pDst++ = (a * c) - (b * d);
-    *pDst++ = (a * d) + (b * c);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in the destination buffer. */
-    *pDst++ = (a * c) - (b * d);
-    *pDst++ = (a * d) + (b * c);
-
-    /* Decrement the numSamples loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of CmplxByCmplxMult group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_cmplx_mult_cmplx_f32.c   
+*   
+* Description:	Floating-point complex-by-complex multiplication   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* -------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @defgroup CmplxByCmplxMult Complex-by-Complex Multiplication   
+ *   
+ * Multiplies a complex vector by another complex vector and generates a complex result.   
+ * The data in the complex arrays is stored in an interleaved fashion   
+ * (real, imag, real, imag, ...).   
+ * The parameter numSamples represents the number of complex   
+ * samples processed.  The complex arrays have a total of 2*numSamples   
+ * real values.   
+ *   
+ * The underlying algorithm is used:   
+ *   
+ * 
   
+ * for(n=0; n   
+ *   
+ * There are separate functions for floating-point, Q15, and Q31 data types.   
+ */
+
+/**   
+ * @addtogroup CmplxByCmplxMult   
+ * @{   
+ */
+
+
+/**   
+ * @brief  Floating-point complex-by-complex multiplication   
+ * @param[in]  *pSrcA points to the first input vector   
+ * @param[in]  *pSrcB points to the second input vector   
+ * @param[out]  *pDst  points to the output vector   
+ * @param[in]  numSamples number of complex samples in each vector   
+ * @return none.   
+ */
+
+void arm_cmplx_mult_cmplx_f32(
+  float32_t * pSrcA,
+  float32_t * pSrcB,
+  float32_t * pDst,
+  uint32_t numSamples)
+{
+  float32_t a, b, c, d;                          /* Temporary variables to store real and imaginary values */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counters */
+
+  /* loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
+    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in the destination buffer. */
+    *pDst++ = (a * c) - (b * d);
+    *pDst++ = (a * d) + (b * c);
+
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    *pDst++ = (a * c) - (b * d);
+    *pDst++ = (a * d) + (b * c);
+
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    *pDst++ = (a * c) - (b * d);
+    *pDst++ = (a * d) + (b * c);
+
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    *pDst++ = (a * c) - (b * d);
+    *pDst++ = (a * d) + (b * c);
+
+    /* Decrement the numSamples loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
+    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in the destination buffer. */
+    *pDst++ = (a * c) - (b * d);
+    *pDst++ = (a * d) + (b * c);
+
+    /* Decrement the numSamples loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
+    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in the destination buffer. */
+    *pDst++ = (a * c) - (b * d);
+    *pDst++ = (a * d) + (b * c);
+
+    /* Decrement the numSamples loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of CmplxByCmplxMult group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q15.c
index ff6606101..b31e1bddb 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q15.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q15.c
@@ -1,182 +1,182 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_cmplx_mult_cmplx_q15.c   
-*   
-* Description:	Q15 complex-by-complex multiplication   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup CmplxByCmplxMult   
- * @{   
- */
-
-/**   
- * @brief  Q15 complex-by-complex multiplication   
- * @param[in]  *pSrcA points to the first input vector   
- * @param[in]  *pSrcB points to the second input vector   
- * @param[out]  *pDst  points to the output vector   
- * @param[in]  numSamples number of complex samples in each vector   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function implements 1.15 by 1.15 multiplications and finally output is converted into 3.13 format.   
- */
-
-void arm_cmplx_mult_cmplx_q15(
-  q15_t * pSrcA,
-  q15_t * pSrcB,
-  q15_t * pDst,
-  uint32_t numSamples)
-{
-  q15_t a, b, c, d;                              /* Temporary variables to store real and imaginary values */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counters */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-  /* If the blockSize is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    /* Decrement the blockSize loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of CmplxByCmplxMult group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_cmplx_mult_cmplx_q15.c   
+*   
+* Description:	Q15 complex-by-complex multiplication   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* -------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup CmplxByCmplxMult   
+ * @{   
+ */
+
+/**   
+ * @brief  Q15 complex-by-complex multiplication   
+ * @param[in]  *pSrcA points to the first input vector   
+ * @param[in]  *pSrcB points to the second input vector   
+ * @param[out]  *pDst  points to the output vector   
+ * @param[in]  numSamples number of complex samples in each vector   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function implements 1.15 by 1.15 multiplications and finally output is converted into 3.13 format.   
+ */
+
+void arm_cmplx_mult_cmplx_q15(
+  q15_t * pSrcA,
+  q15_t * pSrcB,
+  q15_t * pDst,
+  uint32_t numSamples)
+{
+  q15_t a, b, c, d;                              /* Temporary variables to store real and imaginary values */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counters */
+
+  /* loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
+    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
+
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
+
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
+
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
+
+    /* Decrement the blockSize loop counter */
+    blkCnt--;
+  }
+
+  /* If the blockSize is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
+    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
+
+    /* Decrement the blockSize loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
+    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
+    /* store the result in 3.13 format in the destination buffer. */
+    *pDst++ =
+      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
+
+    /* Decrement the blockSize loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of CmplxByCmplxMult group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q31.c
index 059ae50b1..ba8e352fa 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q31.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q31.c
@@ -1,209 +1,209 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_cmplx_mult_cmplx_q31.c   
-*   
-* Description:	Q31 complex-by-complex multiplication   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup CmplxByCmplxMult   
- * @{   
- */
-
-
-/**   
- * @brief  Q31 complex-by-complex multiplication   
- * @param[in]  *pSrcA points to the first input vector   
- * @param[in]  *pSrcB points to the second input vector   
- * @param[out]  *pDst  points to the output vector   
- * @param[in]  numSamples number of complex samples in each vector   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function implements 1.31 by 1.31 multiplications and finally output is converted into 3.29 format.   
- * Input down scaling is not required.   
- */
-
-void arm_cmplx_mult_cmplx_q31(
-  q31_t * pSrcA,
-  q31_t * pSrcB,
-  q31_t * pDst,
-  uint32_t numSamples)
-{
-  q31_t a, b, c, d;                              /* Temporary variables to store real and imaginary values */
-  uint32_t blkCnt;                               /* loop counters */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the real result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
-    /* store the imag result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-  /* If the blockSize is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 1u;
-
-  /* First part of the processing with loop unrolling.  Compute 2 outputs at a time.    
-   ** a second loop below computes the remaining 1 sample. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the real result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
-    /* store the imag result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-  /* If the blockSize is not a multiple of 2, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x2u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of CmplxByCmplxMult group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_cmplx_mult_cmplx_q31.c   
+*   
+* Description:	Q31 complex-by-complex multiplication   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* -------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup CmplxByCmplxMult   
+ * @{   
+ */
+
+
+/**   
+ * @brief  Q31 complex-by-complex multiplication   
+ * @param[in]  *pSrcA points to the first input vector   
+ * @param[in]  *pSrcB points to the second input vector   
+ * @param[out]  *pDst  points to the output vector   
+ * @param[in]  numSamples number of complex samples in each vector   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function implements 1.31 by 1.31 multiplications and finally output is converted into 3.29 format.   
+ * Input down scaling is not required.   
+ */
+
+void arm_cmplx_mult_cmplx_q31(
+  q31_t * pSrcA,
+  q31_t * pSrcB,
+  q31_t * pDst,
+  uint32_t numSamples)
+{
+  q31_t a, b, c, d;                              /* Temporary variables to store real and imaginary values */
+  uint32_t blkCnt;                               /* loop counters */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+
+  /* loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
+    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the real result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
+    /* store the imag result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
+
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
+
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
+
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
+
+    /* Decrement the blockSize loop counter */
+    blkCnt--;
+  }
+
+  /* If the blockSize is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
+    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
+
+    /* Decrement the blockSize loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  /* loop Unrolling */
+  blkCnt = numSamples >> 1u;
+
+  /* First part of the processing with loop unrolling.  Compute 2 outputs at a time.    
+   ** a second loop below computes the remaining 1 sample. */
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
+    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the real result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
+    /* store the imag result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
+
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
+
+    /* Decrement the blockSize loop counter */
+    blkCnt--;
+  }
+
+  /* If the blockSize is not a multiple of 2, compute any remaining output samples here.    
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x2u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
+    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
+    a = *pSrcA++;
+    b = *pSrcA++;
+    c = *pSrcB++;
+    d = *pSrcB++;
+
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * c) >> 33) - (((q63_t) b * d) >> 33));
+    /* store the result in 3.29 format in the destination buffer. */
+    *pDst++ = (q31_t) ((((q63_t) a * d) >> 33) + (((q63_t) b * c) >> 33));
+
+    /* Decrement the blockSize loop counter */
+    blkCnt--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of CmplxByCmplxMult group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_f32.c
index b09c34fdd..5d00cdcb1 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_f32.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_f32.c
@@ -1,157 +1,157 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_cmplx_mult_real_f32.c   
-*   
-* Description:	Floating-point complex by real multiplication   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @defgroup CmplxByRealMult Complex-by-Real Multiplication   
- *   
- * Multiplies a complex vector by a real vector and generates a complex result.   
- * The data in the complex arrays is stored in an interleaved fashion   
- * (real, imag, real, imag, ...).   
- * The parameter numSamples represents the number of complex   
- * samples processed.  The complex arrays have a total of 2*numSamples   
- * real values while the real array has a total of numSamples   
- * real values.   
- *   
- * The underlying algorithm is used:   
- *   
- * 
   
- * for(n=0; n   
- *   
- * There are separate functions for floating-point, Q15, and Q31 data types.   
- */
-
-/**   
- * @addtogroup CmplxByRealMult   
- * @{   
- */
-
-
-/**   
- * @brief  Floating-point complex-by-real multiplication   
- * @param[in]  *pSrcCmplx points to the complex input vector   
- * @param[in]  *pSrcReal points to the real input vector   
- * @param[out]  *pCmplxDst points to the complex output vector   
- * @param[in]  numSamples number of samples in each vector   
- * @return none.   
- */
-
-void arm_cmplx_mult_real_f32(
-  float32_t * pSrcCmplx,
-  float32_t * pSrcReal,
-  float32_t * pCmplxDst,
-  uint32_t numSamples)
-{
-  float32_t in;                                  /* Temporary variable to store input value */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counters */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-
-    in = *pSrcReal++;
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-
-    in = *pSrcReal++;
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-
-    in = *pSrcReal++;
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* realOut = realA * realB.            */
-    /* imagOut = imagA * realB.                */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-
-    /* Decrement the numSamples loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of CmplxByRealMult group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_cmplx_mult_real_f32.c   
+*   
+* Description:	Floating-point complex by real multiplication   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* -------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @defgroup CmplxByRealMult Complex-by-Real Multiplication   
+ *   
+ * Multiplies a complex vector by a real vector and generates a complex result.   
+ * The data in the complex arrays is stored in an interleaved fashion   
+ * (real, imag, real, imag, ...).   
+ * The parameter numSamples represents the number of complex   
+ * samples processed.  The complex arrays have a total of 2*numSamples   
+ * real values while the real array has a total of numSamples   
+ * real values.   
+ *   
+ * The underlying algorithm is used:   
+ *   
+ * 
   
+ * for(n=0; n   
+ *   
+ * There are separate functions for floating-point, Q15, and Q31 data types.   
+ */
+
+/**   
+ * @addtogroup CmplxByRealMult   
+ * @{   
+ */
+
+
+/**   
+ * @brief  Floating-point complex-by-real multiplication   
+ * @param[in]  *pSrcCmplx points to the complex input vector   
+ * @param[in]  *pSrcReal points to the real input vector   
+ * @param[out]  *pCmplxDst points to the complex output vector   
+ * @param[in]  numSamples number of samples in each vector   
+ * @return none.   
+ */
+
+void arm_cmplx_mult_real_f32(
+  float32_t * pSrcCmplx,
+  float32_t * pSrcReal,
+  float32_t * pCmplxDst,
+  uint32_t numSamples)
+{
+  float32_t in;                                  /* Temporary variable to store input value */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counters */
+
+  /* loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[i].            */
+    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
+    in = *pSrcReal++;
+    /* store the result in the destination buffer. */
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+
+    in = *pSrcReal++;
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+
+    in = *pSrcReal++;
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+
+    in = *pSrcReal++;
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+
+    /* Decrement the numSamples loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[i].            */
+    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
+    in = *pSrcReal++;
+    /* store the result in the destination buffer. */
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+
+    /* Decrement the numSamples loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* realOut = realA * realB.            */
+    /* imagOut = imagA * realB.                */
+    in = *pSrcReal++;
+    /* store the result in the destination buffer. */
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+    *pCmplxDst++ = (*pSrcCmplx++) * (in);
+
+    /* Decrement the numSamples loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of CmplxByRealMult group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q15.c
index 3f95021b0..253fc20e6 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q15.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q15.c
@@ -1,151 +1,151 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_cmplx_mult_real_q15.c   
-*   
-* Description:	Q15 complex by real multiplication   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup CmplxByRealMult   
- * @{   
- */
-
-
-/**   
- * @brief  Q15 complex-by-real multiplication   
- * @param[in]  *pSrcCmplx points to the complex input vector   
- * @param[in]  *pSrcReal points to the real input vector   
- * @param[out]  *pCmplxDst points to the complex output vector   
- * @param[in]  numSamples number of samples in each vector   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function uses saturating arithmetic.   
- * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated.   
- */
-
-void arm_cmplx_mult_real_q15(
-  q15_t * pSrcCmplx,
-  q15_t * pSrcReal,
-  q15_t * pCmplxDst,
-  uint32_t numSamples)
-{
-  q15_t in;                                      /* Temporary variable to store input value */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counters */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-
-    in = *pSrcReal++;
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-
-    in = *pSrcReal++;
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-
-    in = *pSrcReal++;
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* realOut = realA * realB.            */
-    /* imagOut = imagA * realB.                */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-
-    /* Decrement the numSamples loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of CmplxByRealMult group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_cmplx_mult_real_q15.c   
+*   
+* Description:	Q15 complex by real multiplication   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* -------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup CmplxByRealMult   
+ * @{   
+ */
+
+
+/**   
+ * @brief  Q15 complex-by-real multiplication   
+ * @param[in]  *pSrcCmplx points to the complex input vector   
+ * @param[in]  *pSrcReal points to the real input vector   
+ * @param[out]  *pCmplxDst points to the complex output vector   
+ * @param[in]  numSamples number of samples in each vector   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function uses saturating arithmetic.   
+ * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated.   
+ */
+
+void arm_cmplx_mult_real_q15(
+  q15_t * pSrcCmplx,
+  q15_t * pSrcReal,
+  q15_t * pCmplxDst,
+  uint32_t numSamples)
+{
+  q15_t in;                                      /* Temporary variable to store input value */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counters */
+
+  /* loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[i].            */
+    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
+    in = *pSrcReal++;
+    /* store the result in the destination buffer. */
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+
+    in = *pSrcReal++;
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+
+    in = *pSrcReal++;
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+
+    in = *pSrcReal++;
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+
+    /* Decrement the numSamples loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[i].            */
+    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
+    in = *pSrcReal++;
+    /* store the result in the destination buffer. */
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+
+    /* Decrement the numSamples loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* realOut = realA * realB.            */
+    /* imagOut = imagA * realB.                */
+    in = *pSrcReal++;
+    /* store the result in the destination buffer. */
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+    *pCmplxDst++ =
+      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
+
+    /* Decrement the numSamples loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of CmplxByRealMult group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q31.c
index 887222ce7..cb5f9d7d4 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q31.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q31.c
@@ -1,151 +1,151 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_cmplx_mult_real_q31.c   
-*   
-* Description:	Q31 complex by real multiplication   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupCmplxMath   
- */
-
-/**   
- * @addtogroup CmplxByRealMult   
- * @{   
- */
-
-
-/**   
- * @brief  Q31 complex-by-real multiplication   
- * @param[in]  *pSrcCmplx points to the complex input vector   
- * @param[in]  *pSrcReal points to the real input vector   
- * @param[out]  *pCmplxDst points to the complex output vector   
- * @param[in]  numSamples number of samples in each vector   
- * @return none.   
- *   
- * Scaling and Overflow Behavior:   
- * \par   
- * The function uses saturating arithmetic.   
- * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated.   
- */
-
-void arm_cmplx_mult_real_q31(
-  q31_t * pSrcCmplx,
-  q31_t * pSrcReal,
-  q31_t * pCmplxDst,
-  uint32_t numSamples)
-{
-  q31_t in;                                      /* Temporary variable to store input value */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counters */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-
-    in = *pSrcReal++;
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-
-    in = *pSrcReal++;
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-
-    in = *pSrcReal++;
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* realOut = realA * realB.            */
-    /* imagReal = imagA * realB.               */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
-
-    /* Decrement the numSamples loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of CmplxByRealMult group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_cmplx_mult_real_q31.c   
+*   
+* Description:	Q31 complex by real multiplication   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* -------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+/**   
+ * @ingroup groupCmplxMath   
+ */
+
+/**   
+ * @addtogroup CmplxByRealMult   
+ * @{   
+ */
+
+
+/**   
+ * @brief  Q31 complex-by-real multiplication   
+ * @param[in]  *pSrcCmplx points to the complex input vector   
+ * @param[in]  *pSrcReal points to the real input vector   
+ * @param[out]  *pCmplxDst points to the complex output vector   
+ * @param[in]  numSamples number of samples in each vector   
+ * @return none.   
+ *   
+ * Scaling and Overflow Behavior:   
+ * \par   
+ * The function uses saturating arithmetic.   
+ * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated.   
+ */
+
+void arm_cmplx_mult_real_q31(
+  q31_t * pSrcCmplx,
+  q31_t * pSrcReal,
+  q31_t * pCmplxDst,
+  uint32_t numSamples)
+{
+  q31_t in;                                      /* Temporary variable to store input value */
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+  uint32_t blkCnt;                               /* loop counters */
+
+  /* loop Unrolling */
+  blkCnt = numSamples >> 2u;
+
+  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.   
+   ** a second loop below computes the remaining 1 to 3 samples. */
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[i].            */
+    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
+    in = *pSrcReal++;
+    /* store the result in the destination buffer. */
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+
+    in = *pSrcReal++;
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+
+    in = *pSrcReal++;
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+
+    in = *pSrcReal++;
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+
+    /* Decrement the numSamples loop counter */
+    blkCnt--;
+  }
+
+  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.   
+   ** No loop unrolling is used. */
+  blkCnt = numSamples % 0x4u;
+
+  while(blkCnt > 0u)
+  {
+    /* C[2 * i] = A[2 * i] * B[i].            */
+    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
+    in = *pSrcReal++;
+    /* store the result in the destination buffer. */
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+
+    /* Decrement the numSamples loop counter */
+    blkCnt--;
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  while(numSamples > 0u)
+  {
+    /* realOut = realA * realB.            */
+    /* imagReal = imagA * realB.               */
+    in = *pSrcReal++;
+    /* store the result in the destination buffer. */
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+    *pCmplxDst++ =
+      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * in) >> 31);
+
+    /* Decrement the numSamples loop counter */
+    numSamples--;
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of CmplxByRealMult group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_f32.c
index f8e1c2e05..3fd65094c 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_f32.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_f32.c
@@ -1,76 +1,76 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_pid_init_f32.c   
-*   
-* Description:	Floating-point PID Control initialization function   
-*				  
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**   
- * @addtogroup PID   
- * @{   
- */
-
-/**   
- * @brief  Initialization function for the floating-point PID Control.  
- * @param[in,out] *S points to an instance of the PID structure.  
- * @param[in]     resetStateFlag  flag to reset the state. 0 = no change in state & 1 = reset the state.  
- * @return none.  
- * \par Description:  
- * \par   
- * The resetStateFlag specifies whether to set state to zero or not. \n  
- * The function computes the structure fields: A0, A1 A2   
- * using the proportional gain( \c Kp), integral gain( \c Ki) and derivative gain( \c Kd)   
- * also sets the state variables to all zeros.   
- */
-
-void arm_pid_init_f32(
-  arm_pid_instance_f32 * S,
-  int32_t resetStateFlag)
-{
-
-  /* Derived coefficient A0 */
-  S->A0 = S->Kp + S->Ki + S->Kd;
-
-  /* Derived coefficient A1 */
-  S->A1 = (-S->Kp) - ((float32_t) 2.0 * S->Kd);
-
-  /* Derived coefficient A2 */
-  S->A2 = S->Kd;
-
-  /* Check whether state needs reset or not */
-  if(resetStateFlag)
-  {
-    /* Clear the state buffer.  The size will be always 3 samples */
-    memset(S->state, 0, 3u * sizeof(float32_t));
-  }
-
-}
-
-/**   
- * @} end of PID group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_pid_init_f32.c   
+*   
+* Description:	Floating-point PID Control initialization function   
+*				  
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+ /**   
+ * @addtogroup PID   
+ * @{   
+ */
+
+/**   
+ * @brief  Initialization function for the floating-point PID Control.  
+ * @param[in,out] *S points to an instance of the PID structure.  
+ * @param[in]     resetStateFlag  flag to reset the state. 0 = no change in state & 1 = reset the state.  
+ * @return none.  
+ * \par Description:  
+ * \par   
+ * The resetStateFlag specifies whether to set state to zero or not. \n  
+ * The function computes the structure fields: A0, A1 A2   
+ * using the proportional gain( \c Kp), integral gain( \c Ki) and derivative gain( \c Kd)   
+ * also sets the state variables to all zeros.   
+ */
+
+void arm_pid_init_f32(
+  arm_pid_instance_f32 * S,
+  int32_t resetStateFlag)
+{
+
+  /* Derived coefficient A0 */
+  S->A0 = S->Kp + S->Ki + S->Kd;
+
+  /* Derived coefficient A1 */
+  S->A1 = (-S->Kp) - ((float32_t) 2.0 * S->Kd);
+
+  /* Derived coefficient A2 */
+  S->A2 = S->Kd;
+
+  /* Check whether state needs reset or not */
+  if(resetStateFlag)
+  {
+    /* Clear the state buffer.  The size will be always 3 samples */
+    memset(S->state, 0, 3u * sizeof(float32_t));
+  }
+
+}
+
+/**   
+ * @} end of PID group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q15.c
index f7e1e7e6f..c1a09e503 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q15.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q15.c
@@ -1,111 +1,111 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_pid_init_q15.c   
-*   
-* Description:	Q15 PID Control initialization function   
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**   
- * @addtogroup PID   
- * @{   
- */
-
-/**   
- * @details   
- * @param[in,out] *S points to an instance of the Q15 PID structure.   
- * @param[in]     resetStateFlag  flag to reset the state. 0 = no change in state 1 = reset the state.   
- * @return none.   
- * \par Description:  
- * \par   
- * The resetStateFlag specifies whether to set state to zero or not. \n  
- * The function computes the structure fields: A0, A1 A2   
- * using the proportional gain( \c Kp), integral gain( \c Ki) and derivative gain( \c Kd)   
- * also sets the state variables to all zeros.   
- */
-
-void arm_pid_init_q15(
-  arm_pid_instance_q15 * S,
-  int32_t resetStateFlag)
-{
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-
-  /* Derived coefficient A0 */
-  S->A0 = __QADD16(__QADD16(S->Kp, S->Ki), S->Kd);
-
-  /* Derived coefficients and pack into A1 */
-
-#ifndef  ARM_MATH_BIG_ENDIAN
-
-  S->A1 = __PKHBT(-__QADD16(__QADD16(S->Kd, S->Kd), S->Kp), S->Kd, 16);
-
-#else
-
-  S->A1 = __PKHBT(S->Kd, -__QADD16(__QADD16(S->Kd, S->Kd), S->Kp), 16);
-
-#endif /*      #ifndef  ARM_MATH_BIG_ENDIAN    */
-
-  /* Check whether state needs reset or not */
-  if(resetStateFlag)
-  {
-    /* Clear the state buffer.  The size will be always 3 samples */
-    memset(S->state, 0, 3u * sizeof(q15_t));
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  q31_t temp;                                    /*to store the sum */
-
-  /* Derived coefficient A0 */
-  temp = S->Kp + S->Ki + S->Kd;
-  S->A0 = (q15_t) __SSAT(temp, 16);
-
-  /* Derived coefficients and pack into A1 */
-  temp = -(S->Kd + S->Kd + S->Kp);
-  S->A1 = (q15_t) __SSAT(temp, 16);
-  S->A2 = S->Kd;
-
-
-
-  /* Check whether state needs reset or not */
-  if(resetStateFlag)
-  {
-    /* Clear the state buffer.  The size will be always 3 samples */
-    memset(S->state, 0, 3u * sizeof(q15_t));
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**   
- * @} end of PID group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_pid_init_q15.c   
+*   
+* Description:	Q15 PID Control initialization function   
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* -------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+ /**   
+ * @addtogroup PID   
+ * @{   
+ */
+
+/**   
+ * @details   
+ * @param[in,out] *S points to an instance of the Q15 PID structure.   
+ * @param[in]     resetStateFlag  flag to reset the state. 0 = no change in state 1 = reset the state.   
+ * @return none.   
+ * \par Description:  
+ * \par   
+ * The resetStateFlag specifies whether to set state to zero or not. \n  
+ * The function computes the structure fields: A0, A1 A2   
+ * using the proportional gain( \c Kp), integral gain( \c Ki) and derivative gain( \c Kd)   
+ * also sets the state variables to all zeros.   
+ */
+
+void arm_pid_init_q15(
+  arm_pid_instance_q15 * S,
+  int32_t resetStateFlag)
+{
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+
+  /* Derived coefficient A0 */
+  S->A0 = __QADD16(__QADD16(S->Kp, S->Ki), S->Kd);
+
+  /* Derived coefficients and pack into A1 */
+
+#ifndef  ARM_MATH_BIG_ENDIAN
+
+  S->A1 = __PKHBT(-__QADD16(__QADD16(S->Kd, S->Kd), S->Kp), S->Kd, 16);
+
+#else
+
+  S->A1 = __PKHBT(S->Kd, -__QADD16(__QADD16(S->Kd, S->Kd), S->Kp), 16);
+
+#endif /*      #ifndef  ARM_MATH_BIG_ENDIAN    */
+
+  /* Check whether state needs reset or not */
+  if(resetStateFlag)
+  {
+    /* Clear the state buffer.  The size will be always 3 samples */
+    memset(S->state, 0, 3u * sizeof(q15_t));
+  }
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  q31_t temp;                                    /*to store the sum */
+
+  /* Derived coefficient A0 */
+  temp = S->Kp + S->Ki + S->Kd;
+  S->A0 = (q15_t) __SSAT(temp, 16);
+
+  /* Derived coefficients and pack into A1 */
+  temp = -(S->Kd + S->Kd + S->Kp);
+  S->A1 = (q15_t) __SSAT(temp, 16);
+  S->A2 = S->Kd;
+
+
+
+  /* Check whether state needs reset or not */
+  if(resetStateFlag)
+  {
+    /* Clear the state buffer.  The size will be always 3 samples */
+    memset(S->state, 0, 3u * sizeof(q15_t));
+  }
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+}
+
+/**   
+ * @} end of PID group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q31.c
index 22b05f228..78f1d3ef2 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q31.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q31.c
@@ -1,96 +1,96 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_pid_init_q31.c   
-*   
-* Description:	Q31 PID Control initialization function    
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**   
- * @addtogroup PID   
- * @{   
- */
-
-/**   
- * @brief  Initialization function for the Q31 PID Control.  
- * @param[in,out] *S points to an instance of the Q31 PID structure.  
- * @param[in]     resetStateFlag  flag to reset the state. 0 = no change in state 1 = reset the state.  
- * @return none.   
- * \par Description:  
- * \par   
- * The resetStateFlag specifies whether to set state to zero or not. \n  
- * The function computes the structure fields: A0, A1 A2   
- * using the proportional gain( \c Kp), integral gain( \c Ki) and derivative gain( \c Kd)   
- * also sets the state variables to all zeros.   
- */
-
-void arm_pid_init_q31(
-  arm_pid_instance_q31 * S,
-  int32_t resetStateFlag)
-{
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-
-  /* Derived coefficient A0 */
-  S->A0 = __QADD(__QADD(S->Kp, S->Ki), S->Kd);
-
-  /* Derived coefficient A1 */
-  S->A1 = -__QADD(__QADD(S->Kd, S->Kd), S->Kp);
-
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  q31_t temp;
-
-  /* Derived coefficient A0 */
-  temp = clip_q63_to_q31((q63_t) S->Kp + S->Ki);
-  S->A0 = clip_q63_to_q31((q63_t) temp + S->Kd);
-
-  /* Derived coefficient A1 */
-  temp = clip_q63_to_q31((q63_t) S->Kd + S->Kd);
-  S->A1 = -clip_q63_to_q31((q63_t) temp + S->Kp);
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  /* Derived coefficient A2 */
-  S->A2 = S->Kd;
-
-  /* Check whether state needs reset or not */
-  if(resetStateFlag)
-  {
-    /* Clear the state buffer.  The size will be always 3 samples */
-    memset(S->state, 0, 3u * sizeof(q31_t));
-  }
-
-}
-
-/**   
- * @} end of PID group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_pid_init_q31.c   
+*   
+* Description:	Q31 PID Control initialization function    
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+ /**   
+ * @addtogroup PID   
+ * @{   
+ */
+
+/**   
+ * @brief  Initialization function for the Q31 PID Control.  
+ * @param[in,out] *S points to an instance of the Q31 PID structure.  
+ * @param[in]     resetStateFlag  flag to reset the state. 0 = no change in state 1 = reset the state.  
+ * @return none.   
+ * \par Description:  
+ * \par   
+ * The resetStateFlag specifies whether to set state to zero or not. \n  
+ * The function computes the structure fields: A0, A1 A2   
+ * using the proportional gain( \c Kp), integral gain( \c Ki) and derivative gain( \c Kd)   
+ * also sets the state variables to all zeros.   
+ */
+
+void arm_pid_init_q31(
+  arm_pid_instance_q31 * S,
+  int32_t resetStateFlag)
+{
+
+#ifndef ARM_MATH_CM0
+
+  /* Run the below code for Cortex-M4 and Cortex-M3 */
+
+  /* Derived coefficient A0 */
+  S->A0 = __QADD(__QADD(S->Kp, S->Ki), S->Kd);
+
+  /* Derived coefficient A1 */
+  S->A1 = -__QADD(__QADD(S->Kd, S->Kd), S->Kp);
+
+
+#else
+
+  /* Run the below code for Cortex-M0 */
+
+  q31_t temp;
+
+  /* Derived coefficient A0 */
+  temp = clip_q63_to_q31((q63_t) S->Kp + S->Ki);
+  S->A0 = clip_q63_to_q31((q63_t) temp + S->Kd);
+
+  /* Derived coefficient A1 */
+  temp = clip_q63_to_q31((q63_t) S->Kd + S->Kd);
+  S->A1 = -clip_q63_to_q31((q63_t) temp + S->Kp);
+
+#endif /* #ifndef ARM_MATH_CM0 */
+
+  /* Derived coefficient A2 */
+  S->A2 = S->Kd;
+
+  /* Check whether state needs reset or not */
+  if(resetStateFlag)
+  {
+    /* Clear the state buffer.  The size will be always 3 samples */
+    memset(S->state, 0, 3u * sizeof(q31_t));
+  }
+
+}
+
+/**   
+ * @} end of PID group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_f32.c
index 51baa6fa4..4d2feda28 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_f32.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_f32.c
@@ -1,54 +1,54 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_pid_reset_f32.c   
-*   
-* Description:	Floating-point PID Control reset function  
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**   
- * @addtogroup PID   
- * @{   
- */
-
-/**   
-* @brief  Reset function for the floating-point PID Control.  
-* @param[in] *S	Instance pointer of PID control data structure.  
-* @return none.   
-* \par Description:  
-* The function resets the state buffer to zeros.   
-*/
-void arm_pid_reset_f32(
-  arm_pid_instance_f32 * S)
-{
-
-  /* Clear the state buffer.  The size will be always 3 samples */
-  memset(S->state, 0, 3u * sizeof(float32_t));
-}
-
-/**   
- * @} end of PID group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_pid_reset_f32.c   
+*   
+* Description:	Floating-point PID Control reset function  
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+ /**   
+ * @addtogroup PID   
+ * @{   
+ */
+
+/**   
+* @brief  Reset function for the floating-point PID Control.  
+* @param[in] *S	Instance pointer of PID control data structure.  
+* @return none.   
+* \par Description:  
+* The function resets the state buffer to zeros.   
+*/
+void arm_pid_reset_f32(
+  arm_pid_instance_f32 * S)
+{
+
+  /* Clear the state buffer.  The size will be always 3 samples */
+  memset(S->state, 0, 3u * sizeof(float32_t));
+}
+
+/**   
+ * @} end of PID group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q15.c
index e71460c15..b6200f1f8 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q15.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q15.c
@@ -1,53 +1,53 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_pid_reset_q15.c   
-*   
-* Description:	Q15 PID Control reset function  
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**   
- * @addtogroup PID   
- * @{   
- */
-
-/**   
-* @brief  Reset function for the Q15 PID Control.  
-* @param[in] *S		Instance pointer of PID control data structure.  
-* @return none.   
-* \par Description:  
-* The function resets the state buffer to zeros.   
-*/
-void arm_pid_reset_q15(
-  arm_pid_instance_q15 * S)
-{
-  /* Reset state to zero, The size will be always 3 samples */
-  memset(S->state, 0, 3u * sizeof(q15_t));
-}
-
-/**   
- * @} end of PID group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_pid_reset_q15.c   
+*   
+* Description:	Q15 PID Control reset function  
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* -------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+ /**   
+ * @addtogroup PID   
+ * @{   
+ */
+
+/**   
+* @brief  Reset function for the Q15 PID Control.  
+* @param[in] *S		Instance pointer of PID control data structure.  
+* @return none.   
+* \par Description:  
+* The function resets the state buffer to zeros.   
+*/
+void arm_pid_reset_q15(
+  arm_pid_instance_q15 * S)
+{
+  /* Reset state to zero, The size will be always 3 samples */
+  memset(S->state, 0, 3u * sizeof(q15_t));
+}
+
+/**   
+ * @} end of PID group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q31.c
index 9714fed62..0b609a4dc 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q31.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q31.c
@@ -1,54 +1,54 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:	    arm_pid_reset_q31.c   
-*   
-* Description:	Q31 PID Control reset function  
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* ------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**   
- * @addtogroup PID   
- * @{   
- */
-
-/**   
-* @brief  Reset function for the Q31 PID Control.  
-* @param[in] *S	Instance pointer of PID control data structure.  
-* @return none.   
-* \par Description:  
-* The function resets the state buffer to zeros.   
-*/
-void arm_pid_reset_q31(
-  arm_pid_instance_q31 * S)
-{
-
-  /* Clear the state buffer.  The size will be always 3 samples */
-  memset(S->state, 0, 3u * sizeof(q31_t));
-}
-
-/**   
- * @} end of PID group   
- */
+/* ----------------------------------------------------------------------   
+* Copyright (C) 2010 ARM Limited. All rights reserved.   
+*   
+* $Date:        15. July 2011  
+* $Revision: 	V1.0.10  
+*   
+* Project: 	    CMSIS DSP Library   
+* Title:	    arm_pid_reset_q31.c   
+*   
+* Description:	Q31 PID Control reset function  
+*   
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*  
+* Version 1.0.10 2011/7/15 
+*    Big Endian support added and Merged M0 and M3/M4 Source code.  
+*   
+* Version 1.0.3 2010/11/29  
+*    Re-organized the CMSIS folders and updated documentation.   
+*    
+* Version 1.0.2 2010/11/11   
+*    Documentation updated.    
+*   
+* Version 1.0.1 2010/10/05    
+*    Production release and review comments incorporated.   
+*   
+* Version 1.0.0 2010/09/20    
+*    Production release and review comments incorporated.   
+* ------------------------------------------------------------------- */
+
+#include "arm_math.h"
+
+ /**   
+ * @addtogroup PID   
+ * @{   
+ */
+
+/**   
+* @brief  Reset function for the Q31 PID Control.  
+* @param[in] *S	Instance pointer of PID control data structure.  
+* @return none.   
+* \par Description:  
+* The function resets the state buffer to zeros.   
+*/
+void arm_pid_reset_q31(
+  arm_pid_instance_q31 * S)
+{
+
+  /* Clear the state buffer.  The size will be always 3 samples */
+  memset(S->state, 0, 3u * sizeof(q31_t));
+}
+
+/**   
+ * @} end of PID group   
+ */
diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_f32.c
index b7c10ec03..6eded6d6b 100644
--- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_f32.c
+++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_f32.c
@@ -1,408 +1,408 @@
-/* ----------------------------------------------------------------------   
-* Copyright (C) 2010 ARM Limited. All rights reserved.   
-*   
-* $Date:        15. July 2011  
-* $Revision: 	V1.0.10  
-*   
-* Project: 	    CMSIS DSP Library   
-* Title:		arm_sin_cos_f32.c   
-*   
-* Description:	Sine and Cosine calculation for floating-point values.  
-*   
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.0.10 2011/7/15 
-*    Big Endian support added and Merged M0 and M3/M4 Source code.  
-*   
-* Version 1.0.3 2010/11/29  
-*    Re-organized the CMSIS folders and updated documentation.   
-*    
-* Version 1.0.2 2010/11/11   
-*    Documentation updated.    
-*   
-* Version 1.0.1 2010/10/05    
-*    Production release and review comments incorporated.   
-*   
-* Version 1.0.0 2010/09/20    
-*    Production release and review comments incorporated.   
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**   
- * @ingroup groupController   
- */
-
-/**   
- * @defgroup SinCos Sine Cosine  
- *   
- * Computes the trigonometric sine and cosine values using a combination of table lookup  
- * and linear interpolation.    
- * There are separate functions for Q31 and floating-point data types.  
- * The input to the floating-point version is in degrees while the  
- * fixed-point Q31 have a scaled input with the range  
- * [-1 1) mapping to [-180 180) degrees.  
- *  
- * The implementation is based on table lookup using 360 values together with linear interpolation.  
- * The steps used are:  
- *  -# Calculation of the nearest integer table index.  
- *  -# Compute the fractional portion (fract) of the input.  
- *  -# Fetch the value corresponding to \c index from sine table to \c y0 and also value from \c index+1 to \c y1.     
- *  -# Sine value is computed as  *psinVal = y0 + (fract * (y1 - y0)).   
- *  -# Fetch the value corresponding to \c index from cosine table to \c y0 and also value from \c index+1 to \c y1.     
- *  -# Cosine value is computed as  *pcosVal = y0 + (fract * (y1 - y0)).   
- */
-
- /**   
- * @addtogroup SinCos   
- * @{   
- */
-
-
-/**   
-* \par   
-* Cosine Table is generated from following loop   
-* 
for(i = 0; i < 360; i++)   
-* {   
-*    cosTable[i]= cos((i-180) * PI/180.0);   
-* } 
-*/ - -static const float32_t cosTable[360] = { - -0.999847695156391270f, -0.999390827019095760f, -0.998629534754573830f, - -0.997564050259824200f, -0.996194698091745550f, -0.994521895368273290f, - -0.992546151641321980f, -0.990268068741570250f, - -0.987688340595137660f, -0.984807753012208020f, -0.981627183447663980f, - -0.978147600733805690f, -0.974370064785235250f, -0.970295726275996470f, - -0.965925826289068200f, -0.961261695938318670f, - -0.956304755963035440f, -0.951056516295153530f, -0.945518575599316740f, - -0.939692620785908320f, -0.933580426497201740f, -0.927183854566787310f, - -0.920504853452440150f, -0.913545457642600760f, - -0.906307787036649940f, -0.898794046299167040f, -0.891006524188367790f, - -0.882947592858926770f, -0.874619707139395740f, -0.866025403784438710f, - -0.857167300702112220f, -0.848048096156425960f, - -0.838670567945424160f, -0.829037572555041620f, -0.819152044288991580f, - -0.809016994374947340f, -0.798635510047292940f, -0.788010753606721900f, - -0.777145961456970680f, -0.766044443118977900f, - -0.754709580222772010f, -0.743144825477394130f, -0.731353701619170460f, - -0.719339800338651300f, -0.707106781186547460f, -0.694658370458997030f, - -0.681998360062498370f, -0.669130606358858240f, - -0.656059028990507500f, -0.642787609686539360f, -0.629320391049837280f, - -0.615661475325658290f, -0.601815023152048380f, -0.587785252292473030f, - -0.573576436351045830f, -0.559192903470746680f, - -0.544639035015027080f, -0.529919264233204790f, -0.515038074910054270f, - -0.499999999999999780f, -0.484809620246337000f, -0.469471562785890530f, - -0.453990499739546750f, -0.438371146789077510f, - -0.422618261740699330f, -0.406736643075800100f, -0.390731128489273600f, - -0.374606593415912070f, -0.358367949545300270f, -0.342020143325668710f, - -0.325568154457156420f, -0.309016994374947340f, - -0.292371704722736660f, -0.275637355816999050f, -0.258819045102520850f, - -0.241921895599667790f, -0.224951054343864810f, -0.207911690817759120f, - -0.190808995376544800f, -0.173648177666930300f, - -0.156434465040231040f, -0.139173100960065350f, -0.121869343405147370f, - -0.104528463267653330f, -0.087155742747658235f, -0.069756473744125330f, - -0.052335956242943620f, -0.034899496702500733f, - -0.017452406437283477f, 0.000000000000000061f, 0.017452406437283376f, - 0.034899496702501080f, 0.052335956242943966f, 0.069756473744125455f, - 0.087155742747658138f, 0.104528463267653460f, - 0.121869343405147490f, 0.139173100960065690f, 0.156434465040230920f, - 0.173648177666930410f, 0.190808995376544920f, 0.207911690817759450f, - 0.224951054343864920f, 0.241921895599667900f, - 0.258819045102520740f, 0.275637355816999160f, 0.292371704722736770f, - 0.309016994374947450f, 0.325568154457156760f, 0.342020143325668820f, - 0.358367949545300380f, 0.374606593415911960f, - 0.390731128489273940f, 0.406736643075800210f, 0.422618261740699440f, - 0.438371146789077460f, 0.453990499739546860f, 0.469471562785890860f, - 0.484809620246337110f, 0.500000000000000110f, - 0.515038074910054380f, 0.529919264233204900f, 0.544639035015027200f, - 0.559192903470746790f, 0.573576436351046050f, 0.587785252292473140f, - 0.601815023152048270f, 0.615661475325658290f, - 0.629320391049837500f, 0.642787609686539360f, 0.656059028990507280f, - 0.669130606358858240f, 0.681998360062498480f, 0.694658370458997370f, - 0.707106781186547570f, 0.719339800338651190f, - 0.731353701619170570f, 0.743144825477394240f, 0.754709580222772010f, - 0.766044443118978010f, 0.777145961456970900f, 0.788010753606722010f, - 0.798635510047292830f, 0.809016994374947450f, - 0.819152044288991800f, 0.829037572555041620f, 0.838670567945424050f, - 0.848048096156425960f, 0.857167300702112330f, 0.866025403784438710f, - 0.874619707139395740f, 0.882947592858926990f, - 0.891006524188367900f, 0.898794046299167040f, 0.906307787036649940f, - 0.913545457642600870f, 0.920504853452440370f, 0.927183854566787420f, - 0.933580426497201740f, 0.939692620785908430f, - 0.945518575599316850f, 0.951056516295153530f, 0.956304755963035440f, - 0.961261695938318890f, 0.965925826289068310f, 0.970295726275996470f, - 0.974370064785235250f, 0.978147600733805690f, - 0.981627183447663980f, 0.984807753012208020f, 0.987688340595137770f, - 0.990268068741570360f, 0.992546151641321980f, 0.994521895368273290f, - 0.996194698091745550f, 0.997564050259824200f, - 0.998629534754573830f, 0.999390827019095760f, 0.999847695156391270f, - 1.000000000000000000f, 0.999847695156391270f, 0.999390827019095760f, - 0.998629534754573830f, 0.997564050259824200f, - 0.996194698091745550f, 0.994521895368273290f, 0.992546151641321980f, - 0.990268068741570360f, 0.987688340595137770f, 0.984807753012208020f, - 0.981627183447663980f, 0.978147600733805690f, - 0.974370064785235250f, 0.970295726275996470f, 0.965925826289068310f, - 0.961261695938318890f, 0.956304755963035440f, 0.951056516295153530f, - 0.945518575599316850f, 0.939692620785908430f, - 0.933580426497201740f, 0.927183854566787420f, 0.920504853452440370f, - 0.913545457642600870f, 0.906307787036649940f, 0.898794046299167040f, - 0.891006524188367900f, 0.882947592858926990f, - 0.874619707139395740f, 0.866025403784438710f, 0.857167300702112330f, - 0.848048096156425960f, 0.838670567945424050f, 0.829037572555041620f, - 0.819152044288991800f, 0.809016994374947450f, - 0.798635510047292830f, 0.788010753606722010f, 0.777145961456970900f, - 0.766044443118978010f, 0.754709580222772010f, 0.743144825477394240f, - 0.731353701619170570f, 0.719339800338651190f, - 0.707106781186547570f, 0.694658370458997370f, 0.681998360062498480f, - 0.669130606358858240f, 0.656059028990507280f, 0.642787609686539360f, - 0.629320391049837500f, 0.615661475325658290f, - 0.601815023152048270f, 0.587785252292473140f, 0.573576436351046050f, - 0.559192903470746790f, 0.544639035015027200f, 0.529919264233204900f, - 0.515038074910054380f, 0.500000000000000110f, - 0.484809620246337110f, 0.469471562785890860f, 0.453990499739546860f, - 0.438371146789077460f, 0.422618261740699440f, 0.406736643075800210f, - 0.390731128489273940f, 0.374606593415911960f, - 0.358367949545300380f, 0.342020143325668820f, 0.325568154457156760f, - 0.309016994374947450f, 0.292371704722736770f, 0.275637355816999160f, - 0.258819045102520740f, 0.241921895599667900f, - 0.224951054343864920f, 0.207911690817759450f, 0.190808995376544920f, - 0.173648177666930410f, 0.156434465040230920f, 0.139173100960065690f, - 0.121869343405147490f, 0.104528463267653460f, - 0.087155742747658138f, 0.069756473744125455f, 0.052335956242943966f, - 0.034899496702501080f, 0.017452406437283376f, 0.000000000000000061f, - -0.017452406437283477f, -0.034899496702500733f, - -0.052335956242943620f, -0.069756473744125330f, -0.087155742747658235f, - -0.104528463267653330f, -0.121869343405147370f, -0.139173100960065350f, - -0.156434465040231040f, -0.173648177666930300f, - -0.190808995376544800f, -0.207911690817759120f, -0.224951054343864810f, - -0.241921895599667790f, -0.258819045102520850f, -0.275637355816999050f, - -0.292371704722736660f, -0.309016994374947340f, - -0.325568154457156420f, -0.342020143325668710f, -0.358367949545300270f, - -0.374606593415912070f, -0.390731128489273600f, -0.406736643075800100f, - -0.422618261740699330f, -0.438371146789077510f, - -0.453990499739546750f, -0.469471562785890530f, -0.484809620246337000f, - -0.499999999999999780f, -0.515038074910054270f, -0.529919264233204790f, - -0.544639035015027080f, -0.559192903470746680f, - -0.573576436351045830f, -0.587785252292473030f, -0.601815023152048380f, - -0.615661475325658290f, -0.629320391049837280f, -0.642787609686539360f, - -0.656059028990507500f, -0.669130606358858240f, - -0.681998360062498370f, -0.694658370458997030f, -0.707106781186547460f, - -0.719339800338651300f, -0.731353701619170460f, -0.743144825477394130f, - -0.754709580222772010f, -0.766044443118977900f, - -0.777145961456970680f, -0.788010753606721900f, -0.798635510047292940f, - -0.809016994374947340f, -0.819152044288991580f, -0.829037572555041620f, - -0.838670567945424160f, -0.848048096156425960f, - -0.857167300702112220f, -0.866025403784438710f, -0.874619707139395740f, - -0.882947592858926770f, -0.891006524188367790f, -0.898794046299167040f, - -0.906307787036649940f, -0.913545457642600760f, - -0.920504853452440150f, -0.927183854566787310f, -0.933580426497201740f, - -0.939692620785908320f, -0.945518575599316740f, -0.951056516295153530f, - -0.956304755963035440f, -0.961261695938318670f, - -0.965925826289068200f, -0.970295726275996470f, -0.974370064785235250f, - -0.978147600733805690f, -0.981627183447663980f, -0.984807753012208020f, - -0.987688340595137660f, -0.990268068741570250f, - -0.992546151641321980f, -0.994521895368273290f, -0.996194698091745550f, - -0.997564050259824200f, -0.998629534754573830f, -0.999390827019095760f, - -0.999847695156391270f, -1.000000000000000000f -}; - -/** -* \par -* Sine Table is generated from following loop -*
for(i = 0; i < 360; i++)   
-* {   
-*    sinTable[i]= sin((i-180) * PI/180.0);   
-* } 
-*/ - - -static const float32_t sinTable[360] = { - -0.017452406437283439f, -0.034899496702500699f, -0.052335956242943807f, - -0.069756473744125524f, -0.087155742747658638f, -0.104528463267653730f, - -0.121869343405147550f, -0.139173100960065740f, - -0.156434465040230980f, -0.173648177666930280f, -0.190808995376544970f, - -0.207911690817759310f, -0.224951054343864780f, -0.241921895599667730f, - -0.258819045102521020f, -0.275637355816999660f, - -0.292371704722737050f, -0.309016994374947510f, -0.325568154457156980f, - -0.342020143325668880f, -0.358367949545300210f, -0.374606593415912240f, - -0.390731128489274160f, -0.406736643075800430f, - -0.422618261740699500f, -0.438371146789077290f, -0.453990499739546860f, - -0.469471562785891080f, -0.484809620246337170f, -0.499999999999999940f, - -0.515038074910054380f, -0.529919264233204900f, - -0.544639035015026860f, -0.559192903470746900f, -0.573576436351046380f, - -0.587785252292473250f, -0.601815023152048160f, -0.615661475325658400f, - -0.629320391049837720f, -0.642787609686539470f, - -0.656059028990507280f, -0.669130606358858350f, -0.681998360062498590f, - -0.694658370458997140f, -0.707106781186547570f, -0.719339800338651410f, - -0.731353701619170570f, -0.743144825477394240f, - -0.754709580222771790f, -0.766044443118978010f, -0.777145961456971010f, - -0.788010753606722010f, -0.798635510047292720f, -0.809016994374947450f, - -0.819152044288992020f, -0.829037572555041740f, - -0.838670567945424050f, -0.848048096156426070f, -0.857167300702112330f, - -0.866025403784438710f, -0.874619707139395850f, -0.882947592858927100f, - -0.891006524188367900f, -0.898794046299166930f, - -0.906307787036650050f, -0.913545457642600980f, -0.920504853452440370f, - -0.927183854566787420f, -0.933580426497201740f, -0.939692620785908430f, - -0.945518575599316850f, -0.951056516295153640f, - -0.956304755963035550f, -0.961261695938318890f, -0.965925826289068310f, - -0.970295726275996470f, -0.974370064785235250f, -0.978147600733805690f, - -0.981627183447663980f, -0.984807753012208020f, - -0.987688340595137660f, -0.990268068741570360f, -0.992546151641322090f, - -0.994521895368273400f, -0.996194698091745550f, -0.997564050259824200f, - -0.998629534754573830f, -0.999390827019095760f, - -0.999847695156391270f, -1.000000000000000000f, -0.999847695156391270f, - -0.999390827019095760f, -0.998629534754573830f, -0.997564050259824200f, - -0.996194698091745550f, -0.994521895368273290f, - -0.992546151641321980f, -0.990268068741570250f, -0.987688340595137770f, - -0.984807753012208020f, -0.981627183447663980f, -0.978147600733805580f, - -0.974370064785235250f, -0.970295726275996470f, - -0.965925826289068310f, -0.961261695938318890f, -0.956304755963035440f, - -0.951056516295153530f, -0.945518575599316740f, -0.939692620785908320f, - -0.933580426497201740f, -0.927183854566787420f, - -0.920504853452440260f, -0.913545457642600870f, -0.906307787036649940f, - -0.898794046299167040f, -0.891006524188367790f, -0.882947592858926880f, - -0.874619707139395740f, -0.866025403784438600f, - -0.857167300702112220f, -0.848048096156426070f, -0.838670567945423940f, - -0.829037572555041740f, -0.819152044288991800f, -0.809016994374947450f, - -0.798635510047292830f, -0.788010753606722010f, - -0.777145961456970790f, -0.766044443118978010f, -0.754709580222772010f, - -0.743144825477394240f, -0.731353701619170460f, -0.719339800338651080f, - -0.707106781186547460f, -0.694658370458997250f, - -0.681998360062498480f, -0.669130606358858240f, -0.656059028990507160f, - -0.642787609686539250f, -0.629320391049837390f, -0.615661475325658180f, - -0.601815023152048270f, -0.587785252292473140f, - -0.573576436351046050f, -0.559192903470746900f, -0.544639035015027080f, - -0.529919264233204900f, -0.515038074910054160f, -0.499999999999999940f, - -0.484809620246337060f, -0.469471562785890810f, - -0.453990499739546750f, -0.438371146789077400f, -0.422618261740699440f, - -0.406736643075800150f, -0.390731128489273720f, -0.374606593415912010f, - -0.358367949545300270f, -0.342020143325668710f, - -0.325568154457156640f, -0.309016994374947400f, -0.292371704722736770f, - -0.275637355816999160f, -0.258819045102520740f, -0.241921895599667730f, - -0.224951054343865000f, -0.207911690817759310f, - -0.190808995376544800f, -0.173648177666930330f, -0.156434465040230870f, - -0.139173100960065440f, -0.121869343405147480f, -0.104528463267653460f, - -0.087155742747658166f, -0.069756473744125302f, - -0.052335956242943828f, -0.034899496702500969f, -0.017452406437283512f, - 0.000000000000000000f, 0.017452406437283512f, 0.034899496702500969f, - 0.052335956242943828f, 0.069756473744125302f, - 0.087155742747658166f, 0.104528463267653460f, 0.121869343405147480f, - 0.139173100960065440f, 0.156434465040230870f, 0.173648177666930330f, - 0.190808995376544800f, 0.207911690817759310f, - 0.224951054343865000f, 0.241921895599667730f, 0.258819045102520740f, - 0.275637355816999160f, 0.292371704722736770f, 0.309016994374947400f, - 0.325568154457156640f, 0.342020143325668710f, - 0.358367949545300270f, 0.374606593415912010f, 0.390731128489273720f, - 0.406736643075800150f, 0.422618261740699440f, 0.438371146789077400f, - 0.453990499739546750f, 0.469471562785890810f, - 0.484809620246337060f, 0.499999999999999940f, 0.515038074910054160f, - 0.529919264233204900f, 0.544639035015027080f, 0.559192903470746900f, - 0.573576436351046050f, 0.587785252292473140f, - 0.601815023152048270f, 0.615661475325658180f, 0.629320391049837390f, - 0.642787609686539250f, 0.656059028990507160f, 0.669130606358858240f, - 0.681998360062498480f, 0.694658370458997250f, - 0.707106781186547460f, 0.719339800338651080f, 0.731353701619170460f, - 0.743144825477394240f, 0.754709580222772010f, 0.766044443118978010f, - 0.777145961456970790f, 0.788010753606722010f, - 0.798635510047292830f, 0.809016994374947450f, 0.819152044288991800f, - 0.829037572555041740f, 0.838670567945423940f, 0.848048096156426070f, - 0.857167300702112220f, 0.866025403784438600f, - 0.874619707139395740f, 0.882947592858926880f, 0.891006524188367790f, - 0.898794046299167040f, 0.906307787036649940f, 0.913545457642600870f, - 0.920504853452440260f, 0.927183854566787420f, - 0.933580426497201740f, 0.939692620785908320f, 0.945518575599316740f, - 0.951056516295153530f, 0.956304755963035440f, 0.961261695938318890f, - 0.965925826289068310f, 0.970295726275996470f, - 0.974370064785235250f, 0.978147600733805580f, 0.981627183447663980f, - 0.984807753012208020f, 0.987688340595137770f, 0.990268068741570250f, - 0.992546151641321980f, 0.994521895368273290f, - 0.996194698091745550f, 0.997564050259824200f, 0.998629534754573830f, - 0.999390827019095760f, 0.999847695156391270f, 1.000000000000000000f, - 0.999847695156391270f, 0.999390827019095760f, - 0.998629534754573830f, 0.997564050259824200f, 0.996194698091745550f, - 0.994521895368273400f, 0.992546151641322090f, 0.990268068741570360f, - 0.987688340595137660f, 0.984807753012208020f, - 0.981627183447663980f, 0.978147600733805690f, 0.974370064785235250f, - 0.970295726275996470f, 0.965925826289068310f, 0.961261695938318890f, - 0.956304755963035550f, 0.951056516295153640f, - 0.945518575599316850f, 0.939692620785908430f, 0.933580426497201740f, - 0.927183854566787420f, 0.920504853452440370f, 0.913545457642600980f, - 0.906307787036650050f, 0.898794046299166930f, - 0.891006524188367900f, 0.882947592858927100f, 0.874619707139395850f, - 0.866025403784438710f, 0.857167300702112330f, 0.848048096156426070f, - 0.838670567945424050f, 0.829037572555041740f, - 0.819152044288992020f, 0.809016994374947450f, 0.798635510047292720f, - 0.788010753606722010f, 0.777145961456971010f, 0.766044443118978010f, - 0.754709580222771790f, 0.743144825477394240f, - 0.731353701619170570f, 0.719339800338651410f, 0.707106781186547570f, - 0.694658370458997140f, 0.681998360062498590f, 0.669130606358858350f, - 0.656059028990507280f, 0.642787609686539470f, - 0.629320391049837720f, 0.615661475325658400f, 0.601815023152048160f, - 0.587785252292473250f, 0.573576436351046380f, 0.559192903470746900f, - 0.544639035015026860f, 0.529919264233204900f, - 0.515038074910054380f, 0.499999999999999940f, 0.484809620246337170f, - 0.469471562785891080f, 0.453990499739546860f, 0.438371146789077290f, - 0.422618261740699500f, 0.406736643075800430f, - 0.390731128489274160f, 0.374606593415912240f, 0.358367949545300210f, - 0.342020143325668880f, 0.325568154457156980f, 0.309016994374947510f, - 0.292371704722737050f, 0.275637355816999660f, - 0.258819045102521020f, 0.241921895599667730f, 0.224951054343864780f, - 0.207911690817759310f, 0.190808995376544970f, 0.173648177666930280f, - 0.156434465040230980f, 0.139173100960065740f, - 0.121869343405147550f, 0.104528463267653730f, 0.087155742747658638f, - 0.069756473744125524f, 0.052335956242943807f, 0.034899496702500699f, - 0.017452406437283439f, 0.000000000000000122f -}; - - -/** - * @brief Floating-point sin_cos function. - * @param[in] theta input value in degrees - * @param[out] *pSinVal points to the processed sine output. - * @param[out] *pCosVal points to the processed cos output. - * @return none. - */ - - -void arm_sin_cos_f32( - float32_t theta, - float32_t * pSinVal, - float32_t * pCosVal) -{ - uint32_t i; /* Index for reading nearwst output values */ - float32_t x1 = -179.0f; /* Initial input value */ - float32_t y0, y1; /* nearest output values */ - float32_t fract; /* fractional part of input */ - - /* Calculation of fractional part */ - if(theta > 0.0f) - { - fract = theta - (float32_t) ((int32_t) theta); - } - else - { - fract = (theta - (float32_t) ((int32_t) theta)) + 1.0f; - } - - /* index calculation for reading nearest output values */ - i = (uint32_t) (theta - x1); - - /* reading nearest sine output values */ - y0 = sinTable[i]; - y1 = sinTable[i + 1u]; - - /* Calculation of sine value */ - *pSinVal = y0 + (fract * (y1 - y0)); - - /* reading nearest cosine output values */ - y0 = cosTable[i]; - y1 = cosTable[i + 1u]; - - /* Calculation of cosine value */ - *pCosVal = y0 + (fract * (y1 - y0)); - -} - -/** - * @} end of SinCos group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sin_cos_f32.c +* +* Description: Sine and Cosine calculation for floating-point values. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupController + */ + +/** + * @defgroup SinCos Sine Cosine + * + * Computes the trigonometric sine and cosine values using a combination of table lookup + * and linear interpolation. + * There are separate functions for Q31 and floating-point data types. + * The input to the floating-point version is in degrees while the + * fixed-point Q31 have a scaled input with the range + * [-1 1) mapping to [-180 180) degrees. + * + * The implementation is based on table lookup using 360 values together with linear interpolation. + * The steps used are: + * -# Calculation of the nearest integer table index. + * -# Compute the fractional portion (fract) of the input. + * -# Fetch the value corresponding to \c index from sine table to \c y0 and also value from \c index+1 to \c y1. + * -# Sine value is computed as *psinVal = y0 + (fract * (y1 - y0)). + * -# Fetch the value corresponding to \c index from cosine table to \c y0 and also value from \c index+1 to \c y1. + * -# Cosine value is computed as *pcosVal = y0 + (fract * (y1 - y0)). + */ + + /** + * @addtogroup SinCos + * @{ + */ + + +/** +* \par +* Cosine Table is generated from following loop +*
for(i = 0; i < 360; i++)   
+* {   
+*    cosTable[i]= cos((i-180) * PI/180.0);   
+* } 
+*/ + +static const float32_t cosTable[360] = { + -0.999847695156391270f, -0.999390827019095760f, -0.998629534754573830f, + -0.997564050259824200f, -0.996194698091745550f, -0.994521895368273290f, + -0.992546151641321980f, -0.990268068741570250f, + -0.987688340595137660f, -0.984807753012208020f, -0.981627183447663980f, + -0.978147600733805690f, -0.974370064785235250f, -0.970295726275996470f, + -0.965925826289068200f, -0.961261695938318670f, + -0.956304755963035440f, -0.951056516295153530f, -0.945518575599316740f, + -0.939692620785908320f, -0.933580426497201740f, -0.927183854566787310f, + -0.920504853452440150f, -0.913545457642600760f, + -0.906307787036649940f, -0.898794046299167040f, -0.891006524188367790f, + -0.882947592858926770f, -0.874619707139395740f, -0.866025403784438710f, + -0.857167300702112220f, -0.848048096156425960f, + -0.838670567945424160f, -0.829037572555041620f, -0.819152044288991580f, + -0.809016994374947340f, -0.798635510047292940f, -0.788010753606721900f, + -0.777145961456970680f, -0.766044443118977900f, + -0.754709580222772010f, -0.743144825477394130f, -0.731353701619170460f, + -0.719339800338651300f, -0.707106781186547460f, -0.694658370458997030f, + -0.681998360062498370f, -0.669130606358858240f, + -0.656059028990507500f, -0.642787609686539360f, -0.629320391049837280f, + -0.615661475325658290f, -0.601815023152048380f, -0.587785252292473030f, + -0.573576436351045830f, -0.559192903470746680f, + -0.544639035015027080f, -0.529919264233204790f, -0.515038074910054270f, + -0.499999999999999780f, -0.484809620246337000f, -0.469471562785890530f, + -0.453990499739546750f, -0.438371146789077510f, + -0.422618261740699330f, -0.406736643075800100f, -0.390731128489273600f, + -0.374606593415912070f, -0.358367949545300270f, -0.342020143325668710f, + -0.325568154457156420f, -0.309016994374947340f, + -0.292371704722736660f, -0.275637355816999050f, -0.258819045102520850f, + -0.241921895599667790f, -0.224951054343864810f, -0.207911690817759120f, + -0.190808995376544800f, -0.173648177666930300f, + -0.156434465040231040f, -0.139173100960065350f, -0.121869343405147370f, + -0.104528463267653330f, -0.087155742747658235f, -0.069756473744125330f, + -0.052335956242943620f, -0.034899496702500733f, + -0.017452406437283477f, 0.000000000000000061f, 0.017452406437283376f, + 0.034899496702501080f, 0.052335956242943966f, 0.069756473744125455f, + 0.087155742747658138f, 0.104528463267653460f, + 0.121869343405147490f, 0.139173100960065690f, 0.156434465040230920f, + 0.173648177666930410f, 0.190808995376544920f, 0.207911690817759450f, + 0.224951054343864920f, 0.241921895599667900f, + 0.258819045102520740f, 0.275637355816999160f, 0.292371704722736770f, + 0.309016994374947450f, 0.325568154457156760f, 0.342020143325668820f, + 0.358367949545300380f, 0.374606593415911960f, + 0.390731128489273940f, 0.406736643075800210f, 0.422618261740699440f, + 0.438371146789077460f, 0.453990499739546860f, 0.469471562785890860f, + 0.484809620246337110f, 0.500000000000000110f, + 0.515038074910054380f, 0.529919264233204900f, 0.544639035015027200f, + 0.559192903470746790f, 0.573576436351046050f, 0.587785252292473140f, + 0.601815023152048270f, 0.615661475325658290f, + 0.629320391049837500f, 0.642787609686539360f, 0.656059028990507280f, + 0.669130606358858240f, 0.681998360062498480f, 0.694658370458997370f, + 0.707106781186547570f, 0.719339800338651190f, + 0.731353701619170570f, 0.743144825477394240f, 0.754709580222772010f, + 0.766044443118978010f, 0.777145961456970900f, 0.788010753606722010f, + 0.798635510047292830f, 0.809016994374947450f, + 0.819152044288991800f, 0.829037572555041620f, 0.838670567945424050f, + 0.848048096156425960f, 0.857167300702112330f, 0.866025403784438710f, + 0.874619707139395740f, 0.882947592858926990f, + 0.891006524188367900f, 0.898794046299167040f, 0.906307787036649940f, + 0.913545457642600870f, 0.920504853452440370f, 0.927183854566787420f, + 0.933580426497201740f, 0.939692620785908430f, + 0.945518575599316850f, 0.951056516295153530f, 0.956304755963035440f, + 0.961261695938318890f, 0.965925826289068310f, 0.970295726275996470f, + 0.974370064785235250f, 0.978147600733805690f, + 0.981627183447663980f, 0.984807753012208020f, 0.987688340595137770f, + 0.990268068741570360f, 0.992546151641321980f, 0.994521895368273290f, + 0.996194698091745550f, 0.997564050259824200f, + 0.998629534754573830f, 0.999390827019095760f, 0.999847695156391270f, + 1.000000000000000000f, 0.999847695156391270f, 0.999390827019095760f, + 0.998629534754573830f, 0.997564050259824200f, + 0.996194698091745550f, 0.994521895368273290f, 0.992546151641321980f, + 0.990268068741570360f, 0.987688340595137770f, 0.984807753012208020f, + 0.981627183447663980f, 0.978147600733805690f, + 0.974370064785235250f, 0.970295726275996470f, 0.965925826289068310f, + 0.961261695938318890f, 0.956304755963035440f, 0.951056516295153530f, + 0.945518575599316850f, 0.939692620785908430f, + 0.933580426497201740f, 0.927183854566787420f, 0.920504853452440370f, + 0.913545457642600870f, 0.906307787036649940f, 0.898794046299167040f, + 0.891006524188367900f, 0.882947592858926990f, + 0.874619707139395740f, 0.866025403784438710f, 0.857167300702112330f, + 0.848048096156425960f, 0.838670567945424050f, 0.829037572555041620f, + 0.819152044288991800f, 0.809016994374947450f, + 0.798635510047292830f, 0.788010753606722010f, 0.777145961456970900f, + 0.766044443118978010f, 0.754709580222772010f, 0.743144825477394240f, + 0.731353701619170570f, 0.719339800338651190f, + 0.707106781186547570f, 0.694658370458997370f, 0.681998360062498480f, + 0.669130606358858240f, 0.656059028990507280f, 0.642787609686539360f, + 0.629320391049837500f, 0.615661475325658290f, + 0.601815023152048270f, 0.587785252292473140f, 0.573576436351046050f, + 0.559192903470746790f, 0.544639035015027200f, 0.529919264233204900f, + 0.515038074910054380f, 0.500000000000000110f, + 0.484809620246337110f, 0.469471562785890860f, 0.453990499739546860f, + 0.438371146789077460f, 0.422618261740699440f, 0.406736643075800210f, + 0.390731128489273940f, 0.374606593415911960f, + 0.358367949545300380f, 0.342020143325668820f, 0.325568154457156760f, + 0.309016994374947450f, 0.292371704722736770f, 0.275637355816999160f, + 0.258819045102520740f, 0.241921895599667900f, + 0.224951054343864920f, 0.207911690817759450f, 0.190808995376544920f, + 0.173648177666930410f, 0.156434465040230920f, 0.139173100960065690f, + 0.121869343405147490f, 0.104528463267653460f, + 0.087155742747658138f, 0.069756473744125455f, 0.052335956242943966f, + 0.034899496702501080f, 0.017452406437283376f, 0.000000000000000061f, + -0.017452406437283477f, -0.034899496702500733f, + -0.052335956242943620f, -0.069756473744125330f, -0.087155742747658235f, + -0.104528463267653330f, -0.121869343405147370f, -0.139173100960065350f, + -0.156434465040231040f, -0.173648177666930300f, + -0.190808995376544800f, -0.207911690817759120f, -0.224951054343864810f, + -0.241921895599667790f, -0.258819045102520850f, -0.275637355816999050f, + -0.292371704722736660f, -0.309016994374947340f, + -0.325568154457156420f, -0.342020143325668710f, -0.358367949545300270f, + -0.374606593415912070f, -0.390731128489273600f, -0.406736643075800100f, + -0.422618261740699330f, -0.438371146789077510f, + -0.453990499739546750f, -0.469471562785890530f, -0.484809620246337000f, + -0.499999999999999780f, -0.515038074910054270f, -0.529919264233204790f, + -0.544639035015027080f, -0.559192903470746680f, + -0.573576436351045830f, -0.587785252292473030f, -0.601815023152048380f, + -0.615661475325658290f, -0.629320391049837280f, -0.642787609686539360f, + -0.656059028990507500f, -0.669130606358858240f, + -0.681998360062498370f, -0.694658370458997030f, -0.707106781186547460f, + -0.719339800338651300f, -0.731353701619170460f, -0.743144825477394130f, + -0.754709580222772010f, -0.766044443118977900f, + -0.777145961456970680f, -0.788010753606721900f, -0.798635510047292940f, + -0.809016994374947340f, -0.819152044288991580f, -0.829037572555041620f, + -0.838670567945424160f, -0.848048096156425960f, + -0.857167300702112220f, -0.866025403784438710f, -0.874619707139395740f, + -0.882947592858926770f, -0.891006524188367790f, -0.898794046299167040f, + -0.906307787036649940f, -0.913545457642600760f, + -0.920504853452440150f, -0.927183854566787310f, -0.933580426497201740f, + -0.939692620785908320f, -0.945518575599316740f, -0.951056516295153530f, + -0.956304755963035440f, -0.961261695938318670f, + -0.965925826289068200f, -0.970295726275996470f, -0.974370064785235250f, + -0.978147600733805690f, -0.981627183447663980f, -0.984807753012208020f, + -0.987688340595137660f, -0.990268068741570250f, + -0.992546151641321980f, -0.994521895368273290f, -0.996194698091745550f, + -0.997564050259824200f, -0.998629534754573830f, -0.999390827019095760f, + -0.999847695156391270f, -1.000000000000000000f +}; + +/** +* \par +* Sine Table is generated from following loop +*
for(i = 0; i < 360; i++)   
+* {   
+*    sinTable[i]= sin((i-180) * PI/180.0);   
+* } 
+*/ + + +static const float32_t sinTable[360] = { + -0.017452406437283439f, -0.034899496702500699f, -0.052335956242943807f, + -0.069756473744125524f, -0.087155742747658638f, -0.104528463267653730f, + -0.121869343405147550f, -0.139173100960065740f, + -0.156434465040230980f, -0.173648177666930280f, -0.190808995376544970f, + -0.207911690817759310f, -0.224951054343864780f, -0.241921895599667730f, + -0.258819045102521020f, -0.275637355816999660f, + -0.292371704722737050f, -0.309016994374947510f, -0.325568154457156980f, + -0.342020143325668880f, -0.358367949545300210f, -0.374606593415912240f, + -0.390731128489274160f, -0.406736643075800430f, + -0.422618261740699500f, -0.438371146789077290f, -0.453990499739546860f, + -0.469471562785891080f, -0.484809620246337170f, -0.499999999999999940f, + -0.515038074910054380f, -0.529919264233204900f, + -0.544639035015026860f, -0.559192903470746900f, -0.573576436351046380f, + -0.587785252292473250f, -0.601815023152048160f, -0.615661475325658400f, + -0.629320391049837720f, -0.642787609686539470f, + -0.656059028990507280f, -0.669130606358858350f, -0.681998360062498590f, + -0.694658370458997140f, -0.707106781186547570f, -0.719339800338651410f, + -0.731353701619170570f, -0.743144825477394240f, + -0.754709580222771790f, -0.766044443118978010f, -0.777145961456971010f, + -0.788010753606722010f, -0.798635510047292720f, -0.809016994374947450f, + -0.819152044288992020f, -0.829037572555041740f, + -0.838670567945424050f, -0.848048096156426070f, -0.857167300702112330f, + -0.866025403784438710f, -0.874619707139395850f, -0.882947592858927100f, + -0.891006524188367900f, -0.898794046299166930f, + -0.906307787036650050f, -0.913545457642600980f, -0.920504853452440370f, + -0.927183854566787420f, -0.933580426497201740f, -0.939692620785908430f, + -0.945518575599316850f, -0.951056516295153640f, + -0.956304755963035550f, -0.961261695938318890f, -0.965925826289068310f, + -0.970295726275996470f, -0.974370064785235250f, -0.978147600733805690f, + -0.981627183447663980f, -0.984807753012208020f, + -0.987688340595137660f, -0.990268068741570360f, -0.992546151641322090f, + -0.994521895368273400f, -0.996194698091745550f, -0.997564050259824200f, + -0.998629534754573830f, -0.999390827019095760f, + -0.999847695156391270f, -1.000000000000000000f, -0.999847695156391270f, + -0.999390827019095760f, -0.998629534754573830f, -0.997564050259824200f, + -0.996194698091745550f, -0.994521895368273290f, + -0.992546151641321980f, -0.990268068741570250f, -0.987688340595137770f, + -0.984807753012208020f, -0.981627183447663980f, -0.978147600733805580f, + -0.974370064785235250f, -0.970295726275996470f, + -0.965925826289068310f, -0.961261695938318890f, -0.956304755963035440f, + -0.951056516295153530f, -0.945518575599316740f, -0.939692620785908320f, + -0.933580426497201740f, -0.927183854566787420f, + -0.920504853452440260f, -0.913545457642600870f, -0.906307787036649940f, + -0.898794046299167040f, -0.891006524188367790f, -0.882947592858926880f, + -0.874619707139395740f, -0.866025403784438600f, + -0.857167300702112220f, -0.848048096156426070f, -0.838670567945423940f, + -0.829037572555041740f, -0.819152044288991800f, -0.809016994374947450f, + -0.798635510047292830f, -0.788010753606722010f, + -0.777145961456970790f, -0.766044443118978010f, -0.754709580222772010f, + -0.743144825477394240f, -0.731353701619170460f, -0.719339800338651080f, + -0.707106781186547460f, -0.694658370458997250f, + -0.681998360062498480f, -0.669130606358858240f, -0.656059028990507160f, + -0.642787609686539250f, -0.629320391049837390f, -0.615661475325658180f, + -0.601815023152048270f, -0.587785252292473140f, + -0.573576436351046050f, -0.559192903470746900f, -0.544639035015027080f, + -0.529919264233204900f, -0.515038074910054160f, -0.499999999999999940f, + -0.484809620246337060f, -0.469471562785890810f, + -0.453990499739546750f, -0.438371146789077400f, -0.422618261740699440f, + -0.406736643075800150f, -0.390731128489273720f, -0.374606593415912010f, + -0.358367949545300270f, -0.342020143325668710f, + -0.325568154457156640f, -0.309016994374947400f, -0.292371704722736770f, + -0.275637355816999160f, -0.258819045102520740f, -0.241921895599667730f, + -0.224951054343865000f, -0.207911690817759310f, + -0.190808995376544800f, -0.173648177666930330f, -0.156434465040230870f, + -0.139173100960065440f, -0.121869343405147480f, -0.104528463267653460f, + -0.087155742747658166f, -0.069756473744125302f, + -0.052335956242943828f, -0.034899496702500969f, -0.017452406437283512f, + 0.000000000000000000f, 0.017452406437283512f, 0.034899496702500969f, + 0.052335956242943828f, 0.069756473744125302f, + 0.087155742747658166f, 0.104528463267653460f, 0.121869343405147480f, + 0.139173100960065440f, 0.156434465040230870f, 0.173648177666930330f, + 0.190808995376544800f, 0.207911690817759310f, + 0.224951054343865000f, 0.241921895599667730f, 0.258819045102520740f, + 0.275637355816999160f, 0.292371704722736770f, 0.309016994374947400f, + 0.325568154457156640f, 0.342020143325668710f, + 0.358367949545300270f, 0.374606593415912010f, 0.390731128489273720f, + 0.406736643075800150f, 0.422618261740699440f, 0.438371146789077400f, + 0.453990499739546750f, 0.469471562785890810f, + 0.484809620246337060f, 0.499999999999999940f, 0.515038074910054160f, + 0.529919264233204900f, 0.544639035015027080f, 0.559192903470746900f, + 0.573576436351046050f, 0.587785252292473140f, + 0.601815023152048270f, 0.615661475325658180f, 0.629320391049837390f, + 0.642787609686539250f, 0.656059028990507160f, 0.669130606358858240f, + 0.681998360062498480f, 0.694658370458997250f, + 0.707106781186547460f, 0.719339800338651080f, 0.731353701619170460f, + 0.743144825477394240f, 0.754709580222772010f, 0.766044443118978010f, + 0.777145961456970790f, 0.788010753606722010f, + 0.798635510047292830f, 0.809016994374947450f, 0.819152044288991800f, + 0.829037572555041740f, 0.838670567945423940f, 0.848048096156426070f, + 0.857167300702112220f, 0.866025403784438600f, + 0.874619707139395740f, 0.882947592858926880f, 0.891006524188367790f, + 0.898794046299167040f, 0.906307787036649940f, 0.913545457642600870f, + 0.920504853452440260f, 0.927183854566787420f, + 0.933580426497201740f, 0.939692620785908320f, 0.945518575599316740f, + 0.951056516295153530f, 0.956304755963035440f, 0.961261695938318890f, + 0.965925826289068310f, 0.970295726275996470f, + 0.974370064785235250f, 0.978147600733805580f, 0.981627183447663980f, + 0.984807753012208020f, 0.987688340595137770f, 0.990268068741570250f, + 0.992546151641321980f, 0.994521895368273290f, + 0.996194698091745550f, 0.997564050259824200f, 0.998629534754573830f, + 0.999390827019095760f, 0.999847695156391270f, 1.000000000000000000f, + 0.999847695156391270f, 0.999390827019095760f, + 0.998629534754573830f, 0.997564050259824200f, 0.996194698091745550f, + 0.994521895368273400f, 0.992546151641322090f, 0.990268068741570360f, + 0.987688340595137660f, 0.984807753012208020f, + 0.981627183447663980f, 0.978147600733805690f, 0.974370064785235250f, + 0.970295726275996470f, 0.965925826289068310f, 0.961261695938318890f, + 0.956304755963035550f, 0.951056516295153640f, + 0.945518575599316850f, 0.939692620785908430f, 0.933580426497201740f, + 0.927183854566787420f, 0.920504853452440370f, 0.913545457642600980f, + 0.906307787036650050f, 0.898794046299166930f, + 0.891006524188367900f, 0.882947592858927100f, 0.874619707139395850f, + 0.866025403784438710f, 0.857167300702112330f, 0.848048096156426070f, + 0.838670567945424050f, 0.829037572555041740f, + 0.819152044288992020f, 0.809016994374947450f, 0.798635510047292720f, + 0.788010753606722010f, 0.777145961456971010f, 0.766044443118978010f, + 0.754709580222771790f, 0.743144825477394240f, + 0.731353701619170570f, 0.719339800338651410f, 0.707106781186547570f, + 0.694658370458997140f, 0.681998360062498590f, 0.669130606358858350f, + 0.656059028990507280f, 0.642787609686539470f, + 0.629320391049837720f, 0.615661475325658400f, 0.601815023152048160f, + 0.587785252292473250f, 0.573576436351046380f, 0.559192903470746900f, + 0.544639035015026860f, 0.529919264233204900f, + 0.515038074910054380f, 0.499999999999999940f, 0.484809620246337170f, + 0.469471562785891080f, 0.453990499739546860f, 0.438371146789077290f, + 0.422618261740699500f, 0.406736643075800430f, + 0.390731128489274160f, 0.374606593415912240f, 0.358367949545300210f, + 0.342020143325668880f, 0.325568154457156980f, 0.309016994374947510f, + 0.292371704722737050f, 0.275637355816999660f, + 0.258819045102521020f, 0.241921895599667730f, 0.224951054343864780f, + 0.207911690817759310f, 0.190808995376544970f, 0.173648177666930280f, + 0.156434465040230980f, 0.139173100960065740f, + 0.121869343405147550f, 0.104528463267653730f, 0.087155742747658638f, + 0.069756473744125524f, 0.052335956242943807f, 0.034899496702500699f, + 0.017452406437283439f, 0.000000000000000122f +}; + + +/** + * @brief Floating-point sin_cos function. + * @param[in] theta input value in degrees + * @param[out] *pSinVal points to the processed sine output. + * @param[out] *pCosVal points to the processed cos output. + * @return none. + */ + + +void arm_sin_cos_f32( + float32_t theta, + float32_t * pSinVal, + float32_t * pCosVal) +{ + uint32_t i; /* Index for reading nearwst output values */ + float32_t x1 = -179.0f; /* Initial input value */ + float32_t y0, y1; /* nearest output values */ + float32_t fract; /* fractional part of input */ + + /* Calculation of fractional part */ + if(theta > 0.0f) + { + fract = theta - (float32_t) ((int32_t) theta); + } + else + { + fract = (theta - (float32_t) ((int32_t) theta)) + 1.0f; + } + + /* index calculation for reading nearest output values */ + i = (uint32_t) (theta - x1); + + /* reading nearest sine output values */ + y0 = sinTable[i]; + y1 = sinTable[i + 1u]; + + /* Calculation of sine value */ + *pSinVal = y0 + (fract * (y1 - y0)); + + /* reading nearest cosine output values */ + y0 = cosTable[i]; + y1 = cosTable[i + 1u]; + + /* Calculation of cosine value */ + *pCosVal = y0 + (fract * (y1 - y0)); + +} + +/** + * @} end of SinCos group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_q31.c index 0ad8bb95b..118599475 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_q31.c @@ -1,311 +1,311 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_sin_cos_q31.c -* -* Description: Cosine & Sine calculation for Q31 values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupController - */ - - /** - * @addtogroup SinCos - * @{ - */ - -/** -* \par -* Sine Table is generated from following loop -*
for(i = 0; i < 360; i++)   
-* {   
-*    sinTable[i]= sin((i-180) * PI/180.0);   
-* } 
-* Convert above coefficients to fixed point 1.31 format. -*/ - -static const int32_t sinTableQ31[360] = { - - 0x0, 0xfdc41e9b, 0xfb8869ce, 0xf94d0e2e, 0xf7123849, 0xf4d814a4, 0xf29ecfb2, - 0xf06695da, - 0xee2f9369, 0xebf9f498, 0xe9c5e582, 0xe7939223, 0xe5632654, 0xe334cdc9, - 0xe108b40d, 0xdedf047d, - 0xdcb7ea46, 0xda939061, 0xd8722192, 0xd653c860, 0xd438af17, 0xd220ffc0, - 0xd00ce422, 0xcdfc85bb, - 0xcbf00dbe, 0xc9e7a512, 0xc7e3744b, 0xc5e3a3a9, 0xc3e85b18, 0xc1f1c224, - 0xc0000000, 0xbe133b7c, - 0xbc2b9b05, 0xba4944a2, 0xb86c5df0, 0xb6950c1e, 0xb4c373ee, 0xb2f7b9af, - 0xb1320139, 0xaf726def, - 0xadb922b7, 0xac0641fb, 0xaa59eda4, 0xa8b4471a, 0xa7156f3c, 0xa57d8666, - 0xa3ecac65, 0xa263007d, - 0xa0e0a15f, 0x9f65ad2d, 0x9df24175, 0x9c867b2c, 0x9b2276b0, 0x99c64fc5, - 0x98722192, 0x9726069c, - 0x95e218c9, 0x94a6715d, 0x937328f5, 0x92485786, 0x9126145f, 0x900c7621, - 0x8efb92c2, 0x8df37f8b, - 0x8cf45113, 0x8bfe1b3f, 0x8b10f144, 0x8a2ce59f, 0x89520a1a, 0x88806fc4, - 0x87b826f7, 0x86f93f50, - 0x8643c7b3, 0x8597ce46, 0x84f56073, 0x845c8ae3, 0x83cd5982, 0x8347d77b, - 0x82cc0f36, 0x825a0a5b, - 0x81f1d1ce, 0x81936daf, 0x813ee55b, 0x80f43f69, 0x80b381ac, 0x807cb130, - 0x804fd23a, 0x802ce84c, - 0x8013f61d, 0x8004fda0, 0x80000000, 0x8004fda0, 0x8013f61d, 0x802ce84c, - 0x804fd23a, 0x807cb130, - 0x80b381ac, 0x80f43f69, 0x813ee55b, 0x81936daf, 0x81f1d1ce, 0x825a0a5b, - 0x82cc0f36, 0x8347d77b, - 0x83cd5982, 0x845c8ae3, 0x84f56073, 0x8597ce46, 0x8643c7b3, 0x86f93f50, - 0x87b826f7, 0x88806fc4, - 0x89520a1a, 0x8a2ce59f, 0x8b10f144, 0x8bfe1b3f, 0x8cf45113, 0x8df37f8b, - 0x8efb92c2, 0x900c7621, - 0x9126145f, 0x92485786, 0x937328f5, 0x94a6715d, 0x95e218c9, 0x9726069c, - 0x98722192, 0x99c64fc5, - 0x9b2276b0, 0x9c867b2c, 0x9df24175, 0x9f65ad2d, 0xa0e0a15f, 0xa263007d, - 0xa3ecac65, 0xa57d8666, - 0xa7156f3c, 0xa8b4471a, 0xaa59eda4, 0xac0641fb, 0xadb922b7, 0xaf726def, - 0xb1320139, 0xb2f7b9af, - 0xb4c373ee, 0xb6950c1e, 0xb86c5df0, 0xba4944a2, 0xbc2b9b05, 0xbe133b7c, - 0xc0000000, 0xc1f1c224, - 0xc3e85b18, 0xc5e3a3a9, 0xc7e3744b, 0xc9e7a512, 0xcbf00dbe, 0xcdfc85bb, - 0xd00ce422, 0xd220ffc0, - 0xd438af17, 0xd653c860, 0xd8722192, 0xda939061, 0xdcb7ea46, 0xdedf047d, - 0xe108b40d, 0xe334cdc9, - 0xe5632654, 0xe7939223, 0xe9c5e582, 0xebf9f498, 0xee2f9369, 0xf06695da, - 0xf29ecfb2, 0xf4d814a4, - 0xf7123849, 0xf94d0e2e, 0xfb8869ce, 0xfdc41e9b, 0x0, 0x23be165, 0x4779632, - 0x6b2f1d2, - 0x8edc7b7, 0xb27eb5c, 0xd61304e, 0xf996a26, 0x11d06c97, 0x14060b68, - 0x163a1a7e, 0x186c6ddd, - 0x1a9cd9ac, 0x1ccb3237, 0x1ef74bf3, 0x2120fb83, 0x234815ba, 0x256c6f9f, - 0x278dde6e, 0x29ac37a0, - 0x2bc750e9, 0x2ddf0040, 0x2ff31bde, 0x32037a45, 0x340ff242, 0x36185aee, - 0x381c8bb5, 0x3a1c5c57, - 0x3c17a4e8, 0x3e0e3ddc, 0x40000000, 0x41ecc484, 0x43d464fb, 0x45b6bb5e, - 0x4793a210, 0x496af3e2, - 0x4b3c8c12, 0x4d084651, 0x4ecdfec7, 0x508d9211, 0x5246dd49, 0x53f9be05, - 0x55a6125c, 0x574bb8e6, - 0x58ea90c4, 0x5a82799a, 0x5c13539b, 0x5d9cff83, 0x5f1f5ea1, 0x609a52d3, - 0x620dbe8b, 0x637984d4, - 0x64dd8950, 0x6639b03b, 0x678dde6e, 0x68d9f964, 0x6a1de737, 0x6b598ea3, - 0x6c8cd70b, 0x6db7a87a, - 0x6ed9eba1, 0x6ff389df, 0x71046d3e, 0x720c8075, 0x730baeed, 0x7401e4c1, - 0x74ef0ebc, 0x75d31a61, - 0x76adf5e6, 0x777f903c, 0x7847d909, 0x7906c0b0, 0x79bc384d, 0x7a6831ba, - 0x7b0a9f8d, 0x7ba3751d, - 0x7c32a67e, 0x7cb82885, 0x7d33f0ca, 0x7da5f5a5, 0x7e0e2e32, 0x7e6c9251, - 0x7ec11aa5, 0x7f0bc097, - 0x7f4c7e54, 0x7f834ed0, 0x7fb02dc6, 0x7fd317b4, 0x7fec09e3, 0x7ffb0260, - 0x7fffffff, 0x7ffb0260, - 0x7fec09e3, 0x7fd317b4, 0x7fb02dc6, 0x7f834ed0, 0x7f4c7e54, 0x7f0bc097, - 0x7ec11aa5, 0x7e6c9251, - 0x7e0e2e32, 0x7da5f5a5, 0x7d33f0ca, 0x7cb82885, 0x7c32a67e, 0x7ba3751d, - 0x7b0a9f8d, 0x7a6831ba, - 0x79bc384d, 0x7906c0b0, 0x7847d909, 0x777f903c, 0x76adf5e6, 0x75d31a61, - 0x74ef0ebc, 0x7401e4c1, - 0x730baeed, 0x720c8075, 0x71046d3e, 0x6ff389df, 0x6ed9eba1, 0x6db7a87a, - 0x6c8cd70b, 0x6b598ea3, - 0x6a1de737, 0x68d9f964, 0x678dde6e, 0x6639b03b, 0x64dd8950, 0x637984d4, - 0x620dbe8b, 0x609a52d3, - 0x5f1f5ea1, 0x5d9cff83, 0x5c13539b, 0x5a82799a, 0x58ea90c4, 0x574bb8e6, - 0x55a6125c, 0x53f9be05, - 0x5246dd49, 0x508d9211, 0x4ecdfec7, 0x4d084651, 0x4b3c8c12, 0x496af3e2, - 0x4793a210, 0x45b6bb5e, - 0x43d464fb, 0x41ecc484, 0x40000000, 0x3e0e3ddc, 0x3c17a4e8, 0x3a1c5c57, - 0x381c8bb5, 0x36185aee, - 0x340ff242, 0x32037a45, 0x2ff31bde, 0x2ddf0040, 0x2bc750e9, 0x29ac37a0, - 0x278dde6e, 0x256c6f9f, - 0x234815ba, 0x2120fb83, 0x1ef74bf3, 0x1ccb3237, 0x1a9cd9ac, 0x186c6ddd, - 0x163a1a7e, 0x14060b68, - 0x11d06c97, 0xf996a26, 0xd61304e, 0xb27eb5c, 0x8edc7b7, 0x6b2f1d2, - 0x4779632, 0x23be165, - - -}; - -/** -* \par -* Cosine Table is generated from following loop -*
for(i = 0; i < 360; i++)   
-* {   
-*    cosTable[i]= cos((i-180) * PI/180.0);   
-* } 
-* \par -* Convert above coefficients to fixed point 1.31 format. -*/ -static const int32_t cosTableQ31[360] = { - 0x80000000, 0x8004fda0, 0x8013f61d, 0x802ce84c, 0x804fd23a, 0x807cb130, - 0x80b381ac, 0x80f43f69, - 0x813ee55b, 0x81936daf, 0x81f1d1ce, 0x825a0a5b, 0x82cc0f36, 0x8347d77b, - 0x83cd5982, 0x845c8ae3, - 0x84f56073, 0x8597ce46, 0x8643c7b3, 0x86f93f50, 0x87b826f7, 0x88806fc4, - 0x89520a1a, 0x8a2ce59f, - 0x8b10f144, 0x8bfe1b3f, 0x8cf45113, 0x8df37f8b, 0x8efb92c2, 0x900c7621, - 0x9126145f, 0x92485786, - 0x937328f5, 0x94a6715d, 0x95e218c9, 0x9726069c, 0x98722192, 0x99c64fc5, - 0x9b2276b0, 0x9c867b2c, - 0x9df24175, 0x9f65ad2d, 0xa0e0a15f, 0xa263007d, 0xa3ecac65, 0xa57d8666, - 0xa7156f3c, 0xa8b4471a, - 0xaa59eda4, 0xac0641fb, 0xadb922b7, 0xaf726def, 0xb1320139, 0xb2f7b9af, - 0xb4c373ee, 0xb6950c1e, - 0xb86c5df0, 0xba4944a2, 0xbc2b9b05, 0xbe133b7c, 0xc0000000, 0xc1f1c224, - 0xc3e85b18, 0xc5e3a3a9, - 0xc7e3744b, 0xc9e7a512, 0xcbf00dbe, 0xcdfc85bb, 0xd00ce422, 0xd220ffc0, - 0xd438af17, 0xd653c860, - 0xd8722192, 0xda939061, 0xdcb7ea46, 0xdedf047d, 0xe108b40d, 0xe334cdc9, - 0xe5632654, 0xe7939223, - 0xe9c5e582, 0xebf9f498, 0xee2f9369, 0xf06695da, 0xf29ecfb2, 0xf4d814a4, - 0xf7123849, 0xf94d0e2e, - 0xfb8869ce, 0xfdc41e9b, 0x0, 0x23be165, 0x4779632, 0x6b2f1d2, 0x8edc7b7, - 0xb27eb5c, - 0xd61304e, 0xf996a26, 0x11d06c97, 0x14060b68, 0x163a1a7e, 0x186c6ddd, - 0x1a9cd9ac, 0x1ccb3237, - 0x1ef74bf3, 0x2120fb83, 0x234815ba, 0x256c6f9f, 0x278dde6e, 0x29ac37a0, - 0x2bc750e9, 0x2ddf0040, - 0x2ff31bde, 0x32037a45, 0x340ff242, 0x36185aee, 0x381c8bb5, 0x3a1c5c57, - 0x3c17a4e8, 0x3e0e3ddc, - 0x40000000, 0x41ecc484, 0x43d464fb, 0x45b6bb5e, 0x4793a210, 0x496af3e2, - 0x4b3c8c12, 0x4d084651, - 0x4ecdfec7, 0x508d9211, 0x5246dd49, 0x53f9be05, 0x55a6125c, 0x574bb8e6, - 0x58ea90c4, 0x5a82799a, - 0x5c13539b, 0x5d9cff83, 0x5f1f5ea1, 0x609a52d3, 0x620dbe8b, 0x637984d4, - 0x64dd8950, 0x6639b03b, - 0x678dde6e, 0x68d9f964, 0x6a1de737, 0x6b598ea3, 0x6c8cd70b, 0x6db7a87a, - 0x6ed9eba1, 0x6ff389df, - 0x71046d3e, 0x720c8075, 0x730baeed, 0x7401e4c1, 0x74ef0ebc, 0x75d31a61, - 0x76adf5e6, 0x777f903c, - 0x7847d909, 0x7906c0b0, 0x79bc384d, 0x7a6831ba, 0x7b0a9f8d, 0x7ba3751d, - 0x7c32a67e, 0x7cb82885, - 0x7d33f0ca, 0x7da5f5a5, 0x7e0e2e32, 0x7e6c9251, 0x7ec11aa5, 0x7f0bc097, - 0x7f4c7e54, 0x7f834ed0, - 0x7fb02dc6, 0x7fd317b4, 0x7fec09e3, 0x7ffb0260, 0x7fffffff, 0x7ffb0260, - 0x7fec09e3, 0x7fd317b4, - 0x7fb02dc6, 0x7f834ed0, 0x7f4c7e54, 0x7f0bc097, 0x7ec11aa5, 0x7e6c9251, - 0x7e0e2e32, 0x7da5f5a5, - 0x7d33f0ca, 0x7cb82885, 0x7c32a67e, 0x7ba3751d, 0x7b0a9f8d, 0x7a6831ba, - 0x79bc384d, 0x7906c0b0, - 0x7847d909, 0x777f903c, 0x76adf5e6, 0x75d31a61, 0x74ef0ebc, 0x7401e4c1, - 0x730baeed, 0x720c8075, - 0x71046d3e, 0x6ff389df, 0x6ed9eba1, 0x6db7a87a, 0x6c8cd70b, 0x6b598ea3, - 0x6a1de737, 0x68d9f964, - 0x678dde6e, 0x6639b03b, 0x64dd8950, 0x637984d4, 0x620dbe8b, 0x609a52d3, - 0x5f1f5ea1, 0x5d9cff83, - 0x5c13539b, 0x5a82799a, 0x58ea90c4, 0x574bb8e6, 0x55a6125c, 0x53f9be05, - 0x5246dd49, 0x508d9211, - 0x4ecdfec7, 0x4d084651, 0x4b3c8c12, 0x496af3e2, 0x4793a210, 0x45b6bb5e, - 0x43d464fb, 0x41ecc484, - 0x40000000, 0x3e0e3ddc, 0x3c17a4e8, 0x3a1c5c57, 0x381c8bb5, 0x36185aee, - 0x340ff242, 0x32037a45, - 0x2ff31bde, 0x2ddf0040, 0x2bc750e9, 0x29ac37a0, 0x278dde6e, 0x256c6f9f, - 0x234815ba, 0x2120fb83, - 0x1ef74bf3, 0x1ccb3237, 0x1a9cd9ac, 0x186c6ddd, 0x163a1a7e, 0x14060b68, - 0x11d06c97, 0xf996a26, - 0xd61304e, 0xb27eb5c, 0x8edc7b7, 0x6b2f1d2, 0x4779632, 0x23be165, 0x0, - 0xfdc41e9b, - 0xfb8869ce, 0xf94d0e2e, 0xf7123849, 0xf4d814a4, 0xf29ecfb2, 0xf06695da, - 0xee2f9369, 0xebf9f498, - 0xe9c5e582, 0xe7939223, 0xe5632654, 0xe334cdc9, 0xe108b40d, 0xdedf047d, - 0xdcb7ea46, 0xda939061, - 0xd8722192, 0xd653c860, 0xd438af17, 0xd220ffc0, 0xd00ce422, 0xcdfc85bb, - 0xcbf00dbe, 0xc9e7a512, - 0xc7e3744b, 0xc5e3a3a9, 0xc3e85b18, 0xc1f1c224, 0xc0000000, 0xbe133b7c, - 0xbc2b9b05, 0xba4944a2, - 0xb86c5df0, 0xb6950c1e, 0xb4c373ee, 0xb2f7b9af, 0xb1320139, 0xaf726def, - 0xadb922b7, 0xac0641fb, - 0xaa59eda4, 0xa8b4471a, 0xa7156f3c, 0xa57d8666, 0xa3ecac65, 0xa263007d, - 0xa0e0a15f, 0x9f65ad2d, - 0x9df24175, 0x9c867b2c, 0x9b2276b0, 0x99c64fc5, 0x98722192, 0x9726069c, - 0x95e218c9, 0x94a6715d, - 0x937328f5, 0x92485786, 0x9126145f, 0x900c7621, 0x8efb92c2, 0x8df37f8b, - 0x8cf45113, 0x8bfe1b3f, - 0x8b10f144, 0x8a2ce59f, 0x89520a1a, 0x88806fc4, 0x87b826f7, 0x86f93f50, - 0x8643c7b3, 0x8597ce46, - 0x84f56073, 0x845c8ae3, 0x83cd5982, 0x8347d77b, 0x82cc0f36, 0x825a0a5b, - 0x81f1d1ce, 0x81936daf, - 0x813ee55b, 0x80f43f69, 0x80b381ac, 0x807cb130, 0x804fd23a, 0x802ce84c, - 0x8013f61d, 0x8004fda0, - -}; - - -/** - * @brief Q31 sin_cos function. - * @param[in] theta scaled input value in degrees - * @param[out] *pSinVal points to the processed sine output. - * @param[out] *pCosVal points to the processed cosine output. - * @return none. - * - * The Q31 input value is in the range [-1 +1) and is mapped to a degree value in the range [-180 180). - * - */ - - -void arm_sin_cos_q31( - q31_t theta, - q31_t * pSinVal, - q31_t * pCosVal) -{ - q31_t x0; /* Nearest input value */ - q31_t y0, y1; /* Nearest output values */ - q31_t xSpacing = INPUT_SPACING; /* Spaing between inputs */ - uint32_t i; /* Index */ - q31_t oneByXSpacing; /* 1/ xSpacing value */ - q31_t out; /* temporary variable */ - uint32_t sign_bits; /* No.of sign bits */ - uint32_t firstX = 0x80000000; /* First X value */ - - /* Calculation of index */ - i = ((uint32_t) theta - firstX) / (uint32_t) xSpacing; - - /* Calculation of first nearest input value */ - x0 = (q31_t) firstX + ((q31_t) i * xSpacing); - - /* Reading nearest sine output values from table */ - y0 = sinTableQ31[i]; - y1 = sinTableQ31[i + 1u]; - - /* Calculation of 1/(x1-x0) */ - /* (x1-x0) is xSpacing which is fixed value */ - sign_bits = 8u; - oneByXSpacing = 0x5A000000; - - /* Calculation of (theta - x0)/(x1-x0) */ - out = - (((q31_t) (((q63_t) (theta - x0) * oneByXSpacing) >> 32)) << sign_bits); - - /* Calculation of y0 + (y1 - y0) * ((theta - x0)/(x1-x0)) */ - *pSinVal = y0 + ((q31_t) (((q63_t) (y1 - y0) * out) >> 30)); - - /* Reading nearest cosine output values from table */ - y0 = cosTableQ31[i]; - y1 = cosTableQ31[i + 1u]; - - /* Calculation of y0 + (y1 - y0) * ((theta - x0)/(x1-x0)) */ - *pCosVal = y0 + ((q31_t) (((q63_t) (y1 - y0) * out) >> 30)); - -} - -/** - * @} end of SinCos group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sin_cos_q31.c +* +* Description: Cosine & Sine calculation for Q31 values. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupController + */ + + /** + * @addtogroup SinCos + * @{ + */ + +/** +* \par +* Sine Table is generated from following loop +*
for(i = 0; i < 360; i++)   
+* {   
+*    sinTable[i]= sin((i-180) * PI/180.0);   
+* } 
+* Convert above coefficients to fixed point 1.31 format. +*/ + +static const int32_t sinTableQ31[360] = { + + 0x0, 0xfdc41e9b, 0xfb8869ce, 0xf94d0e2e, 0xf7123849, 0xf4d814a4, 0xf29ecfb2, + 0xf06695da, + 0xee2f9369, 0xebf9f498, 0xe9c5e582, 0xe7939223, 0xe5632654, 0xe334cdc9, + 0xe108b40d, 0xdedf047d, + 0xdcb7ea46, 0xda939061, 0xd8722192, 0xd653c860, 0xd438af17, 0xd220ffc0, + 0xd00ce422, 0xcdfc85bb, + 0xcbf00dbe, 0xc9e7a512, 0xc7e3744b, 0xc5e3a3a9, 0xc3e85b18, 0xc1f1c224, + 0xc0000000, 0xbe133b7c, + 0xbc2b9b05, 0xba4944a2, 0xb86c5df0, 0xb6950c1e, 0xb4c373ee, 0xb2f7b9af, + 0xb1320139, 0xaf726def, + 0xadb922b7, 0xac0641fb, 0xaa59eda4, 0xa8b4471a, 0xa7156f3c, 0xa57d8666, + 0xa3ecac65, 0xa263007d, + 0xa0e0a15f, 0x9f65ad2d, 0x9df24175, 0x9c867b2c, 0x9b2276b0, 0x99c64fc5, + 0x98722192, 0x9726069c, + 0x95e218c9, 0x94a6715d, 0x937328f5, 0x92485786, 0x9126145f, 0x900c7621, + 0x8efb92c2, 0x8df37f8b, + 0x8cf45113, 0x8bfe1b3f, 0x8b10f144, 0x8a2ce59f, 0x89520a1a, 0x88806fc4, + 0x87b826f7, 0x86f93f50, + 0x8643c7b3, 0x8597ce46, 0x84f56073, 0x845c8ae3, 0x83cd5982, 0x8347d77b, + 0x82cc0f36, 0x825a0a5b, + 0x81f1d1ce, 0x81936daf, 0x813ee55b, 0x80f43f69, 0x80b381ac, 0x807cb130, + 0x804fd23a, 0x802ce84c, + 0x8013f61d, 0x8004fda0, 0x80000000, 0x8004fda0, 0x8013f61d, 0x802ce84c, + 0x804fd23a, 0x807cb130, + 0x80b381ac, 0x80f43f69, 0x813ee55b, 0x81936daf, 0x81f1d1ce, 0x825a0a5b, + 0x82cc0f36, 0x8347d77b, + 0x83cd5982, 0x845c8ae3, 0x84f56073, 0x8597ce46, 0x8643c7b3, 0x86f93f50, + 0x87b826f7, 0x88806fc4, + 0x89520a1a, 0x8a2ce59f, 0x8b10f144, 0x8bfe1b3f, 0x8cf45113, 0x8df37f8b, + 0x8efb92c2, 0x900c7621, + 0x9126145f, 0x92485786, 0x937328f5, 0x94a6715d, 0x95e218c9, 0x9726069c, + 0x98722192, 0x99c64fc5, + 0x9b2276b0, 0x9c867b2c, 0x9df24175, 0x9f65ad2d, 0xa0e0a15f, 0xa263007d, + 0xa3ecac65, 0xa57d8666, + 0xa7156f3c, 0xa8b4471a, 0xaa59eda4, 0xac0641fb, 0xadb922b7, 0xaf726def, + 0xb1320139, 0xb2f7b9af, + 0xb4c373ee, 0xb6950c1e, 0xb86c5df0, 0xba4944a2, 0xbc2b9b05, 0xbe133b7c, + 0xc0000000, 0xc1f1c224, + 0xc3e85b18, 0xc5e3a3a9, 0xc7e3744b, 0xc9e7a512, 0xcbf00dbe, 0xcdfc85bb, + 0xd00ce422, 0xd220ffc0, + 0xd438af17, 0xd653c860, 0xd8722192, 0xda939061, 0xdcb7ea46, 0xdedf047d, + 0xe108b40d, 0xe334cdc9, + 0xe5632654, 0xe7939223, 0xe9c5e582, 0xebf9f498, 0xee2f9369, 0xf06695da, + 0xf29ecfb2, 0xf4d814a4, + 0xf7123849, 0xf94d0e2e, 0xfb8869ce, 0xfdc41e9b, 0x0, 0x23be165, 0x4779632, + 0x6b2f1d2, + 0x8edc7b7, 0xb27eb5c, 0xd61304e, 0xf996a26, 0x11d06c97, 0x14060b68, + 0x163a1a7e, 0x186c6ddd, + 0x1a9cd9ac, 0x1ccb3237, 0x1ef74bf3, 0x2120fb83, 0x234815ba, 0x256c6f9f, + 0x278dde6e, 0x29ac37a0, + 0x2bc750e9, 0x2ddf0040, 0x2ff31bde, 0x32037a45, 0x340ff242, 0x36185aee, + 0x381c8bb5, 0x3a1c5c57, + 0x3c17a4e8, 0x3e0e3ddc, 0x40000000, 0x41ecc484, 0x43d464fb, 0x45b6bb5e, + 0x4793a210, 0x496af3e2, + 0x4b3c8c12, 0x4d084651, 0x4ecdfec7, 0x508d9211, 0x5246dd49, 0x53f9be05, + 0x55a6125c, 0x574bb8e6, + 0x58ea90c4, 0x5a82799a, 0x5c13539b, 0x5d9cff83, 0x5f1f5ea1, 0x609a52d3, + 0x620dbe8b, 0x637984d4, + 0x64dd8950, 0x6639b03b, 0x678dde6e, 0x68d9f964, 0x6a1de737, 0x6b598ea3, + 0x6c8cd70b, 0x6db7a87a, + 0x6ed9eba1, 0x6ff389df, 0x71046d3e, 0x720c8075, 0x730baeed, 0x7401e4c1, + 0x74ef0ebc, 0x75d31a61, + 0x76adf5e6, 0x777f903c, 0x7847d909, 0x7906c0b0, 0x79bc384d, 0x7a6831ba, + 0x7b0a9f8d, 0x7ba3751d, + 0x7c32a67e, 0x7cb82885, 0x7d33f0ca, 0x7da5f5a5, 0x7e0e2e32, 0x7e6c9251, + 0x7ec11aa5, 0x7f0bc097, + 0x7f4c7e54, 0x7f834ed0, 0x7fb02dc6, 0x7fd317b4, 0x7fec09e3, 0x7ffb0260, + 0x7fffffff, 0x7ffb0260, + 0x7fec09e3, 0x7fd317b4, 0x7fb02dc6, 0x7f834ed0, 0x7f4c7e54, 0x7f0bc097, + 0x7ec11aa5, 0x7e6c9251, + 0x7e0e2e32, 0x7da5f5a5, 0x7d33f0ca, 0x7cb82885, 0x7c32a67e, 0x7ba3751d, + 0x7b0a9f8d, 0x7a6831ba, + 0x79bc384d, 0x7906c0b0, 0x7847d909, 0x777f903c, 0x76adf5e6, 0x75d31a61, + 0x74ef0ebc, 0x7401e4c1, + 0x730baeed, 0x720c8075, 0x71046d3e, 0x6ff389df, 0x6ed9eba1, 0x6db7a87a, + 0x6c8cd70b, 0x6b598ea3, + 0x6a1de737, 0x68d9f964, 0x678dde6e, 0x6639b03b, 0x64dd8950, 0x637984d4, + 0x620dbe8b, 0x609a52d3, + 0x5f1f5ea1, 0x5d9cff83, 0x5c13539b, 0x5a82799a, 0x58ea90c4, 0x574bb8e6, + 0x55a6125c, 0x53f9be05, + 0x5246dd49, 0x508d9211, 0x4ecdfec7, 0x4d084651, 0x4b3c8c12, 0x496af3e2, + 0x4793a210, 0x45b6bb5e, + 0x43d464fb, 0x41ecc484, 0x40000000, 0x3e0e3ddc, 0x3c17a4e8, 0x3a1c5c57, + 0x381c8bb5, 0x36185aee, + 0x340ff242, 0x32037a45, 0x2ff31bde, 0x2ddf0040, 0x2bc750e9, 0x29ac37a0, + 0x278dde6e, 0x256c6f9f, + 0x234815ba, 0x2120fb83, 0x1ef74bf3, 0x1ccb3237, 0x1a9cd9ac, 0x186c6ddd, + 0x163a1a7e, 0x14060b68, + 0x11d06c97, 0xf996a26, 0xd61304e, 0xb27eb5c, 0x8edc7b7, 0x6b2f1d2, + 0x4779632, 0x23be165, + + +}; + +/** +* \par +* Cosine Table is generated from following loop +*
for(i = 0; i < 360; i++)   
+* {   
+*    cosTable[i]= cos((i-180) * PI/180.0);   
+* } 
+* \par +* Convert above coefficients to fixed point 1.31 format. +*/ +static const int32_t cosTableQ31[360] = { + 0x80000000, 0x8004fda0, 0x8013f61d, 0x802ce84c, 0x804fd23a, 0x807cb130, + 0x80b381ac, 0x80f43f69, + 0x813ee55b, 0x81936daf, 0x81f1d1ce, 0x825a0a5b, 0x82cc0f36, 0x8347d77b, + 0x83cd5982, 0x845c8ae3, + 0x84f56073, 0x8597ce46, 0x8643c7b3, 0x86f93f50, 0x87b826f7, 0x88806fc4, + 0x89520a1a, 0x8a2ce59f, + 0x8b10f144, 0x8bfe1b3f, 0x8cf45113, 0x8df37f8b, 0x8efb92c2, 0x900c7621, + 0x9126145f, 0x92485786, + 0x937328f5, 0x94a6715d, 0x95e218c9, 0x9726069c, 0x98722192, 0x99c64fc5, + 0x9b2276b0, 0x9c867b2c, + 0x9df24175, 0x9f65ad2d, 0xa0e0a15f, 0xa263007d, 0xa3ecac65, 0xa57d8666, + 0xa7156f3c, 0xa8b4471a, + 0xaa59eda4, 0xac0641fb, 0xadb922b7, 0xaf726def, 0xb1320139, 0xb2f7b9af, + 0xb4c373ee, 0xb6950c1e, + 0xb86c5df0, 0xba4944a2, 0xbc2b9b05, 0xbe133b7c, 0xc0000000, 0xc1f1c224, + 0xc3e85b18, 0xc5e3a3a9, + 0xc7e3744b, 0xc9e7a512, 0xcbf00dbe, 0xcdfc85bb, 0xd00ce422, 0xd220ffc0, + 0xd438af17, 0xd653c860, + 0xd8722192, 0xda939061, 0xdcb7ea46, 0xdedf047d, 0xe108b40d, 0xe334cdc9, + 0xe5632654, 0xe7939223, + 0xe9c5e582, 0xebf9f498, 0xee2f9369, 0xf06695da, 0xf29ecfb2, 0xf4d814a4, + 0xf7123849, 0xf94d0e2e, + 0xfb8869ce, 0xfdc41e9b, 0x0, 0x23be165, 0x4779632, 0x6b2f1d2, 0x8edc7b7, + 0xb27eb5c, + 0xd61304e, 0xf996a26, 0x11d06c97, 0x14060b68, 0x163a1a7e, 0x186c6ddd, + 0x1a9cd9ac, 0x1ccb3237, + 0x1ef74bf3, 0x2120fb83, 0x234815ba, 0x256c6f9f, 0x278dde6e, 0x29ac37a0, + 0x2bc750e9, 0x2ddf0040, + 0x2ff31bde, 0x32037a45, 0x340ff242, 0x36185aee, 0x381c8bb5, 0x3a1c5c57, + 0x3c17a4e8, 0x3e0e3ddc, + 0x40000000, 0x41ecc484, 0x43d464fb, 0x45b6bb5e, 0x4793a210, 0x496af3e2, + 0x4b3c8c12, 0x4d084651, + 0x4ecdfec7, 0x508d9211, 0x5246dd49, 0x53f9be05, 0x55a6125c, 0x574bb8e6, + 0x58ea90c4, 0x5a82799a, + 0x5c13539b, 0x5d9cff83, 0x5f1f5ea1, 0x609a52d3, 0x620dbe8b, 0x637984d4, + 0x64dd8950, 0x6639b03b, + 0x678dde6e, 0x68d9f964, 0x6a1de737, 0x6b598ea3, 0x6c8cd70b, 0x6db7a87a, + 0x6ed9eba1, 0x6ff389df, + 0x71046d3e, 0x720c8075, 0x730baeed, 0x7401e4c1, 0x74ef0ebc, 0x75d31a61, + 0x76adf5e6, 0x777f903c, + 0x7847d909, 0x7906c0b0, 0x79bc384d, 0x7a6831ba, 0x7b0a9f8d, 0x7ba3751d, + 0x7c32a67e, 0x7cb82885, + 0x7d33f0ca, 0x7da5f5a5, 0x7e0e2e32, 0x7e6c9251, 0x7ec11aa5, 0x7f0bc097, + 0x7f4c7e54, 0x7f834ed0, + 0x7fb02dc6, 0x7fd317b4, 0x7fec09e3, 0x7ffb0260, 0x7fffffff, 0x7ffb0260, + 0x7fec09e3, 0x7fd317b4, + 0x7fb02dc6, 0x7f834ed0, 0x7f4c7e54, 0x7f0bc097, 0x7ec11aa5, 0x7e6c9251, + 0x7e0e2e32, 0x7da5f5a5, + 0x7d33f0ca, 0x7cb82885, 0x7c32a67e, 0x7ba3751d, 0x7b0a9f8d, 0x7a6831ba, + 0x79bc384d, 0x7906c0b0, + 0x7847d909, 0x777f903c, 0x76adf5e6, 0x75d31a61, 0x74ef0ebc, 0x7401e4c1, + 0x730baeed, 0x720c8075, + 0x71046d3e, 0x6ff389df, 0x6ed9eba1, 0x6db7a87a, 0x6c8cd70b, 0x6b598ea3, + 0x6a1de737, 0x68d9f964, + 0x678dde6e, 0x6639b03b, 0x64dd8950, 0x637984d4, 0x620dbe8b, 0x609a52d3, + 0x5f1f5ea1, 0x5d9cff83, + 0x5c13539b, 0x5a82799a, 0x58ea90c4, 0x574bb8e6, 0x55a6125c, 0x53f9be05, + 0x5246dd49, 0x508d9211, + 0x4ecdfec7, 0x4d084651, 0x4b3c8c12, 0x496af3e2, 0x4793a210, 0x45b6bb5e, + 0x43d464fb, 0x41ecc484, + 0x40000000, 0x3e0e3ddc, 0x3c17a4e8, 0x3a1c5c57, 0x381c8bb5, 0x36185aee, + 0x340ff242, 0x32037a45, + 0x2ff31bde, 0x2ddf0040, 0x2bc750e9, 0x29ac37a0, 0x278dde6e, 0x256c6f9f, + 0x234815ba, 0x2120fb83, + 0x1ef74bf3, 0x1ccb3237, 0x1a9cd9ac, 0x186c6ddd, 0x163a1a7e, 0x14060b68, + 0x11d06c97, 0xf996a26, + 0xd61304e, 0xb27eb5c, 0x8edc7b7, 0x6b2f1d2, 0x4779632, 0x23be165, 0x0, + 0xfdc41e9b, + 0xfb8869ce, 0xf94d0e2e, 0xf7123849, 0xf4d814a4, 0xf29ecfb2, 0xf06695da, + 0xee2f9369, 0xebf9f498, + 0xe9c5e582, 0xe7939223, 0xe5632654, 0xe334cdc9, 0xe108b40d, 0xdedf047d, + 0xdcb7ea46, 0xda939061, + 0xd8722192, 0xd653c860, 0xd438af17, 0xd220ffc0, 0xd00ce422, 0xcdfc85bb, + 0xcbf00dbe, 0xc9e7a512, + 0xc7e3744b, 0xc5e3a3a9, 0xc3e85b18, 0xc1f1c224, 0xc0000000, 0xbe133b7c, + 0xbc2b9b05, 0xba4944a2, + 0xb86c5df0, 0xb6950c1e, 0xb4c373ee, 0xb2f7b9af, 0xb1320139, 0xaf726def, + 0xadb922b7, 0xac0641fb, + 0xaa59eda4, 0xa8b4471a, 0xa7156f3c, 0xa57d8666, 0xa3ecac65, 0xa263007d, + 0xa0e0a15f, 0x9f65ad2d, + 0x9df24175, 0x9c867b2c, 0x9b2276b0, 0x99c64fc5, 0x98722192, 0x9726069c, + 0x95e218c9, 0x94a6715d, + 0x937328f5, 0x92485786, 0x9126145f, 0x900c7621, 0x8efb92c2, 0x8df37f8b, + 0x8cf45113, 0x8bfe1b3f, + 0x8b10f144, 0x8a2ce59f, 0x89520a1a, 0x88806fc4, 0x87b826f7, 0x86f93f50, + 0x8643c7b3, 0x8597ce46, + 0x84f56073, 0x845c8ae3, 0x83cd5982, 0x8347d77b, 0x82cc0f36, 0x825a0a5b, + 0x81f1d1ce, 0x81936daf, + 0x813ee55b, 0x80f43f69, 0x80b381ac, 0x807cb130, 0x804fd23a, 0x802ce84c, + 0x8013f61d, 0x8004fda0, + +}; + + +/** + * @brief Q31 sin_cos function. + * @param[in] theta scaled input value in degrees + * @param[out] *pSinVal points to the processed sine output. + * @param[out] *pCosVal points to the processed cosine output. + * @return none. + * + * The Q31 input value is in the range [-1 +1) and is mapped to a degree value in the range [-180 180). + * + */ + + +void arm_sin_cos_q31( + q31_t theta, + q31_t * pSinVal, + q31_t * pCosVal) +{ + q31_t x0; /* Nearest input value */ + q31_t y0, y1; /* Nearest output values */ + q31_t xSpacing = INPUT_SPACING; /* Spaing between inputs */ + uint32_t i; /* Index */ + q31_t oneByXSpacing; /* 1/ xSpacing value */ + q31_t out; /* temporary variable */ + uint32_t sign_bits; /* No.of sign bits */ + uint32_t firstX = 0x80000000; /* First X value */ + + /* Calculation of index */ + i = ((uint32_t) theta - firstX) / (uint32_t) xSpacing; + + /* Calculation of first nearest input value */ + x0 = (q31_t) firstX + ((q31_t) i * xSpacing); + + /* Reading nearest sine output values from table */ + y0 = sinTableQ31[i]; + y1 = sinTableQ31[i + 1u]; + + /* Calculation of 1/(x1-x0) */ + /* (x1-x0) is xSpacing which is fixed value */ + sign_bits = 8u; + oneByXSpacing = 0x5A000000; + + /* Calculation of (theta - x0)/(x1-x0) */ + out = + (((q31_t) (((q63_t) (theta - x0) * oneByXSpacing) >> 32)) << sign_bits); + + /* Calculation of y0 + (y1 - y0) * ((theta - x0)/(x1-x0)) */ + *pSinVal = y0 + ((q31_t) (((q63_t) (y1 - y0) * out) >> 30)); + + /* Reading nearest cosine output values from table */ + y0 = cosTableQ31[i]; + y1 = cosTableQ31[i + 1u]; + + /* Calculation of y0 + (y1 - y0) * ((theta - x0)/(x1-x0)) */ + *pCosVal = y0 + ((q31_t) (((q63_t) (y1 - y0) * out) >> 30)); + +} + +/** + * @} end of SinCos group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_f32.c index c29469fa4..59f787732 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_f32.c @@ -1,254 +1,254 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_cos_f32.c -* -* Description: Fast cosine calculation for floating-point values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -/** - * @ingroup groupFastMath - */ - -/** - * @defgroup cos Cosine - * - * Computes the trigonometric cosine function using a combination of table lookup - * and cubic interpolation. There are separate functions for - * Q15, Q31, and floating-point data types. - * The input to the floating-point version is in radians while the - * fixed-point Q15 and Q31 have a scaled input with the range - * [0 1) mapping to [0 2*pi). - * - * The implementation is based on table lookup using 256 values together with cubic interpolation. - * The steps used are: - * -# Calculation of the nearest integer table index - * -# Fetch the four table values a, b, c, and d - * -# Compute the fractional portion (fract) of the table index. - * -# Calculation of wa, wb, wc, wd - * -# The final result equals a*wa + b*wb + c*wc + d*wd - * - * where - *
   
- *    a=Table[index-1];   
- *    b=Table[index+0];   
- *    c=Table[index+1];   
- *    d=Table[index+2];   
- * 
- * and - *
   
- *    wa=-(1/6)*fract.^3 + (1/2)*fract.^2 - (1/3)*fract;   
- *    wb=(1/2)*fract.^3 - fract.^2 - (1/2)*fract + 1;   
- *    wc=-(1/2)*fract.^3+(1/2)*fract.^2+fract;   
- *    wd=(1/6)*fract.^3 - (1/6)*fract;   
- * 
- */ - - /** - * @addtogroup cos - * @{ - */ - - -/** -* \par -* Example code for Generation of Cos Table: -* tableSize = 256; -*
for(n = -1; n < (tableSize + 1); n++)   
-* {   
-*	cosTable[n+1]= cos(2*pi*n/tableSize);   
-* } 
-* where pi value is 3.14159265358979 -*/ - -static const float32_t cosTable[259] = { - 0.999698817729949950f, 1.000000000000000000f, 0.999698817729949950f, - 0.998795449733734130f, 0.997290432453155520f, 0.995184719562530520f, - 0.992479562759399410f, 0.989176511764526370f, - 0.985277652740478520f, 0.980785250663757320f, 0.975702106952667240f, - 0.970031261444091800f, 0.963776051998138430f, 0.956940352916717530f, - 0.949528157711029050f, 0.941544055938720700f, - 0.932992815971374510f, 0.923879504203796390f, 0.914209783077239990f, - 0.903989315032958980f, 0.893224298954010010f, 0.881921291351318360f, - 0.870086967945098880f, 0.857728600502014160f, - 0.844853579998016360f, 0.831469595432281490f, 0.817584812641143800f, - 0.803207516670227050f, 0.788346409797668460f, 0.773010432720184330f, - 0.757208824157714840f, 0.740951120853424070f, - 0.724247097969055180f, 0.707106769084930420f, 0.689540565013885500f, - 0.671558976173400880f, 0.653172850608825680f, 0.634393274784088130f, - 0.615231573581695560f, 0.595699310302734380f, - 0.575808167457580570f, 0.555570244789123540f, 0.534997642040252690f, - 0.514102756977081300f, 0.492898195981979370f, 0.471396744251251220f, - 0.449611335992813110f, 0.427555084228515630f, - 0.405241310596466060f, 0.382683426141738890f, 0.359895050525665280f, - 0.336889863014221190f, 0.313681751489639280f, 0.290284663438797000f, - 0.266712754964828490f, 0.242980182170867920f, - 0.219101235270500180f, 0.195090323686599730f, 0.170961886644363400f, - 0.146730467677116390f, 0.122410677373409270f, 0.098017141222953796f, - 0.073564566671848297f, 0.049067676067352295f, - 0.024541229009628296f, 0.000000000000000061f, -0.024541229009628296f, - -0.049067676067352295f, -0.073564566671848297f, -0.098017141222953796f, - -0.122410677373409270f, -0.146730467677116390f, - -0.170961886644363400f, -0.195090323686599730f, -0.219101235270500180f, - -0.242980182170867920f, -0.266712754964828490f, -0.290284663438797000f, - -0.313681751489639280f, -0.336889863014221190f, - -0.359895050525665280f, -0.382683426141738890f, -0.405241310596466060f, - -0.427555084228515630f, -0.449611335992813110f, -0.471396744251251220f, - -0.492898195981979370f, -0.514102756977081300f, - -0.534997642040252690f, -0.555570244789123540f, -0.575808167457580570f, - -0.595699310302734380f, -0.615231573581695560f, -0.634393274784088130f, - -0.653172850608825680f, -0.671558976173400880f, - -0.689540565013885500f, -0.707106769084930420f, -0.724247097969055180f, - -0.740951120853424070f, -0.757208824157714840f, -0.773010432720184330f, - -0.788346409797668460f, -0.803207516670227050f, - -0.817584812641143800f, -0.831469595432281490f, -0.844853579998016360f, - -0.857728600502014160f, -0.870086967945098880f, -0.881921291351318360f, - -0.893224298954010010f, -0.903989315032958980f, - -0.914209783077239990f, -0.923879504203796390f, -0.932992815971374510f, - -0.941544055938720700f, -0.949528157711029050f, -0.956940352916717530f, - -0.963776051998138430f, -0.970031261444091800f, - -0.975702106952667240f, -0.980785250663757320f, -0.985277652740478520f, - -0.989176511764526370f, -0.992479562759399410f, -0.995184719562530520f, - -0.997290432453155520f, -0.998795449733734130f, - -0.999698817729949950f, -1.000000000000000000f, -0.999698817729949950f, - -0.998795449733734130f, -0.997290432453155520f, -0.995184719562530520f, - -0.992479562759399410f, -0.989176511764526370f, - -0.985277652740478520f, -0.980785250663757320f, -0.975702106952667240f, - -0.970031261444091800f, -0.963776051998138430f, -0.956940352916717530f, - -0.949528157711029050f, -0.941544055938720700f, - -0.932992815971374510f, -0.923879504203796390f, -0.914209783077239990f, - -0.903989315032958980f, -0.893224298954010010f, -0.881921291351318360f, - -0.870086967945098880f, -0.857728600502014160f, - -0.844853579998016360f, -0.831469595432281490f, -0.817584812641143800f, - -0.803207516670227050f, -0.788346409797668460f, -0.773010432720184330f, - -0.757208824157714840f, -0.740951120853424070f, - -0.724247097969055180f, -0.707106769084930420f, -0.689540565013885500f, - -0.671558976173400880f, -0.653172850608825680f, -0.634393274784088130f, - -0.615231573581695560f, -0.595699310302734380f, - -0.575808167457580570f, -0.555570244789123540f, -0.534997642040252690f, - -0.514102756977081300f, -0.492898195981979370f, -0.471396744251251220f, - -0.449611335992813110f, -0.427555084228515630f, - -0.405241310596466060f, -0.382683426141738890f, -0.359895050525665280f, - -0.336889863014221190f, -0.313681751489639280f, -0.290284663438797000f, - -0.266712754964828490f, -0.242980182170867920f, - -0.219101235270500180f, -0.195090323686599730f, -0.170961886644363400f, - -0.146730467677116390f, -0.122410677373409270f, -0.098017141222953796f, - -0.073564566671848297f, -0.049067676067352295f, - -0.024541229009628296f, -0.000000000000000184f, 0.024541229009628296f, - 0.049067676067352295f, 0.073564566671848297f, 0.098017141222953796f, - 0.122410677373409270f, 0.146730467677116390f, - 0.170961886644363400f, 0.195090323686599730f, 0.219101235270500180f, - 0.242980182170867920f, 0.266712754964828490f, 0.290284663438797000f, - 0.313681751489639280f, 0.336889863014221190f, - 0.359895050525665280f, 0.382683426141738890f, 0.405241310596466060f, - 0.427555084228515630f, 0.449611335992813110f, 0.471396744251251220f, - 0.492898195981979370f, 0.514102756977081300f, - 0.534997642040252690f, 0.555570244789123540f, 0.575808167457580570f, - 0.595699310302734380f, 0.615231573581695560f, 0.634393274784088130f, - 0.653172850608825680f, 0.671558976173400880f, - 0.689540565013885500f, 0.707106769084930420f, 0.724247097969055180f, - 0.740951120853424070f, 0.757208824157714840f, 0.773010432720184330f, - 0.788346409797668460f, 0.803207516670227050f, - 0.817584812641143800f, 0.831469595432281490f, 0.844853579998016360f, - 0.857728600502014160f, 0.870086967945098880f, 0.881921291351318360f, - 0.893224298954010010f, 0.903989315032958980f, - 0.914209783077239990f, 0.923879504203796390f, 0.932992815971374510f, - 0.941544055938720700f, 0.949528157711029050f, 0.956940352916717530f, - 0.963776051998138430f, 0.970031261444091800f, - 0.975702106952667240f, 0.980785250663757320f, 0.985277652740478520f, - 0.989176511764526370f, 0.992479562759399410f, 0.995184719562530520f, - 0.997290432453155520f, 0.998795449733734130f, - 0.999698817729949950f, 1.000000000000000000f, 0.999698817729949950f -}; - -/** - * @brief Fast approximation to the trigonometric cosine function for floating-point data. - * @param[in] x input value in radians. - * @return cos(x). - */ - -float32_t arm_cos_f32( - float32_t x) -{ - float32_t cosVal, fract, in; - uint32_t index; - uint32_t tableSize = (uint32_t) TABLE_SIZE; - float32_t wa, wb, wc, wd; - float32_t a, b, c, d; - float32_t *tablePtr; - int32_t n; - - /* input x is in radians */ - /* Scale the input to [0 1] range from [0 2*PI] , divide input by 2*pi */ - in = x * 0.159154943092f; - - /* Calculation of floor value of input */ - n = (int32_t) in; - - /* Make negative values towards -infinity */ - if(x < 0.0f) - { - n = n - 1; - } - - /* Map input value to [0 1] */ - in = in - (float32_t) n; - - /* Calculation of index of the table */ - index = (uint32_t) (tableSize * in); - - /* fractional value calculation */ - fract = ((float32_t) tableSize * in) - (float32_t) index; - - /* Initialise table pointer */ - tablePtr = (float32_t *) & cosTable[index]; - - /* Read four nearest values of input value from the cos table */ - a = *tablePtr++; - b = *tablePtr++; - c = *tablePtr++; - d = *tablePtr++; - - /* Cubic interpolation process */ - wa = -(((0.166666667f) * fract) * (fract * fract)) + - (((0.5f) * (fract * fract)) - ((0.3333333333333f) * fract)); - wb = ((((0.5f) * fract) * (fract * fract)) - (fract * fract)) + - (-((0.5f) * fract) + 1.0f); - wc = -(((0.5f) * fract) * (fract * fract)) + - (((0.5f) * (fract * fract)) + fract); - wd = (((0.166666667f) * fract) * (fract * fract)) - - ((0.166666667f) * fract); - - /* Calculate cos value */ - cosVal = ((a * wa) + (b * wb)) + ((c * wc) + (d * wd)); - - /* Return the output value */ - return (cosVal); - -} - -/** - * @} end of cos group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_cos_f32.c +* +* Description: Fast cosine calculation for floating-point values. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" +/** + * @ingroup groupFastMath + */ + +/** + * @defgroup cos Cosine + * + * Computes the trigonometric cosine function using a combination of table lookup + * and cubic interpolation. There are separate functions for + * Q15, Q31, and floating-point data types. + * The input to the floating-point version is in radians while the + * fixed-point Q15 and Q31 have a scaled input with the range + * [0 1) mapping to [0 2*pi). + * + * The implementation is based on table lookup using 256 values together with cubic interpolation. + * The steps used are: + * -# Calculation of the nearest integer table index + * -# Fetch the four table values a, b, c, and d + * -# Compute the fractional portion (fract) of the table index. + * -# Calculation of wa, wb, wc, wd + * -# The final result equals a*wa + b*wb + c*wc + d*wd + * + * where + *
   
+ *    a=Table[index-1];   
+ *    b=Table[index+0];   
+ *    c=Table[index+1];   
+ *    d=Table[index+2];   
+ * 
+ * and + *
   
+ *    wa=-(1/6)*fract.^3 + (1/2)*fract.^2 - (1/3)*fract;   
+ *    wb=(1/2)*fract.^3 - fract.^2 - (1/2)*fract + 1;   
+ *    wc=-(1/2)*fract.^3+(1/2)*fract.^2+fract;   
+ *    wd=(1/6)*fract.^3 - (1/6)*fract;   
+ * 
+ */ + + /** + * @addtogroup cos + * @{ + */ + + +/** +* \par +* Example code for Generation of Cos Table: +* tableSize = 256; +*
for(n = -1; n < (tableSize + 1); n++)   
+* {   
+*	cosTable[n+1]= cos(2*pi*n/tableSize);   
+* } 
+* where pi value is 3.14159265358979 +*/ + +static const float32_t cosTable[259] = { + 0.999698817729949950f, 1.000000000000000000f, 0.999698817729949950f, + 0.998795449733734130f, 0.997290432453155520f, 0.995184719562530520f, + 0.992479562759399410f, 0.989176511764526370f, + 0.985277652740478520f, 0.980785250663757320f, 0.975702106952667240f, + 0.970031261444091800f, 0.963776051998138430f, 0.956940352916717530f, + 0.949528157711029050f, 0.941544055938720700f, + 0.932992815971374510f, 0.923879504203796390f, 0.914209783077239990f, + 0.903989315032958980f, 0.893224298954010010f, 0.881921291351318360f, + 0.870086967945098880f, 0.857728600502014160f, + 0.844853579998016360f, 0.831469595432281490f, 0.817584812641143800f, + 0.803207516670227050f, 0.788346409797668460f, 0.773010432720184330f, + 0.757208824157714840f, 0.740951120853424070f, + 0.724247097969055180f, 0.707106769084930420f, 0.689540565013885500f, + 0.671558976173400880f, 0.653172850608825680f, 0.634393274784088130f, + 0.615231573581695560f, 0.595699310302734380f, + 0.575808167457580570f, 0.555570244789123540f, 0.534997642040252690f, + 0.514102756977081300f, 0.492898195981979370f, 0.471396744251251220f, + 0.449611335992813110f, 0.427555084228515630f, + 0.405241310596466060f, 0.382683426141738890f, 0.359895050525665280f, + 0.336889863014221190f, 0.313681751489639280f, 0.290284663438797000f, + 0.266712754964828490f, 0.242980182170867920f, + 0.219101235270500180f, 0.195090323686599730f, 0.170961886644363400f, + 0.146730467677116390f, 0.122410677373409270f, 0.098017141222953796f, + 0.073564566671848297f, 0.049067676067352295f, + 0.024541229009628296f, 0.000000000000000061f, -0.024541229009628296f, + -0.049067676067352295f, -0.073564566671848297f, -0.098017141222953796f, + -0.122410677373409270f, -0.146730467677116390f, + -0.170961886644363400f, -0.195090323686599730f, -0.219101235270500180f, + -0.242980182170867920f, -0.266712754964828490f, -0.290284663438797000f, + -0.313681751489639280f, -0.336889863014221190f, + -0.359895050525665280f, -0.382683426141738890f, -0.405241310596466060f, + -0.427555084228515630f, -0.449611335992813110f, -0.471396744251251220f, + -0.492898195981979370f, -0.514102756977081300f, + -0.534997642040252690f, -0.555570244789123540f, -0.575808167457580570f, + -0.595699310302734380f, -0.615231573581695560f, -0.634393274784088130f, + -0.653172850608825680f, -0.671558976173400880f, + -0.689540565013885500f, -0.707106769084930420f, -0.724247097969055180f, + -0.740951120853424070f, -0.757208824157714840f, -0.773010432720184330f, + -0.788346409797668460f, -0.803207516670227050f, + -0.817584812641143800f, -0.831469595432281490f, -0.844853579998016360f, + -0.857728600502014160f, -0.870086967945098880f, -0.881921291351318360f, + -0.893224298954010010f, -0.903989315032958980f, + -0.914209783077239990f, -0.923879504203796390f, -0.932992815971374510f, + -0.941544055938720700f, -0.949528157711029050f, -0.956940352916717530f, + -0.963776051998138430f, -0.970031261444091800f, + -0.975702106952667240f, -0.980785250663757320f, -0.985277652740478520f, + -0.989176511764526370f, -0.992479562759399410f, -0.995184719562530520f, + -0.997290432453155520f, -0.998795449733734130f, + -0.999698817729949950f, -1.000000000000000000f, -0.999698817729949950f, + -0.998795449733734130f, -0.997290432453155520f, -0.995184719562530520f, + -0.992479562759399410f, -0.989176511764526370f, + -0.985277652740478520f, -0.980785250663757320f, -0.975702106952667240f, + -0.970031261444091800f, -0.963776051998138430f, -0.956940352916717530f, + -0.949528157711029050f, -0.941544055938720700f, + -0.932992815971374510f, -0.923879504203796390f, -0.914209783077239990f, + -0.903989315032958980f, -0.893224298954010010f, -0.881921291351318360f, + -0.870086967945098880f, -0.857728600502014160f, + -0.844853579998016360f, -0.831469595432281490f, -0.817584812641143800f, + -0.803207516670227050f, -0.788346409797668460f, -0.773010432720184330f, + -0.757208824157714840f, -0.740951120853424070f, + -0.724247097969055180f, -0.707106769084930420f, -0.689540565013885500f, + -0.671558976173400880f, -0.653172850608825680f, -0.634393274784088130f, + -0.615231573581695560f, -0.595699310302734380f, + -0.575808167457580570f, -0.555570244789123540f, -0.534997642040252690f, + -0.514102756977081300f, -0.492898195981979370f, -0.471396744251251220f, + -0.449611335992813110f, -0.427555084228515630f, + -0.405241310596466060f, -0.382683426141738890f, -0.359895050525665280f, + -0.336889863014221190f, -0.313681751489639280f, -0.290284663438797000f, + -0.266712754964828490f, -0.242980182170867920f, + -0.219101235270500180f, -0.195090323686599730f, -0.170961886644363400f, + -0.146730467677116390f, -0.122410677373409270f, -0.098017141222953796f, + -0.073564566671848297f, -0.049067676067352295f, + -0.024541229009628296f, -0.000000000000000184f, 0.024541229009628296f, + 0.049067676067352295f, 0.073564566671848297f, 0.098017141222953796f, + 0.122410677373409270f, 0.146730467677116390f, + 0.170961886644363400f, 0.195090323686599730f, 0.219101235270500180f, + 0.242980182170867920f, 0.266712754964828490f, 0.290284663438797000f, + 0.313681751489639280f, 0.336889863014221190f, + 0.359895050525665280f, 0.382683426141738890f, 0.405241310596466060f, + 0.427555084228515630f, 0.449611335992813110f, 0.471396744251251220f, + 0.492898195981979370f, 0.514102756977081300f, + 0.534997642040252690f, 0.555570244789123540f, 0.575808167457580570f, + 0.595699310302734380f, 0.615231573581695560f, 0.634393274784088130f, + 0.653172850608825680f, 0.671558976173400880f, + 0.689540565013885500f, 0.707106769084930420f, 0.724247097969055180f, + 0.740951120853424070f, 0.757208824157714840f, 0.773010432720184330f, + 0.788346409797668460f, 0.803207516670227050f, + 0.817584812641143800f, 0.831469595432281490f, 0.844853579998016360f, + 0.857728600502014160f, 0.870086967945098880f, 0.881921291351318360f, + 0.893224298954010010f, 0.903989315032958980f, + 0.914209783077239990f, 0.923879504203796390f, 0.932992815971374510f, + 0.941544055938720700f, 0.949528157711029050f, 0.956940352916717530f, + 0.963776051998138430f, 0.970031261444091800f, + 0.975702106952667240f, 0.980785250663757320f, 0.985277652740478520f, + 0.989176511764526370f, 0.992479562759399410f, 0.995184719562530520f, + 0.997290432453155520f, 0.998795449733734130f, + 0.999698817729949950f, 1.000000000000000000f, 0.999698817729949950f +}; + +/** + * @brief Fast approximation to the trigonometric cosine function for floating-point data. + * @param[in] x input value in radians. + * @return cos(x). + */ + +float32_t arm_cos_f32( + float32_t x) +{ + float32_t cosVal, fract, in; + uint32_t index; + uint32_t tableSize = (uint32_t) TABLE_SIZE; + float32_t wa, wb, wc, wd; + float32_t a, b, c, d; + float32_t *tablePtr; + int32_t n; + + /* input x is in radians */ + /* Scale the input to [0 1] range from [0 2*PI] , divide input by 2*pi */ + in = x * 0.159154943092f; + + /* Calculation of floor value of input */ + n = (int32_t) in; + + /* Make negative values towards -infinity */ + if(x < 0.0f) + { + n = n - 1; + } + + /* Map input value to [0 1] */ + in = in - (float32_t) n; + + /* Calculation of index of the table */ + index = (uint32_t) (tableSize * in); + + /* fractional value calculation */ + fract = ((float32_t) tableSize * in) - (float32_t) index; + + /* Initialise table pointer */ + tablePtr = (float32_t *) & cosTable[index]; + + /* Read four nearest values of input value from the cos table */ + a = *tablePtr++; + b = *tablePtr++; + c = *tablePtr++; + d = *tablePtr++; + + /* Cubic interpolation process */ + wa = -(((0.166666667f) * fract) * (fract * fract)) + + (((0.5f) * (fract * fract)) - ((0.3333333333333f) * fract)); + wb = ((((0.5f) * fract) * (fract * fract)) - (fract * fract)) + + (-((0.5f) * fract) + 1.0f); + wc = -(((0.5f) * fract) * (fract * fract)) + + (((0.5f) * (fract * fract)) + fract); + wd = (((0.166666667f) * fract) * (fract * fract)) - + ((0.166666667f) * fract); + + /* Calculate cos value */ + cosVal = ((a * wa) + (b * wb)) + ((c * wc) + (d * wd)); + + /* Return the output value */ + return (cosVal); + +} + +/** + * @} end of cos group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_q15.c index 50bfa105e..6e804c30e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_q15.c @@ -1,189 +1,189 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_cos_q15.c -* -* Description: Fast cosine calculation for Q15 values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFastMath - */ - - /** - * @addtogroup cos - * @{ - */ - -/** -* \par -* Table Values are in Q15(1.15 Fixed point format) and generation is done in three steps -* \par -* First Generate cos values in floating point: -* tableSize = 256; -*
for(n = -1; n < (tableSize + 1); n++)   
-* {   
-*	cosTable[n+1]= cos(2*pi*n/tableSize);   
-* }
-* where pi value is 3.14159265358979 -* \par -* Secondly Convert Floating point to Q15(Fixed point): -* (cosTable[i] * pow(2, 15)) -* \par -* Finally Rounding to nearest integer is done -* cosTable[i] += (cosTable[i] > 0 ? 0.5 :-0.5); -*/ - -static const q15_t cosTableQ15[259] = { - 0x7ff6, 0x7fff, 0x7ff6, 0x7fd9, 0x7fa7, 0x7f62, 0x7f0a, 0x7e9d, - 0x7e1e, 0x7d8a, 0x7ce4, 0x7c2a, 0x7b5d, 0x7a7d, 0x798a, 0x7885, - 0x776c, 0x7642, 0x7505, 0x73b6, 0x7255, 0x70e3, 0x6f5f, 0x6dca, - 0x6c24, 0x6a6e, 0x68a7, 0x66d0, 0x64e9, 0x62f2, 0x60ec, 0x5ed7, - 0x5cb4, 0x5a82, 0x5843, 0x55f6, 0x539b, 0x5134, 0x4ec0, 0x4c40, - 0x49b4, 0x471d, 0x447b, 0x41ce, 0x3f17, 0x3c57, 0x398d, 0x36ba, - 0x33df, 0x30fc, 0x2e11, 0x2b1f, 0x2827, 0x2528, 0x2224, 0x1f1a, - 0x1c0c, 0x18f9, 0x15e2, 0x12c8, 0xfab, 0xc8c, 0x96b, 0x648, - 0x324, 0x0, 0xfcdc, 0xf9b8, 0xf695, 0xf374, 0xf055, 0xed38, - 0xea1e, 0xe707, 0xe3f4, 0xe0e6, 0xdddc, 0xdad8, 0xd7d9, 0xd4e1, - 0xd1ef, 0xcf04, 0xcc21, 0xc946, 0xc673, 0xc3a9, 0xc0e9, 0xbe32, - 0xbb85, 0xb8e3, 0xb64c, 0xb3c0, 0xb140, 0xaecc, 0xac65, 0xaa0a, - 0xa7bd, 0xa57e, 0xa34c, 0xa129, 0x9f14, 0x9d0e, 0x9b17, 0x9930, - 0x9759, 0x9592, 0x93dc, 0x9236, 0x90a1, 0x8f1d, 0x8dab, 0x8c4a, - 0x8afb, 0x89be, 0x8894, 0x877b, 0x8676, 0x8583, 0x84a3, 0x83d6, - 0x831c, 0x8276, 0x81e2, 0x8163, 0x80f6, 0x809e, 0x8059, 0x8027, - 0x800a, 0x8000, 0x800a, 0x8027, 0x8059, 0x809e, 0x80f6, 0x8163, - 0x81e2, 0x8276, 0x831c, 0x83d6, 0x84a3, 0x8583, 0x8676, 0x877b, - 0x8894, 0x89be, 0x8afb, 0x8c4a, 0x8dab, 0x8f1d, 0x90a1, 0x9236, - 0x93dc, 0x9592, 0x9759, 0x9930, 0x9b17, 0x9d0e, 0x9f14, 0xa129, - 0xa34c, 0xa57e, 0xa7bd, 0xaa0a, 0xac65, 0xaecc, 0xb140, 0xb3c0, - 0xb64c, 0xb8e3, 0xbb85, 0xbe32, 0xc0e9, 0xc3a9, 0xc673, 0xc946, - 0xcc21, 0xcf04, 0xd1ef, 0xd4e1, 0xd7d9, 0xdad8, 0xdddc, 0xe0e6, - 0xe3f4, 0xe707, 0xea1e, 0xed38, 0xf055, 0xf374, 0xf695, 0xf9b8, - 0xfcdc, 0x0, 0x324, 0x648, 0x96b, 0xc8c, 0xfab, 0x12c8, - 0x15e2, 0x18f9, 0x1c0c, 0x1f1a, 0x2224, 0x2528, 0x2827, 0x2b1f, - 0x2e11, 0x30fc, 0x33df, 0x36ba, 0x398d, 0x3c57, 0x3f17, 0x41ce, - 0x447b, 0x471d, 0x49b4, 0x4c40, 0x4ec0, 0x5134, 0x539b, 0x55f6, - 0x5843, 0x5a82, 0x5cb4, 0x5ed7, 0x60ec, 0x62f2, 0x64e9, 0x66d0, - 0x68a7, 0x6a6e, 0x6c24, 0x6dca, 0x6f5f, 0x70e3, 0x7255, 0x73b6, - 0x7505, 0x7642, 0x776c, 0x7885, 0x798a, 0x7a7d, 0x7b5d, 0x7c2a, - 0x7ce4, 0x7d8a, 0x7e1e, 0x7e9d, 0x7f0a, 0x7f62, 0x7fa7, 0x7fd9, - 0x7ff6, 0x7fff, 0x7ff6 -}; - - -/** - * @brief Fast approximation to the trigonometric cosine function for Q15 data. - * @param[in] x Scaled input value in radians. - * @return cos(x). - * - * The Q15 input value is in the range [0 +1) and is mapped to a radian value in the range [0 2*pi). - */ - -q15_t arm_cos_q15( - q15_t x) -{ - q31_t cosVal; /* Temporary variable for output */ - q15_t *tablePtr; /* Pointer to table */ - q15_t in, in2; /* Temporary variables for input */ - q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ - q15_t a, b, c, d; /* Four nearest output values */ - q15_t fract, fractCube, fractSquare; /* Variables for fractional value */ - q15_t oneBy6 = 0x1555; /* Fixed point value of 1/6 */ - q15_t tableSpacing = TABLE_SPACING_Q15; /* Table spacing */ - int32_t index; /* Index variable */ - - in = x; - - /* Calculate the nearest index */ - index = (int32_t) in / tableSpacing; - - /* Calculate the nearest value of input */ - in2 = (q15_t) index *tableSpacing; - - /* Calculation of fractional value */ - fract = (in - in2) << 8; - - /* fractSquare = fract * fract */ - fractSquare = (q15_t) ((fract * fract) >> 15); - - /* fractCube = fract * fract * fract */ - fractCube = (q15_t) ((fractSquare * fract) >> 15); - - /* Initialise table pointer */ - tablePtr = (q15_t *) & cosTableQ15[index]; - - /* Cubic interpolation process */ - /* Calculation of wa */ - /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAA)*fract; */ - wa = (q31_t) oneBy6 *fractCube; - wa += (q31_t) 0x2AAA *fract; - wa = -(wa >> 15); - wa += (fractSquare >> 1u); - - /* Read first nearest value of output from the cos table */ - a = *tablePtr++; - - /* cosVal = a * wa */ - cosVal = a * wa; - - /* Calculation of wb */ - wb = (((fractCube >> 1u) - fractSquare) - (fract >> 1u)) + 0x7FFF; - - /* Read second nearest value of output from the cos table */ - b = *tablePtr++; - - /* cosVal += b*wb */ - cosVal += b * wb; - - /* Calculation of wc */ - wc = -(q31_t) fractCube + fractSquare; - wc = (wc >> 1u) + fract; - - /* Read third nearest value of output from the cos table */ - c = *tablePtr++; - - /* cosVal += c*wc */ - cosVal += c * wc; - - /* Calculation of wd */ - /* wd = (oneBy6)*fractCube - (oneBy6)*fract; */ - fractCube = fractCube - fract; - wd = ((q15_t) (((q31_t) oneBy6 * fractCube) >> 15)); - - /* Read fourth nearest value of output from the cos table */ - d = *tablePtr++; - - /* cosVal += d*wd; */ - cosVal += d * wd; - - /* Return the output value in 1.15(q15) format */ - return ((q15_t) (cosVal >> 15u)); - -} - -/** - * @} end of cos group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_cos_q15.c +* +* Description: Fast cosine calculation for Q15 values. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFastMath + */ + + /** + * @addtogroup cos + * @{ + */ + +/** +* \par +* Table Values are in Q15(1.15 Fixed point format) and generation is done in three steps +* \par +* First Generate cos values in floating point: +* tableSize = 256; +*
for(n = -1; n < (tableSize + 1); n++)   
+* {   
+*	cosTable[n+1]= cos(2*pi*n/tableSize);   
+* }
+* where pi value is 3.14159265358979 +* \par +* Secondly Convert Floating point to Q15(Fixed point): +* (cosTable[i] * pow(2, 15)) +* \par +* Finally Rounding to nearest integer is done +* cosTable[i] += (cosTable[i] > 0 ? 0.5 :-0.5); +*/ + +static const q15_t cosTableQ15[259] = { + 0x7ff6, 0x7fff, 0x7ff6, 0x7fd9, 0x7fa7, 0x7f62, 0x7f0a, 0x7e9d, + 0x7e1e, 0x7d8a, 0x7ce4, 0x7c2a, 0x7b5d, 0x7a7d, 0x798a, 0x7885, + 0x776c, 0x7642, 0x7505, 0x73b6, 0x7255, 0x70e3, 0x6f5f, 0x6dca, + 0x6c24, 0x6a6e, 0x68a7, 0x66d0, 0x64e9, 0x62f2, 0x60ec, 0x5ed7, + 0x5cb4, 0x5a82, 0x5843, 0x55f6, 0x539b, 0x5134, 0x4ec0, 0x4c40, + 0x49b4, 0x471d, 0x447b, 0x41ce, 0x3f17, 0x3c57, 0x398d, 0x36ba, + 0x33df, 0x30fc, 0x2e11, 0x2b1f, 0x2827, 0x2528, 0x2224, 0x1f1a, + 0x1c0c, 0x18f9, 0x15e2, 0x12c8, 0xfab, 0xc8c, 0x96b, 0x648, + 0x324, 0x0, 0xfcdc, 0xf9b8, 0xf695, 0xf374, 0xf055, 0xed38, + 0xea1e, 0xe707, 0xe3f4, 0xe0e6, 0xdddc, 0xdad8, 0xd7d9, 0xd4e1, + 0xd1ef, 0xcf04, 0xcc21, 0xc946, 0xc673, 0xc3a9, 0xc0e9, 0xbe32, + 0xbb85, 0xb8e3, 0xb64c, 0xb3c0, 0xb140, 0xaecc, 0xac65, 0xaa0a, + 0xa7bd, 0xa57e, 0xa34c, 0xa129, 0x9f14, 0x9d0e, 0x9b17, 0x9930, + 0x9759, 0x9592, 0x93dc, 0x9236, 0x90a1, 0x8f1d, 0x8dab, 0x8c4a, + 0x8afb, 0x89be, 0x8894, 0x877b, 0x8676, 0x8583, 0x84a3, 0x83d6, + 0x831c, 0x8276, 0x81e2, 0x8163, 0x80f6, 0x809e, 0x8059, 0x8027, + 0x800a, 0x8000, 0x800a, 0x8027, 0x8059, 0x809e, 0x80f6, 0x8163, + 0x81e2, 0x8276, 0x831c, 0x83d6, 0x84a3, 0x8583, 0x8676, 0x877b, + 0x8894, 0x89be, 0x8afb, 0x8c4a, 0x8dab, 0x8f1d, 0x90a1, 0x9236, + 0x93dc, 0x9592, 0x9759, 0x9930, 0x9b17, 0x9d0e, 0x9f14, 0xa129, + 0xa34c, 0xa57e, 0xa7bd, 0xaa0a, 0xac65, 0xaecc, 0xb140, 0xb3c0, + 0xb64c, 0xb8e3, 0xbb85, 0xbe32, 0xc0e9, 0xc3a9, 0xc673, 0xc946, + 0xcc21, 0xcf04, 0xd1ef, 0xd4e1, 0xd7d9, 0xdad8, 0xdddc, 0xe0e6, + 0xe3f4, 0xe707, 0xea1e, 0xed38, 0xf055, 0xf374, 0xf695, 0xf9b8, + 0xfcdc, 0x0, 0x324, 0x648, 0x96b, 0xc8c, 0xfab, 0x12c8, + 0x15e2, 0x18f9, 0x1c0c, 0x1f1a, 0x2224, 0x2528, 0x2827, 0x2b1f, + 0x2e11, 0x30fc, 0x33df, 0x36ba, 0x398d, 0x3c57, 0x3f17, 0x41ce, + 0x447b, 0x471d, 0x49b4, 0x4c40, 0x4ec0, 0x5134, 0x539b, 0x55f6, + 0x5843, 0x5a82, 0x5cb4, 0x5ed7, 0x60ec, 0x62f2, 0x64e9, 0x66d0, + 0x68a7, 0x6a6e, 0x6c24, 0x6dca, 0x6f5f, 0x70e3, 0x7255, 0x73b6, + 0x7505, 0x7642, 0x776c, 0x7885, 0x798a, 0x7a7d, 0x7b5d, 0x7c2a, + 0x7ce4, 0x7d8a, 0x7e1e, 0x7e9d, 0x7f0a, 0x7f62, 0x7fa7, 0x7fd9, + 0x7ff6, 0x7fff, 0x7ff6 +}; + + +/** + * @brief Fast approximation to the trigonometric cosine function for Q15 data. + * @param[in] x Scaled input value in radians. + * @return cos(x). + * + * The Q15 input value is in the range [0 +1) and is mapped to a radian value in the range [0 2*pi). + */ + +q15_t arm_cos_q15( + q15_t x) +{ + q31_t cosVal; /* Temporary variable for output */ + q15_t *tablePtr; /* Pointer to table */ + q15_t in, in2; /* Temporary variables for input */ + q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ + q15_t a, b, c, d; /* Four nearest output values */ + q15_t fract, fractCube, fractSquare; /* Variables for fractional value */ + q15_t oneBy6 = 0x1555; /* Fixed point value of 1/6 */ + q15_t tableSpacing = TABLE_SPACING_Q15; /* Table spacing */ + int32_t index; /* Index variable */ + + in = x; + + /* Calculate the nearest index */ + index = (int32_t) in / tableSpacing; + + /* Calculate the nearest value of input */ + in2 = (q15_t) index *tableSpacing; + + /* Calculation of fractional value */ + fract = (in - in2) << 8; + + /* fractSquare = fract * fract */ + fractSquare = (q15_t) ((fract * fract) >> 15); + + /* fractCube = fract * fract * fract */ + fractCube = (q15_t) ((fractSquare * fract) >> 15); + + /* Initialise table pointer */ + tablePtr = (q15_t *) & cosTableQ15[index]; + + /* Cubic interpolation process */ + /* Calculation of wa */ + /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAA)*fract; */ + wa = (q31_t) oneBy6 *fractCube; + wa += (q31_t) 0x2AAA *fract; + wa = -(wa >> 15); + wa += (fractSquare >> 1u); + + /* Read first nearest value of output from the cos table */ + a = *tablePtr++; + + /* cosVal = a * wa */ + cosVal = a * wa; + + /* Calculation of wb */ + wb = (((fractCube >> 1u) - fractSquare) - (fract >> 1u)) + 0x7FFF; + + /* Read second nearest value of output from the cos table */ + b = *tablePtr++; + + /* cosVal += b*wb */ + cosVal += b * wb; + + /* Calculation of wc */ + wc = -(q31_t) fractCube + fractSquare; + wc = (wc >> 1u) + fract; + + /* Read third nearest value of output from the cos table */ + c = *tablePtr++; + + /* cosVal += c*wc */ + cosVal += c * wc; + + /* Calculation of wd */ + /* wd = (oneBy6)*fractCube - (oneBy6)*fract; */ + fractCube = fractCube - fract; + wd = ((q15_t) (((q31_t) oneBy6 * fractCube) >> 15)); + + /* Read fourth nearest value of output from the cos table */ + d = *tablePtr++; + + /* cosVal += d*wd; */ + cosVal += d * wd; + + /* Return the output value in 1.15(q15) format */ + return ((q15_t) (cosVal >> 15u)); + +} + +/** + * @} end of cos group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_q31.c index 7203e06c3..bcbda5908 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_cos_q31.c @@ -1,225 +1,225 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_cos_q31.c -* -* Description: Fast cosine calculation for Q31 values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFastMath - */ - - /** - * @addtogroup cos - * @{ - */ - -/** - * \par - * Table Values are in Q31(1.31 Fixed point format) and generation is done in three steps - * First Generate cos values in floating point: - * tableSize = 256; - *
for(n = -1; n < (tableSize + 1); n++)   
- * {   
- *	cosTable[n+1]= cos(2*pi*n/tableSize);   
- * } 
- * where pi value is 3.14159265358979 - * \par - * Secondly Convert Floating point to Q31(Fixed point): - * (cosTable[i] * pow(2, 31)) - * \par - * Finally Rounding to nearest integer is done - * cosTable[i] += (cosTable[i] > 0 ? 0.5 :-0.5); - */ - - -static const q31_t cosTableQ31[259] = { - 0x7ff62182, 0x7fffffff, 0x7ff62182, 0x7fd8878e, 0x7fa736b4, 0x7f62368f, - 0x7f0991c4, 0x7e9d55fc, - 0x7e1d93ea, 0x7d8a5f40, 0x7ce3ceb2, 0x7c29fbee, 0x7b5d039e, 0x7a7d055b, - 0x798a23b1, 0x78848414, - 0x776c4edb, 0x7641af3d, 0x7504d345, 0x73b5ebd1, 0x72552c85, 0x70e2cbc6, - 0x6f5f02b2, 0x6dca0d14, - 0x6c242960, 0x6a6d98a4, 0x68a69e81, 0x66cf8120, 0x64e88926, 0x62f201ac, - 0x60ec3830, 0x5ed77c8a, - 0x5cb420e0, 0x5a82799a, 0x5842dd54, 0x55f5a4d2, 0x539b2af0, 0x5133cc94, - 0x4ebfe8a5, 0x4c3fdff4, - 0x49b41533, 0x471cece7, 0x447acd50, 0x41ce1e65, 0x3f1749b8, 0x3c56ba70, - 0x398cdd32, 0x36ba2014, - 0x33def287, 0x30fbc54d, 0x2e110a62, 0x2b1f34eb, 0x2826b928, 0x25280c5e, - 0x2223a4c5, 0x1f19f97b, - 0x1c0b826a, 0x18f8b83c, 0x15e21445, 0x12c8106f, 0xfab272b, 0xc8bd35e, - 0x96a9049, 0x647d97c, - 0x3242abf, 0x0, 0xfcdbd541, 0xf9b82684, 0xf6956fb7, 0xf3742ca2, 0xf054d8d5, - 0xed37ef91, - 0xea1debbb, 0xe70747c4, 0xe3f47d96, 0xe0e60685, 0xdddc5b3b, 0xdad7f3a2, - 0xd7d946d8, 0xd4e0cb15, - 0xd1eef59e, 0xcf043ab3, 0xcc210d79, 0xc945dfec, 0xc67322ce, 0xc3a94590, - 0xc0e8b648, 0xbe31e19b, - 0xbb8532b0, 0xb8e31319, 0xb64beacd, 0xb3c0200c, 0xb140175b, 0xaecc336c, - 0xac64d510, 0xaa0a5b2e, - 0xa7bd22ac, 0xa57d8666, 0xa34bdf20, 0xa1288376, 0x9f13c7d0, 0x9d0dfe54, - 0x9b1776da, 0x99307ee0, - 0x9759617f, 0x9592675c, 0x93dbd6a0, 0x9235f2ec, 0x90a0fd4e, 0x8f1d343a, - 0x8daad37b, 0x8c4a142f, - 0x8afb2cbb, 0x89be50c3, 0x8893b125, 0x877b7bec, 0x8675dc4f, 0x8582faa5, - 0x84a2fc62, 0x83d60412, - 0x831c314e, 0x8275a0c0, 0x81e26c16, 0x8162aa04, 0x80f66e3c, 0x809dc971, - 0x8058c94c, 0x80277872, - 0x8009de7e, 0x80000000, 0x8009de7e, 0x80277872, 0x8058c94c, 0x809dc971, - 0x80f66e3c, 0x8162aa04, - 0x81e26c16, 0x8275a0c0, 0x831c314e, 0x83d60412, 0x84a2fc62, 0x8582faa5, - 0x8675dc4f, 0x877b7bec, - 0x8893b125, 0x89be50c3, 0x8afb2cbb, 0x8c4a142f, 0x8daad37b, 0x8f1d343a, - 0x90a0fd4e, 0x9235f2ec, - 0x93dbd6a0, 0x9592675c, 0x9759617f, 0x99307ee0, 0x9b1776da, 0x9d0dfe54, - 0x9f13c7d0, 0xa1288376, - 0xa34bdf20, 0xa57d8666, 0xa7bd22ac, 0xaa0a5b2e, 0xac64d510, 0xaecc336c, - 0xb140175b, 0xb3c0200c, - 0xb64beacd, 0xb8e31319, 0xbb8532b0, 0xbe31e19b, 0xc0e8b648, 0xc3a94590, - 0xc67322ce, 0xc945dfec, - 0xcc210d79, 0xcf043ab3, 0xd1eef59e, 0xd4e0cb15, 0xd7d946d8, 0xdad7f3a2, - 0xdddc5b3b, 0xe0e60685, - 0xe3f47d96, 0xe70747c4, 0xea1debbb, 0xed37ef91, 0xf054d8d5, 0xf3742ca2, - 0xf6956fb7, 0xf9b82684, - 0xfcdbd541, 0x0, 0x3242abf, 0x647d97c, 0x96a9049, 0xc8bd35e, 0xfab272b, - 0x12c8106f, - 0x15e21445, 0x18f8b83c, 0x1c0b826a, 0x1f19f97b, 0x2223a4c5, 0x25280c5e, - 0x2826b928, 0x2b1f34eb, - 0x2e110a62, 0x30fbc54d, 0x33def287, 0x36ba2014, 0x398cdd32, 0x3c56ba70, - 0x3f1749b8, 0x41ce1e65, - 0x447acd50, 0x471cece7, 0x49b41533, 0x4c3fdff4, 0x4ebfe8a5, 0x5133cc94, - 0x539b2af0, 0x55f5a4d2, - 0x5842dd54, 0x5a82799a, 0x5cb420e0, 0x5ed77c8a, 0x60ec3830, 0x62f201ac, - 0x64e88926, 0x66cf8120, - 0x68a69e81, 0x6a6d98a4, 0x6c242960, 0x6dca0d14, 0x6f5f02b2, 0x70e2cbc6, - 0x72552c85, 0x73b5ebd1, - 0x7504d345, 0x7641af3d, 0x776c4edb, 0x78848414, 0x798a23b1, 0x7a7d055b, - 0x7b5d039e, 0x7c29fbee, - 0x7ce3ceb2, 0x7d8a5f40, 0x7e1d93ea, 0x7e9d55fc, 0x7f0991c4, 0x7f62368f, - 0x7fa736b4, 0x7fd8878e, - 0x7ff62182, 0x7fffffff, 0x7ff62182 -}; - -/** - * @brief Fast approximation to the trigonometric cosine function for Q31 data. - * @param[in] x Scaled input value in radians. - * @return cos(x). - * - * The Q31 input value is in the range [0 +1) and is mapped to a radian value in the range [0 2*pi). - */ - -q31_t arm_cos_q31( - q31_t x) -{ - q31_t cosVal, in, in2; /* Temporary variables for input, output */ - q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ - q31_t a, b, c, d; /* Four nearest output values */ - q31_t *tablePtr; /* Pointer to table */ - q31_t fract, fractCube, fractSquare; /* Temporary values for fractional values */ - q31_t oneBy6 = 0x15555555; /* Fixed point value of 1/6 */ - q31_t tableSpacing = TABLE_SPACING_Q31; /* Table spacing */ - q31_t temp; /* Temporary variable for intermediate process */ - uint32_t index; /* Index variable */ - - in = x; - - /* Calculate the nearest index */ - index = in / tableSpacing; - - /* Calculate the nearest value of input */ - in2 = ((q31_t) index) * tableSpacing; - - /* Calculation of fractional value */ - fract = (in - in2) << 8; - - /* fractSquare = fract * fract */ - fractSquare = ((q31_t) (((q63_t) fract * fract) >> 32)); - fractSquare = fractSquare << 1; - - /* fractCube = fract * fract * fract */ - fractCube = ((q31_t) (((q63_t) fractSquare * fract) >> 32)); - fractCube = fractCube << 1; - - /* Initialise table pointer */ - tablePtr = (q31_t *) & cosTableQ31[index]; - - /* Cubic interpolation process */ - /* Calculation of wa */ - /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAAAAAA)*fract; */ - wa = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); - temp = 0x2AAAAAAA; - wa = (q31_t) ((((q63_t) wa << 32) + ((q63_t) temp * fract)) >> 32); - wa = -(wa << 1u); - wa += (fractSquare >> 1u); - - /* Read first nearest value of output from the cos table */ - a = *tablePtr++; - - /* cosVal = a*wa */ - cosVal = ((q31_t) (((q63_t) a * wa) >> 32)); - - /* q31(1.31) Fixed point value of 1 */ - temp = 0x7FFFFFFF; - - /* Calculation of wb */ - wb = ((fractCube >> 1u) - (fractSquare + (fract >> 1u))) + temp; - /* Read second nearest value of output from the cos table */ - b = *tablePtr++; - - /* cosVal += b*wb */ - cosVal = (q31_t) ((((q63_t) cosVal << 32) + ((q63_t) b * (wb))) >> 32); - - /* Calculation of wc */ - wc = -fractCube + fractSquare; - wc = (wc >> 1u) + fract; - /* Read third nearest values of output value from the cos table */ - c = *tablePtr++; - - /* cosVal += c*wc */ - cosVal = (q31_t) ((((q63_t) cosVal << 32) + ((q63_t) c * (wc))) >> 32); - - /* Calculation of wd */ - /* wd = (oneBy6)*fractCube - (oneBy6)*fract; */ - fractCube = fractCube - fract; - wd = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); - wd = (wd << 1u); - - /* Read fourth nearest value of output from the cos table */ - d = *tablePtr++; - - /* cosVal += d*wd; */ - cosVal = (q31_t) ((((q63_t) cosVal << 32) + ((q63_t) d * (wd))) >> 32); - - /* convert cosVal in 2.30 format to 1.31 format */ - return (cosVal << 1u); - -} - -/** - * @} end of cos group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_cos_q31.c +* +* Description: Fast cosine calculation for Q31 values. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFastMath + */ + + /** + * @addtogroup cos + * @{ + */ + +/** + * \par + * Table Values are in Q31(1.31 Fixed point format) and generation is done in three steps + * First Generate cos values in floating point: + * tableSize = 256; + *
for(n = -1; n < (tableSize + 1); n++)   
+ * {   
+ *	cosTable[n+1]= cos(2*pi*n/tableSize);   
+ * } 
+ * where pi value is 3.14159265358979 + * \par + * Secondly Convert Floating point to Q31(Fixed point): + * (cosTable[i] * pow(2, 31)) + * \par + * Finally Rounding to nearest integer is done + * cosTable[i] += (cosTable[i] > 0 ? 0.5 :-0.5); + */ + + +static const q31_t cosTableQ31[259] = { + 0x7ff62182, 0x7fffffff, 0x7ff62182, 0x7fd8878e, 0x7fa736b4, 0x7f62368f, + 0x7f0991c4, 0x7e9d55fc, + 0x7e1d93ea, 0x7d8a5f40, 0x7ce3ceb2, 0x7c29fbee, 0x7b5d039e, 0x7a7d055b, + 0x798a23b1, 0x78848414, + 0x776c4edb, 0x7641af3d, 0x7504d345, 0x73b5ebd1, 0x72552c85, 0x70e2cbc6, + 0x6f5f02b2, 0x6dca0d14, + 0x6c242960, 0x6a6d98a4, 0x68a69e81, 0x66cf8120, 0x64e88926, 0x62f201ac, + 0x60ec3830, 0x5ed77c8a, + 0x5cb420e0, 0x5a82799a, 0x5842dd54, 0x55f5a4d2, 0x539b2af0, 0x5133cc94, + 0x4ebfe8a5, 0x4c3fdff4, + 0x49b41533, 0x471cece7, 0x447acd50, 0x41ce1e65, 0x3f1749b8, 0x3c56ba70, + 0x398cdd32, 0x36ba2014, + 0x33def287, 0x30fbc54d, 0x2e110a62, 0x2b1f34eb, 0x2826b928, 0x25280c5e, + 0x2223a4c5, 0x1f19f97b, + 0x1c0b826a, 0x18f8b83c, 0x15e21445, 0x12c8106f, 0xfab272b, 0xc8bd35e, + 0x96a9049, 0x647d97c, + 0x3242abf, 0x0, 0xfcdbd541, 0xf9b82684, 0xf6956fb7, 0xf3742ca2, 0xf054d8d5, + 0xed37ef91, + 0xea1debbb, 0xe70747c4, 0xe3f47d96, 0xe0e60685, 0xdddc5b3b, 0xdad7f3a2, + 0xd7d946d8, 0xd4e0cb15, + 0xd1eef59e, 0xcf043ab3, 0xcc210d79, 0xc945dfec, 0xc67322ce, 0xc3a94590, + 0xc0e8b648, 0xbe31e19b, + 0xbb8532b0, 0xb8e31319, 0xb64beacd, 0xb3c0200c, 0xb140175b, 0xaecc336c, + 0xac64d510, 0xaa0a5b2e, + 0xa7bd22ac, 0xa57d8666, 0xa34bdf20, 0xa1288376, 0x9f13c7d0, 0x9d0dfe54, + 0x9b1776da, 0x99307ee0, + 0x9759617f, 0x9592675c, 0x93dbd6a0, 0x9235f2ec, 0x90a0fd4e, 0x8f1d343a, + 0x8daad37b, 0x8c4a142f, + 0x8afb2cbb, 0x89be50c3, 0x8893b125, 0x877b7bec, 0x8675dc4f, 0x8582faa5, + 0x84a2fc62, 0x83d60412, + 0x831c314e, 0x8275a0c0, 0x81e26c16, 0x8162aa04, 0x80f66e3c, 0x809dc971, + 0x8058c94c, 0x80277872, + 0x8009de7e, 0x80000000, 0x8009de7e, 0x80277872, 0x8058c94c, 0x809dc971, + 0x80f66e3c, 0x8162aa04, + 0x81e26c16, 0x8275a0c0, 0x831c314e, 0x83d60412, 0x84a2fc62, 0x8582faa5, + 0x8675dc4f, 0x877b7bec, + 0x8893b125, 0x89be50c3, 0x8afb2cbb, 0x8c4a142f, 0x8daad37b, 0x8f1d343a, + 0x90a0fd4e, 0x9235f2ec, + 0x93dbd6a0, 0x9592675c, 0x9759617f, 0x99307ee0, 0x9b1776da, 0x9d0dfe54, + 0x9f13c7d0, 0xa1288376, + 0xa34bdf20, 0xa57d8666, 0xa7bd22ac, 0xaa0a5b2e, 0xac64d510, 0xaecc336c, + 0xb140175b, 0xb3c0200c, + 0xb64beacd, 0xb8e31319, 0xbb8532b0, 0xbe31e19b, 0xc0e8b648, 0xc3a94590, + 0xc67322ce, 0xc945dfec, + 0xcc210d79, 0xcf043ab3, 0xd1eef59e, 0xd4e0cb15, 0xd7d946d8, 0xdad7f3a2, + 0xdddc5b3b, 0xe0e60685, + 0xe3f47d96, 0xe70747c4, 0xea1debbb, 0xed37ef91, 0xf054d8d5, 0xf3742ca2, + 0xf6956fb7, 0xf9b82684, + 0xfcdbd541, 0x0, 0x3242abf, 0x647d97c, 0x96a9049, 0xc8bd35e, 0xfab272b, + 0x12c8106f, + 0x15e21445, 0x18f8b83c, 0x1c0b826a, 0x1f19f97b, 0x2223a4c5, 0x25280c5e, + 0x2826b928, 0x2b1f34eb, + 0x2e110a62, 0x30fbc54d, 0x33def287, 0x36ba2014, 0x398cdd32, 0x3c56ba70, + 0x3f1749b8, 0x41ce1e65, + 0x447acd50, 0x471cece7, 0x49b41533, 0x4c3fdff4, 0x4ebfe8a5, 0x5133cc94, + 0x539b2af0, 0x55f5a4d2, + 0x5842dd54, 0x5a82799a, 0x5cb420e0, 0x5ed77c8a, 0x60ec3830, 0x62f201ac, + 0x64e88926, 0x66cf8120, + 0x68a69e81, 0x6a6d98a4, 0x6c242960, 0x6dca0d14, 0x6f5f02b2, 0x70e2cbc6, + 0x72552c85, 0x73b5ebd1, + 0x7504d345, 0x7641af3d, 0x776c4edb, 0x78848414, 0x798a23b1, 0x7a7d055b, + 0x7b5d039e, 0x7c29fbee, + 0x7ce3ceb2, 0x7d8a5f40, 0x7e1d93ea, 0x7e9d55fc, 0x7f0991c4, 0x7f62368f, + 0x7fa736b4, 0x7fd8878e, + 0x7ff62182, 0x7fffffff, 0x7ff62182 +}; + +/** + * @brief Fast approximation to the trigonometric cosine function for Q31 data. + * @param[in] x Scaled input value in radians. + * @return cos(x). + * + * The Q31 input value is in the range [0 +1) and is mapped to a radian value in the range [0 2*pi). + */ + +q31_t arm_cos_q31( + q31_t x) +{ + q31_t cosVal, in, in2; /* Temporary variables for input, output */ + q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ + q31_t a, b, c, d; /* Four nearest output values */ + q31_t *tablePtr; /* Pointer to table */ + q31_t fract, fractCube, fractSquare; /* Temporary values for fractional values */ + q31_t oneBy6 = 0x15555555; /* Fixed point value of 1/6 */ + q31_t tableSpacing = TABLE_SPACING_Q31; /* Table spacing */ + q31_t temp; /* Temporary variable for intermediate process */ + uint32_t index; /* Index variable */ + + in = x; + + /* Calculate the nearest index */ + index = in / tableSpacing; + + /* Calculate the nearest value of input */ + in2 = ((q31_t) index) * tableSpacing; + + /* Calculation of fractional value */ + fract = (in - in2) << 8; + + /* fractSquare = fract * fract */ + fractSquare = ((q31_t) (((q63_t) fract * fract) >> 32)); + fractSquare = fractSquare << 1; + + /* fractCube = fract * fract * fract */ + fractCube = ((q31_t) (((q63_t) fractSquare * fract) >> 32)); + fractCube = fractCube << 1; + + /* Initialise table pointer */ + tablePtr = (q31_t *) & cosTableQ31[index]; + + /* Cubic interpolation process */ + /* Calculation of wa */ + /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAAAAAA)*fract; */ + wa = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); + temp = 0x2AAAAAAA; + wa = (q31_t) ((((q63_t) wa << 32) + ((q63_t) temp * fract)) >> 32); + wa = -(wa << 1u); + wa += (fractSquare >> 1u); + + /* Read first nearest value of output from the cos table */ + a = *tablePtr++; + + /* cosVal = a*wa */ + cosVal = ((q31_t) (((q63_t) a * wa) >> 32)); + + /* q31(1.31) Fixed point value of 1 */ + temp = 0x7FFFFFFF; + + /* Calculation of wb */ + wb = ((fractCube >> 1u) - (fractSquare + (fract >> 1u))) + temp; + /* Read second nearest value of output from the cos table */ + b = *tablePtr++; + + /* cosVal += b*wb */ + cosVal = (q31_t) ((((q63_t) cosVal << 32) + ((q63_t) b * (wb))) >> 32); + + /* Calculation of wc */ + wc = -fractCube + fractSquare; + wc = (wc >> 1u) + fract; + /* Read third nearest values of output value from the cos table */ + c = *tablePtr++; + + /* cosVal += c*wc */ + cosVal = (q31_t) ((((q63_t) cosVal << 32) + ((q63_t) c * (wc))) >> 32); + + /* Calculation of wd */ + /* wd = (oneBy6)*fractCube - (oneBy6)*fract; */ + fractCube = fractCube - fract; + wd = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); + wd = (wd << 1u); + + /* Read fourth nearest value of output from the cos table */ + d = *tablePtr++; + + /* cosVal += d*wd; */ + cosVal = (q31_t) ((((q63_t) cosVal << 32) + ((q63_t) d * (wd))) >> 32); + + /* convert cosVal in 2.30 format to 1.31 format */ + return (cosVal << 1u); + +} + +/** + * @} end of cos group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_f32.c index 28985cfe1..877cfa422 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_f32.c @@ -1,257 +1,257 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_sin_f32.c -* -* Description: Fast sine calculation for floating-point values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFastMath - */ - -/** - * @defgroup sin Sine - * - * Computes the trigonometric sine function using a combination of table lookup - * and cubic interpolation. There are separate functions for - * Q15, Q31, and floating-point data types. - * The input to the floating-point version is in radians while the - * fixed-point Q15 and Q31 have a scaled input with the range - * [0 1) mapping to [0 2*pi). - * - * The implementation is based on table lookup using 256 values together with cubic interpolation. - * The steps used are: - * -# Calculation of the nearest integer table index - * -# Fetch the four table values a, b, c, and d - * -# Compute the fractional portion (fract) of the table index. - * -# Calculation of wa, wb, wc, wd - * -# The final result equals a*wa + b*wb + c*wc + d*wd - * - * where - *
   
- *    a=Table[index-1];   
- *    b=Table[index+0];   
- *    c=Table[index+1];   
- *    d=Table[index+2];   
- * 
- * and - *
   
- *    wa=-(1/6)*fract.^3 + (1/2)*fract.^2 - (1/3)*fract;   
- *    wb=(1/2)*fract.^3 - fract.^2 - (1/2)*fract + 1;   
- *    wc=-(1/2)*fract.^3+(1/2)*fract.^2+fract;   
- *    wd=(1/6)*fract.^3 - (1/6)*fract;   
- * 
- */ - -/** - * @addtogroup sin - * @{ - */ - - -/** - * \par - * Example code for Generation of Floating-point Sin Table: - * tableSize = 256; - *
for(n = -1; n < (tableSize + 1); n++)   
- * {   
- *	sinTable[n+1]=sin(2*pi*n/tableSize);   
- * }
- * \par - * where pi value is 3.14159265358979 - */ - -static const float32_t sinTable[259] = { - -0.024541229009628296f, 0.000000000000000000f, 0.024541229009628296f, - 0.049067676067352295f, 0.073564566671848297f, 0.098017141222953796f, - 0.122410677373409270f, 0.146730467677116390f, - 0.170961886644363400f, 0.195090323686599730f, 0.219101235270500180f, - 0.242980182170867920f, 0.266712754964828490f, 0.290284663438797000f, - 0.313681751489639280f, 0.336889863014221190f, - 0.359895050525665280f, 0.382683426141738890f, 0.405241310596466060f, - 0.427555084228515630f, 0.449611335992813110f, 0.471396744251251220f, - 0.492898195981979370f, 0.514102756977081300f, - 0.534997642040252690f, 0.555570244789123540f, 0.575808167457580570f, - 0.595699310302734380f, 0.615231573581695560f, 0.634393274784088130f, - 0.653172850608825680f, 0.671558976173400880f, - 0.689540565013885500f, 0.707106769084930420f, 0.724247097969055180f, - 0.740951120853424070f, 0.757208824157714840f, 0.773010432720184330f, - 0.788346409797668460f, 0.803207516670227050f, - 0.817584812641143800f, 0.831469595432281490f, 0.844853579998016360f, - 0.857728600502014160f, 0.870086967945098880f, 0.881921291351318360f, - 0.893224298954010010f, 0.903989315032958980f, - 0.914209783077239990f, 0.923879504203796390f, 0.932992815971374510f, - 0.941544055938720700f, 0.949528157711029050f, 0.956940352916717530f, - 0.963776051998138430f, 0.970031261444091800f, - 0.975702106952667240f, 0.980785250663757320f, 0.985277652740478520f, - 0.989176511764526370f, 0.992479562759399410f, 0.995184719562530520f, - 0.997290432453155520f, 0.998795449733734130f, - 0.999698817729949950f, 1.000000000000000000f, 0.999698817729949950f, - 0.998795449733734130f, 0.997290432453155520f, 0.995184719562530520f, - 0.992479562759399410f, 0.989176511764526370f, - 0.985277652740478520f, 0.980785250663757320f, 0.975702106952667240f, - 0.970031261444091800f, 0.963776051998138430f, 0.956940352916717530f, - 0.949528157711029050f, 0.941544055938720700f, - 0.932992815971374510f, 0.923879504203796390f, 0.914209783077239990f, - 0.903989315032958980f, 0.893224298954010010f, 0.881921291351318360f, - 0.870086967945098880f, 0.857728600502014160f, - 0.844853579998016360f, 0.831469595432281490f, 0.817584812641143800f, - 0.803207516670227050f, 0.788346409797668460f, 0.773010432720184330f, - 0.757208824157714840f, 0.740951120853424070f, - 0.724247097969055180f, 0.707106769084930420f, 0.689540565013885500f, - 0.671558976173400880f, 0.653172850608825680f, 0.634393274784088130f, - 0.615231573581695560f, 0.595699310302734380f, - 0.575808167457580570f, 0.555570244789123540f, 0.534997642040252690f, - 0.514102756977081300f, 0.492898195981979370f, 0.471396744251251220f, - 0.449611335992813110f, 0.427555084228515630f, - 0.405241310596466060f, 0.382683426141738890f, 0.359895050525665280f, - 0.336889863014221190f, 0.313681751489639280f, 0.290284663438797000f, - 0.266712754964828490f, 0.242980182170867920f, - 0.219101235270500180f, 0.195090323686599730f, 0.170961886644363400f, - 0.146730467677116390f, 0.122410677373409270f, 0.098017141222953796f, - 0.073564566671848297f, 0.049067676067352295f, - 0.024541229009628296f, 0.000000000000000122f, -0.024541229009628296f, - -0.049067676067352295f, -0.073564566671848297f, -0.098017141222953796f, - -0.122410677373409270f, -0.146730467677116390f, - -0.170961886644363400f, -0.195090323686599730f, -0.219101235270500180f, - -0.242980182170867920f, -0.266712754964828490f, -0.290284663438797000f, - -0.313681751489639280f, -0.336889863014221190f, - -0.359895050525665280f, -0.382683426141738890f, -0.405241310596466060f, - -0.427555084228515630f, -0.449611335992813110f, -0.471396744251251220f, - -0.492898195981979370f, -0.514102756977081300f, - -0.534997642040252690f, -0.555570244789123540f, -0.575808167457580570f, - -0.595699310302734380f, -0.615231573581695560f, -0.634393274784088130f, - -0.653172850608825680f, -0.671558976173400880f, - -0.689540565013885500f, -0.707106769084930420f, -0.724247097969055180f, - -0.740951120853424070f, -0.757208824157714840f, -0.773010432720184330f, - -0.788346409797668460f, -0.803207516670227050f, - -0.817584812641143800f, -0.831469595432281490f, -0.844853579998016360f, - -0.857728600502014160f, -0.870086967945098880f, -0.881921291351318360f, - -0.893224298954010010f, -0.903989315032958980f, - -0.914209783077239990f, -0.923879504203796390f, -0.932992815971374510f, - -0.941544055938720700f, -0.949528157711029050f, -0.956940352916717530f, - -0.963776051998138430f, -0.970031261444091800f, - -0.975702106952667240f, -0.980785250663757320f, -0.985277652740478520f, - -0.989176511764526370f, -0.992479562759399410f, -0.995184719562530520f, - -0.997290432453155520f, -0.998795449733734130f, - -0.999698817729949950f, -1.000000000000000000f, -0.999698817729949950f, - -0.998795449733734130f, -0.997290432453155520f, -0.995184719562530520f, - -0.992479562759399410f, -0.989176511764526370f, - -0.985277652740478520f, -0.980785250663757320f, -0.975702106952667240f, - -0.970031261444091800f, -0.963776051998138430f, -0.956940352916717530f, - -0.949528157711029050f, -0.941544055938720700f, - -0.932992815971374510f, -0.923879504203796390f, -0.914209783077239990f, - -0.903989315032958980f, -0.893224298954010010f, -0.881921291351318360f, - -0.870086967945098880f, -0.857728600502014160f, - -0.844853579998016360f, -0.831469595432281490f, -0.817584812641143800f, - -0.803207516670227050f, -0.788346409797668460f, -0.773010432720184330f, - -0.757208824157714840f, -0.740951120853424070f, - -0.724247097969055180f, -0.707106769084930420f, -0.689540565013885500f, - -0.671558976173400880f, -0.653172850608825680f, -0.634393274784088130f, - -0.615231573581695560f, -0.595699310302734380f, - -0.575808167457580570f, -0.555570244789123540f, -0.534997642040252690f, - -0.514102756977081300f, -0.492898195981979370f, -0.471396744251251220f, - -0.449611335992813110f, -0.427555084228515630f, - -0.405241310596466060f, -0.382683426141738890f, -0.359895050525665280f, - -0.336889863014221190f, -0.313681751489639280f, -0.290284663438797000f, - -0.266712754964828490f, -0.242980182170867920f, - -0.219101235270500180f, -0.195090323686599730f, -0.170961886644363400f, - -0.146730467677116390f, -0.122410677373409270f, -0.098017141222953796f, - -0.073564566671848297f, -0.049067676067352295f, - -0.024541229009628296f, -0.000000000000000245f, 0.024541229009628296f -}; - - -/** - * @brief Fast approximation to the trigonometric sine function for floating-point data. - * @param[in] x input value in radians. - * @return sin(x). - */ - -float32_t arm_sin_f32( - float32_t x) -{ - float32_t sinVal, fract, in; /* Temporary variables for input, output */ - uint32_t index; /* Index variable */ - uint32_t tableSize = (uint32_t) TABLE_SIZE; /* Initialise tablesize */ - float32_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ - float32_t a, b, c, d; /* Four nearest output values */ - float32_t *tablePtr; /* Pointer to table */ - int32_t n; - - /* input x is in radians */ - /* Scale the input to [0 1] range from [0 2*PI] , divide input by 2*pi */ - in = x * 0.159154943092f; - - /* Calculation of floor value of input */ - n = (int32_t) in; - - /* Make negative values towards -infinity */ - if(x < 0.0f) - { - n = n - 1; - } - - /* Map input value to [0 1] */ - in = in - (float32_t) n; - - /* Calculation of index of the table */ - index = (uint32_t) (tableSize * in); - - /* fractional value calculation */ - fract = ((float32_t) tableSize * in) - (float32_t) index; - - /* Initialise table pointer */ - tablePtr = (float32_t *) & sinTable[index]; - - /* Read four nearest values of output value from the sin table */ - a = *tablePtr++; - b = *tablePtr++; - c = *tablePtr++; - d = *tablePtr++; - - /* Cubic interpolation process */ - wa = -(((0.166666667f) * (fract * (fract * fract))) + - ((0.3333333333333f) * fract)) + ((0.5f) * (fract * fract)); - wb = (((0.5f) * (fract * (fract * fract))) - - ((fract * fract) + ((0.5f) * fract))) + 1.0f; - wc = (-((0.5f) * (fract * (fract * fract))) + - ((0.5f) * (fract * fract))) + fract; - wd = ((0.166666667f) * (fract * (fract * fract))) - - ((0.166666667f) * fract); - - /* Calculate sin value */ - sinVal = ((a * wa) + (b * wb)) + ((c * wc) + (d * wd)); - - /* Return the output value */ - return (sinVal); - -} - -/** - * @} end of sin group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sin_f32.c +* +* Description: Fast sine calculation for floating-point values. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFastMath + */ + +/** + * @defgroup sin Sine + * + * Computes the trigonometric sine function using a combination of table lookup + * and cubic interpolation. There are separate functions for + * Q15, Q31, and floating-point data types. + * The input to the floating-point version is in radians while the + * fixed-point Q15 and Q31 have a scaled input with the range + * [0 1) mapping to [0 2*pi). + * + * The implementation is based on table lookup using 256 values together with cubic interpolation. + * The steps used are: + * -# Calculation of the nearest integer table index + * -# Fetch the four table values a, b, c, and d + * -# Compute the fractional portion (fract) of the table index. + * -# Calculation of wa, wb, wc, wd + * -# The final result equals a*wa + b*wb + c*wc + d*wd + * + * where + *
   
+ *    a=Table[index-1];   
+ *    b=Table[index+0];   
+ *    c=Table[index+1];   
+ *    d=Table[index+2];   
+ * 
+ * and + *
   
+ *    wa=-(1/6)*fract.^3 + (1/2)*fract.^2 - (1/3)*fract;   
+ *    wb=(1/2)*fract.^3 - fract.^2 - (1/2)*fract + 1;   
+ *    wc=-(1/2)*fract.^3+(1/2)*fract.^2+fract;   
+ *    wd=(1/6)*fract.^3 - (1/6)*fract;   
+ * 
+ */ + +/** + * @addtogroup sin + * @{ + */ + + +/** + * \par + * Example code for Generation of Floating-point Sin Table: + * tableSize = 256; + *
for(n = -1; n < (tableSize + 1); n++)   
+ * {   
+ *	sinTable[n+1]=sin(2*pi*n/tableSize);   
+ * }
+ * \par + * where pi value is 3.14159265358979 + */ + +static const float32_t sinTable[259] = { + -0.024541229009628296f, 0.000000000000000000f, 0.024541229009628296f, + 0.049067676067352295f, 0.073564566671848297f, 0.098017141222953796f, + 0.122410677373409270f, 0.146730467677116390f, + 0.170961886644363400f, 0.195090323686599730f, 0.219101235270500180f, + 0.242980182170867920f, 0.266712754964828490f, 0.290284663438797000f, + 0.313681751489639280f, 0.336889863014221190f, + 0.359895050525665280f, 0.382683426141738890f, 0.405241310596466060f, + 0.427555084228515630f, 0.449611335992813110f, 0.471396744251251220f, + 0.492898195981979370f, 0.514102756977081300f, + 0.534997642040252690f, 0.555570244789123540f, 0.575808167457580570f, + 0.595699310302734380f, 0.615231573581695560f, 0.634393274784088130f, + 0.653172850608825680f, 0.671558976173400880f, + 0.689540565013885500f, 0.707106769084930420f, 0.724247097969055180f, + 0.740951120853424070f, 0.757208824157714840f, 0.773010432720184330f, + 0.788346409797668460f, 0.803207516670227050f, + 0.817584812641143800f, 0.831469595432281490f, 0.844853579998016360f, + 0.857728600502014160f, 0.870086967945098880f, 0.881921291351318360f, + 0.893224298954010010f, 0.903989315032958980f, + 0.914209783077239990f, 0.923879504203796390f, 0.932992815971374510f, + 0.941544055938720700f, 0.949528157711029050f, 0.956940352916717530f, + 0.963776051998138430f, 0.970031261444091800f, + 0.975702106952667240f, 0.980785250663757320f, 0.985277652740478520f, + 0.989176511764526370f, 0.992479562759399410f, 0.995184719562530520f, + 0.997290432453155520f, 0.998795449733734130f, + 0.999698817729949950f, 1.000000000000000000f, 0.999698817729949950f, + 0.998795449733734130f, 0.997290432453155520f, 0.995184719562530520f, + 0.992479562759399410f, 0.989176511764526370f, + 0.985277652740478520f, 0.980785250663757320f, 0.975702106952667240f, + 0.970031261444091800f, 0.963776051998138430f, 0.956940352916717530f, + 0.949528157711029050f, 0.941544055938720700f, + 0.932992815971374510f, 0.923879504203796390f, 0.914209783077239990f, + 0.903989315032958980f, 0.893224298954010010f, 0.881921291351318360f, + 0.870086967945098880f, 0.857728600502014160f, + 0.844853579998016360f, 0.831469595432281490f, 0.817584812641143800f, + 0.803207516670227050f, 0.788346409797668460f, 0.773010432720184330f, + 0.757208824157714840f, 0.740951120853424070f, + 0.724247097969055180f, 0.707106769084930420f, 0.689540565013885500f, + 0.671558976173400880f, 0.653172850608825680f, 0.634393274784088130f, + 0.615231573581695560f, 0.595699310302734380f, + 0.575808167457580570f, 0.555570244789123540f, 0.534997642040252690f, + 0.514102756977081300f, 0.492898195981979370f, 0.471396744251251220f, + 0.449611335992813110f, 0.427555084228515630f, + 0.405241310596466060f, 0.382683426141738890f, 0.359895050525665280f, + 0.336889863014221190f, 0.313681751489639280f, 0.290284663438797000f, + 0.266712754964828490f, 0.242980182170867920f, + 0.219101235270500180f, 0.195090323686599730f, 0.170961886644363400f, + 0.146730467677116390f, 0.122410677373409270f, 0.098017141222953796f, + 0.073564566671848297f, 0.049067676067352295f, + 0.024541229009628296f, 0.000000000000000122f, -0.024541229009628296f, + -0.049067676067352295f, -0.073564566671848297f, -0.098017141222953796f, + -0.122410677373409270f, -0.146730467677116390f, + -0.170961886644363400f, -0.195090323686599730f, -0.219101235270500180f, + -0.242980182170867920f, -0.266712754964828490f, -0.290284663438797000f, + -0.313681751489639280f, -0.336889863014221190f, + -0.359895050525665280f, -0.382683426141738890f, -0.405241310596466060f, + -0.427555084228515630f, -0.449611335992813110f, -0.471396744251251220f, + -0.492898195981979370f, -0.514102756977081300f, + -0.534997642040252690f, -0.555570244789123540f, -0.575808167457580570f, + -0.595699310302734380f, -0.615231573581695560f, -0.634393274784088130f, + -0.653172850608825680f, -0.671558976173400880f, + -0.689540565013885500f, -0.707106769084930420f, -0.724247097969055180f, + -0.740951120853424070f, -0.757208824157714840f, -0.773010432720184330f, + -0.788346409797668460f, -0.803207516670227050f, + -0.817584812641143800f, -0.831469595432281490f, -0.844853579998016360f, + -0.857728600502014160f, -0.870086967945098880f, -0.881921291351318360f, + -0.893224298954010010f, -0.903989315032958980f, + -0.914209783077239990f, -0.923879504203796390f, -0.932992815971374510f, + -0.941544055938720700f, -0.949528157711029050f, -0.956940352916717530f, + -0.963776051998138430f, -0.970031261444091800f, + -0.975702106952667240f, -0.980785250663757320f, -0.985277652740478520f, + -0.989176511764526370f, -0.992479562759399410f, -0.995184719562530520f, + -0.997290432453155520f, -0.998795449733734130f, + -0.999698817729949950f, -1.000000000000000000f, -0.999698817729949950f, + -0.998795449733734130f, -0.997290432453155520f, -0.995184719562530520f, + -0.992479562759399410f, -0.989176511764526370f, + -0.985277652740478520f, -0.980785250663757320f, -0.975702106952667240f, + -0.970031261444091800f, -0.963776051998138430f, -0.956940352916717530f, + -0.949528157711029050f, -0.941544055938720700f, + -0.932992815971374510f, -0.923879504203796390f, -0.914209783077239990f, + -0.903989315032958980f, -0.893224298954010010f, -0.881921291351318360f, + -0.870086967945098880f, -0.857728600502014160f, + -0.844853579998016360f, -0.831469595432281490f, -0.817584812641143800f, + -0.803207516670227050f, -0.788346409797668460f, -0.773010432720184330f, + -0.757208824157714840f, -0.740951120853424070f, + -0.724247097969055180f, -0.707106769084930420f, -0.689540565013885500f, + -0.671558976173400880f, -0.653172850608825680f, -0.634393274784088130f, + -0.615231573581695560f, -0.595699310302734380f, + -0.575808167457580570f, -0.555570244789123540f, -0.534997642040252690f, + -0.514102756977081300f, -0.492898195981979370f, -0.471396744251251220f, + -0.449611335992813110f, -0.427555084228515630f, + -0.405241310596466060f, -0.382683426141738890f, -0.359895050525665280f, + -0.336889863014221190f, -0.313681751489639280f, -0.290284663438797000f, + -0.266712754964828490f, -0.242980182170867920f, + -0.219101235270500180f, -0.195090323686599730f, -0.170961886644363400f, + -0.146730467677116390f, -0.122410677373409270f, -0.098017141222953796f, + -0.073564566671848297f, -0.049067676067352295f, + -0.024541229009628296f, -0.000000000000000245f, 0.024541229009628296f +}; + + +/** + * @brief Fast approximation to the trigonometric sine function for floating-point data. + * @param[in] x input value in radians. + * @return sin(x). + */ + +float32_t arm_sin_f32( + float32_t x) +{ + float32_t sinVal, fract, in; /* Temporary variables for input, output */ + uint32_t index; /* Index variable */ + uint32_t tableSize = (uint32_t) TABLE_SIZE; /* Initialise tablesize */ + float32_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ + float32_t a, b, c, d; /* Four nearest output values */ + float32_t *tablePtr; /* Pointer to table */ + int32_t n; + + /* input x is in radians */ + /* Scale the input to [0 1] range from [0 2*PI] , divide input by 2*pi */ + in = x * 0.159154943092f; + + /* Calculation of floor value of input */ + n = (int32_t) in; + + /* Make negative values towards -infinity */ + if(x < 0.0f) + { + n = n - 1; + } + + /* Map input value to [0 1] */ + in = in - (float32_t) n; + + /* Calculation of index of the table */ + index = (uint32_t) (tableSize * in); + + /* fractional value calculation */ + fract = ((float32_t) tableSize * in) - (float32_t) index; + + /* Initialise table pointer */ + tablePtr = (float32_t *) & sinTable[index]; + + /* Read four nearest values of output value from the sin table */ + a = *tablePtr++; + b = *tablePtr++; + c = *tablePtr++; + d = *tablePtr++; + + /* Cubic interpolation process */ + wa = -(((0.166666667f) * (fract * (fract * fract))) + + ((0.3333333333333f) * fract)) + ((0.5f) * (fract * fract)); + wb = (((0.5f) * (fract * (fract * fract))) - + ((fract * fract) + ((0.5f) * fract))) + 1.0f; + wc = (-((0.5f) * (fract * (fract * fract))) + + ((0.5f) * (fract * fract))) + fract; + wd = ((0.166666667f) * (fract * (fract * fract))) - + ((0.166666667f) * fract); + + /* Calculate sin value */ + sinVal = ((a * wa) + (b * wb)) + ((c * wc) + (d * wd)); + + /* Return the output value */ + return (sinVal); + +} + +/** + * @} end of sin group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_q15.c index d796fc7d4..8f3f3650b 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_q15.c @@ -1,192 +1,192 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_sin_q15.c -* -* Description: Fast sine calculation for Q15 values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFastMath - */ - - /** - * @addtogroup sin - * @{ - */ - - -/** - * \par - * Example code for Generation of Q15 Sin Table: - * \par - *
tableSize = 256;   
- * for(n = -1; n < (tableSize + 1); n++)   
- * {   
- *	sinTable[n+1]=sin(2*pi*n/tableSize);   
- * } 
- * where pi value is 3.14159265358979 - * \par - * Convert Floating point to Q15(Fixed point): - * (sinTable[i] * pow(2, 15)) - * \par - * rounding to nearest integer is done - * sinTable[i] += (sinTable[i] > 0 ? 0.5 :-0.5); - */ - - -static const q15_t sinTableQ15[259] = { - 0xfcdc, 0x0, 0x324, 0x648, 0x96b, 0xc8c, 0xfab, 0x12c8, - 0x15e2, 0x18f9, 0x1c0c, 0x1f1a, 0x2224, 0x2528, 0x2827, 0x2b1f, - 0x2e11, 0x30fc, 0x33df, 0x36ba, 0x398d, 0x3c57, 0x3f17, 0x41ce, - 0x447b, 0x471d, 0x49b4, 0x4c40, 0x4ec0, 0x5134, 0x539b, 0x55f6, - 0x5843, 0x5a82, 0x5cb4, 0x5ed7, 0x60ec, 0x62f2, 0x64e9, 0x66d0, - 0x68a7, 0x6a6e, 0x6c24, 0x6dca, 0x6f5f, 0x70e3, 0x7255, 0x73b6, - 0x7505, 0x7642, 0x776c, 0x7885, 0x798a, 0x7a7d, 0x7b5d, 0x7c2a, - 0x7ce4, 0x7d8a, 0x7e1e, 0x7e9d, 0x7f0a, 0x7f62, 0x7fa7, 0x7fd9, - 0x7ff6, 0x7fff, 0x7ff6, 0x7fd9, 0x7fa7, 0x7f62, 0x7f0a, 0x7e9d, - 0x7e1e, 0x7d8a, 0x7ce4, 0x7c2a, 0x7b5d, 0x7a7d, 0x798a, 0x7885, - 0x776c, 0x7642, 0x7505, 0x73b6, 0x7255, 0x70e3, 0x6f5f, 0x6dca, - 0x6c24, 0x6a6e, 0x68a7, 0x66d0, 0x64e9, 0x62f2, 0x60ec, 0x5ed7, - 0x5cb4, 0x5a82, 0x5843, 0x55f6, 0x539b, 0x5134, 0x4ec0, 0x4c40, - 0x49b4, 0x471d, 0x447b, 0x41ce, 0x3f17, 0x3c57, 0x398d, 0x36ba, - 0x33df, 0x30fc, 0x2e11, 0x2b1f, 0x2827, 0x2528, 0x2224, 0x1f1a, - 0x1c0c, 0x18f9, 0x15e2, 0x12c8, 0xfab, 0xc8c, 0x96b, 0x648, - 0x324, 0x0, 0xfcdc, 0xf9b8, 0xf695, 0xf374, 0xf055, 0xed38, - 0xea1e, 0xe707, 0xe3f4, 0xe0e6, 0xdddc, 0xdad8, 0xd7d9, 0xd4e1, - 0xd1ef, 0xcf04, 0xcc21, 0xc946, 0xc673, 0xc3a9, 0xc0e9, 0xbe32, - 0xbb85, 0xb8e3, 0xb64c, 0xb3c0, 0xb140, 0xaecc, 0xac65, 0xaa0a, - 0xa7bd, 0xa57e, 0xa34c, 0xa129, 0x9f14, 0x9d0e, 0x9b17, 0x9930, - 0x9759, 0x9592, 0x93dc, 0x9236, 0x90a1, 0x8f1d, 0x8dab, 0x8c4a, - 0x8afb, 0x89be, 0x8894, 0x877b, 0x8676, 0x8583, 0x84a3, 0x83d6, - 0x831c, 0x8276, 0x81e2, 0x8163, 0x80f6, 0x809e, 0x8059, 0x8027, - 0x800a, 0x8000, 0x800a, 0x8027, 0x8059, 0x809e, 0x80f6, 0x8163, - 0x81e2, 0x8276, 0x831c, 0x83d6, 0x84a3, 0x8583, 0x8676, 0x877b, - 0x8894, 0x89be, 0x8afb, 0x8c4a, 0x8dab, 0x8f1d, 0x90a1, 0x9236, - 0x93dc, 0x9592, 0x9759, 0x9930, 0x9b17, 0x9d0e, 0x9f14, 0xa129, - 0xa34c, 0xa57e, 0xa7bd, 0xaa0a, 0xac65, 0xaecc, 0xb140, 0xb3c0, - 0xb64c, 0xb8e3, 0xbb85, 0xbe32, 0xc0e9, 0xc3a9, 0xc673, 0xc946, - 0xcc21, 0xcf04, 0xd1ef, 0xd4e1, 0xd7d9, 0xdad8, 0xdddc, 0xe0e6, - 0xe3f4, 0xe707, 0xea1e, 0xed38, 0xf055, 0xf374, 0xf695, 0xf9b8, - 0xfcdc, 0x0, 0x324 -}; - - -/** - * @brief Fast approximation to the trigonometric sine function for Q15 data. - * @param[in] x Scaled input value in radians. - * @return sin(x). - * - * The Q15 input value is in the range [0 +1) and is mapped to a radian value in the range [0 2*pi). - */ - -q15_t arm_sin_q15( - q15_t x) -{ - q31_t sinVal; /* Temporary variables output */ - q15_t *tablePtr; /* Pointer to table */ - q15_t fract, in, in2; /* Temporary variables for input, output */ - q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ - q15_t a, b, c, d; /* Four nearest output values */ - q15_t fractCube, fractSquare; /* Temporary values for fractional value */ - q15_t oneBy6 = 0x1555; /* Fixed point value of 1/6 */ - q15_t tableSpacing = TABLE_SPACING_Q15; /* Table spacing */ - int32_t index; /* Index variable */ - - in = x; - - /* Calculate the nearest index */ - index = (int32_t) in / tableSpacing; - - /* Calculate the nearest value of input */ - in2 = (q15_t) ((index) * tableSpacing); - - /* Calculation of fractional value */ - fract = (in - in2) << 8; - - /* fractSquare = fract * fract */ - fractSquare = (q15_t) ((fract * fract) >> 15); - - /* fractCube = fract * fract * fract */ - fractCube = (q15_t) ((fractSquare * fract) >> 15); - - /* Initialise table pointer */ - tablePtr = (q15_t *) & sinTableQ15[index]; - - /* Cubic interpolation process */ - /* Calculation of wa */ - /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAA)*fract; */ - wa = (q31_t) oneBy6 *fractCube; - wa += (q31_t) 0x2AAA *fract; - wa = -(wa >> 15); - wa += ((q31_t) fractSquare >> 1u); - - /* Read first nearest value of output from the sin table */ - a = *tablePtr++; - - /* sinVal = a * wa */ - sinVal = a * wa; - - /* Calculation of wb */ - wb = (((q31_t) fractCube >> 1u) - (q31_t) fractSquare) - - (((q31_t) fract >> 1u) - 0x7FFF); - - /* Read second nearest value of output from the sin table */ - b = *tablePtr++; - - /* sinVal += b*wb */ - sinVal += b * wb; - - - /* Calculation of wc */ - wc = -(q31_t) fractCube + fractSquare; - wc = (wc >> 1u) + fract; - - /* Read third nearest value of output from the sin table */ - c = *tablePtr++; - - /* sinVal += c*wc */ - sinVal += c * wc; - - /* Calculation of wd */ - /* wd = (oneBy6)*fractCube - (oneBy6)*fract; */ - fractCube = fractCube - fract; - wd = ((q15_t) (((q31_t) oneBy6 * fractCube) >> 15)); - - /* Read fourth nearest value of output from the sin table */ - d = *tablePtr++; - - /* sinVal += d*wd; */ - sinVal += d * wd; - - /* Return the output value in 1.15(q15) format */ - return ((q15_t) (sinVal >> 15u)); - -} - -/** - * @} end of sin group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sin_q15.c +* +* Description: Fast sine calculation for Q15 values. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFastMath + */ + + /** + * @addtogroup sin + * @{ + */ + + +/** + * \par + * Example code for Generation of Q15 Sin Table: + * \par + *
tableSize = 256;   
+ * for(n = -1; n < (tableSize + 1); n++)   
+ * {   
+ *	sinTable[n+1]=sin(2*pi*n/tableSize);   
+ * } 
+ * where pi value is 3.14159265358979 + * \par + * Convert Floating point to Q15(Fixed point): + * (sinTable[i] * pow(2, 15)) + * \par + * rounding to nearest integer is done + * sinTable[i] += (sinTable[i] > 0 ? 0.5 :-0.5); + */ + + +static const q15_t sinTableQ15[259] = { + 0xfcdc, 0x0, 0x324, 0x648, 0x96b, 0xc8c, 0xfab, 0x12c8, + 0x15e2, 0x18f9, 0x1c0c, 0x1f1a, 0x2224, 0x2528, 0x2827, 0x2b1f, + 0x2e11, 0x30fc, 0x33df, 0x36ba, 0x398d, 0x3c57, 0x3f17, 0x41ce, + 0x447b, 0x471d, 0x49b4, 0x4c40, 0x4ec0, 0x5134, 0x539b, 0x55f6, + 0x5843, 0x5a82, 0x5cb4, 0x5ed7, 0x60ec, 0x62f2, 0x64e9, 0x66d0, + 0x68a7, 0x6a6e, 0x6c24, 0x6dca, 0x6f5f, 0x70e3, 0x7255, 0x73b6, + 0x7505, 0x7642, 0x776c, 0x7885, 0x798a, 0x7a7d, 0x7b5d, 0x7c2a, + 0x7ce4, 0x7d8a, 0x7e1e, 0x7e9d, 0x7f0a, 0x7f62, 0x7fa7, 0x7fd9, + 0x7ff6, 0x7fff, 0x7ff6, 0x7fd9, 0x7fa7, 0x7f62, 0x7f0a, 0x7e9d, + 0x7e1e, 0x7d8a, 0x7ce4, 0x7c2a, 0x7b5d, 0x7a7d, 0x798a, 0x7885, + 0x776c, 0x7642, 0x7505, 0x73b6, 0x7255, 0x70e3, 0x6f5f, 0x6dca, + 0x6c24, 0x6a6e, 0x68a7, 0x66d0, 0x64e9, 0x62f2, 0x60ec, 0x5ed7, + 0x5cb4, 0x5a82, 0x5843, 0x55f6, 0x539b, 0x5134, 0x4ec0, 0x4c40, + 0x49b4, 0x471d, 0x447b, 0x41ce, 0x3f17, 0x3c57, 0x398d, 0x36ba, + 0x33df, 0x30fc, 0x2e11, 0x2b1f, 0x2827, 0x2528, 0x2224, 0x1f1a, + 0x1c0c, 0x18f9, 0x15e2, 0x12c8, 0xfab, 0xc8c, 0x96b, 0x648, + 0x324, 0x0, 0xfcdc, 0xf9b8, 0xf695, 0xf374, 0xf055, 0xed38, + 0xea1e, 0xe707, 0xe3f4, 0xe0e6, 0xdddc, 0xdad8, 0xd7d9, 0xd4e1, + 0xd1ef, 0xcf04, 0xcc21, 0xc946, 0xc673, 0xc3a9, 0xc0e9, 0xbe32, + 0xbb85, 0xb8e3, 0xb64c, 0xb3c0, 0xb140, 0xaecc, 0xac65, 0xaa0a, + 0xa7bd, 0xa57e, 0xa34c, 0xa129, 0x9f14, 0x9d0e, 0x9b17, 0x9930, + 0x9759, 0x9592, 0x93dc, 0x9236, 0x90a1, 0x8f1d, 0x8dab, 0x8c4a, + 0x8afb, 0x89be, 0x8894, 0x877b, 0x8676, 0x8583, 0x84a3, 0x83d6, + 0x831c, 0x8276, 0x81e2, 0x8163, 0x80f6, 0x809e, 0x8059, 0x8027, + 0x800a, 0x8000, 0x800a, 0x8027, 0x8059, 0x809e, 0x80f6, 0x8163, + 0x81e2, 0x8276, 0x831c, 0x83d6, 0x84a3, 0x8583, 0x8676, 0x877b, + 0x8894, 0x89be, 0x8afb, 0x8c4a, 0x8dab, 0x8f1d, 0x90a1, 0x9236, + 0x93dc, 0x9592, 0x9759, 0x9930, 0x9b17, 0x9d0e, 0x9f14, 0xa129, + 0xa34c, 0xa57e, 0xa7bd, 0xaa0a, 0xac65, 0xaecc, 0xb140, 0xb3c0, + 0xb64c, 0xb8e3, 0xbb85, 0xbe32, 0xc0e9, 0xc3a9, 0xc673, 0xc946, + 0xcc21, 0xcf04, 0xd1ef, 0xd4e1, 0xd7d9, 0xdad8, 0xdddc, 0xe0e6, + 0xe3f4, 0xe707, 0xea1e, 0xed38, 0xf055, 0xf374, 0xf695, 0xf9b8, + 0xfcdc, 0x0, 0x324 +}; + + +/** + * @brief Fast approximation to the trigonometric sine function for Q15 data. + * @param[in] x Scaled input value in radians. + * @return sin(x). + * + * The Q15 input value is in the range [0 +1) and is mapped to a radian value in the range [0 2*pi). + */ + +q15_t arm_sin_q15( + q15_t x) +{ + q31_t sinVal; /* Temporary variables output */ + q15_t *tablePtr; /* Pointer to table */ + q15_t fract, in, in2; /* Temporary variables for input, output */ + q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ + q15_t a, b, c, d; /* Four nearest output values */ + q15_t fractCube, fractSquare; /* Temporary values for fractional value */ + q15_t oneBy6 = 0x1555; /* Fixed point value of 1/6 */ + q15_t tableSpacing = TABLE_SPACING_Q15; /* Table spacing */ + int32_t index; /* Index variable */ + + in = x; + + /* Calculate the nearest index */ + index = (int32_t) in / tableSpacing; + + /* Calculate the nearest value of input */ + in2 = (q15_t) ((index) * tableSpacing); + + /* Calculation of fractional value */ + fract = (in - in2) << 8; + + /* fractSquare = fract * fract */ + fractSquare = (q15_t) ((fract * fract) >> 15); + + /* fractCube = fract * fract * fract */ + fractCube = (q15_t) ((fractSquare * fract) >> 15); + + /* Initialise table pointer */ + tablePtr = (q15_t *) & sinTableQ15[index]; + + /* Cubic interpolation process */ + /* Calculation of wa */ + /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAA)*fract; */ + wa = (q31_t) oneBy6 *fractCube; + wa += (q31_t) 0x2AAA *fract; + wa = -(wa >> 15); + wa += ((q31_t) fractSquare >> 1u); + + /* Read first nearest value of output from the sin table */ + a = *tablePtr++; + + /* sinVal = a * wa */ + sinVal = a * wa; + + /* Calculation of wb */ + wb = (((q31_t) fractCube >> 1u) - (q31_t) fractSquare) - + (((q31_t) fract >> 1u) - 0x7FFF); + + /* Read second nearest value of output from the sin table */ + b = *tablePtr++; + + /* sinVal += b*wb */ + sinVal += b * wb; + + + /* Calculation of wc */ + wc = -(q31_t) fractCube + fractSquare; + wc = (wc >> 1u) + fract; + + /* Read third nearest value of output from the sin table */ + c = *tablePtr++; + + /* sinVal += c*wc */ + sinVal += c * wc; + + /* Calculation of wd */ + /* wd = (oneBy6)*fractCube - (oneBy6)*fract; */ + fractCube = fractCube - fract; + wd = ((q15_t) (((q31_t) oneBy6 * fractCube) >> 15)); + + /* Read fourth nearest value of output from the sin table */ + d = *tablePtr++; + + /* sinVal += d*wd; */ + sinVal += d * wd; + + /* Return the output value in 1.15(q15) format */ + return ((q15_t) (sinVal >> 15u)); + +} + +/** + * @} end of sin group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_q31.c index 0ab10573d..28b58ab3d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sin_q31.c @@ -1,227 +1,227 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_sin_q31.c -* -* Description: Fast sine calculation for Q31 values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFastMath - */ - - /** - * @addtogroup sin - * @{ - */ - -/** - * \par - * Tables generated are in Q31(1.31 Fixed point format) - * Generation of sin values in floating point: - *
tableSize = 256;     
- * for(n = -1; n < (tableSize + 1); n++)   
- * {   
- *	sinTable[n+1]= sin(2*pi*n/tableSize);   
- * } 
- * where pi value is 3.14159265358979 - * \par - * Convert Floating point to Q31(Fixed point): - * (sinTable[i] * pow(2, 31)) - * \par - * rounding to nearest integer is done - * sinTable[i] += (sinTable[i] > 0 ? 0.5 :-0.5); - */ - -static const q31_t sinTableQ31[259] = { - 0xfcdbd541, 0x0, 0x3242abf, 0x647d97c, 0x96a9049, 0xc8bd35e, 0xfab272b, - 0x12c8106f, - 0x15e21445, 0x18f8b83c, 0x1c0b826a, 0x1f19f97b, 0x2223a4c5, 0x25280c5e, - 0x2826b928, 0x2b1f34eb, - 0x2e110a62, 0x30fbc54d, 0x33def287, 0x36ba2014, 0x398cdd32, 0x3c56ba70, - 0x3f1749b8, 0x41ce1e65, - 0x447acd50, 0x471cece7, 0x49b41533, 0x4c3fdff4, 0x4ebfe8a5, 0x5133cc94, - 0x539b2af0, 0x55f5a4d2, - 0x5842dd54, 0x5a82799a, 0x5cb420e0, 0x5ed77c8a, 0x60ec3830, 0x62f201ac, - 0x64e88926, 0x66cf8120, - 0x68a69e81, 0x6a6d98a4, 0x6c242960, 0x6dca0d14, 0x6f5f02b2, 0x70e2cbc6, - 0x72552c85, 0x73b5ebd1, - 0x7504d345, 0x7641af3d, 0x776c4edb, 0x78848414, 0x798a23b1, 0x7a7d055b, - 0x7b5d039e, 0x7c29fbee, - 0x7ce3ceb2, 0x7d8a5f40, 0x7e1d93ea, 0x7e9d55fc, 0x7f0991c4, 0x7f62368f, - 0x7fa736b4, 0x7fd8878e, - 0x7ff62182, 0x7fffffff, 0x7ff62182, 0x7fd8878e, 0x7fa736b4, 0x7f62368f, - 0x7f0991c4, 0x7e9d55fc, - 0x7e1d93ea, 0x7d8a5f40, 0x7ce3ceb2, 0x7c29fbee, 0x7b5d039e, 0x7a7d055b, - 0x798a23b1, 0x78848414, - 0x776c4edb, 0x7641af3d, 0x7504d345, 0x73b5ebd1, 0x72552c85, 0x70e2cbc6, - 0x6f5f02b2, 0x6dca0d14, - 0x6c242960, 0x6a6d98a4, 0x68a69e81, 0x66cf8120, 0x64e88926, 0x62f201ac, - 0x60ec3830, 0x5ed77c8a, - 0x5cb420e0, 0x5a82799a, 0x5842dd54, 0x55f5a4d2, 0x539b2af0, 0x5133cc94, - 0x4ebfe8a5, 0x4c3fdff4, - 0x49b41533, 0x471cece7, 0x447acd50, 0x41ce1e65, 0x3f1749b8, 0x3c56ba70, - 0x398cdd32, 0x36ba2014, - 0x33def287, 0x30fbc54d, 0x2e110a62, 0x2b1f34eb, 0x2826b928, 0x25280c5e, - 0x2223a4c5, 0x1f19f97b, - 0x1c0b826a, 0x18f8b83c, 0x15e21445, 0x12c8106f, 0xfab272b, 0xc8bd35e, - 0x96a9049, 0x647d97c, - 0x3242abf, 0x0, 0xfcdbd541, 0xf9b82684, 0xf6956fb7, 0xf3742ca2, 0xf054d8d5, - 0xed37ef91, - 0xea1debbb, 0xe70747c4, 0xe3f47d96, 0xe0e60685, 0xdddc5b3b, 0xdad7f3a2, - 0xd7d946d8, 0xd4e0cb15, - 0xd1eef59e, 0xcf043ab3, 0xcc210d79, 0xc945dfec, 0xc67322ce, 0xc3a94590, - 0xc0e8b648, 0xbe31e19b, - 0xbb8532b0, 0xb8e31319, 0xb64beacd, 0xb3c0200c, 0xb140175b, 0xaecc336c, - 0xac64d510, 0xaa0a5b2e, - 0xa7bd22ac, 0xa57d8666, 0xa34bdf20, 0xa1288376, 0x9f13c7d0, 0x9d0dfe54, - 0x9b1776da, 0x99307ee0, - 0x9759617f, 0x9592675c, 0x93dbd6a0, 0x9235f2ec, 0x90a0fd4e, 0x8f1d343a, - 0x8daad37b, 0x8c4a142f, - 0x8afb2cbb, 0x89be50c3, 0x8893b125, 0x877b7bec, 0x8675dc4f, 0x8582faa5, - 0x84a2fc62, 0x83d60412, - 0x831c314e, 0x8275a0c0, 0x81e26c16, 0x8162aa04, 0x80f66e3c, 0x809dc971, - 0x8058c94c, 0x80277872, - 0x8009de7e, 0x80000000, 0x8009de7e, 0x80277872, 0x8058c94c, 0x809dc971, - 0x80f66e3c, 0x8162aa04, - 0x81e26c16, 0x8275a0c0, 0x831c314e, 0x83d60412, 0x84a2fc62, 0x8582faa5, - 0x8675dc4f, 0x877b7bec, - 0x8893b125, 0x89be50c3, 0x8afb2cbb, 0x8c4a142f, 0x8daad37b, 0x8f1d343a, - 0x90a0fd4e, 0x9235f2ec, - 0x93dbd6a0, 0x9592675c, 0x9759617f, 0x99307ee0, 0x9b1776da, 0x9d0dfe54, - 0x9f13c7d0, 0xa1288376, - 0xa34bdf20, 0xa57d8666, 0xa7bd22ac, 0xaa0a5b2e, 0xac64d510, 0xaecc336c, - 0xb140175b, 0xb3c0200c, - 0xb64beacd, 0xb8e31319, 0xbb8532b0, 0xbe31e19b, 0xc0e8b648, 0xc3a94590, - 0xc67322ce, 0xc945dfec, - 0xcc210d79, 0xcf043ab3, 0xd1eef59e, 0xd4e0cb15, 0xd7d946d8, 0xdad7f3a2, - 0xdddc5b3b, 0xe0e60685, - 0xe3f47d96, 0xe70747c4, 0xea1debbb, 0xed37ef91, 0xf054d8d5, 0xf3742ca2, - 0xf6956fb7, 0xf9b82684, - 0xfcdbd541, 0x0, 0x3242abf -}; - - -/** - * @brief Fast approximation to the trigonometric sine function for Q31 data. - * @param[in] x Scaled input value in radians. - * @return sin(x). - * - * The Q31 input value is in the range [0 +1) and is mapped to a radian value in the range [0 2*pi). - */ - -q31_t arm_sin_q31( - q31_t x) -{ - q31_t sinVal, in, in2; /* Temporary variables for input, output */ - uint32_t index; /* Index variables */ - q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ - q31_t a, b, c, d; /* Four nearest output values */ - q31_t *tablePtr; /* Pointer to table */ - q31_t fract, fractCube, fractSquare; /* Temporary values for fractional values */ - q31_t oneBy6 = 0x15555555; /* Fixed point value of 1/6 */ - q31_t tableSpacing = TABLE_SPACING_Q31; /* Table spacing */ - q31_t temp; /* Temporary variable for intermediate process */ - - in = x; - - /* Calculate the nearest index */ - index = (uint32_t) in / (uint32_t) tableSpacing; - - /* Calculate the nearest value of input */ - in2 = (q31_t) index *tableSpacing; - - /* Calculation of fractional value */ - fract = (in - in2) << 8; - - /* fractSquare = fract * fract */ - fractSquare = ((q31_t) (((q63_t) fract * fract) >> 32)); - fractSquare = fractSquare << 1; - - /* fractCube = fract * fract * fract */ - fractCube = ((q31_t) (((q63_t) fractSquare * fract) >> 32)); - fractCube = fractCube << 1; - - /* Initialise table pointer */ - tablePtr = (q31_t *) & sinTableQ31[index]; - - /* Cubic interpolation process */ - /* Calculation of wa */ - /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAAAAAA)*fract; */ - wa = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); - temp = 0x2AAAAAAA; - wa = (q31_t) ((((q63_t) wa << 32) + ((q63_t) temp * fract)) >> 32); - wa = -(wa << 1u); - wa += (fractSquare >> 1u); - - /* Read first nearest value of output from the sin table */ - a = *tablePtr++; - - /* sinVal = a*wa */ - sinVal = ((q31_t) (((q63_t) a * wa) >> 32)); - - /* q31(1.31) Fixed point value of 1 */ - temp = 0x7FFFFFFF; - - /* Calculation of wb */ - wb = ((fractCube >> 1u) - (fractSquare + (fract >> 1u))) + temp; - - /* Read second nearest value of output from the sin table */ - b = *tablePtr++; - - /* sinVal += b*wb */ - sinVal = (q31_t) ((((q63_t) sinVal << 32) + (q63_t) b * (wb)) >> 32); - - /* Calculation of wc */ - wc = -fractCube + fractSquare; - wc = (wc >> 1u) + fract; - - /* Read third nearest value of output from the sin table */ - c = *tablePtr++; - - /* sinVal += c*wc */ - sinVal = (q31_t) ((((q63_t) sinVal << 32) + ((q63_t) c * wc)) >> 32); - - /* Calculation of wd */ - /* wd = (oneBy6) * fractCube - (oneBy6) * fract; */ - fractCube = fractCube - fract; - wd = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); - wd = (wd << 1u); - - /* Read fourth nearest value of output from the sin table */ - d = *tablePtr++; - - /* sinVal += d*wd; */ - sinVal = (q31_t) ((((q63_t) sinVal << 32) + ((q63_t) d * wd)) >> 32); - - /* convert sinVal in 2.30 format to 1.31 format */ - return (sinVal << 1u); - -} - -/** - * @} end of sin group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sin_q31.c +* +* Description: Fast sine calculation for Q31 values. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFastMath + */ + + /** + * @addtogroup sin + * @{ + */ + +/** + * \par + * Tables generated are in Q31(1.31 Fixed point format) + * Generation of sin values in floating point: + *
tableSize = 256;     
+ * for(n = -1; n < (tableSize + 1); n++)   
+ * {   
+ *	sinTable[n+1]= sin(2*pi*n/tableSize);   
+ * } 
+ * where pi value is 3.14159265358979 + * \par + * Convert Floating point to Q31(Fixed point): + * (sinTable[i] * pow(2, 31)) + * \par + * rounding to nearest integer is done + * sinTable[i] += (sinTable[i] > 0 ? 0.5 :-0.5); + */ + +static const q31_t sinTableQ31[259] = { + 0xfcdbd541, 0x0, 0x3242abf, 0x647d97c, 0x96a9049, 0xc8bd35e, 0xfab272b, + 0x12c8106f, + 0x15e21445, 0x18f8b83c, 0x1c0b826a, 0x1f19f97b, 0x2223a4c5, 0x25280c5e, + 0x2826b928, 0x2b1f34eb, + 0x2e110a62, 0x30fbc54d, 0x33def287, 0x36ba2014, 0x398cdd32, 0x3c56ba70, + 0x3f1749b8, 0x41ce1e65, + 0x447acd50, 0x471cece7, 0x49b41533, 0x4c3fdff4, 0x4ebfe8a5, 0x5133cc94, + 0x539b2af0, 0x55f5a4d2, + 0x5842dd54, 0x5a82799a, 0x5cb420e0, 0x5ed77c8a, 0x60ec3830, 0x62f201ac, + 0x64e88926, 0x66cf8120, + 0x68a69e81, 0x6a6d98a4, 0x6c242960, 0x6dca0d14, 0x6f5f02b2, 0x70e2cbc6, + 0x72552c85, 0x73b5ebd1, + 0x7504d345, 0x7641af3d, 0x776c4edb, 0x78848414, 0x798a23b1, 0x7a7d055b, + 0x7b5d039e, 0x7c29fbee, + 0x7ce3ceb2, 0x7d8a5f40, 0x7e1d93ea, 0x7e9d55fc, 0x7f0991c4, 0x7f62368f, + 0x7fa736b4, 0x7fd8878e, + 0x7ff62182, 0x7fffffff, 0x7ff62182, 0x7fd8878e, 0x7fa736b4, 0x7f62368f, + 0x7f0991c4, 0x7e9d55fc, + 0x7e1d93ea, 0x7d8a5f40, 0x7ce3ceb2, 0x7c29fbee, 0x7b5d039e, 0x7a7d055b, + 0x798a23b1, 0x78848414, + 0x776c4edb, 0x7641af3d, 0x7504d345, 0x73b5ebd1, 0x72552c85, 0x70e2cbc6, + 0x6f5f02b2, 0x6dca0d14, + 0x6c242960, 0x6a6d98a4, 0x68a69e81, 0x66cf8120, 0x64e88926, 0x62f201ac, + 0x60ec3830, 0x5ed77c8a, + 0x5cb420e0, 0x5a82799a, 0x5842dd54, 0x55f5a4d2, 0x539b2af0, 0x5133cc94, + 0x4ebfe8a5, 0x4c3fdff4, + 0x49b41533, 0x471cece7, 0x447acd50, 0x41ce1e65, 0x3f1749b8, 0x3c56ba70, + 0x398cdd32, 0x36ba2014, + 0x33def287, 0x30fbc54d, 0x2e110a62, 0x2b1f34eb, 0x2826b928, 0x25280c5e, + 0x2223a4c5, 0x1f19f97b, + 0x1c0b826a, 0x18f8b83c, 0x15e21445, 0x12c8106f, 0xfab272b, 0xc8bd35e, + 0x96a9049, 0x647d97c, + 0x3242abf, 0x0, 0xfcdbd541, 0xf9b82684, 0xf6956fb7, 0xf3742ca2, 0xf054d8d5, + 0xed37ef91, + 0xea1debbb, 0xe70747c4, 0xe3f47d96, 0xe0e60685, 0xdddc5b3b, 0xdad7f3a2, + 0xd7d946d8, 0xd4e0cb15, + 0xd1eef59e, 0xcf043ab3, 0xcc210d79, 0xc945dfec, 0xc67322ce, 0xc3a94590, + 0xc0e8b648, 0xbe31e19b, + 0xbb8532b0, 0xb8e31319, 0xb64beacd, 0xb3c0200c, 0xb140175b, 0xaecc336c, + 0xac64d510, 0xaa0a5b2e, + 0xa7bd22ac, 0xa57d8666, 0xa34bdf20, 0xa1288376, 0x9f13c7d0, 0x9d0dfe54, + 0x9b1776da, 0x99307ee0, + 0x9759617f, 0x9592675c, 0x93dbd6a0, 0x9235f2ec, 0x90a0fd4e, 0x8f1d343a, + 0x8daad37b, 0x8c4a142f, + 0x8afb2cbb, 0x89be50c3, 0x8893b125, 0x877b7bec, 0x8675dc4f, 0x8582faa5, + 0x84a2fc62, 0x83d60412, + 0x831c314e, 0x8275a0c0, 0x81e26c16, 0x8162aa04, 0x80f66e3c, 0x809dc971, + 0x8058c94c, 0x80277872, + 0x8009de7e, 0x80000000, 0x8009de7e, 0x80277872, 0x8058c94c, 0x809dc971, + 0x80f66e3c, 0x8162aa04, + 0x81e26c16, 0x8275a0c0, 0x831c314e, 0x83d60412, 0x84a2fc62, 0x8582faa5, + 0x8675dc4f, 0x877b7bec, + 0x8893b125, 0x89be50c3, 0x8afb2cbb, 0x8c4a142f, 0x8daad37b, 0x8f1d343a, + 0x90a0fd4e, 0x9235f2ec, + 0x93dbd6a0, 0x9592675c, 0x9759617f, 0x99307ee0, 0x9b1776da, 0x9d0dfe54, + 0x9f13c7d0, 0xa1288376, + 0xa34bdf20, 0xa57d8666, 0xa7bd22ac, 0xaa0a5b2e, 0xac64d510, 0xaecc336c, + 0xb140175b, 0xb3c0200c, + 0xb64beacd, 0xb8e31319, 0xbb8532b0, 0xbe31e19b, 0xc0e8b648, 0xc3a94590, + 0xc67322ce, 0xc945dfec, + 0xcc210d79, 0xcf043ab3, 0xd1eef59e, 0xd4e0cb15, 0xd7d946d8, 0xdad7f3a2, + 0xdddc5b3b, 0xe0e60685, + 0xe3f47d96, 0xe70747c4, 0xea1debbb, 0xed37ef91, 0xf054d8d5, 0xf3742ca2, + 0xf6956fb7, 0xf9b82684, + 0xfcdbd541, 0x0, 0x3242abf +}; + + +/** + * @brief Fast approximation to the trigonometric sine function for Q31 data. + * @param[in] x Scaled input value in radians. + * @return sin(x). + * + * The Q31 input value is in the range [0 +1) and is mapped to a radian value in the range [0 2*pi). + */ + +q31_t arm_sin_q31( + q31_t x) +{ + q31_t sinVal, in, in2; /* Temporary variables for input, output */ + uint32_t index; /* Index variables */ + q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ + q31_t a, b, c, d; /* Four nearest output values */ + q31_t *tablePtr; /* Pointer to table */ + q31_t fract, fractCube, fractSquare; /* Temporary values for fractional values */ + q31_t oneBy6 = 0x15555555; /* Fixed point value of 1/6 */ + q31_t tableSpacing = TABLE_SPACING_Q31; /* Table spacing */ + q31_t temp; /* Temporary variable for intermediate process */ + + in = x; + + /* Calculate the nearest index */ + index = (uint32_t) in / (uint32_t) tableSpacing; + + /* Calculate the nearest value of input */ + in2 = (q31_t) index *tableSpacing; + + /* Calculation of fractional value */ + fract = (in - in2) << 8; + + /* fractSquare = fract * fract */ + fractSquare = ((q31_t) (((q63_t) fract * fract) >> 32)); + fractSquare = fractSquare << 1; + + /* fractCube = fract * fract * fract */ + fractCube = ((q31_t) (((q63_t) fractSquare * fract) >> 32)); + fractCube = fractCube << 1; + + /* Initialise table pointer */ + tablePtr = (q31_t *) & sinTableQ31[index]; + + /* Cubic interpolation process */ + /* Calculation of wa */ + /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAAAAAA)*fract; */ + wa = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); + temp = 0x2AAAAAAA; + wa = (q31_t) ((((q63_t) wa << 32) + ((q63_t) temp * fract)) >> 32); + wa = -(wa << 1u); + wa += (fractSquare >> 1u); + + /* Read first nearest value of output from the sin table */ + a = *tablePtr++; + + /* sinVal = a*wa */ + sinVal = ((q31_t) (((q63_t) a * wa) >> 32)); + + /* q31(1.31) Fixed point value of 1 */ + temp = 0x7FFFFFFF; + + /* Calculation of wb */ + wb = ((fractCube >> 1u) - (fractSquare + (fract >> 1u))) + temp; + + /* Read second nearest value of output from the sin table */ + b = *tablePtr++; + + /* sinVal += b*wb */ + sinVal = (q31_t) ((((q63_t) sinVal << 32) + (q63_t) b * (wb)) >> 32); + + /* Calculation of wc */ + wc = -fractCube + fractSquare; + wc = (wc >> 1u) + fract; + + /* Read third nearest value of output from the sin table */ + c = *tablePtr++; + + /* sinVal += c*wc */ + sinVal = (q31_t) ((((q63_t) sinVal << 32) + ((q63_t) c * wc)) >> 32); + + /* Calculation of wd */ + /* wd = (oneBy6) * fractCube - (oneBy6) * fract; */ + fractCube = fractCube - fract; + wd = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); + wd = (wd << 1u); + + /* Read fourth nearest value of output from the sin table */ + d = *tablePtr++; + + /* sinVal += d*wd; */ + sinVal = (q31_t) ((((q63_t) sinVal << 32) + ((q63_t) d * wd)) >> 32); + + /* convert sinVal in 2.30 format to 1.31 format */ + return (sinVal << 1u); + +} + +/** + * @} end of sin group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q15.c index 7e27baacb..bcd5287f9 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q15.c @@ -1,178 +1,178 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_sqrt_q15.c -* -* Description: Q15 square root function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -#include "arm_common_tables.h" - - -/** - * @ingroup groupFastMath - */ - -/** - * @addtogroup SQRT - * @{ - */ - - /** - * @brief Q15 square root function. - * @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF. - * @param[out] *pOut square root of input value. - * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if - * in is negative value and returns zero output for negative values. - */ - -arm_status arm_sqrt_q15( - q15_t in, - q15_t * pOut) -{ - q31_t prevOut; - q15_t oneByOut; - uint32_t sign_bits; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t out; - - if(in > 0) - { - /* run for ten iterations */ - - /* Take initial guess as half of the input and first iteration */ - out = ((q31_t) in >> 1u) + 0x3FFF; - - /* Calculation of reciprocal of out */ - /* oneByOut contains reciprocal of out which is in 2.14 format - and oneByOut should be upscaled by signBits */ - sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); - - /* 0.5 * (out) */ - out = out >> 1u; - /* prevOut = 0.5 * out + (in * (oneByOut << signBits))) */ - prevOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - - /* Third iteration */ - sign_bits = arm_recip_q15((q15_t) prevOut, &oneByOut, armRecipTableQ15); - prevOut = prevOut >> 1u; - out = prevOut + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - - sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); - out = out >> 1u; - prevOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - - /* Fifth iteration */ - sign_bits = arm_recip_q15((q15_t) prevOut, &oneByOut, armRecipTableQ15); - prevOut = prevOut >> 1u; - out = prevOut + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - - sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); - out = out >> 1u; - prevOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - - /* Seventh iteration */ - sign_bits = arm_recip_q15((q15_t) prevOut, &oneByOut, armRecipTableQ15); - prevOut = prevOut >> 1u; - out = prevOut + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - - sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); - out = out >> 1u; - prevOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - - sign_bits = arm_recip_q15((q15_t) prevOut, &oneByOut, armRecipTableQ15); - prevOut = prevOut >> 1u; - out = prevOut + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - - /* tenth iteration */ - sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); - out = out >> 1u; - *pOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - - return (ARM_MATH_SUCCESS); - } - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t out, loopVar; /* Temporary variable for output, loop variable */ - if(in > 0) - { - /* run for ten iterations */ - - /* Take initial guess as half of the input and first iteration */ - out = ((q31_t) in >> 1u) + 0x3FFF; - - /* Calculation of reciprocal of out */ - - /* oneByOut contains reciprocal of out which is in 2.14 format - and oneByOut should be upscaled by sign bits */ - sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); - - /* 0.5 * (out) */ - out = out >> 1u; - /* prevOut = 0.5 * out + (in * oneByOut) << signbits))) */ - prevOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - - /* loop for third iteration to tenth iteration */ - - for (loopVar = 1; loopVar <= 8; loopVar++) - { - - sign_bits = arm_recip_q15((q15_t) prevOut, &oneByOut, armRecipTableQ15); - /* 0.5 * (prevOut) */ - prevOut = prevOut >> 1u; - /* prevOut = 0.5 * prevOut+ (in * oneByOut) << signbits))) */ - out = - prevOut + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); - /* prevOut = out */ - prevOut = out; - - } - /* output is moved to pOut pointer */ - *pOut = prevOut; - - return (ARM_MATH_SUCCESS); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - else - { - - *pOut = 0; - return (ARM_MATH_ARGUMENT_ERROR); - } - -} - -/** - * @} end of SQRT group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sqrt_q15.c +* +* Description: Q15 square root function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" +#include "arm_common_tables.h" + + +/** + * @ingroup groupFastMath + */ + +/** + * @addtogroup SQRT + * @{ + */ + + /** + * @brief Q15 square root function. + * @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF. + * @param[out] *pOut square root of input value. + * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if + * in is negative value and returns zero output for negative values. + */ + +arm_status arm_sqrt_q15( + q15_t in, + q15_t * pOut) +{ + q31_t prevOut; + q15_t oneByOut; + uint32_t sign_bits; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t out; + + if(in > 0) + { + /* run for ten iterations */ + + /* Take initial guess as half of the input and first iteration */ + out = ((q31_t) in >> 1u) + 0x3FFF; + + /* Calculation of reciprocal of out */ + /* oneByOut contains reciprocal of out which is in 2.14 format + and oneByOut should be upscaled by signBits */ + sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); + + /* 0.5 * (out) */ + out = out >> 1u; + /* prevOut = 0.5 * out + (in * (oneByOut << signBits))) */ + prevOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + + /* Third iteration */ + sign_bits = arm_recip_q15((q15_t) prevOut, &oneByOut, armRecipTableQ15); + prevOut = prevOut >> 1u; + out = prevOut + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + + sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); + out = out >> 1u; + prevOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + + /* Fifth iteration */ + sign_bits = arm_recip_q15((q15_t) prevOut, &oneByOut, armRecipTableQ15); + prevOut = prevOut >> 1u; + out = prevOut + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + + sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); + out = out >> 1u; + prevOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + + /* Seventh iteration */ + sign_bits = arm_recip_q15((q15_t) prevOut, &oneByOut, armRecipTableQ15); + prevOut = prevOut >> 1u; + out = prevOut + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + + sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); + out = out >> 1u; + prevOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + + sign_bits = arm_recip_q15((q15_t) prevOut, &oneByOut, armRecipTableQ15); + prevOut = prevOut >> 1u; + out = prevOut + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + + /* tenth iteration */ + sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); + out = out >> 1u; + *pOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + + return (ARM_MATH_SUCCESS); + } + +#else + + /* Run the below code for Cortex-M0 */ + + q31_t out, loopVar; /* Temporary variable for output, loop variable */ + if(in > 0) + { + /* run for ten iterations */ + + /* Take initial guess as half of the input and first iteration */ + out = ((q31_t) in >> 1u) + 0x3FFF; + + /* Calculation of reciprocal of out */ + + /* oneByOut contains reciprocal of out which is in 2.14 format + and oneByOut should be upscaled by sign bits */ + sign_bits = arm_recip_q15((q15_t) out, &oneByOut, armRecipTableQ15); + + /* 0.5 * (out) */ + out = out >> 1u; + /* prevOut = 0.5 * out + (in * oneByOut) << signbits))) */ + prevOut = out + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + + /* loop for third iteration to tenth iteration */ + + for (loopVar = 1; loopVar <= 8; loopVar++) + { + + sign_bits = arm_recip_q15((q15_t) prevOut, &oneByOut, armRecipTableQ15); + /* 0.5 * (prevOut) */ + prevOut = prevOut >> 1u; + /* prevOut = 0.5 * prevOut+ (in * oneByOut) << signbits))) */ + out = + prevOut + (((q15_t) (((q31_t) in * oneByOut) >> 16)) << sign_bits); + /* prevOut = out */ + prevOut = out; + + } + /* output is moved to pOut pointer */ + *pOut = prevOut; + + return (ARM_MATH_SUCCESS); + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + else + { + + *pOut = 0; + return (ARM_MATH_ARGUMENT_ERROR); + } + +} + +/** + * @} end of SQRT group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q31.c index ab2779e79..043678da3 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q31.c @@ -1,199 +1,199 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_sqrt_q31.c -* -* Description: Q31 square root function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupFastMath - */ - -/** - * @addtogroup SQRT - * @{ - */ - -/** - * @brief Q31 square root function. - * @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF. - * @param[out] *pOut square root of input value. - * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if - * in is negative value and returns zero output for negative values. - */ - -arm_status arm_sqrt_q31( - q31_t in, - q31_t * pOut) -{ - q63_t prevOut; - q31_t oneByOut; - uint32_t signBits; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q63_t out; - - if(in > 0) - { - - /* run for ten iterations */ - - /* Take initial guess as half of the input and first iteration */ - out = (in >> 1) + 0x3FFFFFFF; - - /* Calculation of reciprocal of out */ - /* oneByOut contains reciprocal of out which is in 2.30 format - and oneByOut should be upscaled by signBits */ - signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); - - /* 0.5 * (out) */ - out = out >> 1u; - - /* prevOut = 0.5 * out + (in * (oneByOut << signBits))) */ - prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - /* Third iteration */ - signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); - prevOut = prevOut >> 1u; - out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); - out = out >> 1u; - prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - /* Fifth iteration */ - signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); - prevOut = prevOut >> 1u; - out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); - out = out >> 1u; - prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - /* Seventh iteration */ - signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); - prevOut = prevOut >> 1u; - out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); - out = out >> 1u; - prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); - prevOut = prevOut >> 1u; - out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); - out = out >> 1u; - prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); - prevOut = prevOut >> 1u; - out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); - out = out >> 1u; - prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); - prevOut = prevOut >> 1u; - out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); - out = out >> 1u; - prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); - prevOut = prevOut >> 1u; - out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - /* tenth iteration */ - signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); - out = out >> 1u; - *pOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - return (ARM_MATH_SUCCESS); - } - -#else - - /* Run the below code for Cortex-M0 */ - - q63_t out, loopVar; /* Temporary variable for output, loop variable */ - if(in > 0) - { - - /* run for ten iterations */ - - /* Take initial guess as half of the input and first iteration */ - out = (in >> 1) + 0x3FFFFFFF; - - /* Calculation of reciprocal of out */ - /* oneByOut contains reciprocal of out which is in 2.30 format - and oneByOut should be upscaled by sign bits */ - signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); - - /* 0.5 * (out) */ - out = out >> 1u; - - /* prevOut = 0.5 * out + (in * (oneByOut) << signbits) */ - prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - - - /* loop for third iteration to tength iteration */ - - for (loopVar = 1; loopVar <= 14; loopVar++) - { - - signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); - /* 0.5 * (prevOut) */ - prevOut = prevOut >> 1u; - /* out = 0.5 * prevOut + (in * oneByOut) << signbits))) */ - out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); - /* prevOut = out */ - prevOut = out; - - } - /* output is moved to pOut pointer */ - *pOut = prevOut; - - return (ARM_MATH_SUCCESS); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - else - { - *pOut = 0; - return (ARM_MATH_ARGUMENT_ERROR); - } -} - -/** - * @} end of SQRT group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_sqrt_q31.c +* +* Description: Q31 square root function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" +#include "arm_common_tables.h" + +/** + * @ingroup groupFastMath + */ + +/** + * @addtogroup SQRT + * @{ + */ + +/** + * @brief Q31 square root function. + * @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF. + * @param[out] *pOut square root of input value. + * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if + * in is negative value and returns zero output for negative values. + */ + +arm_status arm_sqrt_q31( + q31_t in, + q31_t * pOut) +{ + q63_t prevOut; + q31_t oneByOut; + uint32_t signBits; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q63_t out; + + if(in > 0) + { + + /* run for ten iterations */ + + /* Take initial guess as half of the input and first iteration */ + out = (in >> 1) + 0x3FFFFFFF; + + /* Calculation of reciprocal of out */ + /* oneByOut contains reciprocal of out which is in 2.30 format + and oneByOut should be upscaled by signBits */ + signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); + + /* 0.5 * (out) */ + out = out >> 1u; + + /* prevOut = 0.5 * out + (in * (oneByOut << signBits))) */ + prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + /* Third iteration */ + signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); + prevOut = prevOut >> 1u; + out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); + out = out >> 1u; + prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + /* Fifth iteration */ + signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); + prevOut = prevOut >> 1u; + out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); + out = out >> 1u; + prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + /* Seventh iteration */ + signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); + prevOut = prevOut >> 1u; + out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); + out = out >> 1u; + prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); + prevOut = prevOut >> 1u; + out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); + out = out >> 1u; + prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); + prevOut = prevOut >> 1u; + out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); + out = out >> 1u; + prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); + prevOut = prevOut >> 1u; + out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); + out = out >> 1u; + prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); + prevOut = prevOut >> 1u; + out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + /* tenth iteration */ + signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); + out = out >> 1u; + *pOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + return (ARM_MATH_SUCCESS); + } + +#else + + /* Run the below code for Cortex-M0 */ + + q63_t out, loopVar; /* Temporary variable for output, loop variable */ + if(in > 0) + { + + /* run for ten iterations */ + + /* Take initial guess as half of the input and first iteration */ + out = (in >> 1) + 0x3FFFFFFF; + + /* Calculation of reciprocal of out */ + /* oneByOut contains reciprocal of out which is in 2.30 format + and oneByOut should be upscaled by sign bits */ + signBits = arm_recip_q31((q31_t) out, &oneByOut, armRecipTableQ31); + + /* 0.5 * (out) */ + out = out >> 1u; + + /* prevOut = 0.5 * out + (in * (oneByOut) << signbits) */ + prevOut = out + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + + + /* loop for third iteration to tength iteration */ + + for (loopVar = 1; loopVar <= 14; loopVar++) + { + + signBits = arm_recip_q31((q31_t) prevOut, &oneByOut, armRecipTableQ31); + /* 0.5 * (prevOut) */ + prevOut = prevOut >> 1u; + /* out = 0.5 * prevOut + (in * oneByOut) << signbits))) */ + out = prevOut + (((q31_t) (((q63_t) in * oneByOut) >> 32)) << signBits); + /* prevOut = out */ + prevOut = out; + + } + /* output is moved to pOut pointer */ + *pOut = prevOut; + + return (ARM_MATH_SUCCESS); + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + else + { + *pOut = 0; + return (ARM_MATH_ARGUMENT_ERROR); + } +} + +/** + * @} end of SQRT group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_init_q31.c index ec4b058a9..ff6239a9e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_init_q31.c @@ -1,102 +1,102 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_32x64_init_q31.c -* -* Description: High precision Q31 Biquad cascade filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1_32x64 - * @{ - */ - -/** - * @details - * - * @param[in,out] *S points to an instance of the high precision Q31 Biquad cascade filter structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] postShift Shift to be applied after the accumulator. Varies according to the coefficients format. - * @return none - * - * Coefficient and State Ordering: - * - * \par - * The coefficients are stored in the array pCoeffs in the following order: - *
   
- *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}   
- * 
- * where b1x and a1x are the coefficients for the first stage, - * b2x and a2x are the coefficients for the second stage, - * and so on. The pCoeffs array contains a total of 5*numStages values. - * - * \par - * The pState points to state variables array and size of each state variable is 1.63 format. - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. - * The state variables are arranged in the state array as: - *
   
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
- * 
- * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - */ - -void arm_biquad_cas_df1_32x64_init_q31( - arm_biquad_cas_df1_32x64_ins_q31 * S, - uint8_t numStages, - q31_t * pCoeffs, - q63_t * pState, - uint8_t postShift) -{ - /* Assign filter stages */ - S->numStages = numStages; - - /* Assign postShift to be applied to the output */ - S->postShift = postShift; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always 4 * numStages */ - memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(q63_t)); - - /* Assign state pointer */ - S->pState = pState; -} - -/** - * @} end of BiquadCascadeDF1_32x64 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df1_32x64_init_q31.c +* +* Description: High precision Q31 Biquad cascade filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup BiquadCascadeDF1_32x64 + * @{ + */ + +/** + * @details + * + * @param[in,out] *S points to an instance of the high precision Q31 Biquad cascade filter structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] postShift Shift to be applied after the accumulator. Varies according to the coefficients format. + * @return none + * + * Coefficient and State Ordering: + * + * \par + * The coefficients are stored in the array pCoeffs in the following order: + *
   
+ *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}   
+ * 
+ * where b1x and a1x are the coefficients for the first stage, + * b2x and a2x are the coefficients for the second stage, + * and so on. The pCoeffs array contains a total of 5*numStages values. + * + * \par + * The pState points to state variables array and size of each state variable is 1.63 format. + * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. + * The state variables are arranged in the state array as: + *
   
+ *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
+ * 
+ * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. + * The state array has a total length of 4*numStages values. + * The state variables are updated after each block of data is processed; the coefficients are untouched. + */ + +void arm_biquad_cas_df1_32x64_init_q31( + arm_biquad_cas_df1_32x64_ins_q31 * S, + uint8_t numStages, + q31_t * pCoeffs, + q63_t * pState, + uint8_t postShift) +{ + /* Assign filter stages */ + S->numStages = numStages; + + /* Assign postShift to be applied to the output */ + S->postShift = postShift; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always 4 * numStages */ + memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(q63_t)); + + /* Assign state pointer */ + S->pState = pState; +} + +/** + * @} end of BiquadCascadeDF1_32x64 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_q31.c index 35cfe856f..73ff8b0d7 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_q31.c @@ -1,476 +1,476 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_32x64_q31.c -* -* Description: High precision Q31 Biquad cascade filter processing function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup BiquadCascadeDF1_32x64 High Precision Q31 Biquad Cascade Filter - * - * This function implements a high precision Biquad cascade filter which operates on - * Q31 data values. The filter coefficients are in 1.31 format and the state variables - * are in 1.63 format. The double precision state variables reduce quantization noise - * in the filter and provide a cleaner output. - * These filters are particularly useful when implementing filters in which the - * singularities are close to the unit circle. This is common for low pass or high - * pass filters with very low cutoff frequencies. - * - * The function operates on blocks of input and output data - * and each call to the function processes blockSize samples through - * the filter. pSrc and pDst points to input and output arrays - * containing blockSize Q31 values. - * - * \par Algorithm - * Each Biquad stage implements a second order filter using the difference equation: - *
   
- *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2]   
- * 
- * A Direct Form I algorithm is used with 5 coefficients and 4 state variables per stage. - * \image html Biquad.gif "Single Biquad filter stage" - * Coefficients b0, b1, and b2 multiply the input signal x[n] and are referred to as the feedforward coefficients. - * Coefficients a1 and a2 multiply the output signal y[n] and are referred to as the feedback coefficients. - * Pay careful attention to the sign of the feedback coefficients. - * Some design tools use the difference equation - *
   
- *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] - a1 * y[n-1] - a2 * y[n-2]   
- * 
- * In this case the feedback coefficients a1 and a2 must be negated when used with the CMSIS DSP Library. - * - * \par - * Higher order filters are realized as a cascade of second order sections. - * numStages refers to the number of second order stages used. - * For example, an 8th order filter would be realized with numStages=4 second order stages. - * \image html BiquadCascade.gif "8th order filter using a cascade of Biquad stages" - * A 9th order filter would be realized with numStages=5 second order stages with the coefficients for one of the stages configured as a first order filter (b2=0 and a2=0). - * - * \par - * The pState points to state variables array . - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2] and each state variable in 1.63 format to improve precision. - * The state variables are arranged in the array as: - *
   
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
- * 
- * - * \par - * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values of data in 1.63 format. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * - * \par Init Function - * There is also an associated initialization function which performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * For example, to statically initialize the filter instance structure use - *
   
- *     arm_biquad_cas_df1_32x64_ins_q31 S1 = {numStages, pState, pCoeffs, postShift};   
- * 
- * where numStages is the number of Biquad stages in the filter; pState is the address of the state buffer; - * pCoeffs is the address of the coefficient buffer; postShift shift to be applied which is described in detail below. - * \par Fixed-Point Behavior - * Care must be taken while using Biquad Cascade 32x64 filter function. - * Following issues must be considered: - * - Scaling of coefficients - * - Filter gain - * - Overflow and saturation - * - * \par - * Filter coefficients are represented as fractional values and - * restricted to lie in the range [-1 +1). - * The processing function has an additional scaling parameter postShift - * which allows the filter coefficients to exceed the range [+1 -1). - * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. - * \image html BiquadPostshift.gif "Fixed-point Biquad with shift by postShift bits after accumulator" - * This essentially scales the filter coefficients by 2^postShift. - * For example, to realize the coefficients - *
   
- *    {1.5, -0.8, 1.2, 1.6, -0.9}   
- * 
- * set the Coefficient array to: - *
   
- *    {0.75, -0.4, 0.6, 0.8, -0.45}   
- * 
- * and set postShift=1 - * - * \par - * The second thing to keep in mind is the gain through the filter. - * The frequency response of a Biquad filter is a function of its coefficients. - * It is possible for the gain through the filter to exceed 1.0 meaning that the filter increases the amplitude of certain frequencies. - * This means that an input signal with amplitude < 1.0 may result in an output > 1.0 and these are saturated or overflowed based on the implementation of the filter. - * To avoid this behavior the filter needs to be scaled down such that its peak gain < 1.0 or the input signal must be scaled down so that the combination of input and filter are never overflowed. - * - * \par - * The third item to consider is the overflow and saturation behavior of the fixed-point Q31 version. - * This is described in the function specific documentation below. - */ - -/** - * @addtogroup BiquadCascadeDF1_32x64 - * @{ - */ - -/** - * @details - - * @param[in] *S points to an instance of the high precision Q31 Biquad cascade filter. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - * @return none. - * - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 2 bits and lie in the range [-0.25 +0.25). - * After all 5 multiply-accumulates are performed, the 2.62 accumulator is shifted by postShift bits and the result truncated to - * 1.31 format by discarding the low 32 bits. - * - * \par - * Two related functions are provided in the CMSIS DSP library. - * arm_biquad_cascade_df1_q31() implements a Biquad cascade with 32-bit coefficients and state variables with a Q63 accumulator. - * arm_biquad_cascade_df1_fast_q31() implements a Biquad cascade with 32-bit coefficients and state variables with a Q31 accumulator. - */ - -void arm_biquad_cas_df1_32x64_q31( - const arm_biquad_cas_df1_32x64_ins_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pIn = pSrc; /* input pointer initialization */ - q31_t *pOut = pDst; /* output pointer initialization */ - q63_t *pState = S->pState; /* state pointer initialization */ - q31_t *pCoeffs = S->pCoeffs; /* coeff pointer initialization */ - q63_t acc; /* accumulator */ - q63_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ - q31_t b0, b1, b2, a1, a2; /* Filter coefficients */ - q63_t Xn; /* temporary input */ - int32_t shift = (int32_t) S->postShift + 1; /* Shift to be applied to the output */ - uint32_t sample, stage = S->numStages; /* loop counters */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* Apply loop unrolling and compute 4 output values simultaneously. */ - /* The variable acc hold output value that is being computed and - * stored in the destination buffer - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* The value is shifted to the MSB to perform 32x64 multiplication */ - Xn = Xn << 32; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = mult32x64(Xn, b0); - /* acc += b1 * x[n-1] */ - acc += mult32x64(Xn1, b1); - /* acc += b[2] * x[n-2] */ - acc += mult32x64(Xn2, b2); - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn1, a1); - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn2, a2); - - /* The result is converted to 1.63 , Yn2 variable is reused */ - Yn2 = acc << shift; - - /* Store the output in the destination buffer in 1.31 format. */ - *pOut++ = (q31_t) (acc >> (32 - shift)); - - /* Read the second input into Xn2, to reuse the value */ - Xn2 = *pIn++; - - /* The value is shifted to the MSB to perform 32x64 multiplication */ - Xn2 = Xn2 << 32; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = mult32x64(Xn2, b0); - /* acc += b1 * x[n-1] */ - acc += mult32x64(Xn, b1); - /* acc += b[2] * x[n-2] */ - acc += mult32x64(Xn1, b2); - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn2, a1); - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn1, a2); - - /* The result is converted to 1.63, Yn1 variable is reused */ - Yn1 = acc << shift; - - /* The result is converted to 1.31 */ - /* Store the output in the destination buffer. */ - *pOut++ = (q31_t) (acc >> (32 - shift)); - - /* Read the third input into Xn1, to reuse the value */ - Xn1 = *pIn++; - - /* The value is shifted to the MSB to perform 32x64 multiplication */ - Xn1 = Xn1 << 32; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = mult32x64(Xn1, b0); - /* acc += b1 * x[n-1] */ - acc += mult32x64(Xn2, b1); - /* acc += b[2] * x[n-2] */ - acc += mult32x64(Xn, b2); - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn1, a1); - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn2, a2); - - /* The result is converted to 1.63, Yn2 variable is reused */ - Yn2 = acc << shift; - - /* Store the output in the destination buffer in 1.31 format. */ - *pOut++ = (q31_t) (acc >> (32 - shift)); - - /* Read the fourth input into Xn, to reuse the value */ - Xn = *pIn++; - - /* The value is shifted to the MSB to perform 32x64 multiplication */ - Xn = Xn << 32; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = mult32x64(Xn, b0); - /* acc += b1 * x[n-1] */ - acc += mult32x64(Xn1, b1); - /* acc += b[2] * x[n-2] */ - acc += mult32x64(Xn2, b2); - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn2, a1); - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn1, a2); - - /* The result is converted to 1.63, Yn1 variable is reused */ - Yn1 = acc << shift; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - - /* Store the output in the destination buffer in 1.31 format. */ - *pOut++ = (q31_t) (acc >> (32 - shift)); - - /* decrement the loop counter */ - sample--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - sample = (blockSize & 0x3u); - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* The value is shifted to the MSB to perform 32x64 multiplication */ - Xn = Xn << 32; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = mult32x64(Xn, b0); - /* acc += b1 * x[n-1] */ - acc += mult32x64(Xn1, b1); - /* acc += b[2] * x[n-2] */ - acc += mult32x64(Xn2, b2); - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn1, a1); - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn2, a2); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = acc << shift; - - /* Store the output in the destination buffer in 1.31 format. */ - *pOut++ = (q31_t) (acc >> (32 - shift)); - - /* decrement the loop counter */ - sample--; - } - - /* The first stage output is given as input to the second stage. */ - pIn = pDst; - - /* Reset to destination buffer working pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); - -#else - - /* Run the below code for Cortex-M0 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* The variable acc hold output value that is being computed and - * stored in the destination buffer - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* The value is shifted to the MSB to perform 32x64 multiplication */ - Xn = Xn << 32; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = mult32x64(Xn, b0); - /* acc += b1 * x[n-1] */ - acc += mult32x64(Xn1, b1); - /* acc += b[2] * x[n-2] */ - acc += mult32x64(Xn2, b2); - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn1, a1); - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn2, a2); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = acc << shift; - - /* Store the output in the destination buffer in 1.31 format. */ - *pOut++ = (q31_t) (acc >> (32 - shift)); - - /* decrement the loop counter */ - sample--; - } - - /* The first stage output is given as input to the second stage. */ - pIn = pDst; - - /* Reset to destination buffer working pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); - -#endif /* #ifndef ARM_MATH_CM0 */ -} - - /** - * @} end of BiquadCascadeDF1_32x64 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df1_32x64_q31.c +* +* Description: High precision Q31 Biquad cascade filter processing function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup BiquadCascadeDF1_32x64 High Precision Q31 Biquad Cascade Filter + * + * This function implements a high precision Biquad cascade filter which operates on + * Q31 data values. The filter coefficients are in 1.31 format and the state variables + * are in 1.63 format. The double precision state variables reduce quantization noise + * in the filter and provide a cleaner output. + * These filters are particularly useful when implementing filters in which the + * singularities are close to the unit circle. This is common for low pass or high + * pass filters with very low cutoff frequencies. + * + * The function operates on blocks of input and output data + * and each call to the function processes blockSize samples through + * the filter. pSrc and pDst points to input and output arrays + * containing blockSize Q31 values. + * + * \par Algorithm + * Each Biquad stage implements a second order filter using the difference equation: + *
   
+ *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2]   
+ * 
+ * A Direct Form I algorithm is used with 5 coefficients and 4 state variables per stage. + * \image html Biquad.gif "Single Biquad filter stage" + * Coefficients b0, b1, and b2 multiply the input signal x[n] and are referred to as the feedforward coefficients. + * Coefficients a1 and a2 multiply the output signal y[n] and are referred to as the feedback coefficients. + * Pay careful attention to the sign of the feedback coefficients. + * Some design tools use the difference equation + *
   
+ *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] - a1 * y[n-1] - a2 * y[n-2]   
+ * 
+ * In this case the feedback coefficients a1 and a2 must be negated when used with the CMSIS DSP Library. + * + * \par + * Higher order filters are realized as a cascade of second order sections. + * numStages refers to the number of second order stages used. + * For example, an 8th order filter would be realized with numStages=4 second order stages. + * \image html BiquadCascade.gif "8th order filter using a cascade of Biquad stages" + * A 9th order filter would be realized with numStages=5 second order stages with the coefficients for one of the stages configured as a first order filter (b2=0 and a2=0). + * + * \par + * The pState points to state variables array . + * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2] and each state variable in 1.63 format to improve precision. + * The state variables are arranged in the array as: + *
   
+ *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
+ * 
+ * + * \par + * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. + * The state array has a total length of 4*numStages values of data in 1.63 format. + * The state variables are updated after each block of data is processed; the coefficients are untouched. + * + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter. + * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. + * + * \par Init Function + * There is also an associated initialization function which performs the following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Set the values in the state buffer to zeros before static initialization. + * For example, to statically initialize the filter instance structure use + *
   
+ *     arm_biquad_cas_df1_32x64_ins_q31 S1 = {numStages, pState, pCoeffs, postShift};   
+ * 
+ * where numStages is the number of Biquad stages in the filter; pState is the address of the state buffer; + * pCoeffs is the address of the coefficient buffer; postShift shift to be applied which is described in detail below. + * \par Fixed-Point Behavior + * Care must be taken while using Biquad Cascade 32x64 filter function. + * Following issues must be considered: + * - Scaling of coefficients + * - Filter gain + * - Overflow and saturation + * + * \par + * Filter coefficients are represented as fractional values and + * restricted to lie in the range [-1 +1). + * The processing function has an additional scaling parameter postShift + * which allows the filter coefficients to exceed the range [+1 -1). + * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. + * \image html BiquadPostshift.gif "Fixed-point Biquad with shift by postShift bits after accumulator" + * This essentially scales the filter coefficients by 2^postShift. + * For example, to realize the coefficients + *
   
+ *    {1.5, -0.8, 1.2, 1.6, -0.9}   
+ * 
+ * set the Coefficient array to: + *
   
+ *    {0.75, -0.4, 0.6, 0.8, -0.45}   
+ * 
+ * and set postShift=1 + * + * \par + * The second thing to keep in mind is the gain through the filter. + * The frequency response of a Biquad filter is a function of its coefficients. + * It is possible for the gain through the filter to exceed 1.0 meaning that the filter increases the amplitude of certain frequencies. + * This means that an input signal with amplitude < 1.0 may result in an output > 1.0 and these are saturated or overflowed based on the implementation of the filter. + * To avoid this behavior the filter needs to be scaled down such that its peak gain < 1.0 or the input signal must be scaled down so that the combination of input and filter are never overflowed. + * + * \par + * The third item to consider is the overflow and saturation behavior of the fixed-point Q31 version. + * This is described in the function specific documentation below. + */ + +/** + * @addtogroup BiquadCascadeDF1_32x64 + * @{ + */ + +/** + * @details + + * @param[in] *S points to an instance of the high precision Q31 Biquad cascade filter. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + * + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around rather than clip. + * In order to avoid overflows completely the input signal must be scaled down by 2 bits and lie in the range [-0.25 +0.25). + * After all 5 multiply-accumulates are performed, the 2.62 accumulator is shifted by postShift bits and the result truncated to + * 1.31 format by discarding the low 32 bits. + * + * \par + * Two related functions are provided in the CMSIS DSP library. + * arm_biquad_cascade_df1_q31() implements a Biquad cascade with 32-bit coefficients and state variables with a Q63 accumulator. + * arm_biquad_cascade_df1_fast_q31() implements a Biquad cascade with 32-bit coefficients and state variables with a Q31 accumulator. + */ + +void arm_biquad_cas_df1_32x64_q31( + const arm_biquad_cas_df1_32x64_ins_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t *pIn = pSrc; /* input pointer initialization */ + q31_t *pOut = pDst; /* output pointer initialization */ + q63_t *pState = S->pState; /* state pointer initialization */ + q31_t *pCoeffs = S->pCoeffs; /* coeff pointer initialization */ + q63_t acc; /* accumulator */ + q63_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ + q31_t b0, b1, b2, a1, a2; /* Filter coefficients */ + q63_t Xn; /* temporary input */ + int32_t shift = (int32_t) S->postShift + 1; /* Shift to be applied to the output */ + uint32_t sample, stage = S->numStages; /* loop counters */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + do + { + /* Reading the coefficients */ + b0 = *pCoeffs++; + b1 = *pCoeffs++; + b2 = *pCoeffs++; + a1 = *pCoeffs++; + a2 = *pCoeffs++; + + /* Reading the state values */ + Xn1 = pState[0]; + Xn2 = pState[1]; + Yn1 = pState[2]; + Yn2 = pState[3]; + + /* Apply loop unrolling and compute 4 output values simultaneously. */ + /* The variable acc hold output value that is being computed and + * stored in the destination buffer + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + */ + + sample = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* The value is shifted to the MSB to perform 32x64 multiplication */ + Xn = Xn << 32; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + + /* acc = b0 * x[n] */ + acc = mult32x64(Xn, b0); + /* acc += b1 * x[n-1] */ + acc += mult32x64(Xn1, b1); + /* acc += b[2] * x[n-2] */ + acc += mult32x64(Xn2, b2); + /* acc += a1 * y[n-1] */ + acc += mult32x64(Yn1, a1); + /* acc += a2 * y[n-2] */ + acc += mult32x64(Yn2, a2); + + /* The result is converted to 1.63 , Yn2 variable is reused */ + Yn2 = acc << shift; + + /* Store the output in the destination buffer in 1.31 format. */ + *pOut++ = (q31_t) (acc >> (32 - shift)); + + /* Read the second input into Xn2, to reuse the value */ + Xn2 = *pIn++; + + /* The value is shifted to the MSB to perform 32x64 multiplication */ + Xn2 = Xn2 << 32; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + + /* acc = b0 * x[n] */ + acc = mult32x64(Xn2, b0); + /* acc += b1 * x[n-1] */ + acc += mult32x64(Xn, b1); + /* acc += b[2] * x[n-2] */ + acc += mult32x64(Xn1, b2); + /* acc += a1 * y[n-1] */ + acc += mult32x64(Yn2, a1); + /* acc += a2 * y[n-2] */ + acc += mult32x64(Yn1, a2); + + /* The result is converted to 1.63, Yn1 variable is reused */ + Yn1 = acc << shift; + + /* The result is converted to 1.31 */ + /* Store the output in the destination buffer. */ + *pOut++ = (q31_t) (acc >> (32 - shift)); + + /* Read the third input into Xn1, to reuse the value */ + Xn1 = *pIn++; + + /* The value is shifted to the MSB to perform 32x64 multiplication */ + Xn1 = Xn1 << 32; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = mult32x64(Xn1, b0); + /* acc += b1 * x[n-1] */ + acc += mult32x64(Xn2, b1); + /* acc += b[2] * x[n-2] */ + acc += mult32x64(Xn, b2); + /* acc += a1 * y[n-1] */ + acc += mult32x64(Yn1, a1); + /* acc += a2 * y[n-2] */ + acc += mult32x64(Yn2, a2); + + /* The result is converted to 1.63, Yn2 variable is reused */ + Yn2 = acc << shift; + + /* Store the output in the destination buffer in 1.31 format. */ + *pOut++ = (q31_t) (acc >> (32 - shift)); + + /* Read the fourth input into Xn, to reuse the value */ + Xn = *pIn++; + + /* The value is shifted to the MSB to perform 32x64 multiplication */ + Xn = Xn << 32; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = mult32x64(Xn, b0); + /* acc += b1 * x[n-1] */ + acc += mult32x64(Xn1, b1); + /* acc += b[2] * x[n-2] */ + acc += mult32x64(Xn2, b2); + /* acc += a1 * y[n-1] */ + acc += mult32x64(Yn2, a1); + /* acc += a2 * y[n-2] */ + acc += mult32x64(Yn1, a2); + + /* The result is converted to 1.63, Yn1 variable is reused */ + Yn1 = acc << shift; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + + /* Store the output in the destination buffer in 1.31 format. */ + *pOut++ = (q31_t) (acc >> (32 - shift)); + + /* decrement the loop counter */ + sample--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + sample = (blockSize & 0x3u); + + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* The value is shifted to the MSB to perform 32x64 multiplication */ + Xn = Xn << 32; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = mult32x64(Xn, b0); + /* acc += b1 * x[n-1] */ + acc += mult32x64(Xn1, b1); + /* acc += b[2] * x[n-2] */ + acc += mult32x64(Xn2, b2); + /* acc += a1 * y[n-1] */ + acc += mult32x64(Yn1, a1); + /* acc += a2 * y[n-2] */ + acc += mult32x64(Yn2, a2); + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + Yn2 = Yn1; + Yn1 = acc << shift; + + /* Store the output in the destination buffer in 1.31 format. */ + *pOut++ = (q31_t) (acc >> (32 - shift)); + + /* decrement the loop counter */ + sample--; + } + + /* The first stage output is given as input to the second stage. */ + pIn = pDst; + + /* Reset to destination buffer working pointer */ + pOut = pDst; + + /* Store the updated state variables back into the pState array */ + *pState++ = Xn1; + *pState++ = Xn2; + *pState++ = Yn1; + *pState++ = Yn2; + + } while(--stage); + +#else + + /* Run the below code for Cortex-M0 */ + + do + { + /* Reading the coefficients */ + b0 = *pCoeffs++; + b1 = *pCoeffs++; + b2 = *pCoeffs++; + a1 = *pCoeffs++; + a2 = *pCoeffs++; + + /* Reading the state values */ + Xn1 = pState[0]; + Xn2 = pState[1]; + Yn1 = pState[2]; + Yn2 = pState[3]; + + /* The variable acc hold output value that is being computed and + * stored in the destination buffer + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + */ + + sample = blockSize; + + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* The value is shifted to the MSB to perform 32x64 multiplication */ + Xn = Xn << 32; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = mult32x64(Xn, b0); + /* acc += b1 * x[n-1] */ + acc += mult32x64(Xn1, b1); + /* acc += b[2] * x[n-2] */ + acc += mult32x64(Xn2, b2); + /* acc += a1 * y[n-1] */ + acc += mult32x64(Yn1, a1); + /* acc += a2 * y[n-2] */ + acc += mult32x64(Yn2, a2); + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + Yn2 = Yn1; + Yn1 = acc << shift; + + /* Store the output in the destination buffer in 1.31 format. */ + *pOut++ = (q31_t) (acc >> (32 - shift)); + + /* decrement the loop counter */ + sample--; + } + + /* The first stage output is given as input to the second stage. */ + pIn = pDst; + + /* Reset to destination buffer working pointer */ + pOut = pDst; + + /* Store the updated state variables back into the pState array */ + *pState++ = Xn1; + *pState++ = Xn2; + *pState++ = Yn1; + *pState++ = Yn2; + + } while(--stage); + +#endif /* #ifndef ARM_MATH_CM0 */ +} + + /** + * @} end of BiquadCascadeDF1_32x64 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_f32.c index b5a744d0f..bdfbf22fe 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_f32.c @@ -1,418 +1,418 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_f32.c -* -* Description: Processing function for the -* floating-point Biquad cascade DirectFormI(DF1) filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup BiquadCascadeDF1 Biquad Cascade IIR Filters Using Direct Form I Structure - * - * This set of functions implements arbitrary order recursive (IIR) filters. - * The filters are implemented as a cascade of second order Biquad sections. - * The functions support Q15, Q31 and floating-point data types. - * Fast version of Q15 and Q31 also supported on CortexM4 and Cortex-M3. - * - * The functions operate on blocks of input and output data and each call to the function - * processes blockSize samples through the filter. - * pSrc points to the array of input data and - * pDst points to the array of output data. - * Both arrays contain blockSize values. - * - * \par Algorithm - * Each Biquad stage implements a second order filter using the difference equation: - *
   
- *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2]   
- * 
- * A Direct Form I algorithm is used with 5 coefficients and 4 state variables per stage. - * \image html Biquad.gif "Single Biquad filter stage" - * Coefficients b0, b1 and b2 multiply the input signal x[n] and are referred to as the feedforward coefficients. - * Coefficients a1 and a2 multiply the output signal y[n] and are referred to as the feedback coefficients. - * Pay careful attention to the sign of the feedback coefficients. - * Some design tools use the difference equation - *
   
- *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] - a1 * y[n-1] - a2 * y[n-2]   
- * 
- * In this case the feedback coefficients a1 and a2 must be negated when used with the CMSIS DSP Library. - * - * \par - * Higher order filters are realized as a cascade of second order sections. - * numStages refers to the number of second order stages used. - * For example, an 8th order filter would be realized with numStages=4 second order stages. - * \image html BiquadCascade.gif "8th order filter using a cascade of Biquad stages" - * A 9th order filter would be realized with numStages=5 second order stages with the coefficients for one of the stages configured as a first order filter (b2=0 and a2=0). - * - * \par - * The pState points to state variables array. - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. - * The state variables are arranged in the pState array as: - *
   
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
- * 
- * - * \par - * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values. - * The state variables are updated after each block of data is processed, the coefficients are untouched. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Init Functions - * There is also an associated initialization function for each data type. - * The initialization function performs following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * The code below statically initializes each of the 3 different data type filter instance structures - *
   
- *     arm_biquad_casd_df1_inst_f32 S1 = {numStages, pState, pCoeffs};   
- *     arm_biquad_casd_df1_inst_q15 S2 = {numStages, pState, pCoeffs, postShift};   
- *     arm_biquad_casd_df1_inst_q31 S3 = {numStages, pState, pCoeffs, postShift};   
- * 
- * where numStages is the number of Biquad stages in the filter; pState is the address of the state buffer; - * pCoeffs is the address of the coefficient buffer; postShift shift to be applied. - * - * \par Fixed-Point Behavior - * Care must be taken when using the Q15 and Q31 versions of the Biquad Cascade filter functions. - * Following issues must be considered: - * - Scaling of coefficients - * - Filter gain - * - Overflow and saturation - * - * \par - * Scaling of coefficients: - * Filter coefficients are represented as fractional values and - * coefficients are restricted to lie in the range [-1 +1). - * The fixed-point functions have an additional scaling parameter postShift - * which allow the filter coefficients to exceed the range [+1 -1). - * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. - * \image html BiquadPostshift.gif "Fixed-point Biquad with shift by postShift bits after accumulator" - * This essentially scales the filter coefficients by 2^postShift. - * For example, to realize the coefficients - *
   
- *    {1.5, -0.8, 1.2, 1.6, -0.9}   
- * 
- * set the pCoeffs array to: - *
   
- *    {0.75, -0.4, 0.6, 0.8, -0.45}   
- * 
- * and set postShift=1 - * - * \par - * Filter gain: - * The frequency response of a Biquad filter is a function of its coefficients. - * It is possible for the gain through the filter to exceed 1.0 meaning that the filter increases the amplitude of certain frequencies. - * This means that an input signal with amplitude < 1.0 may result in an output > 1.0 and these are saturated or overflowed based on the implementation of the filter. - * To avoid this behavior the filter needs to be scaled down such that its peak gain < 1.0 or the input signal must be scaled down so that the combination of input and filter are never overflowed. - * - * \par - * Overflow and saturation: - * For Q15 and Q31 versions, it is described separately as part of the function specific documentation below. - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @param[in] *S points to an instance of the floating-point Biquad cascade structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - */ - -void arm_biquad_cascade_df1_f32( - const arm_biquad_casd_df1_inst_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pIn = pSrc; /* source pointer */ - float32_t *pOut = pDst; /* destination pointer */ - float32_t *pState = S->pState; /* pState pointer */ - float32_t *pCoeffs = S->pCoeffs; /* coefficient pointer */ - float32_t acc; /* Simulates the accumulator */ - float32_t b0, b1, b2, a1, a2; /* Filter coefficients */ - float32_t Xn1, Xn2, Yn1, Yn2; /* Filter pState variables */ - float32_t Xn; /* temporary input */ - uint32_t sample, stage = S->numStages; /* loop counters */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the pState values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* Apply loop unrolling and compute 4 output values simultaneously. */ - /* The variable acc hold output values that are being computed: - * - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(sample > 0u) - { - /* Read the first input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - Yn2 = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn1) + (a2 * Yn2); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = Yn2; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - - /* Read the second input */ - Xn2 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - Yn1 = (b0 * Xn2) + (b1 * Xn) + (b2 * Xn1) + (a1 * Yn2) + (a2 * Yn1); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = Yn1; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - - /* Read the third input */ - Xn1 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - Yn2 = (b0 * Xn1) + (b1 * Xn2) + (b2 * Xn) + (a1 * Yn1) + (a2 * Yn2); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = Yn2; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - - /* Read the forth input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - Yn1 = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn2) + (a2 * Yn1); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = Yn1; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - - /* decrement the loop counter */ - sample--; - - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - sample = blockSize & 0x3u; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - acc = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn1) + (a2 * Yn2); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = acc; - - /* decrement the loop counter */ - sample--; - - } - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent numStages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset the output pointer */ - pOut = pDst; - - /* decrement the loop counter */ - stage--; - - } while(stage > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the pState values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* The variables acc holds the output value that is computed: - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - acc = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn1) + (a2 * Yn2); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = acc; - - /* decrement the loop counter */ - sample--; - } - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent numStages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset the output pointer */ - pOut = pDst; - - /* decrement the loop counter */ - stage--; - - } while(stage > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - - /** - * @} end of BiquadCascadeDF1 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df1_f32.c +* +* Description: Processing function for the +* floating-point Biquad cascade DirectFormI(DF1) filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup BiquadCascadeDF1 Biquad Cascade IIR Filters Using Direct Form I Structure + * + * This set of functions implements arbitrary order recursive (IIR) filters. + * The filters are implemented as a cascade of second order Biquad sections. + * The functions support Q15, Q31 and floating-point data types. + * Fast version of Q15 and Q31 also supported on CortexM4 and Cortex-M3. + * + * The functions operate on blocks of input and output data and each call to the function + * processes blockSize samples through the filter. + * pSrc points to the array of input data and + * pDst points to the array of output data. + * Both arrays contain blockSize values. + * + * \par Algorithm + * Each Biquad stage implements a second order filter using the difference equation: + *
   
+ *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2]   
+ * 
+ * A Direct Form I algorithm is used with 5 coefficients and 4 state variables per stage. + * \image html Biquad.gif "Single Biquad filter stage" + * Coefficients b0, b1 and b2 multiply the input signal x[n] and are referred to as the feedforward coefficients. + * Coefficients a1 and a2 multiply the output signal y[n] and are referred to as the feedback coefficients. + * Pay careful attention to the sign of the feedback coefficients. + * Some design tools use the difference equation + *
   
+ *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] - a1 * y[n-1] - a2 * y[n-2]   
+ * 
+ * In this case the feedback coefficients a1 and a2 must be negated when used with the CMSIS DSP Library. + * + * \par + * Higher order filters are realized as a cascade of second order sections. + * numStages refers to the number of second order stages used. + * For example, an 8th order filter would be realized with numStages=4 second order stages. + * \image html BiquadCascade.gif "8th order filter using a cascade of Biquad stages" + * A 9th order filter would be realized with numStages=5 second order stages with the coefficients for one of the stages configured as a first order filter (b2=0 and a2=0). + * + * \par + * The pState points to state variables array. + * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. + * The state variables are arranged in the pState array as: + *
   
+ *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
+ * 
+ * + * \par + * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. + * The state array has a total length of 4*numStages values. + * The state variables are updated after each block of data is processed, the coefficients are untouched. + * + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter. + * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Init Functions + * There is also an associated initialization function for each data type. + * The initialization function performs following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Set the values in the state buffer to zeros before static initialization. + * The code below statically initializes each of the 3 different data type filter instance structures + *
   
+ *     arm_biquad_casd_df1_inst_f32 S1 = {numStages, pState, pCoeffs};   
+ *     arm_biquad_casd_df1_inst_q15 S2 = {numStages, pState, pCoeffs, postShift};   
+ *     arm_biquad_casd_df1_inst_q31 S3 = {numStages, pState, pCoeffs, postShift};   
+ * 
+ * where numStages is the number of Biquad stages in the filter; pState is the address of the state buffer; + * pCoeffs is the address of the coefficient buffer; postShift shift to be applied. + * + * \par Fixed-Point Behavior + * Care must be taken when using the Q15 and Q31 versions of the Biquad Cascade filter functions. + * Following issues must be considered: + * - Scaling of coefficients + * - Filter gain + * - Overflow and saturation + * + * \par + * Scaling of coefficients: + * Filter coefficients are represented as fractional values and + * coefficients are restricted to lie in the range [-1 +1). + * The fixed-point functions have an additional scaling parameter postShift + * which allow the filter coefficients to exceed the range [+1 -1). + * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. + * \image html BiquadPostshift.gif "Fixed-point Biquad with shift by postShift bits after accumulator" + * This essentially scales the filter coefficients by 2^postShift. + * For example, to realize the coefficients + *
   
+ *    {1.5, -0.8, 1.2, 1.6, -0.9}   
+ * 
+ * set the pCoeffs array to: + *
   
+ *    {0.75, -0.4, 0.6, 0.8, -0.45}   
+ * 
+ * and set postShift=1 + * + * \par + * Filter gain: + * The frequency response of a Biquad filter is a function of its coefficients. + * It is possible for the gain through the filter to exceed 1.0 meaning that the filter increases the amplitude of certain frequencies. + * This means that an input signal with amplitude < 1.0 may result in an output > 1.0 and these are saturated or overflowed based on the implementation of the filter. + * To avoid this behavior the filter needs to be scaled down such that its peak gain < 1.0 or the input signal must be scaled down so that the combination of input and filter are never overflowed. + * + * \par + * Overflow and saturation: + * For Q15 and Q31 versions, it is described separately as part of the function specific documentation below. + */ + +/** + * @addtogroup BiquadCascadeDF1 + * @{ + */ + +/** + * @param[in] *S points to an instance of the floating-point Biquad cascade structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + */ + +void arm_biquad_cascade_df1_f32( + const arm_biquad_casd_df1_inst_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + float32_t *pIn = pSrc; /* source pointer */ + float32_t *pOut = pDst; /* destination pointer */ + float32_t *pState = S->pState; /* pState pointer */ + float32_t *pCoeffs = S->pCoeffs; /* coefficient pointer */ + float32_t acc; /* Simulates the accumulator */ + float32_t b0, b1, b2, a1, a2; /* Filter coefficients */ + float32_t Xn1, Xn2, Yn1, Yn2; /* Filter pState variables */ + float32_t Xn; /* temporary input */ + uint32_t sample, stage = S->numStages; /* loop counters */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + do + { + /* Reading the coefficients */ + b0 = *pCoeffs++; + b1 = *pCoeffs++; + b2 = *pCoeffs++; + a1 = *pCoeffs++; + a2 = *pCoeffs++; + + /* Reading the pState values */ + Xn1 = pState[0]; + Xn2 = pState[1]; + Yn1 = pState[2]; + Yn2 = pState[3]; + + /* Apply loop unrolling and compute 4 output values simultaneously. */ + /* The variable acc hold output values that are being computed: + * + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + */ + + sample = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(sample > 0u) + { + /* Read the first input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + Yn2 = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn1) + (a2 * Yn2); + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = Yn2; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + + /* Read the second input */ + Xn2 = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + Yn1 = (b0 * Xn2) + (b1 * Xn) + (b2 * Xn1) + (a1 * Yn2) + (a2 * Yn1); + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = Yn1; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + + /* Read the third input */ + Xn1 = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + Yn2 = (b0 * Xn1) + (b1 * Xn2) + (b2 * Xn) + (a1 * Yn1) + (a2 * Yn2); + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = Yn2; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + + /* Read the forth input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + Yn1 = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn2) + (a2 * Yn1); + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = Yn1; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + + /* decrement the loop counter */ + sample--; + + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + sample = blockSize & 0x3u; + + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + acc = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn1) + (a2 * Yn2); + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = acc; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + Yn2 = Yn1; + Yn1 = acc; + + /* decrement the loop counter */ + sample--; + + } + + /* Store the updated state variables back into the pState array */ + *pState++ = Xn1; + *pState++ = Xn2; + *pState++ = Yn1; + *pState++ = Yn2; + + /* The first stage goes from the input buffer to the output buffer. */ + /* Subsequent numStages occur in-place in the output buffer */ + pIn = pDst; + + /* Reset the output pointer */ + pOut = pDst; + + /* decrement the loop counter */ + stage--; + + } while(stage > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + do + { + /* Reading the coefficients */ + b0 = *pCoeffs++; + b1 = *pCoeffs++; + b2 = *pCoeffs++; + a1 = *pCoeffs++; + a2 = *pCoeffs++; + + /* Reading the pState values */ + Xn1 = pState[0]; + Xn2 = pState[1]; + Yn1 = pState[2]; + Yn2 = pState[3]; + + /* The variables acc holds the output value that is computed: + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + */ + + sample = blockSize; + + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + acc = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn1) + (a2 * Yn2); + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = acc; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + Yn2 = Yn1; + Yn1 = acc; + + /* decrement the loop counter */ + sample--; + } + + /* Store the updated state variables back into the pState array */ + *pState++ = Xn1; + *pState++ = Xn2; + *pState++ = Yn1; + *pState++ = Yn2; + + /* The first stage goes from the input buffer to the output buffer. */ + /* Subsequent numStages occur in-place in the output buffer */ + pIn = pDst; + + /* Reset the output pointer */ + pOut = pDst; + + /* decrement the loop counter */ + stage--; + + } while(stage > 0u); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + + /** + * @} end of BiquadCascadeDF1 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q15.c index c2270fabd..c2ac80255 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q15.c @@ -1,283 +1,283 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_fast_q15.c -* -* Description: Fast processing function for the -* Q15 Biquad cascade filter. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.9 2010/08/16 -* Initial version -* -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @details - * @param[in] *S points to an instance of the Q15 Biquad cascade structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around and distorts the result. - * In order to avoid overflows completely the input signal must be scaled down by two bits and lie in the range [-0.25 +0.25). - * The 2.30 accumulator is then shifted by postShift bits and the result truncated to 1.15 format by discarding the low 16 bits. - * - * \par - * Refer to the function arm_biquad_cascade_df1_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. Both the slow and the fast versions use the same instance structure. - * Use the function arm_biquad_cascade_df1_init_q15() to initialize the filter structure. - * - */ - -void arm_biquad_cascade_df1_fast_q15( - const arm_biquad_casd_df1_inst_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pIn = pSrc; /* Source pointer */ - q15_t *pOut = pDst; /* Destination pointer */ - q31_t in; /* Temporary variable to hold input value */ - q31_t out; /* Temporary variable to hold output value */ - q31_t b0; /* Temporary variable to hold bo value */ - q31_t b1, a1; /* Filter coefficients */ - q31_t state_in, state_out; /* Filter state variables */ - q31_t acc0; /* Accumulator */ - int32_t shift = (int32_t) (15 - S->postShift); /* Post shift */ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pState_q31; /* 32-bit state pointer for SIMD implementation */ - uint32_t sample, stage = S->numStages; /* Stage loop counter */ - - - - do - { - /* Initialize state pointer of type q31 */ - pState_q31 = (q31_t *) (pState); - - /* Read the b0 and 0 coefficients using SIMD */ - b0 = *__SIMD32(pCoeffs)++; - - /* Read the b1 and b2 coefficients using SIMD */ - b1 = *__SIMD32(pCoeffs)++; - - /* Read the a1 and a2 coefficients using SIMD */ - a1 = *__SIMD32(pCoeffs)++; - - /* Read the input state values from the state buffer: x[n-1], x[n-2] */ - state_in = (q31_t) (*pState_q31++); - - /* Read the output state values from the state buffer: y[n-1], y[n-2] */ - state_out = (q31_t) (*pState_q31); - - /* Apply loop unrolling and compute 2 output values simultaneously. */ - /* The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - * acc0 = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - sample = blockSize >> 1u; - - /* First part of the processing with loop unrolling. Compute 2 outputs at a time. - ** a second loop below computes the remaining 1 sample. */ - while(sample > 0u) - { - - /* Read the input */ - in = *__SIMD32(pIn)++; - - /* out = b0 * x[n] + 0 * 0 */ - out = __SMUAD(b0, in); - /* acc0 = b1 * x[n-1] + acc0 += b2 * x[n-2] + out */ - acc0 = __SMLAD(b1, state_in, out); - /* acc0 += a1 * y[n-1] + acc0 += a2 * y[n-2] */ - acc0 = __SMLAD(a1, state_out, acc0); - - /* The result is converted from 3.29 to 1.31 and then saturation is applied */ - out = __SSAT((acc0 >> shift), 16); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc0 */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, (in >> 16), 16); - state_out = __PKHBT(state_out >> 16, (out), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* out = b0 * x[n] + 0 * 0 */ - out = __SMUADX(b0, in); - /* acc0 = b1 * x[n-1] + acc0 += b2 * x[n-2] + out */ - acc0 = __SMLAD(b1, state_in, out); - /* acc0 += a1 * y[n-1] + acc0 += a2 * y[n-2] */ - acc0 = __SMLAD(a1, state_out, acc0); - - /* The result is converted from 3.29 to 1.31 and then saturation is applied */ - out = __SSAT((acc0 >> shift), 16); - - - /* Store the output in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = __PKHBT(state_out, out, 16); - -#else - - *__SIMD32(pOut)++ = __PKHBT(out, state_out >> 16, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc0 */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in >> 16, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, in, 16); - state_out = __PKHBT(state_out >> 16, out, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - /* Decrement the loop counter */ - sample--; - - } - - /* If the blockSize is not a multiple of 2, compute any remaining output samples here. - ** No loop unrolling is used. */ - - if((blockSize & 0x1u) != 0u) - { - /* Read the input */ - in = *pIn++; - - /* out = b0 * x[n] + 0 * 0 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - out = __SMUAD(b0, in); - -#else - - out = __SMUADX(b0, in); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc0 = b1 * x[n-1] + acc0 += b2 * x[n-2] + out */ - acc0 = __SMLAD(b1, state_in, out); - /* acc0 += a1 * y[n-1] + acc0 += a2 * y[n-2] */ - acc0 = __SMLAD(a1, state_out, acc0); - - /* The result is converted from 3.29 to 1.31 and then saturation is applied */ - out = __SSAT((acc0 >> shift), 16); - - /* Store the output in the destination buffer. */ - *pOut++ = (q15_t) out; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc0 */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, in, 16); - state_out = __PKHBT(state_out >> 16, out, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - } - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent (numStages - 1) occur in-place in the output buffer */ - pIn = pDst; - - /* Reset the output pointer */ - pOut = pDst; - - /* Store the updated state variables back into the state array */ - *__SIMD32(pState)++ = state_in; - *__SIMD32(pState)++ = state_out; - - - /* Decrement the loop counter */ - stage--; - - } while(stage > 0u); -} - - -/** - * @} end of BiquadCascadeDF1 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df1_fast_q15.c +* +* Description: Fast processing function for the +* Q15 Biquad cascade filter. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.9 2010/08/16 +* Initial version +* +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup BiquadCascadeDF1 + * @{ + */ + +/** + * @details + * @param[in] *S points to an instance of the Q15 Biquad cascade structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * This fast version uses a 32-bit accumulator with 2.30 format. + * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around and distorts the result. + * In order to avoid overflows completely the input signal must be scaled down by two bits and lie in the range [-0.25 +0.25). + * The 2.30 accumulator is then shifted by postShift bits and the result truncated to 1.15 format by discarding the low 16 bits. + * + * \par + * Refer to the function arm_biquad_cascade_df1_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. Both the slow and the fast versions use the same instance structure. + * Use the function arm_biquad_cascade_df1_init_q15() to initialize the filter structure. + * + */ + +void arm_biquad_cascade_df1_fast_q15( + const arm_biquad_casd_df1_inst_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + q15_t *pIn = pSrc; /* Source pointer */ + q15_t *pOut = pDst; /* Destination pointer */ + q31_t in; /* Temporary variable to hold input value */ + q31_t out; /* Temporary variable to hold output value */ + q31_t b0; /* Temporary variable to hold bo value */ + q31_t b1, a1; /* Filter coefficients */ + q31_t state_in, state_out; /* Filter state variables */ + q31_t acc0; /* Accumulator */ + int32_t shift = (int32_t) (15 - S->postShift); /* Post shift */ + q15_t *pState = S->pState; /* State pointer */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *pState_q31; /* 32-bit state pointer for SIMD implementation */ + uint32_t sample, stage = S->numStages; /* Stage loop counter */ + + + + do + { + /* Initialize state pointer of type q31 */ + pState_q31 = (q31_t *) (pState); + + /* Read the b0 and 0 coefficients using SIMD */ + b0 = *__SIMD32(pCoeffs)++; + + /* Read the b1 and b2 coefficients using SIMD */ + b1 = *__SIMD32(pCoeffs)++; + + /* Read the a1 and a2 coefficients using SIMD */ + a1 = *__SIMD32(pCoeffs)++; + + /* Read the input state values from the state buffer: x[n-1], x[n-2] */ + state_in = (q31_t) (*pState_q31++); + + /* Read the output state values from the state buffer: y[n-1], y[n-2] */ + state_out = (q31_t) (*pState_q31); + + /* Apply loop unrolling and compute 2 output values simultaneously. */ + /* The variables acc0 ... acc3 hold output values that are being computed: + * + * acc0 = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + * acc0 = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + */ + sample = blockSize >> 1u; + + /* First part of the processing with loop unrolling. Compute 2 outputs at a time. + ** a second loop below computes the remaining 1 sample. */ + while(sample > 0u) + { + + /* Read the input */ + in = *__SIMD32(pIn)++; + + /* out = b0 * x[n] + 0 * 0 */ + out = __SMUAD(b0, in); + /* acc0 = b1 * x[n-1] + acc0 += b2 * x[n-2] + out */ + acc0 = __SMLAD(b1, state_in, out); + /* acc0 += a1 * y[n-1] + acc0 += a2 * y[n-2] */ + acc0 = __SMLAD(a1, state_out, acc0); + + /* The result is converted from 3.29 to 1.31 and then saturation is applied */ + out = __SSAT((acc0 >> shift), 16); + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc0 */ + /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ + /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ + +#ifndef ARM_MATH_BIG_ENDIAN + + state_in = __PKHBT(in, state_in, 16); + state_out = __PKHBT(out, state_out, 16); + +#else + + state_in = __PKHBT(state_in >> 16, (in >> 16), 16); + state_out = __PKHBT(state_out >> 16, (out), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* out = b0 * x[n] + 0 * 0 */ + out = __SMUADX(b0, in); + /* acc0 = b1 * x[n-1] + acc0 += b2 * x[n-2] + out */ + acc0 = __SMLAD(b1, state_in, out); + /* acc0 += a1 * y[n-1] + acc0 += a2 * y[n-2] */ + acc0 = __SMLAD(a1, state_out, acc0); + + /* The result is converted from 3.29 to 1.31 and then saturation is applied */ + out = __SSAT((acc0 >> shift), 16); + + + /* Store the output in the destination buffer. */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pOut)++ = __PKHBT(state_out, out, 16); + +#else + + *__SIMD32(pOut)++ = __PKHBT(out, state_out >> 16, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc0 */ + /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ + /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ + +#ifndef ARM_MATH_BIG_ENDIAN + + state_in = __PKHBT(in >> 16, state_in, 16); + state_out = __PKHBT(out, state_out, 16); + +#else + + state_in = __PKHBT(state_in >> 16, in, 16); + state_out = __PKHBT(state_out >> 16, out, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + + /* Decrement the loop counter */ + sample--; + + } + + /* If the blockSize is not a multiple of 2, compute any remaining output samples here. + ** No loop unrolling is used. */ + + if((blockSize & 0x1u) != 0u) + { + /* Read the input */ + in = *pIn++; + + /* out = b0 * x[n] + 0 * 0 */ + +#ifndef ARM_MATH_BIG_ENDIAN + + out = __SMUAD(b0, in); + +#else + + out = __SMUADX(b0, in); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* acc0 = b1 * x[n-1] + acc0 += b2 * x[n-2] + out */ + acc0 = __SMLAD(b1, state_in, out); + /* acc0 += a1 * y[n-1] + acc0 += a2 * y[n-2] */ + acc0 = __SMLAD(a1, state_out, acc0); + + /* The result is converted from 3.29 to 1.31 and then saturation is applied */ + out = __SSAT((acc0 >> shift), 16); + + /* Store the output in the destination buffer. */ + *pOut++ = (q15_t) out; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc0 */ + /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ + /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ + +#ifndef ARM_MATH_BIG_ENDIAN + + state_in = __PKHBT(in, state_in, 16); + state_out = __PKHBT(out, state_out, 16); + +#else + + state_in = __PKHBT(state_in >> 16, in, 16); + state_out = __PKHBT(state_out >> 16, out, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + } + + /* The first stage goes from the input buffer to the output buffer. */ + /* Subsequent (numStages - 1) occur in-place in the output buffer */ + pIn = pDst; + + /* Reset the output pointer */ + pOut = pDst; + + /* Store the updated state variables back into the state array */ + *__SIMD32(pState)++ = state_in; + *__SIMD32(pState)++ = state_out; + + + /* Decrement the loop counter */ + stage--; + + } while(stage > 0u); +} + + +/** + * @} end of BiquadCascadeDF1 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q31.c index 5a86ee1bc..1242ae720 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q31.c @@ -1,271 +1,271 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_fast_q31.c -* -* Description: Processing function for the -* Q31 Fast Biquad cascade DirectFormI(DF1) filter. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.9 2010/08/27 -* Initial version -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @details - * - * @param[in] *S points to an instance of the Q31 Biquad cascade structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * This function is optimized for speed at the expense of fixed-point precision and overflow protection. - * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. - * These intermediate results are added to a 2.30 accumulator. - * Finally, the accumulator is saturated and converted to a 1.31 result. - * The fast version has the same overflow behavior as the standard version and provides less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signal must be scaled down by two bits and lie in the range [-0.25 +0.25). Use the intialization function - * arm_biquad_cascade_df1_init_q31() to initialize filter structure. - * - * \par - * Refer to the function arm_biquad_cascade_df1_q31() for a slower implementation of this function which uses 64-bit accumulation to provide higher precision. Both the slow and the fast versions use the same instance structure. - * Use the function arm_biquad_cascade_df1_init_q31() to initialize the filter structure. - */ - -void arm_biquad_cascade_df1_fast_q31( - const arm_biquad_casd_df1_inst_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pIn = pSrc; /* input pointer initialization */ - q31_t *pOut = pDst; /* output pointer initialization */ - q31_t *pState = S->pState; /* pState pointer initialization */ - q31_t *pCoeffs = S->pCoeffs; /* coeff pointer initialization */ - q31_t acc; /* accumulator */ - q31_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ - q31_t b0, b1, b2, a1, a2; /* Filter coefficients */ - q31_t Xn; /* temporary input */ - int32_t shift = (int32_t) S->postShift + 1; /* Shift to be applied to the output */ - uint32_t sample, stage = S->numStages; /* loop counters */ - - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* Apply loop unrolling and compute 4 output values simultaneously. */ - /* The variables acc ... acc3 hold output values that are being computed: - * - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) (((q63_t) b0 * Xn) >> 32); - /* acc += b1 * x[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn1))) >> 32); - /* acc += b[2] * x[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn2))) >> 32); - /* acc += a1 * y[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn1))) >> 32); - /* acc += a2 * y[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn2))) >> 32); - - /* The result is converted to 1.31 , Yn2 variable is reused */ - Yn2 = acc << shift; - - /* Store the output in the destination buffer. */ - *pOut++ = Yn2; - - /* Read the second input */ - Xn2 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) (((q63_t) b0 * (Xn2)) >> 32); - /* acc += b1 * x[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn))) >> 32); - /* acc += b[2] * x[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn1))) >> 32); - /* acc += a1 * y[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn2))) >> 32); - /* acc += a2 * y[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn1))) >> 32); - - /* The result is converted to 1.31, Yn1 variable is reused */ - Yn1 = acc << shift; - - /* Store the output in the destination buffer. */ - *pOut++ = Yn1; - - /* Read the third input */ - Xn1 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) (((q63_t) b0 * (Xn1)) >> 32); - /* acc += b1 * x[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn2))) >> 32); - /* acc += b[2] * x[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn))) >> 32); - /* acc += a1 * y[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn1))) >> 32); - /* acc += a2 * y[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn2))) >> 32); - - /* The result is converted to 1.31, Yn2 variable is reused */ - Yn2 = acc << shift; - - /* Store the output in the destination buffer. */ - *pOut++ = Yn2; - - /* Read the forth input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) (((q63_t) b0 * (Xn)) >> 32); - /* acc += b1 * x[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn1))) >> 32); - /* acc += b[2] * x[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn2))) >> 32); - /* acc += a1 * y[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn2))) >> 32); - /* acc += a2 * y[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn1))) >> 32); - - /* The result is converted to 1.31, Yn1 variable is reused */ - Yn1 = acc << shift; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - - /* Store the output in the destination buffer. */ - *pOut++ = Yn1; - - /* decrement the loop counter */ - sample--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - sample = (blockSize & 0x3u); - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) (((q63_t) b0 * (Xn)) >> 32); - /* acc += b1 * x[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn1))) >> 32); - /* acc += b[2] * x[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn2))) >> 32); - /* acc += a1 * y[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn1))) >> 32); - /* acc += a2 * y[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn2))) >> 32); - /* The result is converted to 1.31 */ - acc = acc << shift; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = acc; - - /* Store the output in the destination buffer. */ - *pOut++ = acc; - - /* decrement the loop counter */ - sample--; - } - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent stages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset to destination pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); -} - -/** - * @} end of BiquadCascadeDF1 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df1_fast_q31.c +* +* Description: Processing function for the +* Q31 Fast Biquad cascade DirectFormI(DF1) filter. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.9 2010/08/27 +* Initial version +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup BiquadCascadeDF1 + * @{ + */ + +/** + * @details + * + * @param[in] *S points to an instance of the Q31 Biquad cascade structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * This function is optimized for speed at the expense of fixed-point precision and overflow protection. + * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. + * These intermediate results are added to a 2.30 accumulator. + * Finally, the accumulator is saturated and converted to a 1.31 result. + * The fast version has the same overflow behavior as the standard version and provides less precision since it discards the low 32 bits of each multiplication result. + * In order to avoid overflows completely the input signal must be scaled down by two bits and lie in the range [-0.25 +0.25). Use the intialization function + * arm_biquad_cascade_df1_init_q31() to initialize filter structure. + * + * \par + * Refer to the function arm_biquad_cascade_df1_q31() for a slower implementation of this function which uses 64-bit accumulation to provide higher precision. Both the slow and the fast versions use the same instance structure. + * Use the function arm_biquad_cascade_df1_init_q31() to initialize the filter structure. + */ + +void arm_biquad_cascade_df1_fast_q31( + const arm_biquad_casd_df1_inst_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t *pIn = pSrc; /* input pointer initialization */ + q31_t *pOut = pDst; /* output pointer initialization */ + q31_t *pState = S->pState; /* pState pointer initialization */ + q31_t *pCoeffs = S->pCoeffs; /* coeff pointer initialization */ + q31_t acc; /* accumulator */ + q31_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ + q31_t b0, b1, b2, a1, a2; /* Filter coefficients */ + q31_t Xn; /* temporary input */ + int32_t shift = (int32_t) S->postShift + 1; /* Shift to be applied to the output */ + uint32_t sample, stage = S->numStages; /* loop counters */ + + + do + { + /* Reading the coefficients */ + b0 = *pCoeffs++; + b1 = *pCoeffs++; + b2 = *pCoeffs++; + a1 = *pCoeffs++; + a2 = *pCoeffs++; + + /* Reading the state values */ + Xn1 = pState[0]; + Xn2 = pState[1]; + Yn1 = pState[2]; + Yn2 = pState[3]; + + /* Apply loop unrolling and compute 4 output values simultaneously. */ + /* The variables acc ... acc3 hold output values that are being computed: + * + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + */ + + sample = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = (q31_t) (((q63_t) b0 * Xn) >> 32); + /* acc += b1 * x[n-1] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn1))) >> 32); + /* acc += b[2] * x[n-2] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn2))) >> 32); + /* acc += a1 * y[n-1] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn1))) >> 32); + /* acc += a2 * y[n-2] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn2))) >> 32); + + /* The result is converted to 1.31 , Yn2 variable is reused */ + Yn2 = acc << shift; + + /* Store the output in the destination buffer. */ + *pOut++ = Yn2; + + /* Read the second input */ + Xn2 = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = (q31_t) (((q63_t) b0 * (Xn2)) >> 32); + /* acc += b1 * x[n-1] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn))) >> 32); + /* acc += b[2] * x[n-2] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn1))) >> 32); + /* acc += a1 * y[n-1] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn2))) >> 32); + /* acc += a2 * y[n-2] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn1))) >> 32); + + /* The result is converted to 1.31, Yn1 variable is reused */ + Yn1 = acc << shift; + + /* Store the output in the destination buffer. */ + *pOut++ = Yn1; + + /* Read the third input */ + Xn1 = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = (q31_t) (((q63_t) b0 * (Xn1)) >> 32); + /* acc += b1 * x[n-1] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn2))) >> 32); + /* acc += b[2] * x[n-2] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn))) >> 32); + /* acc += a1 * y[n-1] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn1))) >> 32); + /* acc += a2 * y[n-2] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn2))) >> 32); + + /* The result is converted to 1.31, Yn2 variable is reused */ + Yn2 = acc << shift; + + /* Store the output in the destination buffer. */ + *pOut++ = Yn2; + + /* Read the forth input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = (q31_t) (((q63_t) b0 * (Xn)) >> 32); + /* acc += b1 * x[n-1] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn1))) >> 32); + /* acc += b[2] * x[n-2] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn2))) >> 32); + /* acc += a1 * y[n-1] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn2))) >> 32); + /* acc += a2 * y[n-2] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn1))) >> 32); + + /* The result is converted to 1.31, Yn1 variable is reused */ + Yn1 = acc << shift; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + + /* Store the output in the destination buffer. */ + *pOut++ = Yn1; + + /* decrement the loop counter */ + sample--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + sample = (blockSize & 0x3u); + + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = (q31_t) (((q63_t) b0 * (Xn)) >> 32); + /* acc += b1 * x[n-1] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn1))) >> 32); + /* acc += b[2] * x[n-2] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn2))) >> 32); + /* acc += a1 * y[n-1] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn1))) >> 32); + /* acc += a2 * y[n-2] */ + acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn2))) >> 32); + /* The result is converted to 1.31 */ + acc = acc << shift; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + Yn2 = Yn1; + Yn1 = acc; + + /* Store the output in the destination buffer. */ + *pOut++ = acc; + + /* decrement the loop counter */ + sample--; + } + + /* The first stage goes from the input buffer to the output buffer. */ + /* Subsequent stages occur in-place in the output buffer */ + pIn = pDst; + + /* Reset to destination pointer */ + pOut = pDst; + + /* Store the updated state variables back into the pState array */ + *pState++ = Xn1; + *pState++ = Xn2; + *pState++ = Yn1; + *pState++ = Yn2; + + } while(--stage); +} + +/** + * @} end of BiquadCascadeDF1 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_f32.c index 4ea93db8b..e3e5a8540 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_f32.c @@ -1,104 +1,104 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_init_f32.c -* -* Description: floating-point Biquad cascade DirectFormI(DF1) filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @details - * @brief Initialization function for the floating-point Biquad cascade filter. - * @param[in,out] *S points to an instance of the floating-point Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] *pCoeffs points to the filter coefficients array. - * @param[in] *pState points to the state array. - * @return none - * - * - * Coefficient and State Ordering: - * - * \par - * The coefficients are stored in the array pCoeffs in the following order: - *
   
- *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}   
- * 
- * - * \par - * where b1x and a1x are the coefficients for the first stage, - * b2x and a2x are the coefficients for the second stage, - * and so on. The pCoeffs array contains a total of 5*numStages values. - * - * \par - * The pState is a pointer to state array. - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. - * The state variables are arranged in the pState array as: - *
   
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
- * 
- * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - * - */ - -void arm_biquad_cascade_df1_init_f32( - arm_biquad_casd_df1_inst_f32 * S, - uint8_t numStages, - float32_t * pCoeffs, - float32_t * pState) -{ - /* Assign filter stages */ - S->numStages = numStages; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always 4 * numStages */ - memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; -} - -/** - * @} end of BiquadCascadeDF1 group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df1_init_f32.c +* +* Description: floating-point Biquad cascade DirectFormI(DF1) filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup BiquadCascadeDF1 + * @{ + */ + +/** + * @details + * @brief Initialization function for the floating-point Biquad cascade filter. + * @param[in,out] *S points to an instance of the floating-point Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] *pCoeffs points to the filter coefficients array. + * @param[in] *pState points to the state array. + * @return none + * + * + * Coefficient and State Ordering: + * + * \par + * The coefficients are stored in the array pCoeffs in the following order: + *
   
+ *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}   
+ * 
+ * + * \par + * where b1x and a1x are the coefficients for the first stage, + * b2x and a2x are the coefficients for the second stage, + * and so on. The pCoeffs array contains a total of 5*numStages values. + * + * \par + * The pState is a pointer to state array. + * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. + * The state variables are arranged in the pState array as: + *
   
+ *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
+ * 
+ * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. + * The state array has a total length of 4*numStages values. + * The state variables are updated after each block of data is processed; the coefficients are untouched. + * + */ + +void arm_biquad_cascade_df1_init_f32( + arm_biquad_casd_df1_inst_f32 * S, + uint8_t numStages, + float32_t * pCoeffs, + float32_t * pState) +{ + /* Assign filter stages */ + S->numStages = numStages; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always 4 * numStages */ + memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(float32_t)); + + /* Assign state pointer */ + S->pState = pState; +} + +/** + * @} end of BiquadCascadeDF1 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q15.c index 19ceb32a8..42c60fb14 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q15.c @@ -1,106 +1,106 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_init_q15.c -* -* Description: Q15 Biquad cascade DirectFormI(DF1) filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @details - * - * @param[in,out] *S points to an instance of the Q15 Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] postShift Shift to be applied to the accumulator result. Varies according to the coefficients format - * @return none - * - * Coefficient and State Ordering: - * - * \par - * The coefficients are stored in the array pCoeffs in the following order: - *
   
- *     {b10, 0, b11, b12, a11, a12, b20, 0, b21, b22, a21, a22, ...}   
- * 
- * where b1x and a1x are the coefficients for the first stage, - * b2x and a2x are the coefficients for the second stage, - * and so on. The pCoeffs array contains a total of 6*numStages values. - * The zero coefficient between b1 and b2 facilities use of 16-bit SIMD instructions on the Cortex-M4. - * - * \par - * The state variables are stored in the array pState. - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. - * The state variables are arranged in the pState array as: - *
   
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
- * 
- * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - */ - -void arm_biquad_cascade_df1_init_q15( - arm_biquad_casd_df1_inst_q15 * S, - uint8_t numStages, - q15_t * pCoeffs, - q15_t * pState, - int8_t postShift) -{ - /* Assign filter stages */ - S->numStages = numStages; - - /* Assign postShift to be applied to the output */ - S->postShift = postShift; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always 4 * numStages */ - memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; -} - -/** - * @} end of BiquadCascadeDF1 group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df1_init_q15.c +* +* Description: Q15 Biquad cascade DirectFormI(DF1) filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup BiquadCascadeDF1 + * @{ + */ + +/** + * @details + * + * @param[in,out] *S points to an instance of the Q15 Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] postShift Shift to be applied to the accumulator result. Varies according to the coefficients format + * @return none + * + * Coefficient and State Ordering: + * + * \par + * The coefficients are stored in the array pCoeffs in the following order: + *
   
+ *     {b10, 0, b11, b12, a11, a12, b20, 0, b21, b22, a21, a22, ...}   
+ * 
+ * where b1x and a1x are the coefficients for the first stage, + * b2x and a2x are the coefficients for the second stage, + * and so on. The pCoeffs array contains a total of 6*numStages values. + * The zero coefficient between b1 and b2 facilities use of 16-bit SIMD instructions on the Cortex-M4. + * + * \par + * The state variables are stored in the array pState. + * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. + * The state variables are arranged in the pState array as: + *
   
+ *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
+ * 
+ * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. + * The state array has a total length of 4*numStages values. + * The state variables are updated after each block of data is processed; the coefficients are untouched. + */ + +void arm_biquad_cascade_df1_init_q15( + arm_biquad_casd_df1_inst_q15 * S, + uint8_t numStages, + q15_t * pCoeffs, + q15_t * pState, + int8_t postShift) +{ + /* Assign filter stages */ + S->numStages = numStages; + + /* Assign postShift to be applied to the output */ + S->postShift = postShift; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always 4 * numStages */ + memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(q15_t)); + + /* Assign state pointer */ + S->pState = pState; +} + +/** + * @} end of BiquadCascadeDF1 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q31.c index a41e4daf7..2e6028e9d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q31.c @@ -1,106 +1,106 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_init_q31.c -* -* Description: Q31 Biquad cascade DirectFormI(DF1) filter initialization function. -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @details - * - * @param[in,out] *S points to an instance of the Q31 Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] *pCoeffs points to the filter coefficients buffer. - * @param[in] *pState points to the state buffer. - * @param[in] postShift Shift to be applied after the accumulator. Varies according to the coefficients format - * @return none - * - * Coefficient and State Ordering: - * - * \par - * The coefficients are stored in the array pCoeffs in the following order: - *
   
- *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}   
- * 
- * where b1x and a1x are the coefficients for the first stage, - * b2x and a2x are the coefficients for the second stage, - * and so on. The pCoeffs array contains a total of 5*numStages values. - * - * \par - * The pState points to state variables array. - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. - * The state variables are arranged in the pState array as: - *
   
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
- * 
- * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - */ - -void arm_biquad_cascade_df1_init_q31( - arm_biquad_casd_df1_inst_q31 * S, - uint8_t numStages, - q31_t * pCoeffs, - q31_t * pState, - int8_t postShift) -{ - /* Assign filter stages */ - S->numStages = numStages; - - /* Assign postShift to be applied to the output */ - S->postShift = postShift; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always 4 * numStages */ - memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; -} - -/** - * @} end of BiquadCascadeDF1 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df1_init_q31.c +* +* Description: Q31 Biquad cascade DirectFormI(DF1) filter initialization function. +* +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup BiquadCascadeDF1 + * @{ + */ + +/** + * @details + * + * @param[in,out] *S points to an instance of the Q31 Biquad cascade structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] *pCoeffs points to the filter coefficients buffer. + * @param[in] *pState points to the state buffer. + * @param[in] postShift Shift to be applied after the accumulator. Varies according to the coefficients format + * @return none + * + * Coefficient and State Ordering: + * + * \par + * The coefficients are stored in the array pCoeffs in the following order: + *
   
+ *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}   
+ * 
+ * where b1x and a1x are the coefficients for the first stage, + * b2x and a2x are the coefficients for the second stage, + * and so on. The pCoeffs array contains a total of 5*numStages values. + * + * \par + * The pState points to state variables array. + * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. + * The state variables are arranged in the pState array as: + *
   
+ *     {x[n-1], x[n-2], y[n-1], y[n-2]}   
+ * 
+ * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. + * The state array has a total length of 4*numStages values. + * The state variables are updated after each block of data is processed; the coefficients are untouched. + */ + +void arm_biquad_cascade_df1_init_q31( + arm_biquad_casd_df1_inst_q31 * S, + uint8_t numStages, + q31_t * pCoeffs, + q31_t * pState, + int8_t postShift) +{ + /* Assign filter stages */ + S->numStages = numStages; + + /* Assign postShift to be applied to the output */ + S->postShift = postShift; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always 4 * numStages */ + memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(q31_t)); + + /* Assign state pointer */ + S->pState = pState; +} + +/** + * @} end of BiquadCascadeDF1 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q15.c index a9083f8f1..9e7bd011d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q15.c @@ -1,380 +1,380 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_q15.c -* -* Description: Processing function for the -* Q15 Biquad cascade DirectFormI(DF1) filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @brief Processing function for the Q15 Biquad cascade filter. - * @param[in] *S points to an instance of the Q15 Biquad cascade structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * The accumulator is then shifted by postShift bits to truncate the result to 1.15 format by discarding the low 16 bits. - * Finally, the result is saturated to 1.15 format. - * - * \par - * Refer to the function arm_biquad_cascade_df1_fast_q15() for a faster but less precise implementation of this filter for Cortex-M3 and Cortex-M4. - */ - -void arm_biquad_cascade_df1_q15( - const arm_biquad_casd_df1_inst_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *pIn = pSrc; /* Source pointer */ - q15_t *pOut = pDst; /* Destination pointer */ - q31_t in; /* Temporary variable to hold input value */ - q31_t out; /* Temporary variable to hold output value */ - q31_t b0; /* Temporary variable to hold bo value */ - q31_t b1, a1; /* Filter coefficients */ - q31_t state_in, state_out; /* Filter state variables */ - q63_t acc; /* Accumulator */ - int32_t shift = (15 - (int32_t) S->postShift); /* Post shift */ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pState_q31; /* 32-bit state pointer for SIMD implementation */ - uint32_t sample, stage = (uint32_t) S->numStages; /* Stage loop counter */ - - do - { - /* Initialize state pointer of type q31 */ - pState_q31 = (q31_t *) (pState); - - /* Read the b0 and 0 coefficients using SIMD */ - b0 = *__SIMD32(pCoeffs)++; - - /* Read the b1 and b2 coefficients using SIMD */ - b1 = *__SIMD32(pCoeffs)++; - - /* Read the a1 and a2 coefficients using SIMD */ - a1 = *__SIMD32(pCoeffs)++; - - /* Read the input state values from the state buffer: x[n-1], x[n-2] */ - state_in = (q31_t) (*pState_q31++); - - /* Read the output state values from the state buffer: y[n-1], y[n-2] */ - state_out = (q31_t) (*pState_q31); - - /* Apply loop unrolling and compute 2 output values simultaneously. */ - /* The variable acc hold output values that are being computed: - * - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - sample = blockSize >> 1u; - - /* First part of the processing with loop unrolling. Compute 2 outputs at a time. - ** a second loop below computes the remaining 1 sample. */ - while(sample > 0u) - { - - /* Read the input */ - in = *__SIMD32(pIn)++; - - /* out = b0 * x[n] + 0 * 0 */ - out = __SMUAD(b0, in); - - /* acc += b1 * x[n-1] + b2 * x[n-2] + out */ - acc = __SMLALD(b1, state_in, out); - /* acc += a1 * y[n-1] + a2 * y[n-2] */ - acc = __SMLALD(a1, state_out, acc); - - /* The result is converted from 3.29 to 1.31 if postShift = 1, and then saturation is applied */ - out = __SSAT((acc >> shift), 16); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, (in >> 16), 16); - state_out = __PKHBT(state_out >> 16, (out), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* out = b0 * x[n] + 0 * 0 */ - out = __SMUADX(b0, in); - /* acc += b1 * x[n-1] + b2 * x[n-2] + out */ - acc = __SMLALD(b1, state_in, out); - /* acc += a1 * y[n-1] + a2 * y[n-2] */ - acc = __SMLALD(a1, state_out, acc); - - /* The result is converted from 3.29 to 1.31 if postShift = 1, and then saturation is applied */ - out = __SSAT((acc >> shift), 16); - - /* Store the output in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = __PKHBT(state_out, out, 16); - -#else - - *__SIMD32(pOut)++ = __PKHBT(out, state_out >> 16, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in >> 16, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, in, 16); - state_out = __PKHBT(state_out >> 16, out, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - /* Decrement the loop counter */ - sample--; - - } - - /* If the blockSize is not a multiple of 2, compute any remaining output samples here. - ** No loop unrolling is used. */ - - if((blockSize & 0x1u) != 0u) - { - /* Read the input */ - in = *pIn++; - - /* out = b0 * x[n] + 0 * 0 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - out = __SMUAD(b0, in); - -#else - - out = __SMUADX(b0, in); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc = b1 * x[n-1] + b2 * x[n-2] + out */ - acc = __SMLALD(b1, state_in, out); - /* acc += a1 * y[n-1] + a2 * y[n-2] */ - acc = __SMLALD(a1, state_out, acc); - - /* The result is converted from 3.29 to 1.31 if postShift = 1, and then saturation is applied */ - out = __SSAT((acc >> shift), 16); - - /* Store the output in the destination buffer. */ - *pOut++ = (q15_t) out; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, in, 16); - state_out = __PKHBT(state_out >> 16, out, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - } - - /* The first stage goes from the input wire to the output wire. */ - /* Subsequent numStages occur in-place in the output wire */ - pIn = pDst; - - /* Reset the output pointer */ - pOut = pDst; - - /* Store the updated state variables back into the state array */ - *__SIMD32(pState)++ = state_in; - *__SIMD32(pState)++ = state_out; - - - /* Decrement the loop counter */ - stage--; - - } while(stage > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t *pIn = pSrc; /* Source pointer */ - q15_t *pOut = pDst; /* Destination pointer */ - q15_t b0, b1, b2, a1, a2; /* Filter coefficients */ - q15_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ - q15_t Xn; /* temporary input */ - q63_t acc; /* Accumulator */ - int32_t shift = (15 - (int32_t) S->postShift); /* Post shift */ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - uint32_t sample, stage = (uint32_t) S->numStages; /* Stage loop counter */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* The variables acc holds the output value that is computed: - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) b0 *Xn; - - /* acc += b1 * x[n-1] */ - acc += (q31_t) b1 *Xn1; - /* acc += b[2] * x[n-2] */ - acc += (q31_t) b2 *Xn2; - /* acc += a1 * y[n-1] */ - acc += (q31_t) a1 *Yn1; - /* acc += a2 * y[n-2] */ - acc += (q31_t) a2 *Yn2; - - /* The result is converted to 1.31 */ - acc = __SSAT((acc >> shift), 16); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = (q15_t) acc; - - /* Store the output in the destination buffer. */ - *pOut++ = (q15_t) acc; - - /* decrement the loop counter */ - sample--; - } - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent stages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset to destination pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - -/** - * @} end of BiquadCascadeDF1 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df1_q15.c +* +* Description: Processing function for the +* Q15 Biquad cascade DirectFormI(DF1) filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup BiquadCascadeDF1 + * @{ + */ + +/** + * @brief Processing function for the Q15 Biquad cascade filter. + * @param[in] *S points to an instance of the Q15 Biquad cascade structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the location where the output result is written. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 64-bit internal accumulator. + * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + * The accumulator is then shifted by postShift bits to truncate the result to 1.15 format by discarding the low 16 bits. + * Finally, the result is saturated to 1.15 format. + * + * \par + * Refer to the function arm_biquad_cascade_df1_fast_q15() for a faster but less precise implementation of this filter for Cortex-M3 and Cortex-M4. + */ + +void arm_biquad_cascade_df1_q15( + const arm_biquad_casd_df1_inst_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t *pIn = pSrc; /* Source pointer */ + q15_t *pOut = pDst; /* Destination pointer */ + q31_t in; /* Temporary variable to hold input value */ + q31_t out; /* Temporary variable to hold output value */ + q31_t b0; /* Temporary variable to hold bo value */ + q31_t b1, a1; /* Filter coefficients */ + q31_t state_in, state_out; /* Filter state variables */ + q63_t acc; /* Accumulator */ + int32_t shift = (15 - (int32_t) S->postShift); /* Post shift */ + q15_t *pState = S->pState; /* State pointer */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *pState_q31; /* 32-bit state pointer for SIMD implementation */ + uint32_t sample, stage = (uint32_t) S->numStages; /* Stage loop counter */ + + do + { + /* Initialize state pointer of type q31 */ + pState_q31 = (q31_t *) (pState); + + /* Read the b0 and 0 coefficients using SIMD */ + b0 = *__SIMD32(pCoeffs)++; + + /* Read the b1 and b2 coefficients using SIMD */ + b1 = *__SIMD32(pCoeffs)++; + + /* Read the a1 and a2 coefficients using SIMD */ + a1 = *__SIMD32(pCoeffs)++; + + /* Read the input state values from the state buffer: x[n-1], x[n-2] */ + state_in = (q31_t) (*pState_q31++); + + /* Read the output state values from the state buffer: y[n-1], y[n-2] */ + state_out = (q31_t) (*pState_q31); + + /* Apply loop unrolling and compute 2 output values simultaneously. */ + /* The variable acc hold output values that are being computed: + * + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + */ + sample = blockSize >> 1u; + + /* First part of the processing with loop unrolling. Compute 2 outputs at a time. + ** a second loop below computes the remaining 1 sample. */ + while(sample > 0u) + { + + /* Read the input */ + in = *__SIMD32(pIn)++; + + /* out = b0 * x[n] + 0 * 0 */ + out = __SMUAD(b0, in); + + /* acc += b1 * x[n-1] + b2 * x[n-2] + out */ + acc = __SMLALD(b1, state_in, out); + /* acc += a1 * y[n-1] + a2 * y[n-2] */ + acc = __SMLALD(a1, state_out, acc); + + /* The result is converted from 3.29 to 1.31 if postShift = 1, and then saturation is applied */ + out = __SSAT((acc >> shift), 16); + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ + /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ + +#ifndef ARM_MATH_BIG_ENDIAN + + state_in = __PKHBT(in, state_in, 16); + state_out = __PKHBT(out, state_out, 16); + +#else + + state_in = __PKHBT(state_in >> 16, (in >> 16), 16); + state_out = __PKHBT(state_out >> 16, (out), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* out = b0 * x[n] + 0 * 0 */ + out = __SMUADX(b0, in); + /* acc += b1 * x[n-1] + b2 * x[n-2] + out */ + acc = __SMLALD(b1, state_in, out); + /* acc += a1 * y[n-1] + a2 * y[n-2] */ + acc = __SMLALD(a1, state_out, acc); + + /* The result is converted from 3.29 to 1.31 if postShift = 1, and then saturation is applied */ + out = __SSAT((acc >> shift), 16); + + /* Store the output in the destination buffer. */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pOut)++ = __PKHBT(state_out, out, 16); + +#else + + *__SIMD32(pOut)++ = __PKHBT(out, state_out >> 16, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ + /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ +#ifndef ARM_MATH_BIG_ENDIAN + + state_in = __PKHBT(in >> 16, state_in, 16); + state_out = __PKHBT(out, state_out, 16); + +#else + + state_in = __PKHBT(state_in >> 16, in, 16); + state_out = __PKHBT(state_out >> 16, out, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + + /* Decrement the loop counter */ + sample--; + + } + + /* If the blockSize is not a multiple of 2, compute any remaining output samples here. + ** No loop unrolling is used. */ + + if((blockSize & 0x1u) != 0u) + { + /* Read the input */ + in = *pIn++; + + /* out = b0 * x[n] + 0 * 0 */ + +#ifndef ARM_MATH_BIG_ENDIAN + + out = __SMUAD(b0, in); + +#else + + out = __SMUADX(b0, in); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* acc = b1 * x[n-1] + b2 * x[n-2] + out */ + acc = __SMLALD(b1, state_in, out); + /* acc += a1 * y[n-1] + a2 * y[n-2] */ + acc = __SMLALD(a1, state_out, acc); + + /* The result is converted from 3.29 to 1.31 if postShift = 1, and then saturation is applied */ + out = __SSAT((acc >> shift), 16); + + /* Store the output in the destination buffer. */ + *pOut++ = (q15_t) out; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ + /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ + +#ifndef ARM_MATH_BIG_ENDIAN + + state_in = __PKHBT(in, state_in, 16); + state_out = __PKHBT(out, state_out, 16); + +#else + + state_in = __PKHBT(state_in >> 16, in, 16); + state_out = __PKHBT(state_out >> 16, out, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + } + + /* The first stage goes from the input wire to the output wire. */ + /* Subsequent numStages occur in-place in the output wire */ + pIn = pDst; + + /* Reset the output pointer */ + pOut = pDst; + + /* Store the updated state variables back into the state array */ + *__SIMD32(pState)++ = state_in; + *__SIMD32(pState)++ = state_out; + + + /* Decrement the loop counter */ + stage--; + + } while(stage > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + q15_t *pIn = pSrc; /* Source pointer */ + q15_t *pOut = pDst; /* Destination pointer */ + q15_t b0, b1, b2, a1, a2; /* Filter coefficients */ + q15_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ + q15_t Xn; /* temporary input */ + q63_t acc; /* Accumulator */ + int32_t shift = (15 - (int32_t) S->postShift); /* Post shift */ + q15_t *pState = S->pState; /* State pointer */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + uint32_t sample, stage = (uint32_t) S->numStages; /* Stage loop counter */ + + do + { + /* Reading the coefficients */ + b0 = *pCoeffs++; + b1 = *pCoeffs++; + b2 = *pCoeffs++; + a1 = *pCoeffs++; + a2 = *pCoeffs++; + + /* Reading the state values */ + Xn1 = pState[0]; + Xn2 = pState[1]; + Yn1 = pState[2]; + Yn2 = pState[3]; + + /* The variables acc holds the output value that is computed: + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + */ + + sample = blockSize; + + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = (q31_t) b0 *Xn; + + /* acc += b1 * x[n-1] */ + acc += (q31_t) b1 *Xn1; + /* acc += b[2] * x[n-2] */ + acc += (q31_t) b2 *Xn2; + /* acc += a1 * y[n-1] */ + acc += (q31_t) a1 *Yn1; + /* acc += a2 * y[n-2] */ + acc += (q31_t) a2 *Yn2; + + /* The result is converted to 1.31 */ + acc = __SSAT((acc >> shift), 16); + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + Yn2 = Yn1; + Yn1 = (q15_t) acc; + + /* Store the output in the destination buffer. */ + *pOut++ = (q15_t) acc; + + /* decrement the loop counter */ + sample--; + } + + /* The first stage goes from the input buffer to the output buffer. */ + /* Subsequent stages occur in-place in the output buffer */ + pIn = pDst; + + /* Reset to destination pointer */ + pOut = pDst; + + /* Store the updated state variables back into the pState array */ + *pState++ = Xn1; + *pState++ = Xn2; + *pState++ = Yn1; + *pState++ = Yn2; + + } while(--stage); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + +/** + * @} end of BiquadCascadeDF1 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q31.c index 66d65f803..068722772 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q31.c @@ -1,362 +1,362 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_q31.c -* -* Description: Processing function for the -* Q31 Biquad cascade filter -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @brief Processing function for the Q31 Biquad cascade filter. - * @param[in] *S points to an instance of the Q31 Biquad cascade structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 2 bits and lie in the range [-0.25 +0.25). - * After all 5 multiply-accumulates are performed, the 2.62 accumulator is shifted by postShift bits and the result truncated to - * 1.31 format by discarding the low 32 bits. - * - * \par - * Refer to the function arm_biquad_cascade_df1_fast_q31() for a faster but less precise implementation of this filter for Cortex-M3 and Cortex-M4. - */ - -void arm_biquad_cascade_df1_q31( - const arm_biquad_casd_df1_inst_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pIn = pSrc; /* input pointer initialization */ - q31_t *pOut = pDst; /* output pointer initialization */ - q31_t *pState = S->pState; /* pState pointer initialization */ - q31_t *pCoeffs = S->pCoeffs; /* coeff pointer initialization */ - q63_t acc; /* accumulator */ - q31_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ - q31_t b0, b1, b2, a1, a2; /* Filter coefficients */ - q31_t Xn; /* temporary input */ - uint32_t shift = 32u - ((uint32_t) S->postShift + 1u); /* Shift to be applied to the output */ - uint32_t sample, stage = S->numStages; /* loop counters */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* Apply loop unrolling and compute 4 output values simultaneously. */ - /* The variable acc hold output values that are being computed: - * - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn; - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn1; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn2; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn1; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn2; - - /* The result is converted to 1.31 , Yn2 variable is reused */ - Yn2 = (q31_t) (acc >> shift); - - /* Store the output in the destination buffer. */ - *pOut++ = Yn2; - - /* Read the second input */ - Xn2 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn2; - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn1; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn2; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn1; - - - /* The result is converted to 1.31, Yn1 variable is reused */ - Yn1 = (q31_t) (acc >> shift); - - /* Store the output in the destination buffer. */ - *pOut++ = Yn1; - - /* Read the third input */ - Xn1 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn1; - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn2; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn1; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn2; - - /* The result is converted to 1.31, Yn2 variable is reused */ - Yn2 = (q31_t) (acc >> shift); - - /* Store the output in the destination buffer. */ - *pOut++ = Yn2; - - /* Read the forth input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn; - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn1; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn2; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn2; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn1; - - /* The result is converted to 1.31, Yn1 variable is reused */ - Yn1 = (q31_t) (acc >> shift); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - - /* Store the output in the destination buffer. */ - *pOut++ = Yn1; - - /* decrement the loop counter */ - sample--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - sample = (blockSize & 0x3u); - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn; - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn1; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn2; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn1; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn2; - - /* The result is converted to 1.31 */ - acc = acc >> shift; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = (q31_t) acc; - - /* Store the output in the destination buffer. */ - *pOut++ = (q31_t) acc; - - /* decrement the loop counter */ - sample--; - } - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent stages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset to destination pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); - -#else - - /* Run the below code for Cortex-M0 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* The variables acc holds the output value that is computed: - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn; - - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn1; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn2; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn1; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn2; - - /* The result is converted to 1.31 */ - acc = acc >> shift; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = (q31_t) acc; - - /* Store the output in the destination buffer. */ - *pOut++ = (q31_t) acc; - - /* decrement the loop counter */ - sample--; - } - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent stages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset to destination pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); - -#endif /* #ifndef ARM_MATH_CM0 */ -} - -/** - * @} end of BiquadCascadeDF1 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df1_q31.c +* +* Description: Processing function for the +* Q31 Biquad cascade filter +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup BiquadCascadeDF1 + * @{ + */ + +/** + * @brief Processing function for the Q31 Biquad cascade filter. + * @param[in] *S points to an instance of the Q31 Biquad cascade structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around rather than clip. + * In order to avoid overflows completely the input signal must be scaled down by 2 bits and lie in the range [-0.25 +0.25). + * After all 5 multiply-accumulates are performed, the 2.62 accumulator is shifted by postShift bits and the result truncated to + * 1.31 format by discarding the low 32 bits. + * + * \par + * Refer to the function arm_biquad_cascade_df1_fast_q31() for a faster but less precise implementation of this filter for Cortex-M3 and Cortex-M4. + */ + +void arm_biquad_cascade_df1_q31( + const arm_biquad_casd_df1_inst_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t *pIn = pSrc; /* input pointer initialization */ + q31_t *pOut = pDst; /* output pointer initialization */ + q31_t *pState = S->pState; /* pState pointer initialization */ + q31_t *pCoeffs = S->pCoeffs; /* coeff pointer initialization */ + q63_t acc; /* accumulator */ + q31_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ + q31_t b0, b1, b2, a1, a2; /* Filter coefficients */ + q31_t Xn; /* temporary input */ + uint32_t shift = 32u - ((uint32_t) S->postShift + 1u); /* Shift to be applied to the output */ + uint32_t sample, stage = S->numStages; /* loop counters */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + do + { + /* Reading the coefficients */ + b0 = *pCoeffs++; + b1 = *pCoeffs++; + b2 = *pCoeffs++; + a1 = *pCoeffs++; + a2 = *pCoeffs++; + + /* Reading the state values */ + Xn1 = pState[0]; + Xn2 = pState[1]; + Yn1 = pState[2]; + Yn2 = pState[3]; + + /* Apply loop unrolling and compute 4 output values simultaneously. */ + /* The variable acc hold output values that are being computed: + * + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + */ + + sample = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + + /* acc = b0 * x[n] */ + acc = (q63_t) b0 *Xn; + /* acc += b1 * x[n-1] */ + acc += (q63_t) b1 *Xn1; + /* acc += b[2] * x[n-2] */ + acc += (q63_t) b2 *Xn2; + /* acc += a1 * y[n-1] */ + acc += (q63_t) a1 *Yn1; + /* acc += a2 * y[n-2] */ + acc += (q63_t) a2 *Yn2; + + /* The result is converted to 1.31 , Yn2 variable is reused */ + Yn2 = (q31_t) (acc >> shift); + + /* Store the output in the destination buffer. */ + *pOut++ = Yn2; + + /* Read the second input */ + Xn2 = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + + /* acc = b0 * x[n] */ + acc = (q63_t) b0 *Xn2; + /* acc += b1 * x[n-1] */ + acc += (q63_t) b1 *Xn; + /* acc += b[2] * x[n-2] */ + acc += (q63_t) b2 *Xn1; + /* acc += a1 * y[n-1] */ + acc += (q63_t) a1 *Yn2; + /* acc += a2 * y[n-2] */ + acc += (q63_t) a2 *Yn1; + + + /* The result is converted to 1.31, Yn1 variable is reused */ + Yn1 = (q31_t) (acc >> shift); + + /* Store the output in the destination buffer. */ + *pOut++ = Yn1; + + /* Read the third input */ + Xn1 = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + + /* acc = b0 * x[n] */ + acc = (q63_t) b0 *Xn1; + /* acc += b1 * x[n-1] */ + acc += (q63_t) b1 *Xn2; + /* acc += b[2] * x[n-2] */ + acc += (q63_t) b2 *Xn; + /* acc += a1 * y[n-1] */ + acc += (q63_t) a1 *Yn1; + /* acc += a2 * y[n-2] */ + acc += (q63_t) a2 *Yn2; + + /* The result is converted to 1.31, Yn2 variable is reused */ + Yn2 = (q31_t) (acc >> shift); + + /* Store the output in the destination buffer. */ + *pOut++ = Yn2; + + /* Read the forth input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + + /* acc = b0 * x[n] */ + acc = (q63_t) b0 *Xn; + /* acc += b1 * x[n-1] */ + acc += (q63_t) b1 *Xn1; + /* acc += b[2] * x[n-2] */ + acc += (q63_t) b2 *Xn2; + /* acc += a1 * y[n-1] */ + acc += (q63_t) a1 *Yn2; + /* acc += a2 * y[n-2] */ + acc += (q63_t) a2 *Yn1; + + /* The result is converted to 1.31, Yn1 variable is reused */ + Yn1 = (q31_t) (acc >> shift); + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + + /* Store the output in the destination buffer. */ + *pOut++ = Yn1; + + /* decrement the loop counter */ + sample--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + sample = (blockSize & 0x3u); + + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + + /* acc = b0 * x[n] */ + acc = (q63_t) b0 *Xn; + /* acc += b1 * x[n-1] */ + acc += (q63_t) b1 *Xn1; + /* acc += b[2] * x[n-2] */ + acc += (q63_t) b2 *Xn2; + /* acc += a1 * y[n-1] */ + acc += (q63_t) a1 *Yn1; + /* acc += a2 * y[n-2] */ + acc += (q63_t) a2 *Yn2; + + /* The result is converted to 1.31 */ + acc = acc >> shift; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + Yn2 = Yn1; + Yn1 = (q31_t) acc; + + /* Store the output in the destination buffer. */ + *pOut++ = (q31_t) acc; + + /* decrement the loop counter */ + sample--; + } + + /* The first stage goes from the input buffer to the output buffer. */ + /* Subsequent stages occur in-place in the output buffer */ + pIn = pDst; + + /* Reset to destination pointer */ + pOut = pDst; + + /* Store the updated state variables back into the pState array */ + *pState++ = Xn1; + *pState++ = Xn2; + *pState++ = Yn1; + *pState++ = Yn2; + + } while(--stage); + +#else + + /* Run the below code for Cortex-M0 */ + + do + { + /* Reading the coefficients */ + b0 = *pCoeffs++; + b1 = *pCoeffs++; + b2 = *pCoeffs++; + a1 = *pCoeffs++; + a2 = *pCoeffs++; + + /* Reading the state values */ + Xn1 = pState[0]; + Xn2 = pState[1]; + Yn1 = pState[2]; + Yn2 = pState[3]; + + /* The variables acc holds the output value that is computed: + * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] + */ + + sample = blockSize; + + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ + /* acc = b0 * x[n] */ + acc = (q63_t) b0 *Xn; + + /* acc += b1 * x[n-1] */ + acc += (q63_t) b1 *Xn1; + /* acc += b[2] * x[n-2] */ + acc += (q63_t) b2 *Xn2; + /* acc += a1 * y[n-1] */ + acc += (q63_t) a1 *Yn1; + /* acc += a2 * y[n-2] */ + acc += (q63_t) a2 *Yn2; + + /* The result is converted to 1.31 */ + acc = acc >> shift; + + /* Every time after the output is computed state should be updated. */ + /* The states should be updated as: */ + /* Xn2 = Xn1 */ + /* Xn1 = Xn */ + /* Yn2 = Yn1 */ + /* Yn1 = acc */ + Xn2 = Xn1; + Xn1 = Xn; + Yn2 = Yn1; + Yn1 = (q31_t) acc; + + /* Store the output in the destination buffer. */ + *pOut++ = (q31_t) acc; + + /* decrement the loop counter */ + sample--; + } + + /* The first stage goes from the input buffer to the output buffer. */ + /* Subsequent stages occur in-place in the output buffer */ + pIn = pDst; + + /* Reset to destination pointer */ + pOut = pDst; + + /* Store the updated state variables back into the pState array */ + *pState++ = Xn1; + *pState++ = Xn2; + *pState++ = Yn1; + *pState++ = Yn2; + + } while(--stage); + +#endif /* #ifndef ARM_MATH_CM0 */ +} + +/** + * @} end of BiquadCascadeDF1 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_f32.c index 9c3e0a72f..4cf42173c 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_f32.c @@ -1,359 +1,359 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df2T_f32.c -* -* Description: Processing function for the floating-point transposed -* direct form II Biquad cascade filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup BiquadCascadeDF2T Biquad Cascade IIR Filters Using a Direct Form II Transposed Structure - * - * This set of functions implements arbitrary order recursive (IIR) filters using a transposed direct form II structure. - * The filters are implemented as a cascade of second order Biquad sections. - * These functions provide a slight memory savings as compared to the direct form I Biquad filter functions. - * Only floating-point data is supported. - * - * This function operate on blocks of input and output data and each call to the function - * processes blockSize samples through the filter. - * pSrc points to the array of input data and - * pDst points to the array of output data. - * Both arrays contain blockSize values. - * - * \par Algorithm - * Each Biquad stage implements a second order filter using the difference equation: - *
   
- *    y[n] = b0 * x[n] + d1   
- *    d1 = b1 * x[n] + a1 * y[n] + d2   
- *    d2 = b2 * x[n] + a2 * y[n]   
- * 
- * where d1 and d2 represent the two state values. - * - * \par - * A Biquad filter using a transposed Direct Form II structure is shown below. - * \image html BiquadDF2Transposed.gif "Single transposed Direct Form II Biquad" - * Coefficients b0, b1, and b2 multiply the input signal x[n] and are referred to as the feedforward coefficients. - * Coefficients a1 and a2 multiply the output signal y[n] and are referred to as the feedback coefficients. - * Pay careful attention to the sign of the feedback coefficients. - * Some design tools flip the sign of the feedback coefficients: - *
   
- *    y[n] = b0 * x[n] + d1;   
- *    d1 = b1 * x[n] - a1 * y[n] + d2;   
- *    d2 = b2 * x[n] - a2 * y[n];   
- * 
- * In this case the feedback coefficients a1 and a2 must be negated when used with the CMSIS DSP Library. - * - * \par - * Higher order filters are realized as a cascade of second order sections. - * numStages refers to the number of second order stages used. - * For example, an 8th order filter would be realized with numStages=4 second order stages. - * A 9th order filter would be realized with numStages=5 second order stages with the - * coefficients for one of the stages configured as a first order filter (b2=0 and a2=0). - * - * \par - * pState points to the state variable array. - * Each Biquad stage has 2 state variables d1 and d2. - * The state variables are arranged in the pState array as: - *
   
- *     {d11, d12, d21, d22, ...}   
- * 
- * where d1x refers to the state variables for the first Biquad and - * d2x refers to the state variables for the second Biquad. - * The state array has a total length of 2*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - * - * \par - * The CMSIS library contains Biquad filters in both Direct Form I and transposed Direct Form II. - * The advantage of the Direct Form I structure is that it is numerically more robust for fixed-point data types. - * That is why the Direct Form I structure supports Q15 and Q31 data types. - * The transposed Direct Form II structure, on the other hand, requires a wide dynamic range for the state variables d1 and d2. - * Because of this, the CMSIS library only has a floating-point version of the Direct Form II Biquad. - * The advantage of the Direct Form II Biquad is that it requires half the number of state variables, 2 rather than 4, per Biquad stage. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * - * \par Init Functions - * There is also an associated initialization function. - * The initialization function performs following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * For example, to statically initialize the instance structure use - *
   
- *     arm_biquad_cascade_df2T_instance_f32 S1 = {numStages, pState, pCoeffs};   
- * 
- * where numStages is the number of Biquad stages in the filter; pState is the address of the state buffer. - * pCoeffs is the address of the coefficient buffer; - * - */ - -/** - * @addtogroup BiquadCascadeDF2T - * @{ - */ - -/** - * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in] *S points to an instance of the filter data structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_biquad_cascade_df2T_f32( - const arm_biquad_cascade_df2T_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - - float32_t *pIn = pSrc; /* source pointer */ - float32_t *pOut = pDst; /* destination pointer */ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* coefficient pointer */ - float32_t acc0; /* Simulates the accumulator */ - float32_t b0, b1, b2, a1, a2; /* Filter coefficients */ - float32_t Xn; /* temporary input */ - float32_t d1, d2; /* state variables */ - uint32_t sample, stage = S->numStages; /* loop counters */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /*Reading the state values */ - d1 = pState[0]; - d2 = pState[1]; - - /* Apply loop unrolling and compute 4 output values simultaneously. */ - sample = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(sample > 0u) - { - /* Read the first input */ - Xn = *pIn++; - - /* y[n] = b0 * x[n] + d1 */ - acc0 = (b0 * Xn) + d1; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - - /* Every time after the output is computed state should be updated. */ - /* d1 = b1 * x[n] + a1 * y[n] + d2 */ - d1 = ((b1 * Xn) + (a1 * acc0)) + d2; - - /* d2 = b2 * x[n] + a2 * y[n] */ - d2 = (b2 * Xn) + (a2 * acc0); - - /* Read the second input */ - Xn = *pIn++; - - /* y[n] = b0 * x[n] + d1 */ - acc0 = (b0 * Xn) + d1; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - - /* Every time after the output is computed state should be updated. */ - /* d1 = b1 * x[n] + a1 * y[n] + d2 */ - d1 = ((b1 * Xn) + (a1 * acc0)) + d2; - - /* d2 = b2 * x[n] + a2 * y[n] */ - d2 = (b2 * Xn) + (a2 * acc0); - - /* Read the third input */ - Xn = *pIn++; - - /* y[n] = b0 * x[n] + d1 */ - acc0 = (b0 * Xn) + d1; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - - /* Every time after the output is computed state should be updated. */ - /* d1 = b1 * x[n] + a1 * y[n] + d2 */ - d1 = ((b1 * Xn) + (a1 * acc0)) + d2; - - /* d2 = b2 * x[n] + a2 * y[n] */ - d2 = (b2 * Xn) + (a2 * acc0); - - /* Read the fourth input */ - Xn = *pIn++; - - /* y[n] = b0 * x[n] + d1 */ - acc0 = (b0 * Xn) + d1; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - - /* Every time after the output is computed state should be updated. */ - /* d1 = b1 * x[n] + a1 * y[n] + d2 */ - d1 = (b1 * Xn) + (a1 * acc0) + d2; - - /* d2 = b2 * x[n] + a2 * y[n] */ - d2 = (b2 * Xn) + (a2 * acc0); - - /* decrement the loop counter */ - sample--; - - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - sample = blockSize & 0x3u; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* y[n] = b0 * x[n] + d1 */ - acc0 = (b0 * Xn) + d1; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - - /* Every time after the output is computed state should be updated. */ - /* d1 = b1 * x[n] + a1 * y[n] + d2 */ - d1 = ((b1 * Xn) + (a1 * acc0)) + d2; - - /* d2 = b2 * x[n] + a2 * y[n] */ - d2 = (b2 * Xn) + (a2 * acc0); - - /* decrement the loop counter */ - sample--; - } - - /* Store the updated state variables back into the state array */ - *pState++ = d1; - *pState++ = d2; - - /* The current stage input is given as the output to the next stage */ - pIn = pDst; - - /*Reset the output working pointer */ - pOut = pDst; - - /* decrement the loop counter */ - stage--; - - } while(stage > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /*Reading the state values */ - d1 = pState[0]; - d2 = pState[1]; - - - sample = blockSize; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* y[n] = b0 * x[n] + d1 */ - acc0 = (b0 * Xn) + d1; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - - /* Every time after the output is computed state should be updated. */ - /* d1 = b1 * x[n] + a1 * y[n] + d2 */ - d1 = ((b1 * Xn) + (a1 * acc0)) + d2; - - /* d2 = b2 * x[n] + a2 * y[n] */ - d2 = (b2 * Xn) + (a2 * acc0); - - /* decrement the loop counter */ - sample--; - } - - /* Store the updated state variables back into the state array */ - *pState++ = d1; - *pState++ = d2; - - /* The current stage input is given as the output to the next stage */ - pIn = pDst; - - /*Reset the output working pointer */ - pOut = pDst; - - /* decrement the loop counter */ - stage--; - - } while(stage > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - - /** - * @} end of BiquadCascadeDF2T group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df2T_f32.c +* +* Description: Processing function for the floating-point transposed +* direct form II Biquad cascade filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup BiquadCascadeDF2T Biquad Cascade IIR Filters Using a Direct Form II Transposed Structure + * + * This set of functions implements arbitrary order recursive (IIR) filters using a transposed direct form II structure. + * The filters are implemented as a cascade of second order Biquad sections. + * These functions provide a slight memory savings as compared to the direct form I Biquad filter functions. + * Only floating-point data is supported. + * + * This function operate on blocks of input and output data and each call to the function + * processes blockSize samples through the filter. + * pSrc points to the array of input data and + * pDst points to the array of output data. + * Both arrays contain blockSize values. + * + * \par Algorithm + * Each Biquad stage implements a second order filter using the difference equation: + *
   
+ *    y[n] = b0 * x[n] + d1   
+ *    d1 = b1 * x[n] + a1 * y[n] + d2   
+ *    d2 = b2 * x[n] + a2 * y[n]   
+ * 
+ * where d1 and d2 represent the two state values. + * + * \par + * A Biquad filter using a transposed Direct Form II structure is shown below. + * \image html BiquadDF2Transposed.gif "Single transposed Direct Form II Biquad" + * Coefficients b0, b1, and b2 multiply the input signal x[n] and are referred to as the feedforward coefficients. + * Coefficients a1 and a2 multiply the output signal y[n] and are referred to as the feedback coefficients. + * Pay careful attention to the sign of the feedback coefficients. + * Some design tools flip the sign of the feedback coefficients: + *
   
+ *    y[n] = b0 * x[n] + d1;   
+ *    d1 = b1 * x[n] - a1 * y[n] + d2;   
+ *    d2 = b2 * x[n] - a2 * y[n];   
+ * 
+ * In this case the feedback coefficients a1 and a2 must be negated when used with the CMSIS DSP Library. + * + * \par + * Higher order filters are realized as a cascade of second order sections. + * numStages refers to the number of second order stages used. + * For example, an 8th order filter would be realized with numStages=4 second order stages. + * A 9th order filter would be realized with numStages=5 second order stages with the + * coefficients for one of the stages configured as a first order filter (b2=0 and a2=0). + * + * \par + * pState points to the state variable array. + * Each Biquad stage has 2 state variables d1 and d2. + * The state variables are arranged in the pState array as: + *
   
+ *     {d11, d12, d21, d22, ...}   
+ * 
+ * where d1x refers to the state variables for the first Biquad and + * d2x refers to the state variables for the second Biquad. + * The state array has a total length of 2*numStages values. + * The state variables are updated after each block of data is processed; the coefficients are untouched. + * + * \par + * The CMSIS library contains Biquad filters in both Direct Form I and transposed Direct Form II. + * The advantage of the Direct Form I structure is that it is numerically more robust for fixed-point data types. + * That is why the Direct Form I structure supports Q15 and Q31 data types. + * The transposed Direct Form II structure, on the other hand, requires a wide dynamic range for the state variables d1 and d2. + * Because of this, the CMSIS library only has a floating-point version of the Direct Form II Biquad. + * The advantage of the Direct Form II Biquad is that it requires half the number of state variables, 2 rather than 4, per Biquad stage. + * + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter. + * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. + * + * \par Init Functions + * There is also an associated initialization function. + * The initialization function performs following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Set the values in the state buffer to zeros before static initialization. + * For example, to statically initialize the instance structure use + *
   
+ *     arm_biquad_cascade_df2T_instance_f32 S1 = {numStages, pState, pCoeffs};   
+ * 
+ * where numStages is the number of Biquad stages in the filter; pState is the address of the state buffer. + * pCoeffs is the address of the coefficient buffer; + * + */ + +/** + * @addtogroup BiquadCascadeDF2T + * @{ + */ + +/** + * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in] *S points to an instance of the filter data structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of samples to process. + * @return none. + */ + +void arm_biquad_cascade_df2T_f32( + const arm_biquad_cascade_df2T_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + + float32_t *pIn = pSrc; /* source pointer */ + float32_t *pOut = pDst; /* destination pointer */ + float32_t *pState = S->pState; /* State pointer */ + float32_t *pCoeffs = S->pCoeffs; /* coefficient pointer */ + float32_t acc0; /* Simulates the accumulator */ + float32_t b0, b1, b2, a1, a2; /* Filter coefficients */ + float32_t Xn; /* temporary input */ + float32_t d1, d2; /* state variables */ + uint32_t sample, stage = S->numStages; /* loop counters */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + do + { + /* Reading the coefficients */ + b0 = *pCoeffs++; + b1 = *pCoeffs++; + b2 = *pCoeffs++; + a1 = *pCoeffs++; + a2 = *pCoeffs++; + + /*Reading the state values */ + d1 = pState[0]; + d2 = pState[1]; + + /* Apply loop unrolling and compute 4 output values simultaneously. */ + sample = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(sample > 0u) + { + /* Read the first input */ + Xn = *pIn++; + + /* y[n] = b0 * x[n] + d1 */ + acc0 = (b0 * Xn) + d1; + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = acc0; + + /* Every time after the output is computed state should be updated. */ + /* d1 = b1 * x[n] + a1 * y[n] + d2 */ + d1 = ((b1 * Xn) + (a1 * acc0)) + d2; + + /* d2 = b2 * x[n] + a2 * y[n] */ + d2 = (b2 * Xn) + (a2 * acc0); + + /* Read the second input */ + Xn = *pIn++; + + /* y[n] = b0 * x[n] + d1 */ + acc0 = (b0 * Xn) + d1; + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = acc0; + + /* Every time after the output is computed state should be updated. */ + /* d1 = b1 * x[n] + a1 * y[n] + d2 */ + d1 = ((b1 * Xn) + (a1 * acc0)) + d2; + + /* d2 = b2 * x[n] + a2 * y[n] */ + d2 = (b2 * Xn) + (a2 * acc0); + + /* Read the third input */ + Xn = *pIn++; + + /* y[n] = b0 * x[n] + d1 */ + acc0 = (b0 * Xn) + d1; + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = acc0; + + /* Every time after the output is computed state should be updated. */ + /* d1 = b1 * x[n] + a1 * y[n] + d2 */ + d1 = ((b1 * Xn) + (a1 * acc0)) + d2; + + /* d2 = b2 * x[n] + a2 * y[n] */ + d2 = (b2 * Xn) + (a2 * acc0); + + /* Read the fourth input */ + Xn = *pIn++; + + /* y[n] = b0 * x[n] + d1 */ + acc0 = (b0 * Xn) + d1; + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = acc0; + + /* Every time after the output is computed state should be updated. */ + /* d1 = b1 * x[n] + a1 * y[n] + d2 */ + d1 = (b1 * Xn) + (a1 * acc0) + d2; + + /* d2 = b2 * x[n] + a2 * y[n] */ + d2 = (b2 * Xn) + (a2 * acc0); + + /* decrement the loop counter */ + sample--; + + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + sample = blockSize & 0x3u; + + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* y[n] = b0 * x[n] + d1 */ + acc0 = (b0 * Xn) + d1; + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = acc0; + + /* Every time after the output is computed state should be updated. */ + /* d1 = b1 * x[n] + a1 * y[n] + d2 */ + d1 = ((b1 * Xn) + (a1 * acc0)) + d2; + + /* d2 = b2 * x[n] + a2 * y[n] */ + d2 = (b2 * Xn) + (a2 * acc0); + + /* decrement the loop counter */ + sample--; + } + + /* Store the updated state variables back into the state array */ + *pState++ = d1; + *pState++ = d2; + + /* The current stage input is given as the output to the next stage */ + pIn = pDst; + + /*Reset the output working pointer */ + pOut = pDst; + + /* decrement the loop counter */ + stage--; + + } while(stage > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + do + { + /* Reading the coefficients */ + b0 = *pCoeffs++; + b1 = *pCoeffs++; + b2 = *pCoeffs++; + a1 = *pCoeffs++; + a2 = *pCoeffs++; + + /*Reading the state values */ + d1 = pState[0]; + d2 = pState[1]; + + + sample = blockSize; + + while(sample > 0u) + { + /* Read the input */ + Xn = *pIn++; + + /* y[n] = b0 * x[n] + d1 */ + acc0 = (b0 * Xn) + d1; + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = acc0; + + /* Every time after the output is computed state should be updated. */ + /* d1 = b1 * x[n] + a1 * y[n] + d2 */ + d1 = ((b1 * Xn) + (a1 * acc0)) + d2; + + /* d2 = b2 * x[n] + a2 * y[n] */ + d2 = (b2 * Xn) + (a2 * acc0); + + /* decrement the loop counter */ + sample--; + } + + /* Store the updated state variables back into the state array */ + *pState++ = d1; + *pState++ = d2; + + /* The current stage input is given as the output to the next stage */ + pIn = pDst; + + /*Reset the output working pointer */ + pOut = pDst; + + /* decrement the loop counter */ + stage--; + + } while(stage > 0u); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + + /** + * @} end of BiquadCascadeDF2T group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_init_f32.c index eaf35d85b..552778505 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_init_f32.c @@ -1,94 +1,94 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df2T_init_f32.c -* -* Description: Initialization function for the floating-point transposed -* direct form II Biquad cascade filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF2T - * @{ - */ - -/** - * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in,out] *S points to an instance of the filter data structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @return none - * - * Coefficient and State Ordering: - * \par - * The coefficients are stored in the array pCoeffs in the following order: - *
   
- *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}   
- * 
- * - * \par - * where b1x and a1x are the coefficients for the first stage, - * b2x and a2x are the coefficients for the second stage, - * and so on. The pCoeffs array contains a total of 5*numStages values. - * - * \par - * The pState is a pointer to state array. - * Each Biquad stage has 2 state variables d1, and d2. - * The 2 state variables for stage 1 are first, then the 2 state variables for stage 2, and so on. - * The state array has a total length of 2*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - */ - -void arm_biquad_cascade_df2T_init_f32( - arm_biquad_cascade_df2T_instance_f32 * S, - uint8_t numStages, - float32_t * pCoeffs, - float32_t * pState) -{ - /* Assign filter stages */ - S->numStages = numStages; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always 2 * numStages */ - memset(pState, 0, (2u * (uint32_t) numStages) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; -} - -/** - * @} end of BiquadCascadeDF2T group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_biquad_cascade_df2T_init_f32.c +* +* Description: Initialization function for the floating-point transposed +* direct form II Biquad cascade filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup BiquadCascadeDF2T + * @{ + */ + +/** + * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. + * @param[in,out] *S points to an instance of the filter data structure. + * @param[in] numStages number of 2nd order stages in the filter. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @return none + * + * Coefficient and State Ordering: + * \par + * The coefficients are stored in the array pCoeffs in the following order: + *
   
+ *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}   
+ * 
+ * + * \par + * where b1x and a1x are the coefficients for the first stage, + * b2x and a2x are the coefficients for the second stage, + * and so on. The pCoeffs array contains a total of 5*numStages values. + * + * \par + * The pState is a pointer to state array. + * Each Biquad stage has 2 state variables d1, and d2. + * The 2 state variables for stage 1 are first, then the 2 state variables for stage 2, and so on. + * The state array has a total length of 2*numStages values. + * The state variables are updated after each block of data is processed; the coefficients are untouched. + */ + +void arm_biquad_cascade_df2T_init_f32( + arm_biquad_cascade_df2T_instance_f32 * S, + uint8_t numStages, + float32_t * pCoeffs, + float32_t * pState) +{ + /* Assign filter stages */ + S->numStages = numStages; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always 2 * numStages */ + memset(pState, 0, (2u * (uint32_t) numStages) * sizeof(float32_t)); + + /* Assign state pointer */ + S->pState = pState; +} + +/** + * @} end of BiquadCascadeDF2T group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_f32.c index 1c8a726e2..db3990c57 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_f32.c @@ -1,623 +1,623 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_f32.c -* -* Description: Convolution of floating-point sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup Conv Convolution - * - * Convolution is a mathematical operation that operates on two finite length vectors to generate a finite length output vector. - * Convolution is similar to correlation and is frequently used in filtering and data analysis. - * The CMSIS DSP library contains functions for convolving Q7, Q15, Q31, and floating-point data types. - * The library also provides fast versions of the Q15 and Q31 functions on Cortex-M4 and Cortex-M3. - * - * \par Algorithm - * Let a[n] and b[n] be sequences of length srcALen and srcBLen samples respectively. - * Then the convolution - * - *
   
- *                   c[n] = a[n] * b[n]   
- * 
- * - * \par - * is defined as - * \image html ConvolutionEquation.gif - * \par - * Note that c[n] is of length srcALen + srcBLen - 1 and is defined over the interval n=0, 1, 2, ..., srcALen + srcBLen - 2. - * pSrcA points to the first input vector of length srcALen and - * pSrcB points to the second input vector of length srcBLen. - * The output result is written to pDst and the calling function must allocate srcALen+srcBLen-1 words for the result. - * - * \par - * Conceptually, when two signals a[n] and b[n] are convolved, - * the signal b[n] slides over a[n]. - * For each offset \c n, the overlapping portions of a[n] and b[n] are multiplied and summed together. - * - * \par - * Note that convolution is a commutative operation: - * - *
   
- *                   a[n] * b[n] = b[n] * a[n].   
- * 
- * - * \par - * This means that switching the A and B arguments to the convolution functions has no effect. - * - * Fixed-Point Behavior - * - * \par - * Convolution requires summing up a large number of intermediate products. - * As such, the Q7, Q15, and Q31 functions run a risk of overflow and saturation. - * Refer to the function specific documentation below for further details of the particular algorithm used. - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of floating-point sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - */ - -void arm_conv_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t *pIn1; /* inputA pointer */ - float32_t *pIn2; /* inputB pointer */ - float32_t *pOut = pDst; /* output pointer */ - float32_t *px; /* Intermediate inputA pointer */ - float32_t *py; /* Intermediate inputB pointer */ - float32_t *pSrc1, *pSrc2; /* Intermediate pointers */ - float32_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - float32_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counters */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum += *px++ * *py--; - - /* x[1] * y[srcBLen - 2] */ - sum += *px++ * *py--; - - /* x[2] * y[srcBLen - 3] */ - sum += *px++ * *py--; - - /* x[3] * y[srcBLen - 4] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0.0f; - acc1 = 0.0f; - acc2 = 0.0f; - acc3 = 0.0f; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 += x0 * c0; - - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 += x1 * c0; - - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 += x2 * c0; - - /* acc3 += x[3] * y[srcBLen - 1] */ - acc3 += x3 * c0; - - /* Read y[srcBLen - 2] sample */ - c0 = *(py--); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 += x1 * c0; - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 += x2 * c0; - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 += x3 * c0; - /* acc3 += x[4] * y[srcBLen - 2] */ - acc3 += x0 * c0; - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 += x2 * c0; - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 += x3 * c0; - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 += x0 * c0; - /* acc3 += x[5] * y[srcBLen - 2] */ - acc3 += x1 * c0; - - /* Read y[srcBLen - 4] sample */ - c0 = *(py--); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[srcBLen - 4] */ - acc0 += x3 * c0; - /* acc1 += x[4] * y[srcBLen - 4] */ - acc1 += x0 * c0; - /* acc2 += x[5] * y[srcBLen - 4] */ - acc2 += x1 * c0; - /* acc3 += x[6] * y[srcBLen - 4] */ - acc3 += x2 * c0; - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += x0 * c0; - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += x1 * c0; - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += x2 * c0; - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 += x3 * c0; - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - *pOut++ = acc1; - *pOut++ = acc2; - *pOut++ = acc3; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += *px++ * *py--; - sum += *px++ * *py--; - sum += *px++ * *py--; - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t *pIn1 = pSrcA; /* inputA pointer */ - float32_t *pIn2 = pSrcB; /* inputB pointer */ - float32_t sum; /* Accumulator */ - uint32_t i, j; /* loop counters */ - - /* Loop to calculate convolution for output length number of times */ - for (i = 0u; i < ((srcALen + srcBLen) - 1u); i++) - { - /* Initialize sum with zero to carry out MAC operations */ - sum = 0.0f; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += pIn1[j] * pIn2[i - j]; - } - } - /* Store the output in the destination buffer */ - pDst[i] = sum; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Conv group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_f32.c +* +* Description: Convolution of floating-point sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup Conv Convolution + * + * Convolution is a mathematical operation that operates on two finite length vectors to generate a finite length output vector. + * Convolution is similar to correlation and is frequently used in filtering and data analysis. + * The CMSIS DSP library contains functions for convolving Q7, Q15, Q31, and floating-point data types. + * The library also provides fast versions of the Q15 and Q31 functions on Cortex-M4 and Cortex-M3. + * + * \par Algorithm + * Let a[n] and b[n] be sequences of length srcALen and srcBLen samples respectively. + * Then the convolution + * + *
   
+ *                   c[n] = a[n] * b[n]   
+ * 
+ * + * \par + * is defined as + * \image html ConvolutionEquation.gif + * \par + * Note that c[n] is of length srcALen + srcBLen - 1 and is defined over the interval n=0, 1, 2, ..., srcALen + srcBLen - 2. + * pSrcA points to the first input vector of length srcALen and + * pSrcB points to the second input vector of length srcBLen. + * The output result is written to pDst and the calling function must allocate srcALen+srcBLen-1 words for the result. + * + * \par + * Conceptually, when two signals a[n] and b[n] are convolved, + * the signal b[n] slides over a[n]. + * For each offset \c n, the overlapping portions of a[n] and b[n] are multiplied and summed together. + * + * \par + * Note that convolution is a commutative operation: + * + *
   
+ *                   a[n] * b[n] = b[n] * a[n].   
+ * 
+ * + * \par + * This means that switching the A and B arguments to the convolution functions has no effect. + * + * Fixed-Point Behavior + * + * \par + * Convolution requires summing up a large number of intermediate products. + * As such, the Q7, Q15, and Q31 functions run a risk of overflow and saturation. + * Refer to the function specific documentation below for further details of the particular algorithm used. + */ + +/** + * @addtogroup Conv + * @{ + */ + +/** + * @brief Convolution of floating-point sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + * @return none. + */ + +void arm_conv_f32( + float32_t * pSrcA, + uint32_t srcALen, + float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + float32_t *pIn1; /* inputA pointer */ + float32_t *pIn2; /* inputB pointer */ + float32_t *pOut = pDst; /* output pointer */ + float32_t *px; /* Intermediate inputA pointer */ + float32_t *py; /* Intermediate inputB pointer */ + float32_t *pSrc1, *pSrc2; /* Intermediate pointers */ + float32_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ + float32_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counters */ + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* The algorithm is implemented in three stages. + The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + blockSize3 = blockSize1; + + /* -------------------------- + * initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first stage starts here */ + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 1] */ + sum += *px++ * *py--; + + /* x[1] * y[srcBLen - 2] */ + sum += *px++ * *py--; + + /* x[2] * y[srcBLen - 3] */ + sum += *px++ * *py--; + + /* x[3] * y[srcBLen - 4] */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum; + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pIn2 + count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0.0f; + acc1 = 0.0f; + acc2 = 0.0f; + acc3 = 0.0f; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[srcBLen - 1] sample */ + c0 = *(py--); + + /* Read x[3] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[0] * y[srcBLen - 1] */ + acc0 += x0 * c0; + + /* acc1 += x[1] * y[srcBLen - 1] */ + acc1 += x1 * c0; + + /* acc2 += x[2] * y[srcBLen - 1] */ + acc2 += x2 * c0; + + /* acc3 += x[3] * y[srcBLen - 1] */ + acc3 += x3 * c0; + + /* Read y[srcBLen - 2] sample */ + c0 = *(py--); + + /* Read x[4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[1] * y[srcBLen - 2] */ + acc0 += x1 * c0; + /* acc1 += x[2] * y[srcBLen - 2] */ + acc1 += x2 * c0; + /* acc2 += x[3] * y[srcBLen - 2] */ + acc2 += x3 * c0; + /* acc3 += x[4] * y[srcBLen - 2] */ + acc3 += x0 * c0; + + /* Read y[srcBLen - 3] sample */ + c0 = *(py--); + + /* Read x[5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[2] * y[srcBLen - 3] */ + acc0 += x2 * c0; + /* acc1 += x[3] * y[srcBLen - 2] */ + acc1 += x3 * c0; + /* acc2 += x[4] * y[srcBLen - 2] */ + acc2 += x0 * c0; + /* acc3 += x[5] * y[srcBLen - 2] */ + acc3 += x1 * c0; + + /* Read y[srcBLen - 4] sample */ + c0 = *(py--); + + /* Read x[6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[3] * y[srcBLen - 4] */ + acc0 += x3 * c0; + /* acc1 += x[4] * y[srcBLen - 4] */ + acc1 += x0 * c0; + /* acc2 += x[5] * y[srcBLen - 4] */ + acc2 += x1 * c0; + /* acc3 += x[6] * y[srcBLen - 4] */ + acc3 += x2 * c0; + + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[srcBLen - 5] sample */ + c0 = *(py--); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[srcBLen - 5] */ + acc0 += x0 * c0; + /* acc1 += x[5] * y[srcBLen - 5] */ + acc1 += x1 * c0; + /* acc2 += x[6] * y[srcBLen - 5] */ + acc2 += x2 * c0; + /* acc3 += x[7] * y[srcBLen - 5] */ + acc3 += x3 * c0; + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = acc0; + *pOut++ = acc1; + *pOut++ = acc2; + *pOut++ = acc3; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += *px++ * *py--; + sum += *px++ * *py--; + sum += *px++ * *py--; + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The blockSize3 variable holds the number of MAC operations performed */ + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = blockSize3 >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ + sum += *px++ * *py--; + + /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ + sum += *px++ * *py--; + + /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ + sum += *px++ * *py--; + + /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = blockSize3 % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen-1] * y[srcBLen-1] */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the loop counter */ + blockSize3--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + float32_t *pIn1 = pSrcA; /* inputA pointer */ + float32_t *pIn2 = pSrcB; /* inputB pointer */ + float32_t sum; /* Accumulator */ + uint32_t i, j; /* loop counters */ + + /* Loop to calculate convolution for output length number of times */ + for (i = 0u; i < ((srcALen + srcBLen) - 1u); i++) + { + /* Initialize sum with zero to carry out MAC operations */ + sum = 0.0f; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0u; j <= i; j++) + { + /* Check the array limitations */ + if((((i - j) < srcBLen) && (j < srcALen))) + { + /* z[i] += x[i-j] * y[j] */ + sum += pIn1[j] * pIn2[i - j]; + } + } + /* Store the output in the destination buffer */ + pDst[i] = sum; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of Conv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q15.c index e53dbac13..70038f86a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q15.c @@ -1,677 +1,677 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_fast_q15.c -* -* Description: Fast Q15 Convolution. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - * - * Scaling and Overflow Behavior: - * - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results - * but provides only a single guard bit. There is no saturation on intermediate additions. - * Thus, if the accumulator overflows it wraps around and distorts the result. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down the inputs by log2(min(srcALen, srcBLen)) (log2 is read as log to the base 2) times to avoid overflows, - * as maximum of min(srcALen, srcBLen) number of additions are carried internally. - * The 2.30 accumulator is right shifted by 15 bits and then saturated to 1.15 format to yield the final result. - * - * \par - * See arm_conv_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. - */ - -void arm_conv_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst) -{ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t blockSize1, blockSize2, blockSize3, j, k, count, blkCnt; /* loop counter */ - q31_t *pb; /* 32 bit pointer for inputB buffer */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations less than 4 */ - /* Second part of this stage computes the MAC operations greater than or equal to 4 */ - - /* The first part of the stage starts here */ - while((count < 4u) && (blockSize1 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over number of MAC operations between - * inputA samples and inputB samples */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* The second part of the stage starts here */ - /* The internal loop, over count, is unrolled by 4 */ - /* To, read the last two inputB samples using SIMD: - * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ - py = py - 1; - - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + (count - 1u); - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* Initialize inputB pointer of type q31 */ - pb = (q31_t *) (py - 1u); - - /* count is the index by which the pointer pIn1 to be incremented */ - count = 1u; - - - /* -------------------- - * Stage2 process - * -------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - - /* read x[0], x[1] samples */ - x0 = *(q31_t *) (px++); - /* read x[1], x[2] samples */ - x1 = *(q31_t *) (px++); - - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the last two inputB samples using SIMD: - * y[srcBLen - 1] and y[srcBLen - 2] */ - c0 = *(pb--); - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLADX(x0, c0, acc0); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLADX(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *(q31_t *) (px++); - - /* Read x[3], x[4] */ - x3 = *(q31_t *) (px++); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLADX(x2, c0, acc2); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLADX(x3, c0, acc3); - - /* Read y[srcBLen - 3] and y[srcBLen - 4] */ - c0 = *(pb--); - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLADX(x2, c0, acc0); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLADX(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = *(q31_t *) (px++); - - /* Read x[5], x[6] */ - x1 = *(q31_t *) (px++); - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLADX(x0, c0, acc2); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLADX(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - py = (q15_t *) pb; - py = py + 1; - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[srcBLen - 5] */ - c0 = *(py); -#ifdef ARM_MATH_BIG_ENDIAN - -// c0 = unallign_rev(p, c0); - c0 = c0 << 16; -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLADX(x1, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = *(pb); - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = *pb--; - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - - /* Read y[srcBLen - 7] */ -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = (*pb); -// c0 = (c0 & 0x0000FFFF)<<16; - c0 = (c0) << 16; - -#else - - c0 = (q15_t) (*pb >> 16); - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x1, c0, acc0); - acc1 = __SMLAD(x2, c0, acc1); - acc2 = __SMLADX(x2, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - /* Store the results in the accumulators in the destination buffer. */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = __PKHBT((acc0 >> 15), (acc1 >> 15), 16); - *__SIMD32(pOut)++ = __PKHBT((acc2 >> 15), (acc3 >> 15), 16); - -#else - - *__SIMD32(pOut)++ = __PKHBT((acc1 >> 15), (acc0 >> 15), 16); - *__SIMD32(pOut)++ = __PKHBT((acc3 >> 15), (acc2 >> 15), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - pb = (q31_t *) (py - 1); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - pIn2 = pSrc2 - 1u; - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations greater than 4 */ - /* Second part of this stage computes the MAC operations less than or equal to 4 */ - - /* The first part of the stage starts here */ - j = blockSize3 >> 2u; - - while((j > 0u) && (blockSize3 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied - * with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied - * with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the loop counter */ - blockSize3--; - - j--; - } - - /* The second part of the stage starts here */ - /* SIMD is not used for the next MAC operations, - * so pointer py is updated to read only one sample at a time */ - py = py + 1u; - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -} - -/** - * @} end of Conv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_fast_q15.c +* +* Description: Fast Q15 Convolution. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup Conv + * @{ + */ + +/** + * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + * @return none. + * + * Scaling and Overflow Behavior: + * + * \par + * This fast version uses a 32-bit accumulator with 2.30 format. + * The accumulator maintains full precision of the intermediate multiplication results + * but provides only a single guard bit. There is no saturation on intermediate additions. + * Thus, if the accumulator overflows it wraps around and distorts the result. + * The input signals should be scaled down to avoid intermediate overflows. + * Scale down the inputs by log2(min(srcALen, srcBLen)) (log2 is read as log to the base 2) times to avoid overflows, + * as maximum of min(srcALen, srcBLen) number of additions are carried internally. + * The 2.30 accumulator is right shifted by 15 bits and then saturated to 1.15 format to yield the final result. + * + * \par + * See arm_conv_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. + */ + +void arm_conv_fast_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst) +{ + q15_t *pIn1; /* inputA pointer */ + q15_t *pIn2; /* inputB pointer */ + q15_t *pOut = pDst; /* output pointer */ + q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ + q15_t *px; /* Intermediate inputA pointer */ + q15_t *py; /* Intermediate inputB pointer */ + q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ + q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t blockSize1, blockSize2, blockSize3, j, k, count, blkCnt; /* loop counter */ + q31_t *pb; /* 32 bit pointer for inputB buffer */ + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* The algorithm is implemented in three stages. + The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + blockSize3 = blockSize1; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* For loop unrolling by 4, this stage is divided into two. */ + /* First part of this stage computes the MAC operations less than 4 */ + /* Second part of this stage computes the MAC operations greater than or equal to 4 */ + + /* The first part of the stage starts here */ + while((count < 4u) && (blockSize1 > 0u)) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Loop over number of MAC operations between + * inputA samples and inputB samples */ + k = count; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = __SMLAD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pIn2 + count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* The second part of the stage starts here */ + /* The internal loop, over count, is unrolled by 4 */ + /* To, read the last two inputB samples using SIMD: + * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ + py = py - 1; + + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ + sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ + sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* For the next MAC operations, the pointer py is used without SIMD + * So, py is incremented by 1 */ + py = py + 1u; + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = __SMLAD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pIn2 + (count - 1u); + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* Initialize inputB pointer of type q31 */ + pb = (q31_t *) (py - 1u); + + /* count is the index by which the pointer pIn1 to be incremented */ + count = 1u; + + + /* -------------------- + * Stage2 process + * -------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + + /* read x[0], x[1] samples */ + x0 = *(q31_t *) (px++); + /* read x[1], x[2] samples */ + x1 = *(q31_t *) (px++); + + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read the last two inputB samples using SIMD: + * y[srcBLen - 1] and y[srcBLen - 2] */ + c0 = *(pb--); + + /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ + acc0 = __SMLADX(x0, c0, acc0); + + /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ + acc1 = __SMLADX(x1, c0, acc1); + + /* Read x[2], x[3] */ + x2 = *(q31_t *) (px++); + + /* Read x[3], x[4] */ + x3 = *(q31_t *) (px++); + + /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ + acc2 = __SMLADX(x2, c0, acc2); + + /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ + acc3 = __SMLADX(x3, c0, acc3); + + /* Read y[srcBLen - 3] and y[srcBLen - 4] */ + c0 = *(pb--); + + /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ + acc0 = __SMLADX(x2, c0, acc0); + + /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ + acc1 = __SMLADX(x3, c0, acc1); + + /* Read x[4], x[5] */ + x0 = *(q31_t *) (px++); + + /* Read x[5], x[6] */ + x1 = *(q31_t *) (px++); + + /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ + acc2 = __SMLADX(x0, c0, acc2); + + /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ + acc3 = __SMLADX(x1, c0, acc3); + + } while(--k); + + /* For the next MAC operations, SIMD is not used + * So, the 16 bit pointer if inputB, py is updated */ + py = (q15_t *) pb; + py = py + 1; + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + if(k == 1u) + { + /* Read y[srcBLen - 5] */ + c0 = *(py); +#ifdef ARM_MATH_BIG_ENDIAN + +// c0 = unallign_rev(p, c0); + c0 = c0 << 16; +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + + /* Read x[7] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLAD(x0, c0, acc0); + acc1 = __SMLAD(x1, c0, acc1); + acc2 = __SMLADX(x1, c0, acc2); + acc3 = __SMLADX(x3, c0, acc3); + } + + if(k == 2u) + { + /* Read y[srcBLen - 5], y[srcBLen - 6] */ + c0 = *(pb); + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLADX(x0, c0, acc0); + acc1 = __SMLADX(x1, c0, acc1); + acc2 = __SMLADX(x3, c0, acc2); + acc3 = __SMLADX(x2, c0, acc3); + } + + if(k == 3u) + { + /* Read y[srcBLen - 5], y[srcBLen - 6] */ + c0 = *pb--; + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLADX(x0, c0, acc0); + acc1 = __SMLADX(x1, c0, acc1); + acc2 = __SMLADX(x3, c0, acc2); + acc3 = __SMLADX(x2, c0, acc3); + + /* Read y[srcBLen - 7] */ +#ifdef ARM_MATH_BIG_ENDIAN + + c0 = (*pb); +// c0 = (c0 & 0x0000FFFF)<<16; + c0 = (c0) << 16; + +#else + + c0 = (q15_t) (*pb >> 16); + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + + /* Read x[10] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLADX(x1, c0, acc0); + acc1 = __SMLAD(x2, c0, acc1); + acc2 = __SMLADX(x2, c0, acc2); + acc3 = __SMLADX(x3, c0, acc3); + } + + /* Store the results in the accumulators in the destination buffer. */ +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pOut)++ = __PKHBT((acc0 >> 15), (acc1 >> 15), 16); + *__SIMD32(pOut)++ = __PKHBT((acc2 >> 15), (acc3 >> 15), 16); + +#else + + *__SIMD32(pOut)++ = __PKHBT((acc1 >> 15), (acc0 >> 15), 16); + *__SIMD32(pOut)++ = __PKHBT((acc3 >> 15), (acc2 >> 15), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + pb = (q31_t *) (py - 1); + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q31_t) * px++ * *py--); + sum += ((q31_t) * px++ * *py--); + sum += ((q31_t) * px++ * *py--); + sum += ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The blockSize3 variable holds the number of MAC operations performed */ + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + pIn2 = pSrc2 - 1u; + py = pIn2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + /* For loop unrolling by 4, this stage is divided into two. */ + /* First part of this stage computes the MAC operations greater than 4 */ + /* Second part of this stage computes the MAC operations less than or equal to 4 */ + + /* The first part of the stage starts here */ + j = blockSize3 >> 2u; + + while((j > 0u) && (blockSize3 > 0u)) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = blockSize3 >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied + * with y[srcBLen - 1], y[srcBLen - 2] respectively */ + sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied + * with y[srcBLen - 3], y[srcBLen - 4] respectively */ + sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* For the next MAC operations, the pointer py is used without SIMD + * So, py is incremented by 1 */ + py = py + 1u; + + /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = blockSize3 % 0x4u; + + while(k > 0u) + { + /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ + sum = __SMLAD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pIn2; + + /* Decrement the loop counter */ + blockSize3--; + + j--; + } + + /* The second part of the stage starts here */ + /* SIMD is not used for the next MAC operations, + * so pointer py is updated to read only one sample at a time */ + py = py + 1u; + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = blockSize3; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen-1] * y[srcBLen-1] */ + sum = __SMLAD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the loop counter */ + blockSize3--; + } + +} + +/** + * @} end of Conv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q31.c index 3bd92170f..d1eeeaca1 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q31.c @@ -1,567 +1,567 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_fast_q31.c -* -* Description: Q31 Convolution (fast version). -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * This function is optimized for speed at the expense of fixed-point precision and overflow protection. - * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. - * These intermediate results are accumulated in a 32-bit register in 2.30 format. - * Finally, the accumulator is saturated and converted to a 1.31 result. - * - * \par - * The fast version has the same overflow behavior as the standard version but provides less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signals must be scaled down. - * Scale down the inputs by log2(min(srcALen, srcBLen)) (log2 is read as log to the base 2) times to avoid overflows, - * as maximum of min(srcALen, srcBLen) number of additions are carried internally. - * - * \par - * See arm_conv_q31() for a slower implementation of this function which uses 64-bit accumulation to provide higher precision. - */ - -void arm_conv_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst) -{ - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counter */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[1] * y[srcBLen - 2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[2] * y[srcBLen - 3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[3] * y[srcBLen - 4] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - - /* acc3 += x[3] * y[srcBLen - 1] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Read y[srcBLen - 2] sample */ - c0 = *(py--); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc3 += x[4] * y[srcBLen - 2] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc3 += x[5] * y[srcBLen - 2] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Read y[srcBLen - 4] sample */ - c0 = *(py--); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[srcBLen - 4] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc1 += x[4] * y[srcBLen - 4] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc2 += x[5] * y[srcBLen - 4] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc3 += x[6] * y[srcBLen - 4] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x2 * c0)) >> 32); - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the results in the accumulators in the destination buffer. */ - *pOut++ = (q31_t) (acc0 << 1); - *pOut++ = (q31_t) (acc1 << 1); - *pOut++ = (q31_t) (acc2 << 1); - *pOut++ = (q31_t) (acc3 << 1); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -} - -/** - * @} end of Conv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_fast_q31.c +* +* Description: Q31 Convolution (fast version). +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup Conv + * @{ + */ + +/** + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * This function is optimized for speed at the expense of fixed-point precision and overflow protection. + * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. + * These intermediate results are accumulated in a 32-bit register in 2.30 format. + * Finally, the accumulator is saturated and converted to a 1.31 result. + * + * \par + * The fast version has the same overflow behavior as the standard version but provides less precision since it discards the low 32 bits of each multiplication result. + * In order to avoid overflows completely the input signals must be scaled down. + * Scale down the inputs by log2(min(srcALen, srcBLen)) (log2 is read as log to the base 2) times to avoid overflows, + * as maximum of min(srcALen, srcBLen) number of additions are carried internally. + * + * \par + * See arm_conv_q31() for a slower implementation of this function which uses 64-bit accumulation to provide higher precision. + */ + +void arm_conv_fast_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst) +{ + q31_t *pIn1; /* inputA pointer */ + q31_t *pIn2; /* inputB pointer */ + q31_t *pOut = pDst; /* output pointer */ + q31_t *px; /* Intermediate inputA pointer */ + q31_t *py; /* Intermediate inputB pointer */ + q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ + q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ + q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counter */ + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* The algorithm is implemented in three stages. + The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + blockSize3 = blockSize1; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first stage starts here */ + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 1] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* x[1] * y[srcBLen - 2] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* x[2] * y[srcBLen - 3] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* x[3] * y[srcBLen - 4] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum << 1; + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pIn2 + count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[srcBLen - 1] sample */ + c0 = *(py--); + + /* Read x[3] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[0] * y[srcBLen - 1] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); + + /* acc1 += x[1] * y[srcBLen - 1] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); + + /* acc2 += x[2] * y[srcBLen - 1] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); + + /* acc3 += x[3] * y[srcBLen - 1] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); + + /* Read y[srcBLen - 2] sample */ + c0 = *(py--); + + /* Read x[4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[1] * y[srcBLen - 2] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x1 * c0)) >> 32); + /* acc1 += x[2] * y[srcBLen - 2] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x2 * c0)) >> 32); + /* acc2 += x[3] * y[srcBLen - 2] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x3 * c0)) >> 32); + /* acc3 += x[4] * y[srcBLen - 2] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x0 * c0)) >> 32); + + /* Read y[srcBLen - 3] sample */ + c0 = *(py--); + + /* Read x[5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[2] * y[srcBLen - 3] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x2 * c0)) >> 32); + /* acc1 += x[3] * y[srcBLen - 2] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x3 * c0)) >> 32); + /* acc2 += x[4] * y[srcBLen - 2] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x0 * c0)) >> 32); + /* acc3 += x[5] * y[srcBLen - 2] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x1 * c0)) >> 32); + + /* Read y[srcBLen - 4] sample */ + c0 = *(py--); + + /* Read x[6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[3] * y[srcBLen - 4] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x3 * c0)) >> 32); + /* acc1 += x[4] * y[srcBLen - 4] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x0 * c0)) >> 32); + /* acc2 += x[5] * y[srcBLen - 4] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x1 * c0)) >> 32); + /* acc3 += x[6] * y[srcBLen - 4] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x2 * c0)) >> 32); + + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[srcBLen - 5] sample */ + c0 = *(py--); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[srcBLen - 5] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); + /* acc1 += x[5] * y[srcBLen - 5] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); + /* acc2 += x[6] * y[srcBLen - 5] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); + /* acc3 += x[7] * y[srcBLen - 5] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the results in the accumulators in the destination buffer. */ + *pOut++ = (q31_t) (acc0 << 1); + *pOut++ = (q31_t) (acc1 << 1); + *pOut++ = (q31_t) (acc2 << 1); + *pOut++ = (q31_t) (acc3 << 1); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum << 1; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum << 1; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The blockSize3 variable holds the number of MAC operations performed */ + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = blockSize3 >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = blockSize3 % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum << 1; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the loop counter */ + blockSize3--; + } + +} + +/** + * @} end of Conv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_f32.c index 914ee2b6c..74b8c8e4d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_f32.c @@ -1,641 +1,641 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_f32.c -* -* Description: Partial convolution of floating-point sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup PartialConv Partial Convolution - * - * Partial Convolution is equivalent to Convolution except that a subset of the output samples is generated. - * Each function has two additional arguments. - * firstIndex specifies the starting index of the subset of output samples. - * numPoints is the number of output samples to compute. - * The function computes the output in the range - * [firstIndex, ..., firstIndex+numPoints-1]. - * The output array pDst contains numPoints values. - * - * The allowable range of output indices is [0 srcALen+srcBLen-2]. - * If the requested subset does not fall in this range then the functions return ARM_MATH_ARGUMENT_ERROR. - * Otherwise the functions return ARM_MATH_SUCCESS. - * \note Refer arm_conv_f32() for details on fixed point behavior. - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of floating-point sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - -arm_status arm_conv_partial_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t *pIn1 = pSrcA; /* inputA pointer */ - float32_t *pIn2 = pSrcB; /* inputB pointer */ - float32_t *pOut = pDst; /* output pointer */ - float32_t *px; /* Intermediate inputA pointer */ - float32_t *py; /* Intermediate inputB pointer */ - float32_t *pSrc1, *pSrc2; /* Intermediate pointers */ - float32_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - float32_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t j, k, count = 0u, blkCnt, check; - int32_t blockSize1, blockSize2, blockSize3; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = (int32_t) check - (int32_t) srcALen; - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = ((int32_t) srcBLen - 1) - (int32_t) firstIndex; - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = ((int32_t) check - blockSize3) - - (blockSize1 + (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + firstIndex; - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum += *px++ * *py--; - - /* x[1] * y[srcBLen - 2] */ - sum += *px++ * *py--; - - /* x[2] * y[srcBLen - 3] */ - sum += *px++ * *py--; - - /* x[3] * y[srcBLen - 4] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc1; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0.0f; - acc1 = 0.0f; - acc2 = 0.0f; - acc3 = 0.0f; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 += x0 * c0; - - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 += x1 * c0; - - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 += x2 * c0; - - /* acc3 += x[3] * y[srcBLen - 1] */ - acc3 += x3 * c0; - - /* Read y[srcBLen - 2] sample */ - c0 = *(py--); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 += x1 * c0; - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 += x2 * c0; - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 += x3 * c0; - /* acc3 += x[4] * y[srcBLen - 2] */ - acc3 += x0 * c0; - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 += x2 * c0; - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 += x3 * c0; - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 += x0 * c0; - /* acc3 += x[5] * y[srcBLen - 2] */ - acc3 += x1 * c0; - - /* Read y[srcBLen - 4] sample */ - c0 = *(py--); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[srcBLen - 4] */ - acc0 += x3 * c0; - /* acc1 += x[4] * y[srcBLen - 4] */ - acc1 += x0 * c0; - /* acc2 += x[5] * y[srcBLen - 4] */ - acc2 += x1 * c0; - /* acc3 += x[6] * y[srcBLen - 4] */ - acc3 += x2 * c0; - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += x0 * c0; - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += x1 * c0; - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += x2 * c0; - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 += x3 * c0; - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - *pOut++ = acc1; - *pOut++ = acc2; - *pOut++ = acc3; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += *px++ * *py--; - sum += *px++ * *py--; - sum += *px++ * *py--; - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t *pIn1 = pSrcA; /* inputA pointer */ - float32_t *pIn2 = pSrcB; /* inputB pointer */ - float32_t sum; /* Accumulator */ - uint32_t i, j; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - /* Loop to calculate convolution for output length number of values */ - for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0.0f; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations for inputs */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += pIn1[j] * pIn2[i - j]; - } - } - /* Store the output in the destination buffer */ - pDst[i] = sum; - } - /* set status as ARM_SUCCESS as there are no argument errors */ - status = ARM_MATH_SUCCESS; - } - return (status); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of PartialConv group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_partial_f32.c +* +* Description: Partial convolution of floating-point sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup PartialConv Partial Convolution + * + * Partial Convolution is equivalent to Convolution except that a subset of the output samples is generated. + * Each function has two additional arguments. + * firstIndex specifies the starting index of the subset of output samples. + * numPoints is the number of output samples to compute. + * The function computes the output in the range + * [firstIndex, ..., firstIndex+numPoints-1]. + * The output array pDst contains numPoints values. + * + * The allowable range of output indices is [0 srcALen+srcBLen-2]. + * If the requested subset does not fall in this range then the functions return ARM_MATH_ARGUMENT_ERROR. + * Otherwise the functions return ARM_MATH_SUCCESS. + * \note Refer arm_conv_f32() for details on fixed point behavior. + */ + +/** + * @addtogroup PartialConv + * @{ + */ + +/** + * @brief Partial convolution of floating-point sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + */ + +arm_status arm_conv_partial_f32( + float32_t * pSrcA, + uint32_t srcALen, + float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst, + uint32_t firstIndex, + uint32_t numPoints) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + float32_t *pIn1 = pSrcA; /* inputA pointer */ + float32_t *pIn2 = pSrcB; /* inputB pointer */ + float32_t *pOut = pDst; /* output pointer */ + float32_t *px; /* Intermediate inputA pointer */ + float32_t *py; /* Intermediate inputB pointer */ + float32_t *pSrc1, *pSrc2; /* Intermediate pointers */ + float32_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ + float32_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t j, k, count = 0u, blkCnt, check; + int32_t blockSize1, blockSize2, blockSize3; /* loop counters */ + arm_status status; /* status of Partial convolution */ + + + /* Check for range of output samples to be calculated */ + if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) + { + /* Set status as ARM_MATH_ARGUMENT_ERROR */ + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* Conditions to check which loopCounter holds + * the first and last indices of the output samples to be calculated. */ + check = firstIndex + numPoints; + blockSize3 = (int32_t) check - (int32_t) srcALen; + blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; + blockSize1 = ((int32_t) srcBLen - 1) - (int32_t) firstIndex; + blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : + (int32_t) numPoints) : 0; + blockSize2 = ((int32_t) check - blockSize3) - + (blockSize1 + (int32_t) firstIndex); + blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* Set the output pointer to point to the firstIndex + * of the output sample to be calculated. */ + pOut = pDst + firstIndex; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed. + Since the partial convolution starts from from firstIndex + Number of Macs to be performed is firstIndex + 1 */ + count = 1u + firstIndex; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc1 = pIn2 + firstIndex; + py = pSrc1; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first stage starts here */ + while(blockSize1 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 1] */ + sum += *px++ * *py--; + + /* x[1] * y[srcBLen - 2] */ + sum += *px++ * *py--; + + /* x[2] * y[srcBLen - 3] */ + sum += *px++ * *py--; + + /* x[3] * y[srcBLen - 4] */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum; + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = ++pSrc1; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = ((uint32_t) blockSize2 >> 2u); + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0.0f; + acc1 = 0.0f; + acc2 = 0.0f; + acc3 = 0.0f; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[srcBLen - 1] sample */ + c0 = *(py--); + + /* Read x[3] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[0] * y[srcBLen - 1] */ + acc0 += x0 * c0; + + /* acc1 += x[1] * y[srcBLen - 1] */ + acc1 += x1 * c0; + + /* acc2 += x[2] * y[srcBLen - 1] */ + acc2 += x2 * c0; + + /* acc3 += x[3] * y[srcBLen - 1] */ + acc3 += x3 * c0; + + /* Read y[srcBLen - 2] sample */ + c0 = *(py--); + + /* Read x[4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[1] * y[srcBLen - 2] */ + acc0 += x1 * c0; + /* acc1 += x[2] * y[srcBLen - 2] */ + acc1 += x2 * c0; + /* acc2 += x[3] * y[srcBLen - 2] */ + acc2 += x3 * c0; + /* acc3 += x[4] * y[srcBLen - 2] */ + acc3 += x0 * c0; + + /* Read y[srcBLen - 3] sample */ + c0 = *(py--); + + /* Read x[5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[2] * y[srcBLen - 3] */ + acc0 += x2 * c0; + /* acc1 += x[3] * y[srcBLen - 2] */ + acc1 += x3 * c0; + /* acc2 += x[4] * y[srcBLen - 2] */ + acc2 += x0 * c0; + /* acc3 += x[5] * y[srcBLen - 2] */ + acc3 += x1 * c0; + + /* Read y[srcBLen - 4] sample */ + c0 = *(py--); + + /* Read x[6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[3] * y[srcBLen - 4] */ + acc0 += x3 * c0; + /* acc1 += x[4] * y[srcBLen - 4] */ + acc1 += x0 * c0; + /* acc2 += x[5] * y[srcBLen - 4] */ + acc2 += x1 * c0; + /* acc3 += x[6] * y[srcBLen - 4] */ + acc3 += x2 * c0; + + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[srcBLen - 5] sample */ + c0 = *(py--); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[srcBLen - 5] */ + acc0 += x0 * c0; + /* acc1 += x[5] * y[srcBLen - 5] */ + acc1 += x1 * c0; + /* acc2 += x[6] * y[srcBLen - 5] */ + acc2 += x2 * c0; + /* acc3 += x[7] * y[srcBLen - 5] */ + acc3 += x3 * c0; + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = acc0; + *pOut++ = acc1; + *pOut++ = acc2; + *pOut++ = acc3; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = (uint32_t) blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += *px++ * *py--; + sum += *px++ * *py--; + sum += *px++ * *py--; + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = (uint32_t) blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + while(blockSize3 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ + sum += *px++ * *py--; + + /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ + sum += *px++ * *py--; + + /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ + sum += *px++ * *py--; + + /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen-1] * y[srcBLen-1] */ + sum += *px++ * *py--; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + + } + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); + +#else + + /* Run the below code for Cortex-M0 */ + + float32_t *pIn1 = pSrcA; /* inputA pointer */ + float32_t *pIn2 = pSrcB; /* inputB pointer */ + float32_t sum; /* Accumulator */ + uint32_t i, j; /* loop counters */ + arm_status status; /* status of Partial convolution */ + + /* Check for range of output samples to be calculated */ + if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) + { + /* Set status as ARM_ARGUMENT_ERROR */ + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + /* Loop to calculate convolution for output length number of values */ + for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0.0f; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0u; j <= i; j++) + { + /* Check the array limitations for inputs */ + if((((i - j) < srcBLen) && (j < srcALen))) + { + /* z[i] += x[i-j] * y[j] */ + sum += pIn1[j] * pIn2[i - j]; + } + } + /* Store the output in the destination buffer */ + pDst[i] = sum; + } + /* set status as ARM_SUCCESS as there are no argument errors */ + status = ARM_MATH_SUCCESS; + } + return (status); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of PartialConv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q15.c index af219a8ac..dcb4ed7b5 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q15.c @@ -1,705 +1,705 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_fast_q15.c -* -* Description: Fast Q15 Partial convolution. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * See arm_conv_partial_q15() for a slower implementation of this function which uses a 64-bit accumulator to avoid wrap around distortion. - */ - - -arm_status arm_conv_partial_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counters */ - arm_status status; /* status of Partial convolution */ - q31_t *pb; /* 32 bit pointer for inputB buffer */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations less than 4 */ - /* Second part of this stage computes the MAC operations greater than or equal to 4 */ - - /* The first part of the stage starts here */ - while((count < 4u) && (blockSize1 > 0)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over number of MAC operations between - * inputA samples and inputB samples */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* The second part of the stage starts here */ - /* The internal loop, over count, is unrolled by 4 */ - /* To, read the last two inputB samples using SIMD: - * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ - py = py - 1; - - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2 - 1u; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* Initialize inputB pointer of type q31 */ - pb = (q31_t *) (py - 1u); - - /* count is the index by which the pointer pIn1 to be incremented */ - count = 1u; - - - /* -------------------- - * Stage2 process - * -------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - - /* read x[0], x[1] samples */ - x0 = *(q31_t *) (px++); - /* read x[1], x[2] samples */ - x1 = *(q31_t *) (px++); - - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the last two inputB samples using SIMD: - * y[srcBLen - 1] and y[srcBLen - 2] */ - c0 = *(pb--); - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLADX(x0, c0, acc0); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLADX(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *(q31_t *) (px++); - - /* Read x[3], x[4] */ - x3 = *(q31_t *) (px++); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLADX(x2, c0, acc2); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLADX(x3, c0, acc3); - - /* Read y[srcBLen - 3] and y[srcBLen - 4] */ - c0 = *(pb--); - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLADX(x2, c0, acc0); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLADX(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = *(q31_t *) (px++); - - /* Read x[5], x[6] */ - x1 = *(q31_t *) (px++); - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLADX(x0, c0, acc2); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLADX(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - py = (q15_t *) pb; - py = py + 1; - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[srcBLen - 5] */ - c0 = *(py); -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLADX(x1, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = *(pb); - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = *pb--; - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - - /* Read y[srcBLen - 7] */ -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = (*pb); - c0 = (c0) << 16; - -#else - - c0 = (q15_t) (*pb >> 16); - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x1, c0, acc0); - acc1 = __SMLAD(x2, c0, acc1); - acc2 = __SMLADX(x2, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - /* Store the results in the accumulators in the destination buffer. */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = __PKHBT(acc0 >> 15, acc1 >> 15, 16); - *__SIMD32(pOut)++ = __PKHBT(acc2 >> 15, acc3 >> 15, 16); - -#else - - *__SIMD32(pOut)++ = __PKHBT(acc1 >> 15, acc0 >> 15, 16); - *__SIMD32(pOut)++ = __PKHBT(acc3 >> 15, acc2 >> 15, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - pb = (q31_t *) (py - 1); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - pIn2 = pSrc2 - 1u; - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations greater than 4 */ - /* Second part of this stage computes the MAC operations less than or equal to 4 */ - - /* The first part of the stage starts here */ - j = count >> 2u; - - while((j > 0u) && (blockSize3 > 0)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied - * with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied - * with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - j--; - } - - /* The second part of the stage starts here */ - /* SIMD is not used for the next MAC operations, - * so pointer py is updated to read only one sample at a time */ - py = py + 1u; - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -} - -/** - * @} end of PartialConv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_partial_fast_q15.c +* +* Description: Fast Q15 Partial convolution. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup PartialConv + * @{ + */ + +/** + * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + * + * See arm_conv_partial_q15() for a slower implementation of this function which uses a 64-bit accumulator to avoid wrap around distortion. + */ + + +arm_status arm_conv_partial_fast_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints) +{ + q15_t *pIn1; /* inputA pointer */ + q15_t *pIn2; /* inputB pointer */ + q15_t *pOut = pDst; /* output pointer */ + q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ + q15_t *px; /* Intermediate inputA pointer */ + q15_t *py; /* Intermediate inputB pointer */ + q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ + q31_t x0, x1, x2, x3, c0; + uint32_t j, k, count, check, blkCnt; + int32_t blockSize1, blockSize2, blockSize3; /* loop counters */ + arm_status status; /* status of Partial convolution */ + q31_t *pb; /* 32 bit pointer for inputB buffer */ + + /* Check for range of output samples to be calculated */ + if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) + { + /* Set status as ARM_MATH_ARGUMENT_ERROR */ + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* Conditions to check which loopCounter holds + * the first and last indices of the output samples to be calculated. */ + check = firstIndex + numPoints; + blockSize3 = ((int32_t) check - (int32_t) srcALen); + blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; + blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); + blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : + (int32_t) numPoints) : 0; + blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + + (int32_t) firstIndex); + blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* Set the output pointer to point to the firstIndex + * of the output sample to be calculated. */ + pOut = pDst + firstIndex; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed. + Since the partial convolution starts from firstIndex + Number of Macs to be performed is firstIndex + 1 */ + count = 1u + firstIndex; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + firstIndex; + py = pSrc2; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* For loop unrolling by 4, this stage is divided into two. */ + /* First part of this stage computes the MAC operations less than 4 */ + /* Second part of this stage computes the MAC operations greater than or equal to 4 */ + + /* The first part of the stage starts here */ + while((count < 4u) && (blockSize1 > 0)) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Loop over number of MAC operations between + * inputA samples and inputB samples */ + k = count; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = __SMLAD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = ++pSrc2; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* The second part of the stage starts here */ + /* The internal loop, over count, is unrolled by 4 */ + /* To, read the last two inputB samples using SIMD: + * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ + py = py - 1; + + while(blockSize1 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ + sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ + sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* For the next MAC operations, the pointer py is used without SIMD + * So, py is incremented by 1 */ + py = py + 1u; + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = __SMLAD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = ++pSrc2 - 1u; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* Initialize inputB pointer of type q31 */ + pb = (q31_t *) (py - 1u); + + /* count is the index by which the pointer pIn1 to be incremented */ + count = 1u; + + + /* -------------------- + * Stage2 process + * -------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = ((uint32_t) blockSize2 >> 2u); + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + + /* read x[0], x[1] samples */ + x0 = *(q31_t *) (px++); + /* read x[1], x[2] samples */ + x1 = *(q31_t *) (px++); + + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read the last two inputB samples using SIMD: + * y[srcBLen - 1] and y[srcBLen - 2] */ + c0 = *(pb--); + + /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ + acc0 = __SMLADX(x0, c0, acc0); + + /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ + acc1 = __SMLADX(x1, c0, acc1); + + /* Read x[2], x[3] */ + x2 = *(q31_t *) (px++); + + /* Read x[3], x[4] */ + x3 = *(q31_t *) (px++); + + /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ + acc2 = __SMLADX(x2, c0, acc2); + + /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ + acc3 = __SMLADX(x3, c0, acc3); + + /* Read y[srcBLen - 3] and y[srcBLen - 4] */ + c0 = *(pb--); + + /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ + acc0 = __SMLADX(x2, c0, acc0); + + /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ + acc1 = __SMLADX(x3, c0, acc1); + + /* Read x[4], x[5] */ + x0 = *(q31_t *) (px++); + + /* Read x[5], x[6] */ + x1 = *(q31_t *) (px++); + + /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ + acc2 = __SMLADX(x0, c0, acc2); + + /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ + acc3 = __SMLADX(x1, c0, acc3); + + } while(--k); + + /* For the next MAC operations, SIMD is not used + * So, the 16 bit pointer if inputB, py is updated */ + py = (q15_t *) pb; + py = py + 1; + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + if(k == 1u) + { + /* Read y[srcBLen - 5] */ + c0 = *(py); +#ifdef ARM_MATH_BIG_ENDIAN + + c0 = c0 << 16; + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + + /* Read x[7] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLAD(x0, c0, acc0); + acc1 = __SMLAD(x1, c0, acc1); + acc2 = __SMLADX(x1, c0, acc2); + acc3 = __SMLADX(x3, c0, acc3); + } + + if(k == 2u) + { + /* Read y[srcBLen - 5], y[srcBLen - 6] */ + c0 = *(pb); + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLADX(x0, c0, acc0); + acc1 = __SMLADX(x1, c0, acc1); + acc2 = __SMLADX(x3, c0, acc2); + acc3 = __SMLADX(x2, c0, acc3); + } + + if(k == 3u) + { + /* Read y[srcBLen - 5], y[srcBLen - 6] */ + c0 = *pb--; + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLADX(x0, c0, acc0); + acc1 = __SMLADX(x1, c0, acc1); + acc2 = __SMLADX(x3, c0, acc2); + acc3 = __SMLADX(x2, c0, acc3); + + /* Read y[srcBLen - 7] */ +#ifdef ARM_MATH_BIG_ENDIAN + + c0 = (*pb); + c0 = (c0) << 16; + +#else + + c0 = (q15_t) (*pb >> 16); + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + + /* Read x[10] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLADX(x1, c0, acc0); + acc1 = __SMLAD(x2, c0, acc1); + acc2 = __SMLADX(x2, c0, acc2); + acc3 = __SMLADX(x3, c0, acc3); + } + + /* Store the results in the accumulators in the destination buffer. */ +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pOut)++ = __PKHBT(acc0 >> 15, acc1 >> 15, 16); + *__SIMD32(pOut)++ = __PKHBT(acc2 >> 15, acc3 >> 15, 16); + +#else + + *__SIMD32(pOut)++ = __PKHBT(acc1 >> 15, acc0 >> 15, 16); + *__SIMD32(pOut)++ = __PKHBT(acc3 >> 15, acc2 >> 15, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + pb = (q31_t *) (py - 1); + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = (uint32_t) blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q31_t) * px++ * *py--); + sum += ((q31_t) * px++ * *py--); + sum += ((q31_t) * px++ * *py--); + sum += ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = (uint32_t) blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + pIn2 = pSrc2 - 1u; + py = pIn2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + /* For loop unrolling by 4, this stage is divided into two. */ + /* First part of this stage computes the MAC operations greater than 4 */ + /* Second part of this stage computes the MAC operations less than or equal to 4 */ + + /* The first part of the stage starts here */ + j = count >> 2u; + + while((j > 0u) && (blockSize3 > 0)) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied + * with y[srcBLen - 1], y[srcBLen - 2] respectively */ + sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied + * with y[srcBLen - 3], y[srcBLen - 4] respectively */ + sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* For the next MAC operations, the pointer py is used without SIMD + * So, py is incremented by 1 */ + py = py + 1u; + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ + sum = __SMLAD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pIn2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + + j--; + } + + /* The second part of the stage starts here */ + /* SIMD is not used for the next MAC operations, + * so pointer py is updated to read only one sample at a time */ + py = py + 1u; + + while(blockSize3 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen-1] * y[srcBLen-1] */ + sum = __SMLAD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (sum >> 15); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + } + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); + +} + +/** + * @} end of PartialConv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q31.c index 4003e3af0..0b848053d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q31.c @@ -1,593 +1,593 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_fast_q31.c -* -* Description: Fast Q31 Partial convolution. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * \par - * See arm_conv_partial_q31() for a slower implementation of this function which uses a 64-bit accumulator to provide higher precision. - */ - -arm_status arm_conv_partial_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q31_t x0, x1, x2, x3, c0; - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first loop starts here */ - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[1] * y[srcBLen - 2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[2] * y[srcBLen - 3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[3] * y[srcBLen - 4] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - - /* acc3 += x[3] * y[srcBLen - 1] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Read y[srcBLen - 2] sample */ - c0 = *(py--); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc3 += x[4] * y[srcBLen - 2] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc3 += x[5] * y[srcBLen - 2] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Read y[srcBLen - 4] sample */ - c0 = *(py--); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[srcBLen - 4] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc1 += x[4] * y[srcBLen - 4] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc2 += x[5] * y[srcBLen - 4] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc3 += x[6] * y[srcBLen - 4] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x2 * c0)) >> 32); - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (acc0 << 1); - *pOut++ = (q31_t) (acc1 << 1); - *pOut++ = (q31_t) (acc2 << 1); - *pOut++ = (q31_t) (acc3 << 1); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -} - -/** - * @} end of PartialConv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_partial_fast_q31.c +* +* Description: Fast Q31 Partial convolution. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup PartialConv + * @{ + */ + +/** + * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + * + * \par + * See arm_conv_partial_q31() for a slower implementation of this function which uses a 64-bit accumulator to provide higher precision. + */ + +arm_status arm_conv_partial_fast_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst, + uint32_t firstIndex, + uint32_t numPoints) +{ + q31_t *pIn1; /* inputA pointer */ + q31_t *pIn2; /* inputB pointer */ + q31_t *pOut = pDst; /* output pointer */ + q31_t *px; /* Intermediate inputA pointer */ + q31_t *py; /* Intermediate inputB pointer */ + q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ + q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ + q31_t x0, x1, x2, x3, c0; + uint32_t j, k, count, check, blkCnt; + int32_t blockSize1, blockSize2, blockSize3; /* loop counters */ + arm_status status; /* status of Partial convolution */ + + + /* Check for range of output samples to be calculated */ + if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) + { + /* Set status as ARM_MATH_ARGUMENT_ERROR */ + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* Conditions to check which loopCounter holds + * the first and last indices of the output samples to be calculated. */ + check = firstIndex + numPoints; + blockSize3 = ((int32_t) check - (int32_t) srcALen); + blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; + blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); + blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : + (int32_t) numPoints) : 0; + blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + + (int32_t) firstIndex); + blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* Set the output pointer to point to the firstIndex + * of the output sample to be calculated. */ + pOut = pDst + firstIndex; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed. + Since the partial convolution starts from firstIndex + Number of Macs to be performed is firstIndex + 1 */ + count = 1u + firstIndex; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + firstIndex; + py = pSrc2; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first loop starts here */ + while(blockSize1 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 1] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* x[1] * y[srcBLen - 2] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* x[2] * y[srcBLen - 3] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* x[3] * y[srcBLen - 4] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum << 1; + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = ++pSrc2; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2 */ + blkCnt = ((uint32_t) blockSize2 >> 2u); + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[srcBLen - 1] sample */ + c0 = *(py--); + + /* Read x[3] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[0] * y[srcBLen - 1] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); + + /* acc1 += x[1] * y[srcBLen - 1] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); + + /* acc2 += x[2] * y[srcBLen - 1] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); + + /* acc3 += x[3] * y[srcBLen - 1] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); + + /* Read y[srcBLen - 2] sample */ + c0 = *(py--); + + /* Read x[4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[1] * y[srcBLen - 2] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x1 * c0)) >> 32); + /* acc1 += x[2] * y[srcBLen - 2] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x2 * c0)) >> 32); + /* acc2 += x[3] * y[srcBLen - 2] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x3 * c0)) >> 32); + /* acc3 += x[4] * y[srcBLen - 2] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x0 * c0)) >> 32); + + /* Read y[srcBLen - 3] sample */ + c0 = *(py--); + + /* Read x[5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[2] * y[srcBLen - 3] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x2 * c0)) >> 32); + /* acc1 += x[3] * y[srcBLen - 2] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x3 * c0)) >> 32); + /* acc2 += x[4] * y[srcBLen - 2] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x0 * c0)) >> 32); + /* acc3 += x[5] * y[srcBLen - 2] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x1 * c0)) >> 32); + + /* Read y[srcBLen - 4] sample */ + c0 = *(py--); + + /* Read x[6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[3] * y[srcBLen - 4] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x3 * c0)) >> 32); + /* acc1 += x[4] * y[srcBLen - 4] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x0 * c0)) >> 32); + /* acc2 += x[5] * y[srcBLen - 4] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x1 * c0)) >> 32); + /* acc3 += x[6] * y[srcBLen - 4] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x2 * c0)) >> 32); + + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[srcBLen - 5] sample */ + c0 = *(py--); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[srcBLen - 5] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); + /* acc1 += x[5] * y[srcBLen - 5] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); + /* acc2 += x[6] * y[srcBLen - 5] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); + /* acc3 += x[7] * y[srcBLen - 5] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q31_t) (acc0 << 1); + *pOut++ = (q31_t) (acc1 << 1); + *pOut++ = (q31_t) (acc2 << 1); + *pOut++ = (q31_t) (acc3 << 1); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = (uint32_t) blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum << 1; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = (uint32_t) blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum << 1; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen-1] * y[srcBLen-1] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py--))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = sum << 1; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + + } + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); + +} + +/** + * @} end of PartialConv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q15.c index de8d5065c..4a74726db 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q15.c @@ -1,765 +1,765 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_q15.c -* -* Description: Partial convolution of Q15 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * Refer to arm_conv_partial_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - */ - - -arm_status arm_conv_partial_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q63_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* Temporary input variables */ - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counter */ - arm_status status; /* status of Partial convolution */ - q31_t *pb; /* 32 bit pointer for inputB buffer */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations less than 4 */ - /* Second part of this stage computes the MAC operations greater than or equal to 4 */ - - /* The first part of the stage starts here */ - while((count < 4u) && (blockSize1 > 0)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over number of MAC operations between - * inputA samples and inputB samples */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* The second part of the stage starts here */ - /* The internal loop, over count, is unrolled by 4 */ - /* To, read the last two inputB samples using SIMD: - * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ - py = py - 1; - - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2 - 1u; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* Initialize inputB pointer of type q31 */ - pb = (q31_t *) (py - 1u); - - /* count is the index by which the pointer pIn1 to be incremented */ - count = 1u; - - - /* -------------------- - * Stage2 process - * -------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - - /* read x[0], x[1] samples */ - x0 = *(q31_t *) (px++); - /* read x[1], x[2] samples */ - x1 = *(q31_t *) (px++); - - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the last two inputB samples using SIMD: - * y[srcBLen - 1] and y[srcBLen - 2] */ - c0 = *(pb--); - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLALDX(x0, c0, acc0); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLALDX(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *(q31_t *) (px++); - - /* Read x[3], x[4] */ - x3 = *(q31_t *) (px++); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLALDX(x2, c0, acc2); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLALDX(x3, c0, acc3); - - /* Read y[srcBLen - 3] and y[srcBLen - 4] */ - c0 = *(pb--); - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLALDX(x2, c0, acc0); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLALDX(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = *(q31_t *) (px++); - - /* Read x[5], x[6] */ - x1 = *(q31_t *) (px++); - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLALDX(x0, c0, acc2); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLALDX(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - py = (q15_t *) pb; - py = py + 1; - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[srcBLen - 5] */ - c0 = *(py); - -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - /* Read x[7] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALDX(x1, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = *(pb); - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x0, c0, acc0); - acc1 = __SMLALDX(x1, c0, acc1); - acc2 = __SMLALDX(x3, c0, acc2); - acc3 = __SMLALDX(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = *pb--; - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x0, c0, acc0); - acc1 = __SMLALDX(x1, c0, acc1); - acc2 = __SMLALDX(x3, c0, acc2); - acc3 = __SMLALDX(x2, c0, acc3); - -#ifdef ARM_MATH_BIG_ENDIAN - - /* Read y[srcBLen - 7] */ - c0 = (*pb); - c0 = (c0) << 16; - -#else - - /* Read y[srcBLen - 7] */ - c0 = (q15_t) (*pb >> 16); - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x1, c0, acc0); - acc1 = __SMLALD(x2, c0, acc1); - acc2 = __SMLALDX(x2, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - /* Store the results in the accumulators in the destination buffer. */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - pb = (q31_t *) (py - 1); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - pIn2 = pSrc2 - 1u; - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations greater than 4 */ - /* Second part of this stage computes the MAC operations less than or equal to 4 */ - - /* The first part of the stage starts here */ - j = count >> 2u; - - while((j > 0u) && (blockSize3 > 0)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied - * with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied - * with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - j--; - } - - /* The second part of the stage starts here */ - /* SIMD is not used for the next MAC operations, - * so pointer py is updated to read only one sample at a time */ - py = py + 1u; - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t *pIn1 = pSrcA; /* inputA pointer */ - q15_t *pIn2 = pSrcB; /* inputB pointer */ - q63_t sum; /* Accumulator */ - uint32_t i, j; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - /* Loop to calculate convolution for output length number of values */ - for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q31_t) pIn1[j] * (pIn2[i - j])); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q15_t) __SSAT((sum >> 15u), 16u); - } - /* set status as ARM_SUCCESS as there are no argument errors */ - status = ARM_MATH_SUCCESS; - } - return (status); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of PartialConv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_partial_q15.c +* +* Description: Partial convolution of Q15 sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup PartialConv + * @{ + */ + +/** + * @brief Partial convolution of Q15 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + * + * Refer to arm_conv_partial_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. + */ + + +arm_status arm_conv_partial_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst, + uint32_t firstIndex, + uint32_t numPoints) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t *pIn1; /* inputA pointer */ + q15_t *pIn2; /* inputB pointer */ + q15_t *pOut = pDst; /* output pointer */ + q63_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ + q15_t *px; /* Intermediate inputA pointer */ + q15_t *py; /* Intermediate inputB pointer */ + q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ + q31_t x0, x1, x2, x3, c0; /* Temporary input variables */ + uint32_t j, k, count, check, blkCnt; + int32_t blockSize1, blockSize2, blockSize3; /* loop counter */ + arm_status status; /* status of Partial convolution */ + q31_t *pb; /* 32 bit pointer for inputB buffer */ + + /* Check for range of output samples to be calculated */ + if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) + { + /* Set status as ARM_MATH_ARGUMENT_ERROR */ + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* Conditions to check which loopCounter holds + * the first and last indices of the output samples to be calculated. */ + check = firstIndex + numPoints; + blockSize3 = ((int32_t) check - (int32_t) srcALen); + blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; + blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); + blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : + (int32_t) numPoints) : 0; + blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + + (int32_t) firstIndex); + blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* Set the output pointer to point to the firstIndex + * of the output sample to be calculated. */ + pOut = pDst + firstIndex; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed. + Since the partial convolution starts from firstIndex + Number of Macs to be performed is firstIndex + 1 */ + count = 1u + firstIndex; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + firstIndex; + py = pSrc2; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* For loop unrolling by 4, this stage is divided into two. */ + /* First part of this stage computes the MAC operations less than 4 */ + /* Second part of this stage computes the MAC operations greater than or equal to 4 */ + + /* The first part of the stage starts here */ + while((count < 4u) && (blockSize1 > 0)) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Loop over number of MAC operations between + * inputA samples and inputB samples */ + k = count; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = __SMLALD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = ++pSrc2; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* The second part of the stage starts here */ + /* The internal loop, over count, is unrolled by 4 */ + /* To, read the last two inputB samples using SIMD: + * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ + py = py - 1; + + while(blockSize1 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ + sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ + sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* For the next MAC operations, the pointer py is used without SIMD + * So, py is incremented by 1 */ + py = py + 1u; + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = __SMLALD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = ++pSrc2 - 1u; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* Initialize inputB pointer of type q31 */ + pb = (q31_t *) (py - 1u); + + /* count is the index by which the pointer pIn1 to be incremented */ + count = 1u; + + + /* -------------------- + * Stage2 process + * -------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = ((uint32_t) blockSize2 >> 2u); + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + + /* read x[0], x[1] samples */ + x0 = *(q31_t *) (px++); + /* read x[1], x[2] samples */ + x1 = *(q31_t *) (px++); + + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read the last two inputB samples using SIMD: + * y[srcBLen - 1] and y[srcBLen - 2] */ + c0 = *(pb--); + + /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ + acc0 = __SMLALDX(x0, c0, acc0); + + /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ + acc1 = __SMLALDX(x1, c0, acc1); + + /* Read x[2], x[3] */ + x2 = *(q31_t *) (px++); + + /* Read x[3], x[4] */ + x3 = *(q31_t *) (px++); + + /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ + acc2 = __SMLALDX(x2, c0, acc2); + + /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ + acc3 = __SMLALDX(x3, c0, acc3); + + /* Read y[srcBLen - 3] and y[srcBLen - 4] */ + c0 = *(pb--); + + /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ + acc0 = __SMLALDX(x2, c0, acc0); + + /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ + acc1 = __SMLALDX(x3, c0, acc1); + + /* Read x[4], x[5] */ + x0 = *(q31_t *) (px++); + + /* Read x[5], x[6] */ + x1 = *(q31_t *) (px++); + + /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ + acc2 = __SMLALDX(x0, c0, acc2); + + /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ + acc3 = __SMLALDX(x1, c0, acc3); + + } while(--k); + + /* For the next MAC operations, SIMD is not used + * So, the 16 bit pointer if inputB, py is updated */ + py = (q15_t *) pb; + py = py + 1; + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + if(k == 1u) + { + /* Read y[srcBLen - 5] */ + c0 = *(py); + +#ifdef ARM_MATH_BIG_ENDIAN + + c0 = c0 << 16u; + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + /* Read x[7] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALD(x0, c0, acc0); + acc1 = __SMLALD(x1, c0, acc1); + acc2 = __SMLALDX(x1, c0, acc2); + acc3 = __SMLALDX(x3, c0, acc3); + } + + if(k == 2u) + { + /* Read y[srcBLen - 5], y[srcBLen - 6] */ + c0 = *(pb); + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALDX(x0, c0, acc0); + acc1 = __SMLALDX(x1, c0, acc1); + acc2 = __SMLALDX(x3, c0, acc2); + acc3 = __SMLALDX(x2, c0, acc3); + } + + if(k == 3u) + { + /* Read y[srcBLen - 5], y[srcBLen - 6] */ + c0 = *pb--; + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALDX(x0, c0, acc0); + acc1 = __SMLALDX(x1, c0, acc1); + acc2 = __SMLALDX(x3, c0, acc2); + acc3 = __SMLALDX(x2, c0, acc3); + +#ifdef ARM_MATH_BIG_ENDIAN + + /* Read y[srcBLen - 7] */ + c0 = (*pb); + c0 = (c0) << 16; + +#else + + /* Read y[srcBLen - 7] */ + c0 = (q15_t) (*pb >> 16); + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + + /* Read x[10] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALDX(x1, c0, acc0); + acc1 = __SMLALD(x2, c0, acc1); + acc2 = __SMLALDX(x2, c0, acc2); + acc3 = __SMLALDX(x3, c0, acc3); + } + + /* Store the results in the accumulators in the destination buffer. */ +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pOut)++ = + __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); + *__SIMD32(pOut)++ = + __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); + +#else + + *__SIMD32(pOut)++ = + __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); + *__SIMD32(pOut)++ = + __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + pb = (q31_t *) (py - 1); + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = (uint32_t) blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += (q63_t) ((q31_t) * px++ * *py--); + sum += (q63_t) ((q31_t) * px++ * *py--); + sum += (q63_t) ((q31_t) * px++ * *py--); + sum += (q63_t) ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += (q63_t) ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = (uint32_t) blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + pIn2 = pSrc2 - 1u; + py = pIn2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + /* For loop unrolling by 4, this stage is divided into two. */ + /* First part of this stage computes the MAC operations greater than 4 */ + /* Second part of this stage computes the MAC operations less than or equal to 4 */ + + /* The first part of the stage starts here */ + j = count >> 2u; + + while((j > 0u) && (blockSize3 > 0)) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied + * with y[srcBLen - 1], y[srcBLen - 2] respectively */ + sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied + * with y[srcBLen - 3], y[srcBLen - 4] respectively */ + sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* For the next MAC operations, the pointer py is used without SIMD + * So, py is incremented by 1 */ + py = py + 1u; + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ + sum = __SMLALD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pIn2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + + j--; + } + + /* The second part of the stage starts here */ + /* SIMD is not used for the next MAC operations, + * so pointer py is updated to read only one sample at a time */ + py = py + 1u; + + while(blockSize3 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen-1] * y[srcBLen-1] */ + sum = __SMLALD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + } + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); + +#else + + /* Run the below code for Cortex-M0 */ + + q15_t *pIn1 = pSrcA; /* inputA pointer */ + q15_t *pIn2 = pSrcB; /* inputB pointer */ + q63_t sum; /* Accumulator */ + uint32_t i, j; /* loop counters */ + arm_status status; /* status of Partial convolution */ + + /* Check for range of output samples to be calculated */ + if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) + { + /* Set status as ARM_ARGUMENT_ERROR */ + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + /* Loop to calculate convolution for output length number of values */ + for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0; j <= i; j++) + { + /* Check the array limitations */ + if(((i - j) < srcBLen) && (j < srcALen)) + { + /* z[i] += x[i-j] * y[j] */ + sum += ((q31_t) pIn1[j] * (pIn2[i - j])); + } + } + + /* Store the output in the destination buffer */ + pDst[i] = (q15_t) __SSAT((sum >> 15u), 16u); + } + /* set status as ARM_SUCCESS as there are no argument errors */ + status = ARM_MATH_SUCCESS; + } + return (status); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of PartialConv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q31.c index ab7a4cc01..a592d74d1 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q31.c @@ -1,616 +1,616 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_q31.c -* -* Description: Partial convolution of Q31 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q31 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * See arm_conv_partial_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -arm_status arm_conv_partial_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q63_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t x0, x1, x2, x3, c0; - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counter */ - arm_status status; /* status of Partial convolution */ - - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first loop starts here */ - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum += (q63_t) * px++ * (*py--); - /* x[1] * y[srcBLen - 2] */ - sum += (q63_t) * px++ * (*py--); - /* x[2] * y[srcBLen - 3] */ - sum += (q63_t) * px++ * (*py--); - /* x[3] * y[srcBLen - 4] */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 += (q63_t) x0 *c0; - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 += (q63_t) x1 *c0; - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 += (q63_t) x2 *c0; - /* acc3 += x[3] * y[srcBLen - 1] */ - acc3 += (q63_t) x3 *c0; - - /* Read y[srcBLen - 2] sample */ - c0 = *(py--); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 += (q63_t) x1 *c0; - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 += (q63_t) x2 *c0; - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 += (q63_t) x3 *c0; - /* acc3 += x[4] * y[srcBLen - 2] */ - acc3 += (q63_t) x0 *c0; - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 += (q63_t) x2 *c0; - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 += (q63_t) x3 *c0; - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 += (q63_t) x0 *c0; - /* acc3 += x[5] * y[srcBLen - 2] */ - acc3 += (q63_t) x1 *c0; - - /* Read y[srcBLen - 4] sample */ - c0 = *(py--); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[srcBLen - 4] */ - acc0 += (q63_t) x3 *c0; - /* acc1 += x[4] * y[srcBLen - 4] */ - acc1 += (q63_t) x0 *c0; - /* acc2 += x[5] * y[srcBLen - 4] */ - acc2 += (q63_t) x1 *c0; - /* acc3 += x[6] * y[srcBLen - 4] */ - acc3 += (q63_t) x2 *c0; - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += (q63_t) x0 *c0; - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += (q63_t) x1 *c0; - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += (q63_t) x2 *c0; - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 += (q63_t) x3 *c0; - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (acc0 >> 31); - *pOut++ = (q31_t) (acc1 >> 31); - *pOut++ = (q31_t) (acc2 >> 31); - *pOut++ = (q31_t) (acc3 >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t *pIn1 = pSrcA; /* inputA pointer */ - q31_t *pIn2 = pSrcB; /* inputB pointer */ - q63_t sum; /* Accumulator */ - uint32_t i, j; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - /* Loop to calculate convolution for output length number of values */ - for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q63_t) pIn1[j] * (pIn2[i - j])); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q31_t) (sum >> 31u); - } - /* set status as ARM_SUCCESS as there are no argument errors */ - status = ARM_MATH_SUCCESS; - } - return (status); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of PartialConv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_partial_q31.c +* +* Description: Partial convolution of Q31 sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup PartialConv + * @{ + */ + +/** + * @brief Partial convolution of Q31 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + * + * See arm_conv_partial_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. + */ + +arm_status arm_conv_partial_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst, + uint32_t firstIndex, + uint32_t numPoints) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t *pIn1; /* inputA pointer */ + q31_t *pIn2; /* inputB pointer */ + q31_t *pOut = pDst; /* output pointer */ + q31_t *px; /* Intermediate inputA pointer */ + q31_t *py; /* Intermediate inputB pointer */ + q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ + q63_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ + q31_t x0, x1, x2, x3, c0; + uint32_t j, k, count, check, blkCnt; + int32_t blockSize1, blockSize2, blockSize3; /* loop counter */ + arm_status status; /* status of Partial convolution */ + + + /* Check for range of output samples to be calculated */ + if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) + { + /* Set status as ARM_MATH_ARGUMENT_ERROR */ + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* Conditions to check which loopCounter holds + * the first and last indices of the output samples to be calculated. */ + check = firstIndex + numPoints; + blockSize3 = ((int32_t) check - (int32_t) srcALen); + blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; + blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); + blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : + (int32_t) numPoints) : 0; + blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + + (int32_t) firstIndex); + blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* Set the output pointer to point to the firstIndex + * of the output sample to be calculated. */ + pOut = pDst + firstIndex; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed. + Since the partial convolution starts from firstIndex + Number of Macs to be performed is firstIndex + 1 */ + count = 1u + firstIndex; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + firstIndex; + py = pSrc2; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first loop starts here */ + while(blockSize1 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 1] */ + sum += (q63_t) * px++ * (*py--); + /* x[1] * y[srcBLen - 2] */ + sum += (q63_t) * px++ * (*py--); + /* x[2] * y[srcBLen - 3] */ + sum += (q63_t) * px++ * (*py--); + /* x[3] * y[srcBLen - 4] */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q31_t) (sum >> 31); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = ++pSrc2; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2 */ + blkCnt = ((uint32_t) blockSize2 >> 2u); + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[srcBLen - 1] sample */ + c0 = *(py--); + + /* Read x[3] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[0] * y[srcBLen - 1] */ + acc0 += (q63_t) x0 *c0; + /* acc1 += x[1] * y[srcBLen - 1] */ + acc1 += (q63_t) x1 *c0; + /* acc2 += x[2] * y[srcBLen - 1] */ + acc2 += (q63_t) x2 *c0; + /* acc3 += x[3] * y[srcBLen - 1] */ + acc3 += (q63_t) x3 *c0; + + /* Read y[srcBLen - 2] sample */ + c0 = *(py--); + + /* Read x[4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[1] * y[srcBLen - 2] */ + acc0 += (q63_t) x1 *c0; + /* acc1 += x[2] * y[srcBLen - 2] */ + acc1 += (q63_t) x2 *c0; + /* acc2 += x[3] * y[srcBLen - 2] */ + acc2 += (q63_t) x3 *c0; + /* acc3 += x[4] * y[srcBLen - 2] */ + acc3 += (q63_t) x0 *c0; + + /* Read y[srcBLen - 3] sample */ + c0 = *(py--); + + /* Read x[5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[2] * y[srcBLen - 3] */ + acc0 += (q63_t) x2 *c0; + /* acc1 += x[3] * y[srcBLen - 2] */ + acc1 += (q63_t) x3 *c0; + /* acc2 += x[4] * y[srcBLen - 2] */ + acc2 += (q63_t) x0 *c0; + /* acc3 += x[5] * y[srcBLen - 2] */ + acc3 += (q63_t) x1 *c0; + + /* Read y[srcBLen - 4] sample */ + c0 = *(py--); + + /* Read x[6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[3] * y[srcBLen - 4] */ + acc0 += (q63_t) x3 *c0; + /* acc1 += x[4] * y[srcBLen - 4] */ + acc1 += (q63_t) x0 *c0; + /* acc2 += x[5] * y[srcBLen - 4] */ + acc2 += (q63_t) x1 *c0; + /* acc3 += x[6] * y[srcBLen - 4] */ + acc3 += (q63_t) x2 *c0; + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[srcBLen - 5] sample */ + c0 = *(py--); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[srcBLen - 5] */ + acc0 += (q63_t) x0 *c0; + /* acc1 += x[5] * y[srcBLen - 5] */ + acc1 += (q63_t) x1 *c0; + /* acc2 += x[6] * y[srcBLen - 5] */ + acc2 += (q63_t) x2 *c0; + /* acc3 += x[7] * y[srcBLen - 5] */ + acc3 += (q63_t) x3 *c0; + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q31_t) (acc0 >> 31); + *pOut++ = (q31_t) (acc1 >> 31); + *pOut++ = (q31_t) (acc2 >> 31); + *pOut++ = (q31_t) (acc3 >> 31); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = (uint32_t) blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += (q63_t) * px++ * (*py--); + sum += (q63_t) * px++ * (*py--); + sum += (q63_t) * px++ * (*py--); + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q31_t) (sum >> 31); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = (uint32_t) blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q31_t) (sum >> 31); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The blockSize3 variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + sum += (q63_t) * px++ * (*py--); + sum += (q63_t) * px++ * (*py--); + sum += (q63_t) * px++ * (*py--); + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q31_t) (sum >> 31); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + + } + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); + +#else + + /* Run the below code for Cortex-M0 */ + + q31_t *pIn1 = pSrcA; /* inputA pointer */ + q31_t *pIn2 = pSrcB; /* inputB pointer */ + q63_t sum; /* Accumulator */ + uint32_t i, j; /* loop counters */ + arm_status status; /* status of Partial convolution */ + + /* Check for range of output samples to be calculated */ + if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) + { + /* Set status as ARM_ARGUMENT_ERROR */ + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + /* Loop to calculate convolution for output length number of values */ + for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0; j <= i; j++) + { + /* Check the array limitations */ + if(((i - j) < srcBLen) && (j < srcALen)) + { + /* z[i] += x[i-j] * y[j] */ + sum += ((q63_t) pIn1[j] * (pIn2[i - j])); + } + } + + /* Store the output in the destination buffer */ + pDst[i] = (q31_t) (sum >> 31u); + } + /* set status as ARM_SUCCESS as there are no argument errors */ + status = ARM_MATH_SUCCESS; + } + return (status); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of PartialConv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q7.c index a6a0d5a00..d49903fa5 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q7.c @@ -1,723 +1,723 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_q7.c -* -* Description: Partial convolution of Q7 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - */ - -arm_status arm_conv_partial_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t *pIn1; /* inputA pointer */ - q7_t *pIn2; /* inputB pointer */ - q7_t *pOut = pDst; /* output pointer */ - q7_t *px; /* Intermediate inputA pointer */ - q7_t *py; /* Intermediate inputB pointer */ - q7_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t input1, input2; - q15_t in1, in2; - q7_t x0, x1, x2, x3, c0, c1; - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counter */ - arm_status status; - - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] , x[1] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 1] , y[srcBLen - 2] */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* x[0] * y[srcBLen - 1] */ - /* x[1] * y[srcBLen - 2] */ - sum = __SMLAD(input1, input2, sum); - - /* x[2] , x[3] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 3] , y[srcBLen - 4] */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* x[2] * y[srcBLen - 3] */ - /* x[3] * y[srcBLen - 4] */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - /* Read y[srcBLen - 2] sample */ - c1 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* x[0] and x[1] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 1] and y[srcBLen - 2] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[1] and x[2] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[4] sample */ - x0 = *(px++); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLAD(input1, input2, acc3); - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - /* Read y[srcBLen - 4] sample */ - c1 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 3] and y[srcBLen - 4] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[4] and x[5] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[6] sample */ - x2 = *(px++); - - /* x[5] and x[6] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLAD(input1, input2, acc3); - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += ((q31_t) x0 * c0); - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += ((q31_t) x1 * c0); - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += ((q31_t) x2 * c0); - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 += ((q31_t) x3 * c0); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(acc0 >> 7, 8)); - *pOut++ = (q7_t) (__SSAT(acc1 >> 7, 8)); - *pOut++ = (q7_t) (__SSAT(acc2 >> 7, 8)); - *pOut++ = (q7_t) (__SSAT(acc3 >> 7, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count * 4u; - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Reading two inputs, x[srcALen - srcBLen + 1] and x[srcALen - srcBLen + 2] of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs, y[srcBLen - 1] and y[srcBLen - 2] of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs, x[srcALen - srcBLen + 3] and x[srcALen - srcBLen + 4] of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs, y[srcBLen - 3] and y[srcBLen - 4] of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -#else - - /* Run the below code for Cortex-M0 */ - - q7_t *pIn1 = pSrcA; /* inputA pointer */ - q7_t *pIn2 = pSrcB; /* inputB pointer */ - q31_t sum; /* Accumulator */ - uint32_t i, j; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - /* Loop to calculate convolution for output length number of values */ - for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q15_t) pIn1[j] * (pIn2[i - j])); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q7_t) __SSAT((sum >> 7u), 8u); - } - /* set status as ARM_SUCCESS as there are no argument errors */ - status = ARM_MATH_SUCCESS; - } - return (status); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of PartialConv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_partial_q7.c +* +* Description: Partial convolution of Q7 sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup PartialConv + * @{ + */ + +/** + * @brief Partial convolution of Q7 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + * + */ + +arm_status arm_conv_partial_q7( + q7_t * pSrcA, + uint32_t srcALen, + q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst, + uint32_t firstIndex, + uint32_t numPoints) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q7_t *pIn1; /* inputA pointer */ + q7_t *pIn2; /* inputB pointer */ + q7_t *pOut = pDst; /* output pointer */ + q7_t *px; /* Intermediate inputA pointer */ + q7_t *py; /* Intermediate inputB pointer */ + q7_t *pSrc1, *pSrc2; /* Intermediate pointers */ + q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ + q31_t input1, input2; + q15_t in1, in2; + q7_t x0, x1, x2, x3, c0, c1; + uint32_t j, k, count, check, blkCnt; + int32_t blockSize1, blockSize2, blockSize3; /* loop counter */ + arm_status status; + + + /* Check for range of output samples to be calculated */ + if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) + { + /* Set status as ARM_MATH_ARGUMENT_ERROR */ + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* Conditions to check which loopCounter holds + * the first and last indices of the output samples to be calculated. */ + check = firstIndex + numPoints; + blockSize3 = ((int32_t) check - (int32_t) srcALen); + blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; + blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); + blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : + (int32_t) numPoints) : 0; + blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + + (int32_t) firstIndex); + blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* Set the output pointer to point to the firstIndex + * of the output sample to be calculated. */ + pOut = pDst + firstIndex; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed. + Since the partial convolution starts from from firstIndex + Number of Macs to be performed is firstIndex + 1 */ + count = 1u + firstIndex; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + firstIndex; + py = pSrc2; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first stage starts here */ + while(blockSize1 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] , x[1] */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* y[srcBLen - 1] , y[srcBLen - 2] */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* x[0] * y[srcBLen - 1] */ + /* x[1] * y[srcBLen - 2] */ + sum = __SMLAD(input1, input2, sum); + + /* x[2] , x[3] */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* y[srcBLen - 3] , y[srcBLen - 4] */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* x[2] * y[srcBLen - 3] */ + /* x[3] * y[srcBLen - 4] */ + sum = __SMLAD(input1, input2, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = ++pSrc2; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = ((uint32_t) blockSize2 >> 2u); + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[srcBLen - 1] sample */ + c0 = *(py--); + /* Read y[srcBLen - 2] sample */ + c1 = *(py--); + + /* Read x[3] sample */ + x3 = *(px++); + + /* x[0] and x[1] are packed */ + in1 = (q15_t) x0; + in2 = (q15_t) x1; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* y[srcBLen - 1] and y[srcBLen - 2] are packed */ + in1 = (q15_t) c0; + in2 = (q15_t) c1; + + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ + acc0 = __SMLAD(input1, input2, acc0); + + /* x[1] and x[2] are packed */ + in1 = (q15_t) x1; + in2 = (q15_t) x2; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ + acc1 = __SMLAD(input1, input2, acc1); + + /* x[2] and x[3] are packed */ + in1 = (q15_t) x2; + in2 = (q15_t) x3; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ + acc2 = __SMLAD(input1, input2, acc2); + + /* Read x[4] sample */ + x0 = *(px++); + + /* x[3] and x[4] are packed */ + in1 = (q15_t) x3; + in2 = (q15_t) x0; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ + acc3 = __SMLAD(input1, input2, acc3); + + /* Read y[srcBLen - 3] sample */ + c0 = *(py--); + /* Read y[srcBLen - 4] sample */ + c1 = *(py--); + + /* Read x[5] sample */ + x1 = *(px++); + + /* x[2] and x[3] are packed */ + in1 = (q15_t) x2; + in2 = (q15_t) x3; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* y[srcBLen - 3] and y[srcBLen - 4] are packed */ + in1 = (q15_t) c0; + in2 = (q15_t) c1; + + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ + acc0 = __SMLAD(input1, input2, acc0); + + /* x[3] and x[4] are packed */ + in1 = (q15_t) x3; + in2 = (q15_t) x0; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ + acc1 = __SMLAD(input1, input2, acc1); + + /* x[4] and x[5] are packed */ + in1 = (q15_t) x0; + in2 = (q15_t) x1; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ + acc2 = __SMLAD(input1, input2, acc2); + + /* Read x[6] sample */ + x2 = *(px++); + + /* x[5] and x[6] are packed */ + in1 = (q15_t) x1; + in2 = (q15_t) x2; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ + acc3 = __SMLAD(input1, input2, acc3); + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[srcBLen - 5] sample */ + c0 = *(py--); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[srcBLen - 5] */ + acc0 += ((q31_t) x0 * c0); + /* acc1 += x[5] * y[srcBLen - 5] */ + acc1 += ((q31_t) x1 * c0); + /* acc2 += x[6] * y[srcBLen - 5] */ + acc2 += ((q31_t) x2 * c0); + /* acc3 += x[7] * y[srcBLen - 5] */ + acc3 += ((q31_t) x3 * c0); + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q7_t) (__SSAT(acc0 >> 7, 8)); + *pOut++ = (q7_t) (__SSAT(acc1 >> 7, 8)); + *pOut++ = (q7_t) (__SSAT(acc2 >> 7, 8)); + *pOut++ = (q7_t) (__SSAT(acc3 >> 7, 8)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count * 4u; + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = (uint32_t) blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + + /* Reading two inputs of SrcA buffer and packing */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Reading two inputs of SrcB buffer and packing */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Perform the multiply-accumulates */ + sum = __SMLAD(input1, input2, sum); + + /* Reading two inputs of SrcA buffer and packing */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Reading two inputs of SrcB buffer and packing */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Perform the multiply-accumulates */ + sum = __SMLAD(input1, input2, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = (uint32_t) blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Reading two inputs, x[srcALen - srcBLen + 1] and x[srcALen - srcBLen + 2] of SrcA buffer and packing */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Reading two inputs, y[srcBLen - 1] and y[srcBLen - 2] of SrcB buffer and packing */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ + /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ + sum = __SMLAD(input1, input2, sum); + + /* Reading two inputs, x[srcALen - srcBLen + 3] and x[srcALen - srcBLen + 4] of SrcA buffer and packing */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Reading two inputs, y[srcBLen - 3] and y[srcBLen - 4] of SrcB buffer and packing */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ + /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ + sum = __SMLAD(input1, input2, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen-1] * y[srcBLen-1] */ + sum += ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + + } + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); + +#else + + /* Run the below code for Cortex-M0 */ + + q7_t *pIn1 = pSrcA; /* inputA pointer */ + q7_t *pIn2 = pSrcB; /* inputB pointer */ + q31_t sum; /* Accumulator */ + uint32_t i, j; /* loop counters */ + arm_status status; /* status of Partial convolution */ + + /* Check for range of output samples to be calculated */ + if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) + { + /* Set status as ARM_ARGUMENT_ERROR */ + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + /* Loop to calculate convolution for output length number of values */ + for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0; j <= i; j++) + { + /* Check the array limitations */ + if(((i - j) < srcBLen) && (j < srcALen)) + { + /* z[i] += x[i-j] * y[j] */ + sum += ((q15_t) pIn1[j] * (pIn2[i - j])); + } + } + + /* Store the output in the destination buffer */ + pDst[i] = (q7_t) __SSAT((sum >> 7u), 8u); + } + /* set status as ARM_SUCCESS as there are no argument errors */ + status = ARM_MATH_SUCCESS; + } + return (status); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of PartialConv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q15.c index 71e15fd4c..a33a834ff 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q15.c @@ -1,727 +1,727 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_q15.c -* -* Description: Convolution of Q15 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both inputs are in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * This approach provides 33 guard bits and there is no risk of overflow. - * The 34.30 result is then truncated to 34.15 format by discarding the low 15 bits and then saturated to 1.15 format. - * - * \par - * Refer to arm_conv_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - */ - -void arm_conv_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q63_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t blockSize1, blockSize2, blockSize3, j, k, count, blkCnt; /* loop counter */ - q31_t *pb; /* 32 bit pointer for inputB buffer */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations less than 4 */ - /* Second part of this stage computes the MAC operations greater than or equal to 4 */ - - /* The first part of the stage starts here */ - while((count < 4u) && (blockSize1 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over number of MAC operations between - * inputA samples and inputB samples */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* The second part of the stage starts here */ - /* The internal loop, over count, is unrolled by 4 */ - /* To, read the last two inputB samples using SIMD: - * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ - py = py - 1; - - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + (count - 1u); - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* Initialize inputB pointer of type q31 */ - pb = (q31_t *) (py - 1u); - - /* count is the index by which the pointer pIn1 to be incremented */ - count = 1u; - - - /* -------------------- - * Stage2 process - * -------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - - /* read x[0], x[1] samples */ - x0 = *(q31_t *) (px++); - /* read x[1], x[2] samples */ - x1 = *(q31_t *) (px++); - - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the last two inputB samples using SIMD: - * y[srcBLen - 1] and y[srcBLen - 2] */ - c0 = *(pb--); - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLALDX(x0, c0, acc0); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLALDX(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *(q31_t *) (px++); - - /* Read x[3], x[4] */ - x3 = *(q31_t *) (px++); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLALDX(x2, c0, acc2); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLALDX(x3, c0, acc3); - - /* Read y[srcBLen - 3] and y[srcBLen - 4] */ - c0 = *(pb--); - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLALDX(x2, c0, acc0); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLALDX(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = *(q31_t *) (px++); - - /* Read x[5], x[6] */ - x1 = *(q31_t *) (px++); - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLALDX(x0, c0, acc2); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLALDX(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - py = (q15_t *) pb; - py = py + 1; - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[srcBLen - 5] */ - c0 = *(py); - -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALDX(x1, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = *(pb); - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x0, c0, acc0); - acc1 = __SMLALDX(x1, c0, acc1); - acc2 = __SMLALDX(x3, c0, acc2); - acc3 = __SMLALDX(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = *pb--; - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x0, c0, acc0); - acc1 = __SMLALDX(x1, c0, acc1); - acc2 = __SMLALDX(x3, c0, acc2); - acc3 = __SMLALDX(x2, c0, acc3); - -#ifdef ARM_MATH_BIG_ENDIAN - - /* Read y[srcBLen - 7] */ - c0 = (*pb); - - //c0 = (c0 & 0x0000FFFF)<<16; - c0 = (c0) << 16; - -#else - - /* Read y[srcBLen - 7] */ - c0 = (q15_t) (*pb >> 16); - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x1, c0, acc0); - acc1 = __SMLALD(x2, c0, acc1); - acc2 = __SMLALDX(x2, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - - /* Store the results in the accumulators in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - pb = (q31_t *) (py - 1); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - blockSize3 = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - pIn2 = pSrc2 - 1u; - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations greater than 4 */ - /* Second part of this stage computes the MAC operations less than or equal to 4 */ - - /* The first part of the stage starts here */ - j = blockSize3 >> 2u; - - while((j > 0u) && (blockSize3 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied - * with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied - * with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the loop counter */ - blockSize3--; - - j--; - } - - /* The second part of the stage starts here */ - /* SIMD is not used for the next MAC operations, - * so pointer py is updated to read only one sample at a time */ - py = py + 1u; - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - q15_t *pIn1 = pSrcA; /* input pointer */ - q15_t *pIn2 = pSrcB; /* coefficient pointer */ - q63_t sum; /* Accumulator */ - uint32_t i, j; /* loop counter */ - - /* Loop to calculate output of convolution for output length number of times */ - for (i = 0; i < (srcALen + srcBLen - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += (q31_t) pIn1[j] * (pIn2[i - j]); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q15_t) __SSAT((sum >> 15u), 16u); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Conv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_q15.c +* +* Description: Convolution of Q15 sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup Conv + * @{ + */ + +/** + * @brief Convolution of Q15 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 64-bit internal accumulator. + * Both inputs are in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + * This approach provides 33 guard bits and there is no risk of overflow. + * The 34.30 result is then truncated to 34.15 format by discarding the low 15 bits and then saturated to 1.15 format. + * + * \par + * Refer to arm_conv_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. + */ + +void arm_conv_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst) +{ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t *pIn1; /* inputA pointer */ + q15_t *pIn2; /* inputB pointer */ + q15_t *pOut = pDst; /* output pointer */ + q63_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ + q15_t *px; /* Intermediate inputA pointer */ + q15_t *py; /* Intermediate inputB pointer */ + q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ + q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t blockSize1, blockSize2, blockSize3, j, k, count, blkCnt; /* loop counter */ + q31_t *pb; /* 32 bit pointer for inputB buffer */ + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* The algorithm is implemented in three stages. + The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* For loop unrolling by 4, this stage is divided into two. */ + /* First part of this stage computes the MAC operations less than 4 */ + /* Second part of this stage computes the MAC operations greater than or equal to 4 */ + + /* The first part of the stage starts here */ + while((count < 4u) && (blockSize1 > 0u)) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Loop over number of MAC operations between + * inputA samples and inputB samples */ + k = count; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = __SMLALD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pIn2 + count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* The second part of the stage starts here */ + /* The internal loop, over count, is unrolled by 4 */ + /* To, read the last two inputB samples using SIMD: + * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ + py = py - 1; + + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ + sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ + sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* For the next MAC operations, the pointer py is used without SIMD + * So, py is incremented by 1 */ + py = py + 1u; + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = __SMLALD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pIn2 + (count - 1u); + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* Initialize inputB pointer of type q31 */ + pb = (q31_t *) (py - 1u); + + /* count is the index by which the pointer pIn1 to be incremented */ + count = 1u; + + + /* -------------------- + * Stage2 process + * -------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + + /* read x[0], x[1] samples */ + x0 = *(q31_t *) (px++); + /* read x[1], x[2] samples */ + x1 = *(q31_t *) (px++); + + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read the last two inputB samples using SIMD: + * y[srcBLen - 1] and y[srcBLen - 2] */ + c0 = *(pb--); + + /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ + acc0 = __SMLALDX(x0, c0, acc0); + + /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ + acc1 = __SMLALDX(x1, c0, acc1); + + /* Read x[2], x[3] */ + x2 = *(q31_t *) (px++); + + /* Read x[3], x[4] */ + x3 = *(q31_t *) (px++); + + /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ + acc2 = __SMLALDX(x2, c0, acc2); + + /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ + acc3 = __SMLALDX(x3, c0, acc3); + + /* Read y[srcBLen - 3] and y[srcBLen - 4] */ + c0 = *(pb--); + + /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ + acc0 = __SMLALDX(x2, c0, acc0); + + /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ + acc1 = __SMLALDX(x3, c0, acc1); + + /* Read x[4], x[5] */ + x0 = *(q31_t *) (px++); + + /* Read x[5], x[6] */ + x1 = *(q31_t *) (px++); + + /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ + acc2 = __SMLALDX(x0, c0, acc2); + + /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ + acc3 = __SMLALDX(x1, c0, acc3); + + } while(--k); + + /* For the next MAC operations, SIMD is not used + * So, the 16 bit pointer if inputB, py is updated */ + py = (q15_t *) pb; + py = py + 1; + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + if(k == 1u) + { + /* Read y[srcBLen - 5] */ + c0 = *(py); + +#ifdef ARM_MATH_BIG_ENDIAN + + c0 = c0 << 16u; + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + + /* Read x[7] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALD(x0, c0, acc0); + acc1 = __SMLALD(x1, c0, acc1); + acc2 = __SMLALDX(x1, c0, acc2); + acc3 = __SMLALDX(x3, c0, acc3); + } + + if(k == 2u) + { + /* Read y[srcBLen - 5], y[srcBLen - 6] */ + c0 = *(pb); + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALDX(x0, c0, acc0); + acc1 = __SMLALDX(x1, c0, acc1); + acc2 = __SMLALDX(x3, c0, acc2); + acc3 = __SMLALDX(x2, c0, acc3); + } + + if(k == 3u) + { + /* Read y[srcBLen - 5], y[srcBLen - 6] */ + c0 = *pb--; + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALDX(x0, c0, acc0); + acc1 = __SMLALDX(x1, c0, acc1); + acc2 = __SMLALDX(x3, c0, acc2); + acc3 = __SMLALDX(x2, c0, acc3); + +#ifdef ARM_MATH_BIG_ENDIAN + + /* Read y[srcBLen - 7] */ + c0 = (*pb); + + //c0 = (c0 & 0x0000FFFF)<<16; + c0 = (c0) << 16; + +#else + + /* Read y[srcBLen - 7] */ + c0 = (q15_t) (*pb >> 16); + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + + /* Read x[10] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALDX(x1, c0, acc0); + acc1 = __SMLALD(x2, c0, acc1); + acc2 = __SMLALDX(x2, c0, acc2); + acc3 = __SMLALDX(x3, c0, acc3); + } + + + /* Store the results in the accumulators in the destination buffer. */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pOut)++ = + __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); + *__SIMD32(pOut)++ = + __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); + +#else + + *__SIMD32(pOut)++ = + __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); + *__SIMD32(pOut)++ = + __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + pb = (q31_t *) (py - 1); + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += (q63_t) ((q31_t) * px++ * *py--); + sum += (q63_t) ((q31_t) * px++ * *py--); + sum += (q63_t) ((q31_t) * px++ * *py--); + sum += (q63_t) ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += (q63_t) ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) ((q31_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The blockSize3 variable holds the number of MAC operations performed */ + + blockSize3 = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + pIn2 = pSrc2 - 1u; + py = pIn2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + /* For loop unrolling by 4, this stage is divided into two. */ + /* First part of this stage computes the MAC operations greater than 4 */ + /* Second part of this stage computes the MAC operations less than or equal to 4 */ + + /* The first part of the stage starts here */ + j = blockSize3 >> 2u; + + while((j > 0u) && (blockSize3 > 0u)) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = blockSize3 >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied + * with y[srcBLen - 1], y[srcBLen - 2] respectively */ + sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied + * with y[srcBLen - 3], y[srcBLen - 4] respectively */ + sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* For the next MAC operations, the pointer py is used without SIMD + * So, py is incremented by 1 */ + py = py + 1u; + + /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = blockSize3 % 0x4u; + + while(k > 0u) + { + /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ + sum = __SMLALD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pIn2; + + /* Decrement the loop counter */ + blockSize3--; + + j--; + } + + /* The second part of the stage starts here */ + /* SIMD is not used for the next MAC operations, + * so pointer py is updated to read only one sample at a time */ + py = py + 1u; + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = blockSize3; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen-1] * y[srcBLen-1] */ + sum = __SMLALD(*px++, *py--, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the loop counter */ + blockSize3--; + } + +#else + +/* Run the below code for Cortex-M0 */ + + q15_t *pIn1 = pSrcA; /* input pointer */ + q15_t *pIn2 = pSrcB; /* coefficient pointer */ + q63_t sum; /* Accumulator */ + uint32_t i, j; /* loop counter */ + + /* Loop to calculate output of convolution for output length number of times */ + for (i = 0; i < (srcALen + srcBLen - 1); i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0; j <= i; j++) + { + /* Check the array limitations */ + if(((i - j) < srcBLen) && (j < srcALen)) + { + /* z[i] += x[i-j] * y[j] */ + sum += (q31_t) pIn1[j] * (pIn2[i - j]); + } + } + + /* Store the output in the destination buffer */ + pDst[i] = (q15_t) __SSAT((sum >> 15u), 16u); + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of Conv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q31.c index b98bca063..22a2a9574 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q31.c @@ -1,583 +1,583 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_q31.c -* -* Description: Convolution of Q31 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q31 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * There is no saturation on intermediate additions. - * Thus, if the accumulator overflows it wraps around and distorts the result. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down the inputs by log2(min(srcALen, srcBLen)) (log2 is read as log to the base 2) times to avoid overflows, - * as maximum of min(srcALen, srcBLen) number of additions are carried internally. - * The 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. - * - * \par - * See arm_conv_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -void arm_conv_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q63_t sum; /* Accumulator */ - q63_t acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counter */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (q31_t *) pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = (q31_t *) pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum += (q63_t) * px++ * (*py--); - /* x[1] * y[srcBLen - 2] */ - sum += (q63_t) * px++ * (*py--); - /* x[2] * y[srcBLen - 3] */ - sum += (q63_t) * px++ * (*py--); - /* x[3] * y[srcBLen - 4] */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 += ((q63_t) x0 * c0); - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 += ((q63_t) x1 * c0); - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 += ((q63_t) x2 * c0); - /* acc3 += x[3] * y[srcBLen - 1] */ - acc3 += ((q63_t) x3 * c0); - - /* Read y[srcBLen - 2] sample */ - c0 = *(py--); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 += ((q63_t) x1 * c0); - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 += ((q63_t) x2 * c0); - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 += ((q63_t) x3 * c0); - /* acc3 += x[4] * y[srcBLen - 2] */ - acc3 += ((q63_t) x0 * c0); - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 += ((q63_t) x2 * c0); - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 += ((q63_t) x3 * c0); - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 += ((q63_t) x0 * c0); - /* acc3 += x[5] * y[srcBLen - 2] */ - acc3 += ((q63_t) x1 * c0); - - /* Read y[srcBLen - 4] sample */ - c0 = *(py--); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[srcBLen - 4] */ - acc0 += ((q63_t) x3 * c0); - /* acc1 += x[4] * y[srcBLen - 4] */ - acc1 += ((q63_t) x0 * c0); - /* acc2 += x[5] * y[srcBLen - 4] */ - acc2 += ((q63_t) x1 * c0); - /* acc3 += x[6] * y[srcBLen - 4] */ - acc3 += ((q63_t) x2 * c0); - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += ((q63_t) x0 * c0); - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += ((q63_t) x1 * c0); - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += ((q63_t) x2 * c0); - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 += ((q63_t) x3 * c0); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the results in the accumulators in the destination buffer. */ - *pOut++ = (q31_t) (acc0 >> 31); - *pOut++ = (q31_t) (acc1 >> 31); - *pOut++ = (q31_t) (acc2 >> 31); - *pOut++ = (q31_t) (acc3 >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - sum += (q63_t) * px++ * (*py--); - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum += (q63_t) * px++ * (*py--); - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - sum += (q63_t) * px++ * (*py--); - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t *pIn1 = pSrcA; /* input pointer */ - q31_t *pIn2 = pSrcB; /* coefficient pointer */ - q63_t sum; /* Accumulator */ - uint32_t i, j; /* loop counter */ - - /* Loop to calculate output of convolution for output length number of times */ - for (i = 0; i < (srcALen + srcBLen - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q63_t) pIn1[j] * (pIn2[i - j])); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q31_t) (sum >> 31u); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Conv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_q31.c +* +* Description: Convolution of Q31 sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup Conv + * @{ + */ + +/** + * @brief Convolution of Q31 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * There is no saturation on intermediate additions. + * Thus, if the accumulator overflows it wraps around and distorts the result. + * The input signals should be scaled down to avoid intermediate overflows. + * Scale down the inputs by log2(min(srcALen, srcBLen)) (log2 is read as log to the base 2) times to avoid overflows, + * as maximum of min(srcALen, srcBLen) number of additions are carried internally. + * The 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. + * + * \par + * See arm_conv_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. + */ + +void arm_conv_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t *pIn1; /* inputA pointer */ + q31_t *pIn2; /* inputB pointer */ + q31_t *pOut = pDst; /* output pointer */ + q31_t *px; /* Intermediate inputA pointer */ + q31_t *py; /* Intermediate inputB pointer */ + q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ + q63_t sum; /* Accumulator */ + q63_t acc0, acc1, acc2, acc3; /* Accumulator */ + q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counter */ + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = (q31_t *) pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = (q31_t *) pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* The algorithm is implemented in three stages. + The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + blockSize3 = blockSize1; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first stage starts here */ + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 1] */ + sum += (q63_t) * px++ * (*py--); + /* x[1] * y[srcBLen - 2] */ + sum += (q63_t) * px++ * (*py--); + /* x[2] * y[srcBLen - 3] */ + sum += (q63_t) * px++ * (*py--); + /* x[3] * y[srcBLen - 4] */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q31_t) (sum >> 31); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pIn2 + count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[srcBLen - 1] sample */ + c0 = *(py--); + + /* Read x[3] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[0] * y[srcBLen - 1] */ + acc0 += ((q63_t) x0 * c0); + /* acc1 += x[1] * y[srcBLen - 1] */ + acc1 += ((q63_t) x1 * c0); + /* acc2 += x[2] * y[srcBLen - 1] */ + acc2 += ((q63_t) x2 * c0); + /* acc3 += x[3] * y[srcBLen - 1] */ + acc3 += ((q63_t) x3 * c0); + + /* Read y[srcBLen - 2] sample */ + c0 = *(py--); + + /* Read x[4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[1] * y[srcBLen - 2] */ + acc0 += ((q63_t) x1 * c0); + /* acc1 += x[2] * y[srcBLen - 2] */ + acc1 += ((q63_t) x2 * c0); + /* acc2 += x[3] * y[srcBLen - 2] */ + acc2 += ((q63_t) x3 * c0); + /* acc3 += x[4] * y[srcBLen - 2] */ + acc3 += ((q63_t) x0 * c0); + + /* Read y[srcBLen - 3] sample */ + c0 = *(py--); + + /* Read x[5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[2] * y[srcBLen - 3] */ + acc0 += ((q63_t) x2 * c0); + /* acc1 += x[3] * y[srcBLen - 2] */ + acc1 += ((q63_t) x3 * c0); + /* acc2 += x[4] * y[srcBLen - 2] */ + acc2 += ((q63_t) x0 * c0); + /* acc3 += x[5] * y[srcBLen - 2] */ + acc3 += ((q63_t) x1 * c0); + + /* Read y[srcBLen - 4] sample */ + c0 = *(py--); + + /* Read x[6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[3] * y[srcBLen - 4] */ + acc0 += ((q63_t) x3 * c0); + /* acc1 += x[4] * y[srcBLen - 4] */ + acc1 += ((q63_t) x0 * c0); + /* acc2 += x[5] * y[srcBLen - 4] */ + acc2 += ((q63_t) x1 * c0); + /* acc3 += x[6] * y[srcBLen - 4] */ + acc3 += ((q63_t) x2 * c0); + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[srcBLen - 5] sample */ + c0 = *(py--); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[srcBLen - 5] */ + acc0 += ((q63_t) x0 * c0); + /* acc1 += x[5] * y[srcBLen - 5] */ + acc1 += ((q63_t) x1 * c0); + /* acc2 += x[6] * y[srcBLen - 5] */ + acc2 += ((q63_t) x2 * c0); + /* acc3 += x[7] * y[srcBLen - 5] */ + acc3 += ((q63_t) x3 * c0); + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the results in the accumulators in the destination buffer. */ + *pOut++ = (q31_t) (acc0 >> 31); + *pOut++ = (q31_t) (acc1 >> 31); + *pOut++ = (q31_t) (acc2 >> 31); + *pOut++ = (q31_t) (acc3 >> 31); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += (q63_t) * px++ * (*py--); + sum += (q63_t) * px++ * (*py--); + sum += (q63_t) * px++ * (*py--); + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q31_t) (sum >> 31); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q31_t) (sum >> 31); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The blockSize3 variable holds the number of MAC operations performed */ + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = blockSize3 >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ + sum += (q63_t) * px++ * (*py--); + /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ + sum += (q63_t) * px++ * (*py--); + /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ + sum += (q63_t) * px++ * (*py--); + /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = blockSize3 % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) * px++ * (*py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q31_t) (sum >> 31); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the loop counter */ + blockSize3--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q31_t *pIn1 = pSrcA; /* input pointer */ + q31_t *pIn2 = pSrcB; /* coefficient pointer */ + q63_t sum; /* Accumulator */ + uint32_t i, j; /* loop counter */ + + /* Loop to calculate output of convolution for output length number of times */ + for (i = 0; i < (srcALen + srcBLen - 1); i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0; j <= i; j++) + { + /* Check the array limitations */ + if(((i - j) < srcBLen) && (j < srcALen)) + { + /* z[i] += x[i-j] * y[j] */ + sum += ((q63_t) pIn1[j] * (pIn2[i - j])); + } + } + + /* Store the output in the destination buffer */ + pDst[i] = (q31_t) (sum >> 31u); + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of Conv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q7.c index cfdea705e..6f844dd68 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_conv_q7.c @@ -1,680 +1,680 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_conv_q7.c -* -* Description: Convolution of Q7 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 32-bit internal accumulator. - * Both the inputs are represented in 1.7 format and multiplications yield a 2.14 result. - * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. - * This approach provides 17 guard bits and there is no risk of overflow as long as max(srcALen, srcBLen)<131072. - * The 18.14 result is then truncated to 18.7 format by discarding the low 7 bits and then saturated to 1.7 format. - */ - -void arm_conv_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t *pIn1; /* inputA pointer */ - q7_t *pIn2; /* inputB pointer */ - q7_t *pOut = pDst; /* output pointer */ - q7_t *px; /* Intermediate inputA pointer */ - q7_t *py; /* Intermediate inputB pointer */ - q7_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q7_t x0, x1, x2, x3, c0, c1; /* Temporary variables to hold state and coefficient values */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t input1, input2; /* Temporary input variables */ - q15_t in1, in2; /* Temporary input variables */ - uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counter */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = (srcALen - srcBLen) + 1u; - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] , x[1] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* y[srcBLen - 1] , y[srcBLen - 2] */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* x[0] * y[srcBLen - 1] */ - /* x[1] * y[srcBLen - 2] */ - sum = __SMLAD(input1, input2, sum); - - /* x[2] , x[3] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* y[srcBLen - 3] , y[srcBLen - 4] */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* x[2] * y[srcBLen - 3] */ - /* x[3] * y[srcBLen - 4] */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q15_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - /* Read y[srcBLen - 2] sample */ - c1 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* x[0] and x[1] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* y[srcBLen - 1] and y[srcBLen - 2] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[1] and x[2] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[4] sample */ - x0 = *(px++); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLAD(input1, input2, acc3); - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - /* Read y[srcBLen - 4] sample */ - c1 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* y[srcBLen - 3] and y[srcBLen - 4] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[4] and x[5] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[6] sample */ - x2 = *(px++); - - /* x[5] and x[6] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLAD(input1, input2, acc3); - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += ((q15_t) x0 * c0); - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += ((q15_t) x1 * c0); - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += ((q15_t) x2 * c0); - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 += ((q15_t) x3 * c0); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(acc0 >> 7u, 8)); - *pOut++ = (q7_t) (__SSAT(acc1 >> 7u, 8)); - *pOut++ = (q7_t) (__SSAT(acc2 >> 7u, 8)); - *pOut++ = (q7_t) (__SSAT(acc3 >> 7u, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q15_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q15_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Reading two inputs, x[srcALen - srcBLen + 1] and x[srcALen - srcBLen + 2] of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Reading two inputs, y[srcBLen - 1] and y[srcBLen - 2] of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs, x[srcALen - srcBLen + 3] and x[srcALen - srcBLen + 4] of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Reading two inputs, y[srcBLen - 3] and y[srcBLen - 4] of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q15_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q7_t *pIn1 = pSrcA; /* input pointer */ - q7_t *pIn2 = pSrcB; /* coefficient pointer */ - q31_t sum; /* Accumulator */ - uint32_t i, j; /* loop counter */ - - /* Loop to calculate output of convolution for output length number of times */ - for (i = 0; i < (srcALen + srcBLen - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += (q15_t) pIn1[j] * (pIn2[i - j]); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q7_t) __SSAT((sum >> 7u), 8u); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Conv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_conv_q7.c +* +* Description: Convolution of Q7 sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup Conv + * @{ + */ + +/** + * @brief Convolution of Q7 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 32-bit internal accumulator. + * Both the inputs are represented in 1.7 format and multiplications yield a 2.14 result. + * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. + * This approach provides 17 guard bits and there is no risk of overflow as long as max(srcALen, srcBLen)<131072. + * The 18.14 result is then truncated to 18.7 format by discarding the low 7 bits and then saturated to 1.7 format. + */ + +void arm_conv_q7( + q7_t * pSrcA, + uint32_t srcALen, + q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q7_t *pIn1; /* inputA pointer */ + q7_t *pIn2; /* inputB pointer */ + q7_t *pOut = pDst; /* output pointer */ + q7_t *px; /* Intermediate inputA pointer */ + q7_t *py; /* Intermediate inputB pointer */ + q7_t *pSrc1, *pSrc2; /* Intermediate pointers */ + q7_t x0, x1, x2, x3, c0, c1; /* Temporary variables to hold state and coefficient values */ + q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ + q31_t input1, input2; /* Temporary input variables */ + q15_t in1, in2; /* Temporary input variables */ + uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counter */ + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + } + + /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ + /* The function is internally + * divided into three stages according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first stage of the + * algorithm, the multiplications increase by one for every iteration. + * In the second stage of the algorithm, srcBLen number of multiplications are done. + * In the third stage of the algorithm, the multiplications decrease by one + * for every iteration. */ + + /* The algorithm is implemented in three stages. + The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = (srcALen - srcBLen) + 1u; + blockSize3 = blockSize1; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[0] + * sum = x[0] * y[1] + x[1] * y[0] + * .... + * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first stage starts here */ + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] , x[1] */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* y[srcBLen - 1] , y[srcBLen - 2] */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* x[0] * y[srcBLen - 1] */ + /* x[1] * y[srcBLen - 2] */ + sum = __SMLAD(input1, input2, sum); + + /* x[2] , x[3] */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* y[srcBLen - 3] , y[srcBLen - 4] */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* x[2] * y[srcBLen - 3] */ + /* x[3] * y[srcBLen - 4] */ + sum = __SMLAD(input1, input2, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q15_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pIn2 + count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] + * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] + * .... + * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[srcBLen - 1] sample */ + c0 = *(py--); + /* Read y[srcBLen - 2] sample */ + c1 = *(py--); + + /* Read x[3] sample */ + x3 = *(px++); + + /* x[0] and x[1] are packed */ + in1 = (q15_t) x0; + in2 = (q15_t) x1; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* y[srcBLen - 1] and y[srcBLen - 2] are packed */ + in1 = (q15_t) c0; + in2 = (q15_t) c1; + + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ + acc0 = __SMLAD(input1, input2, acc0); + + /* x[1] and x[2] are packed */ + in1 = (q15_t) x1; + in2 = (q15_t) x2; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ + acc1 = __SMLAD(input1, input2, acc1); + + /* x[2] and x[3] are packed */ + in1 = (q15_t) x2; + in2 = (q15_t) x3; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ + acc2 = __SMLAD(input1, input2, acc2); + + /* Read x[4] sample */ + x0 = *(px++); + + /* x[3] and x[4] are packed */ + in1 = (q15_t) x3; + in2 = (q15_t) x0; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ + acc3 = __SMLAD(input1, input2, acc3); + + /* Read y[srcBLen - 3] sample */ + c0 = *(py--); + /* Read y[srcBLen - 4] sample */ + c1 = *(py--); + + /* Read x[5] sample */ + x1 = *(px++); + + /* x[2] and x[3] are packed */ + in1 = (q15_t) x2; + in2 = (q15_t) x3; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* y[srcBLen - 3] and y[srcBLen - 4] are packed */ + in1 = (q15_t) c0; + in2 = (q15_t) c1; + + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ + acc0 = __SMLAD(input1, input2, acc0); + + /* x[3] and x[4] are packed */ + in1 = (q15_t) x3; + in2 = (q15_t) x0; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ + acc1 = __SMLAD(input1, input2, acc1); + + /* x[4] and x[5] are packed */ + in1 = (q15_t) x0; + in2 = (q15_t) x1; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ + acc2 = __SMLAD(input1, input2, acc2); + + /* Read x[6] sample */ + x2 = *(px++); + + /* x[5] and x[6] are packed */ + in1 = (q15_t) x1; + in2 = (q15_t) x2; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ + acc3 = __SMLAD(input1, input2, acc3); + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[srcBLen - 5] sample */ + c0 = *(py--); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[srcBLen - 5] */ + acc0 += ((q15_t) x0 * c0); + /* acc1 += x[5] * y[srcBLen - 5] */ + acc1 += ((q15_t) x1 * c0); + /* acc2 += x[6] * y[srcBLen - 5] */ + acc2 += ((q15_t) x2 * c0); + /* acc3 += x[7] * y[srcBLen - 5] */ + acc3 += ((q15_t) x3 * c0); + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q7_t) (__SSAT(acc0 >> 7u, 8)); + *pOut++ = (q7_t) (__SSAT(acc1 >> 7u, 8)); + *pOut++ = (q7_t) (__SSAT(acc2 >> 7u, 8)); + *pOut++ = (q7_t) (__SSAT(acc3 >> 7u, 8)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + + /* Reading two inputs of SrcA buffer and packing */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* Reading two inputs of SrcB buffer and packing */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* Perform the multiply-accumulates */ + sum = __SMLAD(input1, input2, sum); + + /* Reading two inputs of SrcA buffer and packing */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* Reading two inputs of SrcB buffer and packing */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* Perform the multiply-accumulates */ + sum = __SMLAD(input1, input2, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q15_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* srcBLen number of MACS should be performed */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += ((q15_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pSrc2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] + * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] + * .... + * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] + * sum += x[srcALen-1] * y[srcBLen-1] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The blockSize3 variable holds the number of MAC operations performed */ + + /* Working pointer of inputA */ + pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); + px = pSrc1; + + /* Working pointer of inputB */ + pSrc2 = pIn2 + (srcBLen - 1u); + py = pSrc2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = blockSize3 >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Reading two inputs, x[srcALen - srcBLen + 1] and x[srcALen - srcBLen + 2] of SrcA buffer and packing */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* Reading two inputs, y[srcBLen - 1] and y[srcBLen - 2] of SrcB buffer and packing */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ + /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ + sum = __SMLAD(input1, input2, sum); + + /* Reading two inputs, x[srcALen - srcBLen + 3] and x[srcALen - srcBLen + 4] of SrcA buffer and packing */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* Reading two inputs, y[srcBLen - 3] and y[srcBLen - 4] of SrcB buffer and packing */ + in1 = (q15_t) * py--; + in2 = (q15_t) * py--; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); + + /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ + /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ + sum = __SMLAD(input1, input2, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = blockSize3 % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q15_t) * px++ * *py--); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pSrc2; + + /* Decrement the loop counter */ + blockSize3--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q7_t *pIn1 = pSrcA; /* input pointer */ + q7_t *pIn2 = pSrcB; /* coefficient pointer */ + q31_t sum; /* Accumulator */ + uint32_t i, j; /* loop counter */ + + /* Loop to calculate output of convolution for output length number of times */ + for (i = 0; i < (srcALen + srcBLen - 1); i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0; j <= i; j++) + { + /* Check the array limitations */ + if(((i - j) < srcBLen) && (j < srcALen)) + { + /* z[i] += x[i-j] * y[j] */ + sum += (q15_t) pIn1[j] * (pIn2[i - j]); + } + } + + /* Store the output in the destination buffer */ + pDst[i] = (q7_t) __SSAT((sum >> 7u), 8u); + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of Conv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_f32.c index 488046efd..bfbe0d34b 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_f32.c @@ -1,718 +1,718 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_f32.c -* -* Description: Correlation of floating-point sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup Corr Correlation - * - * Correlation is a mathematical operation that is similar to convolution. - * As with convolution, correlation uses two signals to produce a third signal. - * The underlying algorithms in correlation and convolution are identical except that one of the inputs is flipped in convolution. - * Correlation is commonly used to measure the similarity between two signals. - * It has applications in pattern recognition, cryptanalysis, and searching. - * The CMSIS library provides correlation functions for Q7, Q15, Q31 and floating-point data types. - * Fast versions of the Q15 and Q31 functions are also provided. - * - * \par Algorithm - * Let a[n] and b[n] be sequences of length srcALen and srcBLen samples respectively. - * The convolution of the two signals is denoted by - *
   
- *                   c[n] = a[n] * b[n]   
- * 
- * In correlation, one of the signals is flipped in time - *
   
- *                   c[n] = a[n] * b[-n]   
- * 
- * - * \par - * and this is mathematically defined as - * \image html CorrelateEquation.gif - * \par - * The pSrcA points to the first input vector of length srcALen and pSrcB points to the second input vector of length srcBLen. - * The result c[n] is of length 2 * max(srcALen, srcBLen) - 1 and is defined over the interval n=0, 1, 2, ..., (2 * max(srcALen, srcBLen) - 2). - * The output result is written to pDst and the calling function must allocate 2 * max(srcALen, srcBLen) - 1 words for the result. - * - * Note - * \par - * The pDst should be initialized to all zeros before being used. - * - * Fixed-Point Behavior - * \par - * Correlation requires summing up a large number of intermediate products. - * As such, the Q7, Q15, and Q31 functions run a risk of overflow and saturation. - * Refer to the function specific documentation below for further details of the particular algorithm used. - */ - -/** - * @addtogroup Corr - * @{ - */ -/** - * @brief Correlation of floating-point sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - */ - -void arm_correlate_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t *pIn1; /* inputA pointer */ - float32_t *pIn2; /* inputB pointer */ - float32_t *pOut = pDst; /* output pointer */ - float32_t *px; /* Intermediate inputA pointer */ - float32_t *py; /* Intermediate inputB pointer */ - float32_t *pSrc1; /* Intermediate pointers */ - float32_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - float32_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counters */ - int32_t inc = 1; /* Destination address modifier */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding has to be done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - //while(j > 0u) - //{ - // /* Zero is stored in the destination buffer */ - // *pOut++ = 0.0f; - - // /* Decrement the loop counter */ - // j--; - //} - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen-2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] */ - sum += *px++ * *py++; - /* x[1] * y[srcBLen - 3] */ - sum += *px++ * *py++; - /* x[2] * y[srcBLen - 2] */ - sum += *px++ * *py++; - /* x[3] * y[srcBLen - 1] */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - /* x[0] * y[srcBLen - 1] */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4, to loop unroll the srcBLen loop */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0.0f; - acc1 = 0.0f; - acc2 = 0.0f; - acc3 = 0.0f; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[0] sample */ - c0 = *(py++); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[0] */ - acc0 += x0 * c0; - /* acc1 += x[1] * y[0] */ - acc1 += x1 * c0; - /* acc2 += x[2] * y[0] */ - acc2 += x2 * c0; - /* acc3 += x[3] * y[0] */ - acc3 += x3 * c0; - - /* Read y[1] sample */ - c0 = *(py++); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[1] */ - acc0 += x1 * c0; - /* acc1 += x[2] * y[1] */ - acc1 += x2 * c0; - /* acc2 += x[3] * y[1] */ - acc2 += x3 * c0; - /* acc3 += x[4] * y[1] */ - acc3 += x0 * c0; - - /* Read y[2] sample */ - c0 = *(py++); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[2] */ - acc0 += x2 * c0; - /* acc1 += x[3] * y[2] */ - acc1 += x3 * c0; - /* acc2 += x[4] * y[2] */ - acc2 += x0 * c0; - /* acc3 += x[5] * y[2] */ - acc3 += x1 * c0; - - /* Read y[3] sample */ - c0 = *(py++); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[3] */ - acc0 += x3 * c0; - /* acc1 += x[4] * y[3] */ - acc1 += x0 * c0; - /* acc2 += x[5] * y[3] */ - acc2 += x1 * c0; - /* acc3 += x[6] * y[3] */ - acc3 += x2 * c0; - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[4] sample */ - c0 = *(py++); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[4] */ - acc0 += x0 * c0; - /* acc1 += x[5] * y[4] */ - acc1 += x1 * c0; - /* acc2 += x[6] * y[4] */ - acc2 += x2 * c0; - /* acc3 += x[7] * y[4] */ - acc3 += x3 * c0; - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = acc0; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = acc1; - pOut += inc; - - *pOut = acc2; - pOut += inc; - - *pOut = acc3; - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pIn2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += *px++ * *py++; - sum += *px++ * *py++; - sum += *px++ * *py++; - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen - srcBLen + 4] * y[3] */ - sum += *px++ * *py++; - /* sum += x[srcALen - srcBLen + 3] * y[2] */ - sum += *px++ * *py++; - /* sum += x[srcALen - srcBLen + 2] * y[1] */ - sum += *px++ * *py++; - /* sum += x[srcALen - srcBLen + 1] * y[0] */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t *pIn1 = pSrcA; /* inputA pointer */ - float32_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ - float32_t sum; /* Accumulator */ - uint32_t i = 0u, j; /* loop counters */ - uint32_t inv = 0u; /* Reverse order flag */ - uint32_t tot = 0u; /* Length */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and a varaible, inv is set to 1 */ - /* If lengths are not equal then zero pad has to be done to make the two - * inputs of same length. But to improve the performance, we include zeroes - * in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the - * starting of the output buffer */ - /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the - * ending of the output buffer */ - /* Once the zero padding is done the remaining of the output is calcualted - * using convolution but with the shorter signal time shifted. */ - - /* Calculate the length of the remaining sequence */ - tot = ((srcALen + srcBLen) - 2u); - - if(srcALen > srcBLen) - { - /* Calculating the number of zeros to be padded to the output */ - j = srcALen - srcBLen; - - /* Initialise the pointer after zero padding */ - pDst += j; - } - - else if(srcALen < srcBLen) - { - /* Initialization to inputB pointer */ - pIn1 = pSrcB; - - /* Initialization to the end of inputA pointer */ - pIn2 = pSrcA + (srcALen - 1u); - - /* Initialisation of the pointer after zero padding */ - pDst = pDst + tot; - - /* Swapping the lengths */ - j = srcALen; - srcALen = srcBLen; - srcBLen = j; - - /* Setting the reverse flag */ - inv = 1; - - } - - /* Loop to calculate convolution for output length number of times */ - for (i = 0u; i <= tot; i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0.0f; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += pIn1[j] * pIn2[-((int32_t) i - j)]; - } - } - /* Store the output in the destination buffer */ - if(inv == 1) - *pDst-- = sum; - else - *pDst++ = sum; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Corr group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_correlate_f32.c +* +* Description: Correlation of floating-point sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup Corr Correlation + * + * Correlation is a mathematical operation that is similar to convolution. + * As with convolution, correlation uses two signals to produce a third signal. + * The underlying algorithms in correlation and convolution are identical except that one of the inputs is flipped in convolution. + * Correlation is commonly used to measure the similarity between two signals. + * It has applications in pattern recognition, cryptanalysis, and searching. + * The CMSIS library provides correlation functions for Q7, Q15, Q31 and floating-point data types. + * Fast versions of the Q15 and Q31 functions are also provided. + * + * \par Algorithm + * Let a[n] and b[n] be sequences of length srcALen and srcBLen samples respectively. + * The convolution of the two signals is denoted by + *
   
+ *                   c[n] = a[n] * b[n]   
+ * 
+ * In correlation, one of the signals is flipped in time + *
   
+ *                   c[n] = a[n] * b[-n]   
+ * 
+ * + * \par + * and this is mathematically defined as + * \image html CorrelateEquation.gif + * \par + * The pSrcA points to the first input vector of length srcALen and pSrcB points to the second input vector of length srcBLen. + * The result c[n] is of length 2 * max(srcALen, srcBLen) - 1 and is defined over the interval n=0, 1, 2, ..., (2 * max(srcALen, srcBLen) - 2). + * The output result is written to pDst and the calling function must allocate 2 * max(srcALen, srcBLen) - 1 words for the result. + * + * Note + * \par + * The pDst should be initialized to all zeros before being used. + * + * Fixed-Point Behavior + * \par + * Correlation requires summing up a large number of intermediate products. + * As such, the Q7, Q15, and Q31 functions run a risk of overflow and saturation. + * Refer to the function specific documentation below for further details of the particular algorithm used. + */ + +/** + * @addtogroup Corr + * @{ + */ +/** + * @brief Correlation of floating-point sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + */ + +void arm_correlate_f32( + float32_t * pSrcA, + uint32_t srcALen, + float32_t * pSrcB, + uint32_t srcBLen, + float32_t * pDst) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + float32_t *pIn1; /* inputA pointer */ + float32_t *pIn2; /* inputB pointer */ + float32_t *pOut = pDst; /* output pointer */ + float32_t *px; /* Intermediate inputA pointer */ + float32_t *py; /* Intermediate inputB pointer */ + float32_t *pSrc1; /* Intermediate pointers */ + float32_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ + float32_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ + uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counters */ + int32_t inc = 1; /* Destination address modifier */ + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + /* But CORR(x, y) is reverse of CORR(y, x) */ + /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ + /* and the destination pointer modifier, inc is set to -1 */ + /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ + /* But to improve the performance, + * we include zeroes in the output instead of zero padding either of the the inputs*/ + /* If srcALen > srcBLen, + * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ + /* If srcALen < srcBLen, + * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = pSrcA; + + /* Initialization of inputB pointer */ + pIn2 = pSrcB; + + /* Number of output samples is calculated */ + outBlockSize = (2u * srcALen) - 1u; + + /* When srcALen > srcBLen, zero padding has to be done to srcB + * to make their lengths equal. + * Instead, (outBlockSize - (srcALen + srcBLen - 1)) + * number of output samples are made zero */ + j = outBlockSize - (srcALen + (srcBLen - 1u)); + + /* Updating the pointer position to non zero value */ + pOut += j; + + //while(j > 0u) + //{ + // /* Zero is stored in the destination buffer */ + // *pOut++ = 0.0f; + + // /* Decrement the loop counter */ + // j--; + //} + + } + else + { + /* Initialization of inputA pointer */ + pIn1 = pSrcB; + + /* Initialization of inputB pointer */ + pIn2 = pSrcA; + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + + /* CORR(x, y) = Reverse order(CORR(y, x)) */ + /* Hence set the destination pointer to point to the last output sample */ + pOut = pDst + ((srcALen + srcBLen) - 2u); + + /* Destination address modifier is set to -1 */ + inc = -1; + + } + + /* The function is internally + * divided into three parts according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first part of the + * algorithm, the multiplications increase by one for every iteration. + * In the second part of the algorithm, srcBLen number of multiplications are done. + * In the third part of the algorithm, the multiplications decrease by one + * for every iteration.*/ + /* The algorithm is implemented in three stages. + * The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + blockSize3 = blockSize1; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[srcBlen - 1] + * sum = x[0] * y[srcBlen-2] + x[1] * y[srcBlen - 1] + * .... + * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc1 = pIn2 + (srcBLen - 1u); + py = pSrc1; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first stage starts here */ + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 4] */ + sum += *px++ * *py++; + /* x[1] * y[srcBLen - 3] */ + sum += *px++ * *py++; + /* x[2] * y[srcBLen - 2] */ + sum += *px++ * *py++; + /* x[3] * y[srcBLen - 1] */ + sum += *px++ * *py++; + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + /* x[0] * y[srcBLen - 1] */ + sum += *px++ * *py++; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = sum; + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pSrc1 - count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] + * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] + * .... + * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4, to loop unroll the srcBLen loop */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0.0f; + acc1 = 0.0f; + acc2 = 0.0f; + acc3 = 0.0f; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[0] sample */ + c0 = *(py++); + + /* Read x[3] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[0] * y[0] */ + acc0 += x0 * c0; + /* acc1 += x[1] * y[0] */ + acc1 += x1 * c0; + /* acc2 += x[2] * y[0] */ + acc2 += x2 * c0; + /* acc3 += x[3] * y[0] */ + acc3 += x3 * c0; + + /* Read y[1] sample */ + c0 = *(py++); + + /* Read x[4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[1] * y[1] */ + acc0 += x1 * c0; + /* acc1 += x[2] * y[1] */ + acc1 += x2 * c0; + /* acc2 += x[3] * y[1] */ + acc2 += x3 * c0; + /* acc3 += x[4] * y[1] */ + acc3 += x0 * c0; + + /* Read y[2] sample */ + c0 = *(py++); + + /* Read x[5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[2] * y[2] */ + acc0 += x2 * c0; + /* acc1 += x[3] * y[2] */ + acc1 += x3 * c0; + /* acc2 += x[4] * y[2] */ + acc2 += x0 * c0; + /* acc3 += x[5] * y[2] */ + acc3 += x1 * c0; + + /* Read y[3] sample */ + c0 = *(py++); + + /* Read x[6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[3] * y[3] */ + acc0 += x3 * c0; + /* acc1 += x[4] * y[3] */ + acc1 += x0 * c0; + /* acc2 += x[5] * y[3] */ + acc2 += x1 * c0; + /* acc3 += x[6] * y[3] */ + acc3 += x2 * c0; + + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[4] sample */ + c0 = *(py++); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[4] */ + acc0 += x0 * c0; + /* acc1 += x[5] * y[4] */ + acc1 += x1 * c0; + /* acc2 += x[6] * y[4] */ + acc2 += x2 * c0; + /* acc3 += x[7] * y[4] */ + acc3 += x3 * c0; + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = acc0; + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + *pOut = acc1; + pOut += inc; + + *pOut = acc2; + pOut += inc; + + *pOut = acc3; + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pIn2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += *px++ * *py++; + sum += *px++ * *py++; + sum += *px++ * *py++; + sum += *px++ * *py++; + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += *px++ * *py++; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = sum; + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* Loop over srcBLen */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += *px++ * *py++; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = sum; + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * .... + * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] + * sum += x[srcALen-1] * y[0] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); + px = pSrc1; + + /* Working pointer of inputB */ + py = pIn2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0.0f; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen - srcBLen + 4] * y[3] */ + sum += *px++ * *py++; + /* sum += x[srcALen - srcBLen + 3] * y[2] */ + sum += *px++ * *py++; + /* sum += x[srcALen - srcBLen + 2] * y[1] */ + sum += *px++ * *py++; + /* sum += x[srcALen - srcBLen + 1] * y[0] */ + sum += *px++ * *py++; + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += *px++ * *py++; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = sum; + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pIn2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + float32_t *pIn1 = pSrcA; /* inputA pointer */ + float32_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ + float32_t sum; /* Accumulator */ + uint32_t i = 0u, j; /* loop counters */ + uint32_t inv = 0u; /* Reverse order flag */ + uint32_t tot = 0u; /* Length */ + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + /* But CORR(x, y) is reverse of CORR(y, x) */ + /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ + /* and a varaible, inv is set to 1 */ + /* If lengths are not equal then zero pad has to be done to make the two + * inputs of same length. But to improve the performance, we include zeroes + * in the output instead of zero padding either of the the inputs*/ + /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the + * starting of the output buffer */ + /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the + * ending of the output buffer */ + /* Once the zero padding is done the remaining of the output is calcualted + * using convolution but with the shorter signal time shifted. */ + + /* Calculate the length of the remaining sequence */ + tot = ((srcALen + srcBLen) - 2u); + + if(srcALen > srcBLen) + { + /* Calculating the number of zeros to be padded to the output */ + j = srcALen - srcBLen; + + /* Initialise the pointer after zero padding */ + pDst += j; + } + + else if(srcALen < srcBLen) + { + /* Initialization to inputB pointer */ + pIn1 = pSrcB; + + /* Initialization to the end of inputA pointer */ + pIn2 = pSrcA + (srcALen - 1u); + + /* Initialisation of the pointer after zero padding */ + pDst = pDst + tot; + + /* Swapping the lengths */ + j = srcALen; + srcALen = srcBLen; + srcBLen = j; + + /* Setting the reverse flag */ + inv = 1; + + } + + /* Loop to calculate convolution for output length number of times */ + for (i = 0u; i <= tot; i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0.0f; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0u; j <= i; j++) + { + /* Check the array limitations */ + if((((i - j) < srcBLen) && (j < srcALen))) + { + /* z[i] += x[i-j] * y[j] */ + sum += pIn1[j] * pIn2[-((int32_t) i - j)]; + } + } + /* Store the output in the destination buffer */ + if(inv == 1) + *pDst-- = sum; + else + *pDst++ = sum; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of Corr group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q15.c index 8c2dd0fb2..f93d85a5b 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q15.c @@ -1,622 +1,622 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_fast_q15.c -* -* Description: Fast Q15 Correlation. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - * - * Scaling and Overflow Behavior: - * - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * There is no saturation on intermediate additions. - * Thus, if the accumulator overflows it wraps around and distorts the result. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down one of the inputs by 1/min(srcALen, srcBLen) to avoid overflow since a - * maximum of min(srcALen, srcBLen) number of additions is carried internally. - * The 2.30 accumulator is right shifted by 15 bits and then saturated to 1.15 format to yield the final result. - * - * \par - * See arm_correlate_q15() for a slower implementation of this function which uses a 64-bit accumulator to avoid wrap around distortion. - */ - -void arm_correlate_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst) -{ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; /* Destination address modifier */ - q31_t *pb; /* 32 bit pointer for inputB buffer */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first loop starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] , x[1] * y[srcBLen - 3] */ - sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - /* x[3] * y[srcBLen - 1] , x[2] * y[srcBLen - 2] */ - sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum = __SMLAD(*px++, *py++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* Initialize inputB pointer of type q31 */ - pb = (q31_t *) (py); - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4, to loop unroll the srcBLen loop */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1] samples */ - x0 = *(q31_t *) (px++); - /* read x[1], x[2] samples */ - x1 = *(q31_t *) (px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the first two inputB samples using SIMD: - * y[0] and y[1] */ - c0 = *(pb++); - - /* acc0 += x[0] * y[0] + x[1] * y[1] */ - acc0 = __SMLAD(x0, c0, acc0); - - /* acc1 += x[1] * y[0] + x[2] * y[1] */ - acc1 = __SMLAD(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *(q31_t *) (px++); - - /* Read x[3], x[4] */ - x3 = *(q31_t *) (px++); - - /* acc2 += x[2] * y[0] + x[3] * y[1] */ - acc2 = __SMLAD(x2, c0, acc2); - - /* acc3 += x[3] * y[0] + x[4] * y[1] */ - acc3 = __SMLAD(x3, c0, acc3); - - /* Read y[2] and y[3] */ - c0 = *(pb++); - - /* acc0 += x[2] * y[2] + x[3] * y[3] */ - acc0 = __SMLAD(x2, c0, acc0); - - /* acc1 += x[3] * y[2] + x[4] * y[3] */ - acc1 = __SMLAD(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = *(q31_t *) (px++); - - /* Read x[5], x[6] */ - x1 = *(q31_t *) (px++); - - /* acc2 += x[4] * y[2] + x[5] * y[3] */ - acc2 = __SMLAD(x0, c0, acc2); - - /* acc3 += x[5] * y[2] + x[6] * y[3] */ - acc3 = __SMLAD(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - py = (q15_t *) (pb); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[4] */ - c0 = *py; -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLADX(x1, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[4], y[5] */ - c0 = *(pb); - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLAD(x3, c0, acc2); - acc3 = __SMLAD(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[4], y[5] */ - c0 = *pb++; - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLAD(x3, c0, acc2); - acc3 = __SMLAD(x2, c0, acc3); - - /* Read y[6] */ -#ifdef ARM_MATH_BIG_ENDIAN - c0 = (*pb); - c0 = c0 & 0xFFFF0000; - -#else - c0 = (q15_t) (*pb); - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x1, c0, acc0); - acc1 = __SMLAD(x2, c0, acc1); - acc2 = __SMLADX(x2, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (acc0 >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q15_t) (acc1 >> 15); - pOut += inc; - - *pOut = (q15_t) (acc2 >> 15); - pOut += inc; - - *pOut = (q15_t) (acc3 >> 15); - pOut += inc; - - /* Increment the pointer pIn1 index, count by 1 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - pb = (q31_t *) (py); - - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen - srcBLen + 4] * y[3] , sum += x[srcALen - srcBLen + 3] * y[2] */ - sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - /* sum += x[srcALen - srcBLen + 2] * y[1] , sum += x[srcALen - srcBLen + 1] * y[0] */ - sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLAD(*px++, *py++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -} - -/** - * @} end of Corr group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_correlate_fast_q15.c +* +* Description: Fast Q15 Correlation. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup Corr + * @{ + */ + +/** + * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + * + * Scaling and Overflow Behavior: + * + * \par + * This fast version uses a 32-bit accumulator with 2.30 format. + * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * There is no saturation on intermediate additions. + * Thus, if the accumulator overflows it wraps around and distorts the result. + * The input signals should be scaled down to avoid intermediate overflows. + * Scale down one of the inputs by 1/min(srcALen, srcBLen) to avoid overflow since a + * maximum of min(srcALen, srcBLen) number of additions is carried internally. + * The 2.30 accumulator is right shifted by 15 bits and then saturated to 1.15 format to yield the final result. + * + * \par + * See arm_correlate_q15() for a slower implementation of this function which uses a 64-bit accumulator to avoid wrap around distortion. + */ + +void arm_correlate_fast_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst) +{ + q15_t *pIn1; /* inputA pointer */ + q15_t *pIn2; /* inputB pointer */ + q15_t *pOut = pDst; /* output pointer */ + q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ + q15_t *px; /* Intermediate inputA pointer */ + q15_t *py; /* Intermediate inputB pointer */ + q15_t *pSrc1; /* Intermediate pointers */ + q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ + uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ + int32_t inc = 1; /* Destination address modifier */ + q31_t *pb; /* 32 bit pointer for inputB buffer */ + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + /* But CORR(x, y) is reverse of CORR(y, x) */ + /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ + /* and the destination pointer modifier, inc is set to -1 */ + /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ + /* But to improve the performance, + * we include zeroes in the output instead of zero padding either of the the inputs*/ + /* If srcALen > srcBLen, + * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ + /* If srcALen < srcBLen, + * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = (pSrcA); + + /* Initialization of inputB pointer */ + pIn2 = (pSrcB); + + /* Number of output samples is calculated */ + outBlockSize = (2u * srcALen) - 1u; + + /* When srcALen > srcBLen, zero padding is done to srcB + * to make their lengths equal. + * Instead, (outBlockSize - (srcALen + srcBLen - 1)) + * number of output samples are made zero */ + j = outBlockSize - (srcALen + (srcBLen - 1u)); + + /* Updating the pointer position to non zero value */ + pOut += j; + + } + else + { + /* Initialization of inputA pointer */ + pIn1 = (pSrcB); + + /* Initialization of inputB pointer */ + pIn2 = (pSrcA); + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + + /* CORR(x, y) = Reverse order(CORR(y, x)) */ + /* Hence set the destination pointer to point to the last output sample */ + pOut = pDst + ((srcALen + srcBLen) - 2u); + + /* Destination address modifier is set to -1 */ + inc = -1; + + } + + /* The function is internally + * divided into three parts according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first part of the + * algorithm, the multiplications increase by one for every iteration. + * In the second part of the algorithm, srcBLen number of multiplications are done. + * In the third part of the algorithm, the multiplications decrease by one + * for every iteration.*/ + /* The algorithm is implemented in three stages. + * The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + blockSize3 = blockSize1; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[srcBlen - 1] + * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] + * .... + * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc1 = pIn2 + (srcBLen - 1u); + py = pSrc1; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first loop starts here */ + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 4] , x[1] * y[srcBLen - 3] */ + sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); + /* x[3] * y[srcBLen - 1] , x[2] * y[srcBLen - 2] */ + sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* x[0] * y[srcBLen - 1] */ + sum = __SMLAD(*px++, *py++, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q15_t) (sum >> 15); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pSrc1 - count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] + * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] + * .... + * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + /* Initialize inputB pointer of type q31 */ + pb = (q31_t *) (py); + + /* count is index by which the pointer pIn1 to be incremented */ + count = 0u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4, to loop unroll the srcBLen loop */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1] samples */ + x0 = *(q31_t *) (px++); + /* read x[1], x[2] samples */ + x1 = *(q31_t *) (px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read the first two inputB samples using SIMD: + * y[0] and y[1] */ + c0 = *(pb++); + + /* acc0 += x[0] * y[0] + x[1] * y[1] */ + acc0 = __SMLAD(x0, c0, acc0); + + /* acc1 += x[1] * y[0] + x[2] * y[1] */ + acc1 = __SMLAD(x1, c0, acc1); + + /* Read x[2], x[3] */ + x2 = *(q31_t *) (px++); + + /* Read x[3], x[4] */ + x3 = *(q31_t *) (px++); + + /* acc2 += x[2] * y[0] + x[3] * y[1] */ + acc2 = __SMLAD(x2, c0, acc2); + + /* acc3 += x[3] * y[0] + x[4] * y[1] */ + acc3 = __SMLAD(x3, c0, acc3); + + /* Read y[2] and y[3] */ + c0 = *(pb++); + + /* acc0 += x[2] * y[2] + x[3] * y[3] */ + acc0 = __SMLAD(x2, c0, acc0); + + /* acc1 += x[3] * y[2] + x[4] * y[3] */ + acc1 = __SMLAD(x3, c0, acc1); + + /* Read x[4], x[5] */ + x0 = *(q31_t *) (px++); + + /* Read x[5], x[6] */ + x1 = *(q31_t *) (px++); + + /* acc2 += x[4] * y[2] + x[5] * y[3] */ + acc2 = __SMLAD(x0, c0, acc2); + + /* acc3 += x[5] * y[2] + x[6] * y[3] */ + acc3 = __SMLAD(x1, c0, acc3); + + } while(--k); + + /* For the next MAC operations, SIMD is not used + * So, the 16 bit pointer if inputB, py is updated */ + py = (q15_t *) (pb); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + if(k == 1u) + { + /* Read y[4] */ + c0 = *py; +#ifdef ARM_MATH_BIG_ENDIAN + + c0 = c0 << 16u; + +#else + + c0 = c0 & 0x0000FFFF; + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + + /* Read x[7] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLAD(x0, c0, acc0); + acc1 = __SMLAD(x1, c0, acc1); + acc2 = __SMLADX(x1, c0, acc2); + acc3 = __SMLADX(x3, c0, acc3); + } + + if(k == 2u) + { + /* Read y[4], y[5] */ + c0 = *(pb); + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLAD(x0, c0, acc0); + acc1 = __SMLAD(x1, c0, acc1); + acc2 = __SMLAD(x3, c0, acc2); + acc3 = __SMLAD(x2, c0, acc3); + } + + if(k == 3u) + { + /* Read y[4], y[5] */ + c0 = *pb++; + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLAD(x0, c0, acc0); + acc1 = __SMLAD(x1, c0, acc1); + acc2 = __SMLAD(x3, c0, acc2); + acc3 = __SMLAD(x2, c0, acc3); + + /* Read y[6] */ +#ifdef ARM_MATH_BIG_ENDIAN + c0 = (*pb); + c0 = c0 & 0xFFFF0000; + +#else + c0 = (q15_t) (*pb); + c0 = c0 & 0x0000FFFF; + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + + /* Read x[10] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLADX(x1, c0, acc0); + acc1 = __SMLAD(x2, c0, acc1); + acc2 = __SMLADX(x2, c0, acc2); + acc3 = __SMLADX(x3, c0, acc3); + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q15_t) (acc0 >> 15); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + *pOut = (q15_t) (acc1 >> 15); + pOut += inc; + + *pOut = (q15_t) (acc2 >> 15); + pOut += inc; + + *pOut = (q15_t) (acc3 >> 15); + pOut += inc; + + /* Increment the pointer pIn1 index, count by 1 */ + count += 4u; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + pb = (q31_t *) (py); + + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q31_t) * px++ * *py++); + sum += ((q31_t) * px++ * *py++); + sum += ((q31_t) * px++ * *py++); + sum += ((q31_t) * px++ * *py++); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q31_t) * px++ * *py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q15_t) (sum >> 15); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Loop over srcBLen */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += ((q31_t) * px++ * *py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q15_t) (sum >> 15); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Increment the MAC count */ + count++; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * .... + * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] + * sum += x[srcALen-1] * y[0] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + py = pIn2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen - srcBLen + 4] * y[3] , sum += x[srcALen - srcBLen + 3] * y[2] */ + sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); + /* sum += x[srcALen - srcBLen + 2] * y[1] , sum += x[srcALen - srcBLen + 1] * y[0] */ + sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = __SMLAD(*px++, *py++, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q15_t) (sum >> 15); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pIn2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + } + +} + +/** + * @} end of Corr group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q31.c index 34cd3f4a4..62d35dd25 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q31.c @@ -1,599 +1,599 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_fast_q31.c -* -* Description: Fast Q31 Correlation. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * This function is optimized for speed at the expense of fixed-point precision and overflow protection. - * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. - * These intermediate results are accumulated in a 32-bit register in 2.30 format. - * Finally, the accumulator is saturated and converted to a 1.31 result. - * - * \par - * The fast version has the same overflow behavior as the standard version but provides less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signals must be scaled down. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down one of the inputs by 1/min(srcALen, srcBLen)to avoid overflows since a - * maximum of min(srcALen, srcBLen) number of additions is carried internally. - * - * \par - * See arm_correlate_q31() for a slower implementation of this function which uses 64-bit accumulation to provide higher precision. - */ - -void arm_correlate_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst) -{ - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1; /* Intermediate pointers */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; /* Destination address modifier */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* x[1] * y[srcBLen - 3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* x[2] * y[srcBLen - 2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* x[3] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum << 1; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[0] sample */ - c0 = *(py++); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[0] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc1 += x[1] * y[0] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc2 += x[2] * y[0] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc3 += x[3] * y[0] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Read y[1] sample */ - c0 = *(py++); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[1] * y[1] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc1 += x[2] * y[1] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc2 += x[3] * y[1] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc3 += x[4] * y[1] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Read y[2] sample */ - c0 = *(py++); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[2] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc1 += x[3] * y[2] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc2 += x[4] * y[2] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc3 += x[5] * y[2] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Read y[3] sample */ - c0 = *(py++); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[3] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc1 += x[4] * y[3] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc2 += x[5] * y[3] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc3 += x[6] * y[3] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x2 * c0)) >> 32); - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[4] sample */ - c0 = *(py++); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[4] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc1 += x[5] * y[4] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc2 += x[6] * y[4] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc3 += x[7] * y[4] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (acc0 << 1); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q31_t) (acc1 << 1); - pOut += inc; - - *pOut = (q31_t) (acc2 << 1); - pOut += inc; - - *pOut = (q31_t) (acc3 << 1); - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pIn2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum << 1; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum << 1; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = ((pIn1 + srcALen) - srcBLen) + 1u; - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen - srcBLen + 4] * y[3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* sum += x[srcALen - srcBLen + 3] * y[2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* sum += x[srcALen - srcBLen + 2] * y[1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* sum += x[srcALen - srcBLen + 1] * y[0] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum << 1; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -} - -/** - * @} end of Corr group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_correlate_fast_q31.c +* +* Description: Fast Q31 Correlation. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup Corr + * @{ + */ + +/** + * @brief Correlation of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * This function is optimized for speed at the expense of fixed-point precision and overflow protection. + * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. + * These intermediate results are accumulated in a 32-bit register in 2.30 format. + * Finally, the accumulator is saturated and converted to a 1.31 result. + * + * \par + * The fast version has the same overflow behavior as the standard version but provides less precision since it discards the low 32 bits of each multiplication result. + * In order to avoid overflows completely the input signals must be scaled down. + * The input signals should be scaled down to avoid intermediate overflows. + * Scale down one of the inputs by 1/min(srcALen, srcBLen)to avoid overflows since a + * maximum of min(srcALen, srcBLen) number of additions is carried internally. + * + * \par + * See arm_correlate_q31() for a slower implementation of this function which uses 64-bit accumulation to provide higher precision. + */ + +void arm_correlate_fast_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst) +{ + q31_t *pIn1; /* inputA pointer */ + q31_t *pIn2; /* inputB pointer */ + q31_t *pOut = pDst; /* output pointer */ + q31_t *px; /* Intermediate inputA pointer */ + q31_t *py; /* Intermediate inputB pointer */ + q31_t *pSrc1; /* Intermediate pointers */ + q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ + q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ + uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ + int32_t inc = 1; /* Destination address modifier */ + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = (pSrcA); + + /* Initialization of inputB pointer */ + pIn2 = (pSrcB); + + /* Number of output samples is calculated */ + outBlockSize = (2u * srcALen) - 1u; + + /* When srcALen > srcBLen, zero padding is done to srcB + * to make their lengths equal. + * Instead, (outBlockSize - (srcALen + srcBLen - 1)) + * number of output samples are made zero */ + j = outBlockSize - (srcALen + (srcBLen - 1u)); + + /* Updating the pointer position to non zero value */ + pOut += j; + + } + else + { + /* Initialization of inputA pointer */ + pIn1 = (pSrcB); + + /* Initialization of inputB pointer */ + pIn2 = (pSrcA); + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + + /* CORR(x, y) = Reverse order(CORR(y, x)) */ + /* Hence set the destination pointer to point to the last output sample */ + pOut = pDst + ((srcALen + srcBLen) - 2u); + + /* Destination address modifier is set to -1 */ + inc = -1; + + } + + /* The function is internally + * divided into three parts according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first part of the + * algorithm, the multiplications increase by one for every iteration. + * In the second part of the algorithm, srcBLen number of multiplications are done. + * In the third part of the algorithm, the multiplications decrease by one + * for every iteration.*/ + /* The algorithm is implemented in three stages. + * The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + blockSize3 = blockSize1; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[srcBlen - 1] + * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] + * .... + * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc1 = pIn2 + (srcBLen - 1u); + py = pSrc1; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first stage starts here */ + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 4] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + /* x[1] * y[srcBLen - 3] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + /* x[2] * y[srcBLen - 2] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + /* x[3] * y[srcBLen - 1] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* x[0] * y[srcBLen - 1] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = sum << 1; + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pSrc1 - count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] + * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] + * .... + * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[0] sample */ + c0 = *(py++); + + /* Read x[3] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[0] * y[0] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); + /* acc1 += x[1] * y[0] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); + /* acc2 += x[2] * y[0] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); + /* acc3 += x[3] * y[0] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); + + /* Read y[1] sample */ + c0 = *(py++); + + /* Read x[4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[1] * y[1] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x1 * c0)) >> 32); + /* acc1 += x[2] * y[1] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x2 * c0)) >> 32); + /* acc2 += x[3] * y[1] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x3 * c0)) >> 32); + /* acc3 += x[4] * y[1] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x0 * c0)) >> 32); + + /* Read y[2] sample */ + c0 = *(py++); + + /* Read x[5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[2] * y[2] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x2 * c0)) >> 32); + /* acc1 += x[3] * y[2] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x3 * c0)) >> 32); + /* acc2 += x[4] * y[2] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x0 * c0)) >> 32); + /* acc3 += x[5] * y[2] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x1 * c0)) >> 32); + + /* Read y[3] sample */ + c0 = *(py++); + + /* Read x[6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[3] * y[3] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x3 * c0)) >> 32); + /* acc1 += x[4] * y[3] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x0 * c0)) >> 32); + /* acc2 += x[5] * y[3] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x1 * c0)) >> 32); + /* acc3 += x[6] * y[3] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x2 * c0)) >> 32); + + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[4] sample */ + c0 = *(py++); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[4] */ + acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); + /* acc1 += x[5] * y[4] */ + acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); + /* acc2 += x[6] * y[4] */ + acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); + /* acc3 += x[7] * y[4] */ + acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q31_t) (acc0 << 1); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + *pOut = (q31_t) (acc1 << 1); + pOut += inc; + + *pOut = (q31_t) (acc2 << 1); + pOut += inc; + + *pOut = (q31_t) (acc3 << 1); + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pIn2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = sum << 1; + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Loop over srcBLen */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = sum << 1; + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * .... + * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] + * sum += x[srcALen-1] * y[0] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = ((pIn1 + srcALen) - srcBLen) + 1u; + px = pSrc1; + + /* Working pointer of inputB */ + py = pIn2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen - srcBLen + 4] * y[3] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + /* sum += x[srcALen - srcBLen + 3] * y[2] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + /* sum += x[srcALen - srcBLen + 2] * y[1] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + /* sum += x[srcALen - srcBLen + 1] * y[0] */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * px++ * (*py++))) >> 32); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = sum << 1; + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pIn2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + } + +} + +/** + * @} end of Corr group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q15.c index a10c1bc51..424cc3185 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q15.c @@ -1,714 +1,714 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_q15.c -* -* Description: Correlation of Q15 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both inputs are in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * This approach provides 33 guard bits and there is no risk of overflow. - * The 34.30 result is then truncated to 34.15 format by discarding the low 15 bits and then saturated to 1.15 format. - * - * \par - * Refer to arm_correlate_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - */ - -void arm_correlate_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q63_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; /* Destination address modifier */ - q31_t *pb; /* 32 bit pointer for inputB buffer */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first loop starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] , x[1] * y[srcBLen - 3] */ - sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - /* x[3] * y[srcBLen - 1] , x[2] * y[srcBLen - 2] */ - sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum = __SMLALD(*px++, *py++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT((sum >> 15), 16)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* Initialize inputB pointer of type q31 */ - pb = (q31_t *) (py); - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4, to loop unroll the srcBLen loop */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1] samples */ - x0 = *(q31_t *) (px++); - /* read x[1], x[2] samples */ - x1 = *(q31_t *) (px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the first two inputB samples using SIMD: - * y[0] and y[1] */ - c0 = *(pb++); - - /* acc0 += x[0] * y[0] + x[1] * y[1] */ - acc0 = __SMLALD(x0, c0, acc0); - - /* acc1 += x[1] * y[0] + x[2] * y[1] */ - acc1 = __SMLALD(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *(q31_t *) (px++); - - /* Read x[3], x[4] */ - x3 = *(q31_t *) (px++); - - /* acc2 += x[2] * y[0] + x[3] * y[1] */ - acc2 = __SMLALD(x2, c0, acc2); - - /* acc3 += x[3] * y[0] + x[4] * y[1] */ - acc3 = __SMLALD(x3, c0, acc3); - - /* Read y[2] and y[3] */ - c0 = *(pb++); - - /* acc0 += x[2] * y[2] + x[3] * y[3] */ - acc0 = __SMLALD(x2, c0, acc0); - - /* acc1 += x[3] * y[2] + x[4] * y[3] */ - acc1 = __SMLALD(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = *(q31_t *) (px++); - - /* Read x[5], x[6] */ - x1 = *(q31_t *) (px++); - - /* acc2 += x[4] * y[2] + x[5] * y[3] */ - acc2 = __SMLALD(x0, c0, acc2); - - /* acc3 += x[5] * y[2] + x[6] * y[3] */ - acc3 = __SMLALD(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - py = (q15_t *) (pb); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[4] */ - c0 = *py; -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - /* Read x[7] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALDX(x1, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[4], y[5] */ - c0 = *(pb); - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALD(x3, c0, acc2); - acc3 = __SMLALD(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[4], y[5] */ - c0 = *pb++; - - /* Read x[7], x[8] */ - x3 = *(q31_t *) px++; - - /* Read x[9] */ - x2 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALD(x3, c0, acc2); - acc3 = __SMLALD(x2, c0, acc3); - - /* Read y[6] */ -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = (*pb); - c0 = c0 & 0xFFFF0000; - -#else - - c0 = (q15_t) (*pb); - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - /* Read x[10] */ - x3 = *(q31_t *) px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x1, c0, acc0); - acc1 = __SMLALD(x2, c0, acc1); - acc2 = __SMLALDX(x2, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT(acc0 >> 15, 16)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q15_t) (__SSAT(acc1 >> 15, 16)); - pOut += inc; - - *pOut = (q15_t) (__SSAT(acc2 >> 15, 16)); - pOut += inc; - - *pOut = (q15_t) (__SSAT(acc3 >> 15, 16)); - pOut += inc; - - /* Increment the count by 4 as 4 output values are computed */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - pb = (q31_t *) (py); - - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q63_t) * px++ * *py++); - sum += ((q63_t) * px++ * *py++); - sum += ((q63_t) * px++ * *py++); - sum += ((q63_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q63_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT(sum >> 15, 16)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment count by 1, as one output value is computed */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q63_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT(sum >> 15, 16)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen - srcBLen + 4] * y[3] , sum += x[srcALen - srcBLen + 3] * y[2] */ - sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - /* sum += x[srcALen - srcBLen + 2] * y[1] , sum += x[srcALen - srcBLen + 1] * y[0] */ - sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLALD(*px++, *py++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT((sum >> 15), 16)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - q15_t *pIn1 = pSrcA; /* inputA pointer */ - q15_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ - q63_t sum; /* Accumulators */ - uint32_t i = 0u, j; /* loop counters */ - uint32_t inv = 0u; /* Reverse order flag */ - uint32_t tot = 0u; /* Length */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and a varaible, inv is set to 1 */ - /* If lengths are not equal then zero pad has to be done to make the two - * inputs of same length. But to improve the performance, we include zeroes - * in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the - * starting of the output buffer */ - /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the - * ending of the output buffer */ - /* Once the zero padding is done the remaining of the output is calcualted - * using convolution but with the shorter signal time shifted. */ - - /* Calculate the length of the remaining sequence */ - tot = ((srcALen + srcBLen) - 2u); - - if(srcALen > srcBLen) - { - /* Calculating the number of zeros to be padded to the output */ - j = srcALen - srcBLen; - - /* Initialise the pointer after zero padding */ - pDst += j; - } - - else if(srcALen < srcBLen) - { - /* Initialization to inputB pointer */ - pIn1 = pSrcB; - - /* Initialization to the end of inputA pointer */ - pIn2 = pSrcA + (srcALen - 1u); - - /* Initialisation of the pointer after zero padding */ - pDst = pDst + tot; - - /* Swapping the lengths */ - j = srcALen; - srcALen = srcBLen; - srcBLen = j; - - /* Setting the reverse flag */ - inv = 1; - - } - - /* Loop to calculate convolution for output length number of times */ - for (i = 0u; i <= tot; i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q31_t) pIn1[j] * pIn2[-((int32_t) i - j)]); - } - } - /* Store the output in the destination buffer */ - if(inv == 1) - *pDst-- = (q15_t) __SSAT((sum >> 15u), 16u); - else - *pDst++ = (q15_t) __SSAT((sum >> 15u), 16u); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Corr group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_correlate_q15.c +* +* Description: Correlation of Q15 sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup Corr + * @{ + */ + +/** + * @brief Correlation of Q15 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 64-bit internal accumulator. + * Both inputs are in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + * This approach provides 33 guard bits and there is no risk of overflow. + * The 34.30 result is then truncated to 34.15 format by discarding the low 15 bits and then saturated to 1.15 format. + * + * \par + * Refer to arm_correlate_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. + */ + +void arm_correlate_q15( + q15_t * pSrcA, + uint32_t srcALen, + q15_t * pSrcB, + uint32_t srcBLen, + q15_t * pDst) +{ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t *pIn1; /* inputA pointer */ + q15_t *pIn2; /* inputB pointer */ + q15_t *pOut = pDst; /* output pointer */ + q63_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ + q15_t *px; /* Intermediate inputA pointer */ + q15_t *py; /* Intermediate inputB pointer */ + q15_t *pSrc1; /* Intermediate pointers */ + q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ + uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ + int32_t inc = 1; /* Destination address modifier */ + q31_t *pb; /* 32 bit pointer for inputB buffer */ + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + /* But CORR(x, y) is reverse of CORR(y, x) */ + /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ + /* and the destination pointer modifier, inc is set to -1 */ + /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ + /* But to improve the performance, + * we include zeroes in the output instead of zero padding either of the the inputs*/ + /* If srcALen > srcBLen, + * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ + /* If srcALen < srcBLen, + * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = (pSrcA); + + /* Initialization of inputB pointer */ + pIn2 = (pSrcB); + + /* Number of output samples is calculated */ + outBlockSize = (2u * srcALen) - 1u; + + /* When srcALen > srcBLen, zero padding is done to srcB + * to make their lengths equal. + * Instead, (outBlockSize - (srcALen + srcBLen - 1)) + * number of output samples are made zero */ + j = outBlockSize - (srcALen + (srcBLen - 1u)); + + /* Updating the pointer position to non zero value */ + pOut += j; + + } + else + { + /* Initialization of inputA pointer */ + pIn1 = (pSrcB); + + /* Initialization of inputB pointer */ + pIn2 = (pSrcA); + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + + /* CORR(x, y) = Reverse order(CORR(y, x)) */ + /* Hence set the destination pointer to point to the last output sample */ + pOut = pDst + ((srcALen + srcBLen) - 2u); + + /* Destination address modifier is set to -1 */ + inc = -1; + + } + + /* The function is internally + * divided into three parts according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first part of the + * algorithm, the multiplications increase by one for every iteration. + * In the second part of the algorithm, srcBLen number of multiplications are done. + * In the third part of the algorithm, the multiplications decrease by one + * for every iteration.*/ + /* The algorithm is implemented in three stages. + * The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + blockSize3 = blockSize1; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[srcBlen - 1] + * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] + * .... + * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc1 = pIn2 + (srcBLen - 1u); + py = pSrc1; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first loop starts here */ + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 4] , x[1] * y[srcBLen - 3] */ + sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); + /* x[3] * y[srcBLen - 1] , x[2] * y[srcBLen - 2] */ + sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* x[0] * y[srcBLen - 1] */ + sum = __SMLALD(*px++, *py++, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q15_t) (__SSAT((sum >> 15), 16)); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pSrc1 - count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] + * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] + * .... + * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + /* Initialize inputB pointer of type q31 */ + pb = (q31_t *) (py); + + /* count is index by which the pointer pIn1 to be incremented */ + count = 0u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4, to loop unroll the srcBLen loop */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1] samples */ + x0 = *(q31_t *) (px++); + /* read x[1], x[2] samples */ + x1 = *(q31_t *) (px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read the first two inputB samples using SIMD: + * y[0] and y[1] */ + c0 = *(pb++); + + /* acc0 += x[0] * y[0] + x[1] * y[1] */ + acc0 = __SMLALD(x0, c0, acc0); + + /* acc1 += x[1] * y[0] + x[2] * y[1] */ + acc1 = __SMLALD(x1, c0, acc1); + + /* Read x[2], x[3] */ + x2 = *(q31_t *) (px++); + + /* Read x[3], x[4] */ + x3 = *(q31_t *) (px++); + + /* acc2 += x[2] * y[0] + x[3] * y[1] */ + acc2 = __SMLALD(x2, c0, acc2); + + /* acc3 += x[3] * y[0] + x[4] * y[1] */ + acc3 = __SMLALD(x3, c0, acc3); + + /* Read y[2] and y[3] */ + c0 = *(pb++); + + /* acc0 += x[2] * y[2] + x[3] * y[3] */ + acc0 = __SMLALD(x2, c0, acc0); + + /* acc1 += x[3] * y[2] + x[4] * y[3] */ + acc1 = __SMLALD(x3, c0, acc1); + + /* Read x[4], x[5] */ + x0 = *(q31_t *) (px++); + + /* Read x[5], x[6] */ + x1 = *(q31_t *) (px++); + + /* acc2 += x[4] * y[2] + x[5] * y[3] */ + acc2 = __SMLALD(x0, c0, acc2); + + /* acc3 += x[5] * y[2] + x[6] * y[3] */ + acc3 = __SMLALD(x1, c0, acc3); + + } while(--k); + + /* For the next MAC operations, SIMD is not used + * So, the 16 bit pointer if inputB, py is updated */ + py = (q15_t *) (pb); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + if(k == 1u) + { + /* Read y[4] */ + c0 = *py; +#ifdef ARM_MATH_BIG_ENDIAN + + c0 = c0 << 16u; + +#else + + c0 = c0 & 0x0000FFFF; + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + /* Read x[7] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALD(x0, c0, acc0); + acc1 = __SMLALD(x1, c0, acc1); + acc2 = __SMLALDX(x1, c0, acc2); + acc3 = __SMLALDX(x3, c0, acc3); + } + + if(k == 2u) + { + /* Read y[4], y[5] */ + c0 = *(pb); + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALD(x0, c0, acc0); + acc1 = __SMLALD(x1, c0, acc1); + acc2 = __SMLALD(x3, c0, acc2); + acc3 = __SMLALD(x2, c0, acc3); + } + + if(k == 3u) + { + /* Read y[4], y[5] */ + c0 = *pb++; + + /* Read x[7], x[8] */ + x3 = *(q31_t *) px++; + + /* Read x[9] */ + x2 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALD(x0, c0, acc0); + acc1 = __SMLALD(x1, c0, acc1); + acc2 = __SMLALD(x3, c0, acc2); + acc3 = __SMLALD(x2, c0, acc3); + + /* Read y[6] */ +#ifdef ARM_MATH_BIG_ENDIAN + + c0 = (*pb); + c0 = c0 & 0xFFFF0000; + +#else + + c0 = (q15_t) (*pb); + c0 = c0 & 0x0000FFFF; + +#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ + /* Read x[10] */ + x3 = *(q31_t *) px++; + + /* Perform the multiply-accumulates */ + acc0 = __SMLALDX(x1, c0, acc0); + acc1 = __SMLALD(x2, c0, acc1); + acc2 = __SMLALDX(x2, c0, acc2); + acc3 = __SMLALDX(x3, c0, acc3); + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q15_t) (__SSAT(acc0 >> 15, 16)); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + *pOut = (q15_t) (__SSAT(acc1 >> 15, 16)); + pOut += inc; + + *pOut = (q15_t) (__SSAT(acc2 >> 15, 16)); + pOut += inc; + + *pOut = (q15_t) (__SSAT(acc3 >> 15, 16)); + pOut += inc; + + /* Increment the count by 4 as 4 output values are computed */ + count += 4u; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + pb = (q31_t *) (py); + + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q63_t) * px++ * *py++); + sum += ((q63_t) * px++ * *py++); + sum += ((q63_t) * px++ * *py++); + sum += ((q63_t) * px++ * *py++); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q63_t) * px++ * *py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q15_t) (__SSAT(sum >> 15, 16)); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Increment count by 1, as one output value is computed */ + count++; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Loop over srcBLen */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += ((q63_t) * px++ * *py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q15_t) (__SSAT(sum >> 15, 16)); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Increment the MAC count */ + count++; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * .... + * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] + * sum += x[srcALen-1] * y[0] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); + px = pSrc1; + + /* Working pointer of inputB */ + py = pIn2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen - srcBLen + 4] * y[3] , sum += x[srcALen - srcBLen + 3] * y[2] */ + sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); + /* sum += x[srcALen - srcBLen + 2] * y[1] , sum += x[srcALen - srcBLen + 1] * y[0] */ + sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum = __SMLALD(*px++, *py++, sum); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q15_t) (__SSAT((sum >> 15), 16)); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pIn2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + } + +#else + +/* Run the below code for Cortex-M0 */ + + q15_t *pIn1 = pSrcA; /* inputA pointer */ + q15_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ + q63_t sum; /* Accumulators */ + uint32_t i = 0u, j; /* loop counters */ + uint32_t inv = 0u; /* Reverse order flag */ + uint32_t tot = 0u; /* Length */ + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + /* But CORR(x, y) is reverse of CORR(y, x) */ + /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ + /* and a varaible, inv is set to 1 */ + /* If lengths are not equal then zero pad has to be done to make the two + * inputs of same length. But to improve the performance, we include zeroes + * in the output instead of zero padding either of the the inputs*/ + /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the + * starting of the output buffer */ + /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the + * ending of the output buffer */ + /* Once the zero padding is done the remaining of the output is calcualted + * using convolution but with the shorter signal time shifted. */ + + /* Calculate the length of the remaining sequence */ + tot = ((srcALen + srcBLen) - 2u); + + if(srcALen > srcBLen) + { + /* Calculating the number of zeros to be padded to the output */ + j = srcALen - srcBLen; + + /* Initialise the pointer after zero padding */ + pDst += j; + } + + else if(srcALen < srcBLen) + { + /* Initialization to inputB pointer */ + pIn1 = pSrcB; + + /* Initialization to the end of inputA pointer */ + pIn2 = pSrcA + (srcALen - 1u); + + /* Initialisation of the pointer after zero padding */ + pDst = pDst + tot; + + /* Swapping the lengths */ + j = srcALen; + srcALen = srcBLen; + srcBLen = j; + + /* Setting the reverse flag */ + inv = 1; + + } + + /* Loop to calculate convolution for output length number of times */ + for (i = 0u; i <= tot; i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0u; j <= i; j++) + { + /* Check the array limitations */ + if((((i - j) < srcBLen) && (j < srcALen))) + { + /* z[i] += x[i-j] * y[j] */ + sum += ((q31_t) pIn1[j] * pIn2[-((int32_t) i - j)]); + } + } + /* Store the output in the destination buffer */ + if(inv == 1) + *pDst-- = (q15_t) __SSAT((sum >> 15u), 16u); + else + *pDst++ = (q15_t) __SSAT((sum >> 15u), 16u); + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of Corr group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q31.c index 49de78702..df1a457fe 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q31.c @@ -1,683 +1,683 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_q31.c -* -* Description: Correlation of Q31 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q31 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * There is no saturation on intermediate additions. - * Thus, if the accumulator overflows it wraps around and distorts the result. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down one of the inputs by 1/min(srcALen, srcBLen)to avoid overflows since a - * maximum of min(srcALen, srcBLen) number of additions is carried internally. - * The 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. - * - * \par - * See arm_correlate_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -void arm_correlate_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1; /* Intermediate pointers */ - q63_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; /* Destination address modifier */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] */ - sum += (q63_t) * px++ * (*py++); - /* x[1] * y[srcBLen - 3] */ - sum += (q63_t) * px++ * (*py++); - /* x[2] * y[srcBLen - 2] */ - sum += (q63_t) * px++ * (*py++); - /* x[3] * y[srcBLen - 1] */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (sum >> 31); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[0] sample */ - c0 = *(py++); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[0] */ - acc0 += ((q63_t) x0 * c0); - /* acc1 += x[1] * y[0] */ - acc1 += ((q63_t) x1 * c0); - /* acc2 += x[2] * y[0] */ - acc2 += ((q63_t) x2 * c0); - /* acc3 += x[3] * y[0] */ - acc3 += ((q63_t) x3 * c0); - - /* Read y[1] sample */ - c0 = *(py++); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[1] * y[1] */ - acc0 += ((q63_t) x1 * c0); - /* acc1 += x[2] * y[1] */ - acc1 += ((q63_t) x2 * c0); - /* acc2 += x[3] * y[1] */ - acc2 += ((q63_t) x3 * c0); - /* acc3 += x[4] * y[1] */ - acc3 += ((q63_t) x0 * c0); - /* Read y[2] sample */ - c0 = *(py++); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[2] */ - acc0 += ((q63_t) x2 * c0); - /* acc1 += x[3] * y[2] */ - acc1 += ((q63_t) x3 * c0); - /* acc2 += x[4] * y[2] */ - acc2 += ((q63_t) x0 * c0); - /* acc3 += x[5] * y[2] */ - acc3 += ((q63_t) x1 * c0); - - /* Read y[3] sample */ - c0 = *(py++); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[3] */ - acc0 += ((q63_t) x3 * c0); - /* acc1 += x[4] * y[3] */ - acc1 += ((q63_t) x0 * c0); - /* acc2 += x[5] * y[3] */ - acc2 += ((q63_t) x1 * c0); - /* acc3 += x[6] * y[3] */ - acc3 += ((q63_t) x2 * c0); - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[4] sample */ - c0 = *(py++); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[4] */ - acc0 += ((q63_t) x0 * c0); - /* acc1 += x[5] * y[4] */ - acc1 += ((q63_t) x1 * c0); - /* acc2 += x[6] * y[4] */ - acc2 += ((q63_t) x2 * c0); - /* acc3 += x[7] * y[4] */ - acc3 += ((q63_t) x3 * c0); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (acc0 >> 31); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q31_t) (acc1 >> 31); - pOut += inc; - - *pOut = (q31_t) (acc2 >> 31); - pOut += inc; - - *pOut = (q31_t) (acc3 >> 31); - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pIn2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) * px++ * (*py++); - sum += (q63_t) * px++ * (*py++); - sum += (q63_t) * px++ * (*py++); - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (sum >> 31); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (sum >> 31); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen - srcBLen + 4] * y[3] */ - sum += (q63_t) * px++ * (*py++); - /* sum += x[srcALen - srcBLen + 3] * y[2] */ - sum += (q63_t) * px++ * (*py++); - /* sum += x[srcALen - srcBLen + 2] * y[1] */ - sum += (q63_t) * px++ * (*py++); - /* sum += x[srcALen - srcBLen + 1] * y[0] */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (sum >> 31); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t *pIn1 = pSrcA; /* inputA pointer */ - q31_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ - q63_t sum; /* Accumulators */ - uint32_t i = 0u, j; /* loop counters */ - uint32_t inv = 0u; /* Reverse order flag */ - uint32_t tot = 0u; /* Length */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and a varaible, inv is set to 1 */ - /* If lengths are not equal then zero pad has to be done to make the two - * inputs of same length. But to improve the performance, we include zeroes - * in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the - * starting of the output buffer */ - /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the - * ending of the output buffer */ - /* Once the zero padding is done the remaining of the output is calcualted - * using convolution but with the shorter signal time shifted. */ - - /* Calculate the length of the remaining sequence */ - tot = ((srcALen + srcBLen) - 2u); - - if(srcALen > srcBLen) - { - /* Calculating the number of zeros to be padded to the output */ - j = srcALen - srcBLen; - - /* Initialise the pointer after zero padding */ - pDst += j; - } - - else if(srcALen < srcBLen) - { - /* Initialization to inputB pointer */ - pIn1 = pSrcB; - - /* Initialization to the end of inputA pointer */ - pIn2 = pSrcA + (srcALen - 1u); - - /* Initialisation of the pointer after zero padding */ - pDst = pDst + tot; - - /* Swapping the lengths */ - j = srcALen; - srcALen = srcBLen; - srcBLen = j; - - /* Setting the reverse flag */ - inv = 1; - - } - - /* Loop to calculate convolution for output length number of times */ - for (i = 0u; i <= tot; i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q63_t) pIn1[j] * pIn2[-((int32_t) i - j)]); - } - } - /* Store the output in the destination buffer */ - if(inv == 1) - *pDst-- = (q31_t) (sum >> 31u); - else - *pDst++ = (q31_t) (sum >> 31u); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Corr group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_correlate_q31.c +* +* Description: Correlation of Q31 sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup Corr + * @{ + */ + +/** + * @brief Correlation of Q31 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * There is no saturation on intermediate additions. + * Thus, if the accumulator overflows it wraps around and distorts the result. + * The input signals should be scaled down to avoid intermediate overflows. + * Scale down one of the inputs by 1/min(srcALen, srcBLen)to avoid overflows since a + * maximum of min(srcALen, srcBLen) number of additions is carried internally. + * The 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. + * + * \par + * See arm_correlate_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. + */ + +void arm_correlate_q31( + q31_t * pSrcA, + uint32_t srcALen, + q31_t * pSrcB, + uint32_t srcBLen, + q31_t * pDst) +{ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t *pIn1; /* inputA pointer */ + q31_t *pIn2; /* inputB pointer */ + q31_t *pOut = pDst; /* output pointer */ + q31_t *px; /* Intermediate inputA pointer */ + q31_t *py; /* Intermediate inputB pointer */ + q31_t *pSrc1; /* Intermediate pointers */ + q63_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ + q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ + uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ + int32_t inc = 1; /* Destination address modifier */ + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + /* But CORR(x, y) is reverse of CORR(y, x) */ + /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ + /* and the destination pointer modifier, inc is set to -1 */ + /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ + /* But to improve the performance, + * we include zeroes in the output instead of zero padding either of the the inputs*/ + /* If srcALen > srcBLen, + * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ + /* If srcALen < srcBLen, + * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = (pSrcA); + + /* Initialization of inputB pointer */ + pIn2 = (pSrcB); + + /* Number of output samples is calculated */ + outBlockSize = (2u * srcALen) - 1u; + + /* When srcALen > srcBLen, zero padding is done to srcB + * to make their lengths equal. + * Instead, (outBlockSize - (srcALen + srcBLen - 1)) + * number of output samples are made zero */ + j = outBlockSize - (srcALen + (srcBLen - 1u)); + + /* Updating the pointer position to non zero value */ + pOut += j; + + } + else + { + /* Initialization of inputA pointer */ + pIn1 = (pSrcB); + + /* Initialization of inputB pointer */ + pIn2 = (pSrcA); + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + + /* CORR(x, y) = Reverse order(CORR(y, x)) */ + /* Hence set the destination pointer to point to the last output sample */ + pOut = pDst + ((srcALen + srcBLen) - 2u); + + /* Destination address modifier is set to -1 */ + inc = -1; + + } + + /* The function is internally + * divided into three parts according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first part of the + * algorithm, the multiplications increase by one for every iteration. + * In the second part of the algorithm, srcBLen number of multiplications are done. + * In the third part of the algorithm, the multiplications decrease by one + * for every iteration.*/ + /* The algorithm is implemented in three stages. + * The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + blockSize3 = blockSize1; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[srcBlen - 1] + * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] + * .... + * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc1 = pIn2 + (srcBLen - 1u); + py = pSrc1; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first stage starts here */ + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] * y[srcBLen - 4] */ + sum += (q63_t) * px++ * (*py++); + /* x[1] * y[srcBLen - 3] */ + sum += (q63_t) * px++ * (*py++); + /* x[2] * y[srcBLen - 2] */ + sum += (q63_t) * px++ * (*py++); + /* x[3] * y[srcBLen - 1] */ + sum += (q63_t) * px++ * (*py++); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* x[0] * y[srcBLen - 1] */ + sum += (q63_t) * px++ * (*py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q31_t) (sum >> 31); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pSrc1 - count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] + * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] + * .... + * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1], x[2] samples */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[0] sample */ + c0 = *(py++); + + /* Read x[3] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulate */ + /* acc0 += x[0] * y[0] */ + acc0 += ((q63_t) x0 * c0); + /* acc1 += x[1] * y[0] */ + acc1 += ((q63_t) x1 * c0); + /* acc2 += x[2] * y[0] */ + acc2 += ((q63_t) x2 * c0); + /* acc3 += x[3] * y[0] */ + acc3 += ((q63_t) x3 * c0); + + /* Read y[1] sample */ + c0 = *(py++); + + /* Read x[4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[1] * y[1] */ + acc0 += ((q63_t) x1 * c0); + /* acc1 += x[2] * y[1] */ + acc1 += ((q63_t) x2 * c0); + /* acc2 += x[3] * y[1] */ + acc2 += ((q63_t) x3 * c0); + /* acc3 += x[4] * y[1] */ + acc3 += ((q63_t) x0 * c0); + /* Read y[2] sample */ + c0 = *(py++); + + /* Read x[5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[2] * y[2] */ + acc0 += ((q63_t) x2 * c0); + /* acc1 += x[3] * y[2] */ + acc1 += ((q63_t) x3 * c0); + /* acc2 += x[4] * y[2] */ + acc2 += ((q63_t) x0 * c0); + /* acc3 += x[5] * y[2] */ + acc3 += ((q63_t) x1 * c0); + + /* Read y[3] sample */ + c0 = *(py++); + + /* Read x[6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[3] * y[3] */ + acc0 += ((q63_t) x3 * c0); + /* acc1 += x[4] * y[3] */ + acc1 += ((q63_t) x0 * c0); + /* acc2 += x[5] * y[3] */ + acc2 += ((q63_t) x1 * c0); + /* acc3 += x[6] * y[3] */ + acc3 += ((q63_t) x2 * c0); + + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[4] sample */ + c0 = *(py++); + + /* Read x[7] sample */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[4] */ + acc0 += ((q63_t) x0 * c0); + /* acc1 += x[5] * y[4] */ + acc1 += ((q63_t) x1 * c0); + /* acc2 += x[6] * y[4] */ + acc2 += ((q63_t) x2 * c0); + /* acc3 += x[7] * y[4] */ + acc3 += ((q63_t) x3 * c0); + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q31_t) (acc0 >> 31); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + *pOut = (q31_t) (acc1 >> 31); + pOut += inc; + + *pOut = (q31_t) (acc2 >> 31); + pOut += inc; + + *pOut = (q31_t) (acc3 >> 31); + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pIn2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += (q63_t) * px++ * (*py++); + sum += (q63_t) * px++ * (*py++); + sum += (q63_t) * px++ * (*py++); + sum += (q63_t) * px++ * (*py++); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) * px++ * (*py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q31_t) (sum >> 31); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Loop over srcBLen */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += (q63_t) * px++ * (*py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q31_t) (sum >> 31); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * .... + * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] + * sum += x[srcALen-1] * y[0] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); + px = pSrc1; + + /* Working pointer of inputB */ + py = pIn2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* sum += x[srcALen - srcBLen + 4] * y[3] */ + sum += (q63_t) * px++ * (*py++); + /* sum += x[srcALen - srcBLen + 3] * y[2] */ + sum += (q63_t) * px++ * (*py++); + /* sum += x[srcALen - srcBLen + 2] * y[1] */ + sum += (q63_t) * px++ * (*py++); + /* sum += x[srcALen - srcBLen + 1] * y[0] */ + sum += (q63_t) * px++ * (*py++); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += (q63_t) * px++ * (*py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q31_t) (sum >> 31); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pIn2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q31_t *pIn1 = pSrcA; /* inputA pointer */ + q31_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ + q63_t sum; /* Accumulators */ + uint32_t i = 0u, j; /* loop counters */ + uint32_t inv = 0u; /* Reverse order flag */ + uint32_t tot = 0u; /* Length */ + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + /* But CORR(x, y) is reverse of CORR(y, x) */ + /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ + /* and a varaible, inv is set to 1 */ + /* If lengths are not equal then zero pad has to be done to make the two + * inputs of same length. But to improve the performance, we include zeroes + * in the output instead of zero padding either of the the inputs*/ + /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the + * starting of the output buffer */ + /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the + * ending of the output buffer */ + /* Once the zero padding is done the remaining of the output is calcualted + * using convolution but with the shorter signal time shifted. */ + + /* Calculate the length of the remaining sequence */ + tot = ((srcALen + srcBLen) - 2u); + + if(srcALen > srcBLen) + { + /* Calculating the number of zeros to be padded to the output */ + j = srcALen - srcBLen; + + /* Initialise the pointer after zero padding */ + pDst += j; + } + + else if(srcALen < srcBLen) + { + /* Initialization to inputB pointer */ + pIn1 = pSrcB; + + /* Initialization to the end of inputA pointer */ + pIn2 = pSrcA + (srcALen - 1u); + + /* Initialisation of the pointer after zero padding */ + pDst = pDst + tot; + + /* Swapping the lengths */ + j = srcALen; + srcALen = srcBLen; + srcBLen = j; + + /* Setting the reverse flag */ + inv = 1; + + } + + /* Loop to calculate convolution for output length number of times */ + for (i = 0u; i <= tot; i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0u; j <= i; j++) + { + /* Check the array limitations */ + if((((i - j) < srcBLen) && (j < srcALen))) + { + /* z[i] += x[i-j] * y[j] */ + sum += ((q63_t) pIn1[j] * pIn2[-((int32_t) i - j)]); + } + } + /* Store the output in the destination buffer */ + if(inv == 1) + *pDst-- = (q31_t) (sum >> 31u); + else + *pDst++ = (q31_t) (sum >> 31u); + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of Corr group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q7.c index 873b5424f..2496e2c36 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_correlate_q7.c @@ -1,780 +1,780 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_q7.c -* -* Description: Correlation of Q7 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 32-bit internal accumulator. - * Both the inputs are represented in 1.7 format and multiplications yield a 2.14 result. - * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. - * This approach provides 17 guard bits and there is no risk of overflow as long as max(srcALen, srcBLen)<131072. - * The 18.14 result is then truncated to 18.7 format by discarding the low 7 bits and saturated to 1.7 format. - */ - -void arm_correlate_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t *pIn1; /* inputA pointer */ - q7_t *pIn2; /* inputB pointer */ - q7_t *pOut = pDst; /* output pointer */ - q7_t *px; /* Intermediate inputA pointer */ - q7_t *py; /* Intermediate inputB pointer */ - q7_t *pSrc1; /* Intermediate pointers */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q31_t input1, input2; /* temporary variables */ - q15_t in1, in2; /* temporary variables */ - q7_t x0, x1, x2, x3, c0, c1; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] , x[1] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 4] , y[srcBLen - 3] */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* x[0] * y[srcBLen - 4] */ - /* x[1] * y[srcBLen - 3] */ - sum = __SMLAD(input1, input2, sum); - - /* x[2] , x[3] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 2] , y[srcBLen - 1] */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* x[2] * y[srcBLen - 2] */ - /* x[3] * y[srcBLen - 1] */ - sum = __SMLAD(input1, input2, sum); - - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum += (q31_t) ((q15_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(sum >> 7, 8)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 1u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *px++; - x1 = *px++; - x2 = *px++; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[0] sample */ - c0 = *py++; - /* Read y[1] sample */ - c1 = *py++; - - /* Read x[3] sample */ - x3 = *px++; - - /* x[0] and x[1] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[0] and y[1] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc0 += x[0] * y[0] + x[1] * y[1] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[1] and x[2] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc1 += x[1] * y[0] + x[2] * y[1] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc2 += x[2] * y[0] + x[3] * y[1] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[4] sample */ - x0 = *(px++); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc3 += x[3] * y[0] + x[4] * y[1] */ - acc3 = __SMLAD(input1, input2, acc3); - - /* Read y[2] sample */ - c0 = *py++; - /* Read y[3] sample */ - c1 = *py++; - - /* Read x[5] sample */ - x1 = *px++; - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[2] and y[3] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc0 += x[2] * y[2] + x[3] * y[3] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc1 += x[3] * y[2] + x[4] * y[3] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[4] and x[5] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc2 += x[4] * y[2] + x[5] * y[3] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[6] sample */ - x2 = *px++; - - /* x[5] and x[6] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc3 += x[5] * y[2] + x[6] * y[3] */ - acc3 = __SMLAD(input1, input2, acc3); - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[4] sample */ - c0 = *py++; - - /* Read x[7] sample */ - x3 = *px++; - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[4] */ - acc0 += ((q15_t) x0 * c0); - /* acc1 += x[5] * y[4] */ - acc1 += ((q15_t) x1 * c0); - /* acc2 += x[6] * y[4] */ - acc2 += ((q15_t) x2 * c0); - /* acc3 += x[7] * y[4] */ - acc3 += ((q15_t) x3 * c0); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(acc0 >> 7, 8)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q7_t) (__SSAT(acc1 >> 7, 8)); - pOut += inc; - - *pOut = (q7_t) (__SSAT(acc2 >> 7, 8)); - pOut += inc; - - *pOut = (q7_t) (__SSAT(acc3 >> 7, 8)); - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + (count * 4u); - py = pIn2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q15_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(sum >> 7, 8)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q15_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(sum >> 7, 8)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[srcALen - srcBLen + 1] , x[srcALen - srcBLen + 2] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[0] , y[1] */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* sum += x[srcALen - srcBLen + 1] * y[0] */ - /* sum += x[srcALen - srcBLen + 2] * y[1] */ - sum = __SMLAD(input1, input2, sum); - - /* x[srcALen - srcBLen + 3] , x[srcALen - srcBLen + 4] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[2] , y[3] */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* sum += x[srcALen - srcBLen + 3] * y[2] */ - /* sum += x[srcALen - srcBLen + 4] * y[3] */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q15_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(sum >> 7, 8)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - q7_t *pIn1 = pSrcA; /* inputA pointer */ - q7_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ - q31_t sum; /* Accumulator */ - uint32_t i = 0u, j; /* loop counters */ - uint32_t inv = 0u; /* Reverse order flag */ - uint32_t tot = 0u; /* Length */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and a varaible, inv is set to 1 */ - /* If lengths are not equal then zero pad has to be done to make the two - * inputs of same length. But to improve the performance, we include zeroes - * in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the - * starting of the output buffer */ - /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the - * ending of the output buffer */ - /* Once the zero padding is done the remaining of the output is calcualted - * using convolution but with the shorter signal time shifted. */ - - /* Calculate the length of the remaining sequence */ - tot = ((srcALen + srcBLen) - 2u); - - if(srcALen > srcBLen) - { - /* Calculating the number of zeros to be padded to the output */ - j = srcALen - srcBLen; - - /* Initialise the pointer after zero padding */ - pDst += j; - } - - else if(srcALen < srcBLen) - { - /* Initialization to inputB pointer */ - pIn1 = pSrcB; - - /* Initialization to the end of inputA pointer */ - pIn2 = pSrcA + (srcALen - 1u); - - /* Initialisation of the pointer after zero padding */ - pDst = pDst + tot; - - /* Swapping the lengths */ - j = srcALen; - srcALen = srcBLen; - srcBLen = j; - - /* Setting the reverse flag */ - inv = 1; - - } - - /* Loop to calculate convolution for output length number of times */ - for (i = 0u; i <= tot; i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q15_t) pIn1[j] * pIn2[-((int32_t) i - j)]); - } - } - /* Store the output in the destination buffer */ - if(inv == 1) - *pDst-- = (q7_t) __SSAT((sum >> 7u), 8u); - else - *pDst++ = (q7_t) __SSAT((sum >> 7u), 8u); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Corr group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_correlate_q7.c +* +* Description: Correlation of Q7 sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup Corr + * @{ + */ + +/** + * @brief Correlation of Q7 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 32-bit internal accumulator. + * Both the inputs are represented in 1.7 format and multiplications yield a 2.14 result. + * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. + * This approach provides 17 guard bits and there is no risk of overflow as long as max(srcALen, srcBLen)<131072. + * The 18.14 result is then truncated to 18.7 format by discarding the low 7 bits and saturated to 1.7 format. + */ + +void arm_correlate_q7( + q7_t * pSrcA, + uint32_t srcALen, + q7_t * pSrcB, + uint32_t srcBLen, + q7_t * pDst) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q7_t *pIn1; /* inputA pointer */ + q7_t *pIn2; /* inputB pointer */ + q7_t *pOut = pDst; /* output pointer */ + q7_t *px; /* Intermediate inputA pointer */ + q7_t *py; /* Intermediate inputB pointer */ + q7_t *pSrc1; /* Intermediate pointers */ + q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ + q31_t input1, input2; /* temporary variables */ + q15_t in1, in2; /* temporary variables */ + q7_t x0, x1, x2, x3, c0, c1; /* temporary variables for holding input and coefficient values */ + uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ + int32_t inc = 1; + + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + /* But CORR(x, y) is reverse of CORR(y, x) */ + /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ + /* and the destination pointer modifier, inc is set to -1 */ + /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ + /* But to improve the performance, + * we include zeroes in the output instead of zero padding either of the the inputs*/ + /* If srcALen > srcBLen, + * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ + /* If srcALen < srcBLen, + * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ + if(srcALen >= srcBLen) + { + /* Initialization of inputA pointer */ + pIn1 = (pSrcA); + + /* Initialization of inputB pointer */ + pIn2 = (pSrcB); + + /* Number of output samples is calculated */ + outBlockSize = (2u * srcALen) - 1u; + + /* When srcALen > srcBLen, zero padding is done to srcB + * to make their lengths equal. + * Instead, (outBlockSize - (srcALen + srcBLen - 1)) + * number of output samples are made zero */ + j = outBlockSize - (srcALen + (srcBLen - 1u)); + + /* Updating the pointer position to non zero value */ + pOut += j; + + } + else + { + /* Initialization of inputA pointer */ + pIn1 = (pSrcB); + + /* Initialization of inputB pointer */ + pIn2 = (pSrcA); + + /* srcBLen is always considered as shorter or equal to srcALen */ + j = srcBLen; + srcBLen = srcALen; + srcALen = j; + + /* CORR(x, y) = Reverse order(CORR(y, x)) */ + /* Hence set the destination pointer to point to the last output sample */ + pOut = pDst + ((srcALen + srcBLen) - 2u); + + /* Destination address modifier is set to -1 */ + inc = -1; + + } + + /* The function is internally + * divided into three parts according to the number of multiplications that has to be + * taken place between inputA samples and inputB samples. In the first part of the + * algorithm, the multiplications increase by one for every iteration. + * In the second part of the algorithm, srcBLen number of multiplications are done. + * In the third part of the algorithm, the multiplications decrease by one + * for every iteration.*/ + /* The algorithm is implemented in three stages. + * The loop counters of each stage is initiated here. */ + blockSize1 = srcBLen - 1u; + blockSize2 = srcALen - (srcBLen - 1u); + blockSize3 = blockSize1; + + /* -------------------------- + * Initializations of stage1 + * -------------------------*/ + + /* sum = x[0] * y[srcBlen - 1] + * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] + * .... + * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] + */ + + /* In this stage the MAC operations are increased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = 1u; + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + pSrc1 = pIn2 + (srcBLen - 1u); + py = pSrc1; + + /* ------------------------ + * Stage1 process + * ----------------------*/ + + /* The first stage starts here */ + while(blockSize1 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[0] , x[1] */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* y[srcBLen - 4] , y[srcBLen - 3] */ + in1 = (q15_t) * py++; + in2 = (q15_t) * py++; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* x[0] * y[srcBLen - 4] */ + /* x[1] * y[srcBLen - 3] */ + sum = __SMLAD(input1, input2, sum); + + /* x[2] , x[3] */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* y[srcBLen - 2] , y[srcBLen - 1] */ + in1 = (q15_t) * py++; + in2 = (q15_t) * py++; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* x[2] * y[srcBLen - 2] */ + /* x[3] * y[srcBLen - 1] */ + sum = __SMLAD(input1, input2, sum); + + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + /* x[0] * y[srcBLen - 1] */ + sum += (q31_t) ((q15_t) * px++ * *py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q7_t) (__SSAT(sum >> 7, 8)); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + py = pSrc1 - count; + px = pIn1; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blockSize1--; + } + + /* -------------------------- + * Initializations of stage2 + * ------------------------*/ + + /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] + * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] + * .... + * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + */ + + /* Working pointer of inputA */ + px = pIn1; + + /* Working pointer of inputB */ + py = pIn2; + + /* count is index by which the pointer pIn1 to be incremented */ + count = 1u; + + /* ------------------- + * Stage2 process + * ------------------*/ + + /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. + * So, to loop unroll over blockSize2, + * srcBLen should be greater than or equal to 4 */ + if(srcBLen >= 4u) + { + /* Loop unroll over blockSize2, by 4 */ + blkCnt = blockSize2 >> 2u; + + while(blkCnt > 0u) + { + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* read x[0], x[1], x[2] samples */ + x0 = *px++; + x1 = *px++; + x2 = *px++; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + do + { + /* Read y[0] sample */ + c0 = *py++; + /* Read y[1] sample */ + c1 = *py++; + + /* Read x[3] sample */ + x3 = *px++; + + /* x[0] and x[1] are packed */ + in1 = (q15_t) x0; + in2 = (q15_t) x1; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* y[0] and y[1] are packed */ + in1 = (q15_t) c0; + in2 = (q15_t) c1; + + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc0 += x[0] * y[0] + x[1] * y[1] */ + acc0 = __SMLAD(input1, input2, acc0); + + /* x[1] and x[2] are packed */ + in1 = (q15_t) x1; + in2 = (q15_t) x2; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc1 += x[1] * y[0] + x[2] * y[1] */ + acc1 = __SMLAD(input1, input2, acc1); + + /* x[2] and x[3] are packed */ + in1 = (q15_t) x2; + in2 = (q15_t) x3; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc2 += x[2] * y[0] + x[3] * y[1] */ + acc2 = __SMLAD(input1, input2, acc2); + + /* Read x[4] sample */ + x0 = *(px++); + + /* x[3] and x[4] are packed */ + in1 = (q15_t) x3; + in2 = (q15_t) x0; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc3 += x[3] * y[0] + x[4] * y[1] */ + acc3 = __SMLAD(input1, input2, acc3); + + /* Read y[2] sample */ + c0 = *py++; + /* Read y[3] sample */ + c1 = *py++; + + /* Read x[5] sample */ + x1 = *px++; + + /* x[2] and x[3] are packed */ + in1 = (q15_t) x2; + in2 = (q15_t) x3; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* y[2] and y[3] are packed */ + in1 = (q15_t) c0; + in2 = (q15_t) c1; + + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc0 += x[2] * y[2] + x[3] * y[3] */ + acc0 = __SMLAD(input1, input2, acc0); + + /* x[3] and x[4] are packed */ + in1 = (q15_t) x3; + in2 = (q15_t) x0; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc1 += x[3] * y[2] + x[4] * y[3] */ + acc1 = __SMLAD(input1, input2, acc1); + + /* x[4] and x[5] are packed */ + in1 = (q15_t) x0; + in2 = (q15_t) x1; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc2 += x[4] * y[2] + x[5] * y[3] */ + acc2 = __SMLAD(input1, input2, acc2); + + /* Read x[6] sample */ + x2 = *px++; + + /* x[5] and x[6] are packed */ + in1 = (q15_t) x1; + in2 = (q15_t) x2; + + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* acc3 += x[5] * y[2] + x[6] * y[3] */ + acc3 = __SMLAD(input1, input2, acc3); + + } while(--k); + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Read y[4] sample */ + c0 = *py++; + + /* Read x[7] sample */ + x3 = *px++; + + /* Perform the multiply-accumulates */ + /* acc0 += x[4] * y[4] */ + acc0 += ((q15_t) x0 * c0); + /* acc1 += x[5] * y[4] */ + acc1 += ((q15_t) x1 * c0); + /* acc2 += x[6] * y[4] */ + acc2 += ((q15_t) x2 * c0); + /* acc3 += x[7] * y[4] */ + acc3 += ((q15_t) x3 * c0); + + /* Reuse the present samples for the next MAC */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q7_t) (__SSAT(acc0 >> 7, 8)); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + *pOut = (q7_t) (__SSAT(acc1 >> 7, 8)); + pOut += inc; + + *pOut = (q7_t) (__SSAT(acc2 >> 7, 8)); + pOut += inc; + + *pOut = (q7_t) (__SSAT(acc3 >> 7, 8)); + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + (count * 4u); + py = pIn2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize2 % 0x4u; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = srcBLen >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* Reading two inputs of SrcA buffer and packing */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Reading two inputs of SrcB buffer and packing */ + in1 = (q15_t) * py++; + in2 = (q15_t) * py++; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Perform the multiply-accumulates */ + sum = __SMLAD(input1, input2, sum); + + /* Reading two inputs of SrcA buffer and packing */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Reading two inputs of SrcB buffer and packing */ + in1 = (q15_t) * py++; + in2 = (q15_t) * py++; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* Perform the multiply-accumulates */ + sum = __SMLAD(input1, input2, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = srcBLen % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q15_t) * px++ * *py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q7_t) (__SSAT(sum >> 7, 8)); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Increment the pointer pIn1 index, count by 1 */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + else + { + /* If the srcBLen is not a multiple of 4, + * the blockSize2 loop cannot be unrolled by 4 */ + blkCnt = blockSize2; + + while(blkCnt > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Loop over srcBLen */ + k = srcBLen; + + while(k > 0u) + { + /* Perform the multiply-accumulate */ + sum += ((q15_t) * px++ * *py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q7_t) (__SSAT(sum >> 7, 8)); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = pIn1 + count; + py = pIn2; + + /* Increment the MAC count */ + count++; + + /* Decrement the loop counter */ + blkCnt--; + } + } + + /* -------------------------- + * Initializations of stage3 + * -------------------------*/ + + /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] + * .... + * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] + * sum += x[srcALen-1] * y[0] + */ + + /* In this stage the MAC operations are decreased by 1 for every iteration. + The count variable holds the number of MAC operations performed */ + count = srcBLen - 1u; + + /* Working pointer of inputA */ + pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); + px = pSrc1; + + /* Working pointer of inputB */ + py = pIn2; + + /* ------------------- + * Stage3 process + * ------------------*/ + + while(blockSize3 > 0u) + { + /* Accumulator is made zero for every iteration */ + sum = 0; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + k = count >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 MACs at a time. + ** a second loop below computes MACs for the remaining 1 to 3 samples. */ + while(k > 0u) + { + /* x[srcALen - srcBLen + 1] , x[srcALen - srcBLen + 2] */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* y[0] , y[1] */ + in1 = (q15_t) * py++; + in2 = (q15_t) * py++; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* sum += x[srcALen - srcBLen + 1] * y[0] */ + /* sum += x[srcALen - srcBLen + 2] * y[1] */ + sum = __SMLAD(input1, input2, sum); + + /* x[srcALen - srcBLen + 3] , x[srcALen - srcBLen + 4] */ + in1 = (q15_t) * px++; + in2 = (q15_t) * px++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* y[2] , y[3] */ + in1 = (q15_t) * py++; + in2 = (q15_t) * py++; + input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* sum += x[srcALen - srcBLen + 3] * y[2] */ + /* sum += x[srcALen - srcBLen + 4] * y[3] */ + sum = __SMLAD(input1, input2, sum); + + /* Decrement the loop counter */ + k--; + } + + /* If the count is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + k = count % 0x4u; + + while(k > 0u) + { + /* Perform the multiply-accumulates */ + sum += ((q15_t) * px++ * *py++); + + /* Decrement the loop counter */ + k--; + } + + /* Store the result in the accumulator in the destination buffer. */ + *pOut = (q7_t) (__SSAT(sum >> 7, 8)); + /* Destination pointer is updated according to the address modifier, inc */ + pOut += inc; + + /* Update the inputA and inputB pointers for next MAC calculation */ + px = ++pSrc1; + py = pIn2; + + /* Decrement the MAC count */ + count--; + + /* Decrement the loop counter */ + blockSize3--; + } + +#else + +/* Run the below code for Cortex-M0 */ + + q7_t *pIn1 = pSrcA; /* inputA pointer */ + q7_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ + q31_t sum; /* Accumulator */ + uint32_t i = 0u, j; /* loop counters */ + uint32_t inv = 0u; /* Reverse order flag */ + uint32_t tot = 0u; /* Length */ + + /* The algorithm implementation is based on the lengths of the inputs. */ + /* srcB is always made to slide across srcA. */ + /* So srcBLen is always considered as shorter or equal to srcALen */ + /* But CORR(x, y) is reverse of CORR(y, x) */ + /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ + /* and a varaible, inv is set to 1 */ + /* If lengths are not equal then zero pad has to be done to make the two + * inputs of same length. But to improve the performance, we include zeroes + * in the output instead of zero padding either of the the inputs*/ + /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the + * starting of the output buffer */ + /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the + * ending of the output buffer */ + /* Once the zero padding is done the remaining of the output is calcualted + * using convolution but with the shorter signal time shifted. */ + + /* Calculate the length of the remaining sequence */ + tot = ((srcALen + srcBLen) - 2u); + + if(srcALen > srcBLen) + { + /* Calculating the number of zeros to be padded to the output */ + j = srcALen - srcBLen; + + /* Initialise the pointer after zero padding */ + pDst += j; + } + + else if(srcALen < srcBLen) + { + /* Initialization to inputB pointer */ + pIn1 = pSrcB; + + /* Initialization to the end of inputA pointer */ + pIn2 = pSrcA + (srcALen - 1u); + + /* Initialisation of the pointer after zero padding */ + pDst = pDst + tot; + + /* Swapping the lengths */ + j = srcALen; + srcALen = srcBLen; + srcBLen = j; + + /* Setting the reverse flag */ + inv = 1; + + } + + /* Loop to calculate convolution for output length number of times */ + for (i = 0u; i <= tot; i++) + { + /* Initialize sum with zero to carry on MAC operations */ + sum = 0; + + /* Loop to perform MAC operations according to convolution equation */ + for (j = 0u; j <= i; j++) + { + /* Check the array limitations */ + if((((i - j) < srcBLen) && (j < srcALen))) + { + /* z[i] += x[i-j] * y[j] */ + sum += ((q15_t) pIn1[j] * pIn2[-((int32_t) i - j)]); + } + } + /* Store the output in the destination buffer */ + if(inv == 1) + *pDst-- = (q7_t) __SSAT((sum >> 7u), 8u); + else + *pDst++ = (q7_t) __SSAT((sum >> 7u), 8u); + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of Corr group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_f32.c index c66d3f4c1..0ee7d160f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_f32.c @@ -1,370 +1,370 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_f32.c -* -* Description: FIR decimation for floating-point sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup FIR_decimate Finite Impulse Response (FIR) Decimator - * - * These functions combine an FIR filter together with a decimator. - * They are used in multirate systems for reducing the sample rate of a signal without introducing aliasing distortion. - * Conceptually, the functions are equivalent to the block diagram below: - * \image html FIRDecimator.gif "Components included in the FIR Decimator functions" - * When decimating by a factor of M, the signal should be prefiltered by a lowpass filter with a normalized - * cutoff frequency of 1/M in order to prevent aliasing distortion. - * The user of the function is responsible for providing the filter coefficients. - * - * The FIR decimator functions provided in the CMSIS DSP Library combine the FIR filter and the decimator in an efficient manner. - * Instead of calculating all of the FIR filter outputs and discarding M-1 out of every M, only the - * samples output by the decimator are computed. - * The functions operate on blocks of input and output data. - * pSrc points to an array of blockSize input values and - * pDst points to an array of blockSize/M output values. - * In order to have an integer number of output samples blockSize - * must always be a multiple of the decimation factor M. - * - * The library provides separate functions for Q15, Q31 and floating-point data types. - * - * \par Algorithm: - * The FIR portion of the algorithm uses the standard form filter: - *
   
- *    y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]   
- * 
- * where, b[n] are the filter coefficients. - * \par - * The pCoeffs points to a coefficient array of size numTaps. - * Coefficients are stored in time reversed order. - * \par - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to a state array of size numTaps + blockSize - 1. - * Samples in the state buffer are stored in the order: - * \par - *
   
- *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}   
- * 
- * The state variables are updated after each block of data is processed, the coefficients are untouched. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable array should be allocated separately. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - Checks to make sure that the size of the input is a multiple of the decimation factor. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * The code below statically initializes each of the 3 different data type filter instance structures - *
   
- *arm_fir_decimate_instance_f32 S = {M, numTaps, pCoeffs, pState};   
- *arm_fir_decimate_instance_q31 S = {M, numTaps, pCoeffs, pState};   
- *arm_fir_decimate_instance_q15 S = {M, numTaps, pCoeffs, pState};   
- * 
- * where M is the decimation factor; numTaps is the number of filter coefficients in the filter; - * pCoeffs is the address of the coefficient buffer; - * pState is the address of the state buffer. - * Be sure to set the values in the state buffer to zeros when doing static initialization. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the FIR decimate filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - - /** - * @brief Processing function for the floating-point FIR decimator. - * @param[in] *S points to an instance of the floating-point FIR decimator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - * @return none. - */ - -void arm_fir_decimate_f32( - const arm_fir_decimate_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - float32_t sum0; /* Accumulator */ - float32_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - sum0 = 0.0f; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-1] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-2] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-3] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = sum0; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - sum0 = 0.0f; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = sum0; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the start of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Copy numTaps number of values */ - i = (numTaps - 1u); - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_decimate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_decimate_f32.c +* +* Description: FIR decimation for floating-point sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup FIR_decimate Finite Impulse Response (FIR) Decimator + * + * These functions combine an FIR filter together with a decimator. + * They are used in multirate systems for reducing the sample rate of a signal without introducing aliasing distortion. + * Conceptually, the functions are equivalent to the block diagram below: + * \image html FIRDecimator.gif "Components included in the FIR Decimator functions" + * When decimating by a factor of M, the signal should be prefiltered by a lowpass filter with a normalized + * cutoff frequency of 1/M in order to prevent aliasing distortion. + * The user of the function is responsible for providing the filter coefficients. + * + * The FIR decimator functions provided in the CMSIS DSP Library combine the FIR filter and the decimator in an efficient manner. + * Instead of calculating all of the FIR filter outputs and discarding M-1 out of every M, only the + * samples output by the decimator are computed. + * The functions operate on blocks of input and output data. + * pSrc points to an array of blockSize input values and + * pDst points to an array of blockSize/M output values. + * In order to have an integer number of output samples blockSize + * must always be a multiple of the decimation factor M. + * + * The library provides separate functions for Q15, Q31 and floating-point data types. + * + * \par Algorithm: + * The FIR portion of the algorithm uses the standard form filter: + *
   
+ *    y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]   
+ * 
+ * where, b[n] are the filter coefficients. + * \par + * The pCoeffs points to a coefficient array of size numTaps. + * Coefficients are stored in time reversed order. + * \par + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to a state array of size numTaps + blockSize - 1. + * Samples in the state buffer are stored in the order: + * \par + *
   
+ *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}   
+ * 
+ * The state variables are updated after each block of data is processed, the coefficients are untouched. + * + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter. + * Coefficient arrays may be shared among several instances while state variable array should be allocated separately. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * - Checks to make sure that the size of the input is a multiple of the decimation factor. + * + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * The code below statically initializes each of the 3 different data type filter instance structures + *
   
+ *arm_fir_decimate_instance_f32 S = {M, numTaps, pCoeffs, pState};   
+ *arm_fir_decimate_instance_q31 S = {M, numTaps, pCoeffs, pState};   
+ *arm_fir_decimate_instance_q15 S = {M, numTaps, pCoeffs, pState};   
+ * 
+ * where M is the decimation factor; numTaps is the number of filter coefficients in the filter; + * pCoeffs is the address of the coefficient buffer; + * pState is the address of the state buffer. + * Be sure to set the values in the state buffer to zeros when doing static initialization. + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the FIR decimate filter functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + +/** + * @addtogroup FIR_decimate + * @{ + */ + + /** + * @brief Processing function for the floating-point FIR decimator. + * @param[in] *S points to an instance of the floating-point FIR decimator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + * @return none. + */ + +void arm_fir_decimate_f32( + const arm_fir_decimate_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + float32_t *pState = S->pState; /* State pointer */ + float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + float32_t *pStateCurnt; /* Points to the current sample of the state */ + float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ + float32_t sum0; /* Accumulator */ + float32_t x0, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + uint32_t i, tapCnt, blkCnt, outBlockSize = blockSize / S->M; /* Loop counters */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* S->pState buffer contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (numTaps - 1u); + + /* Total number of output samples to be computed */ + blkCnt = outBlockSize; + + while(blkCnt > 0u) + { + /* Copy decimation factor number of new input samples into the state buffer */ + i = S->M; + + do + { + *pStateCurnt++ = *pSrc++; + + } while(--i); + + /* Set accumulator to zero */ + sum0 = 0.0f; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = pCoeffs; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-4 coefficients. */ + while(tapCnt > 0u) + { + /* Read the b[numTaps-1] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-1] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 += x0 * c0; + + /* Read the b[numTaps-2] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-2] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 += x0 * c0; + + /* Read the b[numTaps-3] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-3] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 += x0 * c0; + + /* Read the b[numTaps-4] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 += x0 * c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Read coefficients */ + c0 = *(pb++); + + /* Fetch 1 state variable */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 += x0 * c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance the state pointer by the decimation factor + * to process the next group of decimation factor number samples */ + pState = pState + S->M; + + /* The result is in the accumulator, store in the destination buffer. */ + *pDst++ = sum0; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + i = (numTaps - 1u) >> 2; + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + + i = (numTaps - 1u) % 0x04u; + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + +#else + +/* Run the below code for Cortex-M0 */ + + /* S->pState buffer contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (numTaps - 1u); + + /* Total number of output samples to be computed */ + blkCnt = outBlockSize; + + while(blkCnt > 0u) + { + /* Copy decimation factor number of new input samples into the state buffer */ + i = S->M; + + do + { + *pStateCurnt++ = *pSrc++; + + } while(--i); + + /* Set accumulator to zero */ + sum0 = 0.0f; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = pCoeffs; + + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Read coefficients */ + c0 = *pb++; + + /* Fetch 1 state variable */ + x0 = *px++; + + /* Perform the multiply-accumulate */ + sum0 += x0 * c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance the state pointer by the decimation factor + * to process the next group of decimation factor number samples */ + pState = pState + S->M; + + /* The result is in the accumulator, store in the destination buffer. */ + *pDst++ = sum0; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the start of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + /* Copy numTaps number of values */ + i = (numTaps - 1u); + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR_decimate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q15.c index e9bc3c3d1..ae1ddf8b9 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q15.c @@ -1,199 +1,199 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_fast_q15.c -* -* Description: Fast Q15 FIR Decimator. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. - * @param[in] *S points to an instance of the Q15 FIR decimator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - * @return none - * - * Scaling and Overflow Behavior: - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around and distorts the result. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits (log2 is read as log to the base 2). - * The 2.30 accumulator is then truncated to 2.15 format and saturated to yield the 1.15 result. - * - * \par - * Refer to the function arm_fir_decimate_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. - * Both the slow and the fast versions use the same instance structure. - * Use the function arm_fir_decimate_init_q15() to initialize the filter structure. - */ - -void arm_fir_decimate_fast_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px; /* Temporary pointer for state buffer */ - q15_t *pb; /* Temporary pointer coefficient buffer */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - q31_t sum0; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, blkCnt, tapCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /*Set sum to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the Read b[numTaps-1] and b[numTaps-2] coefficients */ - c0 = *__SIMD32(pb)++; - - /* Read x[n-numTaps-1] and x[n-numTaps-2]sample */ - x0 = *__SIMD32(px)++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLAD(x0, c0, sum0); - - /* Read the b[numTaps-3] and b[numTaps-4] coefficient */ - c0 = *__SIMD32(pb)++; - - /* Read x[n-numTaps-2] and x[n-numTaps-3] sample */ - x0 = *__SIMD32(px)++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLAD(x0, c0, sum0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLAD(x0, c0, sum0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* Store filter output , smlad returns the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - *pDst++ = (q15_t) ((sum0 >> 15)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } -} - -/** - * @} end of FIR_decimate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_decimate_fast_q15.c +* +* Description: Fast Q15 FIR Decimator. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_decimate + * @{ + */ + +/** + * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. + * @param[in] *S points to an instance of the Q15 FIR decimator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + * @return none + * + * Scaling and Overflow Behavior: + * \par + * This fast version uses a 32-bit accumulator with 2.30 format. + * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around and distorts the result. + * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits (log2 is read as log to the base 2). + * The 2.30 accumulator is then truncated to 2.15 format and saturated to yield the 1.15 result. + * + * \par + * Refer to the function arm_fir_decimate_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. + * Both the slow and the fast versions use the same instance structure. + * Use the function arm_fir_decimate_init_q15() to initialize the filter structure. + */ + +void arm_fir_decimate_fast_q15( + const arm_fir_decimate_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + q15_t *pState = S->pState; /* State pointer */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q15_t *pStateCurnt; /* Points to the current sample of the state */ + q15_t *px; /* Temporary pointer for state buffer */ + q15_t *pb; /* Temporary pointer coefficient buffer */ + q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ + q31_t sum0; /* Accumulators */ + uint32_t numTaps = S->numTaps; /* Number of taps */ + uint32_t i, blkCnt, tapCnt, outBlockSize = blockSize / S->M; /* Loop counters */ + + + /* S->pState buffer contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (numTaps - 1u); + + /* Total number of output samples to be computed */ + blkCnt = outBlockSize; + + while(blkCnt > 0u) + { + /* Copy decimation factor number of new input samples into the state buffer */ + i = S->M; + + do + { + *pStateCurnt++ = *pSrc++; + + } while(--i); + + /*Set sum to zero */ + sum0 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = pCoeffs; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-4 coefficients. */ + while(tapCnt > 0u) + { + /* Read the Read b[numTaps-1] and b[numTaps-2] coefficients */ + c0 = *__SIMD32(pb)++; + + /* Read x[n-numTaps-1] and x[n-numTaps-2]sample */ + x0 = *__SIMD32(px)++; + + /* Perform the multiply-accumulate */ + sum0 = __SMLAD(x0, c0, sum0); + + /* Read the b[numTaps-3] and b[numTaps-4] coefficient */ + c0 = *__SIMD32(pb)++; + + /* Read x[n-numTaps-2] and x[n-numTaps-3] sample */ + x0 = *__SIMD32(px)++; + + /* Perform the multiply-accumulate */ + sum0 = __SMLAD(x0, c0, sum0); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Read coefficients */ + c0 = *pb++; + + /* Fetch 1 state variable */ + x0 = *px++; + + /* Perform the multiply-accumulate */ + sum0 = __SMLAD(x0, c0, sum0); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance the state pointer by the decimation factor + * to process the next group of decimation factor number samples */ + pState = pState + S->M; + + /* Store filter output , smlad returns the values in 2.14 format */ + /* so downsacle by 15 to get output in 1.15 */ + *pDst++ = (q15_t) ((sum0 >> 15)); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + i = (numTaps - 1u) >> 2u; + + /* copy data */ + while(i > 0u) + { + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + + /* Decrement the loop counter */ + i--; + } + + i = (numTaps - 1u) % 0x04u; + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } +} + +/** + * @} end of FIR_decimate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q31.c index 67d90587e..86833d829 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q31.c @@ -1,220 +1,220 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_fast_q31.c -* -* Description: Fast Q31 FIR Decimator. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. - * @param[in] *S points to an instance of the Q31 FIR decimator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - * @return none - * - * Scaling and Overflow Behavior: - * - * \par - * This function is optimized for speed at the expense of fixed-point precision and overflow protection. - * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. - * These intermediate results are added to a 2.30 accumulator. - * Finally, the accumulator is saturated and converted to a 1.31 result. - * The fast version has the same overflow behavior as the standard version and provides less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits (where log2 is read as log to the base 2). - * - * \par - * Refer to the function arm_fir_decimate_q31() for a slower implementation of this function which uses a 64-bit accumulator to provide higher precision. - * Both the slow and the fast versions use the same instance structure. - * Use the function arm_fir_decimate_init_q31() to initialize the filter structure. - */ - -void arm_fir_decimate_fast_q31( - arm_fir_decimate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - q31_t *px; /* Temporary pointers for state buffer */ - q31_t *pb; /* Temporary pointers for coefficient buffer */ - q63_t sum0; /* Accumulator */ - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, tapCnt, blkCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-1] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 = (q31_t) ((((q63_t) x0 * c0) + (sum0 << 32)) >> 32); - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-2] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 = (q31_t) ((((q63_t) x0 * c0) + (sum0 << 32)) >> 32); - - /* Read the b[numTaps-3] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 = (q31_t) ((((q63_t) x0 * c0) + (sum0 << 32)) >> 32); - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 = (q31_t) ((((q63_t) x0 * c0) + (sum0 << 32)) >> 32); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 = (q31_t) ((((q63_t) x0 * c0) + (sum0 << 32)) >> 32); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (sum0 << 1); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } -} - -/** - * @} end of FIR_decimate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_decimate_fast_q31.c +* +* Description: Fast Q31 FIR Decimator. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_decimate + * @{ + */ + +/** + * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. + * @param[in] *S points to an instance of the Q31 FIR decimator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + * @return none + * + * Scaling and Overflow Behavior: + * + * \par + * This function is optimized for speed at the expense of fixed-point precision and overflow protection. + * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. + * These intermediate results are added to a 2.30 accumulator. + * Finally, the accumulator is saturated and converted to a 1.31 result. + * The fast version has the same overflow behavior as the standard version and provides less precision since it discards the low 32 bits of each multiplication result. + * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits (where log2 is read as log to the base 2). + * + * \par + * Refer to the function arm_fir_decimate_q31() for a slower implementation of this function which uses a 64-bit accumulator to provide higher precision. + * Both the slow and the fast versions use the same instance structure. + * Use the function arm_fir_decimate_init_q31() to initialize the filter structure. + */ + +void arm_fir_decimate_fast_q31( + arm_fir_decimate_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t *pState = S->pState; /* State pointer */ + q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *pStateCurnt; /* Points to the current sample of the state */ + q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ + q31_t *px; /* Temporary pointers for state buffer */ + q31_t *pb; /* Temporary pointers for coefficient buffer */ + q63_t sum0; /* Accumulator */ + uint32_t numTaps = S->numTaps; /* Number of taps */ + uint32_t i, tapCnt, blkCnt, outBlockSize = blockSize / S->M; /* Loop counters */ + + + /* S->pState buffer contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (numTaps - 1u); + + /* Total number of output samples to be computed */ + blkCnt = outBlockSize; + + while(blkCnt > 0u) + { + /* Copy decimation factor number of new input samples into the state buffer */ + i = S->M; + + do + { + *pStateCurnt++ = *pSrc++; + + } while(--i); + + /* Set accumulator to zero */ + sum0 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = pCoeffs; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-4 coefficients. */ + while(tapCnt > 0u) + { + /* Read the b[numTaps-1] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-1] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 = (q31_t) ((((q63_t) x0 * c0) + (sum0 << 32)) >> 32); + + /* Read the b[numTaps-2] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-2] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 = (q31_t) ((((q63_t) x0 * c0) + (sum0 << 32)) >> 32); + + /* Read the b[numTaps-3] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-3] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 = (q31_t) ((((q63_t) x0 * c0) + (sum0 << 32)) >> 32); + + /* Read the b[numTaps-4] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 = (q31_t) ((((q63_t) x0 * c0) + (sum0 << 32)) >> 32); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Read coefficients */ + c0 = *(pb++); + + /* Fetch 1 state variable */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 = (q31_t) ((((q63_t) x0 * c0) + (sum0 << 32)) >> 32); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance the state pointer by the decimation factor + * to process the next group of decimation factor number samples */ + pState = pState + S->M; + + /* The result is in the accumulator, store in the destination buffer. */ + *pDst++ = (q31_t) (sum0 << 1); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + i = (numTaps - 1u) >> 2u; + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + + i = (numTaps - 1u) % 0x04u; + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } +} + +/** + * @} end of FIR_decimate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_f32.c index c30af4f35..be970ebc1 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_f32.c @@ -1,109 +1,109 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_init_f32.c -* -* Description: Floating-point FIR Decimator initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Initialization function for the floating-point FIR decimator. - * @param[in,out] *S points to an instance of the floating-point FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 words where blockSize is the number of input samples passed to arm_fir_decimate_f32(). - * M is the decimation factor. - */ - -arm_status arm_fir_decimate_init_f32( - arm_fir_decimate_instance_f32 * S, - uint16_t numTaps, - uint8_t M, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize) -{ - arm_status status; - - /* The size of the input block must be a multiple of the decimation factor */ - if((blockSize % M) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Decimation Factor */ - S->M = M; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - -/** - * @} end of FIR_decimate group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_decimate_init_f32.c +* +* Description: Floating-point FIR Decimator initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_decimate + * @{ + */ + +/** + * @brief Initialization function for the floating-point FIR decimator. + * @param[in,out] *S points to an instance of the floating-point FIR decimator structure. + * @param[in] numTaps number of coefficients in the filter. + * @param[in] M decimation factor. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if + * blockSize is not a multiple of M. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to the array of state variables. + * pState is of length numTaps+blockSize-1 words where blockSize is the number of input samples passed to arm_fir_decimate_f32(). + * M is the decimation factor. + */ + +arm_status arm_fir_decimate_init_f32( + arm_fir_decimate_instance_f32 * S, + uint16_t numTaps, + uint8_t M, + float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize) +{ + arm_status status; + + /* The size of the input block must be a multiple of the decimation factor */ + if((blockSize % M) != 0u) + { + /* Set status as ARM_MATH_LENGTH_ERROR */ + status = ARM_MATH_LENGTH_ERROR; + } + else + { + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always (blockSize + numTaps - 1) */ + memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(float32_t)); + + /* Assign state pointer */ + S->pState = pState; + + /* Assign Decimation Factor */ + S->M = M; + + status = ARM_MATH_SUCCESS; + } + + return (status); + +} + +/** + * @} end of FIR_decimate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q15.c index 24b84c6ac..c9f1f3cb7 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q15.c @@ -1,111 +1,111 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_init_q15.c -* -* Description: Initialization function for the Q15 FIR Decimator. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Initialization function for the Q15 FIR decimator. - * @param[in,out] *S points to an instance of the Q15 FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 words where blockSize is the number of input samples - * to the call arm_fir_decimate_q15(). - * M is the decimation factor. - */ - -arm_status arm_fir_decimate_init_q15( - arm_fir_decimate_instance_q15 * S, - uint16_t numTaps, - uint8_t M, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize) -{ - - arm_status status; - - /* The size of the input block must be a multiple of the decimation factor */ - if((blockSize % M) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear the state buffer. The size of buffer is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Decimation factor */ - S->M = M; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - -/** - * @} end of FIR_decimate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_decimate_init_q15.c +* +* Description: Initialization function for the Q15 FIR Decimator. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_decimate + * @{ + */ + +/** + * @brief Initialization function for the Q15 FIR decimator. + * @param[in,out] *S points to an instance of the Q15 FIR decimator structure. + * @param[in] numTaps number of coefficients in the filter. + * @param[in] M decimation factor. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if + * blockSize is not a multiple of M. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to the array of state variables. + * pState is of length numTaps+blockSize-1 words where blockSize is the number of input samples + * to the call arm_fir_decimate_q15(). + * M is the decimation factor. + */ + +arm_status arm_fir_decimate_init_q15( + arm_fir_decimate_instance_q15 * S, + uint16_t numTaps, + uint8_t M, + q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize) +{ + + arm_status status; + + /* The size of the input block must be a multiple of the decimation factor */ + if((blockSize % M) != 0u) + { + /* Set status as ARM_MATH_LENGTH_ERROR */ + status = ARM_MATH_LENGTH_ERROR; + } + else + { + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear the state buffer. The size of buffer is always (blockSize + numTaps - 1) */ + memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); + + /* Assign state pointer */ + S->pState = pState; + + /* Assign Decimation factor */ + S->M = M; + + status = ARM_MATH_SUCCESS; + } + + return (status); + +} + +/** + * @} end of FIR_decimate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q31.c index 55652126d..7fdb6935f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q31.c @@ -1,109 +1,109 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_init_q31.c -* -* Description: Initialization function for Q31 FIR Decimation filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Initialization function for the Q31 FIR decimator. - * @param[in,out] *S points to an instance of the Q31 FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 words where blockSize is the number of input samples passed to arm_fir_decimate_q31(). - * M is the decimation factor. - */ - -arm_status arm_fir_decimate_init_q31( - arm_fir_decimate_instance_q31 * S, - uint16_t numTaps, - uint8_t M, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize) -{ - arm_status status; - - /* The size of the input block must be a multiple of the decimation factor */ - if((blockSize % M) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1)) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Decimation factor */ - S->M = M; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - -/** - * @} end of FIR_decimate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_decimate_init_q31.c +* +* Description: Initialization function for Q31 FIR Decimation filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_decimate + * @{ + */ + +/** + * @brief Initialization function for the Q31 FIR decimator. + * @param[in,out] *S points to an instance of the Q31 FIR decimator structure. + * @param[in] numTaps number of coefficients in the filter. + * @param[in] M decimation factor. + * @param[in] *pCoeffs points to the filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if + * blockSize is not a multiple of M. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to the array of state variables. + * pState is of length numTaps+blockSize-1 words where blockSize is the number of input samples passed to arm_fir_decimate_q31(). + * M is the decimation factor. + */ + +arm_status arm_fir_decimate_init_q31( + arm_fir_decimate_instance_q31 * S, + uint16_t numTaps, + uint8_t M, + q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize) +{ + arm_status status; + + /* The size of the input block must be a multiple of the decimation factor */ + if((blockSize % M) != 0u) + { + /* Set status as ARM_MATH_LENGTH_ERROR */ + status = ARM_MATH_LENGTH_ERROR; + } + else + { + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ + memset(pState, 0, (numTaps + (blockSize - 1)) * sizeof(q31_t)); + + /* Assign state pointer */ + S->pState = pState; + + /* Assign Decimation factor */ + S->M = M; + + status = ARM_MATH_SUCCESS; + } + + return (status); + +} + +/** + * @} end of FIR_decimate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q15.c index 99e91c5b1..be264594f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q15.c @@ -1,285 +1,285 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_q15.c -* -* Description: Q15 FIR Decimator. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Processing function for the Q15 FIR decimator. - * @param[in] *S points to an instance of the Q15 FIR decimator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - * - * \par - * Refer to the function arm_fir_decimate_fast_q15() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -void arm_fir_decimate_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px; /* Temporary pointer for state buffer */ - q15_t *pb; /* Temporary pointer coefficient buffer */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - q63_t sum0; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, blkCnt, tapCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /*Set sum to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the Read b[numTaps-1] and b[numTaps-2] coefficients */ - c0 = *__SIMD32(pb)++; - - /* Read x[n-numTaps-1] and x[n-numTaps-2]sample */ - x0 = *__SIMD32(px)++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLALD(x0, c0, sum0); - - /* Read the b[numTaps-3] and b[numTaps-4] coefficient */ - c0 = *__SIMD32(pb)++; - - /* Read x[n-numTaps-2] and x[n-numTaps-3] sample */ - x0 = *__SIMD32(px)++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLALD(x0, c0, sum0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLALD(x0, c0, sum0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* Store filter output, smlad returns the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /*Set sum to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += (q31_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /*Store filter output , smlad will return the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the start of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = numTaps - 1u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_decimate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_decimate_q15.c +* +* Description: Q15 FIR Decimator. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_decimate + * @{ + */ + +/** + * @brief Processing function for the Q15 FIR decimator. + * @param[in] *S points to an instance of the Q15 FIR decimator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the location where the output result is written. + * @param[in] blockSize number of input samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 64-bit internal accumulator. + * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. + * Lastly, the accumulator is saturated to yield a result in 1.15 format. + * + * \par + * Refer to the function arm_fir_decimate_fast_q15() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. + */ + +void arm_fir_decimate_q15( + const arm_fir_decimate_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + q15_t *pState = S->pState; /* State pointer */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q15_t *pStateCurnt; /* Points to the current sample of the state */ + q15_t *px; /* Temporary pointer for state buffer */ + q15_t *pb; /* Temporary pointer coefficient buffer */ + q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ + q63_t sum0; /* Accumulators */ + uint32_t numTaps = S->numTaps; /* Number of taps */ + uint32_t i, blkCnt, tapCnt, outBlockSize = blockSize / S->M; /* Loop counters */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* S->pState buffer contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (numTaps - 1u); + + /* Total number of output samples to be computed */ + blkCnt = outBlockSize; + + while(blkCnt > 0u) + { + /* Copy decimation factor number of new input samples into the state buffer */ + i = S->M; + + do + { + *pStateCurnt++ = *pSrc++; + + } while(--i); + + /*Set sum to zero */ + sum0 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = pCoeffs; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-4 coefficients. */ + while(tapCnt > 0u) + { + /* Read the Read b[numTaps-1] and b[numTaps-2] coefficients */ + c0 = *__SIMD32(pb)++; + + /* Read x[n-numTaps-1] and x[n-numTaps-2]sample */ + x0 = *__SIMD32(px)++; + + /* Perform the multiply-accumulate */ + sum0 = __SMLALD(x0, c0, sum0); + + /* Read the b[numTaps-3] and b[numTaps-4] coefficient */ + c0 = *__SIMD32(pb)++; + + /* Read x[n-numTaps-2] and x[n-numTaps-3] sample */ + x0 = *__SIMD32(px)++; + + /* Perform the multiply-accumulate */ + sum0 = __SMLALD(x0, c0, sum0); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Read coefficients */ + c0 = *pb++; + + /* Fetch 1 state variable */ + x0 = *px++; + + /* Perform the multiply-accumulate */ + sum0 = __SMLALD(x0, c0, sum0); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance the state pointer by the decimation factor + * to process the next group of decimation factor number samples */ + pState = pState + S->M; + + /* Store filter output, smlad returns the values in 2.14 format */ + /* so downsacle by 15 to get output in 1.15 */ + *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + i = (numTaps - 1u) >> 2u; + + /* copy data */ + while(i > 0u) + { + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + + /* Decrement the loop counter */ + i--; + } + + i = (numTaps - 1u) % 0x04u; + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + +#else + +/* Run the below code for Cortex-M0 */ + + /* S->pState buffer contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (numTaps - 1u); + + /* Total number of output samples to be computed */ + blkCnt = outBlockSize; + + while(blkCnt > 0u) + { + /* Copy decimation factor number of new input samples into the state buffer */ + i = S->M; + + do + { + *pStateCurnt++ = *pSrc++; + + } while(--i); + + /*Set sum to zero */ + sum0 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = pCoeffs; + + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Read coefficients */ + c0 = *pb++; + + /* Fetch 1 state variable */ + x0 = *px++; + + /* Perform the multiply-accumulate */ + sum0 += (q31_t) x0 *c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance the state pointer by the decimation factor + * to process the next group of decimation factor number samples */ + pState = pState + S->M; + + /*Store filter output , smlad will return the values in 2.14 format */ + /* so downsacle by 15 to get output in 1.15 */ + *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the start of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + i = numTaps - 1u; + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR_decimate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q31.c index 227a4ed76..96f7ce1cf 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q31.c @@ -1,303 +1,303 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_q31.c -* -* Description: Q31 FIR Decimator. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Processing function for the Q31 FIR decimator. - * @param[in] *S points to an instance of the Q31 FIR decimator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - * @return none - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits (where log2 is read as log to the base 2). - * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. - * - * \par - * Refer to the function arm_fir_decimate_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -void arm_fir_decimate_q31( - const arm_fir_decimate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - q31_t *px; /* Temporary pointers for state buffer */ - q31_t *pb; /* Temporary pointers for coefficient buffer */ - q63_t sum0; /* Accumulator */ - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, tapCnt, blkCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-1] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-2] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the b[numTaps-3] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (sum0 >> 31); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (sum0 >> 31); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the start of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = numTaps - 1u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_decimate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_decimate_q31.c +* +* Description: Q31 FIR Decimator. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_decimate + * @{ + */ + +/** + * @brief Processing function for the Q31 FIR decimator. + * @param[in] *S points to an instance of the Q31 FIR decimator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of input samples to process per call. + * @return none + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around rather than clip. + * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits (where log2 is read as log to the base 2). + * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. + * + * \par + * Refer to the function arm_fir_decimate_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. + */ + +void arm_fir_decimate_q31( + const arm_fir_decimate_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t *pState = S->pState; /* State pointer */ + q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *pStateCurnt; /* Points to the current sample of the state */ + q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ + q31_t *px; /* Temporary pointers for state buffer */ + q31_t *pb; /* Temporary pointers for coefficient buffer */ + q63_t sum0; /* Accumulator */ + uint32_t numTaps = S->numTaps; /* Number of taps */ + uint32_t i, tapCnt, blkCnt, outBlockSize = blockSize / S->M; /* Loop counters */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* S->pState buffer contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (numTaps - 1u); + + /* Total number of output samples to be computed */ + blkCnt = outBlockSize; + + while(blkCnt > 0u) + { + /* Copy decimation factor number of new input samples into the state buffer */ + i = S->M; + + do + { + *pStateCurnt++ = *pSrc++; + + } while(--i); + + /* Set accumulator to zero */ + sum0 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = pCoeffs; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-4 coefficients. */ + while(tapCnt > 0u) + { + /* Read the b[numTaps-1] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-1] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Read the b[numTaps-2] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-2] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Read the b[numTaps-3] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-3] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Read the b[numTaps-4] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Read coefficients */ + c0 = *(pb++); + + /* Fetch 1 state variable */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance the state pointer by the decimation factor + * to process the next group of decimation factor number samples */ + pState = pState + S->M; + + /* The result is in the accumulator, store in the destination buffer. */ + *pDst++ = (q31_t) (sum0 >> 31); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + i = (numTaps - 1u) >> 2u; + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + + i = (numTaps - 1u) % 0x04u; + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + +#else + +/* Run the below code for Cortex-M0 */ + + /* S->pState buffer contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (numTaps - 1u); + + /* Total number of output samples to be computed */ + blkCnt = outBlockSize; + + while(blkCnt > 0u) + { + /* Copy decimation factor number of new input samples into the state buffer */ + i = S->M; + + do + { + *pStateCurnt++ = *pSrc++; + + } while(--i); + + /* Set accumulator to zero */ + sum0 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = pCoeffs; + + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Read coefficients */ + c0 = *pb++; + + /* Fetch 1 state variable */ + x0 = *px++; + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance the state pointer by the decimation factor + * to process the next group of decimation factor number samples */ + pState = pState + S->M; + + /* The result is in the accumulator, store in the destination buffer. */ + *pDst++ = (q31_t) (sum0 >> 31); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the start of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + i = numTaps - 1u; + + /* copy data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR_decimate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_f32.c index 8ae71f796..1a166544e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_f32.c @@ -1,436 +1,436 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_f32.c -* -* Description: Floating-point FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup FIR Finite Impulse Response (FIR) Filters - * - * This set of functions implements Finite Impulse Response (FIR) filters - * for Q7, Q15, Q31, and floating-point data types. - * Fast versions of Q15 and Q31 are also provided on Cortex-M4 and Cortex-M3. - * The functions operate on blocks of input and output data and each call to the function processes - * blockSize samples through the filter. pSrc and - * pDst points to input and output arrays containing blockSize values. - * - * \par Algorithm: - * The FIR filter algorithm is based upon a sequence of multiply-accumulate (MAC) operations. - * Each filter coefficient b[n] is multiplied by a state variable which equals a previous input sample x[n]. - *
   
- *    y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]   
- * 
- * \par - * \image html FIR.gif "Finite Impulse Response filter" - * \par - * pCoeffs points to a coefficient array of size numTaps. - * Coefficients are stored in time reversed order. - * \par - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to a state array of size numTaps + blockSize - 1. - * Samples in the state buffer are stored in the following order. - * \par - *
   
- *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}   
- * 
- * \par - * Note that the length of the state buffer exceeds the length of the coefficient array by blockSize-1. - * The increased state buffer length allows circular addressing, which is traditionally used in the FIR filters, - * to be avoided and yields a significant speed improvement. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * There are separate instance structure declarations for each of the 4 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * The code below statically initializes each of the 4 different data type filter instance structures - *
   
- *arm_fir_instance_f32 S = {numTaps, pState, pCoeffs};   
- *arm_fir_instance_q31 S = {numTaps, pState, pCoeffs};   
- *arm_fir_instance_q15 S = {numTaps, pState, pCoeffs};   
- *arm_fir_instance_q7 S =  {numTaps, pState, pCoeffs};   
- * 
- * - * where numTaps is the number of filter coefficients in the filter; pState is the address of the state buffer; - * pCoeffs is the address of the coefficient buffer. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the FIR filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * - * @param[in] *S points to an instance of the floating-point FIR filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - */ - -void arm_fir_f32( - const arm_fir_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt; /* Loop counters */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t acc0, acc1, acc2, acc3; /* Accumulators */ - float32_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Set all accumulators to zero */ - acc0 = 0.0f; - acc1 = 0.0f; - acc2 = 0.0f; - acc3 = 0.0f; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Read the first three samples from the state buffer: x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ - x0 = *px++; - x1 = *px++; - x2 = *px++; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2u; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x3 = *(px++); - - /* acc0 += b[numTaps-1] * x[n-numTaps] */ - acc0 += x0 * c0; - - /* acc1 += b[numTaps-1] * x[n-numTaps-1] */ - acc1 += x1 * c0; - - /* acc2 += b[numTaps-1] * x[n-numTaps-2] */ - acc2 += x2 * c0; - - /* acc3 += b[numTaps-1] * x[n-numTaps-3] */ - acc3 += x3 * c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - acc0 += x1 * c0; - acc1 += x2 * c0; - acc2 += x3 * c0; - acc3 += x0 * c0; - - /* Read the b[numTaps-3] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += x2 * c0; - acc1 += x3 * c0; - acc2 += x0 * c0; - acc3 += x1 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += x3 * c0; - acc1 += x0 * c0; - acc2 += x1 * c0; - acc3 += x2 * c0; - - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += x0 * c0; - acc1 += x1 * c0; - acc2 += x2 * c0; - acc3 += x3 * c0; - - /* Reuse the present sample states for next sample */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4; - - /* The results in the 4 accumulators, store in the destination buffer. */ - *pDst++ = acc0; - *pDst++ = acc1; - *pDst++ = acc2; - *pDst++ = acc3; - - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0.0f; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = (pCoeffs); - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - acc0 += *px++ * *pb++; - i--; - - } while(i > 0u); - - /* The result is store in the destination buffer. */ - *pDst++ = acc0; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t acc; - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Initialize blkCnt with blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc = 0.0f; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = pCoeffs; - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ - acc += *px++ * *pb++; - i--; - - } while(i > 0u); - - /* The result is store in the destination buffer. */ - *pDst++ = acc; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the starting of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Copy numTaps number of values */ - tapCnt = numTaps - 1u; - - /* Copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_f32.c +* +* Description: Floating-point FIR filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup FIR Finite Impulse Response (FIR) Filters + * + * This set of functions implements Finite Impulse Response (FIR) filters + * for Q7, Q15, Q31, and floating-point data types. + * Fast versions of Q15 and Q31 are also provided on Cortex-M4 and Cortex-M3. + * The functions operate on blocks of input and output data and each call to the function processes + * blockSize samples through the filter. pSrc and + * pDst points to input and output arrays containing blockSize values. + * + * \par Algorithm: + * The FIR filter algorithm is based upon a sequence of multiply-accumulate (MAC) operations. + * Each filter coefficient b[n] is multiplied by a state variable which equals a previous input sample x[n]. + *
   
+ *    y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]   
+ * 
+ * \par + * \image html FIR.gif "Finite Impulse Response filter" + * \par + * pCoeffs points to a coefficient array of size numTaps. + * Coefficients are stored in time reversed order. + * \par + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to a state array of size numTaps + blockSize - 1. + * Samples in the state buffer are stored in the following order. + * \par + *
   
+ *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}   
+ * 
+ * \par + * Note that the length of the state buffer exceeds the length of the coefficient array by blockSize-1. + * The increased state buffer length allows circular addressing, which is traditionally used in the FIR filters, + * to be avoided and yields a significant speed improvement. + * The state variables are updated after each block of data is processed; the coefficients are untouched. + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter. + * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. + * There are separate instance structure declarations for each of the 4 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Set the values in the state buffer to zeros before static initialization. + * The code below statically initializes each of the 4 different data type filter instance structures + *
   
+ *arm_fir_instance_f32 S = {numTaps, pState, pCoeffs};   
+ *arm_fir_instance_q31 S = {numTaps, pState, pCoeffs};   
+ *arm_fir_instance_q15 S = {numTaps, pState, pCoeffs};   
+ *arm_fir_instance_q7 S =  {numTaps, pState, pCoeffs};   
+ * 
+ * + * where numTaps is the number of filter coefficients in the filter; pState is the address of the state buffer; + * pCoeffs is the address of the coefficient buffer. + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the FIR filter functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + +/** + * @addtogroup FIR + * @{ + */ + +/** + * + * @param[in] *S points to an instance of the floating-point FIR filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + */ + +void arm_fir_f32( + const arm_fir_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + + float32_t *pState = S->pState; /* State pointer */ + float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + float32_t *pStateCurnt; /* Points to the current sample of the state */ + float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + uint32_t i, tapCnt, blkCnt; /* Loop counters */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + float32_t acc0, acc1, acc2, acc3; /* Accumulators */ + float32_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ + + + /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Apply loop unrolling and compute 4 output values simultaneously. + * The variables acc0 ... acc3 hold output values that are being computed: + * + * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] + * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] + * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] + * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] + */ + blkCnt = blockSize >> 2; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Copy four new input samples into the state buffer */ + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + + /* Set all accumulators to zero */ + acc0 = 0.0f; + acc1 = 0.0f; + acc2 = 0.0f; + acc3 = 0.0f; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Read the first three samples from the state buffer: x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ + x0 = *px++; + x1 = *px++; + x2 = *px++; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2u; + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-4 coefficients. */ + while(tapCnt > 0u) + { + /* Read the b[numTaps-1] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-3] sample */ + x3 = *(px++); + + /* acc0 += b[numTaps-1] * x[n-numTaps] */ + acc0 += x0 * c0; + + /* acc1 += b[numTaps-1] * x[n-numTaps-1] */ + acc1 += x1 * c0; + + /* acc2 += b[numTaps-1] * x[n-numTaps-2] */ + acc2 += x2 * c0; + + /* acc3 += b[numTaps-1] * x[n-numTaps-3] */ + acc3 += x3 * c0; + + /* Read the b[numTaps-2] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulate */ + acc0 += x1 * c0; + acc1 += x2 * c0; + acc2 += x3 * c0; + acc3 += x0 * c0; + + /* Read the b[numTaps-3] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += x2 * c0; + acc1 += x3 * c0; + acc2 += x0 * c0; + acc3 += x1 * c0; + + /* Read the b[numTaps-4] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += x3 * c0; + acc1 += x0 * c0; + acc2 += x1 * c0; + acc3 += x2 * c0; + + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Read coefficients */ + c0 = *(pb++); + + /* Fetch 1 state variable */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += x0 * c0; + acc1 += x1 * c0; + acc2 += x2 * c0; + acc3 += x3 * c0; + + /* Reuse the present sample states for next sample */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance the state pointer by 4 to process the next group of 4 samples */ + pState = pState + 4; + + /* The results in the 4 accumulators, store in the destination buffer. */ + *pDst++ = acc0; + *pDst++ = acc1; + *pDst++ = acc2; + *pDst++ = acc3; + + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* Copy one sample at a time into state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Set the accumulator to zero */ + acc0 = 0.0f; + + /* Initialize state pointer */ + px = pState; + + /* Initialize Coefficient pointer */ + pb = (pCoeffs); + + i = numTaps; + + /* Perform the multiply-accumulates */ + do + { + acc0 += *px++ * *pb++; + i--; + + } while(i > 0u); + + /* The result is store in the destination buffer. */ + *pDst++ = acc0; + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + tapCnt = (numTaps - 1u) >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Calculate remaining number of copies */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + float32_t acc; + + /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Initialize blkCnt with blockSize */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Copy one sample at a time into state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Set the accumulator to zero */ + acc = 0.0f; + + /* Initialize state pointer */ + px = pState; + + /* Initialize Coefficient pointer */ + pb = pCoeffs; + + i = numTaps; + + /* Perform the multiply-accumulates */ + do + { + /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ + acc += *px++ * *pb++; + i--; + + } while(i > 0u); + + /* The result is store in the destination buffer. */ + *pDst++ = acc; + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the starting of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + /* Copy numTaps number of values */ + tapCnt = numTaps - 1u; + + /* Copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q15.c index ed333a7cb..cbd0827df 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q15.c @@ -1,279 +1,279 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_fast_q15.c -* -* Description: Q15 Fast FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.9 2010/08/16 -* Initial version -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @param[in] *S points to an instance of the Q15 FIR filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around and distorts the result. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits. - * The 2.30 accumulator is then truncated to 2.15 format and saturated to yield the 1.15 result. - * - * \par - * Refer to the function arm_fir_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. Both the slow and the fast versions use the same instance structure. - * Use the function arm_fir_init_q15() to initialize the filter structure. - */ - -void arm_fir_fast_q15( - const arm_fir_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px1; /* Temporary q15 pointer for state buffer */ - q31_t *pb; /* Temporary pointer for coefficient buffer */ - q31_t *px2; /* Temporary q31 pointer for SIMD state buffer accesses */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold SIMD state and coefficient values */ - q31_t acc0, acc1, acc2, acc3; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of taps in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer. - ** Use 32-bit SIMD to move the 16-bit data. Only requires two copies. */ - *__SIMD32(pStateCurnt)++ = *__SIMD32(pSrc)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pSrc)++; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Initialize state pointer of type q15 */ - px1 = pState; - - /* Initialize coeff pointer of type q31 */ - pb = (q31_t *) (pCoeffs); - - /* Read the first two samples from the state buffer: x[n-N], x[n-N-1] */ - x0 = *(q31_t *) (px1++); - - /* Read the third and forth samples from the state buffer: x[n-N-1], x[n-N-2] */ - x1 = *(q31_t *) (px1++); - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - tapCnt = numTaps >> 2; - do - { - /* Read the first two coefficients using SIMD: b[N] and b[N-1] coefficients */ - c0 = *(pb++); - - /* acc0 += b[N] * x[n-N] + b[N-1] * x[n-N-1] */ - acc0 = __SMLAD(x0, c0, acc0); - - /* acc1 += b[N] * x[n-N-1] + b[N-1] * x[n-N-2] */ - acc1 = __SMLAD(x1, c0, acc1); - - /* Read state x[n-N-2], x[n-N-3] */ - x2 = *(q31_t *) (px1++); - - /* Read state x[n-N-3], x[n-N-4] */ - x3 = *(q31_t *) (px1++); - - /* acc2 += b[N] * x[n-N-2] + b[N-1] * x[n-N-3] */ - acc2 = __SMLAD(x2, c0, acc2); - - /* acc3 += b[N] * x[n-N-3] + b[N-1] * x[n-N-4] */ - acc3 = __SMLAD(x3, c0, acc3); - - /* Read coefficients b[N-2], b[N-3] */ - c0 = *(pb++); - - /* acc0 += b[N-2] * x[n-N-2] + b[N-3] * x[n-N-3] */ - acc0 = __SMLAD(x2, c0, acc0); - - /* acc1 += b[N-2] * x[n-N-3] + b[N-3] * x[n-N-4] */ - acc1 = __SMLAD(x3, c0, acc1); - - /* Read state x[n-N-4], x[n-N-5] */ - x0 = *(q31_t *) (px1++); - - /* Read state x[n-N-5], x[n-N-6] */ - x1 = *(q31_t *) (px1++); - - /* acc2 += b[N-2] * x[n-N-4] + b[N-3] * x[n-N-5] */ - acc2 = __SMLAD(x0, c0, acc2); - - /* acc3 += b[N-2] * x[n-N-5] + b[N-3] * x[n-N-6] */ - acc3 = __SMLAD(x1, c0, acc3); - tapCnt--; - - } - while(tapCnt > 0u); - - /* If the filter length is not a multiple of 4, compute the remaining filter taps. - ** This is always 2 taps since the filter length is always even. */ - if((numTaps & 0x3u) != 0u) - { - /* Read 2 coefficients */ - c0 = *(pb++); - /* Fetch 4 state variables */ - x2 = *(q31_t *) (px1++); - x3 = *(q31_t *) (px1++); - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLAD(x2, c0, acc2); - acc3 = __SMLAD(x3, c0, acc3); - } - - /* The results in the 4 accumulators are in 2.30 format. Convert to 1.15 with saturation. - ** Then store the 4 outputs in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT((acc0 >> 15), (acc1 >> 15), 16u); - *__SIMD32(pDst)++ = __PKHBT((acc2 >> 15), (acc3 >> 15), 16u); - -#else - - *__SIMD32(pDst)++ = __PKHBT((acc1 >> 15), (acc0 >> 15), 16u); - *__SIMD32(pDst)++ = __PKHBT((acc3 >> 15), (acc2 >> 15), 16u); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - while(blkCnt > 0u) - { - /* Copy two samples into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Use SIMD to hold states and coefficients */ - px2 = (q31_t *) pState; - pb = (q31_t *) (pCoeffs); - tapCnt = numTaps >> 1; - - do - { - acc0 = __SMLAD(*px2++, *(pb++), acc0); - tapCnt--; - } - while(tapCnt > 0u); - - /* The result is in 2.30 format. Convert to 1.15 with saturation. - ** Then store the output in the destination buffer. */ - *pDst++ = (q15_t) ((acc0 >> 15)); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - /* Calculation of count for copying integer writes */ - tapCnt = (numTaps - 1u) >> 2; - - while(tapCnt > 0u) - { - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - tapCnt--; - } - - /* Calculation of count for remaining q15_t data */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* copy remaining data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } -} - -/** - * @} end of FIR group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_fast_q15.c +* +* Description: Q15 Fast FIR filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.9 2010/08/16 +* Initial version +* +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR + * @{ + */ + +/** + * @param[in] *S points to an instance of the Q15 FIR filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * This fast version uses a 32-bit accumulator with 2.30 format. + * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around and distorts the result. + * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits. + * The 2.30 accumulator is then truncated to 2.15 format and saturated to yield the 1.15 result. + * + * \par + * Refer to the function arm_fir_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. Both the slow and the fast versions use the same instance structure. + * Use the function arm_fir_init_q15() to initialize the filter structure. + */ + +void arm_fir_fast_q15( + const arm_fir_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + q15_t *pState = S->pState; /* State pointer */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q15_t *pStateCurnt; /* Points to the current sample of the state */ + q15_t *px1; /* Temporary q15 pointer for state buffer */ + q31_t *pb; /* Temporary pointer for coefficient buffer */ + q31_t *px2; /* Temporary q31 pointer for SIMD state buffer accesses */ + q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold SIMD state and coefficient values */ + q31_t acc0, acc1, acc2, acc3; /* Accumulators */ + uint32_t numTaps = S->numTaps; /* Number of taps in the filter */ + uint32_t tapCnt, blkCnt; /* Loop counters */ + + /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Apply loop unrolling and compute 4 output values simultaneously. + * The variables acc0 ... acc3 hold output values that are being computed: + * + * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] + * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] + * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] + * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] + */ + blkCnt = blockSize >> 2; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Copy four new input samples into the state buffer. + ** Use 32-bit SIMD to move the 16-bit data. Only requires two copies. */ + *__SIMD32(pStateCurnt)++ = *__SIMD32(pSrc)++; + *__SIMD32(pStateCurnt)++ = *__SIMD32(pSrc)++; + + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* Initialize state pointer of type q15 */ + px1 = pState; + + /* Initialize coeff pointer of type q31 */ + pb = (q31_t *) (pCoeffs); + + /* Read the first two samples from the state buffer: x[n-N], x[n-N-1] */ + x0 = *(q31_t *) (px1++); + + /* Read the third and forth samples from the state buffer: x[n-N-1], x[n-N-2] */ + x1 = *(q31_t *) (px1++); + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-4 coefficients. */ + tapCnt = numTaps >> 2; + do + { + /* Read the first two coefficients using SIMD: b[N] and b[N-1] coefficients */ + c0 = *(pb++); + + /* acc0 += b[N] * x[n-N] + b[N-1] * x[n-N-1] */ + acc0 = __SMLAD(x0, c0, acc0); + + /* acc1 += b[N] * x[n-N-1] + b[N-1] * x[n-N-2] */ + acc1 = __SMLAD(x1, c0, acc1); + + /* Read state x[n-N-2], x[n-N-3] */ + x2 = *(q31_t *) (px1++); + + /* Read state x[n-N-3], x[n-N-4] */ + x3 = *(q31_t *) (px1++); + + /* acc2 += b[N] * x[n-N-2] + b[N-1] * x[n-N-3] */ + acc2 = __SMLAD(x2, c0, acc2); + + /* acc3 += b[N] * x[n-N-3] + b[N-1] * x[n-N-4] */ + acc3 = __SMLAD(x3, c0, acc3); + + /* Read coefficients b[N-2], b[N-3] */ + c0 = *(pb++); + + /* acc0 += b[N-2] * x[n-N-2] + b[N-3] * x[n-N-3] */ + acc0 = __SMLAD(x2, c0, acc0); + + /* acc1 += b[N-2] * x[n-N-3] + b[N-3] * x[n-N-4] */ + acc1 = __SMLAD(x3, c0, acc1); + + /* Read state x[n-N-4], x[n-N-5] */ + x0 = *(q31_t *) (px1++); + + /* Read state x[n-N-5], x[n-N-6] */ + x1 = *(q31_t *) (px1++); + + /* acc2 += b[N-2] * x[n-N-4] + b[N-3] * x[n-N-5] */ + acc2 = __SMLAD(x0, c0, acc2); + + /* acc3 += b[N-2] * x[n-N-5] + b[N-3] * x[n-N-6] */ + acc3 = __SMLAD(x1, c0, acc3); + tapCnt--; + + } + while(tapCnt > 0u); + + /* If the filter length is not a multiple of 4, compute the remaining filter taps. + ** This is always 2 taps since the filter length is always even. */ + if((numTaps & 0x3u) != 0u) + { + /* Read 2 coefficients */ + c0 = *(pb++); + /* Fetch 4 state variables */ + x2 = *(q31_t *) (px1++); + x3 = *(q31_t *) (px1++); + + /* Perform the multiply-accumulates */ + acc0 = __SMLAD(x0, c0, acc0); + acc1 = __SMLAD(x1, c0, acc1); + acc2 = __SMLAD(x2, c0, acc2); + acc3 = __SMLAD(x3, c0, acc3); + } + + /* The results in the 4 accumulators are in 2.30 format. Convert to 1.15 with saturation. + ** Then store the 4 outputs in the destination buffer. */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = __PKHBT((acc0 >> 15), (acc1 >> 15), 16u); + *__SIMD32(pDst)++ = __PKHBT((acc2 >> 15), (acc3 >> 15), 16u); + +#else + + *__SIMD32(pDst)++ = __PKHBT((acc1 >> 15), (acc0 >> 15), 16u); + *__SIMD32(pDst)++ = __PKHBT((acc3 >> 15), (acc2 >> 15), 16u); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Advance the state pointer by 4 to process the next group of 4 samples */ + pState = pState + 4; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + while(blkCnt > 0u) + { + /* Copy two samples into state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Set the accumulator to zero */ + acc0 = 0; + + /* Use SIMD to hold states and coefficients */ + px2 = (q31_t *) pState; + pb = (q31_t *) (pCoeffs); + tapCnt = numTaps >> 1; + + do + { + acc0 = __SMLAD(*px2++, *(pb++), acc0); + tapCnt--; + } + while(tapCnt > 0u); + + /* The result is in 2.30 format. Convert to 1.15 with saturation. + ** Then store the output in the destination buffer. */ + *pDst++ = (q15_t) ((acc0 >> 15)); + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + /* Calculation of count for copying integer writes */ + tapCnt = (numTaps - 1u) >> 2; + + while(tapCnt > 0u) + { + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + + tapCnt--; + } + + /* Calculation of count for remaining q15_t data */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* copy remaining data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } +} + +/** + * @} end of FIR group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q31.c index 62449352c..6cbfa7f9d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q31.c @@ -1,303 +1,303 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_fast_q31.c -* -* Description: Processing function for the Q31 Fast FIR filter. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.9 2010/08/27 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @param[in] *S points to an instance of the Q31 structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * - * \par - * This function is optimized for speed at the expense of fixed-point precision and overflow protection. - * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. - * These intermediate results are added to a 2.30 accumulator. - * Finally, the accumulator is saturated and converted to a 1.31 result. - * The fast version has the same overflow behavior as the standard version and provides less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits. - * - * \par - * Refer to the function arm_fir_q31() for a slower implementation of this function which uses a 64-bit accumulator to provide higher precision. Both the slow and the fast versions use the same instance structure. - * Use the function arm_fir_init_q31() to initialize the filter structure. - */ - -void arm_fir_fast_q31( - const arm_fir_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t x0, x1, x2, x3; /* Temporary variables to hold state */ - q31_t c0; /* Temporary variable to hold coefficient value */ - q31_t *px; /* Temporary pointer for state */ - q31_t *pb; /* Temporary pointer for coefficient buffer */ - q63_t acc0, acc1, acc2, acc3; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt; /* Loop counters */ - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Read the first three samples from the state buffer: - * x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - i = tapCnt; - - while(i > 0u) - { - /* Read the b[numTaps] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x3 = *(px++); - - /* acc0 += b[numTaps] * x[n-numTaps] */ - acc0 = (q31_t) ((((q63_t) x0 * c0) + (acc0 << 32)) >> 32); - - /* acc1 += b[numTaps] * x[n-numTaps-1] */ - acc1 = (q31_t) ((((q63_t) x1 * c0) + (acc1 << 32)) >> 32); - - /* acc2 += b[numTaps] * x[n-numTaps-2] */ - acc2 = (q31_t) ((((q63_t) x2 * c0) + (acc2 << 32)) >> 32); - - /* acc3 += b[numTaps] * x[n-numTaps-3] */ - acc3 = (q31_t) ((((q63_t) x3 * c0) + (acc3 << 32)) >> 32); - - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 = (q31_t) ((((q63_t) x1 * c0) + (acc0 << 32)) >> 32); - acc1 = (q31_t) ((((q63_t) x2 * c0) + (acc1 << 32)) >> 32); - acc2 = (q31_t) ((((q63_t) x3 * c0) + (acc2 << 32)) >> 32); - acc3 = (q31_t) ((((q63_t) x0 * c0) + (acc3 << 32)) >> 32); - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 = (q31_t) ((((q63_t) x2 * c0) + (acc0 << 32)) >> 32); - acc1 = (q31_t) ((((q63_t) x3 * c0) + (acc1 << 32)) >> 32); - acc2 = (q31_t) ((((q63_t) x0 * c0) + (acc2 << 32)) >> 32); - acc3 = (q31_t) ((((q63_t) x1 * c0) + (acc3 << 32)) >> 32); - - /* Read the b[numTaps-3] coefficients */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 = (q31_t) ((((q63_t) x3 * c0) + (acc0 << 32)) >> 32); - acc1 = (q31_t) ((((q63_t) x0 * c0) + (acc1 << 32)) >> 32); - acc2 = (q31_t) ((((q63_t) x1 * c0) + (acc2 << 32)) >> 32); - acc3 = (q31_t) ((((q63_t) x2 * c0) + (acc3 << 32)) >> 32); - i--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - - i = numTaps - (tapCnt * 4u); - while(i > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 = (q31_t) ((((q63_t) x0 * c0) + (acc0 << 32)) >> 32); - acc1 = (q31_t) ((((q63_t) x1 * c0) + (acc1 << 32)) >> 32); - acc2 = (q31_t) ((((q63_t) x2 * c0) + (acc2 << 32)) >> 32); - acc3 = (q31_t) ((((q63_t) x3 * c0) + (acc3 << 32)) >> 32); - - /* Reuse the present sample states for next sample */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4; - - /* The results in the 4 accumulators are in 2.30 format. Convert to 1.31 - ** Then store the 4 outputs in the destination buffer. */ - *pDst++ = (q31_t) (acc0 << 1); - *pDst++ = (q31_t) (acc1 << 1); - *pDst++ = (q31_t) (acc2 << 1); - *pDst++ = (q31_t) (acc3 << 1); - - /* Decrement the samples loop counter */ - blkCnt--; - } - - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 4u; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = (pCoeffs); - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - acc0 = (q31_t) ((((q63_t) * (px++) * (*(pb++))) + (acc0 << 32)) >> 32); - i--; - } while(i > 0u); - - /* The result is in 2.30 format. Convert to 1.31 - ** Then store the output in the destination buffer. */ - *pDst++ = (q31_t) (acc0 << 1); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -} - -/** - * @} end of FIR group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_fast_q31.c +* +* Description: Processing function for the Q31 Fast FIR filter. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.9 2010/08/27 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR + * @{ + */ + +/** + * @param[in] *S points to an instance of the Q31 structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block output data. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * + * \par + * This function is optimized for speed at the expense of fixed-point precision and overflow protection. + * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. + * These intermediate results are added to a 2.30 accumulator. + * Finally, the accumulator is saturated and converted to a 1.31 result. + * The fast version has the same overflow behavior as the standard version and provides less precision since it discards the low 32 bits of each multiplication result. + * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits. + * + * \par + * Refer to the function arm_fir_q31() for a slower implementation of this function which uses a 64-bit accumulator to provide higher precision. Both the slow and the fast versions use the same instance structure. + * Use the function arm_fir_init_q31() to initialize the filter structure. + */ + +void arm_fir_fast_q31( + const arm_fir_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t *pState = S->pState; /* State pointer */ + q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *pStateCurnt; /* Points to the current sample of the state */ + q31_t x0, x1, x2, x3; /* Temporary variables to hold state */ + q31_t c0; /* Temporary variable to hold coefficient value */ + q31_t *px; /* Temporary pointer for state */ + q31_t *pb; /* Temporary pointer for coefficient buffer */ + q63_t acc0, acc1, acc2, acc3; /* Accumulators */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + uint32_t i, tapCnt, blkCnt; /* Loop counters */ + + /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Apply loop unrolling and compute 4 output values simultaneously. + * The variables acc0 ... acc3 hold output values that are being computed: + * + * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] + * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] + * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] + * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] + */ + blkCnt = blockSize >> 2; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Copy four new input samples into the state buffer */ + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coefficient pointer */ + pb = pCoeffs; + + /* Read the first three samples from the state buffer: + * x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + i = tapCnt; + + while(i > 0u) + { + /* Read the b[numTaps] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-3] sample */ + x3 = *(px++); + + /* acc0 += b[numTaps] * x[n-numTaps] */ + acc0 = (q31_t) ((((q63_t) x0 * c0) + (acc0 << 32)) >> 32); + + /* acc1 += b[numTaps] * x[n-numTaps-1] */ + acc1 = (q31_t) ((((q63_t) x1 * c0) + (acc1 << 32)) >> 32); + + /* acc2 += b[numTaps] * x[n-numTaps-2] */ + acc2 = (q31_t) ((((q63_t) x2 * c0) + (acc2 << 32)) >> 32); + + /* acc3 += b[numTaps] * x[n-numTaps-3] */ + acc3 = (q31_t) ((((q63_t) x3 * c0) + (acc3 << 32)) >> 32); + + /* Read the b[numTaps-1] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 = (q31_t) ((((q63_t) x1 * c0) + (acc0 << 32)) >> 32); + acc1 = (q31_t) ((((q63_t) x2 * c0) + (acc1 << 32)) >> 32); + acc2 = (q31_t) ((((q63_t) x3 * c0) + (acc2 << 32)) >> 32); + acc3 = (q31_t) ((((q63_t) x0 * c0) + (acc3 << 32)) >> 32); + + /* Read the b[numTaps-2] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 = (q31_t) ((((q63_t) x2 * c0) + (acc0 << 32)) >> 32); + acc1 = (q31_t) ((((q63_t) x3 * c0) + (acc1 << 32)) >> 32); + acc2 = (q31_t) ((((q63_t) x0 * c0) + (acc2 << 32)) >> 32); + acc3 = (q31_t) ((((q63_t) x1 * c0) + (acc3 << 32)) >> 32); + + /* Read the b[numTaps-3] coefficients */ + c0 = *(pb++); + + /* Read x[n-numTaps-6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 = (q31_t) ((((q63_t) x3 * c0) + (acc0 << 32)) >> 32); + acc1 = (q31_t) ((((q63_t) x0 * c0) + (acc1 << 32)) >> 32); + acc2 = (q31_t) ((((q63_t) x1 * c0) + (acc2 << 32)) >> 32); + acc3 = (q31_t) ((((q63_t) x2 * c0) + (acc3 << 32)) >> 32); + i--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + + i = numTaps - (tapCnt * 4u); + while(i > 0u) + { + /* Read coefficients */ + c0 = *(pb++); + + /* Fetch 1 state variable */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 = (q31_t) ((((q63_t) x0 * c0) + (acc0 << 32)) >> 32); + acc1 = (q31_t) ((((q63_t) x1 * c0) + (acc1 << 32)) >> 32); + acc2 = (q31_t) ((((q63_t) x2 * c0) + (acc2 << 32)) >> 32); + acc3 = (q31_t) ((((q63_t) x3 * c0) + (acc3 << 32)) >> 32); + + /* Reuse the present sample states for next sample */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + i--; + } + + /* Advance the state pointer by 4 to process the next group of 4 samples */ + pState = pState + 4; + + /* The results in the 4 accumulators are in 2.30 format. Convert to 1.31 + ** Then store the 4 outputs in the destination buffer. */ + *pDst++ = (q31_t) (acc0 << 1); + *pDst++ = (q31_t) (acc1 << 1); + *pDst++ = (q31_t) (acc2 << 1); + *pDst++ = (q31_t) (acc3 << 1); + + /* Decrement the samples loop counter */ + blkCnt--; + } + + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 4u; + + while(blkCnt > 0u) + { + /* Copy one sample at a time into state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Set the accumulator to zero */ + acc0 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize Coefficient pointer */ + pb = (pCoeffs); + + i = numTaps; + + /* Perform the multiply-accumulates */ + do + { + acc0 = (q31_t) ((((q63_t) * (px++) * (*(pb++))) + (acc0 << 32)) >> 32); + i--; + } while(i > 0u); + + /* The result is in 2.30 format. Convert to 1.31 + ** Then store the output in the destination buffer. */ + *pDst++ = (q31_t) (acc0 << 1); + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the samples loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + tapCnt = (numTaps - 1u) >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Calculate remaining number of copies */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +} + +/** + * @} end of FIR group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_f32.c index a06ab0523..100d4ac34 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_f32.c @@ -1,91 +1,91 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_init_f32.c -* -* Description: Floating-point FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @details - * - * @param[in,out] *S points to an instance of the floating-point FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficients buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of samples that are processed per call. - * @return none. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_fir_f32(). - */ - -void arm_fir_init_f32( - arm_fir_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and the size of state buffer is (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_init_f32.c +* +* Description: Floating-point FIR filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR + * @{ + */ + +/** + * @details + * + * @param[in,out] *S points to an instance of the floating-point FIR filter structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficients buffer. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of samples that are processed per call. + * @return none. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to the array of state variables. + * pState is of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_fir_f32(). + */ + +void arm_fir_init_f32( + arm_fir_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and the size of state buffer is (blockSize + numTaps - 1) */ + memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(float32_t)); + + /* Assign state pointer */ + S->pState = pState; + +} + +/** + * @} end of FIR group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q15.c index a160b83aa..9d01aa13a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q15.c @@ -1,149 +1,149 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_init_q15.c -* -* Description: Q15 FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* ------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @param[in,out] *S points to an instance of the Q15 FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4. - * @param[in] *pCoeffs points to the filter coefficients buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize is number of samples processed per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if - * numTaps is not greater than or equal to 4 and even. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * Note that numTaps must be even and greater than or equal to 4. - * To implement an odd length filter simply increase numTaps by 1 and set the last coefficient to zero. - * For example, to implement a filter with numTaps=3 and coefficients - *
   
- *     {0.3, -0.8, 0.3}   
- * 
- * set numTaps=4 and use the coefficients: - *
   
- *     {0.3, -0.8, 0.3, 0}.   
- * 
- * Similarly, to implement a two point filter - *
   
- *     {0.3, -0.3}   
- * 
- * set numTaps=4 and use the coefficients: - *
   
- *     {0.3, -0.3, 0, 0}.   
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1, where blockSize is the number of input samples processed by each call to arm_fir_q15(). - */ - -arm_status arm_fir_init_q15( - arm_fir_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize) -{ - arm_status status; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* The Number of filter coefficients in the filter must be even and at least 4 */ - if((numTaps < 4u) || (numTaps & 0x1u)) - { - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -#else - - /* Run the below code for Cortex-M0 */ - - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - status = ARM_MATH_SUCCESS; - - return (status); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_init_q15.c +* +* Description: Q15 FIR filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* ------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR + * @{ + */ + +/** + * @param[in,out] *S points to an instance of the Q15 FIR filter structure. + * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4. + * @param[in] *pCoeffs points to the filter coefficients buffer. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize is number of samples processed per call. + * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if + * numTaps is not greater than or equal to 4 and even. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * Note that numTaps must be even and greater than or equal to 4. + * To implement an odd length filter simply increase numTaps by 1 and set the last coefficient to zero. + * For example, to implement a filter with numTaps=3 and coefficients + *
   
+ *     {0.3, -0.8, 0.3}   
+ * 
+ * set numTaps=4 and use the coefficients: + *
   
+ *     {0.3, -0.8, 0.3, 0}.   
+ * 
+ * Similarly, to implement a two point filter + *
   
+ *     {0.3, -0.3}   
+ * 
+ * set numTaps=4 and use the coefficients: + *
   
+ *     {0.3, -0.3, 0, 0}.   
+ * 
+ * \par + * pState points to the array of state variables. + * pState is of length numTaps+blockSize-1, where blockSize is the number of input samples processed by each call to arm_fir_q15(). + */ + +arm_status arm_fir_init_q15( + arm_fir_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize) +{ + arm_status status; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* The Number of filter coefficients in the filter must be even and at least 4 */ + if((numTaps < 4u) || (numTaps & 0x1u)) + { + status = ARM_MATH_ARGUMENT_ERROR; + } + else + { + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ + memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); + + /* Assign state pointer */ + S->pState = pState; + + status = ARM_MATH_SUCCESS; + } + + return (status); + +#else + + /* Run the below code for Cortex-M0 */ + + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ + memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); + + /* Assign state pointer */ + S->pState = pState; + + status = ARM_MATH_SUCCESS; + + return (status); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q31.c index c9204946b..19762289e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q31.c @@ -1,91 +1,91 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_init_q31.c -* -* Description: Q31 FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @details - * - * @param[in,out] *S points to an instance of the Q31 FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficients buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of samples that are processed per call. - * @return none. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_fir_q31(). - */ - -void arm_fir_init_q31( - arm_fir_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and state array size is (blockSize + numTaps - 1) */ - memset(pState, 0, (blockSize + ((uint32_t) numTaps - 1u)) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_init_q31.c +* +* Description: Q31 FIR filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR + * @{ + */ + +/** + * @details + * + * @param[in,out] *S points to an instance of the Q31 FIR filter structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficients buffer. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of samples that are processed per call. + * @return none. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to the array of state variables. + * pState is of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_fir_q31(). + */ + +void arm_fir_init_q31( + arm_fir_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and state array size is (blockSize + numTaps - 1) */ + memset(pState, 0, (blockSize + ((uint32_t) numTaps - 1u)) * sizeof(q31_t)); + + /* Assign state pointer */ + S->pState = pState; + +} + +/** + * @} end of FIR group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q7.c index e4db89fc1..33b80a6dd 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q7.c @@ -1,89 +1,89 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_init_q7.c -* -* Description: Q7 FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* ------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ -/** - * @param[in,out] *S points to an instance of the Q7 FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficients buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of samples that are processed per call. - * @return none - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_fir_q7(). - */ - -void arm_fir_init_q7( - arm_fir_instance_q7 * S, - uint16_t numTaps, - q7_t * pCoeffs, - q7_t * pState, - uint32_t blockSize) -{ - - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q7_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_init_q7.c +* +* Description: Q7 FIR filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* ------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR + * @{ + */ +/** + * @param[in,out] *S points to an instance of the Q7 FIR filter structure. + * @param[in] numTaps Number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficients buffer. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of samples that are processed per call. + * @return none + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to the array of state variables. + * pState is of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_fir_q7(). + */ + +void arm_fir_init_q7( + arm_fir_instance_q7 * S, + uint16_t numTaps, + q7_t * pCoeffs, + q7_t * pState, + uint32_t blockSize) +{ + + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ + memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q7_t)); + + /* Assign state pointer */ + S->pState = pState; + +} + +/** + * @} end of FIR group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_f32.c index adcf4eec0..abee5bfba 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_f32.c @@ -1,399 +1,399 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_f32.c -* -* Description: FIR interpolation for floating-point sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @defgroup FIR_Interpolate Finite Impulse Response (FIR) Interpolator - * - * These functions combine an upsampler (zero stuffer) and an FIR filter. - * They are used in multirate systems for increasing the sample rate of a signal without introducing high frequency images. - * Conceptually, the functions are equivalent to the block diagram below: - * \image html FIRInterpolator.gif "Components included in the FIR Interpolator functions" - * After upsampling by a factor of L, the signal should be filtered by a lowpass filter with a normalized - * cutoff frequency of 1/L in order to eliminate high frequency copies of the spectrum. - * The user of the function is responsible for providing the filter coefficients. - * - * The FIR interpolator functions provided in the CMSIS DSP Library combine the upsampler and FIR filter in an efficient manner. - * The upsampler inserts L-1 zeros between each sample. - * Instead of multiplying by these zero values, the FIR filter is designed to skip them. - * This leads to an efficient implementation without any wasted effort. - * The functions operate on blocks of input and output data. - * pSrc points to an array of blockSize input values and - * pDst points to an array of blockSize*L output values. - * - * The library provides separate functions for Q15, Q31, and floating-point data types. - * - * \par Algorithm: - * The functions use a polyphase filter structure: - *
   
- *    y[n] = b[0] * x[n] + b[L]   * x[n-1] + ... + b[L*(phaseLength-1)] * x[n-phaseLength+1]   
- *    y[n+1] = b[1] * x[n] + b[L+1] * x[n-1] + ... + b[L*(phaseLength-1)+1] * x[n-phaseLength+1]   
- *    ...   
- *    y[n+(L-1)] = b[L-1] * x[n] + b[2*L-1] * x[n-1] + ....+ b[L*(phaseLength-1)+(L-1)] * x[n-phaseLength+1]   
- * 
- * This approach is more efficient than straightforward upsample-then-filter algorithms. - * With this method the computation is reduced by a factor of 1/L when compared to using a standard FIR filter. - * \par - * pCoeffs points to a coefficient array of size numTaps. - * numTaps must be a multiple of the interpolation factor L and this is checked by the - * initialization functions. - * Internally, the function divides the FIR filter's impulse response into shorter filters of length - * phaseLength=numTaps/L. - * Coefficients are stored in time reversed order. - * \par - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to a state array of size blockSize + phaseLength - 1. - * Samples in the state buffer are stored in the order: - * \par - *
   
- *    {x[n-phaseLength+1], x[n-phaseLength], x[n-phaseLength-1], x[n-phaseLength-2]....x[0], x[1], ..., x[blockSize-1]}   
- * 
- * The state variables are updated after each block of data is processed, the coefficients are untouched. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable array should be allocated separately. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - Checks to make sure that the length of the filter is a multiple of the interpolation factor. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * The code below statically initializes each of the 3 different data type filter instance structures - *
   
- * arm_fir_interpolate_instance_f32 S = {L, phaseLength, pCoeffs, pState};   
- * arm_fir_interpolate_instance_q31 S = {L, phaseLength, pCoeffs, pState};   
- * arm_fir_interpolate_instance_q15 S = {L, phaseLength, pCoeffs, pState};   
- * 
- * where L is the interpolation factor; phaseLength=numTaps/L is the - * length of each of the shorter FIR filters used internally, - * pCoeffs is the address of the coefficient buffer; - * pState is the address of the state buffer. - * Be sure to set the values in the state buffer to zeros when doing static initialization. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the FIR interpolate filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - -/** - * @brief Processing function for the floating-point FIR interpolator. - * @param[in] *S points to an instance of the floating-point FIR interpolator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - * @return none. - */ - -void arm_fir_interpolate_f32( - const arm_fir_interpolate_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t sum0; /* Accumulators */ - float32_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t i, blkCnt, j; /* Loop counters */ - uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ - - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (phaseLen - 1u); - - /* Total number of intput samples */ - blkCnt = blockSize; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Address modifier index of coefficient buffer */ - j = 1u; - - /* Loop over the Interpolation factor. */ - i = S->L; - while(i > 0u) - { - /* Set accumulator to zero */ - sum0 = 0.0f; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (S->L - j); - - /* Loop over the polyPhase length. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ - tapCnt = phaseLen >> 2u; - while(tapCnt > 0u) - { - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Upsampling is done by stuffing L-1 zeros between each sample. - * So instead of multiplying zeros with coefficients, - * Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = phaseLen % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum0 += *(ptr1++) * (*ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = sum0; - - /* Increment the address modifier index of coefficient buffer */ - j++; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (phaseLen - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (phaseLen - 1u) % 0x04u; - - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t sum; /* Accumulator */ - uint32_t i, blkCnt; /* Loop counters */ - uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ - - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (phaseLen - 1u); - - /* Total number of intput samples */ - blkCnt = blockSize; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Loop over the Interpolation factor. */ - i = S->L; - - while(i > 0u) - { - /* Set accumulator to zero */ - sum = 0.0f; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (i - 1u); - - /* Loop over the polyPhase length */ - tapCnt = phaseLen; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += *ptr1++ * *ptr2; - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = sum; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the start of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = phaseLen - 1u; - - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - /** - * @} end of FIR_Interpolate group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_interpolate_f32.c +* +* Description: FIR interpolation for floating-point sequences. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @defgroup FIR_Interpolate Finite Impulse Response (FIR) Interpolator + * + * These functions combine an upsampler (zero stuffer) and an FIR filter. + * They are used in multirate systems for increasing the sample rate of a signal without introducing high frequency images. + * Conceptually, the functions are equivalent to the block diagram below: + * \image html FIRInterpolator.gif "Components included in the FIR Interpolator functions" + * After upsampling by a factor of L, the signal should be filtered by a lowpass filter with a normalized + * cutoff frequency of 1/L in order to eliminate high frequency copies of the spectrum. + * The user of the function is responsible for providing the filter coefficients. + * + * The FIR interpolator functions provided in the CMSIS DSP Library combine the upsampler and FIR filter in an efficient manner. + * The upsampler inserts L-1 zeros between each sample. + * Instead of multiplying by these zero values, the FIR filter is designed to skip them. + * This leads to an efficient implementation without any wasted effort. + * The functions operate on blocks of input and output data. + * pSrc points to an array of blockSize input values and + * pDst points to an array of blockSize*L output values. + * + * The library provides separate functions for Q15, Q31, and floating-point data types. + * + * \par Algorithm: + * The functions use a polyphase filter structure: + *
   
+ *    y[n] = b[0] * x[n] + b[L]   * x[n-1] + ... + b[L*(phaseLength-1)] * x[n-phaseLength+1]   
+ *    y[n+1] = b[1] * x[n] + b[L+1] * x[n-1] + ... + b[L*(phaseLength-1)+1] * x[n-phaseLength+1]   
+ *    ...   
+ *    y[n+(L-1)] = b[L-1] * x[n] + b[2*L-1] * x[n-1] + ....+ b[L*(phaseLength-1)+(L-1)] * x[n-phaseLength+1]   
+ * 
+ * This approach is more efficient than straightforward upsample-then-filter algorithms. + * With this method the computation is reduced by a factor of 1/L when compared to using a standard FIR filter. + * \par + * pCoeffs points to a coefficient array of size numTaps. + * numTaps must be a multiple of the interpolation factor L and this is checked by the + * initialization functions. + * Internally, the function divides the FIR filter's impulse response into shorter filters of length + * phaseLength=numTaps/L. + * Coefficients are stored in time reversed order. + * \par + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to a state array of size blockSize + phaseLength - 1. + * Samples in the state buffer are stored in the order: + * \par + *
   
+ *    {x[n-phaseLength+1], x[n-phaseLength], x[n-phaseLength-1], x[n-phaseLength-2]....x[0], x[1], ..., x[blockSize-1]}   
+ * 
+ * The state variables are updated after each block of data is processed, the coefficients are untouched. + * + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter. + * Coefficient arrays may be shared among several instances while state variable array should be allocated separately. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * - Checks to make sure that the length of the filter is a multiple of the interpolation factor. + * + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * The code below statically initializes each of the 3 different data type filter instance structures + *
   
+ * arm_fir_interpolate_instance_f32 S = {L, phaseLength, pCoeffs, pState};   
+ * arm_fir_interpolate_instance_q31 S = {L, phaseLength, pCoeffs, pState};   
+ * arm_fir_interpolate_instance_q15 S = {L, phaseLength, pCoeffs, pState};   
+ * 
+ * where L is the interpolation factor; phaseLength=numTaps/L is the + * length of each of the shorter FIR filters used internally, + * pCoeffs is the address of the coefficient buffer; + * pState is the address of the state buffer. + * Be sure to set the values in the state buffer to zeros when doing static initialization. + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the FIR interpolate filter functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + +/** + * @addtogroup FIR_Interpolate + * @{ + */ + +/** + * @brief Processing function for the floating-point FIR interpolator. + * @param[in] *S points to an instance of the floating-point FIR interpolator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + * @return none. + */ + +void arm_fir_interpolate_f32( + const arm_fir_interpolate_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + float32_t *pState = S->pState; /* State pointer */ + float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + float32_t *pStateCurnt; /* Points to the current sample of the state */ + float32_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + float32_t sum0; /* Accumulators */ + float32_t x0, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t i, blkCnt, j; /* Loop counters */ + uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ + + + /* S->pState buffer contains previous frame (phaseLen - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (phaseLen - 1u); + + /* Total number of intput samples */ + blkCnt = blockSize; + + /* Loop over the blockSize. */ + while(blkCnt > 0u) + { + /* Copy new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Address modifier index of coefficient buffer */ + j = 1u; + + /* Loop over the Interpolation factor. */ + i = S->L; + while(i > 0u) + { + /* Set accumulator to zero */ + sum0 = 0.0f; + + /* Initialize state pointer */ + ptr1 = pState; + + /* Initialize coefficient pointer */ + ptr2 = pCoeffs + (S->L - j); + + /* Loop over the polyPhase length. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ + tapCnt = phaseLen >> 2u; + while(tapCnt > 0u) + { + + /* Read the coefficient */ + c0 = *(ptr2); + + /* Upsampling is done by stuffing L-1 zeros between each sample. + * So instead of multiplying zeros with coefficients, + * Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *(ptr1++); + + /* Perform the multiply-accumulate */ + sum0 += x0 * c0; + + /* Read the coefficient */ + c0 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *(ptr1++); + + /* Perform the multiply-accumulate */ + sum0 += x0 * c0; + + /* Read the coefficient */ + c0 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *(ptr1++); + + /* Perform the multiply-accumulate */ + sum0 += x0 * c0; + + /* Read the coefficient */ + c0 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *(ptr1++); + + /* Perform the multiply-accumulate */ + sum0 += x0 * c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = phaseLen % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + sum0 += *(ptr1++) * (*ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* The result is in the accumulator, store in the destination buffer. */ + *pDst++ = sum0; + + /* Increment the address modifier index of coefficient buffer */ + j++; + + /* Decrement the loop counter */ + i--; + } + + /* Advance the state pointer by 1 + * to process the next group of interpolation factor number samples */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + tapCnt = (phaseLen - 1u) >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + tapCnt = (phaseLen - 1u) % 0x04u; + + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + float32_t sum; /* Accumulator */ + uint32_t i, blkCnt; /* Loop counters */ + uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ + + + /* S->pState buffer contains previous frame (phaseLen - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (phaseLen - 1u); + + /* Total number of intput samples */ + blkCnt = blockSize; + + /* Loop over the blockSize. */ + while(blkCnt > 0u) + { + /* Copy new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Loop over the Interpolation factor. */ + i = S->L; + + while(i > 0u) + { + /* Set accumulator to zero */ + sum = 0.0f; + + /* Initialize state pointer */ + ptr1 = pState; + + /* Initialize coefficient pointer */ + ptr2 = pCoeffs + (i - 1u); + + /* Loop over the polyPhase length */ + tapCnt = phaseLen; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + sum += *ptr1++ * *ptr2; + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* The result is in the accumulator, store in the destination buffer. */ + *pDst++ = sum; + + /* Decrement the loop counter */ + i--; + } + + /* Advance the state pointer by 1 + * to process the next group of interpolation factor number samples */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last phaseLen - 1 samples to the start of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + tapCnt = phaseLen - 1u; + + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + /** + * @} end of FIR_Interpolate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_f32.c index bfdc734bd..59802b24d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_f32.c @@ -1,113 +1,113 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_init_f32.c -* -* Description: Floating-point FIR interpolator initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - -/** - * @brief Initialization function for the floating-point FIR interpolator. - * @param[in,out] *S points to an instance of the floating-point FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficient buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[numTaps-2], ..., b[1], b[0]}   
- * 
- * The length of the filter numTaps must be a multiple of the interpolation factor L. - * \par - * pState points to the array of state variables. - * pState is of length (numTaps/L)+blockSize-1 words - * where blockSize is the number of input samples processed by each call to arm_fir_interpolate_f32(). - */ - -arm_status arm_fir_interpolate_init_f32( - arm_fir_interpolate_instance_f32 * S, - uint8_t L, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize) -{ - arm_status status; - - /* The filter length must be a multiple of the interpolation factor */ - if((numTaps % L) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign Interpolation factor */ - S->L = L; - - /* Assign polyPhaseLength */ - S->phaseLength = numTaps / L; - - /* Clear state buffer and size of state array is always phaseLength + blockSize - 1 */ - memset(pState, 0, - (blockSize + - ((uint32_t) S->phaseLength - 1u)) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - - /** - * @} end of FIR_Interpolate group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_interpolate_init_f32.c +* +* Description: Floating-point FIR interpolator initialization function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Interpolate + * @{ + */ + +/** + * @brief Initialization function for the floating-point FIR interpolator. + * @param[in,out] *S points to an instance of the floating-point FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficient buffer. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[numTaps-2], ..., b[1], b[0]}   
+ * 
+ * The length of the filter numTaps must be a multiple of the interpolation factor L. + * \par + * pState points to the array of state variables. + * pState is of length (numTaps/L)+blockSize-1 words + * where blockSize is the number of input samples processed by each call to arm_fir_interpolate_f32(). + */ + +arm_status arm_fir_interpolate_init_f32( + arm_fir_interpolate_instance_f32 * S, + uint8_t L, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + uint32_t blockSize) +{ + arm_status status; + + /* The filter length must be a multiple of the interpolation factor */ + if((numTaps % L) != 0u) + { + /* Set status as ARM_MATH_LENGTH_ERROR */ + status = ARM_MATH_LENGTH_ERROR; + } + else + { + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Assign Interpolation factor */ + S->L = L; + + /* Assign polyPhaseLength */ + S->phaseLength = numTaps / L; + + /* Clear state buffer and size of state array is always phaseLength + blockSize - 1 */ + memset(pState, 0, + (blockSize + + ((uint32_t) S->phaseLength - 1u)) * sizeof(float32_t)); + + /* Assign state pointer */ + S->pState = pState; + + status = ARM_MATH_SUCCESS; + } + + return (status); + +} + + /** + * @} end of FIR_Interpolate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q15.c index 3995f73cd..0ab6e6bc5 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q15.c @@ -1,112 +1,112 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_init_q15.c -* -* Description: Q15 FIR interpolator initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - -/** - * @brief Initialization function for the Q15 FIR interpolator. - * @param[in,out] *S points to an instance of the Q15 FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficient buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[numTaps-2], ..., b[1], b[0]}   
- * 
- * The length of the filter numTaps must be a multiple of the interpolation factor L. - * \par - * pState points to the array of state variables. - * pState is of length (numTaps/L)+blockSize-1 words - * where blockSize is the number of input samples processed by each call to arm_fir_interpolate_q15(). - */ - -arm_status arm_fir_interpolate_init_q15( - arm_fir_interpolate_instance_q15 * S, - uint8_t L, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize) -{ - arm_status status; - - /* The filter length must be a multiple of the interpolation factor */ - if((numTaps % L) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign Interpolation factor */ - S->L = L; - - /* Assign polyPhaseLength */ - S->phaseLength = numTaps / L; - - /* Clear state buffer and size of buffer is always phaseLength + blockSize - 1 */ - memset(pState, 0, - (blockSize + ((uint32_t) S->phaseLength - 1u)) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - - /** - * @} end of FIR_Interpolate group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_interpolate_init_q15.c +* +* Description: Q15 FIR interpolator initialization function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Interpolate + * @{ + */ + +/** + * @brief Initialization function for the Q15 FIR interpolator. + * @param[in,out] *S points to an instance of the Q15 FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficient buffer. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[numTaps-2], ..., b[1], b[0]}   
+ * 
+ * The length of the filter numTaps must be a multiple of the interpolation factor L. + * \par + * pState points to the array of state variables. + * pState is of length (numTaps/L)+blockSize-1 words + * where blockSize is the number of input samples processed by each call to arm_fir_interpolate_q15(). + */ + +arm_status arm_fir_interpolate_init_q15( + arm_fir_interpolate_instance_q15 * S, + uint8_t L, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + uint32_t blockSize) +{ + arm_status status; + + /* The filter length must be a multiple of the interpolation factor */ + if((numTaps % L) != 0u) + { + /* Set status as ARM_MATH_LENGTH_ERROR */ + status = ARM_MATH_LENGTH_ERROR; + } + else + { + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Assign Interpolation factor */ + S->L = L; + + /* Assign polyPhaseLength */ + S->phaseLength = numTaps / L; + + /* Clear state buffer and size of buffer is always phaseLength + blockSize - 1 */ + memset(pState, 0, + (blockSize + ((uint32_t) S->phaseLength - 1u)) * sizeof(q15_t)); + + /* Assign state pointer */ + S->pState = pState; + + status = ARM_MATH_SUCCESS; + } + + return (status); + +} + + /** + * @} end of FIR_Interpolate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q31.c index ade6b071c..92906c11e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q31.c @@ -1,113 +1,113 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_init_q31.c -* -* Description: Q31 FIR interpolator initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - - -/** - * @brief Initialization function for the Q31 FIR interpolator. - * @param[in,out] *S points to an instance of the Q31 FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficient buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[numTaps-2], ..., b[1], b[0]}   
- * 
- * The length of the filter numTaps must be a multiple of the interpolation factor L. - * \par - * pState points to the array of state variables. - * pState is of length (numTaps/L)+blockSize-1 words - * where blockSize is the number of input samples processed by each call to arm_fir_interpolate_q31(). - */ - -arm_status arm_fir_interpolate_init_q31( - arm_fir_interpolate_instance_q31 * S, - uint8_t L, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize) -{ - arm_status status; - - /* The filter length must be a multiple of the interpolation factor */ - if((numTaps % L) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign Interpolation factor */ - S->L = L; - - /* Assign polyPhaseLength */ - S->phaseLength = numTaps / L; - - /* Clear state buffer and size of buffer is always phaseLength + blockSize - 1 */ - memset(pState, 0, - (blockSize + ((uint32_t) S->phaseLength - 1u)) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - - /** - * @} end of FIR_Interpolate group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_interpolate_init_q31.c +* +* Description: Q31 FIR interpolator initialization function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Interpolate + * @{ + */ + + +/** + * @brief Initialization function for the Q31 FIR interpolator. + * @param[in,out] *S points to an instance of the Q31 FIR interpolator structure. + * @param[in] L upsample factor. + * @param[in] numTaps number of filter coefficients in the filter. + * @param[in] *pCoeffs points to the filter coefficient buffer. + * @param[in] *pState points to the state buffer. + * @param[in] blockSize number of input samples to process per call. + * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if + * the filter length numTaps is not a multiple of the interpolation factor L. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[numTaps-2], ..., b[1], b[0]}   
+ * 
+ * The length of the filter numTaps must be a multiple of the interpolation factor L. + * \par + * pState points to the array of state variables. + * pState is of length (numTaps/L)+blockSize-1 words + * where blockSize is the number of input samples processed by each call to arm_fir_interpolate_q31(). + */ + +arm_status arm_fir_interpolate_init_q31( + arm_fir_interpolate_instance_q31 * S, + uint8_t L, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + uint32_t blockSize) +{ + arm_status status; + + /* The filter length must be a multiple of the interpolation factor */ + if((numTaps % L) != 0u) + { + /* Set status as ARM_MATH_LENGTH_ERROR */ + status = ARM_MATH_LENGTH_ERROR; + } + else + { + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Assign Interpolation factor */ + S->L = L; + + /* Assign polyPhaseLength */ + S->phaseLength = numTaps / L; + + /* Clear state buffer and size of buffer is always phaseLength + blockSize - 1 */ + memset(pState, 0, + (blockSize + ((uint32_t) S->phaseLength - 1u)) * sizeof(q31_t)); + + /* Assign state pointer */ + S->pState = pState; + + status = ARM_MATH_SUCCESS; + } + + return (status); + +} + + /** + * @} end of FIR_Interpolate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q15.c index 6403d7f39..56dddcc17 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q15.c @@ -1,349 +1,349 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_q15.c -* -* Description: Q15 FIR interpolation. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - -/** - * @brief Processing function for the Q15 FIR interpolator. - * @param[in] *S points to an instance of the Q15 FIR interpolator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - */ - -void arm_fir_interpolate_q15( - const arm_fir_interpolate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q63_t sum0; /* Accumulators */ - q15_t x0, c0, c1; /* Temporary variables to hold state and coefficient values */ - q31_t c, x; - uint32_t i, blkCnt, j, tapCnt; /* Loop counters */ - uint16_t phaseLen = S->phaseLength; /* Length of each polyphase filter component */ - - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (phaseLen - 1u); - - /* Total number of intput samples */ - blkCnt = blockSize; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Address modifier index of coefficient buffer */ - j = 1u; - - /* Loop over the Interpolation factor. */ - i = S->L; - while(i > 0u) - { - /* Set accumulator to zero */ - sum0 = 0; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (S->L - j); - - /* Loop over the polyPhase length. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ - tapCnt = (uint32_t) phaseLen >> 2u; - while(tapCnt > 0u) - { - /* Read the coefficient */ - c0 = *(ptr2); - - /* Upsampling is done by stuffing L-1 zeros between each sample. - * So instead of multiplying zeros with coefficients, - * Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the coefficient */ - c1 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Pack the coefficients */ -#ifndef ARM_MATH_BIG_ENDIAN - - c = __PKHBT(c0, c1, 16); - -#else - - c = __PKHBT(c1, c0, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Read twp consecutive input samples */ - x = *__SIMD32(ptr1)++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLALD(x, c, sum0); - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Upsampling is done by stuffing L-1 zeros between each sample. - * So insted of multiplying zeros with coefficients, - * Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the coefficient */ - c1 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Pack the coefficients */ -#ifndef ARM_MATH_BIG_ENDIAN - - c = __PKHBT(c0, c1, 16); - -#else - - c = __PKHBT(c1, c0, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Read twp consecutive input samples */ - x = *__SIMD32(ptr1)++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLALD(x, c, sum0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = (uint32_t) phaseLen & 0x3u; - - while(tapCnt > 0u) - { - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 = __SMLALD(x0, c0, sum0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); - - /* Increment the address modifier index of coefficient buffer */ - j++; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = ((uint32_t) phaseLen - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - /* Decrement the loop counter */ - i--; - } - - i = ((uint32_t) phaseLen - 1u) % 0x04u; - - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q63_t sum; /* Accumulator */ - q15_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t i, blkCnt, tapCnt; /* Loop counters */ - uint16_t phaseLen = S->phaseLength; /* Length of each polyphase filter component */ - - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (phaseLen - 1u); - - /* Total number of intput samples */ - blkCnt = blockSize; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Loop over the Interpolation factor. */ - i = S->L; - - while(i > 0u) - { - /* Set accumulator to zero */ - sum = 0; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (i - 1u); - - /* Loop over the polyPhase length */ - tapCnt = (uint32_t) phaseLen; - - while(tapCnt > 0u) - { - /* Read the coefficient */ - c0 = *ptr2; - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *ptr1++; - - /* Perform the multiply-accumulate */ - sum += ((q31_t) x0 * c0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Store the result after converting to 1.15 format in the destination buffer */ - *pDst++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the start of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (uint32_t) phaseLen - 1u; - - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - /** - * @} end of FIR_Interpolate group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_interpolate_q15.c +* +* Description: Q15 FIR interpolation. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Interpolate + * @{ + */ + +/** + * @brief Processing function for the Q15 FIR interpolator. + * @param[in] *S points to an instance of the Q15 FIR interpolator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 64-bit internal accumulator. + * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. + * Lastly, the accumulator is saturated to yield a result in 1.15 format. + */ + +void arm_fir_interpolate_q15( + const arm_fir_interpolate_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + q15_t *pState = S->pState; /* State pointer */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q15_t *pStateCurnt; /* Points to the current sample of the state */ + q15_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q63_t sum0; /* Accumulators */ + q15_t x0, c0, c1; /* Temporary variables to hold state and coefficient values */ + q31_t c, x; + uint32_t i, blkCnt, j, tapCnt; /* Loop counters */ + uint16_t phaseLen = S->phaseLength; /* Length of each polyphase filter component */ + + + /* S->pState buffer contains previous frame (phaseLen - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (phaseLen - 1u); + + /* Total number of intput samples */ + blkCnt = blockSize; + + /* Loop over the blockSize. */ + while(blkCnt > 0u) + { + /* Copy new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Address modifier index of coefficient buffer */ + j = 1u; + + /* Loop over the Interpolation factor. */ + i = S->L; + while(i > 0u) + { + /* Set accumulator to zero */ + sum0 = 0; + + /* Initialize state pointer */ + ptr1 = pState; + + /* Initialize coefficient pointer */ + ptr2 = pCoeffs + (S->L - j); + + /* Loop over the polyPhase length. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ + tapCnt = (uint32_t) phaseLen >> 2u; + while(tapCnt > 0u) + { + /* Read the coefficient */ + c0 = *(ptr2); + + /* Upsampling is done by stuffing L-1 zeros between each sample. + * So instead of multiplying zeros with coefficients, + * Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the coefficient */ + c1 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Pack the coefficients */ +#ifndef ARM_MATH_BIG_ENDIAN + + c = __PKHBT(c0, c1, 16); + +#else + + c = __PKHBT(c1, c0, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Read twp consecutive input samples */ + x = *__SIMD32(ptr1)++; + + /* Perform the multiply-accumulate */ + sum0 = __SMLALD(x, c, sum0); + + /* Read the coefficient */ + c0 = *(ptr2); + + /* Upsampling is done by stuffing L-1 zeros between each sample. + * So insted of multiplying zeros with coefficients, + * Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the coefficient */ + c1 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Pack the coefficients */ +#ifndef ARM_MATH_BIG_ENDIAN + + c = __PKHBT(c0, c1, 16); + +#else + + c = __PKHBT(c1, c0, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Read twp consecutive input samples */ + x = *__SIMD32(ptr1)++; + + /* Perform the multiply-accumulate */ + sum0 = __SMLALD(x, c, sum0); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = (uint32_t) phaseLen & 0x3u; + + while(tapCnt > 0u) + { + /* Read the coefficient */ + c0 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *(ptr1++); + + /* Perform the multiply-accumulate */ + sum0 = __SMLALD(x0, c0, sum0); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* The result is in the accumulator, store in the destination buffer. */ + *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); + + /* Increment the address modifier index of coefficient buffer */ + j++; + + /* Decrement the loop counter */ + i--; + } + + /* Advance the state pointer by 1 + * to process the next group of interpolation factor number samples */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + i = ((uint32_t) phaseLen - 1u) >> 2u; + + /* copy data */ + while(i > 0u) + { + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + + /* Decrement the loop counter */ + i--; + } + + i = ((uint32_t) phaseLen - 1u) % 0x04u; + + while(i > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q63_t sum; /* Accumulator */ + q15_t x0, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t i, blkCnt, tapCnt; /* Loop counters */ + uint16_t phaseLen = S->phaseLength; /* Length of each polyphase filter component */ + + + /* S->pState buffer contains previous frame (phaseLen - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (phaseLen - 1u); + + /* Total number of intput samples */ + blkCnt = blockSize; + + /* Loop over the blockSize. */ + while(blkCnt > 0u) + { + /* Copy new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Loop over the Interpolation factor. */ + i = S->L; + + while(i > 0u) + { + /* Set accumulator to zero */ + sum = 0; + + /* Initialize state pointer */ + ptr1 = pState; + + /* Initialize coefficient pointer */ + ptr2 = pCoeffs + (i - 1u); + + /* Loop over the polyPhase length */ + tapCnt = (uint32_t) phaseLen; + + while(tapCnt > 0u) + { + /* Read the coefficient */ + c0 = *ptr2; + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *ptr1++; + + /* Perform the multiply-accumulate */ + sum += ((q31_t) x0 * c0); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Store the result after converting to 1.15 format in the destination buffer */ + *pDst++ = (q15_t) (__SSAT((sum >> 15), 16)); + + /* Decrement the loop counter */ + i--; + } + + /* Advance the state pointer by 1 + * to process the next group of interpolation factor number samples */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last phaseLen - 1 samples to the start of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + i = (uint32_t) phaseLen - 1u; + + while(i > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + i--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + /** + * @} end of FIR_Interpolate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q31.c index 466dccf1d..660b7dd5b 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q31.c @@ -1,340 +1,340 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_q31.c -* -* Description: Q31 FIR interpolation. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - -/** - * @brief Processing function for the Q31 FIR interpolator. - * @param[in] *S points to an instance of the Q31 FIR interpolator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 1/(numTaps/L). - * since numTaps/L additions occur per output sample. - * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. - */ - - -void arm_fir_interpolate_q31( - const arm_fir_interpolate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q63_t sum0; /* Accumulators */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t i, blkCnt, j; /* Loop counters */ - uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ - - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + ((q31_t) phaseLen - 1); - - /* Total number of intput samples */ - blkCnt = blockSize; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Address modifier index of coefficient buffer */ - j = 1u; - - /* Loop over the Interpolation factor. */ - i = S->L; - while(i > 0u) - { - /* Set accumulator to zero */ - sum0 = 0; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (S->L - j); - - /* Loop over the polyPhase length. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ - tapCnt = phaseLen >> 2; - while(tapCnt > 0u) - { - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Upsampling is done by stuffing L-1 zeros between each sample. - * So instead of multiplying zeros with coefficients, - * Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = phaseLen & 0x3u; - - while(tapCnt > 0u) - { - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (sum0 >> 31); - - /* Increment the address modifier index of coefficient buffer */ - j++; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (phaseLen - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (phaseLen - 1u) % 0x04u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q63_t sum; /* Accumulator */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t i, blkCnt; /* Loop counters */ - uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ - - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + ((q31_t) phaseLen - 1); - - /* Total number of intput samples */ - blkCnt = blockSize; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Loop over the Interpolation factor. */ - i = S->L; - - while(i > 0u) - { - /* Set accumulator to zero */ - sum = 0; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (i - 1u); - - tapCnt = phaseLen; - - while(tapCnt > 0u) - { - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *ptr1++; - - /* Perform the multiply-accumulate */ - sum += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (sum >> 31); - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = phaseLen - 1u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - /** - * @} end of FIR_Interpolate group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_interpolate_q31.c +* +* Description: Q31 FIR interpolation. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Interpolate + * @{ + */ + +/** + * @brief Processing function for the Q31 FIR interpolator. + * @param[in] *S points to an instance of the Q31 FIR interpolator structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of input samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around rather than clip. + * In order to avoid overflows completely the input signal must be scaled down by 1/(numTaps/L). + * since numTaps/L additions occur per output sample. + * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. + */ + + +void arm_fir_interpolate_q31( + const arm_fir_interpolate_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t *pState = S->pState; /* State pointer */ + q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *pStateCurnt; /* Points to the current sample of the state */ + q31_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q63_t sum0; /* Accumulators */ + q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t i, blkCnt, j; /* Loop counters */ + uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ + + + /* S->pState buffer contains previous frame (phaseLen - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + ((q31_t) phaseLen - 1); + + /* Total number of intput samples */ + blkCnt = blockSize; + + /* Loop over the blockSize. */ + while(blkCnt > 0u) + { + /* Copy new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Address modifier index of coefficient buffer */ + j = 1u; + + /* Loop over the Interpolation factor. */ + i = S->L; + while(i > 0u) + { + /* Set accumulator to zero */ + sum0 = 0; + + /* Initialize state pointer */ + ptr1 = pState; + + /* Initialize coefficient pointer */ + ptr2 = pCoeffs + (S->L - j); + + /* Loop over the polyPhase length. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ + tapCnt = phaseLen >> 2; + while(tapCnt > 0u) + { + + /* Read the coefficient */ + c0 = *(ptr2); + + /* Upsampling is done by stuffing L-1 zeros between each sample. + * So instead of multiplying zeros with coefficients, + * Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *(ptr1++); + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Read the coefficient */ + c0 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *(ptr1++); + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Read the coefficient */ + c0 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *(ptr1++); + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Read the coefficient */ + c0 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *(ptr1++); + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = phaseLen & 0x3u; + + while(tapCnt > 0u) + { + /* Read the coefficient */ + c0 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *(ptr1++); + + /* Perform the multiply-accumulate */ + sum0 += (q63_t) x0 *c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* The result is in the accumulator, store in the destination buffer. */ + *pDst++ = (q31_t) (sum0 >> 31); + + /* Increment the address modifier index of coefficient buffer */ + j++; + + /* Decrement the loop counter */ + i--; + } + + /* Advance the state pointer by 1 + * to process the next group of interpolation factor number samples */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + tapCnt = (phaseLen - 1u) >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + tapCnt = (phaseLen - 1u) % 0x04u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q63_t sum; /* Accumulator */ + q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ + uint32_t i, blkCnt; /* Loop counters */ + uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ + + + /* S->pState buffer contains previous frame (phaseLen - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + ((q31_t) phaseLen - 1); + + /* Total number of intput samples */ + blkCnt = blockSize; + + /* Loop over the blockSize. */ + while(blkCnt > 0u) + { + /* Copy new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Loop over the Interpolation factor. */ + i = S->L; + + while(i > 0u) + { + /* Set accumulator to zero */ + sum = 0; + + /* Initialize state pointer */ + ptr1 = pState; + + /* Initialize coefficient pointer */ + ptr2 = pCoeffs + (i - 1u); + + tapCnt = phaseLen; + + while(tapCnt > 0u) + { + /* Read the coefficient */ + c0 = *(ptr2); + + /* Increment the coefficient pointer by interpolation factor times. */ + ptr2 += S->L; + + /* Read the input sample */ + x0 = *ptr1++; + + /* Perform the multiply-accumulate */ + sum += (q63_t) x0 *c0; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* The result is in the accumulator, store in the destination buffer. */ + *pDst++ = (q31_t) (sum >> 31); + + /* Decrement the loop counter */ + i--; + } + + /* Advance the state pointer by 1 + * to process the next group of interpolation factor number samples */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + tapCnt = phaseLen - 1u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + /** + * @} end of FIR_Interpolate group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_f32.c index 90486acb6..4192992f9 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_f32.c @@ -1,496 +1,496 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_f32.c -* -* Description: Processing function for the floating-point FIR Lattice filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup FIR_Lattice Finite Impulse Response (FIR) Lattice Filters - * - * This set of functions implements Finite Impulse Response (FIR) lattice filters - * for Q15, Q31 and floating-point data types. Lattice filters are used in a - * variety of adaptive filter applications. The filter structure is feedforward and - * the net impulse response is finite length. - * The functions operate on blocks - * of input and output data and each call to the function processes - * blockSize samples through the filter. pSrc and - * pDst point to input and output arrays containing blockSize values. - * - * \par Algorithm: - * \image html FIRLattice.gif "Finite Impulse Response Lattice filter" - * The following difference equation is implemented: - *
   
- *    f0[n] = g0[n] = x[n]   
- *    fm[n] = fm-1[n] + km * gm-1[n-1] for m = 1, 2, ...M   
- *    gm[n] = km * fm-1[n] + gm-1[n-1] for m = 1, 2, ...M   
- *    y[n] = fM[n]   
- * 
- * \par - * pCoeffs points to tha array of reflection coefficients of size numStages. - * Reflection Coefficients are stored in the following order. - * \par - *
   
- *    {k1, k2, ..., kM}   
- * 
- * where M is number of stages - * \par - * pState points to a state array of size numStages. - * The state variables (g values) hold previous inputs and are stored in the following order. - *
   
- *    {g0[n], g1[n], g2[n] ...gM-1[n]}   
- * 
- * The state variables are updated after each block of data is processed; the coefficients are untouched. - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros and then manually initialize the instance structure as follows: - *
   
- *arm_fir_lattice_instance_f32 S = {numStages, pState, pCoeffs};   
- *arm_fir_lattice_instance_q31 S = {numStages, pState, pCoeffs};   
- *arm_fir_lattice_instance_q15 S = {numStages, pState, pCoeffs};   
- * 
- * \par - * where numStages is the number of stages in the filter; pState is the address of the state buffer; - * pCoeffs is the address of the coefficient buffer. - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the FIR Lattice filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - - - /** - * @brief Processing function for the floating-point FIR lattice filter. - * @param[in] *S points to an instance of the floating-point FIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_fir_lattice_f32( - const arm_fir_lattice_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *px; /* temporary state pointer */ - float32_t *pk; /* temporary coefficient pointer */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t fcurr1, fnext1, gcurr1, gnext1; /* temporary variables for first sample in loop unrolling */ - float32_t fcurr2, fnext2, gnext2; /* temporary variables for second sample in loop unrolling */ - float32_t fcurr3, fnext3, gnext3; /* temporary variables for third sample in loop unrolling */ - float32_t fcurr4, fnext4, gnext4; /* temporary variables for fourth sample in loop unrolling */ - uint32_t numStages = S->numStages; /* Number of stages in the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - gcurr1 = 0.0f; - pState = &S->pState[0]; - - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - - /* Read two samples from input buffer */ - /* f0(n) = x(n) */ - fcurr1 = *pSrc++; - fcurr2 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* Read g0(n-1) from state */ - gcurr1 = *px; - - /* Process first sample for first tap */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (fcurr1 * (*pk)) + gcurr1; - - /* Process second sample for first tap */ - /* for sample 2 processing */ - fnext2 = fcurr2 + ((*pk) * fcurr1); - gnext2 = (fcurr2 * (*pk)) + fcurr1; - - /* Read next two samples from input buffer */ - /* f0(n+2) = x(n+2) */ - fcurr3 = *pSrc++; - fcurr4 = *pSrc++; - - /* Copy only last input samples into the state buffer - which will be used for next four samples processing */ - *px++ = fcurr4; - - /* Process third sample for first tap */ - fnext3 = fcurr3 + ((*pk) * fcurr2); - gnext3 = (fcurr3 * (*pk)) + fcurr2; - - /* Process fourth sample for first tap */ - fnext4 = fcurr4 + ((*pk) * fcurr3); - gnext4 = (fcurr4 * (*pk++)) + fcurr3; - - /* Update of f values for next coefficient set processing */ - fcurr1 = fnext1; - fcurr2 = fnext2; - fcurr3 = fnext3; - fcurr4 = fnext4; - - /* Loop unrolling. Process 4 taps at a time . */ - stageCnt = (numStages - 1u) >> 2u; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numStages-3 coefficients. */ - - /* Process 2nd, 3rd, 4th and 5th taps ... here */ - while(stageCnt > 0u) - { - /* Read g1(n-1), g3(n-1) .... from state */ - gcurr1 = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext4; - - /* Process first sample for 2nd, 6th .. tap */ - /* Sample processing for K2, K6.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - /* Process second sample for 2nd, 6th .. tap */ - /* for sample 2 processing */ - fnext2 = fcurr2 + ((*pk) * gnext1); - /* Process third sample for 2nd, 6th .. tap */ - fnext3 = fcurr3 + ((*pk) * gnext2); - /* Process fourth sample for 2nd, 6th .. tap */ - fnext4 = fcurr4 + ((*pk) * gnext3); - - /* g2(n) = f1(n) * K2 + g1(n-1) */ - /* Calculation of state values for next stage */ - gnext4 = (fcurr4 * (*pk)) + gnext3; - gnext3 = (fcurr3 * (*pk)) + gnext2; - gnext2 = (fcurr2 * (*pk)) + gnext1; - gnext1 = (fcurr1 * (*pk++)) + gcurr1; - - - /* Read g2(n-1), g4(n-1) .... from state */ - gcurr1 = *px; - - /* save g2(n) in state buffer */ - *px++ = gnext4; - - /* Sample processing for K3, K7.... */ - /* Process first sample for 3rd, 7th .. tap */ - /* f3(n) = f2(n) + K3 * g2(n-1) */ - fcurr1 = fnext1 + ((*pk) * gcurr1); - /* Process second sample for 3rd, 7th .. tap */ - fcurr2 = fnext2 + ((*pk) * gnext1); - /* Process third sample for 3rd, 7th .. tap */ - fcurr3 = fnext3 + ((*pk) * gnext2); - /* Process fourth sample for 3rd, 7th .. tap */ - fcurr4 = fnext4 + ((*pk) * gnext3); - - /* Calculation of state values for next stage */ - /* g3(n) = f2(n) * K3 + g2(n-1) */ - gnext4 = (fnext4 * (*pk)) + gnext3; - gnext3 = (fnext3 * (*pk)) + gnext2; - gnext2 = (fnext2 * (*pk)) + gnext1; - gnext1 = (fnext1 * (*pk++)) + gcurr1; - - - /* Read g1(n-1), g3(n-1) .... from state */ - gcurr1 = *px; - - /* save g3(n) in state buffer */ - *px++ = gnext4; - - /* Sample processing for K4, K8.... */ - /* Process first sample for 4th, 8th .. tap */ - /* f4(n) = f3(n) + K4 * g3(n-1) */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - /* Process second sample for 4th, 8th .. tap */ - /* for sample 2 processing */ - fnext2 = fcurr2 + ((*pk) * gnext1); - /* Process third sample for 4th, 8th .. tap */ - fnext3 = fcurr3 + ((*pk) * gnext2); - /* Process fourth sample for 4th, 8th .. tap */ - fnext4 = fcurr4 + ((*pk) * gnext3); - - /* g4(n) = f3(n) * K4 + g3(n-1) */ - /* Calculation of state values for next stage */ - gnext4 = (fcurr4 * (*pk)) + gnext3; - gnext3 = (fcurr3 * (*pk)) + gnext2; - gnext2 = (fcurr2 * (*pk)) + gnext1; - gnext1 = (fcurr1 * (*pk++)) + gcurr1; - - /* Read g2(n-1), g4(n-1) .... from state */ - gcurr1 = *px; - - /* save g4(n) in state buffer */ - *px++ = gnext4; - - /* Sample processing for K5, K9.... */ - /* Process first sample for 5th, 9th .. tap */ - /* f5(n) = f4(n) + K5 * g4(n-1) */ - fcurr1 = fnext1 + ((*pk) * gcurr1); - /* Process second sample for 5th, 9th .. tap */ - fcurr2 = fnext2 + ((*pk) * gnext1); - /* Process third sample for 5th, 9th .. tap */ - fcurr3 = fnext3 + ((*pk) * gnext2); - /* Process fourth sample for 5th, 9th .. tap */ - fcurr4 = fnext4 + ((*pk) * gnext3); - - /* Calculation of state values for next stage */ - /* g5(n) = f4(n) * K5 + g4(n-1) */ - gnext4 = (fnext4 * (*pk)) + gnext3; - gnext3 = (fnext3 * (*pk)) + gnext2; - gnext2 = (fnext2 * (*pk)) + gnext1; - gnext1 = (fnext1 * (*pk++)) + gcurr1; - - stageCnt--; - } - - /* If the (filter length -1) is not a multiple of 4, compute the remaining filter taps */ - stageCnt = (numStages - 1u) % 0x4u; - - while(stageCnt > 0u) - { - gcurr1 = *px; - - /* save g value in state buffer */ - *px++ = gnext4; - - /* Process four samples for last three taps here */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - fnext2 = fcurr2 + ((*pk) * gnext1); - fnext3 = fcurr3 + ((*pk) * gnext2); - fnext4 = fcurr4 + ((*pk) * gnext3); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext4 = (fcurr4 * (*pk)) + gnext3; - gnext3 = (fcurr3 * (*pk)) + gnext2; - gnext2 = (fcurr2 * (*pk)) + gnext1; - gnext1 = (fcurr1 * (*pk++)) + gcurr1; - - /* Update of f values for next coefficient set processing */ - fcurr1 = fnext1; - fcurr2 = fnext2; - fcurr3 = fnext3; - fcurr4 = fnext4; - - stageCnt--; - - } - - /* The results in the 4 accumulators, store in the destination buffer. */ - /* y(n) = fN(n) */ - *pDst++ = fcurr1; - *pDst++ = fcurr2; - *pDst++ = fcurr3; - *pDst++ = fcurr4; - - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurr1 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g2(n) from state buffer */ - gcurr1 = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (fcurr1 * (*pk++)) + gcurr1; - - /* save g1(n) in state buffer */ - *px++ = fcurr1; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr1 = fnext1; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g2(n) from state buffer */ - gcurr1 = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext1; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext1 = (fcurr1 * (*pk++)) + gcurr1; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr1 = fnext1; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = fcurr1; - - blkCnt--; - - } - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t fcurr, fnext, gcurr, gnext; /* temporary variables */ - uint32_t numStages = S->numStages; /* Length of the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - pState = &S->pState[0]; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize coeff pointer */ - pk = pCoeffs; - - /* Initialize state pointer */ - px = pState; - - /* read g0(n-1) from state buffer */ - gcurr = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext = fcurr + ((*pk) * gcurr); - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext = (fcurr * (*pk++)) + gcurr; - - /* save f0(n) in state buffer */ - *px++ = fcurr; - - /* f1(n) is saved in fcurr - for next stage processing */ - fcurr = fnext; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g2(n) from state buffer */ - gcurr = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext = fcurr + ((*pk) * gcurr); - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext = (fcurr * (*pk++)) + gcurr; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr = fnext; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = fcurr; - - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Lattice group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_lattice_f32.c +* +* Description: Processing function for the floating-point FIR Lattice filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup FIR_Lattice Finite Impulse Response (FIR) Lattice Filters + * + * This set of functions implements Finite Impulse Response (FIR) lattice filters + * for Q15, Q31 and floating-point data types. Lattice filters are used in a + * variety of adaptive filter applications. The filter structure is feedforward and + * the net impulse response is finite length. + * The functions operate on blocks + * of input and output data and each call to the function processes + * blockSize samples through the filter. pSrc and + * pDst point to input and output arrays containing blockSize values. + * + * \par Algorithm: + * \image html FIRLattice.gif "Finite Impulse Response Lattice filter" + * The following difference equation is implemented: + *
   
+ *    f0[n] = g0[n] = x[n]   
+ *    fm[n] = fm-1[n] + km * gm-1[n-1] for m = 1, 2, ...M   
+ *    gm[n] = km * fm-1[n] + gm-1[n-1] for m = 1, 2, ...M   
+ *    y[n] = fM[n]   
+ * 
+ * \par + * pCoeffs points to tha array of reflection coefficients of size numStages. + * Reflection Coefficients are stored in the following order. + * \par + *
   
+ *    {k1, k2, ..., kM}   
+ * 
+ * where M is number of stages + * \par + * pState points to a state array of size numStages. + * The state variables (g values) hold previous inputs and are stored in the following order. + *
   
+ *    {g0[n], g1[n], g2[n] ...gM-1[n]}   
+ * 
+ * The state variables are updated after each block of data is processed; the coefficients are untouched. + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter. + * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Set the values in the state buffer to zeros and then manually initialize the instance structure as follows: + *
   
+ *arm_fir_lattice_instance_f32 S = {numStages, pState, pCoeffs};   
+ *arm_fir_lattice_instance_q31 S = {numStages, pState, pCoeffs};   
+ *arm_fir_lattice_instance_q15 S = {numStages, pState, pCoeffs};   
+ * 
+ * \par + * where numStages is the number of stages in the filter; pState is the address of the state buffer; + * pCoeffs is the address of the coefficient buffer. + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the FIR Lattice filter functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + +/** + * @addtogroup FIR_Lattice + * @{ + */ + + + /** + * @brief Processing function for the floating-point FIR lattice filter. + * @param[in] *S points to an instance of the floating-point FIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of samples to process. + * @return none. + */ + +void arm_fir_lattice_f32( + const arm_fir_lattice_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + float32_t *pState; /* State pointer */ + float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + float32_t *px; /* temporary state pointer */ + float32_t *pk; /* temporary coefficient pointer */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + float32_t fcurr1, fnext1, gcurr1, gnext1; /* temporary variables for first sample in loop unrolling */ + float32_t fcurr2, fnext2, gnext2; /* temporary variables for second sample in loop unrolling */ + float32_t fcurr3, fnext3, gnext3; /* temporary variables for third sample in loop unrolling */ + float32_t fcurr4, fnext4, gnext4; /* temporary variables for fourth sample in loop unrolling */ + uint32_t numStages = S->numStages; /* Number of stages in the filter */ + uint32_t blkCnt, stageCnt; /* temporary variables for counts */ + + gcurr1 = 0.0f; + pState = &S->pState[0]; + + blkCnt = blockSize >> 2; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + + /* Read two samples from input buffer */ + /* f0(n) = x(n) */ + fcurr1 = *pSrc++; + fcurr2 = *pSrc++; + + /* Initialize coeff pointer */ + pk = (pCoeffs); + + /* Initialize state pointer */ + px = pState; + + /* Read g0(n-1) from state */ + gcurr1 = *px; + + /* Process first sample for first tap */ + /* f1(n) = f0(n) + K1 * g0(n-1) */ + fnext1 = fcurr1 + ((*pk) * gcurr1); + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext1 = (fcurr1 * (*pk)) + gcurr1; + + /* Process second sample for first tap */ + /* for sample 2 processing */ + fnext2 = fcurr2 + ((*pk) * fcurr1); + gnext2 = (fcurr2 * (*pk)) + fcurr1; + + /* Read next two samples from input buffer */ + /* f0(n+2) = x(n+2) */ + fcurr3 = *pSrc++; + fcurr4 = *pSrc++; + + /* Copy only last input samples into the state buffer + which will be used for next four samples processing */ + *px++ = fcurr4; + + /* Process third sample for first tap */ + fnext3 = fcurr3 + ((*pk) * fcurr2); + gnext3 = (fcurr3 * (*pk)) + fcurr2; + + /* Process fourth sample for first tap */ + fnext4 = fcurr4 + ((*pk) * fcurr3); + gnext4 = (fcurr4 * (*pk++)) + fcurr3; + + /* Update of f values for next coefficient set processing */ + fcurr1 = fnext1; + fcurr2 = fnext2; + fcurr3 = fnext3; + fcurr4 = fnext4; + + /* Loop unrolling. Process 4 taps at a time . */ + stageCnt = (numStages - 1u) >> 2u; + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numStages-3 coefficients. */ + + /* Process 2nd, 3rd, 4th and 5th taps ... here */ + while(stageCnt > 0u) + { + /* Read g1(n-1), g3(n-1) .... from state */ + gcurr1 = *px; + + /* save g1(n) in state buffer */ + *px++ = gnext4; + + /* Process first sample for 2nd, 6th .. tap */ + /* Sample processing for K2, K6.... */ + /* f2(n) = f1(n) + K2 * g1(n-1) */ + fnext1 = fcurr1 + ((*pk) * gcurr1); + /* Process second sample for 2nd, 6th .. tap */ + /* for sample 2 processing */ + fnext2 = fcurr2 + ((*pk) * gnext1); + /* Process third sample for 2nd, 6th .. tap */ + fnext3 = fcurr3 + ((*pk) * gnext2); + /* Process fourth sample for 2nd, 6th .. tap */ + fnext4 = fcurr4 + ((*pk) * gnext3); + + /* g2(n) = f1(n) * K2 + g1(n-1) */ + /* Calculation of state values for next stage */ + gnext4 = (fcurr4 * (*pk)) + gnext3; + gnext3 = (fcurr3 * (*pk)) + gnext2; + gnext2 = (fcurr2 * (*pk)) + gnext1; + gnext1 = (fcurr1 * (*pk++)) + gcurr1; + + + /* Read g2(n-1), g4(n-1) .... from state */ + gcurr1 = *px; + + /* save g2(n) in state buffer */ + *px++ = gnext4; + + /* Sample processing for K3, K7.... */ + /* Process first sample for 3rd, 7th .. tap */ + /* f3(n) = f2(n) + K3 * g2(n-1) */ + fcurr1 = fnext1 + ((*pk) * gcurr1); + /* Process second sample for 3rd, 7th .. tap */ + fcurr2 = fnext2 + ((*pk) * gnext1); + /* Process third sample for 3rd, 7th .. tap */ + fcurr3 = fnext3 + ((*pk) * gnext2); + /* Process fourth sample for 3rd, 7th .. tap */ + fcurr4 = fnext4 + ((*pk) * gnext3); + + /* Calculation of state values for next stage */ + /* g3(n) = f2(n) * K3 + g2(n-1) */ + gnext4 = (fnext4 * (*pk)) + gnext3; + gnext3 = (fnext3 * (*pk)) + gnext2; + gnext2 = (fnext2 * (*pk)) + gnext1; + gnext1 = (fnext1 * (*pk++)) + gcurr1; + + + /* Read g1(n-1), g3(n-1) .... from state */ + gcurr1 = *px; + + /* save g3(n) in state buffer */ + *px++ = gnext4; + + /* Sample processing for K4, K8.... */ + /* Process first sample for 4th, 8th .. tap */ + /* f4(n) = f3(n) + K4 * g3(n-1) */ + fnext1 = fcurr1 + ((*pk) * gcurr1); + /* Process second sample for 4th, 8th .. tap */ + /* for sample 2 processing */ + fnext2 = fcurr2 + ((*pk) * gnext1); + /* Process third sample for 4th, 8th .. tap */ + fnext3 = fcurr3 + ((*pk) * gnext2); + /* Process fourth sample for 4th, 8th .. tap */ + fnext4 = fcurr4 + ((*pk) * gnext3); + + /* g4(n) = f3(n) * K4 + g3(n-1) */ + /* Calculation of state values for next stage */ + gnext4 = (fcurr4 * (*pk)) + gnext3; + gnext3 = (fcurr3 * (*pk)) + gnext2; + gnext2 = (fcurr2 * (*pk)) + gnext1; + gnext1 = (fcurr1 * (*pk++)) + gcurr1; + + /* Read g2(n-1), g4(n-1) .... from state */ + gcurr1 = *px; + + /* save g4(n) in state buffer */ + *px++ = gnext4; + + /* Sample processing for K5, K9.... */ + /* Process first sample for 5th, 9th .. tap */ + /* f5(n) = f4(n) + K5 * g4(n-1) */ + fcurr1 = fnext1 + ((*pk) * gcurr1); + /* Process second sample for 5th, 9th .. tap */ + fcurr2 = fnext2 + ((*pk) * gnext1); + /* Process third sample for 5th, 9th .. tap */ + fcurr3 = fnext3 + ((*pk) * gnext2); + /* Process fourth sample for 5th, 9th .. tap */ + fcurr4 = fnext4 + ((*pk) * gnext3); + + /* Calculation of state values for next stage */ + /* g5(n) = f4(n) * K5 + g4(n-1) */ + gnext4 = (fnext4 * (*pk)) + gnext3; + gnext3 = (fnext3 * (*pk)) + gnext2; + gnext2 = (fnext2 * (*pk)) + gnext1; + gnext1 = (fnext1 * (*pk++)) + gcurr1; + + stageCnt--; + } + + /* If the (filter length -1) is not a multiple of 4, compute the remaining filter taps */ + stageCnt = (numStages - 1u) % 0x4u; + + while(stageCnt > 0u) + { + gcurr1 = *px; + + /* save g value in state buffer */ + *px++ = gnext4; + + /* Process four samples for last three taps here */ + fnext1 = fcurr1 + ((*pk) * gcurr1); + fnext2 = fcurr2 + ((*pk) * gnext1); + fnext3 = fcurr3 + ((*pk) * gnext2); + fnext4 = fcurr4 + ((*pk) * gnext3); + + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext4 = (fcurr4 * (*pk)) + gnext3; + gnext3 = (fcurr3 * (*pk)) + gnext2; + gnext2 = (fcurr2 * (*pk)) + gnext1; + gnext1 = (fcurr1 * (*pk++)) + gcurr1; + + /* Update of f values for next coefficient set processing */ + fcurr1 = fnext1; + fcurr2 = fnext2; + fcurr3 = fnext3; + fcurr4 = fnext4; + + stageCnt--; + + } + + /* The results in the 4 accumulators, store in the destination buffer. */ + /* y(n) = fN(n) */ + *pDst++ = fcurr1; + *pDst++ = fcurr2; + *pDst++ = fcurr3; + *pDst++ = fcurr4; + + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* f0(n) = x(n) */ + fcurr1 = *pSrc++; + + /* Initialize coeff pointer */ + pk = (pCoeffs); + + /* Initialize state pointer */ + px = pState; + + /* read g2(n) from state buffer */ + gcurr1 = *px; + + /* for sample 1 processing */ + /* f1(n) = f0(n) + K1 * g0(n-1) */ + fnext1 = fcurr1 + ((*pk) * gcurr1); + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext1 = (fcurr1 * (*pk++)) + gcurr1; + + /* save g1(n) in state buffer */ + *px++ = fcurr1; + + /* f1(n) is saved in fcurr1 + for next stage processing */ + fcurr1 = fnext1; + + stageCnt = (numStages - 1u); + + /* stage loop */ + while(stageCnt > 0u) + { + /* read g2(n) from state buffer */ + gcurr1 = *px; + + /* save g1(n) in state buffer */ + *px++ = gnext1; + + /* Sample processing for K2, K3.... */ + /* f2(n) = f1(n) + K2 * g1(n-1) */ + fnext1 = fcurr1 + ((*pk) * gcurr1); + /* g2(n) = f1(n) * K2 + g1(n-1) */ + gnext1 = (fcurr1 * (*pk++)) + gcurr1; + + /* f1(n) is saved in fcurr1 + for next stage processing */ + fcurr1 = fnext1; + + stageCnt--; + + } + + /* y(n) = fN(n) */ + *pDst++ = fcurr1; + + blkCnt--; + + } + +#else + + /* Run the below code for Cortex-M0 */ + + float32_t fcurr, fnext, gcurr, gnext; /* temporary variables */ + uint32_t numStages = S->numStages; /* Length of the filter */ + uint32_t blkCnt, stageCnt; /* temporary variables for counts */ + + pState = &S->pState[0]; + + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* f0(n) = x(n) */ + fcurr = *pSrc++; + + /* Initialize coeff pointer */ + pk = pCoeffs; + + /* Initialize state pointer */ + px = pState; + + /* read g0(n-1) from state buffer */ + gcurr = *px; + + /* for sample 1 processing */ + /* f1(n) = f0(n) + K1 * g0(n-1) */ + fnext = fcurr + ((*pk) * gcurr); + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext = (fcurr * (*pk++)) + gcurr; + + /* save f0(n) in state buffer */ + *px++ = fcurr; + + /* f1(n) is saved in fcurr + for next stage processing */ + fcurr = fnext; + + stageCnt = (numStages - 1u); + + /* stage loop */ + while(stageCnt > 0u) + { + /* read g2(n) from state buffer */ + gcurr = *px; + + /* save g1(n) in state buffer */ + *px++ = gnext; + + /* Sample processing for K2, K3.... */ + /* f2(n) = f1(n) + K2 * g1(n-1) */ + fnext = fcurr + ((*pk) * gcurr); + /* g2(n) = f1(n) * K2 + g1(n-1) */ + gnext = (fcurr * (*pk++)) + gcurr; + + /* f1(n) is saved in fcurr1 + for next stage processing */ + fcurr = fnext; + + stageCnt--; + + } + + /* y(n) = fN(n) */ + *pDst++ = fcurr; + + blkCnt--; + + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_f32.c index ab8da7fab..36e19c2bd 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_f32.c @@ -1,75 +1,75 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_init_f32.c -* -* Description: Floating-point FIR Lattice filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - -/** - * @brief Initialization function for the floating-point FIR lattice filter. - * @param[in] *S points to an instance of the floating-point FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] *pState points to the state buffer. The array is of length numStages. - * @return none. - */ - -void arm_fir_lattice_init_f32( - arm_fir_lattice_instance_f32 * S, - uint16_t numStages, - float32_t * pCoeffs, - float32_t * pState) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always numStages */ - memset(pState, 0, (numStages) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Lattice group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_lattice_init_f32.c +* +* Description: Floating-point FIR Lattice filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Lattice + * @{ + */ + +/** + * @brief Initialization function for the floating-point FIR lattice filter. + * @param[in] *S points to an instance of the floating-point FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] *pState points to the state buffer. The array is of length numStages. + * @return none. + */ + +void arm_fir_lattice_init_f32( + arm_fir_lattice_instance_f32 * S, + uint16_t numStages, + float32_t * pCoeffs, + float32_t * pState) +{ + /* Assign filter taps */ + S->numStages = numStages; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always numStages */ + memset(pState, 0, (numStages) * sizeof(float32_t)); + + /* Assign state pointer */ + S->pState = pState; + +} + +/** + * @} end of FIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q15.c index 7e34c93ee..905e7183e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q15.c @@ -1,75 +1,75 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_init_q15.c -* -* Description: Q15 FIR Lattice filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - - /** - * @brief Initialization function for the Q15 FIR lattice filter. - * @param[in] *S points to an instance of the Q15 FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] *pState points to the state buffer. The array is of length numStages. - * @return none. - */ - -void arm_fir_lattice_init_q15( - arm_fir_lattice_instance_q15 * S, - uint16_t numStages, - q15_t * pCoeffs, - q15_t * pState) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always numStages */ - memset(pState, 0, (numStages) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Lattice group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_lattice_init_q15.c +* +* Description: Q15 FIR Lattice filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Lattice + * @{ + */ + + /** + * @brief Initialization function for the Q15 FIR lattice filter. + * @param[in] *S points to an instance of the Q15 FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] *pState points to the state buffer. The array is of length numStages. + * @return none. + */ + +void arm_fir_lattice_init_q15( + arm_fir_lattice_instance_q15 * S, + uint16_t numStages, + q15_t * pCoeffs, + q15_t * pState) +{ + /* Assign filter taps */ + S->numStages = numStages; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always numStages */ + memset(pState, 0, (numStages) * sizeof(q15_t)); + + /* Assign state pointer */ + S->pState = pState; + +} + +/** + * @} end of FIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q31.c index 31e32cf18..43ba1af5f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q31.c @@ -1,75 +1,75 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_init_q31.c -* -* Description: Q31 FIR lattice filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - - /** - * @brief Initialization function for the Q31 FIR lattice filter. - * @param[in] *S points to an instance of the Q31 FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] *pState points to the state buffer. The array is of length numStages. - * @return none. - */ - -void arm_fir_lattice_init_q31( - arm_fir_lattice_instance_q31 * S, - uint16_t numStages, - q31_t * pCoeffs, - q31_t * pState) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always numStages */ - memset(pState, 0, (numStages) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Lattice group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_lattice_init_q31.c +* +* Description: Q31 FIR lattice filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Lattice + * @{ + */ + + /** + * @brief Initialization function for the Q31 FIR lattice filter. + * @param[in] *S points to an instance of the Q31 FIR lattice structure. + * @param[in] numStages number of filter stages. + * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] *pState points to the state buffer. The array is of length numStages. + * @return none. + */ + +void arm_fir_lattice_init_q31( + arm_fir_lattice_instance_q31 * S, + uint16_t numStages, + q31_t * pCoeffs, + q31_t * pState) +{ + /* Assign filter taps */ + S->numStages = numStages; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always numStages */ + memset(pState, 0, (numStages) * sizeof(q31_t)); + + /* Assign state pointer */ + S->pState = pState; + +} + +/** + * @} end of FIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q15.c index 350f29d15..3aff889f6 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q15.c @@ -1,528 +1,528 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_q15.c -* -* Description: Q15 FIR lattice filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - - -/** - * @brief Processing function for the Q15 FIR lattice filter. - * @param[in] *S points to an instance of the Q15 FIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_fir_lattice_q15( - const arm_fir_lattice_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *px; /* temporary state pointer */ - q15_t *pk; /* temporary coefficient pointer */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t fcurnt1, fnext1, gcurnt1 = 0, gnext1; /* temporary variables for first sample in loop unrolling */ - q31_t fcurnt2, fnext2, gnext2; /* temporary variables for second sample in loop unrolling */ - q31_t fcurnt3, fnext3, gnext3; /* temporary variables for third sample in loop unrolling */ - q31_t fcurnt4, fnext4, gnext4; /* temporary variables for fourth sample in loop unrolling */ - uint32_t numStages = S->numStages; /* Number of stages in the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - pState = &S->pState[0]; - - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - - /* Read two samples from input buffer */ - /* f0(n) = x(n) */ - fcurnt1 = *pSrc++; - fcurnt2 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* Read g0(n-1) from state */ - gcurnt1 = *px; - - /* Process first sample for first tap */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (q31_t) ((fcurnt1 * (*pk)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - /* Process second sample for first tap */ - /* for sample 2 processing */ - fnext2 = (q31_t) ((fcurnt1 * (*pk)) >> 15u) + fcurnt2; - fnext2 = __SSAT(fnext2, 16); - - gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + fcurnt1; - gnext2 = __SSAT(gnext2, 16); - - - /* Read next two samples from input buffer */ - /* f0(n+2) = x(n+2) */ - fcurnt3 = *pSrc++; - fcurnt4 = *pSrc++; - - /* Copy only last input samples into the state buffer - which is used for next four samples processing */ - *px++ = (q15_t) fcurnt4; - - /* Process third sample for first tap */ - fnext3 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + fcurnt3; - fnext3 = __SSAT(fnext3, 16); - gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + fcurnt2; - gnext3 = __SSAT(gnext3, 16); - - /* Process fourth sample for first tap */ - fnext4 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + fcurnt4; - fnext4 = __SSAT(fnext4, 16); - gnext4 = (q31_t) ((fcurnt4 * (*pk++)) >> 15u) + fcurnt3; - gnext4 = __SSAT(gnext4, 16); - - /* Update of f values for next coefficient set processing */ - fcurnt1 = fnext1; - fcurnt2 = fnext2; - fcurnt3 = fnext3; - fcurnt4 = fnext4; - - - /* Loop unrolling. Process 4 taps at a time . */ - stageCnt = (numStages - 1u) >> 2; - - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numStages-3 coefficients. */ - - /* Process 2nd, 3rd, 4th and 5th taps ... here */ - while(stageCnt > 0u) - { - /* Read g1(n-1), g3(n-1) .... from state */ - gcurnt1 = *px; - - /* save g1(n) in state buffer */ - *px++ = (q15_t) gnext4; - - /* Process first sample for 2nd, 6th .. tap */ - /* Sample processing for K2, K6.... */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - - - /* Process second sample for 2nd, 6th .. tap */ - /* for sample 2 processing */ - fnext2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fcurnt2; - fnext2 = __SSAT(fnext2, 16); - /* Process third sample for 2nd, 6th .. tap */ - fnext3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fcurnt3; - fnext3 = __SSAT(fnext3, 16); - /* Process fourth sample for 2nd, 6th .. tap */ - /* fnext4 = fcurnt4 + (*pk) * gnext3; */ - fnext4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fcurnt4; - fnext4 = __SSAT(fnext4, 16); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - /* Calculation of state values for next stage */ - gnext4 = (q31_t) ((fcurnt4 * (*pk)) >> 15u) + gnext3; - gnext4 = __SSAT(gnext4, 16); - gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + gnext2; - gnext3 = __SSAT(gnext3, 16); - - gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + gnext1; - gnext2 = __SSAT(gnext2, 16); - - gnext1 = (q31_t) ((fcurnt1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - - /* Read g2(n-1), g4(n-1) .... from state */ - gcurnt1 = *px; - - /* save g1(n) in state buffer */ - *px++ = (q15_t) gnext4; - - /* Sample processing for K3, K7.... */ - /* Process first sample for 3rd, 7th .. tap */ - /* f3(n) = f2(n) + K3 * g2(n-1) */ - fcurnt1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fnext1; - fcurnt1 = __SSAT(fcurnt1, 16); - - /* Process second sample for 3rd, 7th .. tap */ - fcurnt2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fnext2; - fcurnt2 = __SSAT(fcurnt2, 16); - - /* Process third sample for 3rd, 7th .. tap */ - fcurnt3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fnext3; - fcurnt3 = __SSAT(fcurnt3, 16); - - /* Process fourth sample for 3rd, 7th .. tap */ - fcurnt4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fnext4; - fcurnt4 = __SSAT(fcurnt4, 16); - - /* Calculation of state values for next stage */ - /* g3(n) = f2(n) * K3 + g2(n-1) */ - gnext4 = (q31_t) ((fnext4 * (*pk)) >> 15u) + gnext3; - gnext4 = __SSAT(gnext4, 16); - - gnext3 = (q31_t) ((fnext3 * (*pk)) >> 15u) + gnext2; - gnext3 = __SSAT(gnext3, 16); - - gnext2 = (q31_t) ((fnext2 * (*pk)) >> 15u) + gnext1; - gnext2 = __SSAT(gnext2, 16); - - gnext1 = (q31_t) ((fnext1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - /* Read g1(n-1), g3(n-1) .... from state */ - gcurnt1 = *px; - - /* save g1(n) in state buffer */ - *px++ = (q15_t) gnext4; - - /* Sample processing for K4, K8.... */ - /* Process first sample for 4th, 8th .. tap */ - /* f4(n) = f3(n) + K4 * g3(n-1) */ - fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - - /* Process second sample for 4th, 8th .. tap */ - /* for sample 2 processing */ - fnext2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fcurnt2; - fnext2 = __SSAT(fnext2, 16); - - /* Process third sample for 4th, 8th .. tap */ - fnext3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fcurnt3; - fnext3 = __SSAT(fnext3, 16); - - /* Process fourth sample for 4th, 8th .. tap */ - fnext4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fcurnt4; - fnext4 = __SSAT(fnext4, 16); - - /* g4(n) = f3(n) * K4 + g3(n-1) */ - /* Calculation of state values for next stage */ - gnext4 = (q31_t) ((fcurnt4 * (*pk)) >> 15u) + gnext3; - gnext4 = __SSAT(gnext4, 16); - - gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + gnext2; - gnext3 = __SSAT(gnext3, 16); - - gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + gnext1; - gnext2 = __SSAT(gnext2, 16); - gnext1 = (q31_t) ((fcurnt1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - - /* Read g2(n-1), g4(n-1) .... from state */ - gcurnt1 = *px; - - /* save g4(n) in state buffer */ - *px++ = (q15_t) gnext4; - - /* Sample processing for K5, K9.... */ - /* Process first sample for 5th, 9th .. tap */ - /* f5(n) = f4(n) + K5 * g4(n-1) */ - fcurnt1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fnext1; - fcurnt1 = __SSAT(fcurnt1, 16); - - /* Process second sample for 5th, 9th .. tap */ - fcurnt2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fnext2; - fcurnt2 = __SSAT(fcurnt2, 16); - - /* Process third sample for 5th, 9th .. tap */ - fcurnt3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fnext3; - fcurnt3 = __SSAT(fcurnt3, 16); - - /* Process fourth sample for 5th, 9th .. tap */ - fcurnt4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fnext4; - fcurnt4 = __SSAT(fcurnt4, 16); - - /* Calculation of state values for next stage */ - /* g5(n) = f4(n) * K5 + g4(n-1) */ - gnext4 = (q31_t) ((fnext4 * (*pk)) >> 15u) + gnext3; - gnext4 = __SSAT(gnext4, 16); - gnext3 = (q31_t) ((fnext3 * (*pk)) >> 15u) + gnext2; - gnext3 = __SSAT(gnext3, 16); - gnext2 = (q31_t) ((fnext2 * (*pk)) >> 15u) + gnext1; - gnext2 = __SSAT(gnext2, 16); - gnext1 = (q31_t) ((fnext1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - stageCnt--; - } - - /* If the (filter length -1) is not a multiple of 4, compute the remaining filter taps */ - stageCnt = (numStages - 1u) % 0x4u; - - while(stageCnt > 0u) - { - gcurnt1 = *px; - - /* save g value in state buffer */ - *px++ = (q15_t) gnext4; - - /* Process four samples for last three taps here */ - fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - fnext2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fcurnt2; - fnext2 = __SSAT(fnext2, 16); - - fnext3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fcurnt3; - fnext3 = __SSAT(fnext3, 16); - - fnext4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fcurnt4; - fnext4 = __SSAT(fnext4, 16); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext4 = (q31_t) ((fcurnt4 * (*pk)) >> 15u) + gnext3; - gnext4 = __SSAT(gnext4, 16); - gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + gnext2; - gnext3 = __SSAT(gnext3, 16); - gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + gnext1; - gnext2 = __SSAT(gnext2, 16); - gnext1 = (q31_t) ((fcurnt1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - /* Update of f values for next coefficient set processing */ - fcurnt1 = fnext1; - fcurnt2 = fnext2; - fcurnt3 = fnext3; - fcurnt4 = fnext4; - - stageCnt--; - - } - - /* The results in the 4 accumulators, store in the destination buffer. */ - /* y(n) = fN(n) */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT(fcurnt1, fcurnt2, 16); - *__SIMD32(pDst)++ = __PKHBT(fcurnt3, fcurnt4, 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT(fcurnt2, fcurnt1, 16); - *__SIMD32(pDst)++ = __PKHBT(fcurnt4, fcurnt3, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurnt1 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g2(n) from state buffer */ - gcurnt1 = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = (((q31_t) gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (((q31_t) fcurnt1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - /* save g1(n) in state buffer */ - *px++ = (q15_t) fcurnt1; - - /* f1(n) is saved in fcurnt1 - for next stage processing */ - fcurnt1 = fnext1; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g2(n) from state buffer */ - gcurnt1 = *px; - - /* save g1(n) in state buffer */ - *px++ = (q15_t) gnext1; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext1 = (((q31_t) gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext1 = (((q31_t) fcurnt1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - - /* f1(n) is saved in fcurnt1 - for next stage processing */ - fcurnt1 = fnext1; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = __SSAT(fcurnt1, 16); - - - blkCnt--; - - } - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t fcurnt, fnext, gcurnt, gnext; /* temporary variables */ - uint32_t numStages = S->numStages; /* Length of the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - pState = &S->pState[0]; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurnt = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g0(n-1) from state buffer */ - gcurnt = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext = ((gcurnt * (*pk)) >> 15u) + fcurnt; - fnext = __SSAT(fnext, 16); - - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext = ((fcurnt * (*pk++)) >> 15u) + gcurnt; - gnext = __SSAT(gnext, 16); - - /* save f0(n) in state buffer */ - *px++ = (q15_t) fcurnt; - - /* f1(n) is saved in fcurnt - for next stage processing */ - fcurnt = fnext; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g1(n-1) from state buffer */ - gcurnt = *px; - - /* save g0(n-1) in state buffer */ - *px++ = (q15_t) gnext; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext = ((gcurnt * (*pk)) >> 15u) + fcurnt; - fnext = __SSAT(fnext, 16); - - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext = ((fcurnt * (*pk++)) >> 15u) + gcurnt; - gnext = __SSAT(gnext, 16); - - - /* f1(n) is saved in fcurnt - for next stage processing */ - fcurnt = fnext; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = __SSAT(fcurnt, 16); - - - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Lattice group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_lattice_q15.c +* +* Description: Q15 FIR lattice filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Lattice + * @{ + */ + + +/** + * @brief Processing function for the Q15 FIR lattice filter. + * @param[in] *S points to an instance of the Q15 FIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of samples to process. + * @return none. + */ + +void arm_fir_lattice_q15( + const arm_fir_lattice_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + q15_t *pState; /* State pointer */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q15_t *px; /* temporary state pointer */ + q15_t *pk; /* temporary coefficient pointer */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t fcurnt1, fnext1, gcurnt1 = 0, gnext1; /* temporary variables for first sample in loop unrolling */ + q31_t fcurnt2, fnext2, gnext2; /* temporary variables for second sample in loop unrolling */ + q31_t fcurnt3, fnext3, gnext3; /* temporary variables for third sample in loop unrolling */ + q31_t fcurnt4, fnext4, gnext4; /* temporary variables for fourth sample in loop unrolling */ + uint32_t numStages = S->numStages; /* Number of stages in the filter */ + uint32_t blkCnt, stageCnt; /* temporary variables for counts */ + + pState = &S->pState[0]; + + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + + /* Read two samples from input buffer */ + /* f0(n) = x(n) */ + fcurnt1 = *pSrc++; + fcurnt2 = *pSrc++; + + /* Initialize coeff pointer */ + pk = (pCoeffs); + + /* Initialize state pointer */ + px = pState; + + /* Read g0(n-1) from state */ + gcurnt1 = *px; + + /* Process first sample for first tap */ + /* f1(n) = f0(n) + K1 * g0(n-1) */ + fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; + fnext1 = __SSAT(fnext1, 16); + + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext1 = (q31_t) ((fcurnt1 * (*pk)) >> 15u) + gcurnt1; + gnext1 = __SSAT(gnext1, 16); + + /* Process second sample for first tap */ + /* for sample 2 processing */ + fnext2 = (q31_t) ((fcurnt1 * (*pk)) >> 15u) + fcurnt2; + fnext2 = __SSAT(fnext2, 16); + + gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + fcurnt1; + gnext2 = __SSAT(gnext2, 16); + + + /* Read next two samples from input buffer */ + /* f0(n+2) = x(n+2) */ + fcurnt3 = *pSrc++; + fcurnt4 = *pSrc++; + + /* Copy only last input samples into the state buffer + which is used for next four samples processing */ + *px++ = (q15_t) fcurnt4; + + /* Process third sample for first tap */ + fnext3 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + fcurnt3; + fnext3 = __SSAT(fnext3, 16); + gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + fcurnt2; + gnext3 = __SSAT(gnext3, 16); + + /* Process fourth sample for first tap */ + fnext4 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + fcurnt4; + fnext4 = __SSAT(fnext4, 16); + gnext4 = (q31_t) ((fcurnt4 * (*pk++)) >> 15u) + fcurnt3; + gnext4 = __SSAT(gnext4, 16); + + /* Update of f values for next coefficient set processing */ + fcurnt1 = fnext1; + fcurnt2 = fnext2; + fcurnt3 = fnext3; + fcurnt4 = fnext4; + + + /* Loop unrolling. Process 4 taps at a time . */ + stageCnt = (numStages - 1u) >> 2; + + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numStages-3 coefficients. */ + + /* Process 2nd, 3rd, 4th and 5th taps ... here */ + while(stageCnt > 0u) + { + /* Read g1(n-1), g3(n-1) .... from state */ + gcurnt1 = *px; + + /* save g1(n) in state buffer */ + *px++ = (q15_t) gnext4; + + /* Process first sample for 2nd, 6th .. tap */ + /* Sample processing for K2, K6.... */ + /* f1(n) = f0(n) + K1 * g0(n-1) */ + fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; + fnext1 = __SSAT(fnext1, 16); + + + /* Process second sample for 2nd, 6th .. tap */ + /* for sample 2 processing */ + fnext2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fcurnt2; + fnext2 = __SSAT(fnext2, 16); + /* Process third sample for 2nd, 6th .. tap */ + fnext3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fcurnt3; + fnext3 = __SSAT(fnext3, 16); + /* Process fourth sample for 2nd, 6th .. tap */ + /* fnext4 = fcurnt4 + (*pk) * gnext3; */ + fnext4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fcurnt4; + fnext4 = __SSAT(fnext4, 16); + + /* g1(n) = f0(n) * K1 + g0(n-1) */ + /* Calculation of state values for next stage */ + gnext4 = (q31_t) ((fcurnt4 * (*pk)) >> 15u) + gnext3; + gnext4 = __SSAT(gnext4, 16); + gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + gnext2; + gnext3 = __SSAT(gnext3, 16); + + gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + gnext1; + gnext2 = __SSAT(gnext2, 16); + + gnext1 = (q31_t) ((fcurnt1 * (*pk++)) >> 15u) + gcurnt1; + gnext1 = __SSAT(gnext1, 16); + + + /* Read g2(n-1), g4(n-1) .... from state */ + gcurnt1 = *px; + + /* save g1(n) in state buffer */ + *px++ = (q15_t) gnext4; + + /* Sample processing for K3, K7.... */ + /* Process first sample for 3rd, 7th .. tap */ + /* f3(n) = f2(n) + K3 * g2(n-1) */ + fcurnt1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fnext1; + fcurnt1 = __SSAT(fcurnt1, 16); + + /* Process second sample for 3rd, 7th .. tap */ + fcurnt2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fnext2; + fcurnt2 = __SSAT(fcurnt2, 16); + + /* Process third sample for 3rd, 7th .. tap */ + fcurnt3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fnext3; + fcurnt3 = __SSAT(fcurnt3, 16); + + /* Process fourth sample for 3rd, 7th .. tap */ + fcurnt4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fnext4; + fcurnt4 = __SSAT(fcurnt4, 16); + + /* Calculation of state values for next stage */ + /* g3(n) = f2(n) * K3 + g2(n-1) */ + gnext4 = (q31_t) ((fnext4 * (*pk)) >> 15u) + gnext3; + gnext4 = __SSAT(gnext4, 16); + + gnext3 = (q31_t) ((fnext3 * (*pk)) >> 15u) + gnext2; + gnext3 = __SSAT(gnext3, 16); + + gnext2 = (q31_t) ((fnext2 * (*pk)) >> 15u) + gnext1; + gnext2 = __SSAT(gnext2, 16); + + gnext1 = (q31_t) ((fnext1 * (*pk++)) >> 15u) + gcurnt1; + gnext1 = __SSAT(gnext1, 16); + + /* Read g1(n-1), g3(n-1) .... from state */ + gcurnt1 = *px; + + /* save g1(n) in state buffer */ + *px++ = (q15_t) gnext4; + + /* Sample processing for K4, K8.... */ + /* Process first sample for 4th, 8th .. tap */ + /* f4(n) = f3(n) + K4 * g3(n-1) */ + fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; + fnext1 = __SSAT(fnext1, 16); + + /* Process second sample for 4th, 8th .. tap */ + /* for sample 2 processing */ + fnext2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fcurnt2; + fnext2 = __SSAT(fnext2, 16); + + /* Process third sample for 4th, 8th .. tap */ + fnext3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fcurnt3; + fnext3 = __SSAT(fnext3, 16); + + /* Process fourth sample for 4th, 8th .. tap */ + fnext4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fcurnt4; + fnext4 = __SSAT(fnext4, 16); + + /* g4(n) = f3(n) * K4 + g3(n-1) */ + /* Calculation of state values for next stage */ + gnext4 = (q31_t) ((fcurnt4 * (*pk)) >> 15u) + gnext3; + gnext4 = __SSAT(gnext4, 16); + + gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + gnext2; + gnext3 = __SSAT(gnext3, 16); + + gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + gnext1; + gnext2 = __SSAT(gnext2, 16); + gnext1 = (q31_t) ((fcurnt1 * (*pk++)) >> 15u) + gcurnt1; + gnext1 = __SSAT(gnext1, 16); + + + /* Read g2(n-1), g4(n-1) .... from state */ + gcurnt1 = *px; + + /* save g4(n) in state buffer */ + *px++ = (q15_t) gnext4; + + /* Sample processing for K5, K9.... */ + /* Process first sample for 5th, 9th .. tap */ + /* f5(n) = f4(n) + K5 * g4(n-1) */ + fcurnt1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fnext1; + fcurnt1 = __SSAT(fcurnt1, 16); + + /* Process second sample for 5th, 9th .. tap */ + fcurnt2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fnext2; + fcurnt2 = __SSAT(fcurnt2, 16); + + /* Process third sample for 5th, 9th .. tap */ + fcurnt3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fnext3; + fcurnt3 = __SSAT(fcurnt3, 16); + + /* Process fourth sample for 5th, 9th .. tap */ + fcurnt4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fnext4; + fcurnt4 = __SSAT(fcurnt4, 16); + + /* Calculation of state values for next stage */ + /* g5(n) = f4(n) * K5 + g4(n-1) */ + gnext4 = (q31_t) ((fnext4 * (*pk)) >> 15u) + gnext3; + gnext4 = __SSAT(gnext4, 16); + gnext3 = (q31_t) ((fnext3 * (*pk)) >> 15u) + gnext2; + gnext3 = __SSAT(gnext3, 16); + gnext2 = (q31_t) ((fnext2 * (*pk)) >> 15u) + gnext1; + gnext2 = __SSAT(gnext2, 16); + gnext1 = (q31_t) ((fnext1 * (*pk++)) >> 15u) + gcurnt1; + gnext1 = __SSAT(gnext1, 16); + + stageCnt--; + } + + /* If the (filter length -1) is not a multiple of 4, compute the remaining filter taps */ + stageCnt = (numStages - 1u) % 0x4u; + + while(stageCnt > 0u) + { + gcurnt1 = *px; + + /* save g value in state buffer */ + *px++ = (q15_t) gnext4; + + /* Process four samples for last three taps here */ + fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; + fnext1 = __SSAT(fnext1, 16); + fnext2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fcurnt2; + fnext2 = __SSAT(fnext2, 16); + + fnext3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fcurnt3; + fnext3 = __SSAT(fnext3, 16); + + fnext4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fcurnt4; + fnext4 = __SSAT(fnext4, 16); + + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext4 = (q31_t) ((fcurnt4 * (*pk)) >> 15u) + gnext3; + gnext4 = __SSAT(gnext4, 16); + gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + gnext2; + gnext3 = __SSAT(gnext3, 16); + gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + gnext1; + gnext2 = __SSAT(gnext2, 16); + gnext1 = (q31_t) ((fcurnt1 * (*pk++)) >> 15u) + gcurnt1; + gnext1 = __SSAT(gnext1, 16); + + /* Update of f values for next coefficient set processing */ + fcurnt1 = fnext1; + fcurnt2 = fnext2; + fcurnt3 = fnext3; + fcurnt4 = fnext4; + + stageCnt--; + + } + + /* The results in the 4 accumulators, store in the destination buffer. */ + /* y(n) = fN(n) */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = __PKHBT(fcurnt1, fcurnt2, 16); + *__SIMD32(pDst)++ = __PKHBT(fcurnt3, fcurnt4, 16); + +#else + + *__SIMD32(pDst)++ = __PKHBT(fcurnt2, fcurnt1, 16); + *__SIMD32(pDst)++ = __PKHBT(fcurnt4, fcurnt3, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* f0(n) = x(n) */ + fcurnt1 = *pSrc++; + + /* Initialize coeff pointer */ + pk = (pCoeffs); + + /* Initialize state pointer */ + px = pState; + + /* read g2(n) from state buffer */ + gcurnt1 = *px; + + /* for sample 1 processing */ + /* f1(n) = f0(n) + K1 * g0(n-1) */ + fnext1 = (((q31_t) gcurnt1 * (*pk)) >> 15u) + fcurnt1; + fnext1 = __SSAT(fnext1, 16); + + + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext1 = (((q31_t) fcurnt1 * (*pk++)) >> 15u) + gcurnt1; + gnext1 = __SSAT(gnext1, 16); + + /* save g1(n) in state buffer */ + *px++ = (q15_t) fcurnt1; + + /* f1(n) is saved in fcurnt1 + for next stage processing */ + fcurnt1 = fnext1; + + stageCnt = (numStages - 1u); + + /* stage loop */ + while(stageCnt > 0u) + { + /* read g2(n) from state buffer */ + gcurnt1 = *px; + + /* save g1(n) in state buffer */ + *px++ = (q15_t) gnext1; + + /* Sample processing for K2, K3.... */ + /* f2(n) = f1(n) + K2 * g1(n-1) */ + fnext1 = (((q31_t) gcurnt1 * (*pk)) >> 15u) + fcurnt1; + fnext1 = __SSAT(fnext1, 16); + + /* g2(n) = f1(n) * K2 + g1(n-1) */ + gnext1 = (((q31_t) fcurnt1 * (*pk++)) >> 15u) + gcurnt1; + gnext1 = __SSAT(gnext1, 16); + + + /* f1(n) is saved in fcurnt1 + for next stage processing */ + fcurnt1 = fnext1; + + stageCnt--; + + } + + /* y(n) = fN(n) */ + *pDst++ = __SSAT(fcurnt1, 16); + + + blkCnt--; + + } + +#else + + /* Run the below code for Cortex-M0 */ + + q31_t fcurnt, fnext, gcurnt, gnext; /* temporary variables */ + uint32_t numStages = S->numStages; /* Length of the filter */ + uint32_t blkCnt, stageCnt; /* temporary variables for counts */ + + pState = &S->pState[0]; + + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* f0(n) = x(n) */ + fcurnt = *pSrc++; + + /* Initialize coeff pointer */ + pk = (pCoeffs); + + /* Initialize state pointer */ + px = pState; + + /* read g0(n-1) from state buffer */ + gcurnt = *px; + + /* for sample 1 processing */ + /* f1(n) = f0(n) + K1 * g0(n-1) */ + fnext = ((gcurnt * (*pk)) >> 15u) + fcurnt; + fnext = __SSAT(fnext, 16); + + + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext = ((fcurnt * (*pk++)) >> 15u) + gcurnt; + gnext = __SSAT(gnext, 16); + + /* save f0(n) in state buffer */ + *px++ = (q15_t) fcurnt; + + /* f1(n) is saved in fcurnt + for next stage processing */ + fcurnt = fnext; + + stageCnt = (numStages - 1u); + + /* stage loop */ + while(stageCnt > 0u) + { + /* read g1(n-1) from state buffer */ + gcurnt = *px; + + /* save g0(n-1) in state buffer */ + *px++ = (q15_t) gnext; + + /* Sample processing for K2, K3.... */ + /* f2(n) = f1(n) + K2 * g1(n-1) */ + fnext = ((gcurnt * (*pk)) >> 15u) + fcurnt; + fnext = __SSAT(fnext, 16); + + /* g2(n) = f1(n) * K2 + g1(n-1) */ + gnext = ((fcurnt * (*pk++)) >> 15u) + gcurnt; + gnext = __SSAT(gnext, 16); + + + /* f1(n) is saved in fcurnt + for next stage processing */ + fcurnt = fnext; + + stageCnt--; + + } + + /* y(n) = fN(n) */ + *pDst++ = __SSAT(fcurnt, 16); + + + blkCnt--; + + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q31.c index 2f4c22a50..99c9a87a1 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q31.c @@ -1,440 +1,440 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_q31.c -* -* Description: Q31 FIR lattice filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - - -/** - * @brief Processing function for the Q31 FIR lattice filter. - * @param[in] *S points to an instance of the Q31 FIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of samples to process. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * In order to avoid overflows the input signal must be scaled down by 2*log2(numStages) bits. - */ - -void arm_fir_lattice_q31( - const arm_fir_lattice_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *px; /* temporary state pointer */ - q31_t *pk; /* temporary coefficient pointer */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t fcurr1, fnext1, gcurr1 = 0, gnext1; /* temporary variables for first sample in loop unrolling */ - q63_t fcurr2, fnext2, gnext2; /* temporary variables for second sample in loop unrolling */ - q63_t fcurr3, fnext3, gnext3; /* temporary variables for third sample in loop unrolling */ - q63_t fcurr4, fnext4, gnext4; /* temporary variables for fourth sample in loop unrolling */ - uint32_t numStages = S->numStages; /* Length of the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - pState = &S->pState[0]; - - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - - /* Read two samples from input buffer */ - /* f0(n) = x(n) */ - fcurr1 = *pSrc++; - /* f0(n) = x(n) */ - fcurr2 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* Read g0(n-1) from state */ - gcurr1 = *px; - - /* Process first sample for first tap */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk)) >> 31) + gcurr1; - - /* Process second sample for first tap */ - /* for sample 2 processing */ - fnext2 = (q31_t) (((q63_t) fcurr1 * (*pk)) >> 31) + fcurr2; - gnext2 = (q31_t) (((q63_t) fcurr2 * (*pk)) >> 31) + fcurr1; - - - /* Read next two samples from input buffer */ - /* f0(n+2) = x(n+2) */ - fcurr3 = *pSrc++; - fcurr4 = *pSrc++; - - /* Copy only last input samples into the state buffer - which will be used for next four samples processing */ - *px++ = (q31_t) fcurr4; - - /* Process third sample for first tap */ - fnext3 = (q31_t) (((q63_t) fcurr2 * (*pk)) >> 31) + fcurr3; - gnext3 = (q31_t) (((q63_t) fcurr3 * (*pk)) >> 31) + fcurr2; - - /* Process fourth sample for first tap */ - fnext4 = (q31_t) (((q63_t) fcurr3 * (*pk)) >> 31) + fcurr4; - gnext4 = (q31_t) (((q63_t) fcurr4 * (*pk++)) >> 31) + fcurr3; - - /* save g1(n) in state buffer for next sample processing */ - /* *px++ = gnext4; */ - - /* Update of f values for next coefficient set processing */ - fcurr1 = fnext1; - fcurr2 = fnext2; - fcurr3 = fnext3; - fcurr4 = fnext4; - - - /* Loop unrolling. Process 4 taps at a time . */ - stageCnt = (numStages - 1u) >> 2u; - - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numStages-3 coefficients. */ - - /* Process 2nd, 3rd, 4th and 5th taps ... here */ - while(stageCnt > 0u) - { - /* Read g1(n-1), g3(n-1) .... from state */ - gcurr1 = *px; - - /* save g1(n) in state buffer */ - *px++ = (q31_t) gnext4; - - /* Process first sample for 2nd, 6th .. tap */ - /* Sample processing for K2, K6.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; - /* Process second sample for 2nd, 6th .. tap */ - /* for sample 2 processing */ - fnext2 = (q31_t) (((q63_t) gnext1 * (*pk)) >> 31) + fcurr2; - /* Process third sample for 2nd, 6th .. tap */ - fnext3 = (q31_t) (((q63_t) gnext2 * (*pk)) >> 31) + fcurr3; - /* Process fourth sample for 2nd, 6th .. tap */ - fnext4 = (q31_t) (((q63_t) gnext3 * (*pk)) >> 31) + fcurr4; - - /* g2(n) = f1(n) * K2 + g1(n-1) */ - /* Calculation of state values for next stage */ - gnext4 = (q31_t) (((q63_t) fcurr4 * (*pk)) >> 31) + gnext3; - gnext3 = (q31_t) (((q63_t) fcurr3 * (*pk)) >> 31) + gnext2; - gnext2 = (q31_t) (((q63_t) fcurr2 * (*pk)) >> 31) + gnext1; - gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk++)) >> 31) + gcurr1; - - - /* Read g2(n-1), g4(n-1) .... from state */ - gcurr1 = *px; - - /* save g2(n) in state buffer */ - *px++ = (q31_t) gnext4; - - /* Sample processing for K3, K7.... */ - /* Process first sample for 3rd, 7th .. tap */ - /* f3(n) = f2(n) + K3 * g2(n-1) */ - fcurr1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fnext1; - /* Process second sample for 3rd, 7th .. tap */ - fcurr2 = (q31_t) (((q63_t) gnext1 * (*pk)) >> 31) + fnext2; - /* Process third sample for 3rd, 7th .. tap */ - fcurr3 = (q31_t) (((q63_t) gnext2 * (*pk)) >> 31) + fnext3; - /* Process fourth sample for 3rd, 7th .. tap */ - fcurr4 = (q31_t) (((q63_t) gnext3 * (*pk)) >> 31) + fnext4; - - /* Calculation of state values for next stage */ - /* gnext4 = fnext4 * (*pk) + gnext3; */ - gnext4 = (q31_t) (((q63_t) fnext4 * (*pk)) >> 31) + gnext3; - gnext3 = (q31_t) (((q63_t) fnext3 * (*pk)) >> 31) + gnext2; - /* gnext2 = fnext2 * (*pk) + gnext1; */ - gnext2 = (q31_t) (((q63_t) fnext2 * (*pk)) >> 31) + gnext1; - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - /* gnext1 = fnext1 * (*pk++) + gcurr1; */ - gnext1 = (q31_t) (((q63_t) fnext1 * (*pk++)) >> 31) + gcurr1; - - /* Read g1(n-1), g3(n-1) .... from state */ - gcurr1 = *px; - - /* save g1(n) in state buffer */ - *px++ = (q31_t) gnext4; - - /* Sample processing for K4, K8.... */ - /* Process first sample for 4th, 8th .. tap */ - /* f4(n) = f3(n) + K4 * g3(n-1) */ - fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; - /* Process second sample for 4th, 8th .. tap */ - /* for sample 2 processing */ - fnext2 = (q31_t) (((q63_t) gnext1 * (*pk)) >> 31) + fcurr2; - /* Process third sample for 4th, 8th .. tap */ - fnext3 = (q31_t) (((q63_t) gnext2 * (*pk)) >> 31) + fcurr3; - /* Process fourth sample for 4th, 8th .. tap */ - fnext4 = (q31_t) (((q63_t) gnext3 * (*pk)) >> 31) + fcurr4; - - /* g4(n) = f3(n) * K4 + g3(n-1) */ - /* Calculation of state values for next stage */ - gnext4 = (q31_t) (((q63_t) fcurr4 * (*pk)) >> 31) + gnext3; - gnext3 = (q31_t) (((q63_t) fcurr3 * (*pk)) >> 31) + gnext2; - gnext2 = (q31_t) (((q63_t) fcurr2 * (*pk)) >> 31) + gnext1; - gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk++)) >> 31) + gcurr1; - - /* Read g2(n-1), g4(n-1) .... from state */ - gcurr1 = *px; - - /* save g4(n) in state buffer */ - *px++ = (q31_t) gnext4; - - /* Sample processing for K5, K9.... */ - /* Process first sample for 5th, 9th .. tap */ - /* f5(n) = f4(n) + K5 * g4(n-1) */ - fcurr1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fnext1; - /* Process second sample for 5th, 9th .. tap */ - fcurr2 = (q31_t) (((q63_t) gnext1 * (*pk)) >> 31) + fnext2; - /* Process third sample for 5th, 9th .. tap */ - fcurr3 = (q31_t) (((q63_t) gnext2 * (*pk)) >> 31) + fnext3; - /* Process fourth sample for 5th, 9th .. tap */ - fcurr4 = (q31_t) (((q63_t) gnext3 * (*pk)) >> 31) + fnext4; - - /* Calculation of state values for next stage */ - /* g5(n) = f4(n) * K5 + g4(n-1) */ - gnext4 = (q31_t) (((q63_t) fnext4 * (*pk)) >> 31) + gnext3; - gnext3 = (q31_t) (((q63_t) fnext3 * (*pk)) >> 31) + gnext2; - gnext2 = (q31_t) (((q63_t) fnext2 * (*pk)) >> 31) + gnext1; - gnext1 = (q31_t) (((q63_t) fnext1 * (*pk++)) >> 31) + gcurr1; - - stageCnt--; - } - - /* If the (filter length -1) is not a multiple of 4, compute the remaining filter taps */ - stageCnt = (numStages - 1u) % 0x4u; - - while(stageCnt > 0u) - { - gcurr1 = *px; - - /* save g value in state buffer */ - *px++ = (q31_t) gnext4; - - /* Process four samples for last three taps here */ - fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; - fnext2 = (q31_t) (((q63_t) gnext1 * (*pk)) >> 31) + fcurr2; - fnext3 = (q31_t) (((q63_t) gnext2 * (*pk)) >> 31) + fcurr3; - fnext4 = (q31_t) (((q63_t) gnext3 * (*pk)) >> 31) + fcurr4; - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext4 = (q31_t) (((q63_t) fcurr4 * (*pk)) >> 31) + gnext3; - gnext3 = (q31_t) (((q63_t) fcurr3 * (*pk)) >> 31) + gnext2; - gnext2 = (q31_t) (((q63_t) fcurr2 * (*pk)) >> 31) + gnext1; - gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk++)) >> 31) + gcurr1; - - /* Update of f values for next coefficient set processing */ - fcurr1 = fnext1; - fcurr2 = fnext2; - fcurr3 = fnext3; - fcurr4 = fnext4; - - stageCnt--; - - } - - /* The results in the 4 accumulators, store in the destination buffer. */ - /* y(n) = fN(n) */ - *pDst++ = fcurr1; - *pDst++ = (q31_t) fcurr2; - *pDst++ = (q31_t) fcurr3; - *pDst++ = (q31_t) fcurr4; - - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurr1 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g2(n) from state buffer */ - gcurr1 = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk++)) >> 31) + gcurr1; - /* save g1(n) in state buffer */ - *px++ = fcurr1; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr1 = fnext1; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g2(n) from state buffer */ - gcurr1 = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext1; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk++)) >> 31) + gcurr1; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr1 = fnext1; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = fcurr1; - - blkCnt--; - - } - -#else - -/* Run the below code for Cortex-M0 */ - - q31_t fcurr, fnext, gcurr, gnext; /* temporary variables */ - uint32_t numStages = S->numStages; /* Length of the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - pState = &S->pState[0]; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g0(n-1) from state buffer */ - gcurr = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext = (q31_t) (((q63_t) gcurr * (*pk)) >> 31) + fcurr; - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext = (q31_t) (((q63_t) fcurr * (*pk++)) >> 31) + gcurr; - /* save g1(n) in state buffer */ - *px++ = fcurr; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr = fnext; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g2(n) from state buffer */ - gcurr = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext = (q31_t) (((q63_t) gcurr * (*pk)) >> 31) + fcurr; - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext = (q31_t) (((q63_t) fcurr * (*pk++)) >> 31) + gcurr; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr = fnext; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = fcurr; - - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Lattice group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_lattice_q31.c +* +* Description: Q31 FIR lattice filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Lattice + * @{ + */ + + +/** + * @brief Processing function for the Q31 FIR lattice filter. + * @param[in] *S points to an instance of the Q31 FIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] blockSize number of samples to process. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * In order to avoid overflows the input signal must be scaled down by 2*log2(numStages) bits. + */ + +void arm_fir_lattice_q31( + const arm_fir_lattice_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t *pState; /* State pointer */ + q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *px; /* temporary state pointer */ + q31_t *pk; /* temporary coefficient pointer */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t fcurr1, fnext1, gcurr1 = 0, gnext1; /* temporary variables for first sample in loop unrolling */ + q63_t fcurr2, fnext2, gnext2; /* temporary variables for second sample in loop unrolling */ + q63_t fcurr3, fnext3, gnext3; /* temporary variables for third sample in loop unrolling */ + q63_t fcurr4, fnext4, gnext4; /* temporary variables for fourth sample in loop unrolling */ + uint32_t numStages = S->numStages; /* Length of the filter */ + uint32_t blkCnt, stageCnt; /* temporary variables for counts */ + + pState = &S->pState[0]; + + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + + /* Read two samples from input buffer */ + /* f0(n) = x(n) */ + fcurr1 = *pSrc++; + /* f0(n) = x(n) */ + fcurr2 = *pSrc++; + + /* Initialize coeff pointer */ + pk = (pCoeffs); + + /* Initialize state pointer */ + px = pState; + + /* Read g0(n-1) from state */ + gcurr1 = *px; + + /* Process first sample for first tap */ + /* f1(n) = f0(n) + K1 * g0(n-1) */ + fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk)) >> 31) + gcurr1; + + /* Process second sample for first tap */ + /* for sample 2 processing */ + fnext2 = (q31_t) (((q63_t) fcurr1 * (*pk)) >> 31) + fcurr2; + gnext2 = (q31_t) (((q63_t) fcurr2 * (*pk)) >> 31) + fcurr1; + + + /* Read next two samples from input buffer */ + /* f0(n+2) = x(n+2) */ + fcurr3 = *pSrc++; + fcurr4 = *pSrc++; + + /* Copy only last input samples into the state buffer + which will be used for next four samples processing */ + *px++ = (q31_t) fcurr4; + + /* Process third sample for first tap */ + fnext3 = (q31_t) (((q63_t) fcurr2 * (*pk)) >> 31) + fcurr3; + gnext3 = (q31_t) (((q63_t) fcurr3 * (*pk)) >> 31) + fcurr2; + + /* Process fourth sample for first tap */ + fnext4 = (q31_t) (((q63_t) fcurr3 * (*pk)) >> 31) + fcurr4; + gnext4 = (q31_t) (((q63_t) fcurr4 * (*pk++)) >> 31) + fcurr3; + + /* save g1(n) in state buffer for next sample processing */ + /* *px++ = gnext4; */ + + /* Update of f values for next coefficient set processing */ + fcurr1 = fnext1; + fcurr2 = fnext2; + fcurr3 = fnext3; + fcurr4 = fnext4; + + + /* Loop unrolling. Process 4 taps at a time . */ + stageCnt = (numStages - 1u) >> 2u; + + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numStages-3 coefficients. */ + + /* Process 2nd, 3rd, 4th and 5th taps ... here */ + while(stageCnt > 0u) + { + /* Read g1(n-1), g3(n-1) .... from state */ + gcurr1 = *px; + + /* save g1(n) in state buffer */ + *px++ = (q31_t) gnext4; + + /* Process first sample for 2nd, 6th .. tap */ + /* Sample processing for K2, K6.... */ + /* f2(n) = f1(n) + K2 * g1(n-1) */ + fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; + /* Process second sample for 2nd, 6th .. tap */ + /* for sample 2 processing */ + fnext2 = (q31_t) (((q63_t) gnext1 * (*pk)) >> 31) + fcurr2; + /* Process third sample for 2nd, 6th .. tap */ + fnext3 = (q31_t) (((q63_t) gnext2 * (*pk)) >> 31) + fcurr3; + /* Process fourth sample for 2nd, 6th .. tap */ + fnext4 = (q31_t) (((q63_t) gnext3 * (*pk)) >> 31) + fcurr4; + + /* g2(n) = f1(n) * K2 + g1(n-1) */ + /* Calculation of state values for next stage */ + gnext4 = (q31_t) (((q63_t) fcurr4 * (*pk)) >> 31) + gnext3; + gnext3 = (q31_t) (((q63_t) fcurr3 * (*pk)) >> 31) + gnext2; + gnext2 = (q31_t) (((q63_t) fcurr2 * (*pk)) >> 31) + gnext1; + gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk++)) >> 31) + gcurr1; + + + /* Read g2(n-1), g4(n-1) .... from state */ + gcurr1 = *px; + + /* save g2(n) in state buffer */ + *px++ = (q31_t) gnext4; + + /* Sample processing for K3, K7.... */ + /* Process first sample for 3rd, 7th .. tap */ + /* f3(n) = f2(n) + K3 * g2(n-1) */ + fcurr1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fnext1; + /* Process second sample for 3rd, 7th .. tap */ + fcurr2 = (q31_t) (((q63_t) gnext1 * (*pk)) >> 31) + fnext2; + /* Process third sample for 3rd, 7th .. tap */ + fcurr3 = (q31_t) (((q63_t) gnext2 * (*pk)) >> 31) + fnext3; + /* Process fourth sample for 3rd, 7th .. tap */ + fcurr4 = (q31_t) (((q63_t) gnext3 * (*pk)) >> 31) + fnext4; + + /* Calculation of state values for next stage */ + /* gnext4 = fnext4 * (*pk) + gnext3; */ + gnext4 = (q31_t) (((q63_t) fnext4 * (*pk)) >> 31) + gnext3; + gnext3 = (q31_t) (((q63_t) fnext3 * (*pk)) >> 31) + gnext2; + /* gnext2 = fnext2 * (*pk) + gnext1; */ + gnext2 = (q31_t) (((q63_t) fnext2 * (*pk)) >> 31) + gnext1; + + /* g1(n) = f0(n) * K1 + g0(n-1) */ + /* gnext1 = fnext1 * (*pk++) + gcurr1; */ + gnext1 = (q31_t) (((q63_t) fnext1 * (*pk++)) >> 31) + gcurr1; + + /* Read g1(n-1), g3(n-1) .... from state */ + gcurr1 = *px; + + /* save g1(n) in state buffer */ + *px++ = (q31_t) gnext4; + + /* Sample processing for K4, K8.... */ + /* Process first sample for 4th, 8th .. tap */ + /* f4(n) = f3(n) + K4 * g3(n-1) */ + fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; + /* Process second sample for 4th, 8th .. tap */ + /* for sample 2 processing */ + fnext2 = (q31_t) (((q63_t) gnext1 * (*pk)) >> 31) + fcurr2; + /* Process third sample for 4th, 8th .. tap */ + fnext3 = (q31_t) (((q63_t) gnext2 * (*pk)) >> 31) + fcurr3; + /* Process fourth sample for 4th, 8th .. tap */ + fnext4 = (q31_t) (((q63_t) gnext3 * (*pk)) >> 31) + fcurr4; + + /* g4(n) = f3(n) * K4 + g3(n-1) */ + /* Calculation of state values for next stage */ + gnext4 = (q31_t) (((q63_t) fcurr4 * (*pk)) >> 31) + gnext3; + gnext3 = (q31_t) (((q63_t) fcurr3 * (*pk)) >> 31) + gnext2; + gnext2 = (q31_t) (((q63_t) fcurr2 * (*pk)) >> 31) + gnext1; + gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk++)) >> 31) + gcurr1; + + /* Read g2(n-1), g4(n-1) .... from state */ + gcurr1 = *px; + + /* save g4(n) in state buffer */ + *px++ = (q31_t) gnext4; + + /* Sample processing for K5, K9.... */ + /* Process first sample for 5th, 9th .. tap */ + /* f5(n) = f4(n) + K5 * g4(n-1) */ + fcurr1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fnext1; + /* Process second sample for 5th, 9th .. tap */ + fcurr2 = (q31_t) (((q63_t) gnext1 * (*pk)) >> 31) + fnext2; + /* Process third sample for 5th, 9th .. tap */ + fcurr3 = (q31_t) (((q63_t) gnext2 * (*pk)) >> 31) + fnext3; + /* Process fourth sample for 5th, 9th .. tap */ + fcurr4 = (q31_t) (((q63_t) gnext3 * (*pk)) >> 31) + fnext4; + + /* Calculation of state values for next stage */ + /* g5(n) = f4(n) * K5 + g4(n-1) */ + gnext4 = (q31_t) (((q63_t) fnext4 * (*pk)) >> 31) + gnext3; + gnext3 = (q31_t) (((q63_t) fnext3 * (*pk)) >> 31) + gnext2; + gnext2 = (q31_t) (((q63_t) fnext2 * (*pk)) >> 31) + gnext1; + gnext1 = (q31_t) (((q63_t) fnext1 * (*pk++)) >> 31) + gcurr1; + + stageCnt--; + } + + /* If the (filter length -1) is not a multiple of 4, compute the remaining filter taps */ + stageCnt = (numStages - 1u) % 0x4u; + + while(stageCnt > 0u) + { + gcurr1 = *px; + + /* save g value in state buffer */ + *px++ = (q31_t) gnext4; + + /* Process four samples for last three taps here */ + fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; + fnext2 = (q31_t) (((q63_t) gnext1 * (*pk)) >> 31) + fcurr2; + fnext3 = (q31_t) (((q63_t) gnext2 * (*pk)) >> 31) + fcurr3; + fnext4 = (q31_t) (((q63_t) gnext3 * (*pk)) >> 31) + fcurr4; + + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext4 = (q31_t) (((q63_t) fcurr4 * (*pk)) >> 31) + gnext3; + gnext3 = (q31_t) (((q63_t) fcurr3 * (*pk)) >> 31) + gnext2; + gnext2 = (q31_t) (((q63_t) fcurr2 * (*pk)) >> 31) + gnext1; + gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk++)) >> 31) + gcurr1; + + /* Update of f values for next coefficient set processing */ + fcurr1 = fnext1; + fcurr2 = fnext2; + fcurr3 = fnext3; + fcurr4 = fnext4; + + stageCnt--; + + } + + /* The results in the 4 accumulators, store in the destination buffer. */ + /* y(n) = fN(n) */ + *pDst++ = fcurr1; + *pDst++ = (q31_t) fcurr2; + *pDst++ = (q31_t) fcurr3; + *pDst++ = (q31_t) fcurr4; + + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* f0(n) = x(n) */ + fcurr1 = *pSrc++; + + /* Initialize coeff pointer */ + pk = (pCoeffs); + + /* Initialize state pointer */ + px = pState; + + /* read g2(n) from state buffer */ + gcurr1 = *px; + + /* for sample 1 processing */ + /* f1(n) = f0(n) + K1 * g0(n-1) */ + fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk++)) >> 31) + gcurr1; + /* save g1(n) in state buffer */ + *px++ = fcurr1; + + /* f1(n) is saved in fcurr1 + for next stage processing */ + fcurr1 = fnext1; + + stageCnt = (numStages - 1u); + + /* stage loop */ + while(stageCnt > 0u) + { + /* read g2(n) from state buffer */ + gcurr1 = *px; + + /* save g1(n) in state buffer */ + *px++ = gnext1; + + /* Sample processing for K2, K3.... */ + /* f2(n) = f1(n) + K2 * g1(n-1) */ + fnext1 = (q31_t) (((q63_t) gcurr1 * (*pk)) >> 31) + fcurr1; + /* g2(n) = f1(n) * K2 + g1(n-1) */ + gnext1 = (q31_t) (((q63_t) fcurr1 * (*pk++)) >> 31) + gcurr1; + + /* f1(n) is saved in fcurr1 + for next stage processing */ + fcurr1 = fnext1; + + stageCnt--; + + } + + /* y(n) = fN(n) */ + *pDst++ = fcurr1; + + blkCnt--; + + } + +#else + +/* Run the below code for Cortex-M0 */ + + q31_t fcurr, fnext, gcurr, gnext; /* temporary variables */ + uint32_t numStages = S->numStages; /* Length of the filter */ + uint32_t blkCnt, stageCnt; /* temporary variables for counts */ + + pState = &S->pState[0]; + + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* f0(n) = x(n) */ + fcurr = *pSrc++; + + /* Initialize coeff pointer */ + pk = (pCoeffs); + + /* Initialize state pointer */ + px = pState; + + /* read g0(n-1) from state buffer */ + gcurr = *px; + + /* for sample 1 processing */ + /* f1(n) = f0(n) + K1 * g0(n-1) */ + fnext = (q31_t) (((q63_t) gcurr * (*pk)) >> 31) + fcurr; + /* g1(n) = f0(n) * K1 + g0(n-1) */ + gnext = (q31_t) (((q63_t) fcurr * (*pk++)) >> 31) + gcurr; + /* save g1(n) in state buffer */ + *px++ = fcurr; + + /* f1(n) is saved in fcurr1 + for next stage processing */ + fcurr = fnext; + + stageCnt = (numStages - 1u); + + /* stage loop */ + while(stageCnt > 0u) + { + /* read g2(n) from state buffer */ + gcurr = *px; + + /* save g1(n) in state buffer */ + *px++ = gnext; + + /* Sample processing for K2, K3.... */ + /* f2(n) = f1(n) + K2 * g1(n-1) */ + fnext = (q31_t) (((q63_t) gcurr * (*pk)) >> 31) + fcurr; + /* g2(n) = f1(n) * K2 + g1(n-1) */ + gnext = (q31_t) (((q63_t) fcurr * (*pk++)) >> 31) + gcurr; + + /* f1(n) is saved in fcurr1 + for next stage processing */ + fcurr = fnext; + + stageCnt--; + + } + + /* y(n) = fN(n) */ + *pDst++ = fcurr; + + blkCnt--; + + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q15.c index 28214d11e..ea011d50f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q15.c @@ -1,368 +1,368 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_q15.c -* -* Description: Q15 FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @brief Processing function for the Q15 FIR filter. - * @param[in] *S points to an instance of the Q15 FIR structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - * - * \par - * Refer to the function arm_fir_fast_q15() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -void arm_fir_q15( - const arm_fir_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *px1; /* Temporary q15 pointer for state buffer */ - q31_t *pb; /* Temporary pointer for coefficient buffer */ - q31_t *px2; /* Temporary q31 pointer for SIMD state buffer accesses */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold SIMD state and coefficient values */ - q63_t acc0, acc1, acc2, acc3; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of taps in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer. - ** Use 32-bit SIMD to move the 16-bit data. Only requires two copies. */ - *__SIMD32(pStateCurnt)++ = *__SIMD32(pSrc)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pSrc)++; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Initialize state pointer of type q15 */ - px1 = pState; - - /* Initialize coeff pointer of type q31 */ - pb = (q31_t *) (pCoeffs); - - /* Read the first two samples from the state buffer: x[n-N], x[n-N-1] */ - x0 = *(q31_t *) (px1++); - - /* Read the third and forth samples from the state buffer: x[n-N-1], x[n-N-2] */ - x1 = *(q31_t *) (px1++); - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - tapCnt = numTaps >> 2; - do - { - /* Read the first two coefficients using SIMD: b[N] and b[N-1] coefficients */ - c0 = *(pb++); - - /* acc0 += b[N] * x[n-N] + b[N-1] * x[n-N-1] */ - acc0 = __SMLALD(x0, c0, acc0); - - /* acc1 += b[N] * x[n-N-1] + b[N-1] * x[n-N-2] */ - acc1 = __SMLALD(x1, c0, acc1); - - /* Read state x[n-N-2], x[n-N-3] */ - x2 = *(q31_t *) (px1++); - - /* Read state x[n-N-3], x[n-N-4] */ - x3 = *(q31_t *) (px1++); - - /* acc2 += b[N] * x[n-N-2] + b[N-1] * x[n-N-3] */ - acc2 = __SMLALD(x2, c0, acc2); - - /* acc3 += b[N] * x[n-N-3] + b[N-1] * x[n-N-4] */ - acc3 = __SMLALD(x3, c0, acc3); - - /* Read coefficients b[N-2], b[N-3] */ - c0 = *(pb++); - - /* acc0 += b[N-2] * x[n-N-2] + b[N-3] * x[n-N-3] */ - acc0 = __SMLALD(x2, c0, acc0); - - /* acc1 += b[N-2] * x[n-N-3] + b[N-3] * x[n-N-4] */ - acc1 = __SMLALD(x3, c0, acc1); - - /* Read state x[n-N-4], x[n-N-5] */ - x0 = *(q31_t *) (px1++); - - /* Read state x[n-N-5], x[n-N-6] */ - x1 = *(q31_t *) (px1++); - - /* acc2 += b[N-2] * x[n-N-4] + b[N-3] * x[n-N-5] */ - acc2 = __SMLALD(x0, c0, acc2); - - /* acc3 += b[N-2] * x[n-N-5] + b[N-3] * x[n-N-6] */ - acc3 = __SMLALD(x1, c0, acc3); - tapCnt--; - - } - while(tapCnt > 0u); - - /* If the filter length is not a multiple of 4, compute the remaining filter taps. - ** This is always be 2 taps since the filter length is even. */ - if((numTaps & 0x3u) != 0u) - { - /* Read 2 coefficients */ - c0 = *(pb++); - /* Fetch 4 state variables */ - x2 = *(q31_t *) (px1++); - x3 = *(q31_t *) (px1++); - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALD(x2, c0, acc2); - acc3 = __SMLALD(x3, c0, acc3); - } - - /* The results in the 4 accumulators are in 2.30 format. Convert to 1.15 with saturation. - ** Then store the 4 outputs in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - while(blkCnt > 0u) - { - /* Copy two samples into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Use SIMD to hold states and coefficients */ - px2 = (q31_t *) pState; - pb = (q31_t *) (pCoeffs); - tapCnt = numTaps >> 1; - - do - { - acc0 = __SMLALD(*px2++, *(pb++), acc0); - tapCnt--; - } - while(tapCnt > 0u); - - /* The result is in 2.30 format. Convert to 1.15 with saturation. - ** Then store the output in the destination buffer. */ - *pDst++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Calculation of count for copying integer writes */ - tapCnt = (numTaps - 1u) >> 2; - - while(tapCnt > 0u) - { - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - tapCnt--; - - } - - /* Calculation of count for remaining q15_t data */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* copy remaining data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t *px; /* Temporary pointer for state buffer */ - q15_t *pb; /* Temporary pointer for coefficient buffer */ - q63_t acc; /* Accumulator */ - uint32_t numTaps = S->numTaps; /* Number of nTaps in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Initialize blkCnt with blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = pCoeffs; - - tapCnt = numTaps; - - /* Perform the multiply-accumulates */ - do - { - /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ - acc += (q31_t) * px++ * *pb++; - tapCnt--; - } while(tapCnt > 0u); - - /* The result is in 2.30 format. Convert to 1.15 - ** Then store the output in the destination buffer. */ - *pDst++ = (q15_t) __SSAT((acc >> 15u), 16); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Copy numTaps number of values */ - tapCnt = (numTaps - 1u); - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_q15.c +* +* Description: Q15 FIR filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR + * @{ + */ + +/** + * @brief Processing function for the Q15 FIR filter. + * @param[in] *S points to an instance of the Q15 FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 64-bit internal accumulator. + * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. + * Lastly, the accumulator is saturated to yield a result in 1.15 format. + * + * \par + * Refer to the function arm_fir_fast_q15() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. + */ + +void arm_fir_q15( + const arm_fir_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + q15_t *pState = S->pState; /* State pointer */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q15_t *pStateCurnt; /* Points to the current sample of the state */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t *px1; /* Temporary q15 pointer for state buffer */ + q31_t *pb; /* Temporary pointer for coefficient buffer */ + q31_t *px2; /* Temporary q31 pointer for SIMD state buffer accesses */ + q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold SIMD state and coefficient values */ + q63_t acc0, acc1, acc2, acc3; /* Accumulators */ + uint32_t numTaps = S->numTaps; /* Number of taps in the filter */ + uint32_t tapCnt, blkCnt; /* Loop counters */ + + /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Apply loop unrolling and compute 4 output values simultaneously. + * The variables acc0 ... acc3 hold output values that are being computed: + * + * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] + * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] + * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] + * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] + */ + blkCnt = blockSize >> 2; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Copy four new input samples into the state buffer. + ** Use 32-bit SIMD to move the 16-bit data. Only requires two copies. */ + *__SIMD32(pStateCurnt)++ = *__SIMD32(pSrc)++; + *__SIMD32(pStateCurnt)++ = *__SIMD32(pSrc)++; + + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* Initialize state pointer of type q15 */ + px1 = pState; + + /* Initialize coeff pointer of type q31 */ + pb = (q31_t *) (pCoeffs); + + /* Read the first two samples from the state buffer: x[n-N], x[n-N-1] */ + x0 = *(q31_t *) (px1++); + + /* Read the third and forth samples from the state buffer: x[n-N-1], x[n-N-2] */ + x1 = *(q31_t *) (px1++); + + /* Loop over the number of taps. Unroll by a factor of 4. + ** Repeat until we've computed numTaps-4 coefficients. */ + tapCnt = numTaps >> 2; + do + { + /* Read the first two coefficients using SIMD: b[N] and b[N-1] coefficients */ + c0 = *(pb++); + + /* acc0 += b[N] * x[n-N] + b[N-1] * x[n-N-1] */ + acc0 = __SMLALD(x0, c0, acc0); + + /* acc1 += b[N] * x[n-N-1] + b[N-1] * x[n-N-2] */ + acc1 = __SMLALD(x1, c0, acc1); + + /* Read state x[n-N-2], x[n-N-3] */ + x2 = *(q31_t *) (px1++); + + /* Read state x[n-N-3], x[n-N-4] */ + x3 = *(q31_t *) (px1++); + + /* acc2 += b[N] * x[n-N-2] + b[N-1] * x[n-N-3] */ + acc2 = __SMLALD(x2, c0, acc2); + + /* acc3 += b[N] * x[n-N-3] + b[N-1] * x[n-N-4] */ + acc3 = __SMLALD(x3, c0, acc3); + + /* Read coefficients b[N-2], b[N-3] */ + c0 = *(pb++); + + /* acc0 += b[N-2] * x[n-N-2] + b[N-3] * x[n-N-3] */ + acc0 = __SMLALD(x2, c0, acc0); + + /* acc1 += b[N-2] * x[n-N-3] + b[N-3] * x[n-N-4] */ + acc1 = __SMLALD(x3, c0, acc1); + + /* Read state x[n-N-4], x[n-N-5] */ + x0 = *(q31_t *) (px1++); + + /* Read state x[n-N-5], x[n-N-6] */ + x1 = *(q31_t *) (px1++); + + /* acc2 += b[N-2] * x[n-N-4] + b[N-3] * x[n-N-5] */ + acc2 = __SMLALD(x0, c0, acc2); + + /* acc3 += b[N-2] * x[n-N-5] + b[N-3] * x[n-N-6] */ + acc3 = __SMLALD(x1, c0, acc3); + tapCnt--; + + } + while(tapCnt > 0u); + + /* If the filter length is not a multiple of 4, compute the remaining filter taps. + ** This is always be 2 taps since the filter length is even. */ + if((numTaps & 0x3u) != 0u) + { + /* Read 2 coefficients */ + c0 = *(pb++); + /* Fetch 4 state variables */ + x2 = *(q31_t *) (px1++); + x3 = *(q31_t *) (px1++); + + /* Perform the multiply-accumulates */ + acc0 = __SMLALD(x0, c0, acc0); + acc1 = __SMLALD(x1, c0, acc1); + acc2 = __SMLALD(x2, c0, acc2); + acc3 = __SMLALD(x3, c0, acc3); + } + + /* The results in the 4 accumulators are in 2.30 format. Convert to 1.15 with saturation. + ** Then store the 4 outputs in the destination buffer. */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst)++ = + __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); + *__SIMD32(pDst)++ = + __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); + +#else + + *__SIMD32(pDst)++ = + __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); + *__SIMD32(pDst)++ = + __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Advance the state pointer by 4 to process the next group of 4 samples */ + pState = pState + 4; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + while(blkCnt > 0u) + { + /* Copy two samples into state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Set the accumulator to zero */ + acc0 = 0; + + /* Use SIMD to hold states and coefficients */ + px2 = (q31_t *) pState; + pb = (q31_t *) (pCoeffs); + tapCnt = numTaps >> 1; + + do + { + acc0 = __SMLALD(*px2++, *(pb++), acc0); + tapCnt--; + } + while(tapCnt > 0u); + + /* The result is in 2.30 format. Convert to 1.15 with saturation. + ** Then store the output in the destination buffer. */ + *pDst++ = (q15_t) (__SSAT((acc0 >> 15), 16)); + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + /* Calculation of count for copying integer writes */ + tapCnt = (numTaps - 1u) >> 2; + + while(tapCnt > 0u) + { + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + + tapCnt--; + + } + + /* Calculation of count for remaining q15_t data */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* copy remaining data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q15_t *px; /* Temporary pointer for state buffer */ + q15_t *pb; /* Temporary pointer for coefficient buffer */ + q63_t acc; /* Accumulator */ + uint32_t numTaps = S->numTaps; /* Number of nTaps in the filter */ + uint32_t tapCnt, blkCnt; /* Loop counters */ + + /* S->pState buffer contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Initialize blkCnt with blockSize */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Copy one sample at a time into state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Set the accumulator to zero */ + acc = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize Coefficient pointer */ + pb = pCoeffs; + + tapCnt = numTaps; + + /* Perform the multiply-accumulates */ + do + { + /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ + acc += (q31_t) * px++ * *pb++; + tapCnt--; + } while(tapCnt > 0u); + + /* The result is in 2.30 format. Convert to 1.15 + ** Then store the output in the destination buffer. */ + *pDst++ = (q15_t) __SSAT((acc >> 15u), 16); + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the samples loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + /* Copy numTaps number of values */ + tapCnt = (numTaps - 1u); + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q31.c index adabf8458..0891a7631 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q31.c @@ -1,383 +1,383 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_q31.c -* -* Description: Q31 FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @param[in] *S points to an instance of the Q31 FIR filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits. - * After all multiply-accumulates are performed, the 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. - * - * \par - * Refer to the function arm_fir_fast_q31() for a faster but less precise implementation of this filter for Cortex-M3 and Cortex-M4. - */ - -void arm_fir_q31( - const arm_fir_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t x0, x1, x2, x3; /* Temporary variables to hold state */ - q31_t c0; /* Temporary variable to hold coefficient value */ - q31_t *px; /* Temporary pointer for state */ - q31_t *pb; /* Temporary pointer for coefficient buffer */ - q63_t acc0, acc1, acc2, acc3; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt; /* Loop counters */ - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Read the first three samples from the state buffer: - * x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - i = tapCnt; - - while(i > 0u) - { - /* Read the b[numTaps] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x3 = *(px++); - - /* acc0 += b[numTaps] * x[n-numTaps] */ - acc0 += ((q63_t) x0 * c0); - - /* acc1 += b[numTaps] * x[n-numTaps-1] */ - acc1 += ((q63_t) x1 * c0); - - /* acc2 += b[numTaps] * x[n-numTaps-2] */ - acc2 += ((q63_t) x2 * c0); - - /* acc3 += b[numTaps] * x[n-numTaps-3] */ - acc3 += ((q63_t) x3 * c0); - - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q63_t) x1 * c0); - acc1 += ((q63_t) x2 * c0); - acc2 += ((q63_t) x3 * c0); - acc3 += ((q63_t) x0 * c0); - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q63_t) x2 * c0); - acc1 += ((q63_t) x3 * c0); - acc2 += ((q63_t) x0 * c0); - acc3 += ((q63_t) x1 * c0); - /* Read the b[numTaps-3] coefficients */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q63_t) x3 * c0); - acc1 += ((q63_t) x0 * c0); - acc2 += ((q63_t) x1 * c0); - acc3 += ((q63_t) x2 * c0); - i--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - - i = numTaps - (tapCnt * 4u); - while(i > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q63_t) x0 * c0); - acc1 += ((q63_t) x1 * c0); - acc2 += ((q63_t) x2 * c0); - acc3 += ((q63_t) x3 * c0); - - /* Reuse the present sample states for next sample */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4; - - /* The results in the 4 accumulators are in 2.62 format. Convert to 1.31 - ** Then store the 4 outputs in the destination buffer. */ - *pDst++ = (q31_t) (acc0 >> 31u); - *pDst++ = (q31_t) (acc1 >> 31u); - *pDst++ = (q31_t) (acc2 >> 31u); - *pDst++ = (q31_t) (acc3 >> 31u); - - /* Decrement the samples loop counter */ - blkCnt--; - } - - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 4u; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = (pCoeffs); - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - acc0 += (q63_t) * (px++) * (*(pb++)); - i--; - } while(i > 0u); - - /* The result is in 2.62 format. Convert to 1.31 - ** Then store the output in the destination buffer. */ - *pDst++ = (q31_t) (acc0 >> 31u); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - q31_t *px; /* Temporary pointer for state */ - q31_t *pb; /* Temporary pointer for coefficient buffer */ - q63_t acc; /* Accumulator */ - uint32_t numTaps = S->numTaps; /* Length of the filter */ - uint32_t i, tapCnt, blkCnt; /* Loop counters */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Initialize blkCnt with blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = pCoeffs; - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ - acc += (q63_t) * px++ * *pb++; - i--; - } while(i > 0u); - - /* The result is in 2.62 format. Convert to 1.31 - ** Then store the output in the destination buffer. */ - *pDst++ = (q31_t) (acc >> 31u); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the starting of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Copy numTaps number of values */ - tapCnt = numTaps - 1u; - - /* Copy the data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_q31.c +* +* Description: Q31 FIR filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR + * @{ + */ + +/** + * @param[in] *S points to an instance of the Q31 FIR filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around rather than clip. + * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits. + * After all multiply-accumulates are performed, the 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. + * + * \par + * Refer to the function arm_fir_fast_q31() for a faster but less precise implementation of this filter for Cortex-M3 and Cortex-M4. + */ + +void arm_fir_q31( + const arm_fir_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t *pState = S->pState; /* State pointer */ + q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *pStateCurnt; /* Points to the current sample of the state */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t x0, x1, x2, x3; /* Temporary variables to hold state */ + q31_t c0; /* Temporary variable to hold coefficient value */ + q31_t *px; /* Temporary pointer for state */ + q31_t *pb; /* Temporary pointer for coefficient buffer */ + q63_t acc0, acc1, acc2, acc3; /* Accumulators */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + uint32_t i, tapCnt, blkCnt; /* Loop counters */ + + /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Apply loop unrolling and compute 4 output values simultaneously. + * The variables acc0 ... acc3 hold output values that are being computed: + * + * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] + * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] + * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] + * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] + */ + blkCnt = blockSize >> 2; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Copy four new input samples into the state buffer */ + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coefficient pointer */ + pb = pCoeffs; + + /* Read the first three samples from the state buffer: + * x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + i = tapCnt; + + while(i > 0u) + { + /* Read the b[numTaps] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-3] sample */ + x3 = *(px++); + + /* acc0 += b[numTaps] * x[n-numTaps] */ + acc0 += ((q63_t) x0 * c0); + + /* acc1 += b[numTaps] * x[n-numTaps-1] */ + acc1 += ((q63_t) x1 * c0); + + /* acc2 += b[numTaps] * x[n-numTaps-2] */ + acc2 += ((q63_t) x2 * c0); + + /* acc3 += b[numTaps] * x[n-numTaps-3] */ + acc3 += ((q63_t) x3 * c0); + + /* Read the b[numTaps-1] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += ((q63_t) x1 * c0); + acc1 += ((q63_t) x2 * c0); + acc2 += ((q63_t) x3 * c0); + acc3 += ((q63_t) x0 * c0); + + /* Read the b[numTaps-2] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += ((q63_t) x2 * c0); + acc1 += ((q63_t) x3 * c0); + acc2 += ((q63_t) x0 * c0); + acc3 += ((q63_t) x1 * c0); + /* Read the b[numTaps-3] coefficients */ + c0 = *(pb++); + + /* Read x[n-numTaps-6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += ((q63_t) x3 * c0); + acc1 += ((q63_t) x0 * c0); + acc2 += ((q63_t) x1 * c0); + acc3 += ((q63_t) x2 * c0); + i--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + + i = numTaps - (tapCnt * 4u); + while(i > 0u) + { + /* Read coefficients */ + c0 = *(pb++); + + /* Fetch 1 state variable */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += ((q63_t) x0 * c0); + acc1 += ((q63_t) x1 * c0); + acc2 += ((q63_t) x2 * c0); + acc3 += ((q63_t) x3 * c0); + + /* Reuse the present sample states for next sample */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + i--; + } + + /* Advance the state pointer by 4 to process the next group of 4 samples */ + pState = pState + 4; + + /* The results in the 4 accumulators are in 2.62 format. Convert to 1.31 + ** Then store the 4 outputs in the destination buffer. */ + *pDst++ = (q31_t) (acc0 >> 31u); + *pDst++ = (q31_t) (acc1 >> 31u); + *pDst++ = (q31_t) (acc2 >> 31u); + *pDst++ = (q31_t) (acc3 >> 31u); + + /* Decrement the samples loop counter */ + blkCnt--; + } + + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 4u; + + while(blkCnt > 0u) + { + /* Copy one sample at a time into state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Set the accumulator to zero */ + acc0 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize Coefficient pointer */ + pb = (pCoeffs); + + i = numTaps; + + /* Perform the multiply-accumulates */ + do + { + acc0 += (q63_t) * (px++) * (*(pb++)); + i--; + } while(i > 0u); + + /* The result is in 2.62 format. Convert to 1.31 + ** Then store the output in the destination buffer. */ + *pDst++ = (q31_t) (acc0 >> 31u); + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the samples loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + tapCnt = (numTaps - 1u) >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Calculate remaining number of copies */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + +/* Run the below code for Cortex-M0 */ + + q31_t *px; /* Temporary pointer for state */ + q31_t *pb; /* Temporary pointer for coefficient buffer */ + q63_t acc; /* Accumulator */ + uint32_t numTaps = S->numTaps; /* Length of the filter */ + uint32_t i, tapCnt, blkCnt; /* Loop counters */ + + /* S->pState buffer contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Initialize blkCnt with blockSize */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Copy one sample at a time into state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Set the accumulator to zero */ + acc = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize Coefficient pointer */ + pb = pCoeffs; + + i = numTaps; + + /* Perform the multiply-accumulates */ + do + { + /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ + acc += (q63_t) * px++ * *pb++; + i--; + } while(i > 0u); + + /* The result is in 2.62 format. Convert to 1.31 + ** Then store the output in the destination buffer. */ + *pDst++ = (q31_t) (acc >> 31u); + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the samples loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the starting of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + /* Copy numTaps number of values */ + tapCnt = numTaps - 1u; + + /* Copy the data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q7.c index c2d70c290..42529d095 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_q7.c @@ -1,385 +1,385 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_q7.c -* -* Description: Q7 FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @param[in] *S points to an instance of the Q7 FIR filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 32-bit internal accumulator. - * Both coefficients and state variables are represented in 1.7 format and multiplications yield a 2.14 result. - * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * The accumulator is converted to 18.7 format by discarding the low 7 bits. - * Finally, the result is truncated to 1.7 format. - */ - -void arm_fir_q7( - const arm_fir_instance_q7 * S, - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t *pState = S->pState; /* State pointer */ - q7_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q7_t *pStateCurnt; /* Points to the current sample of the state */ - q7_t x0, x1, x2, x3; /* Temporary variables to hold state */ - q7_t c0; /* Temporary variable to hold coefficient value */ - q7_t *px; /* Temporary pointer for state */ - q7_t *pb; /* Temporary pointer for coefficient buffer */ - q31_t acc0, acc1, acc2, acc3; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt; /* Loop counters */ - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Read the first three samples from the state buffer: - * x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - i = tapCnt; - - while(i > 0u) - { - /* Read the b[numTaps] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x3 = *(px++); - - /* acc0 += b[numTaps] * x[n-numTaps] */ - acc0 += ((q15_t) x0 * c0); - - /* acc1 += b[numTaps] * x[n-numTaps-1] */ - acc1 += ((q15_t) x1 * c0); - - /* acc2 += b[numTaps] * x[n-numTaps-2] */ - acc2 += ((q15_t) x2 * c0); - - /* acc3 += b[numTaps] * x[n-numTaps-3] */ - acc3 += ((q15_t) x3 * c0); - - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q15_t) x1 * c0); - acc1 += ((q15_t) x2 * c0); - acc2 += ((q15_t) x3 * c0); - acc3 += ((q15_t) x0 * c0); - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q15_t) x2 * c0); - acc1 += ((q15_t) x3 * c0); - acc2 += ((q15_t) x0 * c0); - acc3 += ((q15_t) x1 * c0); - /* Read the b[numTaps-3] coefficients */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q15_t) x3 * c0); - acc1 += ((q15_t) x0 * c0); - acc2 += ((q15_t) x1 * c0); - acc3 += ((q15_t) x2 * c0); - i--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - - i = numTaps - (tapCnt * 4u); - while(i > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q15_t) x0 * c0); - acc1 += ((q15_t) x1 * c0); - acc2 += ((q15_t) x2 * c0); - acc3 += ((q15_t) x3 * c0); - - /* Reuse the present sample states for next sample */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4; - - /* The results in the 4 accumulators are in 2.62 format. Convert to 1.31 - ** Then store the 4 outputs in the destination buffer. */ - acc0 = __SSAT((acc0 >> 7u), 8); - *pDst++ = acc0; - acc1 = __SSAT((acc1 >> 7u), 8); - *pDst++ = acc1; - acc2 = __SSAT((acc2 >> 7u), 8); - *pDst++ = acc2; - acc3 = __SSAT((acc3 >> 7u), 8); - *pDst++ = acc3; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 4u; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = (pCoeffs); - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - acc0 += (q15_t) * (px++) * (*(pb++)); - i--; - } while(i > 0u); - - /* The result is in 2.14 format. Convert to 1.7 - ** Then store the output in the destination buffer. */ - *pDst++ = __SSAT((acc0 >> 7u), 8); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - uint32_t numTaps = S->numTaps; /* Number of taps in the filter */ - uint32_t i, blkCnt; /* Loop counters */ - q7_t *pState = S->pState; /* State pointer */ - q7_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q7_t *px, *pb; /* Temporary pointers to state and coeff */ - q31_t acc = 0; /* Accumlator */ - q7_t *pStateCurnt; /* Points to the current sample of the state */ - - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Initialize blkCnt with blockSize */ - blkCnt = blockSize; - - /* Perform filtering upto BlockSize - BlockSize%4 */ - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set accumulator to zero */ - acc = 0; - - /* Initialize state pointer of type q7 */ - px = pState; - - /* Initialize coeff pointer of type q7 */ - pb = pCoeffs; - - - i = numTaps; - - while(i > 0u) - { - /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ - acc += (q15_t) * px++ * *pb++; - i--; - } - - /* Store the 1.7 format filter output in destination buffer */ - *pDst++ = (q7_t) __SSAT((acc >> 7), 8); - - /* Advance the state pointer by 1 to process the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - - /* Copy numTaps number of values */ - i = (numTaps - 1u); - - /* Copy q7_t data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - i--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_q7.c +* +* Description: Q7 FIR filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR + * @{ + */ + +/** + * @param[in] *S points to an instance of the Q7 FIR filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 32-bit internal accumulator. + * Both coefficients and state variables are represented in 1.7 format and multiplications yield a 2.14 result. + * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. + * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + * The accumulator is converted to 18.7 format by discarding the low 7 bits. + * Finally, the result is truncated to 1.7 format. + */ + +void arm_fir_q7( + const arm_fir_instance_q7 * S, + q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize) +{ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q7_t *pState = S->pState; /* State pointer */ + q7_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q7_t *pStateCurnt; /* Points to the current sample of the state */ + q7_t x0, x1, x2, x3; /* Temporary variables to hold state */ + q7_t c0; /* Temporary variable to hold coefficient value */ + q7_t *px; /* Temporary pointer for state */ + q7_t *pb; /* Temporary pointer for coefficient buffer */ + q31_t acc0, acc1, acc2, acc3; /* Accumulators */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + uint32_t i, tapCnt, blkCnt; /* Loop counters */ + + /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Apply loop unrolling and compute 4 output values simultaneously. + * The variables acc0 ... acc3 hold output values that are being computed: + * + * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] + * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] + * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] + * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] + */ + blkCnt = blockSize >> 2; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Copy four new input samples into the state buffer */ + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + *pStateCurnt++ = *pSrc++; + + /* Set all accumulators to zero */ + acc0 = 0; + acc1 = 0; + acc2 = 0; + acc3 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coefficient pointer */ + pb = pCoeffs; + + /* Read the first three samples from the state buffer: + * x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ + x0 = *(px++); + x1 = *(px++); + x2 = *(px++); + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + i = tapCnt; + + while(i > 0u) + { + /* Read the b[numTaps] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-3] sample */ + x3 = *(px++); + + /* acc0 += b[numTaps] * x[n-numTaps] */ + acc0 += ((q15_t) x0 * c0); + + /* acc1 += b[numTaps] * x[n-numTaps-1] */ + acc1 += ((q15_t) x1 * c0); + + /* acc2 += b[numTaps] * x[n-numTaps-2] */ + acc2 += ((q15_t) x2 * c0); + + /* acc3 += b[numTaps] * x[n-numTaps-3] */ + acc3 += ((q15_t) x3 * c0); + + /* Read the b[numTaps-1] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-4] sample */ + x0 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += ((q15_t) x1 * c0); + acc1 += ((q15_t) x2 * c0); + acc2 += ((q15_t) x3 * c0); + acc3 += ((q15_t) x0 * c0); + + /* Read the b[numTaps-2] coefficient */ + c0 = *(pb++); + + /* Read x[n-numTaps-5] sample */ + x1 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += ((q15_t) x2 * c0); + acc1 += ((q15_t) x3 * c0); + acc2 += ((q15_t) x0 * c0); + acc3 += ((q15_t) x1 * c0); + /* Read the b[numTaps-3] coefficients */ + c0 = *(pb++); + + /* Read x[n-numTaps-6] sample */ + x2 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += ((q15_t) x3 * c0); + acc1 += ((q15_t) x0 * c0); + acc2 += ((q15_t) x1 * c0); + acc3 += ((q15_t) x2 * c0); + i--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + + i = numTaps - (tapCnt * 4u); + while(i > 0u) + { + /* Read coefficients */ + c0 = *(pb++); + + /* Fetch 1 state variable */ + x3 = *(px++); + + /* Perform the multiply-accumulates */ + acc0 += ((q15_t) x0 * c0); + acc1 += ((q15_t) x1 * c0); + acc2 += ((q15_t) x2 * c0); + acc3 += ((q15_t) x3 * c0); + + /* Reuse the present sample states for next sample */ + x0 = x1; + x1 = x2; + x2 = x3; + + /* Decrement the loop counter */ + i--; + } + + /* Advance the state pointer by 4 to process the next group of 4 samples */ + pState = pState + 4; + + /* The results in the 4 accumulators are in 2.62 format. Convert to 1.31 + ** Then store the 4 outputs in the destination buffer. */ + acc0 = __SSAT((acc0 >> 7u), 8); + *pDst++ = acc0; + acc1 = __SSAT((acc1 >> 7u), 8); + *pDst++ = acc1; + acc2 = __SSAT((acc2 >> 7u), 8); + *pDst++ = acc2; + acc3 = __SSAT((acc3 >> 7u), 8); + *pDst++ = acc3; + + /* Decrement the samples loop counter */ + blkCnt--; + } + + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 4u; + + while(blkCnt > 0u) + { + /* Copy one sample at a time into state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Set the accumulator to zero */ + acc0 = 0; + + /* Initialize state pointer */ + px = pState; + + /* Initialize Coefficient pointer */ + pb = (pCoeffs); + + i = numTaps; + + /* Perform the multiply-accumulates */ + do + { + acc0 += (q15_t) * (px++) * (*(pb++)); + i--; + } while(i > 0u); + + /* The result is in 2.14 format. Convert to 1.7 + ** Then store the output in the destination buffer. */ + *pDst++ = __SSAT((acc0 >> 7u), 8); + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the samples loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + tapCnt = (numTaps - 1u) >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Calculate remaining number of copies */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + +/* Run the below code for Cortex-M0 */ + + uint32_t numTaps = S->numTaps; /* Number of taps in the filter */ + uint32_t i, blkCnt; /* Loop counters */ + q7_t *pState = S->pState; /* State pointer */ + q7_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q7_t *px, *pb; /* Temporary pointers to state and coeff */ + q31_t acc = 0; /* Accumlator */ + q7_t *pStateCurnt; /* Points to the current sample of the state */ + + + /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = S->pState + (numTaps - 1u); + + /* Initialize blkCnt with blockSize */ + blkCnt = blockSize; + + /* Perform filtering upto BlockSize - BlockSize%4 */ + while(blkCnt > 0u) + { + /* Copy one sample at a time into state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Set accumulator to zero */ + acc = 0; + + /* Initialize state pointer of type q7 */ + px = pState; + + /* Initialize coeff pointer of type q7 */ + pb = pCoeffs; + + + i = numTaps; + + while(i > 0u) + { + /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ + acc += (q15_t) * px++ * *pb++; + i--; + } + + /* Store the 1.7 format filter output in destination buffer */ + *pDst++ = (q7_t) __SSAT((acc >> 7), 8); + + /* Advance the state pointer by 1 to process the next sample */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. + ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. + ** This prepares the state buffer for the next function call. */ + + + /* Points to the start of the state buffer */ + pStateCurnt = S->pState; + + + /* Copy numTaps number of values */ + i = (numTaps - 1u); + + /* Copy q7_t data */ + while(i > 0u) + { + *pStateCurnt++ = *pState++; + i--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_f32.c index c83965b18..aaede629a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_f32.c @@ -1,362 +1,362 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_f32.c -* -* Description: Floating-point sparse FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup FIR_Sparse Finite Impulse Response (FIR) Sparse Filters - * - * This group of functions implements sparse FIR filters. - * Sparse FIR filters are equivalent to standard FIR filters except that most of the coefficients are equal to zero. - * Sparse filters are used for simulating reflections in communications and audio applications. - * - * There are separate functions for Q7, Q15, Q31, and floating-point data types. - * The functions operate on blocks of input and output data and each call to the function processes - * blockSize samples through the filter. pSrc and - * pDst points to input and output arrays respectively containing blockSize values. - * - * \par Algorithm: - * The sparse filter instant structure contains an array of tap indices pTapDelay which specifies the locations of the non-zero coefficients. - * This is in addition to the coefficient array b. - * The implementation essentially skips the multiplications by zero and leads to an efficient realization. - *
  
- *     y[n] = b[0] * x[n-pTapDelay[0]] + b[1] * x[n-pTapDelay[1]] + b[2] * x[n-pTapDelay[2]] + ...+ b[numTaps-1] * x[n-pTapDelay[numTaps-1]]   
- * 
- * \par - * \image html FIRSparse.gif "Sparse FIR filter. b[n] represents the filter coefficients" - * \par - * pCoeffs points to a coefficient array of size numTaps; - * pTapDelay points to an array of nonzero indices and is also of size numTaps; - * pState points to a state array of size maxDelay + blockSize, where - * maxDelay is the largest offset value that is ever used in the pTapDelay array. - * Some of the processing functions also require temporary working buffers. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient and offset arrays may be shared among several instances while state variable arrays cannot be shared. - * There are separate instance structure declarations for each of the 4 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * The code below statically initializes each of the 4 different data type filter instance structures - *
   
- *arm_fir_sparse_instance_f32 S = {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};   
- *arm_fir_sparse_instance_q31 S = {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};   
- *arm_fir_sparse_instance_q15 S = {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};   
- *arm_fir_sparse_instance_q7 S =  {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};   
- * 
- * \par - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the sparse FIR filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Processing function for the floating-point sparse FIR filter. - * @param[in] *S points to an instance of the floating-point sparse FIR structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] *pScratchIn points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - * @return none. - */ - -void arm_fir_sparse_f32( - arm_fir_sparse_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - float32_t * pScratchIn, - uint32_t blockSize) -{ - - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *px; /* Scratch buffer pointer */ - float32_t *py = pState; /* Temporary pointers for state buffer */ - float32_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ - float32_t *pOut; /* Destination pointer */ - int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ - uint32_t delaySize = S->maxDelay + blockSize; /* state length */ - uint16_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - int32_t readIndex; /* Read index of the state buffer */ - uint32_t tapCnt, blkCnt; /* loop counters */ - float32_t coeff = *pCoeffs++; /* Read the first coefficient value */ - - - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_f32((int32_t *) py, delaySize, &S->stateIndex, 1, - (int32_t *) pSrc, 1, blockSize); - - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer */ - px = pb; - - /* Working pointer for destination buffer */ - pOut = pDst; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 Multiplications at a time. */ - blkCnt = blockSize >> 2u; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in destination buffer */ - *pOut++ = *px++ * coeff; - *pOut++ = *px++ * coeff; - *pOut++ = *px++ * coeff; - *pOut++ = *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in destination buffer */ - *pOut++ = *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer */ - px = pb; - - /* Working pointer for destination buffer */ - pOut = pDst; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 MACS at a time. */ - blkCnt = blockSize >> 2u; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pOut++ += *px++ * coeff; - *pOut++ += *px++ * coeff; - *pOut++ += *px++ * coeff; - *pOut++ += *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pOut++ += *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in destination buffer */ - *pOut++ = *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer */ - px = pb; - - /* Working pointer for destination buffer */ - pOut = pDst; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pOut++ += *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = - ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Sparse group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_sparse_f32.c +* +* Description: Floating-point sparse FIR filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ------------------------------------------------------------------- */ +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup FIR_Sparse Finite Impulse Response (FIR) Sparse Filters + * + * This group of functions implements sparse FIR filters. + * Sparse FIR filters are equivalent to standard FIR filters except that most of the coefficients are equal to zero. + * Sparse filters are used for simulating reflections in communications and audio applications. + * + * There are separate functions for Q7, Q15, Q31, and floating-point data types. + * The functions operate on blocks of input and output data and each call to the function processes + * blockSize samples through the filter. pSrc and + * pDst points to input and output arrays respectively containing blockSize values. + * + * \par Algorithm: + * The sparse filter instant structure contains an array of tap indices pTapDelay which specifies the locations of the non-zero coefficients. + * This is in addition to the coefficient array b. + * The implementation essentially skips the multiplications by zero and leads to an efficient realization. + *
  
+ *     y[n] = b[0] * x[n-pTapDelay[0]] + b[1] * x[n-pTapDelay[1]] + b[2] * x[n-pTapDelay[2]] + ...+ b[numTaps-1] * x[n-pTapDelay[numTaps-1]]   
+ * 
+ * \par + * \image html FIRSparse.gif "Sparse FIR filter. b[n] represents the filter coefficients" + * \par + * pCoeffs points to a coefficient array of size numTaps; + * pTapDelay points to an array of nonzero indices and is also of size numTaps; + * pState points to a state array of size maxDelay + blockSize, where + * maxDelay is the largest offset value that is ever used in the pTapDelay array. + * Some of the processing functions also require temporary working buffers. + * + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter. + * Coefficient and offset arrays may be shared among several instances while state variable arrays cannot be shared. + * There are separate instance structure declarations for each of the 4 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Set the values in the state buffer to zeros before static initialization. + * The code below statically initializes each of the 4 different data type filter instance structures + *
   
+ *arm_fir_sparse_instance_f32 S = {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};   
+ *arm_fir_sparse_instance_q31 S = {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};   
+ *arm_fir_sparse_instance_q15 S = {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};   
+ *arm_fir_sparse_instance_q7 S =  {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};   
+ * 
+ * \par + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the sparse FIR filter functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + +/** + * @addtogroup FIR_Sparse + * @{ + */ + +/** + * @brief Processing function for the floating-point sparse FIR filter. + * @param[in] *S points to an instance of the floating-point sparse FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] *pScratchIn points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + * @return none. + */ + +void arm_fir_sparse_f32( + arm_fir_sparse_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + float32_t * pScratchIn, + uint32_t blockSize) +{ + + float32_t *pState = S->pState; /* State pointer */ + float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + float32_t *px; /* Scratch buffer pointer */ + float32_t *py = pState; /* Temporary pointers for state buffer */ + float32_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ + float32_t *pOut; /* Destination pointer */ + int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ + uint32_t delaySize = S->maxDelay + blockSize; /* state length */ + uint16_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + int32_t readIndex; /* Read index of the state buffer */ + uint32_t tapCnt, blkCnt; /* loop counters */ + float32_t coeff = *pCoeffs++; /* Read the first coefficient value */ + + + + /* BlockSize of Input samples are copied into the state buffer */ + /* StateIndex points to the starting position to write in the state buffer */ + arm_circularWrite_f32((int32_t *) py, delaySize, &S->stateIndex, 1, + (int32_t *) pSrc, 1, blockSize); + + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, + (int32_t *) pb, (int32_t *) pb, blockSize, 1, + blockSize); + + /* Working pointer for the scratch buffer */ + px = pb; + + /* Working pointer for destination buffer */ + pOut = pDst; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Loop over the blockSize. Unroll by a factor of 4. + * Compute 4 Multiplications at a time. */ + blkCnt = blockSize >> 2u; + + while(blkCnt > 0u) + { + /* Perform Multiplications and store in destination buffer */ + *pOut++ = *px++ * coeff; + *pOut++ = *px++ * coeff; + *pOut++ = *px++ * coeff; + *pOut++ = *px++ * coeff; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, + * compute the remaining samples */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* Perform Multiplications and store in destination buffer */ + *pOut++ = *px++ * coeff; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Loop over the number of taps. */ + tapCnt = (uint32_t) numTaps - 1u; + + while(tapCnt > 0u) + { + + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, + (int32_t *) pb, (int32_t *) pb, blockSize, 1, + blockSize); + + /* Working pointer for the scratch buffer */ + px = pb; + + /* Working pointer for destination buffer */ + pOut = pDst; + + /* Loop over the blockSize. Unroll by a factor of 4. + * Compute 4 MACS at a time. */ + blkCnt = blockSize >> 2u; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + *pOut++ += *px++ * coeff; + *pOut++ += *px++ * coeff; + *pOut++ += *px++ * coeff; + *pOut++ += *px++ * coeff; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, + * compute the remaining samples */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + *pOut++ += *px++ * coeff; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = ((int32_t) S->stateIndex - + (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Decrement the tap loop counter */ + tapCnt--; + } + +#else + +/* Run the below code for Cortex-M0 */ + + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Perform Multiplications and store in destination buffer */ + *pOut++ = *px++ * coeff; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Loop over the number of taps. */ + tapCnt = (uint32_t) numTaps - 1u; + + while(tapCnt > 0u) + { + + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, + (int32_t *) pb, (int32_t *) pb, blockSize, 1, + blockSize); + + /* Working pointer for the scratch buffer */ + px = pb; + + /* Working pointer for destination buffer */ + pOut = pDst; + + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + *pOut++ += *px++ * coeff; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = + ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Decrement the tap loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR_Sparse group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_f32.c index 1ac9f71d7..3e423a1bf 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_f32.c @@ -1,99 +1,99 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_init_f32.c -* -* Description: Floating-point sparse FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Initialization function for the floating-point sparse FIR filter. - * @param[in,out] *S points to an instance of the floating-point sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] *pCoeffs points to the array of filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] *pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - * @return none - * - * Description: - * \par - * pCoeffs holds the filter coefficients and has length numTaps. - * pState holds the filter's state variables and must be of length - * maxDelay + blockSize, where maxDelay - * is the maximum number of delay line values. - * blockSize is the - * number of samples processed by the arm_fir_sparse_f32() function. - */ - -void arm_fir_sparse_init_f32( - arm_fir_sparse_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign TapDelay pointer */ - S->pTapDelay = pTapDelay; - - /* Assign MaxDelay */ - S->maxDelay = maxDelay; - - /* reset the stateIndex to 0 */ - S->stateIndex = 0u; - - /* Clear state buffer and size is always maxDelay + blockSize */ - memset(pState, 0, (maxDelay + blockSize) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Sparse group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_sparse_init_f32.c +* +* Description: Floating-point sparse FIR filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Sparse + * @{ + */ + +/** + * @brief Initialization function for the floating-point sparse FIR filter. + * @param[in,out] *S points to an instance of the floating-point sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] *pCoeffs points to the array of filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] *pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + * @return none + * + * Description: + * \par + * pCoeffs holds the filter coefficients and has length numTaps. + * pState holds the filter's state variables and must be of length + * maxDelay + blockSize, where maxDelay + * is the maximum number of delay line values. + * blockSize is the + * number of samples processed by the arm_fir_sparse_f32() function. + */ + +void arm_fir_sparse_init_f32( + arm_fir_sparse_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Assign TapDelay pointer */ + S->pTapDelay = pTapDelay; + + /* Assign MaxDelay */ + S->maxDelay = maxDelay; + + /* reset the stateIndex to 0 */ + S->stateIndex = 0u; + + /* Clear state buffer and size is always maxDelay + blockSize */ + memset(pState, 0, (maxDelay + blockSize) * sizeof(float32_t)); + + /* Assign state pointer */ + S->pState = pState; + +} + +/** + * @} end of FIR_Sparse group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q15.c index a74842dff..196b45eec 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q15.c @@ -1,99 +1,99 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_init_q15.c -* -* Description: Q15 sparse FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Initialization function for the Q15 sparse FIR filter. - * @param[in,out] *S points to an instance of the Q15 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] *pCoeffs points to the array of filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] *pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - * @return none - * - * Description: - * \par - * pCoeffs holds the filter coefficients and has length numTaps. - * pState holds the filter's state variables and must be of length - * maxDelay + blockSize, where maxDelay - * is the maximum number of delay line values. - * blockSize is the - * number of words processed by arm_fir_sparse_q15() function. - */ - -void arm_fir_sparse_init_q15( - arm_fir_sparse_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign TapDelay pointer */ - S->pTapDelay = pTapDelay; - - /* Assign MaxDelay */ - S->maxDelay = maxDelay; - - /* reset the stateIndex to 0 */ - S->stateIndex = 0u; - - /* Clear state buffer and size is always maxDelay + blockSize */ - memset(pState, 0, (maxDelay + blockSize) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Sparse group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_sparse_init_q15.c +* +* Description: Q15 sparse FIR filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Sparse + * @{ + */ + +/** + * @brief Initialization function for the Q15 sparse FIR filter. + * @param[in,out] *S points to an instance of the Q15 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] *pCoeffs points to the array of filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] *pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + * @return none + * + * Description: + * \par + * pCoeffs holds the filter coefficients and has length numTaps. + * pState holds the filter's state variables and must be of length + * maxDelay + blockSize, where maxDelay + * is the maximum number of delay line values. + * blockSize is the + * number of words processed by arm_fir_sparse_q15() function. + */ + +void arm_fir_sparse_init_q15( + arm_fir_sparse_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Assign TapDelay pointer */ + S->pTapDelay = pTapDelay; + + /* Assign MaxDelay */ + S->maxDelay = maxDelay; + + /* reset the stateIndex to 0 */ + S->stateIndex = 0u; + + /* Clear state buffer and size is always maxDelay + blockSize */ + memset(pState, 0, (maxDelay + blockSize) * sizeof(q15_t)); + + /* Assign state pointer */ + S->pState = pState; + +} + +/** + * @} end of FIR_Sparse group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q31.c index fc71bc06e..7d1f35d13 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q31.c @@ -1,98 +1,98 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_init_q31.c -* -* Description: Q31 sparse FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Initialization function for the Q31 sparse FIR filter. - * @param[in,out] *S points to an instance of the Q31 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] *pCoeffs points to the array of filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] *pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - * @return none - * - * Description: - * \par - * pCoeffs holds the filter coefficients and has length numTaps. - * pState holds the filter's state variables and must be of length - * maxDelay + blockSize, where maxDelay - * is the maximum number of delay line values. - * blockSize is the number of words processed by arm_fir_sparse_q31() function. - */ - -void arm_fir_sparse_init_q31( - arm_fir_sparse_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign TapDelay pointer */ - S->pTapDelay = pTapDelay; - - /* Assign MaxDelay */ - S->maxDelay = maxDelay; - - /* reset the stateIndex to 0 */ - S->stateIndex = 0u; - - /* Clear state buffer and size is always maxDelay + blockSize */ - memset(pState, 0, (maxDelay + blockSize) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Sparse group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_sparse_init_q31.c +* +* Description: Q31 sparse FIR filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Sparse + * @{ + */ + +/** + * @brief Initialization function for the Q31 sparse FIR filter. + * @param[in,out] *S points to an instance of the Q31 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] *pCoeffs points to the array of filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] *pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + * @return none + * + * Description: + * \par + * pCoeffs holds the filter coefficients and has length numTaps. + * pState holds the filter's state variables and must be of length + * maxDelay + blockSize, where maxDelay + * is the maximum number of delay line values. + * blockSize is the number of words processed by arm_fir_sparse_q31() function. + */ + +void arm_fir_sparse_init_q31( + arm_fir_sparse_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Assign TapDelay pointer */ + S->pTapDelay = pTapDelay; + + /* Assign MaxDelay */ + S->maxDelay = maxDelay; + + /* reset the stateIndex to 0 */ + S->stateIndex = 0u; + + /* Clear state buffer and size is always maxDelay + blockSize */ + memset(pState, 0, (maxDelay + blockSize) * sizeof(q31_t)); + + /* Assign state pointer */ + S->pState = pState; + +} + +/** + * @} end of FIR_Sparse group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q7.c index f6223ac71..c93d6a2c2 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q7.c @@ -1,99 +1,99 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_init_q7.c -* -* Description: Q7 sparse FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Initialization function for the Q7 sparse FIR filter. - * @param[in,out] *S points to an instance of the Q7 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] *pCoeffs points to the array of filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] *pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - * @return none - * - * Description: - * \par - * pCoeffs holds the filter coefficients and has length numTaps. - * pState holds the filter's state variables and must be of length - * maxDelay + blockSize, where maxDelay - * is the maximum number of delay line values. - * blockSize is the - * number of samples processed by the arm_fir_sparse_q7() function. - */ - -void arm_fir_sparse_init_q7( - arm_fir_sparse_instance_q7 * S, - uint16_t numTaps, - q7_t * pCoeffs, - q7_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign TapDelay pointer */ - S->pTapDelay = pTapDelay; - - /* Assign MaxDelay */ - S->maxDelay = maxDelay; - - /* reset the stateIndex to 0 */ - S->stateIndex = 0u; - - /* Clear state buffer and size is always maxDelay + blockSize */ - memset(pState, 0, (maxDelay + blockSize) * sizeof(q7_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Sparse group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_sparse_init_q7.c +* +* Description: Q7 sparse FIR filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Sparse + * @{ + */ + +/** + * @brief Initialization function for the Q7 sparse FIR filter. + * @param[in,out] *S points to an instance of the Q7 sparse FIR structure. + * @param[in] numTaps number of nonzero coefficients in the filter. + * @param[in] *pCoeffs points to the array of filter coefficients. + * @param[in] *pState points to the state buffer. + * @param[in] *pTapDelay points to the array of offset times. + * @param[in] maxDelay maximum offset time supported. + * @param[in] blockSize number of samples that will be processed per block. + * @return none + * + * Description: + * \par + * pCoeffs holds the filter coefficients and has length numTaps. + * pState holds the filter's state variables and must be of length + * maxDelay + blockSize, where maxDelay + * is the maximum number of delay line values. + * blockSize is the + * number of samples processed by the arm_fir_sparse_q7() function. + */ + +void arm_fir_sparse_init_q7( + arm_fir_sparse_instance_q7 * S, + uint16_t numTaps, + q7_t * pCoeffs, + q7_t * pState, + int32_t * pTapDelay, + uint16_t maxDelay, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Assign TapDelay pointer */ + S->pTapDelay = pTapDelay; + + /* Assign MaxDelay */ + S->maxDelay = maxDelay; + + /* reset the stateIndex to 0 */ + S->stateIndex = 0u; + + /* Clear state buffer and size is always maxDelay + blockSize */ + memset(pState, 0, (maxDelay + blockSize) * sizeof(q7_t)); + + /* Assign state pointer */ + S->pState = pState; + +} + +/** + * @} end of FIR_Sparse group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q15.c index c71c1f8bc..28abfa52c 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q15.c @@ -1,403 +1,403 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_q15.c -* -* Description: Q15 sparse FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ -#include "arm_math.h" - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Processing function for the Q15 sparse FIR filter. - * @param[in] *S points to an instance of the Q15 sparse FIR structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] *pScratchIn points to a temporary buffer of size blockSize. - * @param[in] *pScratchOut points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The 1.15 x 1.15 multiplications yield a 2.30 result and these are added to a 2.30 accumulator. - * Thus the full precision of the multiplications is maintained but there is only a single guard bit in the accumulator. - * If the accumulator result overflows it will wrap around rather than saturate. - * After all multiply-accumulates are performed, the 2.30 accumulator is truncated to 2.15 format and then saturated to 1.15 format. - * In order to avoid overflows the input signal or coefficients must be scaled down by log2(numTaps) bits. - */ - - -void arm_fir_sparse_q15( - arm_fir_sparse_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - q15_t * pScratchIn, - q31_t * pScratchOut, - uint32_t blockSize) -{ - - q15_t *pState = S->pState; /* State pointer */ - q15_t *pIn = pSrc; /* Working pointer for input */ - q15_t *pOut = pDst; /* Working pointer for output */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *px; /* Temporary pointers for scratch buffer */ - q15_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ - q15_t *py = pState; /* Temporary pointers for state buffer */ - int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ - uint32_t delaySize = S->maxDelay + blockSize; /* state length */ - uint16_t numTaps = S->numTaps; /* Filter order */ - int32_t readIndex; /* Read index of the state buffer */ - uint32_t tapCnt, blkCnt; /* loop counters */ - q15_t coeff = *pCoeffs++; /* Read the first coefficient value */ - q31_t *pScr2 = pScratchOut; /* Working pointer for pScratchOut */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in1, in2; /* Temporary variables */ - - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_q15(py, delaySize, &S->stateIndex, 1, pIn, 1, blockSize); - - /* Loop over the number of taps. */ - tapCnt = numTaps; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q15(py, delaySize, &readIndex, 1, - pb, pb, blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 multiplications at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q15(py, delaySize, &readIndex, 1, - pb, pb, blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 MACS at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pScratchOut++ += (q31_t) * px++ * coeff; - *pScratchOut++ += (q31_t) * px++ * coeff; - *pScratchOut++ += (q31_t) * px++ * coeff; - *pScratchOut++ += (q31_t) * px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pScratchOut++ += (q31_t) * px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* All the output values are in pScratchOut buffer. - Convert them into 1.15 format, saturate and store in the destination buffer. */ - /* Loop over the blockSize. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - in1 = *pScr2++; - in2 = *pScr2++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT((q15_t) __SSAT(in1 >> 15, 16), (q15_t) __SSAT(in2 >> 15, 16), - 16); - -#else - *__SIMD32(pOut)++ = - __PKHBT((q15_t) __SSAT(in2 >> 15, 16), (q15_t) __SSAT(in1 >> 15, 16), - 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - in1 = *pScr2++; - - in2 = *pScr2++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT((q15_t) __SSAT(in1 >> 15, 16), (q15_t) __SSAT(in2 >> 15, 16), - 16); - -#else - - *__SIMD32(pOut)++ = - __PKHBT((q15_t) __SSAT(in2 >> 15, 16), (q15_t) __SSAT(in1 >> 15, 16), - 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - blkCnt--; - - } - - /* If the blockSize is not a multiple of 4, - remaining samples are processed in the below loop */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - *pOut++ = (q15_t) __SSAT(*pScr2++ >> 15, 16); - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_q15(py, delaySize, &S->stateIndex, 1, pIn, 1, blockSize); - - /* Loop over the number of taps. */ - tapCnt = numTaps; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q15(py, delaySize, &readIndex, 1, - pb, pb, blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q15(py, delaySize, &readIndex, 1, - pb, pb, blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pScratchOut++ += (q31_t) * px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* All the output values are in pScratchOut buffer. - Convert them into 1.15 format, saturate and store in the destination buffer. */ - /* Loop over the blockSize. */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - *pOut++ = (q15_t) __SSAT(*pScr2++ >> 15, 16); - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Sparse group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_sparse_q15.c +* +* Description: Q15 sparse FIR filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ------------------------------------------------------------------- */ +#include "arm_math.h" + +/** + * @addtogroup FIR_Sparse + * @{ + */ + +/** + * @brief Processing function for the Q15 sparse FIR filter. + * @param[in] *S points to an instance of the Q15 sparse FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] *pScratchIn points to a temporary buffer of size blockSize. + * @param[in] *pScratchOut points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 32-bit accumulator. + * The 1.15 x 1.15 multiplications yield a 2.30 result and these are added to a 2.30 accumulator. + * Thus the full precision of the multiplications is maintained but there is only a single guard bit in the accumulator. + * If the accumulator result overflows it will wrap around rather than saturate. + * After all multiply-accumulates are performed, the 2.30 accumulator is truncated to 2.15 format and then saturated to 1.15 format. + * In order to avoid overflows the input signal or coefficients must be scaled down by log2(numTaps) bits. + */ + + +void arm_fir_sparse_q15( + arm_fir_sparse_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + q15_t * pScratchIn, + q31_t * pScratchOut, + uint32_t blockSize) +{ + + q15_t *pState = S->pState; /* State pointer */ + q15_t *pIn = pSrc; /* Working pointer for input */ + q15_t *pOut = pDst; /* Working pointer for output */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q15_t *px; /* Temporary pointers for scratch buffer */ + q15_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ + q15_t *py = pState; /* Temporary pointers for state buffer */ + int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ + uint32_t delaySize = S->maxDelay + blockSize; /* state length */ + uint16_t numTaps = S->numTaps; /* Filter order */ + int32_t readIndex; /* Read index of the state buffer */ + uint32_t tapCnt, blkCnt; /* loop counters */ + q15_t coeff = *pCoeffs++; /* Read the first coefficient value */ + q31_t *pScr2 = pScratchOut; /* Working pointer for pScratchOut */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t in1, in2; /* Temporary variables */ + + + /* BlockSize of Input samples are copied into the state buffer */ + /* StateIndex points to the starting position to write in the state buffer */ + arm_circularWrite_q15(py, delaySize, &S->stateIndex, 1, pIn, 1, blockSize); + + /* Loop over the number of taps. */ + tapCnt = numTaps; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_q15(py, delaySize, &readIndex, 1, + pb, pb, blockSize, 1, blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pScratchOut = pScr2; + + /* Loop over the blockSize. Unroll by a factor of 4. + * Compute 4 multiplications at a time. */ + blkCnt = blockSize >> 2; + + while(blkCnt > 0u) + { + /* Perform multiplication and store in the scratch buffer */ + *pScratchOut++ = ((q31_t) * px++ * coeff); + *pScratchOut++ = ((q31_t) * px++ * coeff); + *pScratchOut++ = ((q31_t) * px++ * coeff); + *pScratchOut++ = ((q31_t) * px++ * coeff); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, + * compute the remaining samples */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* Perform multiplication and store in the scratch buffer */ + *pScratchOut++ = ((q31_t) * px++ * coeff); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Loop over the number of taps. */ + tapCnt = (uint32_t) numTaps - 1u; + + while(tapCnt > 0u) + { + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_q15(py, delaySize, &readIndex, 1, + pb, pb, blockSize, 1, blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pScratchOut = pScr2; + + /* Loop over the blockSize. Unroll by a factor of 4. + * Compute 4 MACS at a time. */ + blkCnt = blockSize >> 2; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + *pScratchOut++ += (q31_t) * px++ * coeff; + *pScratchOut++ += (q31_t) * px++ * coeff; + *pScratchOut++ += (q31_t) * px++ * coeff; + *pScratchOut++ += (q31_t) * px++ * coeff; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, + * compute the remaining samples */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + *pScratchOut++ += (q31_t) * px++ * coeff; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Decrement the tap loop counter */ + tapCnt--; + } + + /* All the output values are in pScratchOut buffer. + Convert them into 1.15 format, saturate and store in the destination buffer. */ + /* Loop over the blockSize. */ + blkCnt = blockSize >> 2; + + while(blkCnt > 0u) + { + in1 = *pScr2++; + in2 = *pScr2++; + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pOut)++ = + __PKHBT((q15_t) __SSAT(in1 >> 15, 16), (q15_t) __SSAT(in2 >> 15, 16), + 16); + +#else + *__SIMD32(pOut)++ = + __PKHBT((q15_t) __SSAT(in2 >> 15, 16), (q15_t) __SSAT(in1 >> 15, 16), + 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + in1 = *pScr2++; + + in2 = *pScr2++; + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pOut)++ = + __PKHBT((q15_t) __SSAT(in1 >> 15, 16), (q15_t) __SSAT(in2 >> 15, 16), + 16); + +#else + + *__SIMD32(pOut)++ = + __PKHBT((q15_t) __SSAT(in2 >> 15, 16), (q15_t) __SSAT(in1 >> 15, 16), + 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + + blkCnt--; + + } + + /* If the blockSize is not a multiple of 4, + remaining samples are processed in the below loop */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + *pOut++ = (q15_t) __SSAT(*pScr2++ >> 15, 16); + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* BlockSize of Input samples are copied into the state buffer */ + /* StateIndex points to the starting position to write in the state buffer */ + arm_circularWrite_q15(py, delaySize, &S->stateIndex, 1, pIn, 1, blockSize); + + /* Loop over the number of taps. */ + tapCnt = numTaps; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_q15(py, delaySize, &readIndex, 1, + pb, pb, blockSize, 1, blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pScratchOut = pScr2; + + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Perform multiplication and store in the scratch buffer */ + *pScratchOut++ = ((q31_t) * px++ * coeff); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Loop over the number of taps. */ + tapCnt = (uint32_t) numTaps - 1u; + + while(tapCnt > 0u) + { + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_q15(py, delaySize, &readIndex, 1, + pb, pb, blockSize, 1, blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pScratchOut = pScr2; + + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + *pScratchOut++ += (q31_t) * px++ * coeff; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Decrement the tap loop counter */ + tapCnt--; + } + + /* All the output values are in pScratchOut buffer. + Convert them into 1.15 format, saturate and store in the destination buffer. */ + /* Loop over the blockSize. */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + *pOut++ = (q15_t) __SSAT(*pScr2++ >> 15, 16); + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR_Sparse group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q31.c index 82808ecb0..5bbd110cf 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q31.c @@ -1,367 +1,367 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_q31.c -* -* Description: Q31 sparse FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ -#include "arm_math.h" - - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Processing function for the Q31 sparse FIR filter. - * @param[in] *S points to an instance of the Q31 sparse FIR structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] *pScratchIn points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The 1.31 x 1.31 multiplications are truncated to 2.30 format. - * This leads to loss of precision on the intermediate multiplications and provides only a single guard bit. - * If the accumulator result overflows, it wraps around rather than saturate. - * In order to avoid overflows the input signal or coefficients must be scaled down by log2(numTaps) bits. - */ - -void arm_fir_sparse_q31( - arm_fir_sparse_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - q31_t * pScratchIn, - uint32_t blockSize) -{ - - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *px; /* Scratch buffer pointer */ - q31_t *py = pState; /* Temporary pointers for state buffer */ - q31_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ - q31_t *pOut; /* Destination pointer */ - q63_t out; /* Temporary output variable */ - int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ - uint32_t delaySize = S->maxDelay + blockSize; /* state length */ - uint16_t numTaps = S->numTaps; /* Filter order */ - int32_t readIndex; /* Read index of the state buffer */ - uint32_t tapCnt, blkCnt; /* loop counters */ - q31_t coeff = *pCoeffs++; /* Read the first coefficient value */ - q31_t in; - - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_f32((int32_t *) py, delaySize, &S->stateIndex, 1, - (int32_t *) pSrc, 1, blockSize); - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pOut = pDst; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 Multiplications at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in the destination buffer */ - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in the destination buffer */ - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pOut = pDst; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 MACS at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* Working output pointer is updated */ - pOut = pDst; - - /* Output is converted into 1.31 format. */ - /* Loop over the blockSize. Unroll by a factor of 4. - * process 4 output samples at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - in = *pOut << 1; - *pOut++ = in; - in = *pOut << 1; - *pOut++ = in; - in = *pOut << 1; - *pOut++ = in; - in = *pOut << 1; - *pOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * process the remaining output samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - in = *pOut << 1; - *pOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in the destination buffer */ - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pOut = pDst; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* Working output pointer is updated */ - pOut = pDst; - - /* Output is converted into 1.31 format. */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - in = *pOut << 1; - *pOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Sparse group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_sparse_q31.c +* +* Description: Q31 sparse FIR filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ------------------------------------------------------------------- */ +#include "arm_math.h" + + +/** + * @addtogroup FIR_Sparse + * @{ + */ + +/** + * @brief Processing function for the Q31 sparse FIR filter. + * @param[in] *S points to an instance of the Q31 sparse FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] *pScratchIn points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 32-bit accumulator. + * The 1.31 x 1.31 multiplications are truncated to 2.30 format. + * This leads to loss of precision on the intermediate multiplications and provides only a single guard bit. + * If the accumulator result overflows, it wraps around rather than saturate. + * In order to avoid overflows the input signal or coefficients must be scaled down by log2(numTaps) bits. + */ + +void arm_fir_sparse_q31( + arm_fir_sparse_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + q31_t * pScratchIn, + uint32_t blockSize) +{ + + q31_t *pState = S->pState; /* State pointer */ + q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *px; /* Scratch buffer pointer */ + q31_t *py = pState; /* Temporary pointers for state buffer */ + q31_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ + q31_t *pOut; /* Destination pointer */ + q63_t out; /* Temporary output variable */ + int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ + uint32_t delaySize = S->maxDelay + blockSize; /* state length */ + uint16_t numTaps = S->numTaps; /* Filter order */ + int32_t readIndex; /* Read index of the state buffer */ + uint32_t tapCnt, blkCnt; /* loop counters */ + q31_t coeff = *pCoeffs++; /* Read the first coefficient value */ + q31_t in; + + + /* BlockSize of Input samples are copied into the state buffer */ + /* StateIndex points to the starting position to write in the state buffer */ + arm_circularWrite_f32((int32_t *) py, delaySize, &S->stateIndex, 1, + (int32_t *) pSrc, 1, blockSize); + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, + (int32_t *) pb, (int32_t *) pb, blockSize, 1, + blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pOut = pDst; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Loop over the blockSize. Unroll by a factor of 4. + * Compute 4 Multiplications at a time. */ + blkCnt = blockSize >> 2; + + while(blkCnt > 0u) + { + /* Perform Multiplications and store in the destination buffer */ + *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); + *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); + *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); + *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, + * compute the remaining samples */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* Perform Multiplications and store in the destination buffer */ + *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Loop over the number of taps. */ + tapCnt = (uint32_t) numTaps - 1u; + + while(tapCnt > 0u) + { + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, + (int32_t *) pb, (int32_t *) pb, blockSize, 1, + blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pOut = pDst; + + /* Loop over the blockSize. Unroll by a factor of 4. + * Compute 4 MACS at a time. */ + blkCnt = blockSize >> 2; + + while(blkCnt > 0u) + { + out = *pOut; + out += ((q63_t) * px++ * coeff) >> 32; + *pOut++ = (q31_t) (out); + + out = *pOut; + out += ((q63_t) * px++ * coeff) >> 32; + *pOut++ = (q31_t) (out); + + out = *pOut; + out += ((q63_t) * px++ * coeff) >> 32; + *pOut++ = (q31_t) (out); + + out = *pOut; + out += ((q63_t) * px++ * coeff) >> 32; + *pOut++ = (q31_t) (out); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, + * compute the remaining samples */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + out = *pOut; + out += ((q63_t) * px++ * coeff) >> 32; + *pOut++ = (q31_t) (out); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Decrement the tap loop counter */ + tapCnt--; + } + + /* Working output pointer is updated */ + pOut = pDst; + + /* Output is converted into 1.31 format. */ + /* Loop over the blockSize. Unroll by a factor of 4. + * process 4 output samples at a time. */ + blkCnt = blockSize >> 2; + + while(blkCnt > 0u) + { + in = *pOut << 1; + *pOut++ = in; + in = *pOut << 1; + *pOut++ = in; + in = *pOut << 1; + *pOut++ = in; + in = *pOut << 1; + *pOut++ = in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, + * process the remaining output samples */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + in = *pOut << 1; + *pOut++ = in; + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Perform Multiplications and store in the destination buffer */ + *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Loop over the number of taps. */ + tapCnt = (uint32_t) numTaps - 1u; + + while(tapCnt > 0u) + { + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, + (int32_t *) pb, (int32_t *) pb, blockSize, 1, + blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pOut = pDst; + + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + out = *pOut; + out += ((q63_t) * px++ * coeff) >> 32; + *pOut++ = (q31_t) (out); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Decrement the tap loop counter */ + tapCnt--; + } + + /* Working output pointer is updated */ + pOut = pDst; + + /* Output is converted into 1.31 format. */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + in = *pOut << 1; + *pOut++ = in; + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR_Sparse group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q7.c index a7dbdb60b..bcba31a74 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q7.c @@ -1,395 +1,395 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_q7.c -* -* Description: Q7 sparse FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ -#include "arm_math.h" - - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - - -/** - * @brief Processing function for the Q7 sparse FIR filter. - * @param[in] *S points to an instance of the Q7 sparse FIR structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] *pScratchIn points to a temporary buffer of size blockSize. - * @param[in] *pScratchOut points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 32-bit internal accumulator. - * Both coefficients and state variables are represented in 1.7 format and multiplications yield a 2.14 result. - * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * The accumulator is then converted to 18.7 format by discarding the low 7 bits. - * Finally, the result is truncated to 1.7 format. - */ - -void arm_fir_sparse_q7( - arm_fir_sparse_instance_q7 * S, - q7_t * pSrc, - q7_t * pDst, - q7_t * pScratchIn, - q31_t * pScratchOut, - uint32_t blockSize) -{ - - q7_t *pState = S->pState; /* State pointer */ - q7_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q7_t *px; /* Scratch buffer pointer */ - q7_t *py = pState; /* Temporary pointers for state buffer */ - q7_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ - q7_t *pOut = pDst; /* Destination pointer */ - int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ - uint32_t delaySize = S->maxDelay + blockSize; /* state length */ - uint16_t numTaps = S->numTaps; /* Filter order */ - int32_t readIndex; /* Read index of the state buffer */ - uint32_t tapCnt, blkCnt; /* loop counters */ - q7_t coeff = *pCoeffs++; /* Read the coefficient value */ - q31_t *pScr2 = pScratchOut; /* Working pointer for scratch buffer of output values */ - q31_t in; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t in1, in2, in3, in4; - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_q7(py, (int32_t) delaySize, &S->stateIndex, 1, pSrc, 1, - blockSize); - - /* Loop over the number of taps. */ - tapCnt = numTaps; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, - (int32_t) blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 multiplications at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, - (int32_t) blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 MACS at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* All the output values are in pScratchOut buffer. - Convert them into 1.15 format, saturate and store in the destination buffer. */ - /* Loop over the blockSize. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - in1 = (q7_t) __SSAT(*pScr2++ >> 7, 8); - in2 = (q7_t) __SSAT(*pScr2++ >> 7, 8); - in3 = (q7_t) __SSAT(*pScr2++ >> 7, 8); - in4 = (q7_t) __SSAT(*pScr2++ >> 7, 8); - - *__SIMD32(pOut)++ = __PACKq7(in1, in2, in3, in4); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - remaining samples are processed in the below loop */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - *pOut++ = (q7_t) __SSAT(*pScr2++ >> 7, 8); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_q7(py, (int32_t) delaySize, &S->stateIndex, 1, pSrc, 1, - blockSize); - - /* Loop over the number of taps. */ - tapCnt = numTaps; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, - (int32_t) blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, - (int32_t) blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = - ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* All the output values are in pScratchOut buffer. - Convert them into 1.15 format, saturate and store in the destination buffer. */ - /* Loop over the blockSize. */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - *pOut++ = (q7_t) __SSAT(*pScr2++ >> 7, 8); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Sparse group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fir_sparse_q7.c +* +* Description: Q7 sparse FIR filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ------------------------------------------------------------------- */ +#include "arm_math.h" + + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup FIR_Sparse + * @{ + */ + + +/** + * @brief Processing function for the Q7 sparse FIR filter. + * @param[in] *S points to an instance of the Q7 sparse FIR structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data + * @param[in] *pScratchIn points to a temporary buffer of size blockSize. + * @param[in] *pScratchOut points to a temporary buffer of size blockSize. + * @param[in] blockSize number of input samples to process per call. + * @return none. + * + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 32-bit internal accumulator. + * Both coefficients and state variables are represented in 1.7 format and multiplications yield a 2.14 result. + * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. + * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + * The accumulator is then converted to 18.7 format by discarding the low 7 bits. + * Finally, the result is truncated to 1.7 format. + */ + +void arm_fir_sparse_q7( + arm_fir_sparse_instance_q7 * S, + q7_t * pSrc, + q7_t * pDst, + q7_t * pScratchIn, + q31_t * pScratchOut, + uint32_t blockSize) +{ + + q7_t *pState = S->pState; /* State pointer */ + q7_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q7_t *px; /* Scratch buffer pointer */ + q7_t *py = pState; /* Temporary pointers for state buffer */ + q7_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ + q7_t *pOut = pDst; /* Destination pointer */ + int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ + uint32_t delaySize = S->maxDelay + blockSize; /* state length */ + uint16_t numTaps = S->numTaps; /* Filter order */ + int32_t readIndex; /* Read index of the state buffer */ + uint32_t tapCnt, blkCnt; /* loop counters */ + q7_t coeff = *pCoeffs++; /* Read the coefficient value */ + q31_t *pScr2 = pScratchOut; /* Working pointer for scratch buffer of output values */ + q31_t in; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q7_t in1, in2, in3, in4; + + /* BlockSize of Input samples are copied into the state buffer */ + /* StateIndex points to the starting position to write in the state buffer */ + arm_circularWrite_q7(py, (int32_t) delaySize, &S->stateIndex, 1, pSrc, 1, + blockSize); + + /* Loop over the number of taps. */ + tapCnt = numTaps; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, + (int32_t) blockSize, 1, blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pScratchOut = pScr2; + + /* Loop over the blockSize. Unroll by a factor of 4. + * Compute 4 multiplications at a time. */ + blkCnt = blockSize >> 2; + + while(blkCnt > 0u) + { + /* Perform multiplication and store in the scratch buffer */ + *pScratchOut++ = ((q31_t) * px++ * coeff); + *pScratchOut++ = ((q31_t) * px++ * coeff); + *pScratchOut++ = ((q31_t) * px++ * coeff); + *pScratchOut++ = ((q31_t) * px++ * coeff); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, + * compute the remaining samples */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* Perform multiplication and store in the scratch buffer */ + *pScratchOut++ = ((q31_t) * px++ * coeff); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Loop over the number of taps. */ + tapCnt = (uint32_t) numTaps - 1u; + + while(tapCnt > 0u) + { + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, + (int32_t) blockSize, 1, blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pScratchOut = pScr2; + + /* Loop over the blockSize. Unroll by a factor of 4. + * Compute 4 MACS at a time. */ + blkCnt = blockSize >> 2; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + in = *pScratchOut + ((q31_t) * px++ * coeff); + *pScratchOut++ = in; + in = *pScratchOut + ((q31_t) * px++ * coeff); + *pScratchOut++ = in; + in = *pScratchOut + ((q31_t) * px++ * coeff); + *pScratchOut++ = in; + in = *pScratchOut + ((q31_t) * px++ * coeff); + *pScratchOut++ = in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, + * compute the remaining samples */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + in = *pScratchOut + ((q31_t) * px++ * coeff); + *pScratchOut++ = in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = ((int32_t) S->stateIndex - + (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Decrement the tap loop counter */ + tapCnt--; + } + + /* All the output values are in pScratchOut buffer. + Convert them into 1.15 format, saturate and store in the destination buffer. */ + /* Loop over the blockSize. */ + blkCnt = blockSize >> 2; + + while(blkCnt > 0u) + { + in1 = (q7_t) __SSAT(*pScr2++ >> 7, 8); + in2 = (q7_t) __SSAT(*pScr2++ >> 7, 8); + in3 = (q7_t) __SSAT(*pScr2++ >> 7, 8); + in4 = (q7_t) __SSAT(*pScr2++ >> 7, 8); + + *__SIMD32(pOut)++ = __PACKq7(in1, in2, in3, in4); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, + remaining samples are processed in the below loop */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + *pOut++ = (q7_t) __SSAT(*pScr2++ >> 7, 8); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* BlockSize of Input samples are copied into the state buffer */ + /* StateIndex points to the starting position to write in the state buffer */ + arm_circularWrite_q7(py, (int32_t) delaySize, &S->stateIndex, 1, pSrc, 1, + blockSize); + + /* Loop over the number of taps. */ + tapCnt = numTaps; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, + (int32_t) blockSize, 1, blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pScratchOut = pScr2; + + /* Loop over the blockSize */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Perform multiplication and store in the scratch buffer */ + *pScratchOut++ = ((q31_t) * px++ * coeff); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Loop over the number of taps. */ + tapCnt = (uint32_t) numTaps - 1u; + + while(tapCnt > 0u) + { + /* Working pointer for state buffer is updated */ + py = pState; + + /* blockSize samples are read from the state buffer */ + arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, + (int32_t) blockSize, 1, blockSize); + + /* Working pointer for the scratch buffer of state values */ + px = pb; + + /* Working pointer for scratch buffer of output values */ + pScratchOut = pScr2; + + /* Loop over the blockSize */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Perform Multiply-Accumulate */ + in = *pScratchOut + ((q31_t) * px++ * coeff); + *pScratchOut++ = in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Load the coefficient value and + * increment the coefficient buffer for the next set of state values */ + coeff = *pCoeffs++; + + /* Read Index, from where the state buffer should be read, is calculated. */ + readIndex = + ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; + + /* Wraparound of readIndex */ + if(readIndex < 0) + { + readIndex += (int32_t) delaySize; + } + + /* Decrement the tap loop counter */ + tapCnt--; + } + + /* All the output values are in pScratchOut buffer. + Convert them into 1.15 format, saturate and store in the destination buffer. */ + /* Loop over the blockSize. */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + *pOut++ = (q7_t) __SSAT(*pScr2++ >> 7, 8); + + /* Decrement the blockSize loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of FIR_Sparse group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_f32.c index c140c0e73..6185ccdc2 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_f32.c @@ -1,402 +1,402 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_f32.c -* -* Description: Floating-point IIR Lattice filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup IIR_Lattice Infinite Impulse Response (IIR) Lattice Filters - * - * This set of functions implements lattice filters - * for Q15, Q31 and floating-point data types. Lattice filters are used in a - * variety of adaptive filter applications. The filter structure has feedforward and - * feedback components and the net impulse response is infinite length. - * The functions operate on blocks - * of input and output data and each call to the function processes - * blockSize samples through the filter. pSrc and - * pDst point to input and output arrays containing blockSize values. - - * \par Algorithm: - * \image html IIRLattice.gif "Infinite Impulse Response Lattice filter" - *
   
- *    fN(n)   =  x(n)   
- *    fm-1(n) = fm(n) - km * gm-1(n-1)   for m = N, N-1, ...1   
- *    gm(n)   = km * fm-1(n) + gm-1(n-1) for m = N, N-1, ...1   
- *    y(n)    = vN * gN(n) + vN-1 * gN-1(n) + ...+ v0 * g0(n)   
- * 
- * \par - * pkCoeffs points to array of reflection coefficients of size numStages. - * Reflection coefficients are stored in time-reversed order. - * \par - *
   
- *    {kN, kN-1, ....k1}   
- * 
- * pvCoeffs points to the array of ladder coefficients of size (numStages+1). - * Ladder coefficients are stored in time-reversed order. - * \par - *
   
- *    {vN, vN-1, ...v0}   
- * 
- * pState points to a state array of size numStages + blockSize. - * The state variables shown in the figure above (the g values) are stored in the pState array. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros and then manually initialize the instance structure as follows: - *
   
- *arm_iir_lattice_instance_f32 S = {numStages, pState, pkCoeffs, pvCoeffs};   
- *arm_iir_lattice_instance_q31 S = {numStages, pState, pkCoeffs, pvCoeffs};   
- *arm_iir_lattice_instance_q15 S = {numStages, pState, pkCoeffs, pvCoeffs};   
- * 
- * \par - * where numStages is the number of stages in the filter; pState points to the state buffer array; - * pkCoeffs points to array of the reflection coefficients; pvCoeffs points to the array of ladder coefficients. - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the IIR lattice filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - -/** - * @brief Processing function for the floating-point IIR lattice filter. - * @param[in] *S points to an instance of the floating-point IIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_iir_lattice_f32( - const arm_iir_lattice_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t fcurr, fnext = 0, gcurr, gnext; /* Temporary variables for lattice stages */ - float32_t acc; /* Accumlator */ - uint32_t blkCnt, tapCnt; /* temporary variables for counts */ - float32_t *px1, *px2, *pk, *pv; /* temporary pointers for state and coef */ - uint32_t numStages = S->numStages; /* number of stages */ - float32_t *pState; /* State pointer */ - float32_t *pStateCurnt; /* State current pointer */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - gcurr = 0.0f; - blkCnt = blockSize; - - pState = &S->pState[0]; - - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0.0f; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - - /* Process sample for first tap */ - gcurr = *px1++; - /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ - fnext = fcurr - ((*pk) * gcurr); - /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ - gnext = (fnext * (*pk++)) + gcurr; - /* write gN(n) into state for next sample processing */ - *px2++ = gnext; - /* y(n) += gN(n) * vN */ - acc += (gnext * (*pv++)); - - /* Update f values for next coefficient processing */ - fcurr = fnext; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = (numStages - 1u) >> 2; - - while(tapCnt > 0u) - { - /* Process sample for 2nd, 6th ...taps */ - /* Read gN-2(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 2nd, 6th .. taps */ - /* fN-2(n) = fN-1(n) - kN-1 * gN-2(n-1) */ - fnext = fcurr - ((*pk) * gcurr); - /* gN-1(n) = kN-1 * fN-2(n) + gN-2(n-1) */ - gnext = (fnext * (*pk++)) + gcurr; - /* y(n) += gN-1(n) * vN-1 */ - /* process for gN-5(n) * vN-5, gN-9(n) * vN-9 ... */ - acc += (gnext * (*pv++)); - /* write gN-1(n) into state for next sample processing */ - *px2++ = gnext; - - - /* Process sample for 3nd, 7th ...taps */ - /* Read gN-3(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 3rd, 7th .. taps */ - /* fN-3(n) = fN-2(n) - kN-2 * gN-3(n-1) */ - fcurr = fnext - ((*pk) * gcurr); - /* gN-2(n) = kN-2 * fN-3(n) + gN-3(n-1) */ - gnext = (fcurr * (*pk++)) + gcurr; - /* y(n) += gN-2(n) * vN-2 */ - /* process for gN-6(n) * vN-6, gN-10(n) * vN-10 ... */ - acc += (gnext * (*pv++)); - /* write gN-2(n) into state for next sample processing */ - *px2++ = gnext; - - - /* Process sample for 4th, 8th ...taps */ - /* Read gN-4(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 4th, 8th .. taps */ - /* fN-4(n) = fN-3(n) - kN-3 * gN-4(n-1) */ - fnext = fcurr - ((*pk) * gcurr); - /* gN-3(n) = kN-3 * fN-4(n) + gN-4(n-1) */ - gnext = (fnext * (*pk++)) + gcurr; - /* y(n) += gN-3(n) * vN-3 */ - /* process for gN-7(n) * vN-7, gN-11(n) * vN-11 ... */ - acc += (gnext * (*pv++)); - /* write gN-3(n) into state for next sample processing */ - *px2++ = gnext; - - - /* Process sample for 5th, 9th ...taps */ - /* Read gN-5(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 5th, 9th .. taps */ - /* fN-5(n) = fN-4(n) - kN-4 * gN-1(n-1) */ - fcurr = fnext - ((*pk) * gcurr); - /* gN-4(n) = kN-4 * fN-5(n) + gN-5(n-1) */ - gnext = (fcurr * (*pk++)) + gcurr; - /* y(n) += gN-4(n) * vN-4 */ - /* process for gN-8(n) * vN-8, gN-12(n) * vN-12 ... */ - acc += (gnext * (*pv++)); - /* write gN-4(n) into state for next sample processing */ - *px2++ = gnext; - - tapCnt--; - - } - - fnext = fcurr; - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = (numStages - 1u) % 0x4u; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample for last taps */ - fnext = fcurr - ((*pk) * gcurr); - gnext = (fnext * (*pk++)) + gcurr; - /* Output samples for last taps */ - acc += (gnext * (*pv++)); - *px2++ = gnext; - fcurr = fnext; - - tapCnt--; - - } - - - /* y(n) += g0(n) * v0 */ - acc += (fnext * (*pv)); - - *px2++ = fnext; - - /* write out into pDst */ - *pDst++ = acc; - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - tapCnt = numStages >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - - } - - /* Calculate remaining number of copies */ - tapCnt = (numStages) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - blkCnt = blockSize; - - pState = &S->pState[0]; - - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0.0f; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - - /* Process sample for numStages */ - tapCnt = numStages; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample for last taps */ - fnext = fcurr - ((*pk) * gcurr); - gnext = (fnext * (*pk++)) + gcurr; - - /* Output samples for last taps */ - acc += (gnext * (*pv++)); - *px2++ = gnext; - fcurr = fnext; - - /* Decrementing loop counter */ - tapCnt--; - - } - - /* y(n) += g0(n) * v0 */ - acc += (fnext * (*pv)); - - *px2++ = fnext; - - /* write out into pDst */ - *pDst++ = acc; - - /* Advance the state pointer by 1 to process the next group of samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - tapCnt = numStages; - - /* Copy the data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - - - -/** - * @} end of IIR_Lattice group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_iir_lattice_f32.c +* +* Description: Floating-point IIR Lattice filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup IIR_Lattice Infinite Impulse Response (IIR) Lattice Filters + * + * This set of functions implements lattice filters + * for Q15, Q31 and floating-point data types. Lattice filters are used in a + * variety of adaptive filter applications. The filter structure has feedforward and + * feedback components and the net impulse response is infinite length. + * The functions operate on blocks + * of input and output data and each call to the function processes + * blockSize samples through the filter. pSrc and + * pDst point to input and output arrays containing blockSize values. + + * \par Algorithm: + * \image html IIRLattice.gif "Infinite Impulse Response Lattice filter" + *
   
+ *    fN(n)   =  x(n)   
+ *    fm-1(n) = fm(n) - km * gm-1(n-1)   for m = N, N-1, ...1   
+ *    gm(n)   = km * fm-1(n) + gm-1(n-1) for m = N, N-1, ...1   
+ *    y(n)    = vN * gN(n) + vN-1 * gN-1(n) + ...+ v0 * g0(n)   
+ * 
+ * \par + * pkCoeffs points to array of reflection coefficients of size numStages. + * Reflection coefficients are stored in time-reversed order. + * \par + *
   
+ *    {kN, kN-1, ....k1}   
+ * 
+ * pvCoeffs points to the array of ladder coefficients of size (numStages+1). + * Ladder coefficients are stored in time-reversed order. + * \par + *
   
+ *    {vN, vN-1, ...v0}   
+ * 
+ * pState points to a state array of size numStages + blockSize. + * The state variables shown in the figure above (the g values) are stored in the pState array. + * The state variables are updated after each block of data is processed; the coefficients are untouched. + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter. + * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Set the values in the state buffer to zeros and then manually initialize the instance structure as follows: + *
   
+ *arm_iir_lattice_instance_f32 S = {numStages, pState, pkCoeffs, pvCoeffs};   
+ *arm_iir_lattice_instance_q31 S = {numStages, pState, pkCoeffs, pvCoeffs};   
+ *arm_iir_lattice_instance_q15 S = {numStages, pState, pkCoeffs, pvCoeffs};   
+ * 
+ * \par + * where numStages is the number of stages in the filter; pState points to the state buffer array; + * pkCoeffs points to array of the reflection coefficients; pvCoeffs points to the array of ladder coefficients. + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the IIR lattice filter functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + +/** + * @addtogroup IIR_Lattice + * @{ + */ + +/** + * @brief Processing function for the floating-point IIR lattice filter. + * @param[in] *S points to an instance of the floating-point IIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + +void arm_iir_lattice_f32( + const arm_iir_lattice_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + float32_t fcurr, fnext = 0, gcurr, gnext; /* Temporary variables for lattice stages */ + float32_t acc; /* Accumlator */ + uint32_t blkCnt, tapCnt; /* temporary variables for counts */ + float32_t *px1, *px2, *pk, *pv; /* temporary pointers for state and coef */ + uint32_t numStages = S->numStages; /* number of stages */ + float32_t *pState; /* State pointer */ + float32_t *pStateCurnt; /* State current pointer */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + gcurr = 0.0f; + blkCnt = blockSize; + + pState = &S->pState[0]; + + /* Sample processing */ + while(blkCnt > 0u) + { + /* Read Sample from input buffer */ + /* fN(n) = x(n) */ + fcurr = *pSrc++; + + /* Initialize state read pointer */ + px1 = pState; + /* Initialize state write pointer */ + px2 = pState; + /* Set accumulator to zero */ + acc = 0.0f; + /* Initialize Ladder coeff pointer */ + pv = &S->pvCoeffs[0]; + /* Initialize Reflection coeff pointer */ + pk = &S->pkCoeffs[0]; + + + /* Process sample for first tap */ + gcurr = *px1++; + /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ + fnext = fcurr - ((*pk) * gcurr); + /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ + gnext = (fnext * (*pk++)) + gcurr; + /* write gN(n) into state for next sample processing */ + *px2++ = gnext; + /* y(n) += gN(n) * vN */ + acc += (gnext * (*pv++)); + + /* Update f values for next coefficient processing */ + fcurr = fnext; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = (numStages - 1u) >> 2; + + while(tapCnt > 0u) + { + /* Process sample for 2nd, 6th ...taps */ + /* Read gN-2(n-1) from state buffer */ + gcurr = *px1++; + /* Process sample for 2nd, 6th .. taps */ + /* fN-2(n) = fN-1(n) - kN-1 * gN-2(n-1) */ + fnext = fcurr - ((*pk) * gcurr); + /* gN-1(n) = kN-1 * fN-2(n) + gN-2(n-1) */ + gnext = (fnext * (*pk++)) + gcurr; + /* y(n) += gN-1(n) * vN-1 */ + /* process for gN-5(n) * vN-5, gN-9(n) * vN-9 ... */ + acc += (gnext * (*pv++)); + /* write gN-1(n) into state for next sample processing */ + *px2++ = gnext; + + + /* Process sample for 3nd, 7th ...taps */ + /* Read gN-3(n-1) from state buffer */ + gcurr = *px1++; + /* Process sample for 3rd, 7th .. taps */ + /* fN-3(n) = fN-2(n) - kN-2 * gN-3(n-1) */ + fcurr = fnext - ((*pk) * gcurr); + /* gN-2(n) = kN-2 * fN-3(n) + gN-3(n-1) */ + gnext = (fcurr * (*pk++)) + gcurr; + /* y(n) += gN-2(n) * vN-2 */ + /* process for gN-6(n) * vN-6, gN-10(n) * vN-10 ... */ + acc += (gnext * (*pv++)); + /* write gN-2(n) into state for next sample processing */ + *px2++ = gnext; + + + /* Process sample for 4th, 8th ...taps */ + /* Read gN-4(n-1) from state buffer */ + gcurr = *px1++; + /* Process sample for 4th, 8th .. taps */ + /* fN-4(n) = fN-3(n) - kN-3 * gN-4(n-1) */ + fnext = fcurr - ((*pk) * gcurr); + /* gN-3(n) = kN-3 * fN-4(n) + gN-4(n-1) */ + gnext = (fnext * (*pk++)) + gcurr; + /* y(n) += gN-3(n) * vN-3 */ + /* process for gN-7(n) * vN-7, gN-11(n) * vN-11 ... */ + acc += (gnext * (*pv++)); + /* write gN-3(n) into state for next sample processing */ + *px2++ = gnext; + + + /* Process sample for 5th, 9th ...taps */ + /* Read gN-5(n-1) from state buffer */ + gcurr = *px1++; + /* Process sample for 5th, 9th .. taps */ + /* fN-5(n) = fN-4(n) - kN-4 * gN-1(n-1) */ + fcurr = fnext - ((*pk) * gcurr); + /* gN-4(n) = kN-4 * fN-5(n) + gN-5(n-1) */ + gnext = (fcurr * (*pk++)) + gcurr; + /* y(n) += gN-4(n) * vN-4 */ + /* process for gN-8(n) * vN-8, gN-12(n) * vN-12 ... */ + acc += (gnext * (*pv++)); + /* write gN-4(n) into state for next sample processing */ + *px2++ = gnext; + + tapCnt--; + + } + + fnext = fcurr; + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = (numStages - 1u) % 0x4u; + + while(tapCnt > 0u) + { + gcurr = *px1++; + /* Process sample for last taps */ + fnext = fcurr - ((*pk) * gcurr); + gnext = (fnext * (*pk++)) + gcurr; + /* Output samples for last taps */ + acc += (gnext * (*pv++)); + *px2++ = gnext; + fcurr = fnext; + + tapCnt--; + + } + + + /* y(n) += g0(n) * v0 */ + acc += (fnext * (*pv)); + + *px2++ = fnext; + + /* write out into pDst */ + *pDst++ = acc; + + /* Advance the state pointer by 4 to process the next group of 4 samples */ + pState = pState + 1u; + blkCnt--; + + } + + /* Processing is complete. Now copy last S->numStages samples to start of the buffer + for the preperation of next frame process */ + + /* Points to the start of the state buffer */ + pStateCurnt = &S->pState[0]; + pState = &S->pState[blockSize]; + + tapCnt = numStages >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + + } + + /* Calculate remaining number of copies */ + tapCnt = (numStages) % 0x4u; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + blkCnt = blockSize; + + pState = &S->pState[0]; + + /* Sample processing */ + while(blkCnt > 0u) + { + /* Read Sample from input buffer */ + /* fN(n) = x(n) */ + fcurr = *pSrc++; + + /* Initialize state read pointer */ + px1 = pState; + /* Initialize state write pointer */ + px2 = pState; + /* Set accumulator to zero */ + acc = 0.0f; + /* Initialize Ladder coeff pointer */ + pv = &S->pvCoeffs[0]; + /* Initialize Reflection coeff pointer */ + pk = &S->pkCoeffs[0]; + + + /* Process sample for numStages */ + tapCnt = numStages; + + while(tapCnt > 0u) + { + gcurr = *px1++; + /* Process sample for last taps */ + fnext = fcurr - ((*pk) * gcurr); + gnext = (fnext * (*pk++)) + gcurr; + + /* Output samples for last taps */ + acc += (gnext * (*pv++)); + *px2++ = gnext; + fcurr = fnext; + + /* Decrementing loop counter */ + tapCnt--; + + } + + /* y(n) += g0(n) * v0 */ + acc += (fnext * (*pv)); + + *px2++ = fnext; + + /* write out into pDst */ + *pDst++ = acc; + + /* Advance the state pointer by 1 to process the next group of samples */ + pState = pState + 1u; + blkCnt--; + + } + + /* Processing is complete. Now copy last S->numStages samples to start of the buffer + for the preperation of next frame process */ + + /* Points to the start of the state buffer */ + pStateCurnt = &S->pState[0]; + pState = &S->pState[blockSize]; + + tapCnt = numStages; + + /* Copy the data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + + + +/** + * @} end of IIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_f32.c index 5c78fc134..07f58b991 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_f32.c @@ -1,83 +1,83 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_init_f32.c -* -* Description: Floating-point IIR lattice filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - -/** - * @brief Initialization function for the floating-point IIR lattice filter. - * @param[in] *S points to an instance of the floating-point IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. - * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. - * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_iir_lattice_init_f32( - arm_iir_lattice_instance_f32 * S, - uint16_t numStages, - float32_t * pkCoeffs, - float32_t * pvCoeffs, - float32_t * pState, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign reflection coefficient pointer */ - S->pkCoeffs = pkCoeffs; - - /* Assign ladder coefficient pointer */ - S->pvCoeffs = pvCoeffs; - - /* Clear state buffer and size is always blockSize + numStages */ - memset(pState, 0, (numStages + blockSize) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - - -} - - /** - * @} end of IIR_Lattice group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_iir_lattice_init_f32.c +* +* Description: Floating-point IIR lattice filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup IIR_Lattice + * @{ + */ + +/** + * @brief Initialization function for the floating-point IIR lattice filter. + * @param[in] *S points to an instance of the floating-point IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. + * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. + * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize. + * @param[in] blockSize number of samples to process. + * @return none. + */ + +void arm_iir_lattice_init_f32( + arm_iir_lattice_instance_f32 * S, + uint16_t numStages, + float32_t * pkCoeffs, + float32_t * pvCoeffs, + float32_t * pState, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numStages = numStages; + + /* Assign reflection coefficient pointer */ + S->pkCoeffs = pkCoeffs; + + /* Assign ladder coefficient pointer */ + S->pvCoeffs = pvCoeffs; + + /* Clear state buffer and size is always blockSize + numStages */ + memset(pState, 0, (numStages + blockSize) * sizeof(float32_t)); + + /* Assign state pointer */ + S->pState = pState; + + +} + + /** + * @} end of IIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q15.c index da4068cbe..d346a93fc 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q15.c @@ -1,83 +1,83 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_init_q15.c -* -* Description: Q15 IIR lattice filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - - /** - * @brief Initialization function for the Q15 IIR lattice filter. - * @param[in] *S points to an instance of the Q15 IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] *pkCoeffs points to reflection coefficient buffer. The array is of length numStages. - * @param[in] *pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1. - * @param[in] *pState points to state buffer. The array is of length numStages+blockSize. - * @param[in] blockSize number of samples to process per call. - * @return none. - */ - -void arm_iir_lattice_init_q15( - arm_iir_lattice_instance_q15 * S, - uint16_t numStages, - q15_t * pkCoeffs, - q15_t * pvCoeffs, - q15_t * pState, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign reflection coefficient pointer */ - S->pkCoeffs = pkCoeffs; - - /* Assign ladder coefficient pointer */ - S->pvCoeffs = pvCoeffs; - - /* Clear state buffer and size is always blockSize + numStages */ - memset(pState, 0, (numStages + blockSize) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - -} - -/** - * @} end of IIR_Lattice group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_iir_lattice_init_q15.c +* +* Description: Q15 IIR lattice filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup IIR_Lattice + * @{ + */ + + /** + * @brief Initialization function for the Q15 IIR lattice filter. + * @param[in] *S points to an instance of the Q15 IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] *pkCoeffs points to reflection coefficient buffer. The array is of length numStages. + * @param[in] *pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1. + * @param[in] *pState points to state buffer. The array is of length numStages+blockSize. + * @param[in] blockSize number of samples to process per call. + * @return none. + */ + +void arm_iir_lattice_init_q15( + arm_iir_lattice_instance_q15 * S, + uint16_t numStages, + q15_t * pkCoeffs, + q15_t * pvCoeffs, + q15_t * pState, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numStages = numStages; + + /* Assign reflection coefficient pointer */ + S->pkCoeffs = pkCoeffs; + + /* Assign ladder coefficient pointer */ + S->pvCoeffs = pvCoeffs; + + /* Clear state buffer and size is always blockSize + numStages */ + memset(pState, 0, (numStages + blockSize) * sizeof(q15_t)); + + /* Assign state pointer */ + S->pState = pState; + + +} + +/** + * @} end of IIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q31.c index 8bbc51902..d3fe2df64 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q31.c @@ -1,83 +1,83 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_init_q31.c -* -* Description: Initialization function for the Q31 IIR lattice filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - - /** - * @brief Initialization function for the Q31 IIR lattice filter. - * @param[in] *S points to an instance of the Q31 IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. - * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. - * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_iir_lattice_init_q31( - arm_iir_lattice_instance_q31 * S, - uint16_t numStages, - q31_t * pkCoeffs, - q31_t * pvCoeffs, - q31_t * pState, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign reflection coefficient pointer */ - S->pkCoeffs = pkCoeffs; - - /* Assign ladder coefficient pointer */ - S->pvCoeffs = pvCoeffs; - - /* Clear state buffer and size is always blockSize + numStages */ - memset(pState, 0, (numStages + blockSize) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - - -} - -/** - * @} end of IIR_Lattice group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_iir_lattice_init_q31.c +* +* Description: Initialization function for the Q31 IIR lattice filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup IIR_Lattice + * @{ + */ + + /** + * @brief Initialization function for the Q31 IIR lattice filter. + * @param[in] *S points to an instance of the Q31 IIR lattice structure. + * @param[in] numStages number of stages in the filter. + * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. + * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. + * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize. + * @param[in] blockSize number of samples to process. + * @return none. + */ + +void arm_iir_lattice_init_q31( + arm_iir_lattice_instance_q31 * S, + uint16_t numStages, + q31_t * pkCoeffs, + q31_t * pvCoeffs, + q31_t * pState, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numStages = numStages; + + /* Assign reflection coefficient pointer */ + S->pkCoeffs = pkCoeffs; + + /* Assign ladder coefficient pointer */ + S->pvCoeffs = pvCoeffs; + + /* Clear state buffer and size is always blockSize + numStages */ + memset(pState, 0, (numStages + blockSize) * sizeof(q31_t)); + + /* Assign state pointer */ + S->pState = pState; + + +} + +/** + * @} end of IIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q15.c index e8bbc60b0..d8233373e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q15.c @@ -1,403 +1,403 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_q15.c -* -* Description: Q15 IIR lattice filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - -/** - * @brief Processing function for the Q15 IIR lattice filter. - * @param[in] *S points to an instance of the Q15 IIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - */ - -void arm_iir_lattice_q15( - const arm_iir_lattice_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t fcurr, fnext, gcurr = 0, gnext; /* Temporary variables for lattice stages */ - q15_t gnext1, gnext2; /* Temporary variables for lattice stages */ - uint32_t stgCnt; /* Temporary variables for counts */ - q63_t acc; /* Accumlator */ - uint32_t blkCnt, tapCnt; /* Temporary variables for counts */ - q15_t *px1, *px2, *pk, *pv; /* temporary pointers for state and coef */ - uint32_t numStages = S->numStages; /* number of stages */ - q15_t *pState; /* State pointer */ - q15_t *pStateCurnt; /* State current pointer */ - q15_t out; /* Temporary variable for output */ - q31_t v; /* Temporary variable for ladder coefficient */ - - - blkCnt = blockSize; - - pState = &S->pState[0]; - - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - - /* Process sample for first tap */ - gcurr = *px1++; - /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ - fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); - fnext = __SSAT(fnext, 16); - /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ - gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; - gnext = __SSAT(gnext, 16); - /* write gN(n) into state for next sample processing */ - *px2++ = (q15_t) gnext; - /* y(n) += gN(n) * vN */ - acc += (q31_t) ((gnext * (*pv++))); - - - /* Update f values for next coefficient processing */ - fcurr = fnext; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = (numStages - 1u) >> 2; - - while(tapCnt > 0u) - { - - /* Process sample for 2nd, 6th ...taps */ - /* Read gN-2(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 2nd, 6th .. taps */ - /* fN-2(n) = fN-1(n) - kN-1 * gN-2(n-1) */ - fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); - fnext = __SSAT(fnext, 16); - /* gN-1(n) = kN-1 * fN-2(n) + gN-2(n-1) */ - gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; - gnext1 = (q15_t) __SSAT(gnext, 16); - /* write gN-1(n) into state */ - *px2++ = (q15_t) gnext1; - - - /* Process sample for 3nd, 7th ...taps */ - /* Read gN-3(n-1) from state */ - gcurr = *px1++; - /* Process sample for 3rd, 7th .. taps */ - /* fN-3(n) = fN-2(n) - kN-2 * gN-3(n-1) */ - fcurr = fnext - (((q31_t) gcurr * (*pk)) >> 15); - fcurr = __SSAT(fcurr, 16); - /* gN-2(n) = kN-2 * fN-3(n) + gN-3(n-1) */ - gnext = (((q31_t) fcurr * (*pk++)) >> 15) + gcurr; - gnext2 = (q15_t) __SSAT(gnext, 16); - /* write gN-2(n) into state */ - *px2++ = (q15_t) gnext2; - - /* Read vN-1 and vN-2 at a time */ - v = *__SIMD32(pv)++; - - - /* Pack gN-1(n) and gN-2(n) */ - -#ifndef ARM_MATH_BIG_ENDIAN - - gnext = __PKHBT(gnext1, gnext2, 16); - -#else - - gnext = __PKHBT(gnext2, gnext1, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* y(n) += gN-1(n) * vN-1 */ - /* process for gN-5(n) * vN-5, gN-9(n) * vN-9 ... */ - /* y(n) += gN-2(n) * vN-2 */ - /* process for gN-6(n) * vN-6, gN-10(n) * vN-10 ... */ - acc = __SMLALD(gnext, v, acc); - - - /* Process sample for 4th, 8th ...taps */ - /* Read gN-4(n-1) from state */ - gcurr = *px1++; - /* Process sample for 4th, 8th .. taps */ - /* fN-4(n) = fN-3(n) - kN-3 * gN-4(n-1) */ - fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); - fnext = __SSAT(fnext, 16); - /* gN-3(n) = kN-3 * fN-1(n) + gN-1(n-1) */ - gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; - gnext1 = (q15_t) __SSAT(gnext, 16); - /* write gN-3(n) for the next sample process */ - *px2++ = (q15_t) gnext1; - - - /* Process sample for 5th, 9th ...taps */ - /* Read gN-5(n-1) from state */ - gcurr = *px1++; - /* Process sample for 5th, 9th .. taps */ - /* fN-5(n) = fN-4(n) - kN-4 * gN-5(n-1) */ - fcurr = fnext - (((q31_t) gcurr * (*pk)) >> 15); - fcurr = __SSAT(fcurr, 16); - /* gN-4(n) = kN-4 * fN-5(n) + gN-5(n-1) */ - gnext = (((q31_t) fcurr * (*pk++)) >> 15) + gcurr; - gnext2 = (q15_t) __SSAT(gnext, 16); - /* write gN-4(n) for the next sample process */ - *px2++ = (q15_t) gnext2; - - /* Read vN-3 and vN-4 at a time */ - v = *__SIMD32(pv)++; - - /* Pack gN-3(n) and gN-4(n) */ -#ifndef ARM_MATH_BIG_ENDIAN - - gnext = __PKHBT(gnext1, gnext2, 16); - -#else - - gnext = __PKHBT(gnext2, gnext1, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* y(n) += gN-4(n) * vN-4 */ - /* process for gN-8(n) * vN-8, gN-12(n) * vN-12 ... */ - /* y(n) += gN-3(n) * vN-3 */ - /* process for gN-7(n) * vN-7, gN-11(n) * vN-11 ... */ - acc = __SMLALD(gnext, v, acc); - - tapCnt--; - - } - - fnext = fcurr; - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = (numStages - 1u) % 0x4u; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample for last taps */ - fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); - fnext = __SSAT(fnext, 16); - gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; - gnext = __SSAT(gnext, 16); - /* Output samples for last taps */ - acc += (q31_t) (((q31_t) gnext * (*pv++))); - *px2++ = (q15_t) gnext; - fcurr = fnext; - - tapCnt--; - } - - /* y(n) += g0(n) * v0 */ - acc += (q31_t) (((q31_t) fnext * (*pv++))); - - out = (q15_t) __SSAT(acc >> 15, 16); - *px2++ = (q15_t) fnext; - - /* write out into pDst */ - *pDst++ = out; - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - stgCnt = (numStages >> 2u); - - /* copy data */ - while(stgCnt > 0u) - { - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - /* Decrement the loop counter */ - stgCnt--; - - } - - /* Calculation of count for remaining q15_t data */ - stgCnt = (numStages) % 0x4u; - - /* copy data */ - while(stgCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - stgCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t fcurr, fnext = 0, gcurr = 0, gnext; /* Temporary variables for lattice stages */ - uint32_t stgCnt; /* Temporary variables for counts */ - q63_t acc; /* Accumlator */ - uint32_t blkCnt, tapCnt; /* Temporary variables for counts */ - q15_t *px1, *px2, *pk, *pv; /* temporary pointers for state and coef */ - uint32_t numStages = S->numStages; /* number of stages */ - q15_t *pState; /* State pointer */ - q15_t *pStateCurnt; /* State current pointer */ - q15_t out; /* Temporary variable for output */ - - - blkCnt = blockSize; - - pState = &S->pState[0]; - - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - tapCnt = numStages; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample */ - /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ - fnext = fcurr - ((gcurr * (*pk)) >> 15); - fnext = __SSAT(fnext, 16); - /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ - gnext = ((fnext * (*pk++)) >> 15) + gcurr; - gnext = __SSAT(gnext, 16); - /* Output samples */ - /* y(n) += gN(n) * vN */ - acc += (q31_t) ((gnext * (*pv++))); - /* write gN(n) into state for next sample processing */ - *px2++ = (q15_t) gnext; - /* Update f values for next coefficient processing */ - fcurr = fnext; - - tapCnt--; - } - - /* y(n) += g0(n) * v0 */ - acc += (q31_t) ((fnext * (*pv++))); - - out = (q15_t) __SSAT(acc >> 15, 16); - *px2++ = (q15_t) fnext; - - /* write out into pDst */ - *pDst++ = out; - - /* Advance the state pointer by 1 to process the next group of samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - stgCnt = numStages; - - /* copy data */ - while(stgCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - stgCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - - - -/** - * @} end of IIR_Lattice group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_iir_lattice_q15.c +* +* Description: Q15 IIR lattice filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup IIR_Lattice + * @{ + */ + +/** + * @brief Processing function for the Q15 IIR lattice filter. + * @param[in] *S points to an instance of the Q15 IIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 64-bit internal accumulator. + * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. + * Lastly, the accumulator is saturated to yield a result in 1.15 format. + */ + +void arm_iir_lattice_q15( + const arm_iir_lattice_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t fcurr, fnext, gcurr = 0, gnext; /* Temporary variables for lattice stages */ + q15_t gnext1, gnext2; /* Temporary variables for lattice stages */ + uint32_t stgCnt; /* Temporary variables for counts */ + q63_t acc; /* Accumlator */ + uint32_t blkCnt, tapCnt; /* Temporary variables for counts */ + q15_t *px1, *px2, *pk, *pv; /* temporary pointers for state and coef */ + uint32_t numStages = S->numStages; /* number of stages */ + q15_t *pState; /* State pointer */ + q15_t *pStateCurnt; /* State current pointer */ + q15_t out; /* Temporary variable for output */ + q31_t v; /* Temporary variable for ladder coefficient */ + + + blkCnt = blockSize; + + pState = &S->pState[0]; + + /* Sample processing */ + while(blkCnt > 0u) + { + /* Read Sample from input buffer */ + /* fN(n) = x(n) */ + fcurr = *pSrc++; + + /* Initialize state read pointer */ + px1 = pState; + /* Initialize state write pointer */ + px2 = pState; + /* Set accumulator to zero */ + acc = 0; + /* Initialize Ladder coeff pointer */ + pv = &S->pvCoeffs[0]; + /* Initialize Reflection coeff pointer */ + pk = &S->pkCoeffs[0]; + + + /* Process sample for first tap */ + gcurr = *px1++; + /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ + fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); + fnext = __SSAT(fnext, 16); + /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ + gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; + gnext = __SSAT(gnext, 16); + /* write gN(n) into state for next sample processing */ + *px2++ = (q15_t) gnext; + /* y(n) += gN(n) * vN */ + acc += (q31_t) ((gnext * (*pv++))); + + + /* Update f values for next coefficient processing */ + fcurr = fnext; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = (numStages - 1u) >> 2; + + while(tapCnt > 0u) + { + + /* Process sample for 2nd, 6th ...taps */ + /* Read gN-2(n-1) from state buffer */ + gcurr = *px1++; + /* Process sample for 2nd, 6th .. taps */ + /* fN-2(n) = fN-1(n) - kN-1 * gN-2(n-1) */ + fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); + fnext = __SSAT(fnext, 16); + /* gN-1(n) = kN-1 * fN-2(n) + gN-2(n-1) */ + gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; + gnext1 = (q15_t) __SSAT(gnext, 16); + /* write gN-1(n) into state */ + *px2++ = (q15_t) gnext1; + + + /* Process sample for 3nd, 7th ...taps */ + /* Read gN-3(n-1) from state */ + gcurr = *px1++; + /* Process sample for 3rd, 7th .. taps */ + /* fN-3(n) = fN-2(n) - kN-2 * gN-3(n-1) */ + fcurr = fnext - (((q31_t) gcurr * (*pk)) >> 15); + fcurr = __SSAT(fcurr, 16); + /* gN-2(n) = kN-2 * fN-3(n) + gN-3(n-1) */ + gnext = (((q31_t) fcurr * (*pk++)) >> 15) + gcurr; + gnext2 = (q15_t) __SSAT(gnext, 16); + /* write gN-2(n) into state */ + *px2++ = (q15_t) gnext2; + + /* Read vN-1 and vN-2 at a time */ + v = *__SIMD32(pv)++; + + + /* Pack gN-1(n) and gN-2(n) */ + +#ifndef ARM_MATH_BIG_ENDIAN + + gnext = __PKHBT(gnext1, gnext2, 16); + +#else + + gnext = __PKHBT(gnext2, gnext1, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* y(n) += gN-1(n) * vN-1 */ + /* process for gN-5(n) * vN-5, gN-9(n) * vN-9 ... */ + /* y(n) += gN-2(n) * vN-2 */ + /* process for gN-6(n) * vN-6, gN-10(n) * vN-10 ... */ + acc = __SMLALD(gnext, v, acc); + + + /* Process sample for 4th, 8th ...taps */ + /* Read gN-4(n-1) from state */ + gcurr = *px1++; + /* Process sample for 4th, 8th .. taps */ + /* fN-4(n) = fN-3(n) - kN-3 * gN-4(n-1) */ + fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); + fnext = __SSAT(fnext, 16); + /* gN-3(n) = kN-3 * fN-1(n) + gN-1(n-1) */ + gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; + gnext1 = (q15_t) __SSAT(gnext, 16); + /* write gN-3(n) for the next sample process */ + *px2++ = (q15_t) gnext1; + + + /* Process sample for 5th, 9th ...taps */ + /* Read gN-5(n-1) from state */ + gcurr = *px1++; + /* Process sample for 5th, 9th .. taps */ + /* fN-5(n) = fN-4(n) - kN-4 * gN-5(n-1) */ + fcurr = fnext - (((q31_t) gcurr * (*pk)) >> 15); + fcurr = __SSAT(fcurr, 16); + /* gN-4(n) = kN-4 * fN-5(n) + gN-5(n-1) */ + gnext = (((q31_t) fcurr * (*pk++)) >> 15) + gcurr; + gnext2 = (q15_t) __SSAT(gnext, 16); + /* write gN-4(n) for the next sample process */ + *px2++ = (q15_t) gnext2; + + /* Read vN-3 and vN-4 at a time */ + v = *__SIMD32(pv)++; + + /* Pack gN-3(n) and gN-4(n) */ +#ifndef ARM_MATH_BIG_ENDIAN + + gnext = __PKHBT(gnext1, gnext2, 16); + +#else + + gnext = __PKHBT(gnext2, gnext1, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* y(n) += gN-4(n) * vN-4 */ + /* process for gN-8(n) * vN-8, gN-12(n) * vN-12 ... */ + /* y(n) += gN-3(n) * vN-3 */ + /* process for gN-7(n) * vN-7, gN-11(n) * vN-11 ... */ + acc = __SMLALD(gnext, v, acc); + + tapCnt--; + + } + + fnext = fcurr; + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = (numStages - 1u) % 0x4u; + + while(tapCnt > 0u) + { + gcurr = *px1++; + /* Process sample for last taps */ + fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); + fnext = __SSAT(fnext, 16); + gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; + gnext = __SSAT(gnext, 16); + /* Output samples for last taps */ + acc += (q31_t) (((q31_t) gnext * (*pv++))); + *px2++ = (q15_t) gnext; + fcurr = fnext; + + tapCnt--; + } + + /* y(n) += g0(n) * v0 */ + acc += (q31_t) (((q31_t) fnext * (*pv++))); + + out = (q15_t) __SSAT(acc >> 15, 16); + *px2++ = (q15_t) fnext; + + /* write out into pDst */ + *pDst++ = out; + + /* Advance the state pointer by 4 to process the next group of 4 samples */ + pState = pState + 1u; + blkCnt--; + + } + + /* Processing is complete. Now copy last S->numStages samples to start of the buffer + for the preperation of next frame process */ + /* Points to the start of the state buffer */ + pStateCurnt = &S->pState[0]; + pState = &S->pState[blockSize]; + + stgCnt = (numStages >> 2u); + + /* copy data */ + while(stgCnt > 0u) + { + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + + /* Decrement the loop counter */ + stgCnt--; + + } + + /* Calculation of count for remaining q15_t data */ + stgCnt = (numStages) % 0x4u; + + /* copy data */ + while(stgCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + stgCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q31_t fcurr, fnext = 0, gcurr = 0, gnext; /* Temporary variables for lattice stages */ + uint32_t stgCnt; /* Temporary variables for counts */ + q63_t acc; /* Accumlator */ + uint32_t blkCnt, tapCnt; /* Temporary variables for counts */ + q15_t *px1, *px2, *pk, *pv; /* temporary pointers for state and coef */ + uint32_t numStages = S->numStages; /* number of stages */ + q15_t *pState; /* State pointer */ + q15_t *pStateCurnt; /* State current pointer */ + q15_t out; /* Temporary variable for output */ + + + blkCnt = blockSize; + + pState = &S->pState[0]; + + /* Sample processing */ + while(blkCnt > 0u) + { + /* Read Sample from input buffer */ + /* fN(n) = x(n) */ + fcurr = *pSrc++; + + /* Initialize state read pointer */ + px1 = pState; + /* Initialize state write pointer */ + px2 = pState; + /* Set accumulator to zero */ + acc = 0; + /* Initialize Ladder coeff pointer */ + pv = &S->pvCoeffs[0]; + /* Initialize Reflection coeff pointer */ + pk = &S->pkCoeffs[0]; + + tapCnt = numStages; + + while(tapCnt > 0u) + { + gcurr = *px1++; + /* Process sample */ + /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ + fnext = fcurr - ((gcurr * (*pk)) >> 15); + fnext = __SSAT(fnext, 16); + /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ + gnext = ((fnext * (*pk++)) >> 15) + gcurr; + gnext = __SSAT(gnext, 16); + /* Output samples */ + /* y(n) += gN(n) * vN */ + acc += (q31_t) ((gnext * (*pv++))); + /* write gN(n) into state for next sample processing */ + *px2++ = (q15_t) gnext; + /* Update f values for next coefficient processing */ + fcurr = fnext; + + tapCnt--; + } + + /* y(n) += g0(n) * v0 */ + acc += (q31_t) ((fnext * (*pv++))); + + out = (q15_t) __SSAT(acc >> 15, 16); + *px2++ = (q15_t) fnext; + + /* write out into pDst */ + *pDst++ = out; + + /* Advance the state pointer by 1 to process the next group of samples */ + pState = pState + 1u; + blkCnt--; + + } + + /* Processing is complete. Now copy last S->numStages samples to start of the buffer + for the preperation of next frame process */ + /* Points to the start of the state buffer */ + pStateCurnt = &S->pState[0]; + pState = &S->pState[blockSize]; + + stgCnt = numStages; + + /* copy data */ + while(stgCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + stgCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + + + +/** + * @} end of IIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q31.c index 04e70386c..115224645 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q31.c @@ -1,342 +1,342 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_q31.c -* -* Description: Q31 IIR lattice filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - -/** - * @brief Processing function for the Q31 IIR lattice filter. - * @param[in] *S points to an instance of the Q31 IIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 2*log2(numStages) bits. - * After all multiply-accumulates are performed, the 2.62 accumulator is saturated to 1.32 format and then truncated to 1.31 format. - */ - -void arm_iir_lattice_q31( - const arm_iir_lattice_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t fcurr, fnext = 0, gcurr = 0, gnext; /* Temporary variables for lattice stages */ - q63_t acc; /* Accumlator */ - uint32_t blkCnt, tapCnt; /* Temporary variables for counts */ - q31_t *px1, *px2, *pk, *pv; /* Temporary pointers for state and coef */ - uint32_t numStages = S->numStages; /* number of stages */ - q31_t *pState; /* State pointer */ - q31_t *pStateCurnt; /* State current pointer */ - - blkCnt = blockSize; - - pState = &S->pState[0]; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - - /* Process sample for first tap */ - gcurr = *px1++; - /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ - fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ - gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); - /* write gN-1(n-1) into state for next sample processing */ - *px2++ = gnext; - /* y(n) += gN(n) * vN */ - acc += ((q63_t) gnext * *pv++); - - /* Update f values for next coefficient processing */ - fcurr = fnext; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = (numStages - 1u) >> 2; - - while(tapCnt > 0u) - { - - /* Process sample for 2nd, 6th .. taps */ - /* Read gN-2(n-1) from state buffer */ - gcurr = *px1++; - /* fN-2(n) = fN-1(n) - kN-1 * gN-2(n-1) */ - fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - /* gN-1(n) = kN-1 * fN-2(n) + gN-2(n-1) */ - gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); - /* y(n) += gN-1(n) * vN-1 */ - /* process for gN-5(n) * vN-5, gN-9(n) * vN-9 ... */ - acc += ((q63_t) gnext * *pv++); - /* write gN-1(n) into state for next sample processing */ - *px2++ = gnext; - - /* Process sample for 3nd, 7th ...taps */ - /* Read gN-3(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 3rd, 7th .. taps */ - /* fN-3(n) = fN-2(n) - kN-2 * gN-3(n-1) */ - fcurr = __QSUB(fnext, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - /* gN-2(n) = kN-2 * fN-3(n) + gN-3(n-1) */ - gnext = __QADD(gcurr, (q31_t) (((q63_t) fcurr * (*pk++)) >> 31)); - /* y(n) += gN-2(n) * vN-2 */ - /* process for gN-6(n) * vN-6, gN-10(n) * vN-10 ... */ - acc += ((q63_t) gnext * *pv++); - /* write gN-2(n) into state for next sample processing */ - *px2++ = gnext; - - - /* Process sample for 4th, 8th ...taps */ - /* Read gN-4(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 4th, 8th .. taps */ - /* fN-4(n) = fN-3(n) - kN-3 * gN-4(n-1) */ - fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - /* gN-3(n) = kN-3 * fN-4(n) + gN-4(n-1) */ - gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); - /* y(n) += gN-3(n) * vN-3 */ - /* process for gN-7(n) * vN-7, gN-11(n) * vN-11 ... */ - acc += ((q63_t) gnext * *pv++); - /* write gN-3(n) into state for next sample processing */ - *px2++ = gnext; - - - /* Process sample for 5th, 9th ...taps */ - /* Read gN-5(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 5th, 9th .. taps */ - /* fN-5(n) = fN-4(n) - kN-4 * gN-1(n-1) */ - fcurr = __QSUB(fnext, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - /* gN-4(n) = kN-4 * fN-5(n) + gN-5(n-1) */ - gnext = __QADD(gcurr, (q31_t) (((q63_t) fcurr * (*pk++)) >> 31)); - /* y(n) += gN-4(n) * vN-4 */ - /* process for gN-8(n) * vN-8, gN-12(n) * vN-12 ... */ - acc += ((q63_t) gnext * *pv++); - /* write gN-4(n) into state for next sample processing */ - *px2++ = gnext; - - tapCnt--; - - } - - fnext = fcurr; - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = (numStages - 1u) % 0x4u; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample for last taps */ - fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); - /* Output samples for last taps */ - acc += ((q63_t) gnext * *pv++); - *px2++ = gnext; - fcurr = fnext; - - tapCnt--; - - } - - /* y(n) += g0(n) * v0 */ - acc += (q63_t) fnext *( - *pv++); - - *px2++ = fnext; - - /* write out into pDst */ - *pDst++ = (q31_t) (acc >> 31u); - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - tapCnt = numStages >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - - } - - /* Calculate remaining number of copies */ - tapCnt = (numStages) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - }; - -#else - - /* Run the below code for Cortex-M0 */ - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - tapCnt = numStages; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample */ - /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ - fnext = - clip_q63_to_q31(((q63_t) fcurr - - ((q31_t) (((q63_t) gcurr * (*pk)) >> 31)))); - /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ - gnext = - clip_q63_to_q31(((q63_t) gcurr + - ((q31_t) (((q63_t) fnext * (*pk++)) >> 31)))); - /* Output samples */ - /* y(n) += gN(n) * vN */ - acc += ((q63_t) gnext * *pv++); - /* write gN-1(n-1) into state for next sample processing */ - *px2++ = gnext; - /* Update f values for next coefficient processing */ - fcurr = fnext; - - tapCnt--; - } - - /* y(n) += g0(n) * v0 */ - acc += (q63_t) fnext *( - *pv++); - - *px2++ = fnext; - - /* write out into pDst */ - *pDst++ = (q31_t) (acc >> 31u); - - /* Advance the state pointer by 1 to process the next group of samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - tapCnt = numStages; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - - - -/** - * @} end of IIR_Lattice group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_iir_lattice_q31.c +* +* Description: Q31 IIR lattice filter processing function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup IIR_Lattice + * @{ + */ + +/** + * @brief Processing function for the Q31 IIR lattice filter. + * @param[in] *S points to an instance of the Q31 IIR lattice structure. + * @param[in] *pSrc points to the block of input data. + * @param[out] *pDst points to the block of output data. + * @param[in] blockSize number of samples to process. + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around rather than clip. + * In order to avoid overflows completely the input signal must be scaled down by 2*log2(numStages) bits. + * After all multiply-accumulates are performed, the 2.62 accumulator is saturated to 1.32 format and then truncated to 1.31 format. + */ + +void arm_iir_lattice_q31( + const arm_iir_lattice_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q31_t fcurr, fnext = 0, gcurr = 0, gnext; /* Temporary variables for lattice stages */ + q63_t acc; /* Accumlator */ + uint32_t blkCnt, tapCnt; /* Temporary variables for counts */ + q31_t *px1, *px2, *pk, *pv; /* Temporary pointers for state and coef */ + uint32_t numStages = S->numStages; /* number of stages */ + q31_t *pState; /* State pointer */ + q31_t *pStateCurnt; /* State current pointer */ + + blkCnt = blockSize; + + pState = &S->pState[0]; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Sample processing */ + while(blkCnt > 0u) + { + /* Read Sample from input buffer */ + /* fN(n) = x(n) */ + fcurr = *pSrc++; + + /* Initialize state read pointer */ + px1 = pState; + /* Initialize state write pointer */ + px2 = pState; + /* Set accumulator to zero */ + acc = 0; + /* Initialize Ladder coeff pointer */ + pv = &S->pvCoeffs[0]; + /* Initialize Reflection coeff pointer */ + pk = &S->pkCoeffs[0]; + + + /* Process sample for first tap */ + gcurr = *px1++; + /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ + fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); + /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ + gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); + /* write gN-1(n-1) into state for next sample processing */ + *px2++ = gnext; + /* y(n) += gN(n) * vN */ + acc += ((q63_t) gnext * *pv++); + + /* Update f values for next coefficient processing */ + fcurr = fnext; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = (numStages - 1u) >> 2; + + while(tapCnt > 0u) + { + + /* Process sample for 2nd, 6th .. taps */ + /* Read gN-2(n-1) from state buffer */ + gcurr = *px1++; + /* fN-2(n) = fN-1(n) - kN-1 * gN-2(n-1) */ + fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); + /* gN-1(n) = kN-1 * fN-2(n) + gN-2(n-1) */ + gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); + /* y(n) += gN-1(n) * vN-1 */ + /* process for gN-5(n) * vN-5, gN-9(n) * vN-9 ... */ + acc += ((q63_t) gnext * *pv++); + /* write gN-1(n) into state for next sample processing */ + *px2++ = gnext; + + /* Process sample for 3nd, 7th ...taps */ + /* Read gN-3(n-1) from state buffer */ + gcurr = *px1++; + /* Process sample for 3rd, 7th .. taps */ + /* fN-3(n) = fN-2(n) - kN-2 * gN-3(n-1) */ + fcurr = __QSUB(fnext, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); + /* gN-2(n) = kN-2 * fN-3(n) + gN-3(n-1) */ + gnext = __QADD(gcurr, (q31_t) (((q63_t) fcurr * (*pk++)) >> 31)); + /* y(n) += gN-2(n) * vN-2 */ + /* process for gN-6(n) * vN-6, gN-10(n) * vN-10 ... */ + acc += ((q63_t) gnext * *pv++); + /* write gN-2(n) into state for next sample processing */ + *px2++ = gnext; + + + /* Process sample for 4th, 8th ...taps */ + /* Read gN-4(n-1) from state buffer */ + gcurr = *px1++; + /* Process sample for 4th, 8th .. taps */ + /* fN-4(n) = fN-3(n) - kN-3 * gN-4(n-1) */ + fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); + /* gN-3(n) = kN-3 * fN-4(n) + gN-4(n-1) */ + gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); + /* y(n) += gN-3(n) * vN-3 */ + /* process for gN-7(n) * vN-7, gN-11(n) * vN-11 ... */ + acc += ((q63_t) gnext * *pv++); + /* write gN-3(n) into state for next sample processing */ + *px2++ = gnext; + + + /* Process sample for 5th, 9th ...taps */ + /* Read gN-5(n-1) from state buffer */ + gcurr = *px1++; + /* Process sample for 5th, 9th .. taps */ + /* fN-5(n) = fN-4(n) - kN-4 * gN-1(n-1) */ + fcurr = __QSUB(fnext, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); + /* gN-4(n) = kN-4 * fN-5(n) + gN-5(n-1) */ + gnext = __QADD(gcurr, (q31_t) (((q63_t) fcurr * (*pk++)) >> 31)); + /* y(n) += gN-4(n) * vN-4 */ + /* process for gN-8(n) * vN-8, gN-12(n) * vN-12 ... */ + acc += ((q63_t) gnext * *pv++); + /* write gN-4(n) into state for next sample processing */ + *px2++ = gnext; + + tapCnt--; + + } + + fnext = fcurr; + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = (numStages - 1u) % 0x4u; + + while(tapCnt > 0u) + { + gcurr = *px1++; + /* Process sample for last taps */ + fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); + gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); + /* Output samples for last taps */ + acc += ((q63_t) gnext * *pv++); + *px2++ = gnext; + fcurr = fnext; + + tapCnt--; + + } + + /* y(n) += g0(n) * v0 */ + acc += (q63_t) fnext *( + *pv++); + + *px2++ = fnext; + + /* write out into pDst */ + *pDst++ = (q31_t) (acc >> 31u); + + /* Advance the state pointer by 4 to process the next group of 4 samples */ + pState = pState + 1u; + blkCnt--; + + } + + /* Processing is complete. Now copy last S->numStages samples to start of the buffer + for the preperation of next frame process */ + + /* Points to the start of the state buffer */ + pStateCurnt = &S->pState[0]; + pState = &S->pState[blockSize]; + + tapCnt = numStages >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + + } + + /* Calculate remaining number of copies */ + tapCnt = (numStages) % 0x4u; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + }; + +#else + + /* Run the below code for Cortex-M0 */ + /* Sample processing */ + while(blkCnt > 0u) + { + /* Read Sample from input buffer */ + /* fN(n) = x(n) */ + fcurr = *pSrc++; + + /* Initialize state read pointer */ + px1 = pState; + /* Initialize state write pointer */ + px2 = pState; + /* Set accumulator to zero */ + acc = 0; + /* Initialize Ladder coeff pointer */ + pv = &S->pvCoeffs[0]; + /* Initialize Reflection coeff pointer */ + pk = &S->pkCoeffs[0]; + + tapCnt = numStages; + + while(tapCnt > 0u) + { + gcurr = *px1++; + /* Process sample */ + /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ + fnext = + clip_q63_to_q31(((q63_t) fcurr - + ((q31_t) (((q63_t) gcurr * (*pk)) >> 31)))); + /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ + gnext = + clip_q63_to_q31(((q63_t) gcurr + + ((q31_t) (((q63_t) fnext * (*pk++)) >> 31)))); + /* Output samples */ + /* y(n) += gN(n) * vN */ + acc += ((q63_t) gnext * *pv++); + /* write gN-1(n-1) into state for next sample processing */ + *px2++ = gnext; + /* Update f values for next coefficient processing */ + fcurr = fnext; + + tapCnt--; + } + + /* y(n) += g0(n) * v0 */ + acc += (q63_t) fnext *( + *pv++); + + *px2++ = fnext; + + /* write out into pDst */ + *pDst++ = (q31_t) (acc >> 31u); + + /* Advance the state pointer by 1 to process the next group of samples */ + pState = pState + 1u; + blkCnt--; + + } + + /* Processing is complete. Now copy last S->numStages samples to start of the buffer + for the preperation of next frame process */ + + /* Points to the start of the state buffer */ + pStateCurnt = &S->pState[0]; + pState = &S->pState[blockSize]; + + tapCnt = numStages; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + + + +/** + * @} end of IIR_Lattice group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_f32.c index e3e1347a1..13053219d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_f32.c @@ -1,431 +1,431 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_f32.c -* -* Description: Processing function for the floating-point LMS filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup LMS Least Mean Square (LMS) Filters - * - * LMS filters are a class of adaptive filters that are able to "learn" an unknown transfer functions. - * LMS filters use a gradient descent method in which the filter coefficients are updated based on the instantaneous error signal. - * Adaptive filters are often used in communication systems, equalizers, and noise removal. - * The CMSIS DSP Library contains LMS filter functions that operate on Q15, Q31, and floating-point data types. - * The library also contains normalized LMS filters in which the filter coefficient adaptation is indepedent of the level of the input signal. - * - * An LMS filter consists of two components as shown below. - * The first component is a standard transversal or FIR filter. - * The second component is a coefficient update mechanism. - * The LMS filter has two input signals. - * The "input" feeds the FIR filter while the "reference input" corresponds to the desired output of the FIR filter. - * That is, the FIR filter coefficients are updated so that the output of the FIR filter matches the reference input. - * The filter coefficient update mechanism is based on the difference between the FIR filter output and the reference input. - * This "error signal" tends towards zero as the filter adapts. - * The LMS processing functions accept the input and reference input signals and generate the filter output and error signal. - * \image html LMS.gif "Internal structure of the Least Mean Square filter" - * - * The functions operate on blocks of data and each call to the function processes - * blockSize samples through the filter. - * pSrc points to input signal, pRef points to reference signal, - * pOut points to output signal and pErr points to error signal. - * All arrays contain blockSize values. - * - * The functions operate on a block-by-block basis. - * Internally, the filter coefficients b[n] are updated on a sample-by-sample basis. - * The convergence of the LMS filter is slower compared to the normalized LMS algorithm. - * - * \par Algorithm: - * The output signal y[n] is computed by a standard FIR filter: - *
   
- *     y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]   
- * 
- * - * \par - * The error signal equals the difference between the reference signal d[n] and the filter output: - *
   
- *     e[n] = d[n] - y[n].   
- * 
- * - * \par - * After each sample of the error signal is computed, the filter coefficients b[k] are updated on a sample-by-sample basis: - *
   
- *     b[k] = b[k] + e[n] * mu * x[n-k],  for k=0, 1, ..., numTaps-1   
- * 
- * where mu is the step size and controls the rate of coefficient convergence. - *\par - * In the APIs, pCoeffs points to a coefficient array of size numTaps. - * Coefficients are stored in time reversed order. - * \par - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to a state array of size numTaps + blockSize - 1. - * Samples in the state buffer are stored in the order: - * \par - *
   
- *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}   
- * 
- * \par - * Note that the length of the state buffer exceeds the length of the coefficient array by blockSize-1 samples. - * The increased state buffer length allows circular addressing, which is traditionally used in FIR filters, - * to be avoided and yields a significant speed improvement. - * The state variables are updated after each block of data is processed. - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter and - * coefficient and state arrays cannot be shared among instances. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * The code below statically initializes each of the 3 different data type filter instance structures - *
   
- *    arm_lms_instance_f32 S = {numTaps, pState, pCoeffs, mu};   
- *    arm_lms_instance_q31 S = {numTaps, pState, pCoeffs, mu, postShift};   
- *    arm_lms_instance_q15 S = {numTaps, pState, pCoeffs, mu, postShift};   
- * 
- * where numTaps is the number of filter coefficients in the filter; pState is the address of the state buffer; - * pCoeffs is the address of the coefficient buffer; mu is the step size parameter; and postShift is the shift applied to coefficients. - * - * \par Fixed-Point Behavior: - * Care must be taken when using the Q15 and Q31 versions of the LMS filter. - * The following issues must be considered: - * - Scaling of coefficients - * - Overflow and saturation - * - * \par Scaling of Coefficients: - * Filter coefficients are represented as fractional values and - * coefficients are restricted to lie in the range [-1 +1). - * The fixed-point functions have an additional scaling parameter postShift. - * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. - * This essentially scales the filter coefficients by 2^postShift and - * allows the filter coefficients to exceed the range [+1 -1). - * The value of postShift is set by the user based on the expected gain through the system being modeled. - * - * \par Overflow and Saturation: - * Overflow and saturation behavior of the fixed-point Q15 and Q31 versions are - * described separately as part of the function specific documentation below. - */ - -/** - * @addtogroup LMS - * @{ - */ - -/** - * @details - * This function operates on floating-point data types. - * - * @brief Processing function for floating-point LMS filter. - * @param[in] *S points to an instance of the floating-point LMS filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[in] *pRef points to the block of reference data. - * @param[out] *pOut points to the block of output data. - * @param[out] *pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_lms_f32( - const arm_lms_instance_f32 * S, - float32_t * pSrc, - float32_t * pRef, - float32_t * pOut, - float32_t * pErr, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - float32_t mu = S->mu; /* Adaptive factor */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - float32_t sum, e, d; /* accumulator, error, reference data sample */ - float32_t w = 0.0f; /* weight factor */ - - e = 0.0f; - d = 0.0f; - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - blkCnt = blockSize; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Set the accumulator to zero */ - sum = 0.0f; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result in the accumulator, store in the destination buffer. */ - *pOut++ = sum; - - /* Compute and store error */ - d = (float32_t) (*pRef++); - e = d - sum; - *pErr++ = e; - - /* Calculation of Weighting factor for the updating filter coefficients */ - w = e * mu; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb = *pb + (w * (*px++)); - pb++; - - *pb = *pb + (w * (*px++)); - pb++; - - *pb = *pb + (w * (*px++)); - pb++; - - *pb = *pb + (w * (*px++)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb = *pb + (w * (*px++)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Loop unrolling for (numTaps - 1u) samples copy */ - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Set the accumulator to zero */ - sum = 0.0f; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is stored in the destination buffer. */ - *pOut++ = sum; - - /* Compute and store error */ - d = (float32_t) (*pRef++); - e = d - sum; - *pErr++ = e; - - /* Weighting factor for the LMS version */ - w = e * mu; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb = *pb + (w * (*px++)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - * start of the state buffer. This prepares the state buffer for the - * next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Copy (numTaps - 1u) samples */ - tapCnt = (numTaps - 1u); - - /* Copy the data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of LMS group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_f32.c +* +* Description: Processing function for the floating-point LMS filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup LMS Least Mean Square (LMS) Filters + * + * LMS filters are a class of adaptive filters that are able to "learn" an unknown transfer functions. + * LMS filters use a gradient descent method in which the filter coefficients are updated based on the instantaneous error signal. + * Adaptive filters are often used in communication systems, equalizers, and noise removal. + * The CMSIS DSP Library contains LMS filter functions that operate on Q15, Q31, and floating-point data types. + * The library also contains normalized LMS filters in which the filter coefficient adaptation is indepedent of the level of the input signal. + * + * An LMS filter consists of two components as shown below. + * The first component is a standard transversal or FIR filter. + * The second component is a coefficient update mechanism. + * The LMS filter has two input signals. + * The "input" feeds the FIR filter while the "reference input" corresponds to the desired output of the FIR filter. + * That is, the FIR filter coefficients are updated so that the output of the FIR filter matches the reference input. + * The filter coefficient update mechanism is based on the difference between the FIR filter output and the reference input. + * This "error signal" tends towards zero as the filter adapts. + * The LMS processing functions accept the input and reference input signals and generate the filter output and error signal. + * \image html LMS.gif "Internal structure of the Least Mean Square filter" + * + * The functions operate on blocks of data and each call to the function processes + * blockSize samples through the filter. + * pSrc points to input signal, pRef points to reference signal, + * pOut points to output signal and pErr points to error signal. + * All arrays contain blockSize values. + * + * The functions operate on a block-by-block basis. + * Internally, the filter coefficients b[n] are updated on a sample-by-sample basis. + * The convergence of the LMS filter is slower compared to the normalized LMS algorithm. + * + * \par Algorithm: + * The output signal y[n] is computed by a standard FIR filter: + *
   
+ *     y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]   
+ * 
+ * + * \par + * The error signal equals the difference between the reference signal d[n] and the filter output: + *
   
+ *     e[n] = d[n] - y[n].   
+ * 
+ * + * \par + * After each sample of the error signal is computed, the filter coefficients b[k] are updated on a sample-by-sample basis: + *
   
+ *     b[k] = b[k] + e[n] * mu * x[n-k],  for k=0, 1, ..., numTaps-1   
+ * 
+ * where mu is the step size and controls the rate of coefficient convergence. + *\par + * In the APIs, pCoeffs points to a coefficient array of size numTaps. + * Coefficients are stored in time reversed order. + * \par + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to a state array of size numTaps + blockSize - 1. + * Samples in the state buffer are stored in the order: + * \par + *
   
+ *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}   
+ * 
+ * \par + * Note that the length of the state buffer exceeds the length of the coefficient array by blockSize-1 samples. + * The increased state buffer length allows circular addressing, which is traditionally used in FIR filters, + * to be avoided and yields a significant speed improvement. + * The state variables are updated after each block of data is processed. + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter and + * coefficient and state arrays cannot be shared among instances. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Set the values in the state buffer to zeros before static initialization. + * The code below statically initializes each of the 3 different data type filter instance structures + *
   
+ *    arm_lms_instance_f32 S = {numTaps, pState, pCoeffs, mu};   
+ *    arm_lms_instance_q31 S = {numTaps, pState, pCoeffs, mu, postShift};   
+ *    arm_lms_instance_q15 S = {numTaps, pState, pCoeffs, mu, postShift};   
+ * 
+ * where numTaps is the number of filter coefficients in the filter; pState is the address of the state buffer; + * pCoeffs is the address of the coefficient buffer; mu is the step size parameter; and postShift is the shift applied to coefficients. + * + * \par Fixed-Point Behavior: + * Care must be taken when using the Q15 and Q31 versions of the LMS filter. + * The following issues must be considered: + * - Scaling of coefficients + * - Overflow and saturation + * + * \par Scaling of Coefficients: + * Filter coefficients are represented as fractional values and + * coefficients are restricted to lie in the range [-1 +1). + * The fixed-point functions have an additional scaling parameter postShift. + * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. + * This essentially scales the filter coefficients by 2^postShift and + * allows the filter coefficients to exceed the range [+1 -1). + * The value of postShift is set by the user based on the expected gain through the system being modeled. + * + * \par Overflow and Saturation: + * Overflow and saturation behavior of the fixed-point Q15 and Q31 versions are + * described separately as part of the function specific documentation below. + */ + +/** + * @addtogroup LMS + * @{ + */ + +/** + * @details + * This function operates on floating-point data types. + * + * @brief Processing function for floating-point LMS filter. + * @param[in] *S points to an instance of the floating-point LMS filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[in] *pRef points to the block of reference data. + * @param[out] *pOut points to the block of output data. + * @param[out] *pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + +void arm_lms_f32( + const arm_lms_instance_f32 * S, + float32_t * pSrc, + float32_t * pRef, + float32_t * pOut, + float32_t * pErr, + uint32_t blockSize) +{ + float32_t *pState = S->pState; /* State pointer */ + float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + float32_t *pStateCurnt; /* Points to the current sample of the state */ + float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ + float32_t mu = S->mu; /* Adaptive factor */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + uint32_t tapCnt, blkCnt; /* Loop counters */ + float32_t sum, e, d; /* accumulator, error, reference data sample */ + float32_t w = 0.0f; /* weight factor */ + + e = 0.0f; + d = 0.0f; + + /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + blkCnt = blockSize; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + while(blkCnt > 0u) + { + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Set the accumulator to zero */ + sum = 0.0f; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + sum += (*px++) * (*pb++); + sum += (*px++) * (*pb++); + sum += (*px++) * (*pb++); + sum += (*px++) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + sum += (*px++) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* The result in the accumulator, store in the destination buffer. */ + *pOut++ = sum; + + /* Compute and store error */ + d = (float32_t) (*pRef++); + e = d - sum; + *pErr++ = e; + + /* Calculation of Weighting factor for the updating filter coefficients */ + w = e * mu; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + /* Update filter coefficients */ + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + *pb = *pb + (w * (*px++)); + pb++; + + *pb = *pb + (w * (*px++)); + pb++; + + *pb = *pb + (w * (*px++)); + pb++; + + *pb = *pb + (w * (*px++)); + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + *pb = *pb + (w * (*px++)); + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + satrt of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Loop unrolling for (numTaps - 1u) samples copy */ + tapCnt = (numTaps - 1u) >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Calculate remaining number of copies */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + while(blkCnt > 0u) + { + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize pCoeffs pointer */ + pb = pCoeffs; + + /* Set the accumulator to zero */ + sum = 0.0f; + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + sum += (*px++) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* The result is stored in the destination buffer. */ + *pOut++ = sum; + + /* Compute and store error */ + d = (float32_t) (*pRef++); + e = d - sum; + *pErr++ = e; + + /* Weighting factor for the LMS version */ + w = e * mu; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize pCoeffs pointer */ + pb = pCoeffs; + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + *pb = *pb + (w * (*px++)); + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + * start of the state buffer. This prepares the state buffer for the + * next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Copy (numTaps - 1u) samples */ + tapCnt = (numTaps - 1u); + + /* Copy the data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of LMS group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_f32.c index 9b08cdf72..46c01044e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_f32.c @@ -1,87 +1,87 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_init_f32.c -* -* Description: Floating-point LMS filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @addtogroup LMS - * @{ - */ - - /** - * @brief Initialization function for floating-point LMS filter. - * @param[in] *S points to an instance of the floating-point LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] *pCoeffs points to the coefficient buffer. - * @param[in] *pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -/** - * \par Description: - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * The initial filter coefficients serve as a starting point for the adaptive filter. - * pState points to an array of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_lms_f32(). - */ - -void arm_lms_init_f32( - arm_lms_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - float32_t mu, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps */ - memset(pState, 0, (numTaps + (blockSize - 1)) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; -} - -/** - * @} end of LMS group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_init_f32.c +* +* Description: Floating-point LMS filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @addtogroup LMS + * @{ + */ + + /** + * @brief Initialization function for floating-point LMS filter. + * @param[in] *S points to an instance of the floating-point LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to the coefficient buffer. + * @param[in] *pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @return none. + */ + +/** + * \par Description: + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * The initial filter coefficients serve as a starting point for the adaptive filter. + * pState points to an array of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_lms_f32(). + */ + +void arm_lms_init_f32( + arm_lms_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + float32_t mu, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always blockSize + numTaps */ + memset(pState, 0, (numTaps + (blockSize - 1)) * sizeof(float32_t)); + + /* Assign state pointer */ + S->pState = pState; + + /* Assign Step size value */ + S->mu = mu; +} + +/** + * @} end of LMS group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q15.c index 3a2a9948e..5caa0a3cd 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q15.c @@ -1,97 +1,97 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_init_q15.c -* -* Description: Q15 LMS filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS - * @{ - */ - -/** -* @brief Initialization function for the Q15 LMS filter. -* @param[in] *S points to an instance of the Q15 LMS filter structure. -* @param[in] numTaps number of filter coefficients. -* @param[in] *pCoeffs points to the coefficient buffer. -* @param[in] *pState points to the state buffer. -* @param[in] mu step size that controls filter coefficient updates. -* @param[in] blockSize number of samples to process. -* @param[in] postShift bit shift applied to coefficients. -* @return none. -* -* \par Description: -* pCoeffs points to the array of filter coefficients stored in time reversed order: -*
   
-*    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
-* 
-* The initial filter coefficients serve as a starting point for the adaptive filter. -* pState points to the array of state variables and size of array is -* numTaps+blockSize-1 samples, where blockSize is the number of -* input samples processed by each call to arm_lms_q15(). -*/ - -void arm_lms_init_q15( - arm_lms_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - q15_t mu, - uint32_t blockSize, - uint32_t postShift) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps - 1 */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; - - /* Assign postShift value to be applied */ - S->postShift = postShift; - -} - -/** - * @} end of LMS group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_init_q15.c +* +* Description: Q15 LMS filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup LMS + * @{ + */ + +/** +* @brief Initialization function for the Q15 LMS filter. +* @param[in] *S points to an instance of the Q15 LMS filter structure. +* @param[in] numTaps number of filter coefficients. +* @param[in] *pCoeffs points to the coefficient buffer. +* @param[in] *pState points to the state buffer. +* @param[in] mu step size that controls filter coefficient updates. +* @param[in] blockSize number of samples to process. +* @param[in] postShift bit shift applied to coefficients. +* @return none. +* +* \par Description: +* pCoeffs points to the array of filter coefficients stored in time reversed order: +*
   
+*    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+* 
+* The initial filter coefficients serve as a starting point for the adaptive filter. +* pState points to the array of state variables and size of array is +* numTaps+blockSize-1 samples, where blockSize is the number of +* input samples processed by each call to arm_lms_q15(). +*/ + +void arm_lms_init_q15( + arm_lms_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + q15_t mu, + uint32_t blockSize, + uint32_t postShift) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always blockSize + numTaps - 1 */ + memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); + + /* Assign state pointer */ + S->pState = pState; + + /* Assign Step size value */ + S->mu = mu; + + /* Assign postShift value to be applied */ + S->postShift = postShift; + +} + +/** + * @} end of LMS group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q31.c index b846be73a..7d8fd49e7 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q31.c @@ -1,97 +1,97 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_init_q31.c -* -* Description: Q31 LMS filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS - * @{ - */ - - /** - * @brief Initialization function for Q31 LMS filter. - * @param[in] *S points to an instance of the Q31 LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] *pCoeffs points to coefficient buffer. - * @param[in] *pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - * @return none. - * - * \par Description: - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * The initial filter coefficients serve as a starting point for the adaptive filter. - * pState points to an array of length numTaps+blockSize-1 samples, - * where blockSize is the number of input samples processed by each call to - * arm_lms_q31(). - */ - -void arm_lms_init_q31( - arm_lms_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - q31_t mu, - uint32_t blockSize, - uint32_t postShift) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps - 1 */ - memset(pState, 0, ((uint32_t) numTaps + (blockSize - 1u)) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; - - /* Assign postShift value to be applied */ - S->postShift = postShift; - -} - -/** - * @} end of LMS group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_init_q31.c +* +* Description: Q31 LMS filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup LMS + * @{ + */ + + /** + * @brief Initialization function for Q31 LMS filter. + * @param[in] *S points to an instance of the Q31 LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to coefficient buffer. + * @param[in] *pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + * @return none. + * + * \par Description: + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * The initial filter coefficients serve as a starting point for the adaptive filter. + * pState points to an array of length numTaps+blockSize-1 samples, + * where blockSize is the number of input samples processed by each call to + * arm_lms_q31(). + */ + +void arm_lms_init_q31( + arm_lms_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + q31_t mu, + uint32_t blockSize, + uint32_t postShift) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always blockSize + numTaps - 1 */ + memset(pState, 0, ((uint32_t) numTaps + (blockSize - 1u)) * sizeof(q31_t)); + + /* Assign state pointer */ + S->pState = pState; + + /* Assign Step size value */ + S->mu = mu; + + /* Assign postShift value to be applied */ + S->postShift = postShift; + +} + +/** + * @} end of LMS group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_f32.c index 2cc304778..ee6022921 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_f32.c @@ -1,453 +1,453 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_f32.c -* -* Description: Processing function for the floating-point Normalised LMS. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup LMS_NORM Normalized LMS Filters - * - * This set of functions implements a commonly used adaptive filter. - * It is related to the Least Mean Square (LMS) adaptive filter and includes an additional normalization - * factor which increases the adaptation rate of the filter. - * The CMSIS DSP Library contains normalized LMS filter functions that operate on Q15, Q31, and floating-point data types. - * - * A normalized least mean square (NLMS) filter consists of two components as shown below. - * The first component is a standard transversal or FIR filter. - * The second component is a coefficient update mechanism. - * The NLMS filter has two input signals. - * The "input" feeds the FIR filter while the "reference input" corresponds to the desired output of the FIR filter. - * That is, the FIR filter coefficients are updated so that the output of the FIR filter matches the reference input. - * The filter coefficient update mechanism is based on the difference between the FIR filter output and the reference input. - * This "error signal" tends towards zero as the filter adapts. - * The NLMS processing functions accept the input and reference input signals and generate the filter output and error signal. - * \image html LMS.gif "Internal structure of the NLMS adaptive filter" - * - * The functions operate on blocks of data and each call to the function processes - * blockSize samples through the filter. - * pSrc points to input signal, pRef points to reference signal, - * pOut points to output signal and pErr points to error signal. - * All arrays contain blockSize values. - * - * The functions operate on a block-by-block basis. - * Internally, the filter coefficients b[n] are updated on a sample-by-sample basis. - * The convergence of the LMS filter is slower compared to the normalized LMS algorithm. - * - * \par Algorithm: - * The output signal y[n] is computed by a standard FIR filter: - *
   
- *     y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]   
- * 
- * - * \par - * The error signal equals the difference between the reference signal d[n] and the filter output: - *
   
- *     e[n] = d[n] - y[n].   
- * 
- * - * \par - * After each sample of the error signal is computed the instanteous energy of the filter state variables is calculated: - *
   
- *    E = x[n]^2 + x[n-1]^2 + ... + x[n-numTaps+1]^2.   
- * 
- * The filter coefficients b[k] are then updated on a sample-by-sample basis: - *
   
- *     b[k] = b[k] + e[n] * (mu/E) * x[n-k],  for k=0, 1, ..., numTaps-1   
- * 
- * where mu is the step size and controls the rate of coefficient convergence. - *\par - * In the APIs, pCoeffs points to a coefficient array of size numTaps. - * Coefficients are stored in time reversed order. - * \par - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * \par - * pState points to a state array of size numTaps + blockSize - 1. - * Samples in the state buffer are stored in the order: - * \par - *
   
- *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}   
- * 
- * \par - * Note that the length of the state buffer exceeds the length of the coefficient array by blockSize-1 samples. - * The increased state buffer length allows circular addressing, which is traditionally used in FIR filters, - * to be avoided and yields a significant speed improvement. - * The state variables are updated after each block of data is processed. - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter and - * coefficient and state arrays cannot be shared among instances. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * \par - * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function. - * \par Fixed-Point Behavior: - * Care must be taken when using the Q15 and Q31 versions of the normalised LMS filter. - * The following issues must be considered: - * - Scaling of coefficients - * - Overflow and saturation - * - * \par Scaling of Coefficients: - * Filter coefficients are represented as fractional values and - * coefficients are restricted to lie in the range [-1 +1). - * The fixed-point functions have an additional scaling parameter postShift. - * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. - * This essentially scales the filter coefficients by 2^postShift and - * allows the filter coefficients to exceed the range [+1 -1). - * The value of postShift is set by the user based on the expected gain through the system being modeled. - * - * \par Overflow and Saturation: - * Overflow and saturation behavior of the fixed-point Q15 and Q31 versions are - * described separately as part of the function specific documentation below. - */ - - -/** - * @addtogroup LMS_NORM - * @{ - */ - - - /** - * @brief Processing function for floating-point normalized LMS filter. - * @param[in] *S points to an instance of the floating-point normalized LMS filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[in] *pRef points to the block of reference data. - * @param[out] *pOut points to the block of output data. - * @param[out] *pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_lms_norm_f32( - arm_lms_norm_instance_f32 * S, - float32_t * pSrc, - float32_t * pRef, - float32_t * pOut, - float32_t * pErr, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - float32_t mu = S->mu; /* Adaptive factor */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - float32_t energy; /* Energy of the input */ - float32_t sum, e, d; /* accumulator, error, reference data sample */ - float32_t w, x0, in; /* weight factor, temporary variable to hold input sample and state */ - - /* Initializations of error, difference, Coefficient update */ - e = 0.0f; - d = 0.0f; - w = 0.0f; - - energy = S->energy; - x0 = S->x0; - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy -= x0 * x0; - energy += in * in; - - /* Set the accumulator to zero */ - sum = 0.0f; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result in the accumulator, store in the destination buffer. */ - *pOut++ = sum; - - /* Compute and store error */ - d = (float32_t) (*pRef++); - e = d - sum; - *pErr++ = e; - - /* Calculation of Weighting factor for updating filter coefficients */ - /* epsilon value 0.000000119209289f */ - w = (e * mu) / (energy + 0.000000119209289f); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb += w * (*px++); - pb++; - - *pb += w * (*px++); - pb++; - - *pb += w * (*px++); - pb++; - - *pb += w * (*px++); - pb++; - - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb += w * (*px++); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - S->energy = energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Loop unrolling for (numTaps - 1u)/4 samples copy */ - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy -= x0 * x0; - energy += in * in; - - /* Set the accumulator to zero */ - sum = 0.0f; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result in the accumulator is stored in the destination buffer. */ - *pOut++ = sum; - - /* Compute and store error */ - d = (float32_t) (*pRef++); - e = d - sum; - *pErr++ = e; - - /* Calculation of Weighting factor for updating filter coefficients */ - /* epsilon value 0.000000119209289f */ - w = (e * mu) / (energy + 0.000000119209289f); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCcoeffs pointer */ - pb = pCoeffs; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb += w * (*px++); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - S->energy = energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Copy (numTaps - 1u) samples */ - tapCnt = (numTaps - 1u); - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of LMS_NORM group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_norm_f32.c +* +* Description: Processing function for the floating-point Normalised LMS. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @defgroup LMS_NORM Normalized LMS Filters + * + * This set of functions implements a commonly used adaptive filter. + * It is related to the Least Mean Square (LMS) adaptive filter and includes an additional normalization + * factor which increases the adaptation rate of the filter. + * The CMSIS DSP Library contains normalized LMS filter functions that operate on Q15, Q31, and floating-point data types. + * + * A normalized least mean square (NLMS) filter consists of two components as shown below. + * The first component is a standard transversal or FIR filter. + * The second component is a coefficient update mechanism. + * The NLMS filter has two input signals. + * The "input" feeds the FIR filter while the "reference input" corresponds to the desired output of the FIR filter. + * That is, the FIR filter coefficients are updated so that the output of the FIR filter matches the reference input. + * The filter coefficient update mechanism is based on the difference between the FIR filter output and the reference input. + * This "error signal" tends towards zero as the filter adapts. + * The NLMS processing functions accept the input and reference input signals and generate the filter output and error signal. + * \image html LMS.gif "Internal structure of the NLMS adaptive filter" + * + * The functions operate on blocks of data and each call to the function processes + * blockSize samples through the filter. + * pSrc points to input signal, pRef points to reference signal, + * pOut points to output signal and pErr points to error signal. + * All arrays contain blockSize values. + * + * The functions operate on a block-by-block basis. + * Internally, the filter coefficients b[n] are updated on a sample-by-sample basis. + * The convergence of the LMS filter is slower compared to the normalized LMS algorithm. + * + * \par Algorithm: + * The output signal y[n] is computed by a standard FIR filter: + *
   
+ *     y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]   
+ * 
+ * + * \par + * The error signal equals the difference between the reference signal d[n] and the filter output: + *
   
+ *     e[n] = d[n] - y[n].   
+ * 
+ * + * \par + * After each sample of the error signal is computed the instanteous energy of the filter state variables is calculated: + *
   
+ *    E = x[n]^2 + x[n-1]^2 + ... + x[n-numTaps+1]^2.   
+ * 
+ * The filter coefficients b[k] are then updated on a sample-by-sample basis: + *
   
+ *     b[k] = b[k] + e[n] * (mu/E) * x[n-k],  for k=0, 1, ..., numTaps-1   
+ * 
+ * where mu is the step size and controls the rate of coefficient convergence. + *\par + * In the APIs, pCoeffs points to a coefficient array of size numTaps. + * Coefficients are stored in time reversed order. + * \par + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * \par + * pState points to a state array of size numTaps + blockSize - 1. + * Samples in the state buffer are stored in the order: + * \par + *
   
+ *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}   
+ * 
+ * \par + * Note that the length of the state buffer exceeds the length of the coefficient array by blockSize-1 samples. + * The increased state buffer length allows circular addressing, which is traditionally used in FIR filters, + * to be avoided and yields a significant speed improvement. + * The state variables are updated after each block of data is processed. + * \par Instance Structure + * The coefficients and state variables for a filter are stored together in an instance data structure. + * A separate instance structure must be defined for each filter and + * coefficient and state arrays cannot be shared among instances. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Zeros out the values in the state buffer. + * \par + * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function. + * \par Fixed-Point Behavior: + * Care must be taken when using the Q15 and Q31 versions of the normalised LMS filter. + * The following issues must be considered: + * - Scaling of coefficients + * - Overflow and saturation + * + * \par Scaling of Coefficients: + * Filter coefficients are represented as fractional values and + * coefficients are restricted to lie in the range [-1 +1). + * The fixed-point functions have an additional scaling parameter postShift. + * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. + * This essentially scales the filter coefficients by 2^postShift and + * allows the filter coefficients to exceed the range [+1 -1). + * The value of postShift is set by the user based on the expected gain through the system being modeled. + * + * \par Overflow and Saturation: + * Overflow and saturation behavior of the fixed-point Q15 and Q31 versions are + * described separately as part of the function specific documentation below. + */ + + +/** + * @addtogroup LMS_NORM + * @{ + */ + + + /** + * @brief Processing function for floating-point normalized LMS filter. + * @param[in] *S points to an instance of the floating-point normalized LMS filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[in] *pRef points to the block of reference data. + * @param[out] *pOut points to the block of output data. + * @param[out] *pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + * @return none. + */ + +void arm_lms_norm_f32( + arm_lms_norm_instance_f32 * S, + float32_t * pSrc, + float32_t * pRef, + float32_t * pOut, + float32_t * pErr, + uint32_t blockSize) +{ + float32_t *pState = S->pState; /* State pointer */ + float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + float32_t *pStateCurnt; /* Points to the current sample of the state */ + float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ + float32_t mu = S->mu; /* Adaptive factor */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + uint32_t tapCnt, blkCnt; /* Loop counters */ + float32_t energy; /* Energy of the input */ + float32_t sum, e, d; /* accumulator, error, reference data sample */ + float32_t w, x0, in; /* weight factor, temporary variable to hold input sample and state */ + + /* Initializations of error, difference, Coefficient update */ + e = 0.0f; + d = 0.0f; + w = 0.0f; + + energy = S->energy; + x0 = S->x0; + + /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + while(blkCnt > 0u) + { + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Read the sample from input buffer */ + in = *pSrc++; + + /* Update the energy calculation */ + energy -= x0 * x0; + energy += in * in; + + /* Set the accumulator to zero */ + sum = 0.0f; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + sum += (*px++) * (*pb++); + sum += (*px++) * (*pb++); + sum += (*px++) * (*pb++); + sum += (*px++) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + sum += (*px++) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* The result in the accumulator, store in the destination buffer. */ + *pOut++ = sum; + + /* Compute and store error */ + d = (float32_t) (*pRef++); + e = d - sum; + *pErr++ = e; + + /* Calculation of Weighting factor for updating filter coefficients */ + /* epsilon value 0.000000119209289f */ + w = (e * mu) / (energy + 0.000000119209289f); + + /* Initialize pState pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + /* Update filter coefficients */ + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + *pb += w * (*px++); + pb++; + + *pb += w * (*px++); + pb++; + + *pb += w * (*px++); + pb++; + + *pb += w * (*px++); + pb++; + + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + *pb += w * (*px++); + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + x0 = *pState; + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + S->energy = energy; + S->x0 = x0; + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + satrt of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Loop unrolling for (numTaps - 1u)/4 samples copy */ + tapCnt = (numTaps - 1u) >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Calculate remaining number of copies */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + while(blkCnt > 0u) + { + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize pCoeffs pointer */ + pb = pCoeffs; + + /* Read the sample from input buffer */ + in = *pSrc++; + + /* Update the energy calculation */ + energy -= x0 * x0; + energy += in * in; + + /* Set the accumulator to zero */ + sum = 0.0f; + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + sum += (*px++) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* The result in the accumulator is stored in the destination buffer. */ + *pOut++ = sum; + + /* Compute and store error */ + d = (float32_t) (*pRef++); + e = d - sum; + *pErr++ = e; + + /* Calculation of Weighting factor for updating filter coefficients */ + /* epsilon value 0.000000119209289f */ + w = (e * mu) / (energy + 0.000000119209289f); + + /* Initialize pState pointer */ + px = pState; + + /* Initialize pCcoeffs pointer */ + pb = pCoeffs; + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + *pb += w * (*px++); + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + x0 = *pState; + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + S->energy = energy; + S->x0 = x0; + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + satrt of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Copy (numTaps - 1u) samples */ + tapCnt = (numTaps - 1u); + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of LMS_NORM group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_f32.c index 8c2423c26..7621ca136 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_f32.c @@ -1,97 +1,97 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_init_f32.c -* -* Description: Floating-point NLMS filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS_NORM - * @{ - */ - - /** - * @brief Initialization function for floating-point normalized LMS filter. - * @param[in] *S points to an instance of the floating-point LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] *pCoeffs points to coefficient buffer. - * @param[in] *pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @return none. - * - * \par Description: - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * The initial filter coefficients serve as a starting point for the adaptive filter. - * pState points to an array of length numTaps+blockSize-1 samples, - * where blockSize is the number of input samples processed by each call to arm_lms_norm_f32(). - */ - -void arm_lms_norm_init_f32( - arm_lms_norm_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - float32_t mu, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps - 1 */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; - - /* Initialise Energy to zero */ - S->energy = 0.0f; - - /* Initialise x0 to zero */ - S->x0 = 0.0f; - -} - -/** - * @} end of LMS_NORM group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_norm_init_f32.c +* +* Description: Floating-point NLMS filter initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup LMS_NORM + * @{ + */ + + /** + * @brief Initialization function for floating-point normalized LMS filter. + * @param[in] *S points to an instance of the floating-point LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to coefficient buffer. + * @param[in] *pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @return none. + * + * \par Description: + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * The initial filter coefficients serve as a starting point for the adaptive filter. + * pState points to an array of length numTaps+blockSize-1 samples, + * where blockSize is the number of input samples processed by each call to arm_lms_norm_f32(). + */ + +void arm_lms_norm_init_f32( + arm_lms_norm_instance_f32 * S, + uint16_t numTaps, + float32_t * pCoeffs, + float32_t * pState, + float32_t mu, + uint32_t blockSize) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always blockSize + numTaps - 1 */ + memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(float32_t)); + + /* Assign state pointer */ + S->pState = pState; + + /* Assign Step size value */ + S->mu = mu; + + /* Initialise Energy to zero */ + S->energy = 0.0f; + + /* Initialise x0 to zero */ + S->x0 = 0.0f; + +} + +/** + * @} end of LMS_NORM group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q15.c index a30419d9a..758a578a4 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q15.c @@ -1,104 +1,104 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_init_q15.c -* -* Description: Q15 NLMS initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @addtogroup LMS_NORM - * @{ - */ - - /** - * @brief Initialization function for Q15 normalized LMS filter. - * @param[in] *S points to an instance of the Q15 normalized LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] *pCoeffs points to coefficient buffer. - * @param[in] *pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - * @return none. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * The initial filter coefficients serve as a starting point for the adaptive filter. - * pState points to the array of state variables and size of array is - * numTaps+blockSize-1 samples, where blockSize is the number of input samples processed - * by each call to arm_lms_norm_q15(). - */ - -void arm_lms_norm_init_q15( - arm_lms_norm_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - q15_t mu, - uint32_t blockSize, - uint8_t postShift) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps - 1 */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); - - /* Assign post Shift value applied to coefficients */ - S->postShift = postShift; - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; - - /* Initialize reciprocal pointer table */ - S->recipTable = armRecipTableQ15; - - /* Initialise Energy to zero */ - S->energy = 0; - - /* Initialise x0 to zero */ - S->x0 = 0; - -} - -/** - * @} end of LMS_NORM group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_norm_init_q15.c +* +* Description: Q15 NLMS initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" +#include "arm_common_tables.h" + +/** + * @addtogroup LMS_NORM + * @{ + */ + + /** + * @brief Initialization function for Q15 normalized LMS filter. + * @param[in] *S points to an instance of the Q15 normalized LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to coefficient buffer. + * @param[in] *pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + * @return none. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * The initial filter coefficients serve as a starting point for the adaptive filter. + * pState points to the array of state variables and size of array is + * numTaps+blockSize-1 samples, where blockSize is the number of input samples processed + * by each call to arm_lms_norm_q15(). + */ + +void arm_lms_norm_init_q15( + arm_lms_norm_instance_q15 * S, + uint16_t numTaps, + q15_t * pCoeffs, + q15_t * pState, + q15_t mu, + uint32_t blockSize, + uint8_t postShift) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always blockSize + numTaps - 1 */ + memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); + + /* Assign post Shift value applied to coefficients */ + S->postShift = postShift; + + /* Assign state pointer */ + S->pState = pState; + + /* Assign Step size value */ + S->mu = mu; + + /* Initialize reciprocal pointer table */ + S->recipTable = armRecipTableQ15; + + /* Initialise Energy to zero */ + S->energy = 0; + + /* Initialise x0 to zero */ + S->x0 = 0; + +} + +/** + * @} end of LMS_NORM group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q31.c index de28a767f..781201ef6 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q31.c @@ -1,103 +1,103 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_init_q31.c -* -* Description: Q31 NLMS initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @addtogroup LMS_NORM - * @{ - */ - - /** - * @brief Initialization function for Q31 normalized LMS filter. - * @param[in] *S points to an instance of the Q31 normalized LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] *pCoeffs points to coefficient buffer. - * @param[in] *pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - * @return none. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
   
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
- * 
- * The initial filter coefficients serve as a starting point for the adaptive filter. - * pState points to an array of length numTaps+blockSize-1 samples, - * where blockSize is the number of input samples processed by each call to arm_lms_norm_q31(). - */ - -void arm_lms_norm_init_q31( - arm_lms_norm_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - q31_t mu, - uint32_t blockSize, - uint8_t postShift) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps - 1 */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q31_t)); - - /* Assign post Shift value applied to coefficients */ - S->postShift = postShift; - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; - - /* Initialize reciprocal pointer table */ - S->recipTable = armRecipTableQ31; - - /* Initialise Energy to zero */ - S->energy = 0; - - /* Initialise x0 to zero */ - S->x0 = 0; - -} - -/** - * @} end of LMS_NORM group - */ +/*----------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_norm_init_q31.c +* +* Description: Q31 NLMS initialization function. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------*/ + +#include "arm_math.h" +#include "arm_common_tables.h" + +/** + * @addtogroup LMS_NORM + * @{ + */ + + /** + * @brief Initialization function for Q31 normalized LMS filter. + * @param[in] *S points to an instance of the Q31 normalized LMS filter structure. + * @param[in] numTaps number of filter coefficients. + * @param[in] *pCoeffs points to coefficient buffer. + * @param[in] *pState points to state buffer. + * @param[in] mu step size that controls filter coefficient updates. + * @param[in] blockSize number of samples to process. + * @param[in] postShift bit shift applied to coefficients. + * @return none. + * + * Description: + * \par + * pCoeffs points to the array of filter coefficients stored in time reversed order: + *
   
+ *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}   
+ * 
+ * The initial filter coefficients serve as a starting point for the adaptive filter. + * pState points to an array of length numTaps+blockSize-1 samples, + * where blockSize is the number of input samples processed by each call to arm_lms_norm_q31(). + */ + +void arm_lms_norm_init_q31( + arm_lms_norm_instance_q31 * S, + uint16_t numTaps, + q31_t * pCoeffs, + q31_t * pState, + q31_t mu, + uint32_t blockSize, + uint8_t postShift) +{ + /* Assign filter taps */ + S->numTaps = numTaps; + + /* Assign coefficient pointer */ + S->pCoeffs = pCoeffs; + + /* Clear state buffer and size is always blockSize + numTaps - 1 */ + memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q31_t)); + + /* Assign post Shift value applied to coefficients */ + S->postShift = postShift; + + /* Assign state pointer */ + S->pState = pState; + + /* Assign Step size value */ + S->mu = mu; + + /* Initialize reciprocal pointer table */ + S->recipTable = armRecipTableQ31; + + /* Initialise Energy to zero */ + S->energy = 0; + + /* Initialise x0 to zero */ + S->x0 = 0; + +} + +/** + * @} end of LMS_NORM group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q15.c index 98ea8a3d7..6417fe485 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q15.c @@ -1,386 +1,386 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_q15.c -* -* Description: Q15 NLMS filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS_NORM - * @{ - */ - -/** -* @brief Processing function for Q15 normalized LMS filter. -* @param[in] *S points to an instance of the Q15 normalized LMS filter structure. -* @param[in] *pSrc points to the block of input data. -* @param[in] *pRef points to the block of reference data. -* @param[out] *pOut points to the block of output data. -* @param[out] *pErr points to the block of error data. -* @param[in] blockSize number of samples to process. -* @return none. -* -* Scaling and Overflow Behavior: -* \par -* The function is implemented using a 64-bit internal accumulator. -* Both coefficients and state variables are represented in 1.15 format and -* multiplications yield a 2.30 result. The 2.30 intermediate results are -* accumulated in a 64-bit accumulator in 34.30 format. -* There is no risk of internal overflow with this approach and the full -* precision of intermediate multiplications is preserved. After all additions -* have been performed, the accumulator is truncated to 34.15 format by -* discarding low 15 bits. Lastly, the accumulator is saturated to yield a -* result in 1.15 format. -* -* \par -* In this filter, filter coefficients are updated for each sample and the updation of filter cofficients are saturted. -* - */ - -void arm_lms_norm_q15( - arm_lms_norm_instance_q15 * S, - q15_t * pSrc, - q15_t * pRef, - q15_t * pOut, - q15_t * pErr, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - q15_t mu = S->mu; /* Adaptive factor */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - q31_t energy; /* Energy of the input */ - q63_t acc; /* Accumulator */ - q15_t e = 0, d = 0; /* error, reference data sample */ - q15_t w = 0, in; /* weight factor and state */ - q15_t x0; /* temporary variable to hold input sample */ - uint32_t shift = (uint32_t) S->postShift + 1u; /* Shift to be applied to the output */ - q15_t errorXmu, oneByEnergy; /* Temporary variables to store error and mu product and reciprocal of energy */ - q15_t postShift; /* Post shift to be applied to weight after reciprocal calculation */ - q31_t coef; /* Teporary variable for coefficient */ - - energy = S->energy; - x0 = S->x0; - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy -= (((q31_t) x0 * (x0)) >> 15); - energy += (((q31_t) in * (in)) >> 15); - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - - /* Perform the multiply-accumulate */ - acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); - acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += (((q31_t) * px++ * (*pb++))); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.15 format */ - acc = __SSAT((acc >> (16u - shift)), 16u); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q15_t) acc; - - /* Compute and store error */ - d = *pRef++; - e = d - (q15_t) acc; - *pErr++ = e; - - /* Calculation of 1/energy */ - postShift = arm_recip_q15((q15_t) energy + DELTA_Q15, - &oneByEnergy, S->recipTable); - - /* Calculation of e * mu value */ - errorXmu = (q15_t) (((q31_t) e * mu) >> 15); - - /* Calculation of (e * mu) * (1/energy) value */ - acc = (((q31_t) errorXmu * oneByEnergy) >> (15 - postShift)); - - /* Weighting factor for the normalized version */ - w = (q15_t) __SSAT((q31_t) acc, 16); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Read the sample from state buffer */ - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Save energy and x0 values for the next frame */ - S->energy = (q15_t) energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Calculation of count for copying integer writes */ - tapCnt = (numTaps - 1u) >> 2; - - while(tapCnt > 0u) - { - - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - tapCnt--; - - } - - /* Calculation of count for remaining q15_t data */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy -= (((q31_t) x0 * (x0)) >> 15); - energy += (((q31_t) in * (in)) >> 15); - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += (((q31_t) * px++ * (*pb++))); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.15 format */ - acc = __SSAT((acc >> (16u - shift)), 16u); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q15_t) acc; - - /* Compute and store error */ - d = *pRef++; - e = d - (q15_t) acc; - *pErr++ = e; - - /* Calculation of 1/energy */ - postShift = arm_recip_q15((q15_t) energy + DELTA_Q15, - &oneByEnergy, S->recipTable); - - /* Calculation of e * mu value */ - errorXmu = (q15_t) (((q31_t) e * mu) >> 15); - - /* Calculation of (e * mu) * (1/energy) value */ - acc = (((q31_t) errorXmu * oneByEnergy) >> (15 - postShift)); - - /* Weighting factor for the normalized version */ - w = (q15_t) __SSAT((q31_t) acc, 16); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Read the sample from state buffer */ - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Save energy and x0 values for the next frame */ - S->energy = (q15_t) energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* copy (numTaps - 1u) data */ - tapCnt = (numTaps - 1u); - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - -/** - * @} end of LMS_NORM group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_norm_q15.c +* +* Description: Q15 NLMS filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup LMS_NORM + * @{ + */ + +/** +* @brief Processing function for Q15 normalized LMS filter. +* @param[in] *S points to an instance of the Q15 normalized LMS filter structure. +* @param[in] *pSrc points to the block of input data. +* @param[in] *pRef points to the block of reference data. +* @param[out] *pOut points to the block of output data. +* @param[out] *pErr points to the block of error data. +* @param[in] blockSize number of samples to process. +* @return none. +* +* Scaling and Overflow Behavior: +* \par +* The function is implemented using a 64-bit internal accumulator. +* Both coefficients and state variables are represented in 1.15 format and +* multiplications yield a 2.30 result. The 2.30 intermediate results are +* accumulated in a 64-bit accumulator in 34.30 format. +* There is no risk of internal overflow with this approach and the full +* precision of intermediate multiplications is preserved. After all additions +* have been performed, the accumulator is truncated to 34.15 format by +* discarding low 15 bits. Lastly, the accumulator is saturated to yield a +* result in 1.15 format. +* +* \par +* In this filter, filter coefficients are updated for each sample and the updation of filter cofficients are saturted. +* + */ + +void arm_lms_norm_q15( + arm_lms_norm_instance_q15 * S, + q15_t * pSrc, + q15_t * pRef, + q15_t * pOut, + q15_t * pErr, + uint32_t blockSize) +{ + q15_t *pState = S->pState; /* State pointer */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q15_t *pStateCurnt; /* Points to the current sample of the state */ + q15_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ + q15_t mu = S->mu; /* Adaptive factor */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + uint32_t tapCnt, blkCnt; /* Loop counters */ + q31_t energy; /* Energy of the input */ + q63_t acc; /* Accumulator */ + q15_t e = 0, d = 0; /* error, reference data sample */ + q15_t w = 0, in; /* weight factor and state */ + q15_t x0; /* temporary variable to hold input sample */ + uint32_t shift = (uint32_t) S->postShift + 1u; /* Shift to be applied to the output */ + q15_t errorXmu, oneByEnergy; /* Temporary variables to store error and mu product and reciprocal of energy */ + q15_t postShift; /* Post shift to be applied to weight after reciprocal calculation */ + q31_t coef; /* Teporary variable for coefficient */ + + energy = S->energy; + x0 = S->x0; + + /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + while(blkCnt > 0u) + { + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Read the sample from input buffer */ + in = *pSrc++; + + /* Update the energy calculation */ + energy -= (((q31_t) x0 * (x0)) >> 15); + energy += (((q31_t) in * (in)) >> 15); + + /* Set the accumulator to zero */ + acc = 0; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + while(tapCnt > 0u) + { + + /* Perform the multiply-accumulate */ + acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); + acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + acc += (((q31_t) * px++ * (*pb++))); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Converting the result to 1.15 format */ + acc = __SSAT((acc >> (16u - shift)), 16u); + + /* Store the result from accumulator into the destination buffer. */ + *pOut++ = (q15_t) acc; + + /* Compute and store error */ + d = *pRef++; + e = d - (q15_t) acc; + *pErr++ = e; + + /* Calculation of 1/energy */ + postShift = arm_recip_q15((q15_t) energy + DELTA_Q15, + &oneByEnergy, S->recipTable); + + /* Calculation of e * mu value */ + errorXmu = (q15_t) (((q31_t) e * mu) >> 15); + + /* Calculation of (e * mu) * (1/energy) value */ + acc = (((q31_t) errorXmu * oneByEnergy) >> (15 - postShift)); + + /* Weighting factor for the normalized version */ + w = (q15_t) __SSAT((q31_t) acc, 16); + + /* Initialize pState pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + /* Update filter coefficients */ + while(tapCnt > 0u) + { + coef = *pb + (((q31_t) w * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + coef = *pb + (((q31_t) w * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + coef = *pb + (((q31_t) w * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + coef = *pb + (((q31_t) w * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + coef = *pb + (((q31_t) w * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Read the sample from state buffer */ + x0 = *pState; + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1u; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Save energy and x0 values for the next frame */ + S->energy = (q15_t) energy; + S->x0 = x0; + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + satrt of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Calculation of count for copying integer writes */ + tapCnt = (numTaps - 1u) >> 2; + + while(tapCnt > 0u) + { + + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + + tapCnt--; + + } + + /* Calculation of count for remaining q15_t data */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + while(blkCnt > 0u) + { + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize pCoeffs pointer */ + pb = pCoeffs; + + /* Read the sample from input buffer */ + in = *pSrc++; + + /* Update the energy calculation */ + energy -= (((q31_t) x0 * (x0)) >> 15); + energy += (((q31_t) in * (in)) >> 15); + + /* Set the accumulator to zero */ + acc = 0; + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + acc += (((q31_t) * px++ * (*pb++))); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Converting the result to 1.15 format */ + acc = __SSAT((acc >> (16u - shift)), 16u); + + /* Store the result from accumulator into the destination buffer. */ + *pOut++ = (q15_t) acc; + + /* Compute and store error */ + d = *pRef++; + e = d - (q15_t) acc; + *pErr++ = e; + + /* Calculation of 1/energy */ + postShift = arm_recip_q15((q15_t) energy + DELTA_Q15, + &oneByEnergy, S->recipTable); + + /* Calculation of e * mu value */ + errorXmu = (q15_t) (((q31_t) e * mu) >> 15); + + /* Calculation of (e * mu) * (1/energy) value */ + acc = (((q31_t) errorXmu * oneByEnergy) >> (15 - postShift)); + + /* Weighting factor for the normalized version */ + w = (q15_t) __SSAT((q31_t) acc, 16); + + /* Initialize pState pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + coef = *pb + (((q31_t) w * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Read the sample from state buffer */ + x0 = *pState; + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1u; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Save energy and x0 values for the next frame */ + S->energy = (q15_t) energy; + S->x0 = x0; + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + satrt of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* copy (numTaps - 1u) data */ + tapCnt = (numTaps - 1u); + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + +/** + * @} end of LMS_NORM group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q31.c index c35a72f68..05e732961 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q31.c @@ -1,404 +1,404 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_q31.c -* -* Description: Processing function for the Q31 NLMS filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS_NORM - * @{ - */ - -/** -* @brief Processing function for Q31 normalized LMS filter. -* @param[in] *S points to an instance of the Q31 normalized LMS filter structure. -* @param[in] *pSrc points to the block of input data. -* @param[in] *pRef points to the block of reference data. -* @param[out] *pOut points to the block of output data. -* @param[out] *pErr points to the block of error data. -* @param[in] blockSize number of samples to process. -* @return none. -* -* Scaling and Overflow Behavior: -* \par -* The function is implemented using an internal 64-bit accumulator. -* The accumulator has a 2.62 format and maintains full precision of the intermediate -* multiplication results but provides only a single guard bit. -* Thus, if the accumulator result overflows it wraps around rather than clip. -* In order to avoid overflows completely the input signal must be scaled down by -* log2(numTaps) bits. The reference signal should not be scaled down. -* After all multiply-accumulates are performed, the 2.62 accumulator is shifted -* and saturated to 1.31 format to yield the final result. -* The output signal and error signal are in 1.31 format. -* -* \par -* In this filter, filter coefficients are updated for each sample and the -* updation of filter cofficients are saturted. -* -*/ - -void arm_lms_norm_q31( - arm_lms_norm_instance_q31 * S, - q31_t * pSrc, - q31_t * pRef, - q31_t * pOut, - q31_t * pErr, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - q31_t mu = S->mu; /* Adaptive factor */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - q63_t energy; /* Energy of the input */ - q63_t acc; /* Accumulator */ - q31_t e = 0, d = 0; /* error, reference data sample */ - q31_t w = 0, in; /* weight factor and state */ - q31_t x0; /* temporary variable to hold input sample */ - uint32_t shift = 32u - ((uint32_t) S->postShift + 1u); /* Shift to be applied to the output */ - q31_t errorXmu, oneByEnergy; /* Temporary variables to store error and mu product and reciprocal of energy */ - q31_t postShift; /* Post shift to be applied to weight after reciprocal calculation */ - q31_t coef; /* Temporary variable for coef */ - - energy = S->energy; - x0 = S->x0; - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - while(blkCnt > 0u) - { - - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy = (q31_t) ((((q63_t) energy << 32) - - (((q63_t) x0 * x0) << 1)) >> 32); - energy = (q31_t) (((((q63_t) in * in) << 1) + (energy << 32)) >> 32); - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += ((q63_t) (*px++)) * (*pb++); - acc += ((q63_t) (*px++)) * (*pb++); - acc += ((q63_t) (*px++)) * (*pb++); - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.31 format */ - acc = (q31_t) (acc >> shift); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q31_t) acc; - - /* Compute and store error */ - d = *pRef++; - e = d - (q31_t) acc; - *pErr++ = e; - - /* Calculates the reciprocal of energy */ - postShift = arm_recip_q31(energy + DELTA_Q31, - &oneByEnergy, &S->recipTable[0]); - - /* Calculation of product of (e * mu) */ - errorXmu = (q31_t) (((q63_t) e * mu) >> 31); - - /* Weighting factor for the normalized version */ - w = clip_q63_to_q31(((q63_t) errorXmu * oneByEnergy) >> (31 - postShift)); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - - /* coef is in 2.30 format */ - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - /* get coef in 1.31 format by left shifting */ - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - /* update coefficient buffer to next coefficient */ - pb++; - - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Read the sample from state buffer */ - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Save energy and x0 values for the next frame */ - S->energy = (q31_t) energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Loop unrolling for (numTaps - 1u) samples copy */ - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy = - (q31_t) ((((q63_t) energy << 32) - (((q63_t) x0 * x0) << 1)) >> 32); - energy = (q31_t) (((((q63_t) in * in) << 1) + (energy << 32)) >> 32); - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.31 format */ - acc = (q31_t) (acc >> shift); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q31_t) acc; - - /* Compute and store error */ - d = *pRef++; - e = d - (q31_t) acc; - *pErr++ = e; - - /* Calculates the reciprocal of energy */ - postShift = - arm_recip_q31(energy + DELTA_Q31, &oneByEnergy, &S->recipTable[0]); - - /* Calculation of product of (e * mu) */ - errorXmu = (q31_t) (((q63_t) e * mu) >> 31); - - /* Weighting factor for the normalized version */ - w = clip_q63_to_q31(((q63_t) errorXmu * oneByEnergy) >> (31 - postShift)); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - /* coef is in 2.30 format */ - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - /* get coef in 1.31 format by left shifting */ - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - /* update coefficient buffer to next coefficient */ - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Read the sample from state buffer */ - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Save energy and x0 values for the next frame */ - S->energy = (q31_t) energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - start of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Loop for (numTaps - 1u) samples copy */ - tapCnt = (numTaps - 1u); - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of LMS_NORM group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_norm_q31.c +* +* Description: Processing function for the Q31 NLMS filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup LMS_NORM + * @{ + */ + +/** +* @brief Processing function for Q31 normalized LMS filter. +* @param[in] *S points to an instance of the Q31 normalized LMS filter structure. +* @param[in] *pSrc points to the block of input data. +* @param[in] *pRef points to the block of reference data. +* @param[out] *pOut points to the block of output data. +* @param[out] *pErr points to the block of error data. +* @param[in] blockSize number of samples to process. +* @return none. +* +* Scaling and Overflow Behavior: +* \par +* The function is implemented using an internal 64-bit accumulator. +* The accumulator has a 2.62 format and maintains full precision of the intermediate +* multiplication results but provides only a single guard bit. +* Thus, if the accumulator result overflows it wraps around rather than clip. +* In order to avoid overflows completely the input signal must be scaled down by +* log2(numTaps) bits. The reference signal should not be scaled down. +* After all multiply-accumulates are performed, the 2.62 accumulator is shifted +* and saturated to 1.31 format to yield the final result. +* The output signal and error signal are in 1.31 format. +* +* \par +* In this filter, filter coefficients are updated for each sample and the +* updation of filter cofficients are saturted. +* +*/ + +void arm_lms_norm_q31( + arm_lms_norm_instance_q31 * S, + q31_t * pSrc, + q31_t * pRef, + q31_t * pOut, + q31_t * pErr, + uint32_t blockSize) +{ + q31_t *pState = S->pState; /* State pointer */ + q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *pStateCurnt; /* Points to the current sample of the state */ + q31_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ + q31_t mu = S->mu; /* Adaptive factor */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + uint32_t tapCnt, blkCnt; /* Loop counters */ + q63_t energy; /* Energy of the input */ + q63_t acc; /* Accumulator */ + q31_t e = 0, d = 0; /* error, reference data sample */ + q31_t w = 0, in; /* weight factor and state */ + q31_t x0; /* temporary variable to hold input sample */ + uint32_t shift = 32u - ((uint32_t) S->postShift + 1u); /* Shift to be applied to the output */ + q31_t errorXmu, oneByEnergy; /* Temporary variables to store error and mu product and reciprocal of energy */ + q31_t postShift; /* Post shift to be applied to weight after reciprocal calculation */ + q31_t coef; /* Temporary variable for coef */ + + energy = S->energy; + x0 = S->x0; + + /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + while(blkCnt > 0u) + { + + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Read the sample from input buffer */ + in = *pSrc++; + + /* Update the energy calculation */ + energy = (q31_t) ((((q63_t) energy << 32) - + (((q63_t) x0 * x0) << 1)) >> 32); + energy = (q31_t) (((((q63_t) in * in) << 1) + (energy << 32)) >> 32); + + /* Set the accumulator to zero */ + acc = 0; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + acc += ((q63_t) (*px++)) * (*pb++); + acc += ((q63_t) (*px++)) * (*pb++); + acc += ((q63_t) (*px++)) * (*pb++); + acc += ((q63_t) (*px++)) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + acc += ((q63_t) (*px++)) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Converting the result to 1.31 format */ + acc = (q31_t) (acc >> shift); + + /* Store the result from accumulator into the destination buffer. */ + *pOut++ = (q31_t) acc; + + /* Compute and store error */ + d = *pRef++; + e = d - (q31_t) acc; + *pErr++ = e; + + /* Calculates the reciprocal of energy */ + postShift = arm_recip_q31(energy + DELTA_Q31, + &oneByEnergy, &S->recipTable[0]); + + /* Calculation of product of (e * mu) */ + errorXmu = (q31_t) (((q63_t) e * mu) >> 31); + + /* Weighting factor for the normalized version */ + w = clip_q63_to_q31(((q63_t) errorXmu * oneByEnergy) >> (31 - postShift)); + + /* Initialize pState pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + /* Update filter coefficients */ + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + + /* coef is in 2.30 format */ + coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); + /* get coef in 1.31 format by left shifting */ + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + /* update coefficient buffer to next coefficient */ + pb++; + + coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + pb++; + + coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + pb++; + + coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Read the sample from state buffer */ + x0 = *pState; + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Save energy and x0 values for the next frame */ + S->energy = (q31_t) energy; + S->x0 = x0; + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + satrt of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Loop unrolling for (numTaps - 1u) samples copy */ + tapCnt = (numTaps - 1u) >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Calculate remaining number of copies */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + while(blkCnt > 0u) + { + + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize pCoeffs pointer */ + pb = pCoeffs; + + /* Read the sample from input buffer */ + in = *pSrc++; + + /* Update the energy calculation */ + energy = + (q31_t) ((((q63_t) energy << 32) - (((q63_t) x0 * x0) << 1)) >> 32); + energy = (q31_t) (((((q63_t) in * in) << 1) + (energy << 32)) >> 32); + + /* Set the accumulator to zero */ + acc = 0; + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + acc += ((q63_t) (*px++)) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Converting the result to 1.31 format */ + acc = (q31_t) (acc >> shift); + + /* Store the result from accumulator into the destination buffer. */ + *pOut++ = (q31_t) acc; + + /* Compute and store error */ + d = *pRef++; + e = d - (q31_t) acc; + *pErr++ = e; + + /* Calculates the reciprocal of energy */ + postShift = + arm_recip_q31(energy + DELTA_Q31, &oneByEnergy, &S->recipTable[0]); + + /* Calculation of product of (e * mu) */ + errorXmu = (q31_t) (((q63_t) e * mu) >> 31); + + /* Weighting factor for the normalized version */ + w = clip_q63_to_q31(((q63_t) errorXmu * oneByEnergy) >> (31 - postShift)); + + /* Initialize pState pointer */ + px = pState; + + /* Initialize coeff pointer */ + pb = (pCoeffs); + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + /* coef is in 2.30 format */ + coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); + /* get coef in 1.31 format by left shifting */ + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + /* update coefficient buffer to next coefficient */ + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Read the sample from state buffer */ + x0 = *pState; + + /* Advance state pointer by 1 for the next sample */ + pState = pState + 1; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Save energy and x0 values for the next frame */ + S->energy = (q31_t) energy; + S->x0 = x0; + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + start of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Loop for (numTaps - 1u) samples copy */ + tapCnt = (numTaps - 1u); + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of LMS_NORM group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_q15.c index 714424825..eb62f1fc2 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_q15.c @@ -1,331 +1,331 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_q15.c -* -* Description: Processing function for the Q15 LMS filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS - * @{ - */ - - /** - * @brief Processing function for Q15 LMS filter. - * @param[in] *S points to an instance of the Q15 LMS filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[in] *pRef points to the block of reference data. - * @param[out] *pOut points to the block of output data. - * @param[out] *pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - * @return none. - * - * \par Scaling and Overflow Behavior: - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - * - * \par - * In this filter, filter coefficients are updated for each sample and the updation of filter cofficients are saturted. - * - */ - -void arm_lms_q15( - const arm_lms_instance_q15 * S, - q15_t * pSrc, - q15_t * pRef, - q15_t * pOut, - q15_t * pErr, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t mu = S->mu; /* Adaptive factor */ - q15_t *px; /* Temporary pointer for state */ - q15_t *pb; /* Temporary pointer for coefficient buffer */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - q63_t acc; /* Accumulator */ - q15_t e = 0; /* error of data sample */ - q15_t alpha; /* Intermediate constant for taps update */ - uint32_t shift = S->postShift + 1u; /* Shift to be applied to the output */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t coef; /* Teporary variable for coefficient */ - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Initializing blkCnt with blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2u; - - while(tapCnt > 0u) - { - /* acc += b[N] * x[n-N] + b[N-1] * x[n-N-1] */ - /* Perform the multiply-accumulate */ - acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); - acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += (q63_t) (((q31_t) (*px++) * (*pb++))); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.15 format and saturate the output */ - acc = __SSAT((acc >> (16 - shift)), 16); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q15_t) acc; - - /* Compute and store error */ - e = *pRef++ - (q15_t) acc; - - *pErr++ = (q15_t) e; - - /* Compute alpha i.e. intermediate constant for taps update */ - alpha = (q15_t) (((q31_t) e * (mu)) >> 15); - - /* Initialize state pointer */ - /* Advance state pointer by 1 for the next sample */ - px = pState++; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2u; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Decrement the loop counter */ - blkCnt--; - - } - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Calculation of count for copying integer writes */ - tapCnt = (numTaps - 1u) >> 2; - - while(tapCnt > 0u) - { - - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - tapCnt--; - - } - - /* Calculation of count for remaining q15_t data */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += (q63_t) ((q31_t) (*px++) * (*pb++)); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.15 format and saturate the output */ - acc = __SSAT((acc >> (16 - shift)), 16); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q15_t) acc; - - /* Compute and store error */ - e = *pRef++ - (q15_t) acc; - - *pErr++ = (q15_t) e; - - /* Compute alpha i.e. intermediate constant for taps update */ - alpha = (q15_t) (((q31_t) e * (mu)) >> 15); - - /* Initialize pState pointer */ - /* Advance state pointer by 1 for the next sample */ - px = pState++; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb++ += (q15_t) (((q31_t) alpha * (*px++)) >> 15); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Decrement the loop counter */ - blkCnt--; - - } - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - start of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Copy (numTaps - 1u) samples */ - tapCnt = (numTaps - 1u); - - /* Copy the data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of LMS group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_q15.c +* +* Description: Processing function for the Q15 LMS filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup LMS + * @{ + */ + + /** + * @brief Processing function for Q15 LMS filter. + * @param[in] *S points to an instance of the Q15 LMS filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[in] *pRef points to the block of reference data. + * @param[out] *pOut points to the block of output data. + * @param[out] *pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + * @return none. + * + * \par Scaling and Overflow Behavior: + * The function is implemented using a 64-bit internal accumulator. + * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. + * Lastly, the accumulator is saturated to yield a result in 1.15 format. + * + * \par + * In this filter, filter coefficients are updated for each sample and the updation of filter cofficients are saturted. + * + */ + +void arm_lms_q15( + const arm_lms_instance_q15 * S, + q15_t * pSrc, + q15_t * pRef, + q15_t * pOut, + q15_t * pErr, + uint32_t blockSize) +{ + q15_t *pState = S->pState; /* State pointer */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q15_t *pStateCurnt; /* Points to the current sample of the state */ + q15_t mu = S->mu; /* Adaptive factor */ + q15_t *px; /* Temporary pointer for state */ + q15_t *pb; /* Temporary pointer for coefficient buffer */ + uint32_t tapCnt, blkCnt; /* Loop counters */ + q63_t acc; /* Accumulator */ + q15_t e = 0; /* error of data sample */ + q15_t alpha; /* Intermediate constant for taps update */ + uint32_t shift = S->postShift + 1u; /* Shift to be applied to the output */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t coef; /* Teporary variable for coefficient */ + + /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Initializing blkCnt with blockSize */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coefficient pointer */ + pb = pCoeffs; + + /* Set the accumulator to zero */ + acc = 0; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2u; + + while(tapCnt > 0u) + { + /* acc += b[N] * x[n-N] + b[N-1] * x[n-N-1] */ + /* Perform the multiply-accumulate */ + acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); + acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + acc += (q63_t) (((q31_t) (*px++) * (*pb++))); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Converting the result to 1.15 format and saturate the output */ + acc = __SSAT((acc >> (16 - shift)), 16); + + /* Store the result from accumulator into the destination buffer. */ + *pOut++ = (q15_t) acc; + + /* Compute and store error */ + e = *pRef++ - (q15_t) acc; + + *pErr++ = (q15_t) e; + + /* Compute alpha i.e. intermediate constant for taps update */ + alpha = (q15_t) (((q31_t) e * (mu)) >> 15); + + /* Initialize state pointer */ + /* Advance state pointer by 1 for the next sample */ + px = pState++; + + /* Initialize coefficient pointer */ + pb = pCoeffs; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2u; + + /* Update filter coefficients */ + while(tapCnt > 0u) + { + coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); + *pb++ = (q15_t) __SSAT((coef), 16); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Decrement the loop counter */ + blkCnt--; + + } + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + satrt of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Calculation of count for copying integer writes */ + tapCnt = (numTaps - 1u) >> 2; + + while(tapCnt > 0u) + { + + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; + + tapCnt--; + + } + + /* Calculation of count for remaining q15_t data */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize pCoeffs pointer */ + pb = pCoeffs; + + /* Set the accumulator to zero */ + acc = 0; + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + acc += (q63_t) ((q31_t) (*px++) * (*pb++)); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Converting the result to 1.15 format and saturate the output */ + acc = __SSAT((acc >> (16 - shift)), 16); + + /* Store the result from accumulator into the destination buffer. */ + *pOut++ = (q15_t) acc; + + /* Compute and store error */ + e = *pRef++ - (q15_t) acc; + + *pErr++ = (q15_t) e; + + /* Compute alpha i.e. intermediate constant for taps update */ + alpha = (q15_t) (((q31_t) e * (mu)) >> 15); + + /* Initialize pState pointer */ + /* Advance state pointer by 1 for the next sample */ + px = pState++; + + /* Initialize pCoeffs pointer */ + pb = pCoeffs; + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + *pb++ += (q15_t) (((q31_t) alpha * (*px++)) >> 15); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Decrement the loop counter */ + blkCnt--; + + } + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + start of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Copy (numTaps - 1u) samples */ + tapCnt = (numTaps - 1u); + + /* Copy the data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of LMS group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_q31.c index 0c9ca3ef6..dced45214 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/FilteringFunctions/arm_lms_q31.c @@ -1,347 +1,347 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_lms_q31.c -* -* Description: Processing function for the Q31 LMS filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS - * @{ - */ - - /** - * @brief Processing function for Q31 LMS filter. - * @param[in] *S points to an instance of the Q15 LMS filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[in] *pRef points to the block of reference data. - * @param[out] *pOut points to the block of output data. - * @param[out] *pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - * @return none. - * - * \par Scaling and Overflow Behavior: - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate - * multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clips. - * In order to avoid overflows completely the input signal must be scaled down by - * log2(numTaps) bits. - * The reference signal should not be scaled down. - * After all multiply-accumulates are performed, the 2.62 accumulator is shifted - * and saturated to 1.31 format to yield the final result. - * The output signal and error signal are in 1.31 format. - * - * \par - * In this filter, filter coefficients are updated for each sample and the updation of filter cofficients are saturted. - */ - -void arm_lms_q31( - const arm_lms_instance_q31 * S, - q31_t * pSrc, - q31_t * pRef, - q31_t * pOut, - q31_t * pErr, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t mu = S->mu; /* Adaptive factor */ - q31_t *px; /* Temporary pointer for state */ - q31_t *pb; /* Temporary pointer for coefficient buffer */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - q63_t acc; /* Accumulator */ - q31_t e = 0; /* error of data sample */ - q31_t alpha; /* Intermediate constant for taps update */ - uint8_t shift = (uint8_t) (32u - (S->postShift + 1u)); /* Shift to be applied to the output */ - q31_t coef; /* Temporary variable for coef */ - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Initializing blkCnt with blockSize */ - blkCnt = blockSize; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - /* acc += b[N] * x[n-N] */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* acc += b[N-1] * x[n-N-1] */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* acc += b[N-2] * x[n-N-2] */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* acc += b[N-3] * x[n-N-3] */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.31 format */ - /* Store the result from accumulator into the destination buffer. */ - acc = (q31_t) (acc >> shift); - - *pOut++ = (q31_t) acc; - - /* Compute and store error */ - e = *pRef++ - (q31_t) acc; - - *pErr++ = (q31_t) e; - - /* Compute alpha i.e. intermediate constant for taps update */ - alpha = (q31_t) (((q63_t) e * mu) >> 31); - - /* Initialize state pointer */ - /* Advance state pointer by 1 for the next sample */ - px = pState++; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - /* coef is in 2.30 format */ - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - /* get coef in 1.31 format by left shifting */ - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - /* update coefficient buffer to next coefficient */ - pb++; - - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Loop unrolling for (numTaps - 1u) samples copy */ - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.31 format */ - /* Store the result from accumulator into the destination buffer. */ - acc = (q31_t) (acc >> shift); - - *pOut++ = (q31_t) acc; - - /* Compute and store error */ - e = *pRef++ - (q31_t) acc; - - *pErr++ = (q31_t) e; - - /* Weighting factor for the LMS version */ - alpha = (q31_t) (((q63_t) e * mu) >> 31); - - /* Initialize pState pointer */ - /* Advance state pointer by 1 for the next sample */ - px = pState++; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - *pb += (coef << 1u); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - start of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Copy (numTaps - 1u) samples */ - tapCnt = (numTaps - 1u); - - /* Copy the data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of LMS group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_lms_q31.c +* +* Description: Processing function for the Q31 LMS filter. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" +/** + * @ingroup groupFilters + */ + +/** + * @addtogroup LMS + * @{ + */ + + /** + * @brief Processing function for Q31 LMS filter. + * @param[in] *S points to an instance of the Q15 LMS filter structure. + * @param[in] *pSrc points to the block of input data. + * @param[in] *pRef points to the block of reference data. + * @param[out] *pOut points to the block of output data. + * @param[out] *pErr points to the block of error data. + * @param[in] blockSize number of samples to process. + * @return none. + * + * \par Scaling and Overflow Behavior: + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate + * multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around rather than clips. + * In order to avoid overflows completely the input signal must be scaled down by + * log2(numTaps) bits. + * The reference signal should not be scaled down. + * After all multiply-accumulates are performed, the 2.62 accumulator is shifted + * and saturated to 1.31 format to yield the final result. + * The output signal and error signal are in 1.31 format. + * + * \par + * In this filter, filter coefficients are updated for each sample and the updation of filter cofficients are saturted. + */ + +void arm_lms_q31( + const arm_lms_instance_q31 * S, + q31_t * pSrc, + q31_t * pRef, + q31_t * pOut, + q31_t * pErr, + uint32_t blockSize) +{ + q31_t *pState = S->pState; /* State pointer */ + uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ + q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ + q31_t *pStateCurnt; /* Points to the current sample of the state */ + q31_t mu = S->mu; /* Adaptive factor */ + q31_t *px; /* Temporary pointer for state */ + q31_t *pb; /* Temporary pointer for coefficient buffer */ + uint32_t tapCnt, blkCnt; /* Loop counters */ + q63_t acc; /* Accumulator */ + q31_t e = 0; /* error of data sample */ + q31_t alpha; /* Intermediate constant for taps update */ + uint8_t shift = (uint8_t) (32u - (S->postShift + 1u)); /* Shift to be applied to the output */ + q31_t coef; /* Temporary variable for coef */ + + /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ + /* pStateCurnt points to the location where the new input data should be written */ + pStateCurnt = &(S->pState[(numTaps - 1u)]); + + /* Initializing blkCnt with blockSize */ + blkCnt = blockSize; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + while(blkCnt > 0u) + { + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Initialize state pointer */ + px = pState; + + /* Initialize coefficient pointer */ + pb = pCoeffs; + + /* Set the accumulator to zero */ + acc = 0; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + /* acc += b[N] * x[n-N] */ + acc += ((q63_t) (*px++)) * (*pb++); + + /* acc += b[N-1] * x[n-N-1] */ + acc += ((q63_t) (*px++)) * (*pb++); + + /* acc += b[N-2] * x[n-N-2] */ + acc += ((q63_t) (*px++)) * (*pb++); + + /* acc += b[N-3] * x[n-N-3] */ + acc += ((q63_t) (*px++)) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + acc += ((q63_t) (*px++)) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Converting the result to 1.31 format */ + /* Store the result from accumulator into the destination buffer. */ + acc = (q31_t) (acc >> shift); + + *pOut++ = (q31_t) acc; + + /* Compute and store error */ + e = *pRef++ - (q31_t) acc; + + *pErr++ = (q31_t) e; + + /* Compute alpha i.e. intermediate constant for taps update */ + alpha = (q31_t) (((q63_t) e * mu) >> 31); + + /* Initialize state pointer */ + /* Advance state pointer by 1 for the next sample */ + px = pState++; + + /* Initialize coefficient pointer */ + pb = pCoeffs; + + /* Loop unrolling. Process 4 taps at a time. */ + tapCnt = numTaps >> 2; + + /* Update filter coefficients */ + while(tapCnt > 0u) + { + /* coef is in 2.30 format */ + coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); + /* get coef in 1.31 format by left shifting */ + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + /* update coefficient buffer to next coefficient */ + pb++; + + coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + pb++; + + coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + pb++; + + coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* If the filter length is not a multiple of 4, compute the remaining filter taps */ + tapCnt = numTaps % 0x4u; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); + *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + satrt of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Loop unrolling for (numTaps - 1u) samples copy */ + tapCnt = (numTaps - 1u) >> 2u; + + /* copy data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Calculate remaining number of copies */ + tapCnt = (numTaps - 1u) % 0x4u; + + /* Copy the remaining q31_t data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + while(blkCnt > 0u) + { + /* Copy the new input sample into the state buffer */ + *pStateCurnt++ = *pSrc++; + + /* Initialize pState pointer */ + px = pState; + + /* Initialize pCoeffs pointer */ + pb = pCoeffs; + + /* Set the accumulator to zero */ + acc = 0; + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + acc += ((q63_t) (*px++)) * (*pb++); + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Converting the result to 1.31 format */ + /* Store the result from accumulator into the destination buffer. */ + acc = (q31_t) (acc >> shift); + + *pOut++ = (q31_t) acc; + + /* Compute and store error */ + e = *pRef++ - (q31_t) acc; + + *pErr++ = (q31_t) e; + + /* Weighting factor for the LMS version */ + alpha = (q31_t) (((q63_t) e * mu) >> 31); + + /* Initialize pState pointer */ + /* Advance state pointer by 1 for the next sample */ + px = pState++; + + /* Initialize pCoeffs pointer */ + pb = pCoeffs; + + /* Loop over numTaps number of values */ + tapCnt = numTaps; + + while(tapCnt > 0u) + { + /* Perform the multiply-accumulate */ + coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); + *pb += (coef << 1u); + pb++; + + /* Decrement the loop counter */ + tapCnt--; + } + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Processing is complete. Now copy the last numTaps - 1 samples to the + start of the state buffer. This prepares the state buffer for the + next function call. */ + + /* Points to the start of the pState buffer */ + pStateCurnt = S->pState; + + /* Copy (numTaps - 1u) samples */ + tapCnt = (numTaps - 1u); + + /* Copy the data */ + while(tapCnt > 0u) + { + *pStateCurnt++ = *pState++; + + /* Decrement the loop counter */ + tapCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of LMS group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_f32.c index 32eb69c41..23348a1ec 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_f32.c @@ -1,154 +1,154 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_add_f32.c -* -* Description: Floating-point matrix addition -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixAdd Matrix Addition - * - * Adds two matrices. - * \image html MatrixAddition.gif "Addition of two 3 x 3 matrices" - * - * The functions check to make sure that - * pSrcA, pSrcB, and pDst have the same - * number of rows and columns. - */ - -/** - * @addtogroup MatrixAdd - * @{ - */ - - -/** - * @brief Floating-point matrix addition. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - -arm_status arm_mat_add_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - float32_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix addition */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop unrolling */ - blkCnt = numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add and then store the results in the destination buffer. */ - *pOut++ = (*pIn1++) + (*pIn2++); - *pOut++ = (*pIn1++) + (*pIn2++); - *pOut++ = (*pIn1++) + (*pIn2++); - *pOut++ = (*pIn1++) + (*pIn2++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add and then store the results in the destination buffer. */ - *pOut++ = (*pIn1++) + (*pIn2++); - - /* Decrement the loop counter */ - blkCnt--; - } - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixAdd group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_add_f32.c +* +* Description: Floating-point matrix addition +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @defgroup MatrixAdd Matrix Addition + * + * Adds two matrices. + * \image html MatrixAddition.gif "Addition of two 3 x 3 matrices" + * + * The functions check to make sure that + * pSrcA, pSrcB, and pDst have the same + * number of rows and columns. + */ + +/** + * @addtogroup MatrixAdd + * @{ + */ + + +/** + * @brief Floating-point matrix addition. + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + +arm_status arm_mat_add_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst) +{ + float32_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ + float32_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ + float32_t *pOut = pDst->pData; /* output data matrix pointer */ + uint32_t numSamples; /* total number of elements in the matrix */ + uint32_t blkCnt; /* loop counters */ + arm_status status; /* status of matrix addition */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrcA->numRows != pSrcB->numRows) || + (pSrcA->numCols != pSrcB->numCols) || + (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + + /* Total number of samples in the input matrix */ + numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Loop unrolling */ + blkCnt = numSamples >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) + B(m,n) */ + /* Add and then store the results in the destination buffer. */ + *pOut++ = (*pIn1++) + (*pIn2++); + *pOut++ = (*pIn1++) + (*pIn2++); + *pOut++ = (*pIn1++) + (*pIn2++); + *pOut++ = (*pIn1++) + (*pIn2++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the numSamples is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = numSamples % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = numSamples; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) + B(m,n) */ + /* Add and then store the results in the destination buffer. */ + *pOut++ = (*pIn1++) + (*pIn2++); + + /* Decrement the loop counter */ + blkCnt--; + } + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixAdd group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q15.c index e16460061..b96feb4b7 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q15.c @@ -1,158 +1,158 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_add_q15.c -* -* Description: Q15 matrix addition -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixAdd - * @{ - */ - -/** - * @brief Q15 matrix addition. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -arm_status arm_mat_add_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst) -{ - q15_t *pInA = pSrcA->pData; /* input data matrix pointer A */ - q15_t *pInB = pSrcB->pData; /* input data matrix pointer B */ - q15_t *pOut = pDst->pData; /* output data matrix pointer */ - uint16_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix addition */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Total number of samples in the input matrix */ - numSamples = (uint16_t) (pSrcA->numRows * pSrcA->numCols); - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop unrolling */ - blkCnt = (uint32_t) numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, Saturate and then store the results in the destination buffer. */ - *__SIMD32(pOut)++ = __QADD16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); - *__SIMD32(pOut)++ = __QADD16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) numSamples % 0x4u; - - /* q15 pointers of input and output are initialized */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, Saturate and then store the results in the destination buffer. */ - *pOut++ = (q15_t) __QADD16(*pInA++, *pInB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = (uint32_t) numSamples; - - - /* q15 pointers of input and output are initialized */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, Saturate and then store the results in the destination buffer. */ - *pOut++ = (q15_t) __SSAT(((q31_t) * pInA++ + *pInB++), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixAdd group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_add_q15.c +* +* Description: Q15 matrix addition +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixAdd + * @{ + */ + +/** + * @brief Q15 matrix addition. + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. + */ + +arm_status arm_mat_add_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst) +{ + q15_t *pInA = pSrcA->pData; /* input data matrix pointer A */ + q15_t *pInB = pSrcB->pData; /* input data matrix pointer B */ + q15_t *pOut = pDst->pData; /* output data matrix pointer */ + uint16_t numSamples; /* total number of elements in the matrix */ + uint32_t blkCnt; /* loop counters */ + arm_status status; /* status of matrix addition */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrcA->numRows != pSrcB->numRows) || + (pSrcA->numCols != pSrcB->numCols) || + (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Total number of samples in the input matrix */ + numSamples = (uint16_t) (pSrcA->numRows * pSrcA->numCols); + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Loop unrolling */ + blkCnt = (uint32_t) numSamples >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) + B(m,n) */ + /* Add, Saturate and then store the results in the destination buffer. */ + *__SIMD32(pOut)++ = __QADD16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); + *__SIMD32(pOut)++ = __QADD16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = (uint32_t) numSamples % 0x4u; + + /* q15 pointers of input and output are initialized */ + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) + B(m,n) */ + /* Add, Saturate and then store the results in the destination buffer. */ + *pOut++ = (q15_t) __QADD16(*pInA++, *pInB++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = (uint32_t) numSamples; + + + /* q15 pointers of input and output are initialized */ + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) + B(m,n) */ + /* Add, Saturate and then store the results in the destination buffer. */ + *pOut++ = (q15_t) __SSAT(((q31_t) * pInA++ + *pInB++), 16); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixAdd group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q31.c index 3d4563ca1..af4ada0ae 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q31.c @@ -1,157 +1,157 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_add_q31.c -* -* Description: Q31 matrix addition -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixAdd - * @{ - */ - -/** - * @brief Q31 matrix addition. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. - */ - -arm_status arm_mat_add_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix addition */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop Unrolling */ - blkCnt = numSamples >> 2u; - - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, saturate and then store the results in the destination buffer. */ - *pOut++ = __QADD(*pIn1++, *pIn2++); - *pOut++ = __QADD(*pIn1++, *pIn2++); - *pOut++ = __QADD(*pIn1++, *pIn2++); - *pOut++ = __QADD(*pIn1++, *pIn2++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, saturate and then store the results in the destination buffer. */ - *pOut++ = __QADD(*pIn1++, *pIn2++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, saturate and then store the results in the destination buffer. */ - *pOut++ = clip_q63_to_q31(((q63_t) (*pIn1++)) + (*pIn2++)); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixAdd group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_add_q31.c +* +* Description: Q31 matrix addition +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixAdd + * @{ + */ + +/** + * @brief Q31 matrix addition. + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. + */ + +arm_status arm_mat_add_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst) +{ + q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ + q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ + q31_t *pOut = pDst->pData; /* output data matrix pointer */ + uint32_t numSamples; /* total number of elements in the matrix */ + uint32_t blkCnt; /* loop counters */ + arm_status status; /* status of matrix addition */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrcA->numRows != pSrcB->numRows) || + (pSrcA->numCols != pSrcB->numCols) || + (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Total number of samples in the input matrix */ + numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Loop Unrolling */ + blkCnt = numSamples >> 2u; + + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) + B(m,n) */ + /* Add, saturate and then store the results in the destination buffer. */ + *pOut++ = __QADD(*pIn1++, *pIn2++); + *pOut++ = __QADD(*pIn1++, *pIn2++); + *pOut++ = __QADD(*pIn1++, *pIn2++); + *pOut++ = __QADD(*pIn1++, *pIn2++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the numSamples is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = numSamples % 0x4u; + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) + B(m,n) */ + /* Add, saturate and then store the results in the destination buffer. */ + *pOut++ = __QADD(*pIn1++, *pIn2++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = numSamples; + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) + B(m,n) */ + /* Add, saturate and then store the results in the destination buffer. */ + *pOut++ = clip_q63_to_q31(((q63_t) (*pIn1++)) + (*pIn2++)); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixAdd group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_f32.c index 96dbc53fd..e27a685b8 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_f32.c @@ -1,83 +1,83 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_init_f32.c -* -* Description: Floating-point matrix initialization. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixInit Matrix Initialization - * - * Initializes the underlying matrix data structure. - * The functions set the numRows, - * numCols, and pData fields - * of the matrix data structure. - */ - -/** - * @addtogroup MatrixInit - * @{ - */ - -/** - * @brief Floating-point matrix initialization. - * @param[in,out] *S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] *pData points to the matrix data array. - * @return none - */ - -void arm_mat_init_f32( - arm_matrix_instance_f32 * S, - uint16_t nRows, - uint16_t nColumns, - float32_t * pData) -{ - /* Assign Number of Rows */ - S->numRows = nRows; - - /* Assign Number of Columns */ - S->numCols = nColumns; - - /* Assign Data pointer */ - S->pData = pData; -} - -/** - * @} end of MatrixInit group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_init_f32.c +* +* Description: Floating-point matrix initialization. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @defgroup MatrixInit Matrix Initialization + * + * Initializes the underlying matrix data structure. + * The functions set the numRows, + * numCols, and pData fields + * of the matrix data structure. + */ + +/** + * @addtogroup MatrixInit + * @{ + */ + +/** + * @brief Floating-point matrix initialization. + * @param[in,out] *S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] *pData points to the matrix data array. + * @return none + */ + +void arm_mat_init_f32( + arm_matrix_instance_f32 * S, + uint16_t nRows, + uint16_t nColumns, + float32_t * pData) +{ + /* Assign Number of Rows */ + S->numRows = nRows; + + /* Assign Number of Columns */ + S->numCols = nColumns; + + /* Assign Data pointer */ + S->pData = pData; +} + +/** + * @} end of MatrixInit group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q15.c index 8c7fb44df..addc2b0f1 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q15.c @@ -1,75 +1,75 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_init_q15.c -* -* Description: Q15 matrix initialization. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixInit - * @{ - */ - - /** - * @brief Q15 matrix initialization. - * @param[in,out] *S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] *pData points to the matrix data array. - * @return none - */ - -void arm_mat_init_q15( - arm_matrix_instance_q15 * S, - uint16_t nRows, - uint16_t nColumns, - q15_t * pData) -{ - /* Assign Number of Rows */ - S->numRows = nRows; - - /* Assign Number of Columns */ - S->numCols = nColumns; - - /* Assign Data pointer */ - S->pData = pData; -} - -/** - * @} end of MatrixInit group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_init_q15.c +* +* Description: Q15 matrix initialization. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------------- */ + + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixInit + * @{ + */ + + /** + * @brief Q15 matrix initialization. + * @param[in,out] *S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] *pData points to the matrix data array. + * @return none + */ + +void arm_mat_init_q15( + arm_matrix_instance_q15 * S, + uint16_t nRows, + uint16_t nColumns, + q15_t * pData) +{ + /* Assign Number of Rows */ + S->numRows = nRows; + + /* Assign Number of Columns */ + S->numCols = nColumns; + + /* Assign Data pointer */ + S->pData = pData; +} + +/** + * @} end of MatrixInit group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q31.c index efe0bbd3c..7e116590a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q31.c @@ -1,79 +1,79 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_init_q31.c -* -* Description: Q31 matrix initialization. -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixInit Matrix Initialization - * - */ - -/** - * @addtogroup MatrixInit - * @{ - */ - - /** - * @brief Q31 matrix initialization. - * @param[in,out] *S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] *pData points to the matrix data array. - * @return none - */ - -void arm_mat_init_q31( - arm_matrix_instance_q31 * S, - uint16_t nRows, - uint16_t nColumns, - q31_t * pData) -{ - /* Assign Number of Rows */ - S->numRows = nRows; - - /* Assign Number of Columns */ - S->numCols = nColumns; - - /* Assign Data pointer */ - S->pData = pData; -} - -/** - * @} end of MatrixInit group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_init_q31.c +* +* Description: Q31 matrix initialization. +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------------- */ + + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @defgroup MatrixInit Matrix Initialization + * + */ + +/** + * @addtogroup MatrixInit + * @{ + */ + + /** + * @brief Q31 matrix initialization. + * @param[in,out] *S points to an instance of the floating-point matrix structure. + * @param[in] nRows number of rows in the matrix. + * @param[in] nColumns number of columns in the matrix. + * @param[in] *pData points to the matrix data array. + * @return none + */ + +void arm_mat_init_q31( + arm_matrix_instance_q31 * S, + uint16_t nRows, + uint16_t nColumns, + q31_t * pData) +{ + /* Assign Number of Rows */ + S->numRows = nRows; + + /* Assign Number of Columns */ + S->numCols = nColumns; + + /* Assign Data pointer */ + S->pData = pData; +} + +/** + * @} end of MatrixInit group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_inverse_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_inverse_f32.c index cd635c8cb..6a1e0e441 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_inverse_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_inverse_f32.c @@ -1,665 +1,665 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_inverse_f32.c -* -* Description: Floating-point matrix inverse. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixInv Matrix Inverse - * - * Computes the inverse of a matrix. - * - * The inverse is defined only if the input matrix is square and non-singular (the determinant - * is non-zero). The function checks that the input and output matrices are square and of the - * same size. - * - * Matrix inversion is numerically sensitive and the CMSIS DSP library only supports matrix - * inversion of floating-point matrices. - * - * \par Algorithm - * The Gauss-Jordan method is used to find the inverse. - * The algorithm performs a sequence of elementary row-operations till it - * reduces the input matrix to an identity matrix. Applying the same sequence - * of elementary row-operations to an identity matrix yields the inverse matrix. - * If the input matrix is singular, then the algorithm terminates and returns error status - * ARM_MATH_SINGULAR. - * \image html MatrixInverse.gif "Matrix Inverse of a 3 x 3 matrix using Gauss-Jordan Method" - */ - -/** - * @addtogroup MatrixInv - * @{ - */ - -/** - * @brief Floating-point matrix inverse. - * @param[in] *pSrc points to input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns - * ARM_MATH_SIZE_MISMATCH if the input matrix is not square or if the size - * of the output matrix does not match the size of the input matrix. - * If the input matrix is found to be singular (non-invertible), then the function returns - * ARM_MATH_SINGULAR. Otherwise, the function returns ARM_MATH_SUCCESS. - */ - -arm_status arm_mat_inverse_f32( - const arm_matrix_instance_f32 * pSrc, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn = pSrc->pData; /* input data matrix pointer */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - float32_t *pInT1, *pInT2; /* Temporary input data matrix pointer */ - float32_t *pInT3, *pInT4; /* Temporary output data matrix pointer */ - float32_t *pPivotRowIn, *pPRT_in, *pPivotRowDst, *pPRT_pDst; /* Temporary input and output data matrix pointer */ - uint32_t numRows = pSrc->numRows; /* Number of rows in the matrix */ - uint32_t numCols = pSrc->numCols; /* Number of Cols in the matrix */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t Xchg, in = 0.0f, in1; /* Temporary input values */ - uint32_t i, rowCnt, flag = 0u, j, loopCnt, k, l; /* loop counters */ - arm_status status; /* status of matrix inverse */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pSrc->numCols) || (pDst->numRows != pDst->numCols) - || (pSrc->numRows != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - - /*-------------------------------------------------------------------------------------------------------------- - * Matrix Inverse can be solved using elementary row operations. - * - * Gauss-Jordan Method: - * - * 1. First combine the identity matrix and the input matrix separated by a bar to form an - * augmented matrix as follows: - * _ _ _ _ - * | a11 a12 | 1 0 | | X11 X12 | - * | | | = | | - * |_ a21 a22 | 0 1 _| |_ X21 X21 _| - * - * 2. In our implementation, pDst Matrix is used as identity matrix. - * - * 3. Begin with the first row. Let i = 1. - * - * 4. Check to see if the pivot for row i is zero. - * The pivot is the element of the main diagonal that is on the current row. - * For instance, if working with row i, then the pivot element is aii. - * If the pivot is zero, exchange that row with a row below it that does not - * contain a zero in column i. If this is not possible, then an inverse - * to that matrix does not exist. - * - * 5. Divide every element of row i by the pivot. - * - * 6. For every row below and row i, replace that row with the sum of that row and - * a multiple of row i so that each new element in column i below row i is zero. - * - * 7. Move to the next row and column and repeat steps 2 through 5 until you have zeros - * for every element below and above the main diagonal. - * - * 8. Now an identical matrix is formed to the left of the bar(input matrix, pSrc). - * Therefore, the matrix to the right of the bar is our solution(pDst matrix, pDst). - *----------------------------------------------------------------------------------------------------------------*/ - - /* Working pointer for destination matrix */ - pInT2 = pOut; - - /* Loop over the number of rows */ - rowCnt = numRows; - - /* Making the destination matrix as identity matrix */ - while(rowCnt > 0u) - { - /* Writing all zeroes in lower triangle of the destination matrix */ - j = numRows - rowCnt; - while(j > 0u) - { - *pInT2++ = 0.0f; - j--; - } - - /* Writing all ones in the diagonal of the destination matrix */ - *pInT2++ = 1.0f; - - /* Writing all zeroes in upper triangle of the destination matrix */ - j = rowCnt - 1u; - while(j > 0u) - { - *pInT2++ = 0.0f; - j--; - } - - /* Decrement the loop counter */ - rowCnt--; - } - - /* Loop over the number of columns of the input matrix. - All the elements in each column are processed by the row operations */ - loopCnt = numCols; - - /* Index modifier to navigate through the columns */ - l = 0u; - - while(loopCnt > 0u) - { - /* Check if the pivot element is zero.. - * If it is zero then interchange the row with non zero row below. - * If there is no non zero element to replace in the rows below, - * then the matrix is Singular. */ - - /* Working pointer for the input matrix that points - * to the pivot element of the particular row */ - pInT1 = pIn + (l * numCols); - - /* Working pointer for the destination matrix that points - * to the pivot element of the particular row */ - pInT3 = pOut + (l * numCols); - - /* Temporary variable to hold the pivot value */ - in = *pInT1; - - /* Destination pointer modifier */ - k = 1u; - - /* Check if the pivot element is zero */ - if(*pInT1 == 0.0f) - { - /* Loop over the number rows present below */ - i = numRows - (l + 1u); - - while(i > 0u) - { - /* Update the input and destination pointers */ - pInT2 = pInT1 + (numCols * l); - pInT4 = pInT3 + (numCols * k); - - /* Check if there is a non zero pivot element to - * replace in the rows below */ - if(*pInT2 != 0.0f) - { - /* Loop over number of columns - * to the right of the pilot element */ - j = numCols - l; - - while(j > 0u) - { - /* Exchange the row elements of the input matrix */ - Xchg = *pInT2; - *pInT2++ = *pInT1; - *pInT1++ = Xchg; - - /* Decrement the loop counter */ - j--; - } - - /* Loop over number of columns of the destination matrix */ - j = numCols; - - while(j > 0u) - { - /* Exchange the row elements of the destination matrix */ - Xchg = *pInT4; - *pInT4++ = *pInT3; - *pInT3++ = Xchg; - - /* Decrement the loop counter */ - j--; - } - - /* Flag to indicate whether exchange is done or not */ - flag = 1u; - - /* Break after exchange is done */ - break; - } - - /* Update the destination pointer modifier */ - k++; - - /* Decrement the loop counter */ - i--; - } - } - - /* Update the status if the matrix is singular */ - if((flag != 1u) && (in == 0.0f)) - { - status = ARM_MATH_SINGULAR; - - break; - } - - /* Points to the pivot row of input and destination matrices */ - pPivotRowIn = pIn + (l * numCols); - pPivotRowDst = pOut + (l * numCols); - - /* Temporary pointers to the pivot row pointers */ - pInT1 = pPivotRowIn; - pInT2 = pPivotRowDst; - - /* Pivot element of the row */ - in = *(pIn + (l * numCols)); - - /* Loop over number of columns - * to the right of the pilot element */ - j = (numCols - l); - - while(j > 0u) - { - /* Divide each element of the row of the input matrix - * by the pivot element */ - in1 = *pInT1; - *pInT1++ = in1 / in; - - /* Decrement the loop counter */ - j--; - } - - /* Loop over number of columns of the destination matrix */ - j = numCols; - - while(j > 0u) - { - /* Divide each element of the row of the destination matrix - * by the pivot element */ - in1 = *pInT2; - *pInT2++ = in1 / in; - - /* Decrement the loop counter */ - j--; - } - - /* Replace the rows with the sum of that row and a multiple of row i - * so that each new element in column i above row i is zero.*/ - - /* Temporary pointers for input and destination matrices */ - pInT1 = pIn; - pInT2 = pOut; - - /* index used to check for pivot element */ - i = 0u; - - /* Loop over number of rows */ - /* to be replaced by the sum of that row and a multiple of row i */ - k = numRows; - - while(k > 0u) - { - /* Check for the pivot element */ - if(i == l) - { - /* If the processing element is the pivot element, - only the columns to the right are to be processed */ - pInT1 += numCols - l; - - pInT2 += numCols; - } - else - { - /* Element of the reference row */ - in = *pInT1; - - /* Working pointers for input and destination pivot rows */ - pPRT_in = pPivotRowIn; - pPRT_pDst = pPivotRowDst; - - /* Loop over the number of columns to the right of the pivot element, - to replace the elements in the input matrix */ - j = (numCols - l); - - while(j > 0u) - { - /* Replace the element by the sum of that row - and a multiple of the reference row */ - in1 = *pInT1; - *pInT1++ = in1 - (in * *pPRT_in++); - - /* Decrement the loop counter */ - j--; - } - - /* Loop over the number of columns to - replace the elements in the destination matrix */ - j = numCols; - - while(j > 0u) - { - /* Replace the element by the sum of that row - and a multiple of the reference row */ - in1 = *pInT2; - *pInT2++ = in1 - (in * *pPRT_pDst++); - - /* Decrement the loop counter */ - j--; - } - - } - - /* Increment the temporary input pointer */ - pInT1 = pInT1 + l; - - /* Decrement the loop counter */ - k--; - - /* Increment the pivot index */ - i++; - } - - /* Increment the input pointer */ - pIn++; - - /* Decrement the loop counter */ - loopCnt--; - - /* Increment the index modifier */ - l++; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t Xchg, in = 0.0f; /* Temporary input values */ - uint32_t i, rowCnt, flag = 0u, j, loopCnt, k, l; /* loop counters */ - arm_status status; /* status of matrix inverse */ - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pSrc->numCols) || (pDst->numRows != pDst->numCols) - || (pSrc->numRows != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - { - - /*-------------------------------------------------------------------------------------------------------------- - * Matrix Inverse can be solved using elementary row operations. - * - * Gauss-Jordan Method: - * - * 1. First combine the identity matrix and the input matrix separated by a bar to form an - * augmented matrix as follows: - * _ _ _ _ _ _ _ _ - * | | a11 a12 | | | 1 0 | | | X11 X12 | - * | | | | | | | = | | - * |_ |_ a21 a22 _| | |_0 1 _| _| |_ X21 X21 _| - * - * 2. In our implementation, pDst Matrix is used as identity matrix. - * - * 3. Begin with the first row. Let i = 1. - * - * 4. Check to see if the pivot for row i is zero. - * The pivot is the element of the main diagonal that is on the current row. - * For instance, if working with row i, then the pivot element is aii. - * If the pivot is zero, exchange that row with a row below it that does not - * contain a zero in column i. If this is not possible, then an inverse - * to that matrix does not exist. - * - * 5. Divide every element of row i by the pivot. - * - * 6. For every row below and row i, replace that row with the sum of that row and - * a multiple of row i so that each new element in column i below row i is zero. - * - * 7. Move to the next row and column and repeat steps 2 through 5 until you have zeros - * for every element below and above the main diagonal. - * - * 8. Now an identical matrix is formed to the left of the bar(input matrix, src). - * Therefore, the matrix to the right of the bar is our solution(dst matrix, dst). - *----------------------------------------------------------------------------------------------------------------*/ - - /* Working pointer for destination matrix */ - pInT2 = pOut; - - /* Loop over the number of rows */ - rowCnt = numRows; - - /* Making the destination matrix as identity matrix */ - while(rowCnt > 0u) - { - /* Writing all zeroes in lower triangle of the destination matrix */ - j = numRows - rowCnt; - while(j > 0u) - { - *pInT2++ = 0.0f; - j--; - } - - /* Writing all ones in the diagonal of the destination matrix */ - *pInT2++ = 1.0f; - - /* Writing all zeroes in upper triangle of the destination matrix */ - j = rowCnt - 1u; - while(j > 0u) - { - *pInT2++ = 0.0f; - j--; - } - - /* Decrement the loop counter */ - rowCnt--; - } - - /* Loop over the number of columns of the input matrix. - All the elements in each column are processed by the row operations */ - loopCnt = numCols; - - /* Index modifier to navigate through the columns */ - l = 0u; - //for(loopCnt = 0u; loopCnt < numCols; loopCnt++) - while(loopCnt > 0u) - { - /* Check if the pivot element is zero.. - * If it is zero then interchange the row with non zero row below. - * If there is no non zero element to replace in the rows below, - * then the matrix is Singular. */ - - /* Working pointer for the input matrix that points - * to the pivot element of the particular row */ - pInT1 = pIn + (l * numCols); - - /* Working pointer for the destination matrix that points - * to the pivot element of the particular row */ - pInT3 = pOut + (l * numCols); - - /* Temporary variable to hold the pivot value */ - in = *pInT1; - - /* Destination pointer modifier */ - k = 1u; - - /* Check if the pivot element is zero */ - if(*pInT1 == 0.0f) - { - /* Loop over the number rows present below */ - for (i = (l + 1u); i < numRows; i++) - { - /* Update the input and destination pointers */ - pInT2 = pInT1 + (numCols * l); - pInT4 = pInT3 + (numCols * k); - - /* Check if there is a non zero pivot element to - * replace in the rows below */ - if(*pInT2 != 0.0f) - { - /* Loop over number of columns - * to the right of the pilot element */ - for (j = 0u; j < (numCols - l); j++) - { - /* Exchange the row elements of the input matrix */ - Xchg = *pInT2; - *pInT2++ = *pInT1; - *pInT1++ = Xchg; - } - - for (j = 0u; j < numCols; j++) - { - Xchg = *pInT4; - *pInT4++ = *pInT3; - *pInT3++ = Xchg; - } - - /* Flag to indicate whether exchange is done or not */ - flag = 1u; - - /* Break after exchange is done */ - break; - } - - /* Update the destination pointer modifier */ - k++; - } - } - - /* Update the status if the matrix is singular */ - if((flag != 1u) && (in == 0.0f)) - { - status = ARM_MATH_SINGULAR; - - break; - } - - /* Points to the pivot row of input and destination matrices */ - pPivotRowIn = pIn + (l * numCols); - pPivotRowDst = pOut + (l * numCols); - - /* Temporary pointers to the pivot row pointers */ - pInT1 = pPivotRowIn; - pInT2 = pPivotRowDst; - - /* Pivot element of the row */ - in = *(pIn + (l * numCols)); - - /* Loop over number of columns - * to the right of the pilot element */ - for (j = 0u; j < (numCols - l); j++) - { - /* Divide each element of the row of the input matrix - * by the pivot element */ - *pInT1++ = *pInT1 / in; - } - for (j = 0u; j < numCols; j++) - { - /* Divide each element of the row of the destination matrix - * by the pivot element */ - *pInT2++ = *pInT2 / in; - } - - /* Replace the rows with the sum of that row and a multiple of row i - * so that each new element in column i above row i is zero.*/ - - /* Temporary pointers for input and destination matrices */ - pInT1 = pIn; - pInT2 = pOut; - - for (i = 0u; i < numRows; i++) - { - /* Check for the pivot element */ - if(i == l) - { - /* If the processing element is the pivot element, - only the columns to the right are to be processed */ - pInT1 += numCols - l; - pInT2 += numCols; - } - else - { - /* Element of the reference row */ - in = *pInT1; - - /* Working pointers for input and destination pivot rows */ - pPRT_in = pPivotRowIn; - pPRT_pDst = pPivotRowDst; - - /* Loop over the number of columns to the right of the pivot element, - to replace the elements in the input matrix */ - for (j = 0u; j < (numCols - l); j++) - { - /* Replace the element by the sum of that row - and a multiple of the reference row */ - *pInT1++ = *pInT1 - (in * *pPRT_in++); - } - /* Loop over the number of columns to - replace the elements in the destination matrix */ - for (j = 0u; j < numCols; j++) - { - /* Replace the element by the sum of that row - and a multiple of the reference row */ - *pInT2++ = *pInT2 - (in * *pPRT_pDst++); - } - - } - /* Increment the temporary input pointer */ - pInT1 = pInT1 + l; - } - /* Increment the input pointer */ - pIn++; - - /* Decrement the loop counter */ - loopCnt--; - /* Increment the index modifier */ - l++; - } - - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - - if((flag != 1u) && (in == 0.0f)) - { - status = ARM_MATH_SINGULAR; - } - } - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixInv group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_inverse_f32.c +* +* Description: Floating-point matrix inverse. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @defgroup MatrixInv Matrix Inverse + * + * Computes the inverse of a matrix. + * + * The inverse is defined only if the input matrix is square and non-singular (the determinant + * is non-zero). The function checks that the input and output matrices are square and of the + * same size. + * + * Matrix inversion is numerically sensitive and the CMSIS DSP library only supports matrix + * inversion of floating-point matrices. + * + * \par Algorithm + * The Gauss-Jordan method is used to find the inverse. + * The algorithm performs a sequence of elementary row-operations till it + * reduces the input matrix to an identity matrix. Applying the same sequence + * of elementary row-operations to an identity matrix yields the inverse matrix. + * If the input matrix is singular, then the algorithm terminates and returns error status + * ARM_MATH_SINGULAR. + * \image html MatrixInverse.gif "Matrix Inverse of a 3 x 3 matrix using Gauss-Jordan Method" + */ + +/** + * @addtogroup MatrixInv + * @{ + */ + +/** + * @brief Floating-point matrix inverse. + * @param[in] *pSrc points to input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns + * ARM_MATH_SIZE_MISMATCH if the input matrix is not square or if the size + * of the output matrix does not match the size of the input matrix. + * If the input matrix is found to be singular (non-invertible), then the function returns + * ARM_MATH_SINGULAR. Otherwise, the function returns ARM_MATH_SUCCESS. + */ + +arm_status arm_mat_inverse_f32( + const arm_matrix_instance_f32 * pSrc, + arm_matrix_instance_f32 * pDst) +{ + float32_t *pIn = pSrc->pData; /* input data matrix pointer */ + float32_t *pOut = pDst->pData; /* output data matrix pointer */ + float32_t *pInT1, *pInT2; /* Temporary input data matrix pointer */ + float32_t *pInT3, *pInT4; /* Temporary output data matrix pointer */ + float32_t *pPivotRowIn, *pPRT_in, *pPivotRowDst, *pPRT_pDst; /* Temporary input and output data matrix pointer */ + uint32_t numRows = pSrc->numRows; /* Number of rows in the matrix */ + uint32_t numCols = pSrc->numCols; /* Number of Cols in the matrix */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + float32_t Xchg, in = 0.0f, in1; /* Temporary input values */ + uint32_t i, rowCnt, flag = 0u, j, loopCnt, k, l; /* loop counters */ + arm_status status; /* status of matrix inverse */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrc->numRows != pSrc->numCols) || (pDst->numRows != pDst->numCols) + || (pSrc->numRows != pDst->numRows)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + + /*-------------------------------------------------------------------------------------------------------------- + * Matrix Inverse can be solved using elementary row operations. + * + * Gauss-Jordan Method: + * + * 1. First combine the identity matrix and the input matrix separated by a bar to form an + * augmented matrix as follows: + * _ _ _ _ + * | a11 a12 | 1 0 | | X11 X12 | + * | | | = | | + * |_ a21 a22 | 0 1 _| |_ X21 X21 _| + * + * 2. In our implementation, pDst Matrix is used as identity matrix. + * + * 3. Begin with the first row. Let i = 1. + * + * 4. Check to see if the pivot for row i is zero. + * The pivot is the element of the main diagonal that is on the current row. + * For instance, if working with row i, then the pivot element is aii. + * If the pivot is zero, exchange that row with a row below it that does not + * contain a zero in column i. If this is not possible, then an inverse + * to that matrix does not exist. + * + * 5. Divide every element of row i by the pivot. + * + * 6. For every row below and row i, replace that row with the sum of that row and + * a multiple of row i so that each new element in column i below row i is zero. + * + * 7. Move to the next row and column and repeat steps 2 through 5 until you have zeros + * for every element below and above the main diagonal. + * + * 8. Now an identical matrix is formed to the left of the bar(input matrix, pSrc). + * Therefore, the matrix to the right of the bar is our solution(pDst matrix, pDst). + *----------------------------------------------------------------------------------------------------------------*/ + + /* Working pointer for destination matrix */ + pInT2 = pOut; + + /* Loop over the number of rows */ + rowCnt = numRows; + + /* Making the destination matrix as identity matrix */ + while(rowCnt > 0u) + { + /* Writing all zeroes in lower triangle of the destination matrix */ + j = numRows - rowCnt; + while(j > 0u) + { + *pInT2++ = 0.0f; + j--; + } + + /* Writing all ones in the diagonal of the destination matrix */ + *pInT2++ = 1.0f; + + /* Writing all zeroes in upper triangle of the destination matrix */ + j = rowCnt - 1u; + while(j > 0u) + { + *pInT2++ = 0.0f; + j--; + } + + /* Decrement the loop counter */ + rowCnt--; + } + + /* Loop over the number of columns of the input matrix. + All the elements in each column are processed by the row operations */ + loopCnt = numCols; + + /* Index modifier to navigate through the columns */ + l = 0u; + + while(loopCnt > 0u) + { + /* Check if the pivot element is zero.. + * If it is zero then interchange the row with non zero row below. + * If there is no non zero element to replace in the rows below, + * then the matrix is Singular. */ + + /* Working pointer for the input matrix that points + * to the pivot element of the particular row */ + pInT1 = pIn + (l * numCols); + + /* Working pointer for the destination matrix that points + * to the pivot element of the particular row */ + pInT3 = pOut + (l * numCols); + + /* Temporary variable to hold the pivot value */ + in = *pInT1; + + /* Destination pointer modifier */ + k = 1u; + + /* Check if the pivot element is zero */ + if(*pInT1 == 0.0f) + { + /* Loop over the number rows present below */ + i = numRows - (l + 1u); + + while(i > 0u) + { + /* Update the input and destination pointers */ + pInT2 = pInT1 + (numCols * l); + pInT4 = pInT3 + (numCols * k); + + /* Check if there is a non zero pivot element to + * replace in the rows below */ + if(*pInT2 != 0.0f) + { + /* Loop over number of columns + * to the right of the pilot element */ + j = numCols - l; + + while(j > 0u) + { + /* Exchange the row elements of the input matrix */ + Xchg = *pInT2; + *pInT2++ = *pInT1; + *pInT1++ = Xchg; + + /* Decrement the loop counter */ + j--; + } + + /* Loop over number of columns of the destination matrix */ + j = numCols; + + while(j > 0u) + { + /* Exchange the row elements of the destination matrix */ + Xchg = *pInT4; + *pInT4++ = *pInT3; + *pInT3++ = Xchg; + + /* Decrement the loop counter */ + j--; + } + + /* Flag to indicate whether exchange is done or not */ + flag = 1u; + + /* Break after exchange is done */ + break; + } + + /* Update the destination pointer modifier */ + k++; + + /* Decrement the loop counter */ + i--; + } + } + + /* Update the status if the matrix is singular */ + if((flag != 1u) && (in == 0.0f)) + { + status = ARM_MATH_SINGULAR; + + break; + } + + /* Points to the pivot row of input and destination matrices */ + pPivotRowIn = pIn + (l * numCols); + pPivotRowDst = pOut + (l * numCols); + + /* Temporary pointers to the pivot row pointers */ + pInT1 = pPivotRowIn; + pInT2 = pPivotRowDst; + + /* Pivot element of the row */ + in = *(pIn + (l * numCols)); + + /* Loop over number of columns + * to the right of the pilot element */ + j = (numCols - l); + + while(j > 0u) + { + /* Divide each element of the row of the input matrix + * by the pivot element */ + in1 = *pInT1; + *pInT1++ = in1 / in; + + /* Decrement the loop counter */ + j--; + } + + /* Loop over number of columns of the destination matrix */ + j = numCols; + + while(j > 0u) + { + /* Divide each element of the row of the destination matrix + * by the pivot element */ + in1 = *pInT2; + *pInT2++ = in1 / in; + + /* Decrement the loop counter */ + j--; + } + + /* Replace the rows with the sum of that row and a multiple of row i + * so that each new element in column i above row i is zero.*/ + + /* Temporary pointers for input and destination matrices */ + pInT1 = pIn; + pInT2 = pOut; + + /* index used to check for pivot element */ + i = 0u; + + /* Loop over number of rows */ + /* to be replaced by the sum of that row and a multiple of row i */ + k = numRows; + + while(k > 0u) + { + /* Check for the pivot element */ + if(i == l) + { + /* If the processing element is the pivot element, + only the columns to the right are to be processed */ + pInT1 += numCols - l; + + pInT2 += numCols; + } + else + { + /* Element of the reference row */ + in = *pInT1; + + /* Working pointers for input and destination pivot rows */ + pPRT_in = pPivotRowIn; + pPRT_pDst = pPivotRowDst; + + /* Loop over the number of columns to the right of the pivot element, + to replace the elements in the input matrix */ + j = (numCols - l); + + while(j > 0u) + { + /* Replace the element by the sum of that row + and a multiple of the reference row */ + in1 = *pInT1; + *pInT1++ = in1 - (in * *pPRT_in++); + + /* Decrement the loop counter */ + j--; + } + + /* Loop over the number of columns to + replace the elements in the destination matrix */ + j = numCols; + + while(j > 0u) + { + /* Replace the element by the sum of that row + and a multiple of the reference row */ + in1 = *pInT2; + *pInT2++ = in1 - (in * *pPRT_pDst++); + + /* Decrement the loop counter */ + j--; + } + + } + + /* Increment the temporary input pointer */ + pInT1 = pInT1 + l; + + /* Decrement the loop counter */ + k--; + + /* Increment the pivot index */ + i++; + } + + /* Increment the input pointer */ + pIn++; + + /* Decrement the loop counter */ + loopCnt--; + + /* Increment the index modifier */ + l++; + } + + +#else + + /* Run the below code for Cortex-M0 */ + + float32_t Xchg, in = 0.0f; /* Temporary input values */ + uint32_t i, rowCnt, flag = 0u, j, loopCnt, k, l; /* loop counters */ + arm_status status; /* status of matrix inverse */ + +#ifdef ARM_MATH_MATRIX_CHECK + + /* Check for matrix mismatch condition */ + if((pSrc->numRows != pSrc->numCols) || (pDst->numRows != pDst->numCols) + || (pSrc->numRows != pDst->numRows)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + { + + /*-------------------------------------------------------------------------------------------------------------- + * Matrix Inverse can be solved using elementary row operations. + * + * Gauss-Jordan Method: + * + * 1. First combine the identity matrix and the input matrix separated by a bar to form an + * augmented matrix as follows: + * _ _ _ _ _ _ _ _ + * | | a11 a12 | | | 1 0 | | | X11 X12 | + * | | | | | | | = | | + * |_ |_ a21 a22 _| | |_0 1 _| _| |_ X21 X21 _| + * + * 2. In our implementation, pDst Matrix is used as identity matrix. + * + * 3. Begin with the first row. Let i = 1. + * + * 4. Check to see if the pivot for row i is zero. + * The pivot is the element of the main diagonal that is on the current row. + * For instance, if working with row i, then the pivot element is aii. + * If the pivot is zero, exchange that row with a row below it that does not + * contain a zero in column i. If this is not possible, then an inverse + * to that matrix does not exist. + * + * 5. Divide every element of row i by the pivot. + * + * 6. For every row below and row i, replace that row with the sum of that row and + * a multiple of row i so that each new element in column i below row i is zero. + * + * 7. Move to the next row and column and repeat steps 2 through 5 until you have zeros + * for every element below and above the main diagonal. + * + * 8. Now an identical matrix is formed to the left of the bar(input matrix, src). + * Therefore, the matrix to the right of the bar is our solution(dst matrix, dst). + *----------------------------------------------------------------------------------------------------------------*/ + + /* Working pointer for destination matrix */ + pInT2 = pOut; + + /* Loop over the number of rows */ + rowCnt = numRows; + + /* Making the destination matrix as identity matrix */ + while(rowCnt > 0u) + { + /* Writing all zeroes in lower triangle of the destination matrix */ + j = numRows - rowCnt; + while(j > 0u) + { + *pInT2++ = 0.0f; + j--; + } + + /* Writing all ones in the diagonal of the destination matrix */ + *pInT2++ = 1.0f; + + /* Writing all zeroes in upper triangle of the destination matrix */ + j = rowCnt - 1u; + while(j > 0u) + { + *pInT2++ = 0.0f; + j--; + } + + /* Decrement the loop counter */ + rowCnt--; + } + + /* Loop over the number of columns of the input matrix. + All the elements in each column are processed by the row operations */ + loopCnt = numCols; + + /* Index modifier to navigate through the columns */ + l = 0u; + //for(loopCnt = 0u; loopCnt < numCols; loopCnt++) + while(loopCnt > 0u) + { + /* Check if the pivot element is zero.. + * If it is zero then interchange the row with non zero row below. + * If there is no non zero element to replace in the rows below, + * then the matrix is Singular. */ + + /* Working pointer for the input matrix that points + * to the pivot element of the particular row */ + pInT1 = pIn + (l * numCols); + + /* Working pointer for the destination matrix that points + * to the pivot element of the particular row */ + pInT3 = pOut + (l * numCols); + + /* Temporary variable to hold the pivot value */ + in = *pInT1; + + /* Destination pointer modifier */ + k = 1u; + + /* Check if the pivot element is zero */ + if(*pInT1 == 0.0f) + { + /* Loop over the number rows present below */ + for (i = (l + 1u); i < numRows; i++) + { + /* Update the input and destination pointers */ + pInT2 = pInT1 + (numCols * l); + pInT4 = pInT3 + (numCols * k); + + /* Check if there is a non zero pivot element to + * replace in the rows below */ + if(*pInT2 != 0.0f) + { + /* Loop over number of columns + * to the right of the pilot element */ + for (j = 0u; j < (numCols - l); j++) + { + /* Exchange the row elements of the input matrix */ + Xchg = *pInT2; + *pInT2++ = *pInT1; + *pInT1++ = Xchg; + } + + for (j = 0u; j < numCols; j++) + { + Xchg = *pInT4; + *pInT4++ = *pInT3; + *pInT3++ = Xchg; + } + + /* Flag to indicate whether exchange is done or not */ + flag = 1u; + + /* Break after exchange is done */ + break; + } + + /* Update the destination pointer modifier */ + k++; + } + } + + /* Update the status if the matrix is singular */ + if((flag != 1u) && (in == 0.0f)) + { + status = ARM_MATH_SINGULAR; + + break; + } + + /* Points to the pivot row of input and destination matrices */ + pPivotRowIn = pIn + (l * numCols); + pPivotRowDst = pOut + (l * numCols); + + /* Temporary pointers to the pivot row pointers */ + pInT1 = pPivotRowIn; + pInT2 = pPivotRowDst; + + /* Pivot element of the row */ + in = *(pIn + (l * numCols)); + + /* Loop over number of columns + * to the right of the pilot element */ + for (j = 0u; j < (numCols - l); j++) + { + /* Divide each element of the row of the input matrix + * by the pivot element */ + *pInT1++ = *pInT1 / in; + } + for (j = 0u; j < numCols; j++) + { + /* Divide each element of the row of the destination matrix + * by the pivot element */ + *pInT2++ = *pInT2 / in; + } + + /* Replace the rows with the sum of that row and a multiple of row i + * so that each new element in column i above row i is zero.*/ + + /* Temporary pointers for input and destination matrices */ + pInT1 = pIn; + pInT2 = pOut; + + for (i = 0u; i < numRows; i++) + { + /* Check for the pivot element */ + if(i == l) + { + /* If the processing element is the pivot element, + only the columns to the right are to be processed */ + pInT1 += numCols - l; + pInT2 += numCols; + } + else + { + /* Element of the reference row */ + in = *pInT1; + + /* Working pointers for input and destination pivot rows */ + pPRT_in = pPivotRowIn; + pPRT_pDst = pPivotRowDst; + + /* Loop over the number of columns to the right of the pivot element, + to replace the elements in the input matrix */ + for (j = 0u; j < (numCols - l); j++) + { + /* Replace the element by the sum of that row + and a multiple of the reference row */ + *pInT1++ = *pInT1 - (in * *pPRT_in++); + } + /* Loop over the number of columns to + replace the elements in the destination matrix */ + for (j = 0u; j < numCols; j++) + { + /* Replace the element by the sum of that row + and a multiple of the reference row */ + *pInT2++ = *pInT2 - (in * *pPRT_pDst++); + } + + } + /* Increment the temporary input pointer */ + pInT1 = pInT1 + l; + } + /* Increment the input pointer */ + pIn++; + + /* Decrement the loop counter */ + loopCnt--; + /* Increment the index modifier */ + l++; + } + + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + + if((flag != 1u) && (in == 0.0f)) + { + status = ARM_MATH_SINGULAR; + } + } + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixInv group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_f32.c index caa0200fa..c91603249 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_f32.c @@ -1,270 +1,270 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_mult_f32.c -* -* Description: Floating-point matrix multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixMult Matrix Multiplication - * - * Multiplies two matrices. - * - * \image html MatrixMultiplication.gif "Multiplication of two 3 x 3 matrices" - - * Matrix multiplication is only defined if the number of columns of the - * first matrix equals the number of rows of the second matrix. - * Multiplying an M x N matrix with an N x P matrix results - * in an M x P matrix. - * When matrix size checking is enabled, the functions check: (1) that the inner dimensions of - * pSrcA and pSrcB are equal; and (2) that the size of the output - * matrix equals the outer dimensions of pSrcA and pSrcB. - */ - - -/** - * @addtogroup MatrixMult - * @{ - */ - -/** - * @brief Floating-point matrix multiplication. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - -arm_status arm_mat_mult_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - float32_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - float32_t *pInA = pSrcA->pData; /* input data matrix pointer A */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - float32_t *px; /* Temporary output data matrix pointer */ - float32_t sum; /* Accumulator */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - uint16_t col, i = 0u, j, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - j = 0u; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0.0f; - - /* Initiate the pointer pIn1 to point to the starting address of the column being processed */ - pIn1 = pInA; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - colCnt = numColsA >> 2; - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum += *pIn1++ * (*pIn2); - pIn2 += numColsB; - sum += *pIn1++ * (*pIn2); - pIn2 += numColsB; - sum += *pIn1++ * (*pIn2); - pIn2 += numColsB; - sum += *pIn1++ * (*pIn2); - pIn2 += numColsB; - - /* Decrement the loop count */ - colCnt--; - } - - /* If the columns of pSrcA is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - colCnt = numColsA % 0x4u; - - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum += *pIn1++ * (*pIn2); - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Store the result in the destination buffer */ - *px++ = sum; - - /* Update the pointer pIn2 to point to the starting address of the next column */ - j++; - pIn2 = pSrcB->pData + j; - - /* Decrement the column loop counter */ - col--; - - } while(col > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t *pInB = pSrcB->pData; /* input data matrix pointer B */ - uint16_t col, i = 0u, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pInA with each column in pInB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0.0f; - - /* Initialize the pointer pIn1 to point to the starting address of the row being processed */ - pIn1 = pInA; - - /* Matrix A columns number of MAC operations are to be performed */ - colCnt = numColsA; - - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum += *pIn1++ * (*pIn2); - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Store the result in the destination buffer */ - *px++ = sum; - - /* Decrement the column loop counter */ - col--; - - /* Update the pointer pIn2 to point to the starting address of the next column */ - pIn2 = pInB + (numColsB - col); - - } while(col > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Update the pointer pInA to point to the starting address of the next row */ - i = i + numColsB; - pInA = pInA + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixMult group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_mult_f32.c +* +* Description: Floating-point matrix multiplication. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @defgroup MatrixMult Matrix Multiplication + * + * Multiplies two matrices. + * + * \image html MatrixMultiplication.gif "Multiplication of two 3 x 3 matrices" + + * Matrix multiplication is only defined if the number of columns of the + * first matrix equals the number of rows of the second matrix. + * Multiplying an M x N matrix with an N x P matrix results + * in an M x P matrix. + * When matrix size checking is enabled, the functions check: (1) that the inner dimensions of + * pSrcA and pSrcB are equal; and (2) that the size of the output + * matrix equals the outer dimensions of pSrcA and pSrcB. + */ + + +/** + * @addtogroup MatrixMult + * @{ + */ + +/** + * @brief Floating-point matrix multiplication. + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + +arm_status arm_mat_mult_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst) +{ + float32_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ + float32_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ + float32_t *pInA = pSrcA->pData; /* input data matrix pointer A */ + float32_t *pOut = pDst->pData; /* output data matrix pointer */ + float32_t *px; /* Temporary output data matrix pointer */ + float32_t sum; /* Accumulator */ + uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ + uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ + uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + uint16_t col, i = 0u, j, row = numRowsA, colCnt; /* loop counters */ + arm_status status; /* status of matrix multiplication */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrcA->numCols != pSrcB->numRows) || + (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) + { + + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ + /* row loop */ + do + { + /* Output pointer is set to starting address of the row being processed */ + px = pOut + i; + + /* For every row wise process, the column loop counter is to be initiated */ + col = numColsB; + + /* For every row wise process, the pIn2 pointer is set + ** to the starting address of the pSrcB data */ + pIn2 = pSrcB->pData; + + j = 0u; + + /* column loop */ + do + { + /* Set the variable sum, that acts as accumulator, to zero */ + sum = 0.0f; + + /* Initiate the pointer pIn1 to point to the starting address of the column being processed */ + pIn1 = pInA; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + colCnt = numColsA >> 2; + + /* matrix multiplication */ + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + sum += *pIn1++ * (*pIn2); + pIn2 += numColsB; + sum += *pIn1++ * (*pIn2); + pIn2 += numColsB; + sum += *pIn1++ * (*pIn2); + pIn2 += numColsB; + sum += *pIn1++ * (*pIn2); + pIn2 += numColsB; + + /* Decrement the loop count */ + colCnt--; + } + + /* If the columns of pSrcA is not a multiple of 4, compute any remaining MACs here. + ** No loop unrolling is used. */ + colCnt = numColsA % 0x4u; + + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + sum += *pIn1++ * (*pIn2); + pIn2 += numColsB; + + /* Decrement the loop counter */ + colCnt--; + } + + /* Store the result in the destination buffer */ + *px++ = sum; + + /* Update the pointer pIn2 to point to the starting address of the next column */ + j++; + pIn2 = pSrcB->pData + j; + + /* Decrement the column loop counter */ + col--; + + } while(col > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + float32_t *pInB = pSrcB->pData; /* input data matrix pointer B */ + uint16_t col, i = 0u, row = numRowsA, colCnt; /* loop counters */ + arm_status status; /* status of matrix multiplication */ + +#ifdef ARM_MATH_MATRIX_CHECK + + /* Check for matrix mismatch condition */ + if((pSrcA->numCols != pSrcB->numRows) || + (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) + { + + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* The following loop performs the dot-product of each row in pInA with each column in pInB */ + /* row loop */ + do + { + /* Output pointer is set to starting address of the row being processed */ + px = pOut + i; + + /* For every row wise process, the column loop counter is to be initiated */ + col = numColsB; + + /* For every row wise process, the pIn2 pointer is set + ** to the starting address of the pSrcB data */ + pIn2 = pSrcB->pData; + + /* column loop */ + do + { + /* Set the variable sum, that acts as accumulator, to zero */ + sum = 0.0f; + + /* Initialize the pointer pIn1 to point to the starting address of the row being processed */ + pIn1 = pInA; + + /* Matrix A columns number of MAC operations are to be performed */ + colCnt = numColsA; + + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + sum += *pIn1++ * (*pIn2); + pIn2 += numColsB; + + /* Decrement the loop counter */ + colCnt--; + } + + /* Store the result in the destination buffer */ + *px++ = sum; + + /* Decrement the column loop counter */ + col--; + + /* Update the pointer pIn2 to point to the starting address of the next column */ + pIn2 = pInB + (numColsB - col); + + } while(col > 0u); + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Update the pointer pInA to point to the starting address of the next row */ + i = i + numColsB; + pInA = pInA + numColsA; + + /* Decrement the row loop counter */ + row--; + + } while(row > 0u); + /* Set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixMult group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q15.c index 871719d96..e97c88844 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q15.c @@ -1,284 +1,284 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_mult_fast_q15.c -* -* Description: Q15 matrix multiplication (fast variant) -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixMult - * @{ - */ - - -/** - * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @param[in] *pState points to the array for storing intermediate results - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The difference between the function arm_mat_mult_q15() and this fast variant is that - * the fast variant use a 32-bit rather than a 64-bit accumulator. - * The result of each 1.15 x 1.15 multiplication is truncated to - * 2.30 format. These intermediate results are accumulated in a 32-bit register in 2.30 - * format. Finally, the accumulator is saturated and converted to a 1.15 result. - * - * \par - * The fast version has the same overflow behavior as the standard version but provides - * less precision since it discards the low 16 bits of each multiplication result. - * In order to avoid overflows completely the input signals must be scaled down. - * Scale down one of the input matrices by log2(numColsA) bits to - * avoid overflows, as a total of numColsA additions are computed internally for each - * output element. - * - * \par - * See arm_mat_mult_q15() for a slower implementation of this function - * which uses 64-bit accumulation to provide higher precision. - */ - -arm_status arm_mat_mult_fast_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst, - q15_t * pState) -{ - q31_t sum; /* accumulator */ - q31_t in; /* Temporary variable to hold the input value */ - q15_t *pSrcBT = pState; /* input data matrix pointer for transpose */ - q15_t *pInA = pSrcA->pData; /* input data matrix pointer A of Q15 type */ - q15_t *pInB = pSrcB->pData; /* input data matrix pointer B of Q15 type */ -// q15_t *pDst = pDst->pData; /* output data matrix pointer */ - q15_t *px; /* Temporary output data matrix pointer */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - uint16_t numRowsB = pSrcB->numRows; /* number of rows of input matrix A */ - uint16_t col, i = 0u, row = numRowsB, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose */ - do - { - /* Apply loop unrolling and exchange the columns with row elements */ - col = numColsB >> 2; - - /* The pointer px is set to starting address of the column being processed */ - px = pSrcBT + i; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(col > 0u) - { - /* Read two elements from the row */ - in = *__SIMD32(pInB)++; - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) in; - -#else - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Unpack and store the second element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *px = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Read two elements from the row */ - in = *__SIMD32(pInB)++; - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) in; - -#else - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Unpack and store the second element in the destination */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *px = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Decrement the column loop counter */ - col--; - } - - /* If the columns of pSrcB is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - col = numColsB % 0x4u; - - while(col > 0u) - { - /* Read and store the input element in the destination */ - *px = *pInB++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Decrement the column loop counter */ - col--; - } - - i++; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* Reset the variables for the usage in the following multiplication process */ - row = numRowsA; - i = 0u; - px = pDst->pData; - - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the transposed pSrcB data */ - pInB = pSrcBT; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Apply loop unrolling and compute 2 MACs simultaneously. */ - colCnt = numColsA >> 1; - - /* Initiate the pointer pIn1 to point to the starting address of the column being processed */ - pInA = pSrcA->pData + i; - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum = __SMLAD(*__SIMD32(pInA)++, *__SIMD32(pInB)++, sum); - - /* Decrement the loop counter */ - colCnt--; - } - - /* process odd column samples */ - if((numColsA & 0x1u) > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum += ((q31_t) * pInA * (*pInB++)); - } - - /* Saturate and store the result in the destination buffer */ - *px = (q15_t) (sum >> 15); - px++; - - /* Decrement the column loop counter */ - col--; - - } while(col > 0u); - - i = i + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixMult group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_mult_fast_q15.c +* +* Description: Q15 matrix multiplication (fast variant) +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixMult + * @{ + */ + + +/** + * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @param[in] *pState points to the array for storing intermediate results + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The difference between the function arm_mat_mult_q15() and this fast variant is that + * the fast variant use a 32-bit rather than a 64-bit accumulator. + * The result of each 1.15 x 1.15 multiplication is truncated to + * 2.30 format. These intermediate results are accumulated in a 32-bit register in 2.30 + * format. Finally, the accumulator is saturated and converted to a 1.15 result. + * + * \par + * The fast version has the same overflow behavior as the standard version but provides + * less precision since it discards the low 16 bits of each multiplication result. + * In order to avoid overflows completely the input signals must be scaled down. + * Scale down one of the input matrices by log2(numColsA) bits to + * avoid overflows, as a total of numColsA additions are computed internally for each + * output element. + * + * \par + * See arm_mat_mult_q15() for a slower implementation of this function + * which uses 64-bit accumulation to provide higher precision. + */ + +arm_status arm_mat_mult_fast_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst, + q15_t * pState) +{ + q31_t sum; /* accumulator */ + q31_t in; /* Temporary variable to hold the input value */ + q15_t *pSrcBT = pState; /* input data matrix pointer for transpose */ + q15_t *pInA = pSrcA->pData; /* input data matrix pointer A of Q15 type */ + q15_t *pInB = pSrcB->pData; /* input data matrix pointer B of Q15 type */ +// q15_t *pDst = pDst->pData; /* output data matrix pointer */ + q15_t *px; /* Temporary output data matrix pointer */ + uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ + uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ + uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ + uint16_t numRowsB = pSrcB->numRows; /* number of rows of input matrix A */ + uint16_t col, i = 0u, row = numRowsB, colCnt; /* loop counters */ + arm_status status; /* status of matrix multiplication */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + + if((pSrcA->numCols != pSrcB->numRows) || + (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Matrix transpose */ + do + { + /* Apply loop unrolling and exchange the columns with row elements */ + col = numColsB >> 2; + + /* The pointer px is set to starting address of the column being processed */ + px = pSrcBT + i; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(col > 0u) + { + /* Read two elements from the row */ + in = *__SIMD32(pInB)++; + + /* Unpack and store one element in the destination */ +#ifndef ARM_MATH_BIG_ENDIAN + + *px = (q15_t) in; + +#else + + *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += numRowsB; + + /* Unpack and store the second element in the destination */ +#ifndef ARM_MATH_BIG_ENDIAN + + *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#else + + *px = (q15_t) in; + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += numRowsB; + + /* Read two elements from the row */ + in = *__SIMD32(pInB)++; + + /* Unpack and store one element in the destination */ +#ifndef ARM_MATH_BIG_ENDIAN + + *px = (q15_t) in; + +#else + + *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += numRowsB; + + /* Unpack and store the second element in the destination */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#else + + *px = (q15_t) in; + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += numRowsB; + + /* Decrement the column loop counter */ + col--; + } + + /* If the columns of pSrcB is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + col = numColsB % 0x4u; + + while(col > 0u) + { + /* Read and store the input element in the destination */ + *px = *pInB++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += numRowsB; + + /* Decrement the column loop counter */ + col--; + } + + i++; + + /* Decrement the row loop counter */ + row--; + + } while(row > 0u); + + /* Reset the variables for the usage in the following multiplication process */ + row = numRowsA; + i = 0u; + px = pDst->pData; + + /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ + /* row loop */ + do + { + /* For every row wise process, the column loop counter is to be initiated */ + col = numColsB; + + /* For every row wise process, the pIn2 pointer is set + ** to the starting address of the transposed pSrcB data */ + pInB = pSrcBT; + + /* column loop */ + do + { + /* Set the variable sum, that acts as accumulator, to zero */ + sum = 0; + + /* Apply loop unrolling and compute 2 MACs simultaneously. */ + colCnt = numColsA >> 1; + + /* Initiate the pointer pIn1 to point to the starting address of the column being processed */ + pInA = pSrcA->pData + i; + + /* matrix multiplication */ + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + sum = __SMLAD(*__SIMD32(pInA)++, *__SIMD32(pInB)++, sum); + + /* Decrement the loop counter */ + colCnt--; + } + + /* process odd column samples */ + if((numColsA & 0x1u) > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + sum += ((q31_t) * pInA * (*pInB++)); + } + + /* Saturate and store the result in the destination buffer */ + *px = (q15_t) (sum >> 15); + px++; + + /* Decrement the column loop counter */ + col--; + + } while(col > 0u); + + i = i + numColsA; + + /* Decrement the row loop counter */ + row--; + + } while(row > 0u); + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixMult group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q31.c index 44387b0e5..8a6ff617e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q31.c @@ -1,202 +1,202 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_mult_fast_q31.c -* -* Description: Q31 matrix multiplication (fast variant). -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixMult - * @{ - */ - -/** - * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The difference between the function arm_mat_mult_q31() and this fast variant is that - * the fast variant use a 32-bit rather than a 64-bit accumulator. - * The result of each 1.31 x 1.31 multiplication is truncated to - * 2.30 format. These intermediate results are accumulated in a 32-bit register in 2.30 - * format. Finally, the accumulator is saturated and converted to a 1.31 result. - * - * \par - * The fast version has the same overflow behavior as the standard version but provides - * less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signals must be scaled down. - * Scale down one of the input matrices by log2(numColsA) bits to - * avoid overflows, as a total of numColsA additions are computed internally for each - * output element. - * - * \par - * See arm_mat_mult_q31() for a slower implementation of this function - * which uses 64-bit accumulation to provide higher precision. - */ - -arm_status arm_mat_mult_fast_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - q31_t *pInA = pSrcA->pData; /* input data matrix pointer A */ -// q31_t *pSrcB = pSrcB->pData; /* input data matrix pointer B */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - q31_t *px; /* Temporary output data matrix pointer */ - q31_t sum; /* Accumulator */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - uint16_t col, i = 0u, j, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - j = 0u; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Initiate the pointer pIn1 to point to the starting address of pInA */ - pIn1 = pInA; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - colCnt = numColsA >> 2; - - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * pIn1++ * (*pIn2))) >> 32); - pIn2 += numColsB; - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * pIn1++ * (*pIn2))) >> 32); - pIn2 += numColsB; - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * pIn1++ * (*pIn2))) >> 32); - pIn2 += numColsB; - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * pIn1++ * (*pIn2))) >> 32); - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* If the columns of pSrcA is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - colCnt = numColsA % 0x4u; - - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * pIn1++ * (*pIn2))) >> 32); - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Convert the result from 2.30 to 1.31 format and store in destination buffer */ - *px++ = sum << 1; - - /* Update the pointer pIn2 to point to the starting address of the next column */ - j++; - pIn2 = pSrcB->pData + j; - - /* Decrement the column loop counter */ - col--; - - } while(col > 0u); - - /* Update the pointer pInA to point to the starting address of the next row */ - i = i + numColsB; - pInA = pInA + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixMult group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_mult_fast_q31.c +* +* Description: Q31 matrix multiplication (fast variant). +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixMult + * @{ + */ + +/** + * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The difference between the function arm_mat_mult_q31() and this fast variant is that + * the fast variant use a 32-bit rather than a 64-bit accumulator. + * The result of each 1.31 x 1.31 multiplication is truncated to + * 2.30 format. These intermediate results are accumulated in a 32-bit register in 2.30 + * format. Finally, the accumulator is saturated and converted to a 1.31 result. + * + * \par + * The fast version has the same overflow behavior as the standard version but provides + * less precision since it discards the low 32 bits of each multiplication result. + * In order to avoid overflows completely the input signals must be scaled down. + * Scale down one of the input matrices by log2(numColsA) bits to + * avoid overflows, as a total of numColsA additions are computed internally for each + * output element. + * + * \par + * See arm_mat_mult_q31() for a slower implementation of this function + * which uses 64-bit accumulation to provide higher precision. + */ + +arm_status arm_mat_mult_fast_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst) +{ + q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ + q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ + q31_t *pInA = pSrcA->pData; /* input data matrix pointer A */ +// q31_t *pSrcB = pSrcB->pData; /* input data matrix pointer B */ + q31_t *pOut = pDst->pData; /* output data matrix pointer */ + q31_t *px; /* Temporary output data matrix pointer */ + q31_t sum; /* Accumulator */ + uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ + uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ + uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ + uint16_t col, i = 0u, j, row = numRowsA, colCnt; /* loop counters */ + arm_status status; /* status of matrix multiplication */ + + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrcA->numCols != pSrcB->numRows) || + (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ + /* row loop */ + do + { + /* Output pointer is set to starting address of the row being processed */ + px = pOut + i; + + /* For every row wise process, the column loop counter is to be initiated */ + col = numColsB; + + /* For every row wise process, the pIn2 pointer is set + ** to the starting address of the pSrcB data */ + pIn2 = pSrcB->pData; + + j = 0u; + + /* column loop */ + do + { + /* Set the variable sum, that acts as accumulator, to zero */ + sum = 0; + + /* Initiate the pointer pIn1 to point to the starting address of pInA */ + pIn1 = pInA; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + colCnt = numColsA >> 2; + + + /* matrix multiplication */ + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + /* Perform the multiply-accumulates */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * pIn1++ * (*pIn2))) >> 32); + pIn2 += numColsB; + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * pIn1++ * (*pIn2))) >> 32); + pIn2 += numColsB; + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * pIn1++ * (*pIn2))) >> 32); + pIn2 += numColsB; + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * pIn1++ * (*pIn2))) >> 32); + pIn2 += numColsB; + + /* Decrement the loop counter */ + colCnt--; + } + + /* If the columns of pSrcA is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + colCnt = numColsA % 0x4u; + + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + /* Perform the multiply-accumulates */ + sum = (q31_t) ((((q63_t) sum << 32) + + ((q63_t) * pIn1++ * (*pIn2))) >> 32); + pIn2 += numColsB; + + /* Decrement the loop counter */ + colCnt--; + } + + /* Convert the result from 2.30 to 1.31 format and store in destination buffer */ + *px++ = sum << 1; + + /* Update the pointer pIn2 to point to the starting address of the next column */ + j++; + pIn2 = pSrcB->pData + j; + + /* Decrement the column loop counter */ + col--; + + } while(col > 0u); + + /* Update the pointer pInA to point to the starting address of the next row */ + i = i + numColsB; + pInA = pInA + numColsA; + + /* Decrement the row loop counter */ + row--; + + } while(row > 0u); + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixMult group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q15.c index 27dd13a22..224d81519 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q15.c @@ -1,378 +1,378 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_mult_q15.c -* -* Description: Q15 matrix multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixMult - * @{ - */ - - -/** - * @brief Q15 matrix multiplication - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @param[in] *pState points to the array for storing intermediate results - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. The inputs to the - * multiplications are in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate - * results are accumulated in a 64-bit accumulator in 34.30 format. This approach - * provides 33 guard bits and there is no risk of overflow. The 34.30 result is then - * truncated to 34.15 format by discarding the low 15 bits and then saturated to - * 1.15 format. - * - * \par - * Refer to arm_mat_mult_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - * - */ - -arm_status arm_mat_mult_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst, - q15_t * pState) -{ - q63_t sum; /* accumulator */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in; /* Temporary variable to hold the input value */ - q15_t *pSrcBT = pState; /* input data matrix pointer for transpose */ - q15_t *pInA = pSrcA->pData; /* input data matrix pointer A of Q15 type */ - q15_t *pInB = pSrcB->pData; /* input data matrix pointer B of Q15 type */ - q15_t *px; /* Temporary output data matrix pointer */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - uint16_t numRowsB = pSrcB->numRows; /* number of rows of input matrix A */ - uint16_t col, i = 0u, row = numRowsB, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose */ - do - { - /* Apply loop unrolling and exchange the columns with row elements */ - col = numColsB >> 2; - - /* The pointer px is set to starting address of the column being processed */ - px = pSrcBT + i; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(col > 0u) - { - /* Read two elements from the row */ - in = *__SIMD32(pInB)++; - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) in; - -#else - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Unpack and store the second element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *px = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Read two elements from the row */ - in = *__SIMD32(pInB)++; - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) in; - -#else - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Unpack and store the second element in the destination */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *px = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Decrement the column loop counter */ - col--; - } - - /* If the columns of pSrcB is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - col = numColsB % 0x4u; - - while(col > 0u) - { - /* Read and store the input element in the destination */ - *px = *pInB++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Decrement the column loop counter */ - col--; - } - - i++; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* Reset the variables for the usage in the following multiplication process */ - row = numRowsA; - i = 0u; - px = pDst->pData; - - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the transposed pSrcB data */ - pInB = pSrcBT; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Apply loop unrolling and compute 2 MACs simultaneously. */ - colCnt = numColsA >> 1; - - /* Initiate the pointer pIn1 to point to the starting address of the column being processed */ - pInA = pSrcA->pData + i; - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum = __SMLALD(*__SIMD32(pInA)++, *__SIMD32(pInB)++, sum); - - /* Decrement the loop counter */ - colCnt--; - } - - /* process odd column samples */ - if((numColsA & 0x1u) > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum += ((q31_t) * pInA * (*pInB++)); - } - - /* Saturate and store the result in the destination buffer */ - *px = (q15_t) (__SSAT((sum >> 15), 16)); - px++; - - /* Decrement the column loop counter */ - col--; - - } while(col > 0u); - - i = i + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - q15_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - q15_t *pInA = pSrcA->pData; /* input data matrix pointer A of Q15 type */ - q15_t *pInB = pSrcB->pData; /* input data matrix pointer B of Q15 type */ - q15_t *pOut = pDst->pData; /* output data matrix pointer */ - q15_t *px; /* Temporary output data matrix pointer */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t col, i = 0u, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Initiate the pointer pIn1 to point to the starting address of pSrcA */ - pIn1 = pInA; - - /* Matrix A columns number of MAC operations are to be performed */ - colCnt = numColsA; - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - sum += (q31_t) * pIn1++ * *pIn2; - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Convert the result from 34.30 to 1.15 format and store the saturated value in destination buffer */ - /* Saturate and store the result in the destination buffer */ - *px++ = (q15_t) __SSAT((sum >> 15), 16); - - /* Decrement the column loop counter */ - col--; - - /* Update the pointer pIn2 to point to the starting address of the next column */ - pIn2 = pInB + (numColsB - col); - - } while(col > 0u); - - /* Update the pointer pSrcA to point to the starting address of the next row */ - i = i + numColsB; - pInA = pInA + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixMult group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_mult_q15.c +* +* Description: Q15 matrix multiplication. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixMult + * @{ + */ + + +/** + * @brief Q15 matrix multiplication + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @param[in] *pState points to the array for storing intermediate results + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 64-bit internal accumulator. The inputs to the + * multiplications are in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate + * results are accumulated in a 64-bit accumulator in 34.30 format. This approach + * provides 33 guard bits and there is no risk of overflow. The 34.30 result is then + * truncated to 34.15 format by discarding the low 15 bits and then saturated to + * 1.15 format. + * + * \par + * Refer to arm_mat_mult_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. + * + */ + +arm_status arm_mat_mult_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst, + q15_t * pState) +{ + q63_t sum; /* accumulator */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t in; /* Temporary variable to hold the input value */ + q15_t *pSrcBT = pState; /* input data matrix pointer for transpose */ + q15_t *pInA = pSrcA->pData; /* input data matrix pointer A of Q15 type */ + q15_t *pInB = pSrcB->pData; /* input data matrix pointer B of Q15 type */ + q15_t *px; /* Temporary output data matrix pointer */ + uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ + uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ + uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ + uint16_t numRowsB = pSrcB->numRows; /* number of rows of input matrix A */ + uint16_t col, i = 0u, row = numRowsB, colCnt; /* loop counters */ + arm_status status; /* status of matrix multiplication */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + + if((pSrcA->numCols != pSrcB->numRows) || + (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Matrix transpose */ + do + { + /* Apply loop unrolling and exchange the columns with row elements */ + col = numColsB >> 2; + + /* The pointer px is set to starting address of the column being processed */ + px = pSrcBT + i; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(col > 0u) + { + /* Read two elements from the row */ + in = *__SIMD32(pInB)++; + + /* Unpack and store one element in the destination */ +#ifndef ARM_MATH_BIG_ENDIAN + + *px = (q15_t) in; + +#else + + *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += numRowsB; + + /* Unpack and store the second element in the destination */ +#ifndef ARM_MATH_BIG_ENDIAN + + *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#else + + *px = (q15_t) in; + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += numRowsB; + + /* Read two elements from the row */ + in = *__SIMD32(pInB)++; + + /* Unpack and store one element in the destination */ +#ifndef ARM_MATH_BIG_ENDIAN + + *px = (q15_t) in; + +#else + + *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += numRowsB; + + /* Unpack and store the second element in the destination */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#else + + *px = (q15_t) in; + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += numRowsB; + + /* Decrement the column loop counter */ + col--; + } + + /* If the columns of pSrcB is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + col = numColsB % 0x4u; + + while(col > 0u) + { + /* Read and store the input element in the destination */ + *px = *pInB++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += numRowsB; + + /* Decrement the column loop counter */ + col--; + } + + i++; + + /* Decrement the row loop counter */ + row--; + + } while(row > 0u); + + /* Reset the variables for the usage in the following multiplication process */ + row = numRowsA; + i = 0u; + px = pDst->pData; + + /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ + /* row loop */ + do + { + /* For every row wise process, the column loop counter is to be initiated */ + col = numColsB; + + /* For every row wise process, the pIn2 pointer is set + ** to the starting address of the transposed pSrcB data */ + pInB = pSrcBT; + + /* column loop */ + do + { + /* Set the variable sum, that acts as accumulator, to zero */ + sum = 0; + + /* Apply loop unrolling and compute 2 MACs simultaneously. */ + colCnt = numColsA >> 1; + + /* Initiate the pointer pIn1 to point to the starting address of the column being processed */ + pInA = pSrcA->pData + i; + + /* matrix multiplication */ + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + sum = __SMLALD(*__SIMD32(pInA)++, *__SIMD32(pInB)++, sum); + + /* Decrement the loop counter */ + colCnt--; + } + + /* process odd column samples */ + if((numColsA & 0x1u) > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + sum += ((q31_t) * pInA * (*pInB++)); + } + + /* Saturate and store the result in the destination buffer */ + *px = (q15_t) (__SSAT((sum >> 15), 16)); + px++; + + /* Decrement the column loop counter */ + col--; + + } while(col > 0u); + + i = i + numColsA; + + /* Decrement the row loop counter */ + row--; + + } while(row > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + q15_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ + q15_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ + q15_t *pInA = pSrcA->pData; /* input data matrix pointer A of Q15 type */ + q15_t *pInB = pSrcB->pData; /* input data matrix pointer B of Q15 type */ + q15_t *pOut = pDst->pData; /* output data matrix pointer */ + q15_t *px; /* Temporary output data matrix pointer */ + uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ + uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ + uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ + uint16_t col, i = 0u, row = numRowsA, colCnt; /* loop counters */ + arm_status status; /* status of matrix multiplication */ + +#ifdef ARM_MATH_MATRIX_CHECK + + /* Check for matrix mismatch condition */ + if((pSrcA->numCols != pSrcB->numRows) || + (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ + /* row loop */ + do + { + /* Output pointer is set to starting address of the row being processed */ + px = pOut + i; + + /* For every row wise process, the column loop counter is to be initiated */ + col = numColsB; + + /* For every row wise process, the pIn2 pointer is set + ** to the starting address of the pSrcB data */ + pIn2 = pSrcB->pData; + + /* column loop */ + do + { + /* Set the variable sum, that acts as accumulator, to zero */ + sum = 0; + + /* Initiate the pointer pIn1 to point to the starting address of pSrcA */ + pIn1 = pInA; + + /* Matrix A columns number of MAC operations are to be performed */ + colCnt = numColsA; + + /* matrix multiplication */ + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + /* Perform the multiply-accumulates */ + sum += (q31_t) * pIn1++ * *pIn2; + pIn2 += numColsB; + + /* Decrement the loop counter */ + colCnt--; + } + + /* Convert the result from 34.30 to 1.15 format and store the saturated value in destination buffer */ + /* Saturate and store the result in the destination buffer */ + *px++ = (q15_t) __SSAT((sum >> 15), 16); + + /* Decrement the column loop counter */ + col--; + + /* Update the pointer pIn2 to point to the starting address of the next column */ + pIn2 = pInB + (numColsB - col); + + } while(col > 0u); + + /* Update the pointer pSrcA to point to the starting address of the next row */ + i = i + numColsB; + pInA = pInA + numColsA; + + /* Decrement the row loop counter */ + row--; + + } while(row > 0u); + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixMult group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q31.c index ad5036547..51999ebbc 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q31.c @@ -1,278 +1,278 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_mult_q31.c -* -* Description: Q31 matrix multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixMult - * @{ - */ - -/** - * @brief Q31 matrix multiplication - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate - * multiplication results but provides only a single guard bit. There is no saturation - * on intermediate additions. Thus, if the accumulator overflows it wraps around and - * distorts the result. The input signals should be scaled down to avoid intermediate - * overflows. The input is thus scaled down by log2(numColsA) bits - * to avoid overflows, as a total of numColsA additions are performed internally. - * The 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. - * - * \par - * See arm_mat_mult_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - * - */ - -arm_status arm_mat_mult_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - q31_t *pInA = pSrcA->pData; /* input data matrix pointer A */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - q31_t *px; /* Temporary output data matrix pointer */ - q63_t sum; /* Accumulator */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - uint16_t col, i = 0u, j, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - j = 0u; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Initiate the pointer pIn1 to point to the starting address of pInA */ - pIn1 = pInA; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - colCnt = numColsA >> 2; - - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - sum += (q63_t) * pIn1++ * *pIn2; - pIn2 += numColsB; - - sum += (q63_t) * pIn1++ * *pIn2; - pIn2 += numColsB; - - sum += (q63_t) * pIn1++ * *pIn2; - pIn2 += numColsB; - - sum += (q63_t) * pIn1++ * *pIn2; - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* If the columns of pSrcA is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - colCnt = numColsA % 0x4u; - - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - sum += (q63_t) * pIn1++ * *pIn2; - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Convert the result from 2.62 to 1.31 format and store in destination buffer */ - *px++ = (q31_t) (sum >> 31); - - /* Update the pointer pIn2 to point to the starting address of the next column */ - j++; - pIn2 = (pSrcB->pData) + j; - - /* Decrement the column loop counter */ - col--; - - } while(col > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t *pInB = pSrcB->pData; /* input data matrix pointer B */ - uint16_t col, i = 0u, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Initiate the pointer pIn1 to point to the starting address of pInA */ - pIn1 = pInA; - - /* Matrix A columns number of MAC operations are to be performed */ - colCnt = numColsA; - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - sum += (q63_t) * pIn1++ * *pIn2; - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Convert the result from 2.62 to 1.31 format and store in destination buffer */ - *px++ = (q31_t) (sum >> 31); - - /* Decrement the column loop counter */ - col--; - - /* Update the pointer pIn2 to point to the starting address of the next column */ - pIn2 = pInB + (numColsB - col); - - } while(col > 0u); - -#endif - - /* Update the pointer pInA to point to the starting address of the next row */ - i = i + numColsB; - pInA = pInA + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixMult group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_mult_q31.c +* +* Description: Q31 matrix multiplication. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixMult + * @{ + */ + +/** + * @brief Q31 matrix multiplication + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate + * multiplication results but provides only a single guard bit. There is no saturation + * on intermediate additions. Thus, if the accumulator overflows it wraps around and + * distorts the result. The input signals should be scaled down to avoid intermediate + * overflows. The input is thus scaled down by log2(numColsA) bits + * to avoid overflows, as a total of numColsA additions are performed internally. + * The 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. + * + * \par + * See arm_mat_mult_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. + * + */ + +arm_status arm_mat_mult_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst) +{ + q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ + q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ + q31_t *pInA = pSrcA->pData; /* input data matrix pointer A */ + q31_t *pOut = pDst->pData; /* output data matrix pointer */ + q31_t *px; /* Temporary output data matrix pointer */ + q63_t sum; /* Accumulator */ + uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ + uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ + uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + uint16_t col, i = 0u, j, row = numRowsA, colCnt; /* loop counters */ + arm_status status; /* status of matrix multiplication */ + + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrcA->numCols != pSrcB->numRows) || + (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ + /* row loop */ + do + { + /* Output pointer is set to starting address of the row being processed */ + px = pOut + i; + + /* For every row wise process, the column loop counter is to be initiated */ + col = numColsB; + + /* For every row wise process, the pIn2 pointer is set + ** to the starting address of the pSrcB data */ + pIn2 = pSrcB->pData; + + j = 0u; + + /* column loop */ + do + { + /* Set the variable sum, that acts as accumulator, to zero */ + sum = 0; + + /* Initiate the pointer pIn1 to point to the starting address of pInA */ + pIn1 = pInA; + + /* Apply loop unrolling and compute 4 MACs simultaneously. */ + colCnt = numColsA >> 2; + + + /* matrix multiplication */ + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + /* Perform the multiply-accumulates */ + sum += (q63_t) * pIn1++ * *pIn2; + pIn2 += numColsB; + + sum += (q63_t) * pIn1++ * *pIn2; + pIn2 += numColsB; + + sum += (q63_t) * pIn1++ * *pIn2; + pIn2 += numColsB; + + sum += (q63_t) * pIn1++ * *pIn2; + pIn2 += numColsB; + + /* Decrement the loop counter */ + colCnt--; + } + + /* If the columns of pSrcA is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + colCnt = numColsA % 0x4u; + + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + /* Perform the multiply-accumulates */ + sum += (q63_t) * pIn1++ * *pIn2; + pIn2 += numColsB; + + /* Decrement the loop counter */ + colCnt--; + } + + /* Convert the result from 2.62 to 1.31 format and store in destination buffer */ + *px++ = (q31_t) (sum >> 31); + + /* Update the pointer pIn2 to point to the starting address of the next column */ + j++; + pIn2 = (pSrcB->pData) + j; + + /* Decrement the column loop counter */ + col--; + + } while(col > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + q31_t *pInB = pSrcB->pData; /* input data matrix pointer B */ + uint16_t col, i = 0u, row = numRowsA, colCnt; /* loop counters */ + arm_status status; /* status of matrix multiplication */ + + +#ifdef ARM_MATH_MATRIX_CHECK + + /* Check for matrix mismatch condition */ + if((pSrcA->numCols != pSrcB->numRows) || + (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ + /* row loop */ + do + { + /* Output pointer is set to starting address of the row being processed */ + px = pOut + i; + + /* For every row wise process, the column loop counter is to be initiated */ + col = numColsB; + + /* For every row wise process, the pIn2 pointer is set + ** to the starting address of the pSrcB data */ + pIn2 = pSrcB->pData; + + /* column loop */ + do + { + /* Set the variable sum, that acts as accumulator, to zero */ + sum = 0; + + /* Initiate the pointer pIn1 to point to the starting address of pInA */ + pIn1 = pInA; + + /* Matrix A columns number of MAC operations are to be performed */ + colCnt = numColsA; + + /* matrix multiplication */ + while(colCnt > 0u) + { + /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ + /* Perform the multiply-accumulates */ + sum += (q63_t) * pIn1++ * *pIn2; + pIn2 += numColsB; + + /* Decrement the loop counter */ + colCnt--; + } + + /* Convert the result from 2.62 to 1.31 format and store in destination buffer */ + *px++ = (q31_t) (sum >> 31); + + /* Decrement the column loop counter */ + col--; + + /* Update the pointer pIn2 to point to the starting address of the next column */ + pIn2 = pInB + (numColsB - col); + + } while(col > 0u); + +#endif + + /* Update the pointer pInA to point to the starting address of the next row */ + i = i + numColsB; + pInA = pInA + numColsA; + + /* Decrement the row loop counter */ + row--; + + } while(row > 0u); + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixMult group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_f32.c index 65d5cfd20..39d1ff9cf 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_f32.c @@ -1,156 +1,156 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_scale_f32.c -* -* Description: Multiplies a floating-point matrix by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixScale Matrix Scale - * - * Multiplies a matrix by a scalar. This is accomplished by multiplying each element in the - * matrix by the scalar. For example: - * \image html MatrixScale.gif "Matrix Scaling of a 3 x 3 matrix" - * - * The function checks to make sure that the input and output matrices are of the same size. - * - * In the fixed-point Q15 and Q31 functions, scale is represented by - * a fractional multiplication scaleFract and an arithmetic shift shift. - * The shift allows the gain of the scaling operation to exceed 1.0. - * The overall scale factor applied to the fixed-point data is - *
   
- *     scale = scaleFract * 2^shift.   
- * 
- */ - -/** - * @addtogroup MatrixScale - * @{ - */ - -/** - * @brief Floating-point matrix scaling. - * @param[in] *pSrc points to input matrix structure - * @param[in] scale scale factor to be applied - * @param[out] *pDst points to output matrix structure - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - * - */ - -arm_status arm_mat_scale_f32( - const arm_matrix_instance_f32 * pSrc, - float32_t scale, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn = pSrc->pData; /* input data matrix pointer */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix scaling */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numRows) || (pSrc->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrc->numRows * pSrc->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop Unrolling */ - blkCnt = numSamples >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * scale */ - /* Scaling and results are stored in the destination buffer. */ - *pOut++ = (*pIn++) * scale; - *pOut++ = (*pIn++) * scale; - *pOut++ = (*pIn++) * scale; - *pOut++ = (*pIn++) * scale; - - /* Decrement the numSamples loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * scale */ - /* The results are stored in the destination buffer. */ - *pOut++ = (*pIn++) * scale; - - /* Decrement the loop counter */ - blkCnt--; - } - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixScale group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_scale_f32.c +* +* Description: Multiplies a floating-point matrix by a scalar. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @defgroup MatrixScale Matrix Scale + * + * Multiplies a matrix by a scalar. This is accomplished by multiplying each element in the + * matrix by the scalar. For example: + * \image html MatrixScale.gif "Matrix Scaling of a 3 x 3 matrix" + * + * The function checks to make sure that the input and output matrices are of the same size. + * + * In the fixed-point Q15 and Q31 functions, scale is represented by + * a fractional multiplication scaleFract and an arithmetic shift shift. + * The shift allows the gain of the scaling operation to exceed 1.0. + * The overall scale factor applied to the fixed-point data is + *
   
+ *     scale = scaleFract * 2^shift.   
+ * 
+ */ + +/** + * @addtogroup MatrixScale + * @{ + */ + +/** + * @brief Floating-point matrix scaling. + * @param[in] *pSrc points to input matrix structure + * @param[in] scale scale factor to be applied + * @param[out] *pDst points to output matrix structure + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + * + */ + +arm_status arm_mat_scale_f32( + const arm_matrix_instance_f32 * pSrc, + float32_t scale, + arm_matrix_instance_f32 * pDst) +{ + float32_t *pIn = pSrc->pData; /* input data matrix pointer */ + float32_t *pOut = pDst->pData; /* output data matrix pointer */ + uint32_t numSamples; /* total number of elements in the matrix */ + uint32_t blkCnt; /* loop counters */ + arm_status status; /* status of matrix scaling */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrc->numRows != pDst->numRows) || (pSrc->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Total number of samples in the input matrix */ + numSamples = (uint32_t) pSrc->numRows * pSrc->numCols; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Loop Unrolling */ + blkCnt = numSamples >> 2; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) * scale */ + /* Scaling and results are stored in the destination buffer. */ + *pOut++ = (*pIn++) * scale; + *pOut++ = (*pIn++) * scale; + *pOut++ = (*pIn++) * scale; + *pOut++ = (*pIn++) * scale; + + /* Decrement the numSamples loop counter */ + blkCnt--; + } + + /* If the numSamples is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = numSamples % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = numSamples; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) * scale */ + /* The results are stored in the destination buffer. */ + *pOut++ = (*pIn++) * scale; + + /* Decrement the loop counter */ + blkCnt--; + } + /* Set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixScale group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q15.c index fbdc51134..aec990412 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q15.c @@ -1,150 +1,150 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_scale_q15.c -* -* Description: Multiplies a Q15 matrix by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixScale - * @{ - */ - -/** - * @brief Q15 matrix scaling. - * @param[in] *pSrc points to input matrix - * @param[in] scaleFract fractional portion of the scale factor - * @param[in] shift number of bits to shift the result by - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The input data *pSrc and scaleFract are in 1.15 format. - * These are multiplied to yield a 2.30 intermediate result and this is shifted with saturation to 1.15 format. - */ - -arm_status arm_mat_scale_q15( - const arm_matrix_instance_q15 * pSrc, - q15_t scaleFract, - int32_t shift, - arm_matrix_instance_q15 * pDst) -{ - q15_t *pIn = pSrc->pData; /* input data matrix pointer */ - q15_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - int32_t totShift = 15 - shift; /* total shift to apply after scaling */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix scaling */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch */ - if((pSrc->numRows != pDst->numRows) || (pSrc->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrc->numRows * pSrc->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - /* Loop Unrolling */ - blkCnt = numSamples >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * k */ - /* Scale, saturate and then store the results in the destination buffer. */ - *pOut++ = - (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); - *pOut++ = - (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); - *pOut++ = - (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); - *pOut++ = - (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); - - /* Decrement the numSamples loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * k */ - /* Scale, saturate and then store the results in the destination buffer. */ - *pOut++ = - (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); - - /* Decrement the numSamples loop counter */ - blkCnt--; - } - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixScale group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_scale_q15.c +* +* Description: Multiplies a Q15 matrix by a scalar. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixScale + * @{ + */ + +/** + * @brief Q15 matrix scaling. + * @param[in] *pSrc points to input matrix + * @param[in] scaleFract fractional portion of the scale factor + * @param[in] shift number of bits to shift the result by + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + * + * @details + * Scaling and Overflow Behavior: + * \par + * The input data *pSrc and scaleFract are in 1.15 format. + * These are multiplied to yield a 2.30 intermediate result and this is shifted with saturation to 1.15 format. + */ + +arm_status arm_mat_scale_q15( + const arm_matrix_instance_q15 * pSrc, + q15_t scaleFract, + int32_t shift, + arm_matrix_instance_q15 * pDst) +{ + q15_t *pIn = pSrc->pData; /* input data matrix pointer */ + q15_t *pOut = pDst->pData; /* output data matrix pointer */ + uint32_t numSamples; /* total number of elements in the matrix */ + int32_t totShift = 15 - shift; /* total shift to apply after scaling */ + uint32_t blkCnt; /* loop counters */ + arm_status status; /* status of matrix scaling */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch */ + if((pSrc->numRows != pDst->numRows) || (pSrc->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Total number of samples in the input matrix */ + numSamples = (uint32_t) pSrc->numRows * pSrc->numCols; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + /* Loop Unrolling */ + blkCnt = numSamples >> 2; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) * k */ + /* Scale, saturate and then store the results in the destination buffer. */ + *pOut++ = + (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); + *pOut++ = + (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); + *pOut++ = + (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); + *pOut++ = + (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); + + /* Decrement the numSamples loop counter */ + blkCnt--; + } + + /* If the numSamples is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = numSamples % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = numSamples; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) * k */ + /* Scale, saturate and then store the results in the destination buffer. */ + *pOut++ = + (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); + + /* Decrement the numSamples loop counter */ + blkCnt--; + } + /* Set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixScale group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q31.c index e94f9a5cb..4b894af1e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q31.c @@ -1,152 +1,152 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_scale_q31.c -* -* Description: Multiplies a Q31 matrix by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixScale - * @{ - */ - -/** - * @brief Q31 matrix scaling. - * @param[in] *pSrc points to input matrix - * @param[in] scaleFract fractional portion of the scale factor - * @param[in] shift number of bits to shift the result by - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The input data *pSrc and scaleFract are in 1.31 format. - * These are multiplied to yield a 2.62 intermediate result and this is shifted with saturation to 1.31 format. - */ - -arm_status arm_mat_scale_q31( - const arm_matrix_instance_q31 * pSrc, - q31_t scaleFract, - int32_t shift, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn = pSrc->pData; /* input data matrix pointer */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - q63_t out; /* temporary variable to hold output value */ - uint32_t numSamples; /* total number of elements in the matrix */ - int32_t totShift = 31 - shift; /* shift to apply after scaling */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix scaling */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch */ - if((pSrc->numRows != pDst->numRows) || (pSrc->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrc->numRows * pSrc->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop Unrolling */ - blkCnt = numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * k */ - /* Scale, saturate and then store the results in the destination buffer. */ - out = ((q63_t) * pIn++ * scaleFract) >> totShift; - *pOut++ = clip_q63_to_q31(out); - out = ((q63_t) * pIn++ * scaleFract) >> totShift; - *pOut++ = clip_q63_to_q31(out); - out = ((q63_t) * pIn++ * scaleFract) >> totShift; - *pOut++ = clip_q63_to_q31(out); - out = ((q63_t) * pIn++ * scaleFract) >> totShift; - *pOut++ = clip_q63_to_q31(out); - - /* Decrement the numSamples loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * k */ - /* Scale, saturate and then store the results in the destination buffer. */ - out = ((q63_t) * pIn++ * scaleFract) >> totShift; - *pOut++ = clip_q63_to_q31(out); - - /* Decrement the numSamples loop counter */ - blkCnt--; - } - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixScale group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_scale_q31.c +* +* Description: Multiplies a Q31 matrix by a scalar. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixScale + * @{ + */ + +/** + * @brief Q31 matrix scaling. + * @param[in] *pSrc points to input matrix + * @param[in] scaleFract fractional portion of the scale factor + * @param[in] shift number of bits to shift the result by + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + * + * @details + * Scaling and Overflow Behavior: + * \par + * The input data *pSrc and scaleFract are in 1.31 format. + * These are multiplied to yield a 2.62 intermediate result and this is shifted with saturation to 1.31 format. + */ + +arm_status arm_mat_scale_q31( + const arm_matrix_instance_q31 * pSrc, + q31_t scaleFract, + int32_t shift, + arm_matrix_instance_q31 * pDst) +{ + q31_t *pIn = pSrc->pData; /* input data matrix pointer */ + q31_t *pOut = pDst->pData; /* output data matrix pointer */ + q63_t out; /* temporary variable to hold output value */ + uint32_t numSamples; /* total number of elements in the matrix */ + int32_t totShift = 31 - shift; /* shift to apply after scaling */ + uint32_t blkCnt; /* loop counters */ + arm_status status; /* status of matrix scaling */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch */ + if((pSrc->numRows != pDst->numRows) || (pSrc->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Total number of samples in the input matrix */ + numSamples = (uint32_t) pSrc->numRows * pSrc->numCols; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Loop Unrolling */ + blkCnt = numSamples >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) * k */ + /* Scale, saturate and then store the results in the destination buffer. */ + out = ((q63_t) * pIn++ * scaleFract) >> totShift; + *pOut++ = clip_q63_to_q31(out); + out = ((q63_t) * pIn++ * scaleFract) >> totShift; + *pOut++ = clip_q63_to_q31(out); + out = ((q63_t) * pIn++ * scaleFract) >> totShift; + *pOut++ = clip_q63_to_q31(out); + out = ((q63_t) * pIn++ * scaleFract) >> totShift; + *pOut++ = clip_q63_to_q31(out); + + /* Decrement the numSamples loop counter */ + blkCnt--; + } + + /* If the numSamples is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = numSamples % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = numSamples; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) * k */ + /* Scale, saturate and then store the results in the destination buffer. */ + out = ((q63_t) * pIn++ * scaleFract) >> totShift; + *pOut++ = clip_q63_to_q31(out); + + /* Decrement the numSamples loop counter */ + blkCnt--; + } + /* Set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixScale group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_f32.c index 4a5823e89..d2cce6820 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_f32.c @@ -1,151 +1,151 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_sub_f32.c -* -* Description: Floating-point matrix subtraction. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixSub Matrix Subtraction - * - * Subtract two matrices. - * \image html MatrixSubtraction.gif "Subraction of two 3 x 3 matrices" - * - * The functions check to make sure that - * pSrcA, pSrcB, and pDst have the same - * number of rows and columns. - */ - -/** - * @addtogroup MatrixSub - * @{ - */ - -/** - * @brief Floating-point matrix subtraction - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - -arm_status arm_mat_sub_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - float32_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix subtraction */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop Unrolling */ - blkCnt = numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract and then store the results in the destination buffer. */ - *pOut++ = (*pIn1++) - (*pIn2++); - *pOut++ = (*pIn1++) - (*pIn2++); - *pOut++ = (*pIn1++) - (*pIn2++); - *pOut++ = (*pIn1++) - (*pIn2++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract and then store the results in the destination buffer. */ - *pOut++ = (*pIn1++) - (*pIn2++); - - /* Decrement the loop counter */ - blkCnt--; - } - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixSub group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_sub_f32.c +* +* Description: Floating-point matrix subtraction. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @defgroup MatrixSub Matrix Subtraction + * + * Subtract two matrices. + * \image html MatrixSubtraction.gif "Subraction of two 3 x 3 matrices" + * + * The functions check to make sure that + * pSrcA, pSrcB, and pDst have the same + * number of rows and columns. + */ + +/** + * @addtogroup MatrixSub + * @{ + */ + +/** + * @brief Floating-point matrix subtraction + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + +arm_status arm_mat_sub_f32( + const arm_matrix_instance_f32 * pSrcA, + const arm_matrix_instance_f32 * pSrcB, + arm_matrix_instance_f32 * pDst) +{ + float32_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ + float32_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ + float32_t *pOut = pDst->pData; /* output data matrix pointer */ + uint32_t numSamples; /* total number of elements in the matrix */ + uint32_t blkCnt; /* loop counters */ + arm_status status; /* status of matrix subtraction */ + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrcA->numRows != pSrcB->numRows) || + (pSrcA->numCols != pSrcB->numCols) || + (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Total number of samples in the input matrix */ + numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Loop Unrolling */ + blkCnt = numSamples >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) - B(m,n) */ + /* Subtract and then store the results in the destination buffer. */ + *pOut++ = (*pIn1++) - (*pIn2++); + *pOut++ = (*pIn1++) - (*pIn2++); + *pOut++ = (*pIn1++) - (*pIn2++); + *pOut++ = (*pIn1++) - (*pIn2++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the numSamples is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = numSamples % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = numSamples; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) - B(m,n) */ + /* Subtract and then store the results in the destination buffer. */ + *pOut++ = (*pIn1++) - (*pIn2++); + + /* Decrement the loop counter */ + blkCnt--; + } + /* Set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixSub group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q15.c index d8acbd31c..5f6dd58d3 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q15.c @@ -1,155 +1,155 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_sub_q15.c -* -* Description: Q15 Matrix subtraction -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixSub - * @{ - */ - -/** - * @brief Q15 matrix subtraction. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -arm_status arm_mat_sub_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst) -{ - q15_t *pInA = pSrcA->pData; /* input data matrix pointer A */ - q15_t *pInB = pSrcB->pData; /* input data matrix pointer B */ - q15_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix subtraction */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Apply loop unrolling */ - blkCnt = numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract, Saturate and then store the results in the destination buffer. */ - *__SIMD32(pOut)++ = __QSUB16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); - *__SIMD32(pOut)++ = __QSUB16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract and then store the results in the destination buffer. */ - *pOut++ = (q15_t) __QSUB16(*pInA++, *pInB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract and then store the results in the destination buffer. */ - *pOut++ = (q15_t) __SSAT(((q31_t) * pInA++ - *pInB++), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixSub group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_sub_q15.c +* +* Description: Q15 Matrix subtraction +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixSub + * @{ + */ + +/** + * @brief Q15 matrix subtraction. + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. + */ + +arm_status arm_mat_sub_q15( + const arm_matrix_instance_q15 * pSrcA, + const arm_matrix_instance_q15 * pSrcB, + arm_matrix_instance_q15 * pDst) +{ + q15_t *pInA = pSrcA->pData; /* input data matrix pointer A */ + q15_t *pInB = pSrcB->pData; /* input data matrix pointer B */ + q15_t *pOut = pDst->pData; /* output data matrix pointer */ + uint32_t numSamples; /* total number of elements in the matrix */ + uint32_t blkCnt; /* loop counters */ + arm_status status; /* status of matrix subtraction */ + + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrcA->numRows != pSrcB->numRows) || + (pSrcA->numCols != pSrcB->numCols) || + (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Total number of samples in the input matrix */ + numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Apply loop unrolling */ + blkCnt = numSamples >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) - B(m,n) */ + /* Subtract, Saturate and then store the results in the destination buffer. */ + *__SIMD32(pOut)++ = __QSUB16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); + *__SIMD32(pOut)++ = __QSUB16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = numSamples % 0x4u; + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) - B(m,n) */ + /* Subtract and then store the results in the destination buffer. */ + *pOut++ = (q15_t) __QSUB16(*pInA++, *pInB++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = numSamples; + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) - B(m,n) */ + /* Subtract and then store the results in the destination buffer. */ + *pOut++ = (q15_t) __SSAT(((q31_t) * pInA++ - *pInB++), 16); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixSub group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q31.c index c5eac4e77..3de675c5f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q31.c @@ -1,158 +1,158 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_sub_q31.c -* -* Description: Q31 matrix subtraction -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixSub - * @{ - */ - -/** - * @brief Q31 matrix subtraction. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. - */ - - -arm_status arm_mat_sub_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix subtraction */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop Unrolling */ - blkCnt = numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract, saturate and then store the results in the destination buffer. */ - *pOut++ = __QSUB(*pIn1++, *pIn2++); - *pOut++ = __QSUB(*pIn1++, *pIn2++); - *pOut++ = __QSUB(*pIn1++, *pIn2++); - *pOut++ = __QSUB(*pIn1++, *pIn2++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract, saturate and then store the results in the destination buffer. */ - *pOut++ = __QSUB(*pIn1++, *pIn2++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract, saturate and then store the results in the destination buffer. */ - *pOut++ = clip_q63_to_q31(((q63_t) (*pIn1++)) - (*pIn2++)); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixSub group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_sub_q31.c +* +* Description: Q31 matrix subtraction +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixSub + * @{ + */ + +/** + * @brief Q31 matrix subtraction. + * @param[in] *pSrcA points to the first input matrix structure + * @param[in] *pSrcB points to the second input matrix structure + * @param[out] *pDst points to output matrix structure + * @return The function returns either + * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. + * + * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. + */ + + +arm_status arm_mat_sub_q31( + const arm_matrix_instance_q31 * pSrcA, + const arm_matrix_instance_q31 * pSrcB, + arm_matrix_instance_q31 * pDst) +{ + q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ + q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ + q31_t *pOut = pDst->pData; /* output data matrix pointer */ + uint32_t numSamples; /* total number of elements in the matrix */ + uint32_t blkCnt; /* loop counters */ + arm_status status; /* status of matrix subtraction */ + + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrcA->numRows != pSrcB->numRows) || + (pSrcA->numCols != pSrcB->numCols) || + (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Total number of samples in the input matrix */ + numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Loop Unrolling */ + blkCnt = numSamples >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) - B(m,n) */ + /* Subtract, saturate and then store the results in the destination buffer. */ + *pOut++ = __QSUB(*pIn1++, *pIn2++); + *pOut++ = __QSUB(*pIn1++, *pIn2++); + *pOut++ = __QSUB(*pIn1++, *pIn2++); + *pOut++ = __QSUB(*pIn1++, *pIn2++); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the numSamples is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = numSamples % 0x4u; + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) - B(m,n) */ + /* Subtract, saturate and then store the results in the destination buffer. */ + *pOut++ = __QSUB(*pIn1++, *pIn2++); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initialize blkCnt with number of samples */ + blkCnt = numSamples; + + while(blkCnt > 0u) + { + /* C(m,n) = A(m,n) - B(m,n) */ + /* Subtract, saturate and then store the results in the destination buffer. */ + *pOut++ = clip_q63_to_q31(((q63_t) (*pIn1++)) - (*pIn2++)); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixSub group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_f32.c index ada0c3914..876fab68b 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_f32.c @@ -1,213 +1,213 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_trans_f32.c -* -* Description: Floating-point matrix transpose. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -/** - * @defgroup MatrixTrans Matrix Transpose - * - * Tranposes a matrix. - * Transposing an M x N matrix flips it around the center diagonal and results in an N x M matrix. - * \image html MatrixTranspose.gif "Transpose of a 3 x 3 matrix" - */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixTrans - * @{ - */ - -/** - * @brief Floating-point matrix transpose. - * @param[in] *pSrc points to the input matrix - * @param[out] *pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - - -arm_status arm_mat_trans_f32( - const arm_matrix_instance_f32 * pSrc, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn = pSrc->pData; /* input data matrix pointer */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - float32_t *px; /* Temporary output data matrix pointer */ - uint16_t nRows = pSrc->numRows; /* number of rows */ - uint16_t nColumns = pSrc->numCols; /* number of columns */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - uint16_t blkCnt, i = 0u, row = nRows; /* loop counters */ - arm_status status; /* status of matrix transpose */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* Loop Unrolling */ - blkCnt = nColumns >> 2; - - /* The pointer px is set to starting address of the column being processed */ - px = pOut + i; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) /* column loop */ - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - blkCnt--; - } - - /* Perform matrix transpose for last 3 samples here. */ - blkCnt = nColumns % 0x4u; - - while(blkCnt > 0u) - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - uint16_t col, i = 0u, row = nRows; /* loop counters */ - arm_status status; /* status of matrix transpose */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* The pointer px is set to starting address of the column being processed */ - px = pOut + i; - - /* Initialize column loop counter */ - col = nColumns; - - while(col > 0u) - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - col--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - i++; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); /* row loop end */ - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixTrans group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_trans_f32.c +* +* Description: Floating-point matrix transpose. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +/** + * @defgroup MatrixTrans Matrix Transpose + * + * Tranposes a matrix. + * Transposing an M x N matrix flips it around the center diagonal and results in an N x M matrix. + * \image html MatrixTranspose.gif "Transpose of a 3 x 3 matrix" + */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixTrans + * @{ + */ + +/** + * @brief Floating-point matrix transpose. + * @param[in] *pSrc points to the input matrix + * @param[out] *pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + + +arm_status arm_mat_trans_f32( + const arm_matrix_instance_f32 * pSrc, + arm_matrix_instance_f32 * pDst) +{ + float32_t *pIn = pSrc->pData; /* input data matrix pointer */ + float32_t *pOut = pDst->pData; /* output data matrix pointer */ + float32_t *px; /* Temporary output data matrix pointer */ + uint16_t nRows = pSrc->numRows; /* number of rows */ + uint16_t nColumns = pSrc->numCols; /* number of columns */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + uint16_t blkCnt, i = 0u, row = nRows; /* loop counters */ + arm_status status; /* status of matrix transpose */ + + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Matrix transpose by exchanging the rows with columns */ + /* row loop */ + do + { + /* Loop Unrolling */ + blkCnt = nColumns >> 2; + + /* The pointer px is set to starting address of the column being processed */ + px = pOut + i; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) /* column loop */ + { + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Decrement the column loop counter */ + blkCnt--; + } + + /* Perform matrix transpose for last 3 samples here. */ + blkCnt = nColumns % 0x4u; + + while(blkCnt > 0u) + { + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Decrement the column loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + uint16_t col, i = 0u, row = nRows; /* loop counters */ + arm_status status; /* status of matrix transpose */ + + +#ifdef ARM_MATH_MATRIX_CHECK + + /* Check for matrix mismatch condition */ + if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Matrix transpose by exchanging the rows with columns */ + /* row loop */ + do + { + /* The pointer px is set to starting address of the column being processed */ + px = pOut + i; + + /* Initialize column loop counter */ + col = nColumns; + + while(col > 0u) + { + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Decrement the column loop counter */ + col--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + i++; + + /* Decrement the row loop counter */ + row--; + + } while(row > 0u); /* row loop end */ + + /* Set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixTrans group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q15.c index c2f0ec388..44cb0f351 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q15.c @@ -1,234 +1,234 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_trans_q15.c -* -* Description: Q15 matrix transpose. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixTrans - * @{ - */ - -/* - * @brief Q15 matrix transpose. - * @param[in] *pSrc points to the input matrix - * @param[out] *pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - -arm_status arm_mat_trans_q15( - const arm_matrix_instance_q15 * pSrc, - arm_matrix_instance_q15 * pDst) -{ - q15_t *pSrcA = pSrc->pData; /* input data matrix pointer */ - q15_t *pOut = pDst->pData; /* output data matrix pointer */ - uint16_t nRows = pSrc->numRows; /* number of nRows */ - uint16_t nColumns = pSrc->numCols; /* number of nColumns */ - uint16_t col, row = nRows, i = 0u; /* row and column loop counters */ - arm_status status; /* status of matrix transpose */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in; /* variable to hold temporary output */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* Apply loop unrolling and exchange the columns with row elements */ - col = nColumns >> 2u; - - /* The pointer pOut is set to starting address of the column being processed */ - pOut = pDst->pData + i; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(col > 0u) - { - /* Read two elements from the row */ - in = *__SIMD32(pSrcA)++; - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *pOut = (q15_t) in; - -#else - - *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer pOut to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Unpack and store the second element in the destination */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *pOut = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer pOut to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Read two elements from the row */ -#ifndef ARM_MATH_BIG_ENDIAN - - in = *__SIMD32(pSrcA)++; - -#else - - in = *__SIMD32(pSrcA)++; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *pOut = (q15_t) in; - -#else - - *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer pOut to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Unpack and store the second element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *pOut = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer pOut to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Decrement the column loop counter */ - col--; - } - - /* Perform matrix transpose for last 3 samples here. */ - col = nColumns % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* The pointer pOut is set to starting address of the column being processed */ - pOut = pDst->pData + i; - - /* Initialize column loop counter */ - col = nColumns; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(col > 0u) - { - /* Read and store the input element in the destination */ - *pOut = *pSrcA++; - - /* Update the pointer pOut to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Decrement the column loop counter */ - col--; - } - - i++; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixTrans group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_trans_q15.c +* +* Description: Q15 matrix transpose. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixTrans + * @{ + */ + +/* + * @brief Q15 matrix transpose. + * @param[in] *pSrc points to the input matrix + * @param[out] *pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + +arm_status arm_mat_trans_q15( + const arm_matrix_instance_q15 * pSrc, + arm_matrix_instance_q15 * pDst) +{ + q15_t *pSrcA = pSrc->pData; /* input data matrix pointer */ + q15_t *pOut = pDst->pData; /* output data matrix pointer */ + uint16_t nRows = pSrc->numRows; /* number of nRows */ + uint16_t nColumns = pSrc->numCols; /* number of nColumns */ + uint16_t col, row = nRows, i = 0u; /* row and column loop counters */ + arm_status status; /* status of matrix transpose */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t in; /* variable to hold temporary output */ + + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Matrix transpose by exchanging the rows with columns */ + /* row loop */ + do + { + /* Apply loop unrolling and exchange the columns with row elements */ + col = nColumns >> 2u; + + /* The pointer pOut is set to starting address of the column being processed */ + pOut = pDst->pData + i; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(col > 0u) + { + /* Read two elements from the row */ + in = *__SIMD32(pSrcA)++; + + /* Unpack and store one element in the destination */ +#ifndef ARM_MATH_BIG_ENDIAN + + *pOut = (q15_t) in; + +#else + + *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the pointer pOut to point to the next row of the transposed matrix */ + pOut += nRows; + + /* Unpack and store the second element in the destination */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#else + + *pOut = (q15_t) in; + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the pointer pOut to point to the next row of the transposed matrix */ + pOut += nRows; + + /* Read two elements from the row */ +#ifndef ARM_MATH_BIG_ENDIAN + + in = *__SIMD32(pSrcA)++; + +#else + + in = *__SIMD32(pSrcA)++; + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Unpack and store one element in the destination */ +#ifndef ARM_MATH_BIG_ENDIAN + + *pOut = (q15_t) in; + +#else + + *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the pointer pOut to point to the next row of the transposed matrix */ + pOut += nRows; + + /* Unpack and store the second element in the destination */ +#ifndef ARM_MATH_BIG_ENDIAN + + *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); + +#else + + *pOut = (q15_t) in; + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Update the pointer pOut to point to the next row of the transposed matrix */ + pOut += nRows; + + /* Decrement the column loop counter */ + col--; + } + + /* Perform matrix transpose for last 3 samples here. */ + col = nColumns % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + +#ifdef ARM_MATH_MATRIX_CHECK + + /* Check for matrix mismatch condition */ + if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Matrix transpose by exchanging the rows with columns */ + /* row loop */ + do + { + /* The pointer pOut is set to starting address of the column being processed */ + pOut = pDst->pData + i; + + /* Initialize column loop counter */ + col = nColumns; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(col > 0u) + { + /* Read and store the input element in the destination */ + *pOut = *pSrcA++; + + /* Update the pointer pOut to point to the next row of the transposed matrix */ + pOut += nRows; + + /* Decrement the column loop counter */ + col--; + } + + i++; + + /* Decrement the row loop counter */ + row--; + + } while(row > 0u); + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixTrans group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q31.c index f96f1b311..ef81039fb 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q31.c @@ -1,205 +1,205 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mat_trans_q31.c -* -* Description: Q31 matrix transpose. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixTrans - * @{ - */ - -/* - * @brief Q31 matrix transpose. - * @param[in] *pSrc points to the input matrix - * @param[out] *pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - -arm_status arm_mat_trans_q31( - const arm_matrix_instance_q31 * pSrc, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn = pSrc->pData; /* input data matrix pointer */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - q31_t *px; /* Temporary output data matrix pointer */ - uint16_t nRows = pSrc->numRows; /* number of nRows */ - uint16_t nColumns = pSrc->numCols; /* number of nColumns */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - uint16_t blkCnt, i = 0u, row = nRows; /* loop counters */ - arm_status status; /* status of matrix transpose */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* Apply loop unrolling and exchange the columns with row elements */ - blkCnt = nColumns >> 2u; - - /* The pointer px is set to starting address of the column being processed */ - px = pOut + i; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - blkCnt--; - } - - /* Perform matrix transpose for last 3 samples here. */ - blkCnt = nColumns % 0x4u; - - while(blkCnt > 0u) - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - uint16_t col, i = 0u, row = nRows; /* loop counters */ - arm_status status; /* status of matrix transpose */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* The pointer px is set to starting address of the column being processed */ - px = pOut + i; - - /* Initialize column loop counter */ - col = nColumns; - - while(col > 0u) - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - col--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - i++; - - /* Decrement the row loop counter */ - row--; - - } - while(row > 0u); /* row loop end */ - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixTrans group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mat_trans_q31.c +* +* Description: Q31 matrix transpose. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupMatrix + */ + +/** + * @addtogroup MatrixTrans + * @{ + */ + +/* + * @brief Q31 matrix transpose. + * @param[in] *pSrc points to the input matrix + * @param[out] *pDst points to the output matrix + * @return The function returns either ARM_MATH_SIZE_MISMATCH + * or ARM_MATH_SUCCESS based on the outcome of size checking. + */ + +arm_status arm_mat_trans_q31( + const arm_matrix_instance_q31 * pSrc, + arm_matrix_instance_q31 * pDst) +{ + q31_t *pIn = pSrc->pData; /* input data matrix pointer */ + q31_t *pOut = pDst->pData; /* output data matrix pointer */ + q31_t *px; /* Temporary output data matrix pointer */ + uint16_t nRows = pSrc->numRows; /* number of nRows */ + uint16_t nColumns = pSrc->numCols; /* number of nColumns */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + uint16_t blkCnt, i = 0u, row = nRows; /* loop counters */ + arm_status status; /* status of matrix transpose */ + + +#ifdef ARM_MATH_MATRIX_CHECK + + + /* Check for matrix mismatch condition */ + if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Matrix transpose by exchanging the rows with columns */ + /* row loop */ + do + { + /* Apply loop unrolling and exchange the columns with row elements */ + blkCnt = nColumns >> 2u; + + /* The pointer px is set to starting address of the column being processed */ + px = pOut + i; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Decrement the column loop counter */ + blkCnt--; + } + + /* Perform matrix transpose for last 3 samples here. */ + blkCnt = nColumns % 0x4u; + + while(blkCnt > 0u) + { + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Decrement the column loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + uint16_t col, i = 0u, row = nRows; /* loop counters */ + arm_status status; /* status of matrix transpose */ + + +#ifdef ARM_MATH_MATRIX_CHECK + + /* Check for matrix mismatch condition */ + if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) + { + /* Set status as ARM_MATH_SIZE_MISMATCH */ + status = ARM_MATH_SIZE_MISMATCH; + } + else +#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ + + { + /* Matrix transpose by exchanging the rows with columns */ + /* row loop */ + do + { + /* The pointer px is set to starting address of the column being processed */ + px = pOut + i; + + /* Initialize column loop counter */ + col = nColumns; + + while(col > 0u) + { + /* Read and store the input element in the destination */ + *px = *pIn++; + + /* Update the pointer px to point to the next row of the transposed matrix */ + px += nRows; + + /* Decrement the column loop counter */ + col--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + i++; + + /* Decrement the row loop counter */ + row--; + + } + while(row > 0u); /* row loop end */ + + /* set status as ARM_MATH_SUCCESS */ + status = ARM_MATH_SUCCESS; + } + + /* Return to application */ + return (status); +} + +/** + * @} end of MatrixTrans group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_f32.c index c63316f00..eb3fc24dd 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_f32.c @@ -1,127 +1,127 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_max_f32.c -* -* Description: Maximum value of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup Max Maximum - * - * Computes the maximum value of an array of data. - * The function returns both the maximum value and its position within the array. - * There are separate functions for floating-point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup Max - * @{ - */ - - -/** - * @brief Maximum value of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult maximum value returned here - * @param[out] *pIndex index of maximum value returned here - * @return none. - */ - -void arm_max_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult, - uint32_t * pIndex) -{ - float32_t maxVal, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop over blockSize number of values */ - blkCnt = (blockSize - 1u); - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - do - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal) - { - /* Update the maximum value and it's index */ - out = maxVal; - outIndex = blockSize - blkCnt; - } - /* Decrement the loop counter */ - blkCnt--; - - } while(blkCnt > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal) - { - /* Update the maximum value and it's index */ - out = maxVal; - outIndex = blockSize - blkCnt; - } - /* Decrement the loop counter */ - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - - /* Store the maximum value and it's index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Max group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_max_f32.c +* +* Description: Maximum value of a floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @defgroup Max Maximum + * + * Computes the maximum value of an array of data. + * The function returns both the maximum value and its position within the array. + * There are separate functions for floating-point, Q31, Q15, and Q7 data types. + */ + +/** + * @addtogroup Max + * @{ + */ + + +/** + * @brief Maximum value of a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult maximum value returned here + * @param[out] *pIndex index of maximum value returned here + * @return none. + */ + +void arm_max_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult, + uint32_t * pIndex) +{ + float32_t maxVal, out; /* Temporary variables to store the output value. */ + uint32_t blkCnt, outIndex; /* loop counter */ + + /* Initialise the index value to zero. */ + outIndex = 0u; + /* Load first input value that act as reference value for comparision */ + out = *pSrc++; + + /* Loop over blockSize number of values */ + blkCnt = (blockSize - 1u); + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + do + { + /* Initialize maxVal to the next consecutive values one by one */ + maxVal = *pSrc++; + + /* compare for the maximum value */ + if(out < maxVal) + { + /* Update the maximum value and it's index */ + out = maxVal; + outIndex = blockSize - blkCnt; + } + /* Decrement the loop counter */ + blkCnt--; + + } while(blkCnt > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + while(blkCnt > 0u) + { + /* Initialize maxVal to the next consecutive values one by one */ + maxVal = *pSrc++; + + /* compare for the maximum value */ + if(out < maxVal) + { + /* Update the maximum value and it's index */ + out = maxVal; + outIndex = blockSize - blkCnt; + } + /* Decrement the loop counter */ + blkCnt--; + + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + + /* Store the maximum value and it's index into destination pointers */ + *pResult = out; + *pIndex = outIndex; +} + +/** + * @} end of Max group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q15.c index 27c995bb2..371e5970a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q15.c @@ -1,119 +1,119 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_max_q15.c -* -* Description: Maximum value of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup Max - * @{ - */ - - -/** - * @brief Maximum value of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult maximum value returned here - * @param[out] *pIndex index of maximum value returned here - * @return none. - */ - -void arm_max_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult, - uint32_t * pIndex) -{ - q15_t maxVal, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop over blockSize number of values */ - blkCnt = (blockSize - 1u); - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - do - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal) - { - /* Update the maximum value and its index */ - out = maxVal; - outIndex = blockSize - blkCnt; - } - - blkCnt--; - - } while(blkCnt > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal) - { - /* Update the maximum value and its index */ - out = maxVal; - outIndex = blockSize - blkCnt; - } - /* Decrement the loop counter */ - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Store the maximum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Max group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_max_q15.c +* +* Description: Maximum value of a Q15 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup Max + * @{ + */ + + +/** + * @brief Maximum value of a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult maximum value returned here + * @param[out] *pIndex index of maximum value returned here + * @return none. + */ + +void arm_max_q15( + q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult, + uint32_t * pIndex) +{ + q15_t maxVal, out; /* Temporary variables to store the output value. */ + uint32_t blkCnt, outIndex; /* loop counter */ + + /* Initialise the index value to zero. */ + outIndex = 0u; + /* Load first input value that act as reference value for comparision */ + out = *pSrc++; + + /* Loop over blockSize number of values */ + blkCnt = (blockSize - 1u); + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + do + { + /* Initialize maxVal to the next consecutive values one by one */ + maxVal = *pSrc++; + + /* compare for the maximum value */ + if(out < maxVal) + { + /* Update the maximum value and its index */ + out = maxVal; + outIndex = blockSize - blkCnt; + } + + blkCnt--; + + } while(blkCnt > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + while(blkCnt > 0u) + { + /* Initialize maxVal to the next consecutive values one by one */ + maxVal = *pSrc++; + + /* compare for the maximum value */ + if(out < maxVal) + { + /* Update the maximum value and its index */ + out = maxVal; + outIndex = blockSize - blkCnt; + } + /* Decrement the loop counter */ + blkCnt--; + + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Store the maximum value and its index into destination pointers */ + *pResult = out; + *pIndex = outIndex; +} + +/** + * @} end of Max group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q31.c index f78c4a366..38451b0df 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q31.c @@ -1,121 +1,121 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_max_q31.c -* -* Description: Maximum value of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup Max - * @{ - */ - - -/** - * @brief Maximum value of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult maximum value returned here - * @param[out] *pIndex index of maximum value returned here - * @return none. - */ - -void arm_max_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult, - uint32_t * pIndex) -{ - q31_t maxVal, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop over blockSize number of values */ - blkCnt = (blockSize - 1u); - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - do - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal) - { - /* Update the maximum value and its index */ - out = maxVal; - outIndex = blockSize - blkCnt; - } - - /* Decrement the loop counter */ - blkCnt--; - - } while(blkCnt > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal = *pSrc++; - - /* Compare for the maximum value */ - if(out < maxVal) - { - /* Update the maximum value and its index */ - out = maxVal; - outIndex = blockSize - blkCnt; - } - - /* Decrement the loop counter */ - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Store the maximum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Max group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_max_q31.c +* +* Description: Maximum value of a Q31 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup Max + * @{ + */ + + +/** + * @brief Maximum value of a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult maximum value returned here + * @param[out] *pIndex index of maximum value returned here + * @return none. + */ + +void arm_max_q31( + q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult, + uint32_t * pIndex) +{ + q31_t maxVal, out; /* Temporary variables to store the output value. */ + uint32_t blkCnt, outIndex; /* loop counter */ + + /* Initialise the index value to zero. */ + outIndex = 0u; + /* Load first input value that act as reference value for comparision */ + out = *pSrc++; + + /* Loop over blockSize number of values */ + blkCnt = (blockSize - 1u); + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + do + { + /* Initialize maxVal to the next consecutive values one by one */ + maxVal = *pSrc++; + + /* compare for the maximum value */ + if(out < maxVal) + { + /* Update the maximum value and its index */ + out = maxVal; + outIndex = blockSize - blkCnt; + } + + /* Decrement the loop counter */ + blkCnt--; + + } while(blkCnt > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + while(blkCnt > 0u) + { + /* Initialize maxVal to the next consecutive values one by one */ + maxVal = *pSrc++; + + /* Compare for the maximum value */ + if(out < maxVal) + { + /* Update the maximum value and its index */ + out = maxVal; + outIndex = blockSize - blkCnt; + } + + /* Decrement the loop counter */ + blkCnt--; + + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Store the maximum value and its index into destination pointers */ + *pResult = out; + *pIndex = outIndex; +} + +/** + * @} end of Max group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q7.c index 86309e53d..ff9a7c071 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_max_q7.c @@ -1,206 +1,206 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_max_q7.c -* -* Description: Maximum value of a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup Max - * @{ - */ - - -/** - * @brief Maximum value of a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult maximum value returned here - * @param[out] *pIndex index of maximum value returned here - * @return none. - */ - -void arm_max_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * pResult, - uint32_t * pIndex) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t res, maxVal, x0, x1, maxVal2, maxVal1; /* Temporary variables to store the output value. */ - uint32_t blkCnt, index1, index2, index3, indx, indxMod; /* loop counter */ - - /* Initialise the index value to zero. */ - indx = 0u; - - /* Load first input value that act as reference value for comparision */ - res = *pSrc++; - - /* Loop unrolling */ - blkCnt = (blockSize - 1u) >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - indxMod = blockSize - (blkCnt * 4u); - - /* Load two input values for comparision */ - x0 = *pSrc++; - x1 = *pSrc++; - - if(x0 < x1) - { - /* Update the maximum value and its index */ - maxVal1 = x1; - index1 = indxMod + 1u; - } - else - { - /* Update the maximum value and its index */ - maxVal1 = x0; - index1 = indxMod; - } - - /* Load two input values for comparision */ - x0 = *pSrc++; - x1 = *pSrc++; - - if(x0 < x1) - { - /* Update the maximum value and its index */ - maxVal2 = x1; - index2 = indxMod + 3u; - } - else - { - /* Update the maximum value and its index */ - maxVal2 = x0; - index2 = indxMod + 2u; - } - - if(maxVal1 < maxVal2) - { - /* Update the maximum value and its index */ - maxVal = maxVal2; - index3 = index2; - } - else - { - /* Update the maximum value and its index */ - maxVal = maxVal1; - index3 = index1; - } - - if(res < maxVal) - { - /* Update the maximum value and its index */ - res = maxVal; - indx = index3; - } - - /* Decrement the loop counter */ - blkCnt--; - - } - - /* If the blockSize - 1 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (blockSize - 1u) % 0x04u; - - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal = *pSrc++; - - /* compare for the maximum value */ - if(res < maxVal) - { - /* Update the maximum value and its index */ - res = maxVal; - indx = blockSize - blkCnt; - } - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the maximum value and its index into destination pointers */ - *pResult = res; - *pIndex = indx; - -#else - - /* Run the below code for Cortex-M0 */ - - q7_t maxVal, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop over blockSize - 1 number of values */ - blkCnt = (blockSize - 1u); - - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal) - { - /* Update the maximum value and its index */ - out = maxVal; - outIndex = blockSize - blkCnt; - } - /* Decrement the loop counter */ - blkCnt--; - - } - - /* Store the maximum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Max group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_max_q7.c +* +* Description: Maximum value of a Q7 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup Max + * @{ + */ + + +/** + * @brief Maximum value of a Q7 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult maximum value returned here + * @param[out] *pIndex index of maximum value returned here + * @return none. + */ + +void arm_max_q7( + q7_t * pSrc, + uint32_t blockSize, + q7_t * pResult, + uint32_t * pIndex) +{ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q7_t res, maxVal, x0, x1, maxVal2, maxVal1; /* Temporary variables to store the output value. */ + uint32_t blkCnt, index1, index2, index3, indx, indxMod; /* loop counter */ + + /* Initialise the index value to zero. */ + indx = 0u; + + /* Load first input value that act as reference value for comparision */ + res = *pSrc++; + + /* Loop unrolling */ + blkCnt = (blockSize - 1u) >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + indxMod = blockSize - (blkCnt * 4u); + + /* Load two input values for comparision */ + x0 = *pSrc++; + x1 = *pSrc++; + + if(x0 < x1) + { + /* Update the maximum value and its index */ + maxVal1 = x1; + index1 = indxMod + 1u; + } + else + { + /* Update the maximum value and its index */ + maxVal1 = x0; + index1 = indxMod; + } + + /* Load two input values for comparision */ + x0 = *pSrc++; + x1 = *pSrc++; + + if(x0 < x1) + { + /* Update the maximum value and its index */ + maxVal2 = x1; + index2 = indxMod + 3u; + } + else + { + /* Update the maximum value and its index */ + maxVal2 = x0; + index2 = indxMod + 2u; + } + + if(maxVal1 < maxVal2) + { + /* Update the maximum value and its index */ + maxVal = maxVal2; + index3 = index2; + } + else + { + /* Update the maximum value and its index */ + maxVal = maxVal1; + index3 = index1; + } + + if(res < maxVal) + { + /* Update the maximum value and its index */ + res = maxVal; + indx = index3; + } + + /* Decrement the loop counter */ + blkCnt--; + + } + + /* If the blockSize - 1 is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = (blockSize - 1u) % 0x04u; + + while(blkCnt > 0u) + { + /* Initialize maxVal to the next consecutive values one by one */ + maxVal = *pSrc++; + + /* compare for the maximum value */ + if(res < maxVal) + { + /* Update the maximum value and its index */ + res = maxVal; + indx = blockSize - blkCnt; + } + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Store the maximum value and its index into destination pointers */ + *pResult = res; + *pIndex = indx; + +#else + + /* Run the below code for Cortex-M0 */ + + q7_t maxVal, out; /* Temporary variables to store the output value. */ + uint32_t blkCnt, outIndex; /* loop counter */ + + /* Initialise the index value to zero. */ + outIndex = 0u; + /* Load first input value that act as reference value for comparision */ + out = *pSrc++; + + /* Loop over blockSize - 1 number of values */ + blkCnt = (blockSize - 1u); + + while(blkCnt > 0u) + { + /* Initialize maxVal to the next consecutive values one by one */ + maxVal = *pSrc++; + + /* compare for the maximum value */ + if(out < maxVal) + { + /* Update the maximum value and its index */ + out = maxVal; + outIndex = blockSize - blkCnt; + } + /* Decrement the loop counter */ + blkCnt--; + + } + + /* Store the maximum value and its index into destination pointers */ + *pResult = out; + *pIndex = outIndex; + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of Max group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_f32.c index 0024b485d..fdda942af 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_f32.c @@ -1,122 +1,122 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mean_f32.c -* -* Description: Mean value of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup mean Mean - * - * Calculates the mean of the input vector. Mean is defined as the average of the elements in the vector. - * The underlying algorithm is used: - * - *
   
- * 	Result = (pSrc[0] + pSrc[1] + pSrc[2] + ... + pSrc[blockSize-1]) / blockSize;   
- * 
- * - * There are separate functions for floating-point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup mean - * @{ - */ - - -/** - * @brief Mean value of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult mean value returned here - * @return none. - */ - - -void arm_mean_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult) -{ - float32_t sum = 0.0f; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ - /* Store the result to the destination */ - *pResult = sum / (float32_t) blockSize; -} - -/** - * @} end of mean group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mean_f32.c +* +* Description: Mean value of a floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @defgroup mean Mean + * + * Calculates the mean of the input vector. Mean is defined as the average of the elements in the vector. + * The underlying algorithm is used: + * + *
   
+ * 	Result = (pSrc[0] + pSrc[1] + pSrc[2] + ... + pSrc[blockSize-1]) / blockSize;   
+ * 
+ * + * There are separate functions for floating-point, Q31, Q15, and Q7 data types. + */ + +/** + * @addtogroup mean + * @{ + */ + + +/** + * @brief Mean value of a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult mean value returned here + * @return none. + */ + + +void arm_mean_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult) +{ + float32_t sum = 0.0f; /* Temporary result storage */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ + /* Store the result to the destination */ + *pResult = sum / (float32_t) blockSize; +} + +/** + * @} end of mean group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q15.c index fc49d125e..2f31a4d5d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q15.c @@ -1,119 +1,119 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mean_q15.c -* -* Description: Mean value of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup mean - * @{ - */ - -/** - * @brief Mean value of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult mean value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 32-bit internal accumulator. - * The input is represented in 1.15 format and is accumulated in a 32-bit - * accumulator in 17.15 format. - * There is no risk of internal overflow with this approach, and the - * full precision of intermediate result is preserved. - * Finally, the accumulator is saturated and truncated to yield a result of 1.15 format. - * - */ - - -void arm_mean_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult) -{ - q31_t sum = 0; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ - /* Store the result to the destination */ - *pResult = (q15_t) (sum / blockSize); -} - -/** - * @} end of mean group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mean_q15.c +* +* Description: Mean value of a Q15 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup mean + * @{ + */ + +/** + * @brief Mean value of a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult mean value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 32-bit internal accumulator. + * The input is represented in 1.15 format and is accumulated in a 32-bit + * accumulator in 17.15 format. + * There is no risk of internal overflow with this approach, and the + * full precision of intermediate result is preserved. + * Finally, the accumulator is saturated and truncated to yield a result of 1.15 format. + * + */ + + +void arm_mean_q15( + q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult) +{ + q31_t sum = 0; /* Temporary result storage */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ + /* Store the result to the destination */ + *pResult = (q15_t) (sum / blockSize); +} + +/** + * @} end of mean group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q31.c index 5cc56bf5a..6692c7cfa 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q31.c @@ -1,119 +1,119 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mean_q31.c -* -* Description: Mean value of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup mean - * @{ - */ - -/** - * @brief Mean value of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult mean value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - *\par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.31 format and is accumulated in a 64-bit - * accumulator in 33.31 format. - * There is no risk of internal overflow with this approach, and the - * full precision of intermediate result is preserved. - * Finally, the accumulator is truncated to yield a result of 1.31 format. - * - */ - - -void arm_mean_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult) -{ - q63_t sum = 0; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ - /* Store the result to the destination */ - *pResult = (q31_t) (sum / (int32_t) blockSize); -} - -/** - * @} end of mean group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mean_q31.c +* +* Description: Mean value of a Q31 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup mean + * @{ + */ + +/** + * @brief Mean value of a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult mean value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + *\par + * The function is implemented using a 64-bit internal accumulator. + * The input is represented in 1.31 format and is accumulated in a 64-bit + * accumulator in 33.31 format. + * There is no risk of internal overflow with this approach, and the + * full precision of intermediate result is preserved. + * Finally, the accumulator is truncated to yield a result of 1.31 format. + * + */ + + +void arm_mean_q31( + q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult) +{ + q63_t sum = 0; /* Temporary result storage */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ + /* Store the result to the destination */ + *pResult = (q31_t) (sum / (int32_t) blockSize); +} + +/** + * @} end of mean group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q7.c index 33ce695f3..b61d1041a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_mean_q7.c @@ -1,119 +1,119 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_mean_q7.c -* -* Description: Mean value of a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup mean - * @{ - */ - -/** - * @brief Mean value of a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult mean value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 32-bit internal accumulator. - * The input is represented in 1.7 format and is accumulated in a 32-bit - * accumulator in 25.7 format. - * There is no risk of internal overflow with this approach, and the - * full precision of intermediate result is preserved. - * Finally, the accumulator is truncated to yield a result of 1.7 format. - * - */ - - -void arm_mean_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * pResult) -{ - q31_t sum = 0; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ - /* Store the result to the destination */ - *pResult = (q7_t) (sum / (int32_t) blockSize); -} - -/** - * @} end of mean group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_mean_q7.c +* +* Description: Mean value of a Q7 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup mean + * @{ + */ + +/** + * @brief Mean value of a Q7 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult mean value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 32-bit internal accumulator. + * The input is represented in 1.7 format and is accumulated in a 32-bit + * accumulator in 25.7 format. + * There is no risk of internal overflow with this approach, and the + * full precision of intermediate result is preserved. + * Finally, the accumulator is truncated to yield a result of 1.7 format. + * + */ + + +void arm_mean_q7( + q7_t * pSrc, + uint32_t blockSize, + q7_t * pResult) +{ + q31_t sum = 0; /* Temporary result storage */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ + /* Store the result to the destination */ + *pResult = (q7_t) (sum / (int32_t) blockSize); +} + +/** + * @} end of mean group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_f32.c index 4319a46cb..b6846bc1a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_f32.c @@ -1,133 +1,133 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_min_f32.c -* -* Description: Minimum value of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup Min Minimum - * - * Computes the minimum value of an array of data. - * The function returns both the minimum value and its position within the array. - * There are separate functions for floating-point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup Min - * @{ - */ - - -/** - * @brief Minimum value of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult minimum value returned here - * @param[out] *pIndex index of minimum value returned here - * @return none. - * - */ - -void arm_min_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult, - uint32_t * pIndex) -{ - float32_t minVal, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - - /* Loop over blockSize number of values */ - blkCnt = (blockSize - 1u); - - do - { - /* Initialize minVal to the next consecutive values one by one */ - minVal = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal) - { - /* Update the minimum value and it's index */ - out = minVal; - outIndex = blockSize - blkCnt; - } - - blkCnt--; - - } while(blkCnt > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize - 1 number of values */ - blkCnt = (blockSize - 1u); - - while(blkCnt > 0u) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal) - { - /* Update the minimum value and it's index */ - out = minVal; - outIndex = blockSize - blkCnt; - } - /* Decrement the loop counter */ - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - - /* Store the minimum value and it's index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Min group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_min_f32.c +* +* Description: Minimum value of a floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @defgroup Min Minimum + * + * Computes the minimum value of an array of data. + * The function returns both the minimum value and its position within the array. + * There are separate functions for floating-point, Q31, Q15, and Q7 data types. + */ + +/** + * @addtogroup Min + * @{ + */ + + +/** + * @brief Minimum value of a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult minimum value returned here + * @param[out] *pIndex index of minimum value returned here + * @return none. + * + */ + +void arm_min_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult, + uint32_t * pIndex) +{ + float32_t minVal, out; /* Temporary variables to store the output value. */ + uint32_t blkCnt, outIndex; /* loop counter */ + + /* Initialise the index value to zero. */ + outIndex = 0u; + /* Load first input value that act as reference value for comparision */ + out = *pSrc++; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + + /* Loop over blockSize number of values */ + blkCnt = (blockSize - 1u); + + do + { + /* Initialize minVal to the next consecutive values one by one */ + minVal = *pSrc++; + + /* compare for the minimum value */ + if(out > minVal) + { + /* Update the minimum value and it's index */ + out = minVal; + outIndex = blockSize - blkCnt; + } + + blkCnt--; + + } while(blkCnt > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize - 1 number of values */ + blkCnt = (blockSize - 1u); + + while(blkCnt > 0u) + { + /* Initialize minVal to the next consecutive values one by one */ + minVal = *pSrc++; + + /* compare for the minimum value */ + if(out > minVal) + { + /* Update the minimum value and it's index */ + out = minVal; + outIndex = blockSize - blkCnt; + } + /* Decrement the loop counter */ + blkCnt--; + + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + + /* Store the minimum value and it's index into destination pointers */ + *pResult = out; + *pIndex = outIndex; +} + +/** + * @} end of Min group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q15.c index 8763c4102..788c8f13d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q15.c @@ -1,127 +1,127 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_min_q15.c -* -* Description: Minimum value of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - - -/** - * @addtogroup Min - * @{ - */ - - -/** - * @brief Minimum value of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult minimum value returned here - * @param[out] *pIndex index of minimum value returned here - * @return none. - * - */ - -void arm_min_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult, - uint32_t * pIndex) -{ - q15_t minVal, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - - /* Loop over blockSize number of values */ - blkCnt = (blockSize - 1u); - - do - { - /* Initialize minVal to the next consecutive values one by one */ - minVal = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal) - { - /* Update the minimum value and its index */ - out = minVal; - outIndex = blockSize - blkCnt; - } - - blkCnt--; - - } while(blkCnt > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize - 1 number of values */ - blkCnt = (blockSize - 1u); - - while(blkCnt > 0u) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal) - { - /* Update the minimum value and its index */ - out = minVal; - outIndex = blockSize - blkCnt; - } - - /* Decrement the loop counter */ - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - - /* Store the minimum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Min group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_min_q15.c +* +* Description: Minimum value of a Q15 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + + +/** + * @addtogroup Min + * @{ + */ + + +/** + * @brief Minimum value of a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult minimum value returned here + * @param[out] *pIndex index of minimum value returned here + * @return none. + * + */ + +void arm_min_q15( + q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult, + uint32_t * pIndex) +{ + q15_t minVal, out; /* Temporary variables to store the output value. */ + uint32_t blkCnt, outIndex; /* loop counter */ + + /* Initialise the index value to zero. */ + outIndex = 0u; + /* Load first input value that act as reference value for comparision */ + out = *pSrc++; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + + /* Loop over blockSize number of values */ + blkCnt = (blockSize - 1u); + + do + { + /* Initialize minVal to the next consecutive values one by one */ + minVal = *pSrc++; + + /* compare for the minimum value */ + if(out > minVal) + { + /* Update the minimum value and its index */ + out = minVal; + outIndex = blockSize - blkCnt; + } + + blkCnt--; + + } while(blkCnt > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize - 1 number of values */ + blkCnt = (blockSize - 1u); + + while(blkCnt > 0u) + { + /* Initialize minVal to the next consecutive values one by one */ + minVal = *pSrc++; + + /* compare for the minimum value */ + if(out > minVal) + { + /* Update the minimum value and its index */ + out = minVal; + outIndex = blockSize - blkCnt; + } + + /* Decrement the loop counter */ + blkCnt--; + + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + + /* Store the minimum value and its index into destination pointers */ + *pResult = out; + *pIndex = outIndex; +} + +/** + * @} end of Min group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q31.c index 6c7f94786..5d285d00b 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q31.c @@ -1,125 +1,125 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_min_q31.c -* -* Description: Minimum value of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - - -/** - * @addtogroup Min - * @{ - */ - - -/** - * @brief Minimum value of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult minimum value returned here - * @param[out] *pIndex index of minimum value returned here - * @return none. - * - */ - -void arm_min_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult, - uint32_t * pIndex) -{ - q31_t minVal, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop over blockSize number of values */ - blkCnt = (blockSize - 1u); - - do - { - /* Initialize minVal to the next consecutive values one by one */ - minVal = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal) - { - /* Update the minimum value and its index */ - out = minVal; - outIndex = blockSize - blkCnt; - } - - blkCnt--; - - } while(blkCnt > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize -1 number of values */ - blkCnt = (blockSize - 1u); - - while(blkCnt > 0u) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal) - { - /* Update the minimum value and its index */ - out = minVal; - outIndex = blockSize - blkCnt; - } - - /* Decrement the loop counter */ - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Store the minimum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Min group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_min_q31.c +* +* Description: Minimum value of a Q31 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + + +/** + * @addtogroup Min + * @{ + */ + + +/** + * @brief Minimum value of a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult minimum value returned here + * @param[out] *pIndex index of minimum value returned here + * @return none. + * + */ + +void arm_min_q31( + q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult, + uint32_t * pIndex) +{ + q31_t minVal, out; /* Temporary variables to store the output value. */ + uint32_t blkCnt, outIndex; /* loop counter */ + + /* Initialise the index value to zero. */ + outIndex = 0u; + /* Load first input value that act as reference value for comparision */ + out = *pSrc++; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Loop over blockSize number of values */ + blkCnt = (blockSize - 1u); + + do + { + /* Initialize minVal to the next consecutive values one by one */ + minVal = *pSrc++; + + /* compare for the minimum value */ + if(out > minVal) + { + /* Update the minimum value and its index */ + out = minVal; + outIndex = blockSize - blkCnt; + } + + blkCnt--; + + } while(blkCnt > 0u); + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize -1 number of values */ + blkCnt = (blockSize - 1u); + + while(blkCnt > 0u) + { + /* Initialize minVal to the next consecutive values one by one */ + minVal = *pSrc++; + + /* compare for the minimum value */ + if(out > minVal) + { + /* Update the minimum value and its index */ + out = minVal; + outIndex = blockSize - blkCnt; + } + + /* Decrement the loop counter */ + blkCnt--; + + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Store the minimum value and its index into destination pointers */ + *pResult = out; + *pIndex = outIndex; +} + +/** + * @} end of Min group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q7.c index 5f8250c22..da6dc7571 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_min_q7.c @@ -1,204 +1,204 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_min_q7.c -* -* Description: Minimum value of a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup Min - * @{ - */ - - -/** - * @brief Minimum value of a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult minimum value returned here - * @param[out] *pIndex index of minimum value returned here - * @return none. - * - */ - -void arm_min_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * pResult, - uint32_t * pIndex) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t minVal, minVal1, minVal2, res, x0, x1; /* Temporary variables to store the output value. */ - uint32_t blkCnt, indx, index1, index2, index3, indxMod; /* loop counter */ - - /* Initialise the index value to zero. */ - indx = 0u; - - /* Load first input value that act as reference value for comparision */ - res = *pSrc++; - - /* Loop over blockSize number of values */ - blkCnt = (blockSize - 1u) >> 2u; - - while(blkCnt > 0u) - { - indxMod = blockSize - (blkCnt * 4u); - - /* Load two input values for comparision */ - x0 = *pSrc++; - x1 = *pSrc++; - - if(x0 > x1) - { - /* Update the minimum value and its index */ - minVal1 = x1; - index1 = indxMod + 1u; - } - else - { - /* Update the minimum value and its index */ - minVal1 = x0; - index1 = indxMod; - } - - /* Load two input values for comparision */ - x0 = *pSrc++; - x1 = *pSrc++; - - if(x0 > x1) - { - /* Update the minimum value and its index */ - minVal2 = x1; - index2 = indxMod + 3u; - } - else - { - /* Update the minimum value and its index */ - minVal2 = x0; - index2 = indxMod + 2u; - } - - if(minVal1 > minVal2) - { - /* Update the minimum value and its index */ - minVal = minVal2; - index3 = index2; - } - else - { - /* Update the minimum value and its index */ - minVal = minVal1; - index3 = index1; - } - - if(res > minVal) - { - /* Update the minimum value and its index */ - res = minVal; - indx = index3; - } - - /* Decrement the loop counter */ - blkCnt--; - - } - - blkCnt = (blockSize - 1u) % 0x04u; - - while(blkCnt > 0u) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal = *pSrc++; - - /* compare for the minimum value */ - if(res > minVal) - { - /* Update the minimum value and its index */ - res = minVal; - indx = blockSize - blkCnt; - } - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the minimum value and its index into destination pointers */ - *pResult = res; - *pIndex = indx; - -#else - - /* Run the below code for Cortex-M0 */ - - q7_t minVal, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop over blockSize - 1 number of values */ - blkCnt = (blockSize - 1u); - - while(blkCnt > 0u) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal) - { - /* Update the minimum value and its index */ - out = minVal; - outIndex = blockSize - blkCnt; - } - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the minimum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Min group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_min_q7.c +* +* Description: Minimum value of a Q7 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup Min + * @{ + */ + + +/** + * @brief Minimum value of a Q7 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult minimum value returned here + * @param[out] *pIndex index of minimum value returned here + * @return none. + * + */ + +void arm_min_q7( + q7_t * pSrc, + uint32_t blockSize, + q7_t * pResult, + uint32_t * pIndex) +{ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q7_t minVal, minVal1, minVal2, res, x0, x1; /* Temporary variables to store the output value. */ + uint32_t blkCnt, indx, index1, index2, index3, indxMod; /* loop counter */ + + /* Initialise the index value to zero. */ + indx = 0u; + + /* Load first input value that act as reference value for comparision */ + res = *pSrc++; + + /* Loop over blockSize number of values */ + blkCnt = (blockSize - 1u) >> 2u; + + while(blkCnt > 0u) + { + indxMod = blockSize - (blkCnt * 4u); + + /* Load two input values for comparision */ + x0 = *pSrc++; + x1 = *pSrc++; + + if(x0 > x1) + { + /* Update the minimum value and its index */ + minVal1 = x1; + index1 = indxMod + 1u; + } + else + { + /* Update the minimum value and its index */ + minVal1 = x0; + index1 = indxMod; + } + + /* Load two input values for comparision */ + x0 = *pSrc++; + x1 = *pSrc++; + + if(x0 > x1) + { + /* Update the minimum value and its index */ + minVal2 = x1; + index2 = indxMod + 3u; + } + else + { + /* Update the minimum value and its index */ + minVal2 = x0; + index2 = indxMod + 2u; + } + + if(minVal1 > minVal2) + { + /* Update the minimum value and its index */ + minVal = minVal2; + index3 = index2; + } + else + { + /* Update the minimum value and its index */ + minVal = minVal1; + index3 = index1; + } + + if(res > minVal) + { + /* Update the minimum value and its index */ + res = minVal; + indx = index3; + } + + /* Decrement the loop counter */ + blkCnt--; + + } + + blkCnt = (blockSize - 1u) % 0x04u; + + while(blkCnt > 0u) + { + /* Initialize minVal to the next consecutive values one by one */ + minVal = *pSrc++; + + /* compare for the minimum value */ + if(res > minVal) + { + /* Update the minimum value and its index */ + res = minVal; + indx = blockSize - blkCnt; + } + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Store the minimum value and its index into destination pointers */ + *pResult = res; + *pIndex = indx; + +#else + + /* Run the below code for Cortex-M0 */ + + q7_t minVal, out; /* Temporary variables to store the output value. */ + uint32_t blkCnt, outIndex; /* loop counter */ + + /* Initialise the index value to zero. */ + outIndex = 0u; + + /* Load first input value that act as reference value for comparision */ + out = *pSrc++; + + /* Loop over blockSize - 1 number of values */ + blkCnt = (blockSize - 1u); + + while(blkCnt > 0u) + { + /* Initialize minVal to the next consecutive values one by one */ + minVal = *pSrc++; + + /* compare for the minimum value */ + if(out > minVal) + { + /* Update the minimum value and its index */ + out = minVal; + outIndex = blockSize - blkCnt; + } + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Store the minimum value and its index into destination pointers */ + *pResult = out; + *pIndex = outIndex; + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of Min group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_f32.c index 8139afd0e..70a188bce 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_f32.c @@ -1,135 +1,135 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_power_f32.c -* -* Description: Sum of the squares of the elements of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup power Power - * - * Calculates the sum of the squares of the elements in the input vector. - * The underlying algorithm is used: - * - *
   
- * 	Result = pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + pSrc[2] * pSrc[2] + ... + pSrc[blockSize-1] * pSrc[blockSize-1];   
- * 
- * - * There are separate functions for floating point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup power - * @{ - */ - - -/** - * @brief Sum of the squares of the elements of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult sum of the squares value returned here - * @return none. - * - */ - - -void arm_power_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult) -{ - float32_t sum = 0.0f; /* accumulator */ - float32_t in; /* Temporary variable to store input value */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* compute power and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the result to the destination */ - *pResult = sum; -} - -/** - * @} end of power group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_power_f32.c +* +* Description: Sum of the squares of the elements of a floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @defgroup power Power + * + * Calculates the sum of the squares of the elements in the input vector. + * The underlying algorithm is used: + * + *
   
+ * 	Result = pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + pSrc[2] * pSrc[2] + ... + pSrc[blockSize-1] * pSrc[blockSize-1];   
+ * 
+ * + * There are separate functions for floating point, Q31, Q15, and Q7 data types. + */ + +/** + * @addtogroup power + * @{ + */ + + +/** + * @brief Sum of the squares of the elements of a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult sum of the squares value returned here + * @return none. + * + */ + + +void arm_power_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult) +{ + float32_t sum = 0.0f; /* accumulator */ + float32_t in; /* Temporary variable to store input value */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute Power and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* compute power and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += in * in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Store the result to the destination */ + *pResult = sum; +} + +/** + * @} end of power group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q15.c index 45d1c43cc..3b5b8482e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q15.c @@ -1,141 +1,141 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_power_q15.c -* -* Description: Sum of the squares of the elements of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup power - * @{ - */ - -/** - * @brief Sum of the squares of the elements of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult sum of the squares value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.15 format. - * Intermediate multiplication yields a 2.30 format, and this - * result is added without saturation to a 64-bit accumulator in 34.30 format. - * With 33 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the return result is in 34.30 format. - * - */ - -void arm_power_q15( - q15_t * pSrc, - uint32_t blockSize, - q63_t * pResult) -{ - q63_t sum = 0; /* Temporary result storage */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in32; /* Temporary variable to store input value */ - q15_t in16; /* Temporary variable to store input value */ - uint32_t blkCnt; /* loop counter */ - - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in32 = *__SIMD32(pSrc)++; - sum = __SMLALD(in32, in32, sum); - in32 = *__SIMD32(pSrc)++; - sum = __SMLALD(in32, in32, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in16 = *pSrc++; - sum = __SMLALD(in16, in16, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t in; /* Temporary variable to store input value */ - uint32_t blkCnt; /* loop counter */ - - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += ((q31_t) in * in); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Store the results in 34.30 format */ - *pResult = sum; -} - -/** - * @} end of power group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_power_q15.c +* +* Description: Sum of the squares of the elements of a Q15 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup power + * @{ + */ + +/** + * @brief Sum of the squares of the elements of a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult sum of the squares value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 64-bit internal accumulator. + * The input is represented in 1.15 format. + * Intermediate multiplication yields a 2.30 format, and this + * result is added without saturation to a 64-bit accumulator in 34.30 format. + * With 33 guard bits in the accumulator, there is no risk of overflow, and the + * full precision of the intermediate multiplication is preserved. + * Finally, the return result is in 34.30 format. + * + */ + +void arm_power_q15( + q15_t * pSrc, + uint32_t blockSize, + q63_t * pResult) +{ + q63_t sum = 0; /* Temporary result storage */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t in32; /* Temporary variable to store input value */ + q15_t in16; /* Temporary variable to store input value */ + uint32_t blkCnt; /* loop counter */ + + + /* loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute Power and then store the result in a temporary variable, sum. */ + in32 = *__SIMD32(pSrc)++; + sum = __SMLALD(in32, in32, sum); + in32 = *__SIMD32(pSrc)++; + sum = __SMLALD(in32, in32, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute Power and then store the result in a temporary variable, sum. */ + in16 = *pSrc++; + sum = __SMLALD(in16, in16, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q15_t in; /* Temporary variable to store input value */ + uint32_t blkCnt; /* loop counter */ + + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute Power and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += ((q31_t) in * in); + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Store the results in 34.30 format */ + *pResult = sum; +} + +/** + * @} end of power group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q31.c index b47195577..c25621ee1 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q31.c @@ -1,132 +1,132 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_power_q31.c -* -* Description: Sum of the squares of the elements of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup power - * @{ - */ - -/** - * @brief Sum of the squares of the elements of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult sum of the squares value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.31 format. - * Intermediate multiplication yields a 2.62 format, and this - * result is truncated to 2.48 format by discarding the lower 14 bits. - * The 2.48 result is then added without saturation to a 64-bit accumulator in 16.48 format. - * With 15 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the return result is in 16.48 format. - * - */ - -void arm_power_q31( - q31_t * pSrc, - uint32_t blockSize, - q63_t * pResult) -{ - q63_t sum = 0; /* Temporary result storage */ - q31_t in; - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power then shift intermediate results by 14 bits to maintain 16.48 format and then store the result in a temporary variable sum, providing 15 guard bits. */ - in = *pSrc++; - sum += ((q63_t) in * in) >> 14u; - - in = *pSrc++; - sum += ((q63_t) in * in) >> 14u; - - in = *pSrc++; - sum += ((q63_t) in * in) >> 14u; - - in = *pSrc++; - sum += ((q63_t) in * in) >> 14u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += ((q63_t) in * in) >> 14u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the results in 16.48 format */ - *pResult = sum; -} - -/** - * @} end of power group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_power_q31.c +* +* Description: Sum of the squares of the elements of a Q31 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup power + * @{ + */ + +/** + * @brief Sum of the squares of the elements of a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult sum of the squares value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 64-bit internal accumulator. + * The input is represented in 1.31 format. + * Intermediate multiplication yields a 2.62 format, and this + * result is truncated to 2.48 format by discarding the lower 14 bits. + * The 2.48 result is then added without saturation to a 64-bit accumulator in 16.48 format. + * With 15 guard bits in the accumulator, there is no risk of overflow, and the + * full precision of the intermediate multiplication is preserved. + * Finally, the return result is in 16.48 format. + * + */ + +void arm_power_q31( + q31_t * pSrc, + uint32_t blockSize, + q63_t * pResult) +{ + q63_t sum = 0; /* Temporary result storage */ + q31_t in; + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute Power then shift intermediate results by 14 bits to maintain 16.48 format and then store the result in a temporary variable sum, providing 15 guard bits. */ + in = *pSrc++; + sum += ((q63_t) in * in) >> 14u; + + in = *pSrc++; + sum += ((q63_t) in * in) >> 14u; + + in = *pSrc++; + sum += ((q63_t) in * in) >> 14u; + + in = *pSrc++; + sum += ((q63_t) in * in) >> 14u; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute Power and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += ((q63_t) in * in) >> 14u; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Store the results in 16.48 format */ + *pResult = sum; +} + +/** + * @} end of power group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q7.c index 52159be2f..457950e2b 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_power_q7.c @@ -1,137 +1,137 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_power_q7.c -* -* Description: Sum of the squares of the elements of a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup power - * @{ - */ - -/** - * @brief Sum of the squares of the elements of a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult sum of the squares value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 32-bit internal accumulator. - * The input is represented in 1.7 format. - * Intermediate multiplication yields a 2.14 format, and this - * result is added without saturation to an accumulator in 18.14 format. - * With 17 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the return result is in 18.14 format. - * - */ - -void arm_power_q7( - q7_t * pSrc, - uint32_t blockSize, - q31_t * pResult) -{ - q31_t sum = 0; /* Temporary result storage */ - q7_t in; /* Temporary variable to store input */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t input1; /* Temporary variable to store packed input */ - q15_t in1, in2; /* Temporary variables to store input */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Reading two inputs of pSrc vector and packing */ - in1 = (q15_t) * pSrc++; - in2 = (q15_t) * pSrc++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - sum = __SMLAD(input1, input1, sum); - - /* Reading two inputs of pSrc vector and packing */ - in1 = (q15_t) * pSrc++; - in2 = (q15_t) * pSrc++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - sum = __SMLAD(input1, input1, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += ((q15_t) in * in); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the result in 18.14 format */ - *pResult = sum; -} - -/** - * @} end of power group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_power_q7.c +* +* Description: Sum of the squares of the elements of a Q7 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup power + * @{ + */ + +/** + * @brief Sum of the squares of the elements of a Q7 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult sum of the squares value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 32-bit internal accumulator. + * The input is represented in 1.7 format. + * Intermediate multiplication yields a 2.14 format, and this + * result is added without saturation to an accumulator in 18.14 format. + * With 17 guard bits in the accumulator, there is no risk of overflow, and the + * full precision of the intermediate multiplication is preserved. + * Finally, the return result is in 18.14 format. + * + */ + +void arm_power_q7( + q7_t * pSrc, + uint32_t blockSize, + q31_t * pResult) +{ + q31_t sum = 0; /* Temporary result storage */ + q7_t in; /* Temporary variable to store input */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t input1; /* Temporary variable to store packed input */ + q15_t in1, in2; /* Temporary variables to store input */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* Reading two inputs of pSrc vector and packing */ + in1 = (q15_t) * pSrc++; + in2 = (q15_t) * pSrc++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute Power and then store the result in a temporary variable, sum. */ + sum = __SMLAD(input1, input1, sum); + + /* Reading two inputs of pSrc vector and packing */ + in1 = (q15_t) * pSrc++; + in2 = (q15_t) * pSrc++; + input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); + + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute Power and then store the result in a temporary variable, sum. */ + sum = __SMLAD(input1, input1, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute Power and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += ((q15_t) in * in); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Store the result in 18.14 format */ + *pResult = sum; +} + +/** + * @} end of power group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_f32.c index 4293a5280..de3ea396c 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_f32.c @@ -1,130 +1,130 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_rms_f32.c -* -* Description: Root mean square value of an array of F32 type -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup RMS Root mean square (RMS) - * - * - * Calculates the Root Mean Sqaure of the elements in the input vector. - * The underlying algorithm is used: - * - *
   
- * 	Result = sqrt(((pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + ... + pSrc[blockSize-1] * pSrc[blockSize-1]) / blockSize));   
- * 
- * - * There are separate functions for floating point, Q31, and Q15 data types. - */ - -/** - * @addtogroup RMS - * @{ - */ - - -/** - * @brief Root Mean Square of the elements of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult rms value returned here - * @return none. - * - */ - -void arm_rms_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult) -{ - float32_t sum = 0.0f; /* Accumulator */ - float32_t in; /* Tempoprary variable to store input value */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute sum of the squares and then store the result in a temporary variable, sum */ - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Rms and store the result in the destination */ - arm_sqrt_f32(sum / (float32_t) blockSize, pResult); -} - -/** - * @} end of RMS group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_rms_f32.c +* +* Description: Root mean square value of an array of F32 type +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @defgroup RMS Root mean square (RMS) + * + * + * Calculates the Root Mean Sqaure of the elements in the input vector. + * The underlying algorithm is used: + * + *
   
+ * 	Result = sqrt(((pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + ... + pSrc[blockSize-1] * pSrc[blockSize-1]) / blockSize));   
+ * 
+ * + * There are separate functions for floating point, Q31, and Q15 data types. + */ + +/** + * @addtogroup RMS + * @{ + */ + + +/** + * @brief Root Mean Square of the elements of a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult rms value returned here + * @return none. + * + */ + +void arm_rms_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult) +{ + float32_t sum = 0.0f; /* Accumulator */ + float32_t in; /* Tempoprary variable to store input value */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute sum of the squares and then store the result in a temporary variable, sum */ + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute sum of the squares and then store the results in a temporary variable, sum */ + in = *pSrc++; + sum += in * in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute Rms and store the result in the destination */ + arm_sqrt_f32(sum / (float32_t) blockSize, pResult); +} + +/** + * @} end of RMS group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_q15.c index d5548cc7f..e57485fc0 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_q15.c @@ -1,150 +1,150 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_rms_q15.c -* -* Description: Root Mean Square of the elements of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @addtogroup RMS - * @{ - */ - -/** - * @brief Root Mean Square of the elements of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult rms value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.15 format. - * Intermediate multiplication yields a 2.30 format, and this - * result is added without saturation to a 64-bit accumulator in 34.30 format. - * With 33 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the 34.30 result is truncated to 34.15 format by discarding the lower - * 15 bits, and then saturated to yield a result in 1.15 format. - * - */ - -void arm_rms_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult) -{ - q63_t sum = 0; /* accumulator */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in; /* temporary variable to store the input value */ - q15_t in1; /* temporary variable to store the input value */ - uint32_t blkCnt; /* loop counter */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in = *__SIMD32(pSrc)++; - sum = __SMLALD(in, in, sum); - in = *__SIMD32(pSrc)++; - sum = __SMLALD(in, in, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in1 = *pSrc++; - sum = __SMLALD(in1, in1, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Truncating and saturating the accumulator to 1.15 format */ - sum = __SSAT((q31_t) (sum >> 15), 16); - - in1 = (q15_t) (sum / blockSize); - - /* Store the result in the destination */ - arm_sqrt_q15(in1, pResult); - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t in; /* temporary variable to store the input value */ - uint32_t blkCnt; /* loop counter */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in = *pSrc++; - sum += ((q31_t) in * in); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Truncating and saturating the accumulator to 1.15 format */ - sum = __SSAT((q31_t) (sum >> 15), 16); - - in = (q15_t) (sum / blockSize); - - /* Store the result in the destination */ - arm_sqrt_q15(in, pResult); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of RMS group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_rms_q15.c +* +* Description: Root Mean Square of the elements of a Q15 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @addtogroup RMS + * @{ + */ + +/** + * @brief Root Mean Square of the elements of a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult rms value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 64-bit internal accumulator. + * The input is represented in 1.15 format. + * Intermediate multiplication yields a 2.30 format, and this + * result is added without saturation to a 64-bit accumulator in 34.30 format. + * With 33 guard bits in the accumulator, there is no risk of overflow, and the + * full precision of the intermediate multiplication is preserved. + * Finally, the 34.30 result is truncated to 34.15 format by discarding the lower + * 15 bits, and then saturated to yield a result in 1.15 format. + * + */ + +void arm_rms_q15( + q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult) +{ + q63_t sum = 0; /* accumulator */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t in; /* temporary variable to store the input value */ + q15_t in1; /* temporary variable to store the input value */ + uint32_t blkCnt; /* loop counter */ + + /* loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute sum of the squares and then store the results in a temporary variable, sum */ + in = *__SIMD32(pSrc)++; + sum = __SMLALD(in, in, sum); + in = *__SIMD32(pSrc)++; + sum = __SMLALD(in, in, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute sum of the squares and then store the results in a temporary variable, sum */ + in1 = *pSrc++; + sum = __SMLALD(in1, in1, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Truncating and saturating the accumulator to 1.15 format */ + sum = __SSAT((q31_t) (sum >> 15), 16); + + in1 = (q15_t) (sum / blockSize); + + /* Store the result in the destination */ + arm_sqrt_q15(in1, pResult); + +#else + + /* Run the below code for Cortex-M0 */ + + q15_t in; /* temporary variable to store the input value */ + uint32_t blkCnt; /* loop counter */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute sum of the squares and then store the results in a temporary variable, sum */ + in = *pSrc++; + sum += ((q31_t) in * in); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Truncating and saturating the accumulator to 1.15 format */ + sum = __SSAT((q31_t) (sum >> 15), 16); + + in = (q15_t) (sum / blockSize); + + /* Store the result in the destination */ + arm_sqrt_q15(in, pResult); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of RMS group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_q31.c index 5d5805316..a2533b129 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_rms_q31.c @@ -1,143 +1,143 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_rms_q31.c -* -* Description: Root Mean Square of the elements of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @addtogroup RMS - * @{ - */ - - -/** - * @brief Root Mean Square of the elements of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult rms value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - *\par - * The function is implemented using an internal 64-bit accumulator. - * The input is represented in 1.31 format, and intermediate multiplication - * yields a 2.62 format. - * The accumulator maintains full precision of the intermediate multiplication results, - * but provides only a single guard bit. - * There is no saturation on intermediate additions. - * If the accumulator overflows, it wraps around and distorts the result. - * In order to avoid overflows completely, the input signal must be scaled down by - * log2(blockSize) bits, as a total of blockSize additions are performed internally. - * Finally, the 2.62 accumulator is right shifted by 31 bits to yield a 1.31 format value. - * - */ - -void arm_rms_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult) -{ - q63_t sum = 0; /* accumulator */ - q31_t in; /* Temporary variable to store the input */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t *pIn1 = pSrc; /* SrcA pointer */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute sum of the squares and then store the result in a temporary variable, sum */ - in = *pIn1++; - sum += (q63_t) in *in; - in = *pIn1++; - sum += (q63_t) in *in; - in = *pIn1++; - sum += (q63_t) in *in; - in = *pIn1++; - sum += (q63_t) in *in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in = *pIn1++; - sum += (q63_t) in *in; - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in = *pSrc++; - sum += (q63_t) in *in; - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Convert data in 2.62 to 1.31 by 31 right shifts */ - sum = sum >> 31; - - /* Compute Rms and store the result in the destination vector */ - arm_sqrt_q31((q31_t) (sum / (int32_t) blockSize), pResult); -} - -/** - * @} end of RMS group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_rms_q31.c +* +* Description: Root Mean Square of the elements of a Q31 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @addtogroup RMS + * @{ + */ + + +/** + * @brief Root Mean Square of the elements of a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult rms value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + *\par + * The function is implemented using an internal 64-bit accumulator. + * The input is represented in 1.31 format, and intermediate multiplication + * yields a 2.62 format. + * The accumulator maintains full precision of the intermediate multiplication results, + * but provides only a single guard bit. + * There is no saturation on intermediate additions. + * If the accumulator overflows, it wraps around and distorts the result. + * In order to avoid overflows completely, the input signal must be scaled down by + * log2(blockSize) bits, as a total of blockSize additions are performed internally. + * Finally, the 2.62 accumulator is right shifted by 31 bits to yield a 1.31 format value. + * + */ + +void arm_rms_q31( + q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult) +{ + q63_t sum = 0; /* accumulator */ + q31_t in; /* Temporary variable to store the input */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t *pIn1 = pSrc; /* SrcA pointer */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute sum of the squares and then store the result in a temporary variable, sum */ + in = *pIn1++; + sum += (q63_t) in *in; + in = *pIn1++; + sum += (q63_t) in *in; + in = *pIn1++; + sum += (q63_t) in *in; + in = *pIn1++; + sum += (q63_t) in *in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute sum of the squares and then store the results in a temporary variable, sum */ + in = *pIn1++; + sum += (q63_t) in *in; + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ + /* Compute sum of the squares and then store the results in a temporary variable, sum */ + in = *pSrc++; + sum += (q63_t) in *in; + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Convert data in 2.62 to 1.31 by 31 right shifts */ + sum = sum >> 31; + + /* Compute Rms and store the result in the destination vector */ + arm_sqrt_q31((q31_t) (sum / (int32_t) blockSize), pResult); +} + +/** + * @} end of RMS group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_f32.c index ea8c5b97d..800969702 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_f32.c @@ -1,222 +1,222 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_std_f32.c -* -* Description: Standard deviation of the elements of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup STD Standard deviation - * - * Calculates the standard deviation of the elements in the input vector. - * The underlying algorithm is used: - * - *
   
- * 	Result = sqrt((sumOfSquares - sum2 / blockSize) / (blockSize - 1))  
- *  
- *	   where, sumOfSquares = pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + ... + pSrc[blockSize-1] * pSrc[blockSize-1]  
- *  
- *	                   sum = pSrc[0] + pSrc[1] + pSrc[2] + ... + pSrc[blockSize-1]  
- * 
- * - * There are separate functions for floating point, Q31, and Q15 data types. - */ - -/** - * @addtogroup STD - * @{ - */ - - -/** - * @brief Standard deviation of the elements of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult standard deviation value returned here - * @return none. - * - */ - - -void arm_std_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult) -{ - float32_t sum = 0.0f; /* Temporary result storage */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t meanOfSquares, mean, in, squareOfMean; - uint32_t blkCnt; /* loop counter */ - float32_t *pIn; /* Temporary pointer */ - - pIn = pSrc; - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - meanOfSquares = sum / ((float32_t) blockSize - 1.0f); - - /* Reset the accumulator */ - sum = 0.0f; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Reset the input working pointer */ - pSrc = pIn; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - /* Compute mean of all input values */ - mean = sum / (float32_t) blockSize; - - /* Compute square of mean */ - squareOfMean = (mean * mean) * (((float32_t) blockSize) / - ((float32_t) blockSize - 1.0f)); - - /* Compute standard deviation and then store the result to the destination */ - arm_sqrt_f32((meanOfSquares - squareOfMean), pResult); - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t sumOfSquares = 0.0f; /* Sum of squares */ - float32_t squareOfSum; /* Square of Sum */ - float32_t in; /* input value */ - float32_t var; /* Temporary varaince storage */ - uint32_t blkCnt; /* loop counter */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += in * in; - - /* C = (A[0] + A[1] + ... + A[blockSize-1]) */ - /* Compute Sum of the input samples - * and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute the square of sum */ - squareOfSum = ((sum * sum) / (float32_t) blockSize); - - /* Compute the variance */ - var = ((sumOfSquares - squareOfSum) / (float32_t) (blockSize - 1.0f)); - - /* Compute standard deviation and then store the result to the destination */ - arm_sqrt_f32(var, pResult); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of STD group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_std_f32.c +* +* Description: Standard deviation of the elements of a floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @defgroup STD Standard deviation + * + * Calculates the standard deviation of the elements in the input vector. + * The underlying algorithm is used: + * + *
   
+ * 	Result = sqrt((sumOfSquares - sum2 / blockSize) / (blockSize - 1))  
+ *  
+ *	   where, sumOfSquares = pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + ... + pSrc[blockSize-1] * pSrc[blockSize-1]  
+ *  
+ *	                   sum = pSrc[0] + pSrc[1] + pSrc[2] + ... + pSrc[blockSize-1]  
+ * 
+ * + * There are separate functions for floating point, Q31, and Q15 data types. + */ + +/** + * @addtogroup STD + * @{ + */ + + +/** + * @brief Standard deviation of the elements of a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult standard deviation value returned here + * @return none. + * + */ + + +void arm_std_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult) +{ + float32_t sum = 0.0f; /* Temporary result storage */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + float32_t meanOfSquares, mean, in, squareOfMean; + uint32_t blkCnt; /* loop counter */ + float32_t *pIn; /* Temporary pointer */ + + pIn = pSrc; + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += in * in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute Mean of squares of the input samples + * and then store the result in a temporary variable, meanOfSquares. */ + meanOfSquares = sum / ((float32_t) blockSize - 1.0f); + + /* Reset the accumulator */ + sum = 0.0f; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Reset the input working pointer */ + pSrc = pIn; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + /* Compute mean of all input values */ + mean = sum / (float32_t) blockSize; + + /* Compute square of mean */ + squareOfMean = (mean * mean) * (((float32_t) blockSize) / + ((float32_t) blockSize - 1.0f)); + + /* Compute standard deviation and then store the result to the destination */ + arm_sqrt_f32((meanOfSquares - squareOfMean), pResult); + +#else + + /* Run the below code for Cortex-M0 */ + + float32_t sumOfSquares = 0.0f; /* Sum of squares */ + float32_t squareOfSum; /* Square of Sum */ + float32_t in; /* input value */ + float32_t var; /* Temporary varaince storage */ + uint32_t blkCnt; /* loop counter */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sumOfSquares. */ + in = *pSrc++; + sumOfSquares += in * in; + + /* C = (A[0] + A[1] + ... + A[blockSize-1]) */ + /* Compute Sum of the input samples + * and then store the result in a temporary variable, sum. */ + sum += in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute the square of sum */ + squareOfSum = ((sum * sum) / (float32_t) blockSize); + + /* Compute the variance */ + var = ((sumOfSquares - squareOfSum) / (float32_t) (blockSize - 1.0f)); + + /* Compute standard deviation and then store the result to the destination */ + arm_sqrt_f32(var, pResult); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of STD group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_q15.c index 371652dd2..19d9884d3 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_q15.c @@ -1,229 +1,229 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_std_q15.c -* -* Description: Standard deviation of an array of Q15 type. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup STD - * @{ - */ - -/** - * @brief Standard deviation of the elements of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult standard deviation value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.15 format. - * Intermediate multiplication yields a 2.30 format, and this - * result is added without saturation to a 64-bit accumulator in 34.30 format. - * With 33 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the 34.30 result is truncated to 34.15 format by discarding the lower - * 15 bits, and then saturated to yield a result in 1.15 format. - */ - -void arm_std_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult) -{ - q63_t sum = 0; /* Accumulator */ - q31_t meanOfSquares, squareOfMean; /* square of mean and mean of square */ - q15_t mean; /* mean */ - uint32_t blkCnt; /* loop counter */ - q15_t t; /* Temporary variable */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *pIn; /* Temporary pointer */ - q31_t in; /* input value */ - q15_t in1; /* input value */ - - pIn = pSrc; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *__SIMD32(pSrc)++; - sum = __SMLALD(in, in, sum); - in = *__SIMD32(pSrc)++; - sum = __SMLALD(in, in, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in1 = *pSrc++; - sum = __SMLALD(in1, in1, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q15_t) ((1.0 / (blockSize - 1)) * 16384LL); - sum = __SSAT((sum >> 15u), 16u); - - meanOfSquares = (q31_t) ((sum * t) >> 14u); - - /* Reset the accumulator */ - sum = 0; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Reset the input working pointer */ - pSrc = pIn; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - /* Compute mean of all input values */ - t = (q15_t) ((1.0 / (blockSize * (blockSize - 1))) * 32768LL); - mean = (q15_t) __SSAT(sum, 16u); - - /* Compute square of mean */ - squareOfMean = ((q31_t) mean * mean) >> 15; - squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 15); - - /* mean of the squares minus the square of the mean. */ - in1 = (q15_t) (meanOfSquares - squareOfMean); - - /* Compute standard deviation and store the result to the destination */ - arm_sqrt_q15(in1, pResult); - -#else - - /* Run the below code for Cortex-M0 */ - - q63_t sumOfSquares = 0; /* Accumulator */ - q15_t in; /* input value */ - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += (in * in); - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q15_t) ((1.0 / (blockSize - 1)) * 16384LL); - sumOfSquares = __SSAT((sumOfSquares >> 15u), 16u); - meanOfSquares = (q31_t) ((sumOfSquares * t) >> 14u); - - /* Compute mean of all input values */ - mean = (q15_t) __SSAT(sum, 16u); - - /* Compute square of mean of the input samples - * and then store the result in a temporary variable, squareOfMean.*/ - t = (q15_t) ((1.0 / (blockSize * (blockSize - 1))) * 32768LL); - squareOfMean = ((q31_t) mean * mean) >> 15; - squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 15); - - /* mean of the squares minus the square of the mean. */ - in = (q15_t) (meanOfSquares - squareOfMean); - - /* Compute standard deviation and store the result to the destination */ - arm_sqrt_q15(in, pResult); - -#endif /* #ifndef ARM_MATH_CM0 */ - - -} - -/** - * @} end of STD group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_std_q15.c +* +* Description: Standard deviation of an array of Q15 type. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup STD + * @{ + */ + +/** + * @brief Standard deviation of the elements of a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult standard deviation value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 64-bit internal accumulator. + * The input is represented in 1.15 format. + * Intermediate multiplication yields a 2.30 format, and this + * result is added without saturation to a 64-bit accumulator in 34.30 format. + * With 33 guard bits in the accumulator, there is no risk of overflow, and the + * full precision of the intermediate multiplication is preserved. + * Finally, the 34.30 result is truncated to 34.15 format by discarding the lower + * 15 bits, and then saturated to yield a result in 1.15 format. + */ + +void arm_std_q15( + q15_t * pSrc, + uint32_t blockSize, + q15_t * pResult) +{ + q63_t sum = 0; /* Accumulator */ + q31_t meanOfSquares, squareOfMean; /* square of mean and mean of square */ + q15_t mean; /* mean */ + uint32_t blkCnt; /* loop counter */ + q15_t t; /* Temporary variable */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t *pIn; /* Temporary pointer */ + q31_t in; /* input value */ + q15_t in1; /* input value */ + + pIn = pSrc; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in = *__SIMD32(pSrc)++; + sum = __SMLALD(in, in, sum); + in = *__SIMD32(pSrc)++; + sum = __SMLALD(in, in, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in1 = *pSrc++; + sum = __SMLALD(in1, in1, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute Mean of squares of the input samples + * and then store the result in a temporary variable, meanOfSquares. */ + t = (q15_t) ((1.0 / (blockSize - 1)) * 16384LL); + sum = __SSAT((sum >> 15u), 16u); + + meanOfSquares = (q31_t) ((sum * t) >> 14u); + + /* Reset the accumulator */ + sum = 0; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Reset the input working pointer */ + pSrc = pIn; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + /* Compute mean of all input values */ + t = (q15_t) ((1.0 / (blockSize * (blockSize - 1))) * 32768LL); + mean = (q15_t) __SSAT(sum, 16u); + + /* Compute square of mean */ + squareOfMean = ((q31_t) mean * mean) >> 15; + squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 15); + + /* mean of the squares minus the square of the mean. */ + in1 = (q15_t) (meanOfSquares - squareOfMean); + + /* Compute standard deviation and store the result to the destination */ + arm_sqrt_q15(in1, pResult); + +#else + + /* Run the below code for Cortex-M0 */ + + q63_t sumOfSquares = 0; /* Accumulator */ + q15_t in; /* input value */ + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sumOfSquares. */ + in = *pSrc++; + sumOfSquares += (in * in); + + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute Mean of squares of the input samples + * and then store the result in a temporary variable, meanOfSquares. */ + t = (q15_t) ((1.0 / (blockSize - 1)) * 16384LL); + sumOfSquares = __SSAT((sumOfSquares >> 15u), 16u); + meanOfSquares = (q31_t) ((sumOfSquares * t) >> 14u); + + /* Compute mean of all input values */ + mean = (q15_t) __SSAT(sum, 16u); + + /* Compute square of mean of the input samples + * and then store the result in a temporary variable, squareOfMean.*/ + t = (q15_t) ((1.0 / (blockSize * (blockSize - 1))) * 32768LL); + squareOfMean = ((q31_t) mean * mean) >> 15; + squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 15); + + /* mean of the squares minus the square of the mean. */ + in = (q15_t) (meanOfSquares - squareOfMean); + + /* Compute standard deviation and store the result to the destination */ + arm_sqrt_q15(in, pResult); + +#endif /* #ifndef ARM_MATH_CM0 */ + + +} + +/** + * @} end of STD group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_q31.c index a33d51b4f..d167ed730 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_std_q31.c @@ -1,219 +1,219 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_std_q31.c -* -* Description: Standard deviation of an array of Q31 type. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup STD - * @{ - */ - - -/** - * @brief Standard deviation of the elements of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult standard deviation value returned here - * @return none. - * @details - * Scaling and Overflow Behavior: - * - *\par - * The function is implemented using an internal 64-bit accumulator. - * The input is represented in 1.31 format, and intermediate multiplication - * yields a 2.62 format. - * The accumulator maintains full precision of the intermediate multiplication results, - * but provides only a single guard bit. - * There is no saturation on intermediate additions. - * If the accumulator overflows it wraps around and distorts the result. - * In order to avoid overflows completely the input signal must be scaled down by - * log2(blockSize) bits, as a total of blockSize additions are performed internally. - * Finally, the 2.62 accumulator is right shifted by 31 bits to yield a 1.31 format value. - * - */ - - -void arm_std_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult) -{ - q63_t sum = 0; /* Accumulator */ - q31_t meanOfSquares, squareOfMean; /* square of mean and mean of square */ - q31_t mean; /* mean */ - q31_t in; /* input value */ - q31_t t; /* Temporary variable */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t *pIn; /* Temporary pointer */ - - pIn = pSrc; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += ((q63_t) (in) * (in)); - in = *pSrc++; - sum += ((q63_t) (in) * (in)); - in = *pSrc++; - sum += ((q63_t) (in) * (in)); - in = *pSrc++; - sum += ((q63_t) (in) * (in)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += ((q63_t) (in) * (in)); - - /* Decrement the loop counter */ - blkCnt--; - } - - t = (q31_t) ((1.0f / (float32_t) (blockSize - 1u)) * 1073741824.0f); - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - sum = (sum >> 31); - meanOfSquares = (q31_t) ((sum * t) >> 30); - - /* Reset the accumulator */ - sum = 0; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Reset the input working pointer */ - pSrc = pIn; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q63_t sumOfSquares = 0; /* Accumulator */ - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += ((q63_t) (in) * (in)); - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q31_t) ((1.0f / (float32_t) (blockSize - 1u)) * 1073741824.0f); - sumOfSquares = (sumOfSquares >> 31); - meanOfSquares = (q31_t) ((sumOfSquares * t) >> 30); - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Compute mean of all input values */ - t = (q31_t) ((1.0f / (blockSize * (blockSize - 1u))) * 2147483648.0f); - mean = (q31_t) (sum); - - /* Compute square of mean */ - squareOfMean = (q31_t) (((q63_t) mean * mean) >> 31); - squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 31); - - - /* Compute standard deviation and then store the result to the destination */ - arm_sqrt_q31(meanOfSquares - squareOfMean, pResult); - -} - -/** - * @} end of STD group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_std_q31.c +* +* Description: Standard deviation of an array of Q31 type. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup STD + * @{ + */ + + +/** + * @brief Standard deviation of the elements of a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult standard deviation value returned here + * @return none. + * @details + * Scaling and Overflow Behavior: + * + *\par + * The function is implemented using an internal 64-bit accumulator. + * The input is represented in 1.31 format, and intermediate multiplication + * yields a 2.62 format. + * The accumulator maintains full precision of the intermediate multiplication results, + * but provides only a single guard bit. + * There is no saturation on intermediate additions. + * If the accumulator overflows it wraps around and distorts the result. + * In order to avoid overflows completely the input signal must be scaled down by + * log2(blockSize) bits, as a total of blockSize additions are performed internally. + * Finally, the 2.62 accumulator is right shifted by 31 bits to yield a 1.31 format value. + * + */ + + +void arm_std_q31( + q31_t * pSrc, + uint32_t blockSize, + q31_t * pResult) +{ + q63_t sum = 0; /* Accumulator */ + q31_t meanOfSquares, squareOfMean; /* square of mean and mean of square */ + q31_t mean; /* mean */ + q31_t in; /* input value */ + q31_t t; /* Temporary variable */ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t *pIn; /* Temporary pointer */ + + pIn = pSrc; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += ((q63_t) (in) * (in)); + in = *pSrc++; + sum += ((q63_t) (in) * (in)); + in = *pSrc++; + sum += ((q63_t) (in) * (in)); + in = *pSrc++; + sum += ((q63_t) (in) * (in)); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += ((q63_t) (in) * (in)); + + /* Decrement the loop counter */ + blkCnt--; + } + + t = (q31_t) ((1.0f / (float32_t) (blockSize - 1u)) * 1073741824.0f); + + /* Compute Mean of squares of the input samples + * and then store the result in a temporary variable, meanOfSquares. */ + sum = (sum >> 31); + meanOfSquares = (q31_t) ((sum * t) >> 30); + + /* Reset the accumulator */ + sum = 0; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Reset the input working pointer */ + pSrc = pIn; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q63_t sumOfSquares = 0; /* Accumulator */ + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sumOfSquares. */ + in = *pSrc++; + sumOfSquares += ((q63_t) (in) * (in)); + + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute Mean of squares of the input samples + * and then store the result in a temporary variable, meanOfSquares. */ + t = (q31_t) ((1.0f / (float32_t) (blockSize - 1u)) * 1073741824.0f); + sumOfSquares = (sumOfSquares >> 31); + meanOfSquares = (q31_t) ((sumOfSquares * t) >> 30); + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Compute mean of all input values */ + t = (q31_t) ((1.0f / (blockSize * (blockSize - 1u))) * 2147483648.0f); + mean = (q31_t) (sum); + + /* Compute square of mean */ + squareOfMean = (q31_t) (((q63_t) mean * mean) >> 31); + squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 31); + + + /* Compute standard deviation and then store the result to the destination */ + arm_sqrt_q31(meanOfSquares - squareOfMean, pResult); + +} + +/** + * @} end of STD group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_f32.c index 89aca0e39..9b6a5a89d 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_f32.c @@ -1,219 +1,219 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_var_f32.c -* -* Description: Variance of the elements of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup variance Variance - * - * Calculates the variance of the elements in the input vector. - * The underlying algorithm is used: - * - *
   
- * 	Result = (sumOfSquares - sum2 / blockSize) / (blockSize - 1)  
- *  
- *	   where, sumOfSquares = pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + ... + pSrc[blockSize-1] * pSrc[blockSize-1]  
- *  
- *	                   sum = pSrc[0] + pSrc[1] + pSrc[2] + ... + pSrc[blockSize-1]  
- * 
- * - * There are separate functions for floating point, Q31, and Q15 data types. - */ - -/** - * @addtogroup variance - * @{ - */ - - -/** - * @brief Variance of the elements of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult variance value returned here - * @return none. - * - */ - - -void arm_var_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t sum = (float32_t) 0.0; /* Accumulator */ - float32_t meanOfSquares, mean, in, squareOfMean; /* Temporary variables */ - uint32_t blkCnt; /* loop counter */ - float32_t *pIn; /* Temporary pointer */ - - /* updating temporary pointer */ - pIn = pSrc; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - meanOfSquares = sum / ((float32_t) blockSize - 1.0f); - - /* Reset the accumulator */ - sum = 0.0f; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Reset the input working pointer */ - pSrc = pIn; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - /* Compute mean of all input values */ - mean = sum / (float32_t) blockSize; - - /* Compute square of mean */ - squareOfMean = (mean * mean) * (((float32_t) blockSize) / - ((float32_t) blockSize - 1.0f)); - - /* Compute variance and then store the result to the destination */ - *pResult = meanOfSquares - squareOfMean; - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t sum = 0.0f; /* Temporary result storage */ - float32_t sumOfSquares = 0.0f; /* Sum of squares */ - float32_t squareOfSum; /* Square of Sum */ - float32_t in; /* input value */ - uint32_t blkCnt; /* loop counter */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += in * in; - - /* C = (A[0] + A[1] + ... + A[blockSize-1]) */ - /* Compute Sum of the input samples - * and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute the square of sum */ - squareOfSum = ((sum * sum) / (float32_t) blockSize); - - /* Compute the variance */ - *pResult = ((sumOfSquares - squareOfSum) / (float32_t) (blockSize - 1.0f)); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of variance group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_var_f32.c +* +* Description: Variance of the elements of a floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @defgroup variance Variance + * + * Calculates the variance of the elements in the input vector. + * The underlying algorithm is used: + * + *
   
+ * 	Result = (sumOfSquares - sum2 / blockSize) / (blockSize - 1)  
+ *  
+ *	   where, sumOfSquares = pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + ... + pSrc[blockSize-1] * pSrc[blockSize-1]  
+ *  
+ *	                   sum = pSrc[0] + pSrc[1] + pSrc[2] + ... + pSrc[blockSize-1]  
+ * 
+ * + * There are separate functions for floating point, Q31, and Q15 data types. + */ + +/** + * @addtogroup variance + * @{ + */ + + +/** + * @brief Variance of the elements of a floating-point vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult variance value returned here + * @return none. + * + */ + + +void arm_var_f32( + float32_t * pSrc, + uint32_t blockSize, + float32_t * pResult) +{ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + float32_t sum = (float32_t) 0.0; /* Accumulator */ + float32_t meanOfSquares, mean, in, squareOfMean; /* Temporary variables */ + uint32_t blkCnt; /* loop counter */ + float32_t *pIn; /* Temporary pointer */ + + /* updating temporary pointer */ + pIn = pSrc; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + in = *pSrc++; + sum += in * in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += in * in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute Mean of squares of the input samples + * and then store the result in a temporary variable, meanOfSquares. */ + meanOfSquares = sum / ((float32_t) blockSize - 1.0f); + + /* Reset the accumulator */ + sum = 0.0f; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Reset the input working pointer */ + pSrc = pIn; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + /* Compute mean of all input values */ + mean = sum / (float32_t) blockSize; + + /* Compute square of mean */ + squareOfMean = (mean * mean) * (((float32_t) blockSize) / + ((float32_t) blockSize - 1.0f)); + + /* Compute variance and then store the result to the destination */ + *pResult = meanOfSquares - squareOfMean; + +#else + + /* Run the below code for Cortex-M0 */ + + float32_t sum = 0.0f; /* Temporary result storage */ + float32_t sumOfSquares = 0.0f; /* Sum of squares */ + float32_t squareOfSum; /* Square of Sum */ + float32_t in; /* input value */ + uint32_t blkCnt; /* loop counter */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sumOfSquares. */ + in = *pSrc++; + sumOfSquares += in * in; + + /* C = (A[0] + A[1] + ... + A[blockSize-1]) */ + /* Compute Sum of the input samples + * and then store the result in a temporary variable, sum. */ + sum += in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute the square of sum */ + squareOfSum = ((sum * sum) / (float32_t) blockSize); + + /* Compute the variance */ + *pResult = ((sumOfSquares - squareOfSum) / (float32_t) (blockSize - 1.0f)); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of variance group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_q15.c index 972183422..e557a0d85 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_q15.c @@ -1,214 +1,214 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_var_q15.c -* -* Description: Variance of an array of Q15 type. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup variance - * @{ - */ - -/** - * @brief Variance of the elements of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult variance value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.15 format. - * Intermediate multiplication yields a 2.30 format, and this - * result is added without saturation to a 64-bit accumulator in 34.30 format. - * With 33 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the 34.30 result is truncated to 34.15 format by discarding the lower - * 15 bits, and then saturated to yield a result in 1.15 format. - * - */ - - -void arm_var_q15( - q15_t * pSrc, - uint32_t blockSize, - q31_t * pResult) -{ - q63_t sum = 0; /* Accumulator */ - q31_t meanOfSquares, squareOfMean; /* Mean of square and square of mean */ - q15_t mean; /* mean */ - uint32_t blkCnt; /* loop counter */ - q15_t t; /* Temporary variable */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in; /* Input variable */ - q15_t in1; /* Temporary variable */ - q15_t *pIn; /* Temporary pointer */ - - pIn = pSrc; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *__SIMD32(pSrc)++; - sum = __SMLALD(in, in, sum); - in = *__SIMD32(pSrc)++; - sum = __SMLALD(in, in, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in1 = *pSrc++; - sum = __SMLALD(in1, in1, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q15_t) ((1.0f / (float32_t) (blockSize - 1u)) * 16384); - sum = __SSAT((sum >> 15u), 16u); - - meanOfSquares = (q31_t) ((sum * t) >> 14u); - - /* Reset the accumulator */ - sum = 0; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Reset the input working pointer */ - pSrc = pIn; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q63_t sumOfSquares = 0; /* Accumulator */ - q15_t in; /* Temporary variable */ - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += (in * in); - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q15_t) ((1.0f / (float32_t) (blockSize - 1u)) * 16384); - sumOfSquares = __SSAT((sumOfSquares >> 15u), 16u); - meanOfSquares = (q31_t) ((sumOfSquares * t) >> 14u); - - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Compute mean of all input values */ - t = (q15_t) ((1.0f / (float32_t) (blockSize * (blockSize - 1u))) * 32768); - mean = __SSAT(sum, 16u); - - /* Compute square of mean */ - squareOfMean = ((q31_t) mean * mean) >> 15; - squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 15); - - /* Compute variance and then store the result to the destination */ - *pResult = (meanOfSquares - squareOfMean); - -} - -/** - * @} end of variance group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_var_q15.c +* +* Description: Variance of an array of Q15 type. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup variance + * @{ + */ + +/** + * @brief Variance of the elements of a Q15 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult variance value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + * \par + * The function is implemented using a 64-bit internal accumulator. + * The input is represented in 1.15 format. + * Intermediate multiplication yields a 2.30 format, and this + * result is added without saturation to a 64-bit accumulator in 34.30 format. + * With 33 guard bits in the accumulator, there is no risk of overflow, and the + * full precision of the intermediate multiplication is preserved. + * Finally, the 34.30 result is truncated to 34.15 format by discarding the lower + * 15 bits, and then saturated to yield a result in 1.15 format. + * + */ + + +void arm_var_q15( + q15_t * pSrc, + uint32_t blockSize, + q31_t * pResult) +{ + q63_t sum = 0; /* Accumulator */ + q31_t meanOfSquares, squareOfMean; /* Mean of square and square of mean */ + q15_t mean; /* mean */ + uint32_t blkCnt; /* loop counter */ + q15_t t; /* Temporary variable */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t in; /* Input variable */ + q15_t in1; /* Temporary variable */ + q15_t *pIn; /* Temporary pointer */ + + pIn = pSrc; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in = *__SIMD32(pSrc)++; + sum = __SMLALD(in, in, sum); + in = *__SIMD32(pSrc)++; + sum = __SMLALD(in, in, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in1 = *pSrc++; + sum = __SMLALD(in1, in1, sum); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute Mean of squares of the input samples + * and then store the result in a temporary variable, meanOfSquares. */ + t = (q15_t) ((1.0f / (float32_t) (blockSize - 1u)) * 16384); + sum = __SSAT((sum >> 15u), 16u); + + meanOfSquares = (q31_t) ((sum * t) >> 14u); + + /* Reset the accumulator */ + sum = 0; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Reset the input working pointer */ + pSrc = pIn; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q63_t sumOfSquares = 0; /* Accumulator */ + q15_t in; /* Temporary variable */ + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sumOfSquares. */ + in = *pSrc++; + sumOfSquares += (in * in); + + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute Mean of squares of the input samples + * and then store the result in a temporary variable, meanOfSquares. */ + t = (q15_t) ((1.0f / (float32_t) (blockSize - 1u)) * 16384); + sumOfSquares = __SSAT((sumOfSquares >> 15u), 16u); + meanOfSquares = (q31_t) ((sumOfSquares * t) >> 14u); + + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Compute mean of all input values */ + t = (q15_t) ((1.0f / (float32_t) (blockSize * (blockSize - 1u))) * 32768); + mean = __SSAT(sum, 16u); + + /* Compute square of mean */ + squareOfMean = ((q31_t) mean * mean) >> 15; + squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 15); + + /* Compute variance and then store the result to the destination */ + *pResult = (meanOfSquares - squareOfMean); + +} + +/** + * @} end of variance group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_q31.c index 94d3405db..c22f0224e 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/StatisticsFunctions/arm_var_q31.c @@ -1,216 +1,216 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_var_q31.c -* -* Description: Variance of an array of Q31 type. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup variance - * @{ - */ - -/** - * @brief Variance of the elements of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult variance value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - *\par - * The function is implemented using an internal 64-bit accumulator. - * The input is represented in 1.31 format, and intermediate multiplication - * yields a 2.62 format. - * The accumulator maintains full precision of the intermediate multiplication results, - * but provides only a single guard bit. - * There is no saturation on intermediate additions. - * If the accumulator overflows it wraps around and distorts the result. - * In order to avoid overflows completely the input signal must be scaled down by - * log2(blockSize) bits, as a total of blockSize additions are performed internally. - * Finally, the 2.62 accumulator is right shifted by 31 bits to yield a 1.31 format value. - * - */ - - -void arm_var_q31( - q31_t * pSrc, - uint32_t blockSize, - q63_t * pResult) -{ - q63_t sum = 0; /* Accumulator */ - q31_t meanOfSquares, squareOfMean; /* Mean of square and square of mean */ - q31_t mean; /* Mean */ - q31_t in; /* Input variable */ - q31_t t; /* Temporary variable */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t *pIn; /* Temporary pointer */ - - pIn = pSrc; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += ((q63_t) (in) * (in)); - in = *pSrc++; - sum += ((q63_t) (in) * (in)); - in = *pSrc++; - sum += ((q63_t) (in) * (in)); - in = *pSrc++; - sum += ((q63_t) (in) * (in)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += ((q63_t) (in) * (in)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q31_t) ((1.0 / (blockSize - 1)) * 1073741824LL); - sum = (sum >> 31); - meanOfSquares = (q31_t) ((sum * t) >> 30); - - /* Reset the accumulator */ - sum = 0; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Reset the input working pointer */ - pSrc = pIn; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q63_t sumOfSquares = 0; /* Accumulator */ - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += ((q63_t) (in) * (in)); - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q31_t) ((1.0 / (blockSize - 1)) * 1073741824LL); - sumOfSquares = (sumOfSquares >> 31); - meanOfSquares = (q31_t) ((sumOfSquares * t) >> 30); - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Compute mean of all input values */ - t = (q31_t) ((1.0 / (blockSize * (blockSize - 1u))) * 2147483648LL); - mean = (q31_t) (sum); - - /* Compute square of mean */ - squareOfMean = (q31_t) (((q63_t) mean * mean) >> 31); - squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 31); - - /* Compute variance and then store the result to the destination */ - *pResult = (q63_t) meanOfSquares - squareOfMean; - -} - -/** - * @} end of variance group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_var_q31.c +* +* Description: Variance of an array of Q31 type. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupStats + */ + +/** + * @addtogroup variance + * @{ + */ + +/** + * @brief Variance of the elements of a Q31 vector. + * @param[in] *pSrc points to the input vector + * @param[in] blockSize length of the input vector + * @param[out] *pResult variance value returned here + * @return none. + * + * @details + * Scaling and Overflow Behavior: + * + *\par + * The function is implemented using an internal 64-bit accumulator. + * The input is represented in 1.31 format, and intermediate multiplication + * yields a 2.62 format. + * The accumulator maintains full precision of the intermediate multiplication results, + * but provides only a single guard bit. + * There is no saturation on intermediate additions. + * If the accumulator overflows it wraps around and distorts the result. + * In order to avoid overflows completely the input signal must be scaled down by + * log2(blockSize) bits, as a total of blockSize additions are performed internally. + * Finally, the 2.62 accumulator is right shifted by 31 bits to yield a 1.31 format value. + * + */ + + +void arm_var_q31( + q31_t * pSrc, + uint32_t blockSize, + q63_t * pResult) +{ + q63_t sum = 0; /* Accumulator */ + q31_t meanOfSquares, squareOfMean; /* Mean of square and square of mean */ + q31_t mean; /* Mean */ + q31_t in; /* Input variable */ + q31_t t; /* Temporary variable */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t *pIn; /* Temporary pointer */ + + pIn = pSrc; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += ((q63_t) (in) * (in)); + in = *pSrc++; + sum += ((q63_t) (in) * (in)); + in = *pSrc++; + sum += ((q63_t) (in) * (in)); + in = *pSrc++; + sum += ((q63_t) (in) * (in)); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sum. */ + in = *pSrc++; + sum += ((q63_t) (in) * (in)); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute Mean of squares of the input samples + * and then store the result in a temporary variable, meanOfSquares. */ + t = (q31_t) ((1.0 / (blockSize - 1)) * 1073741824LL); + sum = (sum >> 31); + meanOfSquares = (q31_t) ((sum * t) >> 30); + + /* Reset the accumulator */ + sum = 0; + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Reset the input working pointer */ + pSrc = pIn; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + +#else + + /* Run the below code for Cortex-M0 */ + + q63_t sumOfSquares = 0; /* Accumulator */ + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ + /* Compute Sum of squares of the input samples + * and then store the result in a temporary variable, sumOfSquares. */ + in = *pSrc++; + sumOfSquares += ((q63_t) (in) * (in)); + + /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ + /* Compute sum of all input values and then store the result in a temporary variable, sum. */ + sum += in; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* Compute Mean of squares of the input samples + * and then store the result in a temporary variable, meanOfSquares. */ + t = (q31_t) ((1.0 / (blockSize - 1)) * 1073741824LL); + sumOfSquares = (sumOfSquares >> 31); + meanOfSquares = (q31_t) ((sumOfSquares * t) >> 30); + +#endif /* #ifndef ARM_MATH_CM0 */ + + /* Compute mean of all input values */ + t = (q31_t) ((1.0 / (blockSize * (blockSize - 1u))) * 2147483648LL); + mean = (q31_t) (sum); + + /* Compute square of mean */ + squareOfMean = (q31_t) (((q63_t) mean * mean) >> 31); + squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 31); + + /* Compute variance and then store the result to the destination */ + *pResult = (q63_t) meanOfSquares - squareOfMean; + +} + +/** + * @} end of variance group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_f32.c index 32ad4682f..86652cd35 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_f32.c @@ -1,121 +1,121 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_copy_f32.c -* -* Description: Copies the elements of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup copy Vector Copy - * - * Copies sample by sample from source vector to destination vector. - * - *
   
- * 	pDst[n] = pSrc[n];   0 <= n < blockSize.   
- * 
- * - * There are separate functions for floating point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup copy - * @{ - */ - -/** - * @brief Copies the elements of a floating-point vector. - * @param[in] *pSrc points to input vector - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the input vector - * @return none. - * - */ - - -void arm_copy_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the results in the destination buffer */ - *pDst++ = *pSrc++; - *pDst++ = *pSrc++; - *pDst++ = *pSrc++; - *pDst++ = *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the results in the destination buffer */ - *pDst++ = *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicCopy group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_copy_f32.c +* +* Description: Copies the elements of a floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @defgroup copy Vector Copy + * + * Copies sample by sample from source vector to destination vector. + * + *
   
+ * 	pDst[n] = pSrc[n];   0 <= n < blockSize.   
+ * 
+ * + * There are separate functions for floating point, Q31, Q15, and Q7 data types. + */ + +/** + * @addtogroup copy + * @{ + */ + +/** + * @brief Copies the elements of a floating-point vector. + * @param[in] *pSrc points to input vector + * @param[out] *pDst points to output vector + * @param[in] blockSize length of the input vector + * @return none. + * + */ + + +void arm_copy_f32( + float32_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A */ + /* Copy and then store the results in the destination buffer */ + *pDst++ = *pSrc++; + *pDst++ = *pSrc++; + *pDst++ = *pSrc++; + *pDst++ = *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A */ + /* Copy and then store the results in the destination buffer */ + *pDst++ = *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of BasicCopy group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q15.c index 80c31bbd6..d1a9c48a6 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q15.c @@ -1,130 +1,130 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_copy_q15.c -* -* Description: Copies the elements of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup copy - * @{ - */ -/** - * @brief Copies the elements of a Q15 vector. - * @param[in] *pSrc points to input vector - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the input vector - * @return none. - * - */ - -void arm_copy_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t in1, in2; /* Temporary variables */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A */ - /* Read two inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - -#ifndef ARM_MATH_BIG_ENDIAN - - /* Store the values in the destination buffer by packing the two inputs */ - *__SIMD32(pDst)++ = __PKHBT(in1, in2, 16); - - in1 = *pSrc++; - in2 = *pSrc++; - *__SIMD32(pDst)++ = __PKHBT(in1, in2, 16); - -#else - - /* Store the values in the destination buffer by packing the two inputs */ - *__SIMD32(pDst)++ = __PKHBT(in2, in1, 16); - - in1 = *pSrc++; - in2 = *pSrc++; - *__SIMD32(pDst)++ = __PKHBT(in2, in1, 16); - - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the value in the destination buffer */ - *pDst++ = *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicCopy group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_copy_q15.c +* +* Description: Copies the elements of a Q15 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup copy + * @{ + */ +/** + * @brief Copies the elements of a Q15 vector. + * @param[in] *pSrc points to input vector + * @param[out] *pDst points to output vector + * @param[in] blockSize length of the input vector + * @return none. + * + */ + +void arm_copy_q15( + q15_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q15_t in1, in2; /* Temporary variables */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A */ + /* Read two inputs */ + in1 = *pSrc++; + in2 = *pSrc++; + +#ifndef ARM_MATH_BIG_ENDIAN + + /* Store the values in the destination buffer by packing the two inputs */ + *__SIMD32(pDst)++ = __PKHBT(in1, in2, 16); + + in1 = *pSrc++; + in2 = *pSrc++; + *__SIMD32(pDst)++ = __PKHBT(in1, in2, 16); + +#else + + /* Store the values in the destination buffer by packing the two inputs */ + *__SIMD32(pDst)++ = __PKHBT(in2, in1, 16); + + in1 = *pSrc++; + in2 = *pSrc++; + *__SIMD32(pDst)++ = __PKHBT(in2, in1, 16); + + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A */ + /* Copy and then store the value in the destination buffer */ + *pDst++ = *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of BasicCopy group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q31.c index ed482d4be..db445b305 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q31.c @@ -1,109 +1,109 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_copy_q31.c -* -* Description: Copies the elements of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup copy - * @{ - */ - -/** - * @brief Copies the elements of a Q31 vector. - * @param[in] *pSrc points to input vector - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the input vector - * @return none. - * - */ - -void arm_copy_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the values in the destination buffer */ - *pDst++ = *pSrc++; - *pDst++ = *pSrc++; - *pDst++ = *pSrc++; - *pDst++ = *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the value in the destination buffer */ - *pDst++ = *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicCopy group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_copy_q31.c +* +* Description: Copies the elements of a Q31 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup copy + * @{ + */ + +/** + * @brief Copies the elements of a Q31 vector. + * @param[in] *pSrc points to input vector + * @param[out] *pDst points to output vector + * @param[in] blockSize length of the input vector + * @return none. + * + */ + +void arm_copy_q31( + q31_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A */ + /* Copy and then store the values in the destination buffer */ + *pDst++ = *pSrc++; + *pDst++ = *pSrc++; + *pDst++ = *pSrc++; + *pDst++ = *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = A */ + /* Copy and then store the value in the destination buffer */ + *pDst++ = *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of BasicCopy group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q7.c index a8fc25c64..57647d864 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_copy_q7.c @@ -1,107 +1,107 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_copy_q7.c -* -* Description: Copies the elements of a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup copy - * @{ - */ - -/** - * @brief Copies the elements of a Q7 vector. - * @param[in] *pSrc points to input vector - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the input vector - * @return none. - * - */ - -void arm_copy_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the results in the destination buffer */ - /* 4 samples are copied and stored at a time using SIMD */ - *__SIMD32(pDst)++ = *__SIMD32(pSrc)++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the results in the destination buffer */ - *pDst++ = *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicCopy group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_copy_q7.c +* +* Description: Copies the elements of a Q7 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup copy + * @{ + */ + +/** + * @brief Copies the elements of a Q7 vector. + * @param[in] *pSrc points to input vector + * @param[out] *pDst points to output vector + * @param[in] blockSize length of the input vector + * @return none. + * + */ + +void arm_copy_q7( + q7_t * pSrc, + q7_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = A */ + /* Copy and then store the results in the destination buffer */ + /* 4 samples are copied and stored at a time using SIMD */ + *__SIMD32(pDst)++ = *__SIMD32(pSrc)++; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = A */ + /* Copy and then store the results in the destination buffer */ + *pDst++ = *pSrc++; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of BasicCopy group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_f32.c index 3e7cf934f..ec9e2a153 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_f32.c @@ -1,122 +1,122 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fill_f32.c -* -* Description: Fills a constant value into a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup Fill Vector Fill - * - * Fills the destination vector with a constant value. - * - *
   
- * 	pDst[n] = value;   0 <= n < blockSize.   
- * 
- * - * There are separate functions for floating point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup Fill - * @{ - */ - -/** - * @brief Fills a constant value into a floating-point vector. - * @param[in] value input value to be filled - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the output vector - * @return none. - * - */ - - -void arm_fill_f32( - float32_t value, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = value; - *pDst++ = value; - *pDst++ = value; - *pDst++ = value; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = value; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of Fill group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fill_f32.c +* +* Description: Fills a constant value into a floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @defgroup Fill Vector Fill + * + * Fills the destination vector with a constant value. + * + *
   
+ * 	pDst[n] = value;   0 <= n < blockSize.   
+ * 
+ * + * There are separate functions for floating point, Q31, Q15, and Q7 data types. + */ + +/** + * @addtogroup Fill + * @{ + */ + +/** + * @brief Fills a constant value into a floating-point vector. + * @param[in] value input value to be filled + * @param[out] *pDst points to output vector + * @param[in] blockSize length of the output vector + * @return none. + * + */ + + +void arm_fill_f32( + float32_t value, + float32_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = value */ + /* Fill the value in the destination buffer */ + *pDst++ = value; + *pDst++ = value; + *pDst++ = value; + *pDst++ = value; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + + while(blkCnt > 0u) + { + /* C = value */ + /* Fill the value in the destination buffer */ + *pDst++ = value; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of Fill group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q15.c index a5da51a7a..2d8d7ad71 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q15.c @@ -1,112 +1,112 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fill_q15.c -* -* Description: Fills a constant value into a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup Fill - * @{ - */ - -/** - * @brief Fills a constant value into a Q15 vector. - * @param[in] value input value to be filled - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the output vector - * @return none. - * - */ - -void arm_fill_q15( - q15_t value, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t packedValue; /* value packed to 32 bits */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Packing two 16 bit values to 32 bit value in order to use SIMD */ - packedValue = __PKHBT(value, value, 16u); - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *__SIMD32(pDst)++ = packedValue; - *__SIMD32(pDst)++ = packedValue; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = value; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of Fill group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fill_q15.c +* +* Description: Fills a constant value into a Q15 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup Fill + * @{ + */ + +/** + * @brief Fills a constant value into a Q15 vector. + * @param[in] value input value to be filled + * @param[out] *pDst points to output vector + * @param[in] blockSize length of the output vector + * @return none. + * + */ + +void arm_fill_q15( + q15_t value, + q15_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t packedValue; /* value packed to 32 bits */ + + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Packing two 16 bit values to 32 bit value in order to use SIMD */ + packedValue = __PKHBT(value, value, 16u); + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = value */ + /* Fill the value in the destination buffer */ + *__SIMD32(pDst)++ = packedValue; + *__SIMD32(pDst)++ = packedValue; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = value */ + /* Fill the value in the destination buffer */ + *pDst++ = value; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of Fill group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q31.c index b571fdc9a..559f671d4 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q31.c @@ -1,109 +1,109 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fill_q31.c -* -* Description: Fills a constant value into a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup Fill - * @{ - */ - -/** - * @brief Fills a constant value into a Q31 vector. - * @param[in] value input value to be filled - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the output vector - * @return none. - * - */ - -void arm_fill_q31( - q31_t value, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = value; - *pDst++ = value; - *pDst++ = value; - *pDst++ = value; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = value; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of Fill group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fill_q31.c +* +* Description: Fills a constant value into a Q31 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup Fill + * @{ + */ + +/** + * @brief Fills a constant value into a Q31 vector. + * @param[in] value input value to be filled + * @param[out] *pDst points to output vector + * @param[in] blockSize length of the output vector + * @return none. + * + */ + +void arm_fill_q31( + q31_t value, + q31_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = value */ + /* Fill the value in the destination buffer */ + *pDst++ = value; + *pDst++ = value; + *pDst++ = value; + *pDst++ = value; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = value */ + /* Fill the value in the destination buffer */ + *pDst++ = value; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of Fill group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q7.c index 18bdf8007..277f918b6 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_fill_q7.c @@ -1,110 +1,110 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_fill_q7.c -* -* Description: Fills a constant value into a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup Fill - * @{ - */ - -/** - * @brief Fills a constant value into a Q7 vector. - * @param[in] value input value to be filled - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the output vector - * @return none. - * - */ - -void arm_fill_q7( - q7_t value, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t packedValue; /* value packed to 32 bits */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Packing four 8 bit values to 32 bit value in order to use SIMD */ - packedValue = __PACKq7(value, value, value, value); - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *__SIMD32(pDst)++ = packedValue; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = value; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of Fill group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_fill_q7.c +* +* Description: Fills a constant value into a Q7 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup Fill + * @{ + */ + +/** + * @brief Fills a constant value into a Q7 vector. + * @param[in] value input value to be filled + * @param[out] *pDst points to output vector + * @param[in] blockSize length of the output vector + * @return none. + * + */ + +void arm_fill_q7( + q7_t value, + q7_t * pDst, + uint32_t blockSize) +{ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t packedValue; /* value packed to 32 bits */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* Packing four 8 bit values to 32 bit value in order to use SIMD */ + packedValue = __PACKq7(value, value, value, value); + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = value */ + /* Fill the value in the destination buffer */ + *__SIMD32(pDst)++ = packedValue; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = value */ + /* Fill the value in the destination buffer */ + *pDst++ = value; + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of Fill group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q15.c index 85a740a42..c0f354d09 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q15.c @@ -1,193 +1,193 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_float_to_q15.c -* -* Description: Converts the elements of the floating-point vector to Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup float_to_x - * @{ - */ - -/** - * @brief Converts the elements of the floating-point vector to Q15 vector. - * @param[in] *pSrc points to the floating-point input vector - * @param[out] *pDst points to the Q15 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * \par - * The equation used for the conversion process is: - *
   
- * 	pDst[n] = (q15_t)(pSrc[n] * 32768);   0 <= n < blockSize.   
- * 
- * \par Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - * \note - * In order to apply rounding, the library should be rebuilt with the ROUNDING macro - * defined in the preprocessor section of project options. - * - */ - - -void arm_float_to_q15( - float32_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - float32_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifdef ARM_MATH_ROUNDING - - float32_t in; - -#endif /* #ifdef ARM_MATH_ROUNDING */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - -#else - - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - -#else - - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5f : -0.5f; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - -#else - - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of float_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_float_to_q15.c +* +* Description: Converts the elements of the floating-point vector to Q15 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup float_to_x + * @{ + */ + +/** + * @brief Converts the elements of the floating-point vector to Q15 vector. + * @param[in] *pSrc points to the floating-point input vector + * @param[out] *pDst points to the Q15 output vector + * @param[in] blockSize length of the input vector + * @return none. + * + * \par Description: + * \par + * The equation used for the conversion process is: + *
   
+ * 	pDst[n] = (q15_t)(pSrc[n] * 32768);   0 <= n < blockSize.   
+ * 
+ * \par Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. + * \note + * In order to apply rounding, the library should be rebuilt with the ROUNDING macro + * defined in the preprocessor section of project options. + * + */ + + +void arm_float_to_q15( + float32_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + float32_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + +#ifdef ARM_MATH_ROUNDING + + float32_t in; + +#endif /* #ifdef ARM_MATH_ROUNDING */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + +#ifdef ARM_MATH_ROUNDING + /* C = A * 32768 */ + /* convert from float to q15 and then store the results in the destination buffer */ + in = *pIn++; + in = (in * 32768.0f); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); + + in = *pIn++; + in = (in * 32768.0f); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); + + in = *pIn++; + in = (in * 32768.0f); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); + + in = *pIn++; + in = (in * 32768.0f); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); + +#else + + /* C = A * 32768 */ + /* convert from float to q15 and then store the results in the destination buffer */ + *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); + *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); + *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); + *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); + +#endif /* #ifdef ARM_MATH_ROUNDING */ + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + +#ifdef ARM_MATH_ROUNDING + /* C = A * 32768 */ + /* convert from float to q15 and then store the results in the destination buffer */ + in = *pIn++; + in = (in * 32768.0f); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); + +#else + + /* C = A * 32768 */ + /* convert from float to q15 and then store the results in the destination buffer */ + *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); + +#endif /* #ifdef ARM_MATH_ROUNDING */ + + /* Decrement the loop counter */ + blkCnt--; + } + + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + +#ifdef ARM_MATH_ROUNDING + /* C = A * 32768 */ + /* convert from float to q15 and then store the results in the destination buffer */ + in = *pIn++; + in = (in * 32768.0f); + in += in > 0 ? 0.5f : -0.5f; + *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); + +#else + + /* C = A * 32768 */ + /* convert from float to q15 and then store the results in the destination buffer */ + *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); + +#endif /* #ifdef ARM_MATH_ROUNDING */ + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of float_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q31.c index fa9a6e74f..4d77624c7 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q31.c @@ -1,200 +1,200 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_float_to_q31.c -* -* Description: Converts the elements of the floating-point vector to Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup float_to_x Convert 32-bit floating point value - */ - -/** - * @addtogroup float_to_x - * @{ - */ - -/** - * @brief Converts the elements of the floating-point vector to Q31 vector. - * @param[in] *pSrc points to the floating-point input vector - * @param[out] *pDst points to the Q31 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - *\par Description: - * \par - * The equation used for the conversion process is: - * - *
   
- * 	pDst[n] = (q31_t)(pSrc[n] * 2147483648);   0 <= n < blockSize.   
- * 
- * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated. - * - * \note In order to apply rounding, the library should be rebuilt with the ROUNDING macro - * defined in the preprocessor section of project options. - */ - - -void arm_float_to_q31( - float32_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - float32_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifdef ARM_MATH_ROUNDING - - float32_t in; - -#endif /* #ifdef ARM_MATH_ROUNDING */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - - /* C = A * 32768 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - -#else - - /* C = A * 2147483648 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - - /* C = A * 2147483648 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - -#else - - /* C = A * 2147483648 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - - /* C = A * 2147483648 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5f : -0.5f; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - -#else - - /* C = A * 2147483648 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of float_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_float_to_q31.c +* +* Description: Converts the elements of the floating-point vector to Q31 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @defgroup float_to_x Convert 32-bit floating point value + */ + +/** + * @addtogroup float_to_x + * @{ + */ + +/** + * @brief Converts the elements of the floating-point vector to Q31 vector. + * @param[in] *pSrc points to the floating-point input vector + * @param[out] *pDst points to the Q31 output vector + * @param[in] blockSize length of the input vector + * @return none. + * + *\par Description: + * \par + * The equation used for the conversion process is: + * + *
   
+ * 	pDst[n] = (q31_t)(pSrc[n] * 2147483648);   0 <= n < blockSize.   
+ * 
+ * Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated. + * + * \note In order to apply rounding, the library should be rebuilt with the ROUNDING macro + * defined in the preprocessor section of project options. + */ + + +void arm_float_to_q31( + float32_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + float32_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + +#ifdef ARM_MATH_ROUNDING + + float32_t in; + +#endif /* #ifdef ARM_MATH_ROUNDING */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + +#ifdef ARM_MATH_ROUNDING + + /* C = A * 32768 */ + /* convert from float to Q31 and then store the results in the destination buffer */ + in = *pIn++; + in = (in * 2147483648.0f); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = clip_q63_to_q31((q63_t) (in)); + + in = *pIn++; + in = (in * 2147483648.0f); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = clip_q63_to_q31((q63_t) (in)); + + in = *pIn++; + in = (in * 2147483648.0f); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = clip_q63_to_q31((q63_t) (in)); + + in = *pIn++; + in = (in * 2147483648.0f); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = clip_q63_to_q31((q63_t) (in)); + +#else + + /* C = A * 2147483648 */ + /* convert from float to Q31 and then store the results in the destination buffer */ + *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); + *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); + *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); + *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); + +#endif /* #ifdef ARM_MATH_ROUNDING */ + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + +#ifdef ARM_MATH_ROUNDING + + /* C = A * 2147483648 */ + /* convert from float to Q31 and then store the results in the destination buffer */ + in = *pIn++; + in = (in * 2147483648.0f); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = clip_q63_to_q31((q63_t) (in)); + +#else + + /* C = A * 2147483648 */ + /* convert from float to Q31 and then store the results in the destination buffer */ + *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); + +#endif /* #ifdef ARM_MATH_ROUNDING */ + + /* Decrement the loop counter */ + blkCnt--; + } + + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { + +#ifdef ARM_MATH_ROUNDING + + /* C = A * 2147483648 */ + /* convert from float to Q31 and then store the results in the destination buffer */ + in = *pIn++; + in = (in * 2147483648.0f); + in += in > 0 ? 0.5f : -0.5f; + *pDst++ = clip_q63_to_q31((q63_t) (in)); + +#else + + /* C = A * 2147483648 */ + /* convert from float to Q31 and then store the results in the destination buffer */ + *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); + +#endif /* #ifdef ARM_MATH_ROUNDING */ + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of float_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q7.c index 610ef3ae8..1a8a4a5a0 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_float_to_q7.c @@ -1,192 +1,192 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_float_to_q7.c -* -* Description: Converts the elements of the floating-point vector to Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup float_to_x - * @{ - */ - -/** - * @brief Converts the elements of the floating-point vector to Q7 vector. - * @param[in] *pSrc points to the floating-point input vector - * @param[out] *pDst points to the Q7 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - *\par Description: - * \par - * The equation used for the conversion process is: - *
   
- * 	pDst[n] = (q7_t)(pSrc[n] * 128);   0 <= n < blockSize.   
- * 
- * \par Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. - * \note - * In order to apply rounding, the library should be rebuilt with the ROUNDING macro - * defined in the preprocessor section of project options. - */ - - -void arm_float_to_q7( - float32_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - float32_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifdef ARM_MATH_ROUNDING - - float32_t in; - -#endif /* #ifdef ARM_MATH_ROUNDING */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 128); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); - - in = *pIn++; - in = (in * 128); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); - - in = *pIn++; - in = (in * 128); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); - - in = *pIn++; - in = (in * 128); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); - -#else - - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); - *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); - *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); - *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 128); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); - -#else - - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { -#ifdef ARM_MATH_ROUNDING - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 128.0f); - in += in > 0 ? 0.5f : -0.5f; - *pDst++ = (q7_t) (__SSAT((q31_t) (in), 8)); - -#else - - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - *pDst++ = (q7_t) __SSAT((q31_t) (*pIn++ * 128.0f), 8); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of float_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_float_to_q7.c +* +* Description: Converts the elements of the floating-point vector to Q7 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup float_to_x + * @{ + */ + +/** + * @brief Converts the elements of the floating-point vector to Q7 vector. + * @param[in] *pSrc points to the floating-point input vector + * @param[out] *pDst points to the Q7 output vector + * @param[in] blockSize length of the input vector + * @return none. + * + *\par Description: + * \par + * The equation used for the conversion process is: + *
   
+ * 	pDst[n] = (q7_t)(pSrc[n] * 128);   0 <= n < blockSize.   
+ * 
+ * \par Scaling and Overflow Behavior: + * \par + * The function uses saturating arithmetic. + * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. + * \note + * In order to apply rounding, the library should be rebuilt with the ROUNDING macro + * defined in the preprocessor section of project options. + */ + + +void arm_float_to_q7( + float32_t * pSrc, + q7_t * pDst, + uint32_t blockSize) +{ + float32_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + +#ifdef ARM_MATH_ROUNDING + + float32_t in; + +#endif /* #ifdef ARM_MATH_ROUNDING */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + +#ifdef ARM_MATH_ROUNDING + /* C = A * 128 */ + /* convert from float to q7 and then store the results in the destination buffer */ + in = *pIn++; + in = (in * 128); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); + + in = *pIn++; + in = (in * 128); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); + + in = *pIn++; + in = (in * 128); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); + + in = *pIn++; + in = (in * 128); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); + +#else + + /* C = A * 128 */ + /* convert from float to q7 and then store the results in the destination buffer */ + *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); + *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); + *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); + *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); + +#endif /* #ifdef ARM_MATH_ROUNDING */ + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + + while(blkCnt > 0u) + { + +#ifdef ARM_MATH_ROUNDING + /* C = A * 128 */ + /* convert from float to q7 and then store the results in the destination buffer */ + in = *pIn++; + in = (in * 128); + in += in > 0 ? 0.5 : -0.5; + *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); + +#else + + /* C = A * 128 */ + /* convert from float to q7 and then store the results in the destination buffer */ + *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); + +#endif /* #ifdef ARM_MATH_ROUNDING */ + + /* Decrement the loop counter */ + blkCnt--; + } + + +#else + + /* Run the below code for Cortex-M0 */ + + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + + while(blkCnt > 0u) + { +#ifdef ARM_MATH_ROUNDING + /* C = A * 128 */ + /* convert from float to q7 and then store the results in the destination buffer */ + in = *pIn++; + in = (in * 128.0f); + in += in > 0 ? 0.5f : -0.5f; + *pDst++ = (q7_t) (__SSAT((q31_t) (in), 8)); + +#else + + /* C = A * 128 */ + /* convert from float to q7 and then store the results in the destination buffer */ + *pDst++ = (q7_t) __SSAT((q31_t) (*pIn++ * 128.0f), 8); + +#endif /* #ifdef ARM_MATH_ROUNDING */ + + /* Decrement the loop counter */ + blkCnt--; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of float_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_float.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_float.c index 888379c2b..42aa0727c 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_float.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_float.c @@ -1,123 +1,123 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_q15_to_float.c -* -* Description: Converts the elements of the Q15 vector to floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup q15_to_x Convert 16-bit Integer value - */ - -/** - * @addtogroup q15_to_x - * @{ - */ - - - - -/** - * @brief Converts the elements of the Q15 vector to floating-point vector. - * @param[in] *pSrc points to the Q15 input vector - * @param[out] *pDst points to the floating-point output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
   
- * 	pDst[n] = (float32_t) pSrc[n] / 32768;   0 <= n < blockSize.   
- * 
- * - */ - - -void arm_q15_to_float( - q15_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - q15_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (float32_t) A / 32768 */ - /* convert from q15 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 32768.0f); - *pDst++ = ((float32_t) * pIn++ / 32768.0f); - *pDst++ = ((float32_t) * pIn++ / 32768.0f); - *pDst++ = ((float32_t) * pIn++ / 32768.0f); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (float32_t) A / 32768 */ - /* convert from q15 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 32768.0f); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of q15_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_q15_to_float.c +* +* Description: Converts the elements of the Q15 vector to floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @defgroup q15_to_x Convert 16-bit Integer value + */ + +/** + * @addtogroup q15_to_x + * @{ + */ + + + + +/** + * @brief Converts the elements of the Q15 vector to floating-point vector. + * @param[in] *pSrc points to the Q15 input vector + * @param[out] *pDst points to the floating-point output vector + * @param[in] blockSize length of the input vector + * @return none. + * + * \par Description: + * + * The equation used for the conversion process is: + * + *
   
+ * 	pDst[n] = (float32_t) pSrc[n] / 32768;   0 <= n < blockSize.   
+ * 
+ * + */ + + +void arm_q15_to_float( + q15_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + q15_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (float32_t) A / 32768 */ + /* convert from q15 to float and then store the results in the destination buffer */ + *pDst++ = ((float32_t) * pIn++ / 32768.0f); + *pDst++ = ((float32_t) * pIn++ / 32768.0f); + *pDst++ = ((float32_t) * pIn++ / 32768.0f); + *pDst++ = ((float32_t) * pIn++ / 32768.0f); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (float32_t) A / 32768 */ + /* convert from q15 to float and then store the results in the destination buffer */ + *pDst++ = ((float32_t) * pIn++ / 32768.0f); + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of q15_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_q31.c index c8902dec8..16043e058 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_q31.c @@ -1,116 +1,116 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_q15_to_q31.c -* -* Description: Converts the elements of the Q15 vector to Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q15_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q15 vector to Q31 vector. - * @param[in] *pSrc points to the Q15 input vector - * @param[out] *pDst points to the Q31 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
   
- * 	pDst[n] = (q31_t) pSrc[n] << 16;   0 <= n < blockSize.   
- * 
- * - */ - - -void arm_q15_to_q31( - q15_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q15_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q31_t)A << 16 */ - /* convert from q15 to q31 and then store the results in the destination buffer */ - *pDst++ = (q31_t) * pIn++ << 16; - *pDst++ = (q31_t) * pIn++ << 16; - *pDst++ = (q31_t) * pIn++ << 16; - *pDst++ = (q31_t) * pIn++ << 16; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q31_t)A << 16 */ - /* convert from q15 to q31 and then store the results in the destination buffer */ - *pDst++ = (q31_t) * pIn++ << 16; - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q15_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_q15_to_q31.c +* +* Description: Converts the elements of the Q15 vector to Q31 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup q15_to_x + * @{ + */ + +/** + * @brief Converts the elements of the Q15 vector to Q31 vector. + * @param[in] *pSrc points to the Q15 input vector + * @param[out] *pDst points to the Q31 output vector + * @param[in] blockSize length of the input vector + * @return none. + * + * \par Description: + * + * The equation used for the conversion process is: + * + *
   
+ * 	pDst[n] = (q31_t) pSrc[n] << 16;   0 <= n < blockSize.   
+ * 
+ * + */ + + +void arm_q15_to_q31( + q15_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q15_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (q31_t)A << 16 */ + /* convert from q15 to q31 and then store the results in the destination buffer */ + *pDst++ = (q31_t) * pIn++ << 16; + *pDst++ = (q31_t) * pIn++ << 16; + *pDst++ = (q31_t) * pIn++ << 16; + *pDst++ = (q31_t) * pIn++ << 16; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (q31_t)A << 16 */ + /* convert from q15 to q31 and then store the results in the destination buffer */ + *pDst++ = (q31_t) * pIn++ << 16; + + /* Decrement the loop counter */ + blkCnt--; + } + +} + +/** + * @} end of q15_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_q7.c index bfd8da823..0ca22df2c 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q15_to_q7.c @@ -1,117 +1,117 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_q15_to_q7.c -* -* Description: Converts the elements of the Q15 vector to Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q15_to_x - * @{ - */ - - -/** - * @brief Converts the elements of the Q15 vector to Q7 vector. - * @param[in] *pSrc points to the Q15 input vector - * @param[out] *pDst points to the Q7 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
   
- * 	pDst[n] = (q7_t) pSrc[n] >> 8;   0 <= n < blockSize.   
- * 
- * - */ - - -void arm_q15_to_q7( - q15_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - q15_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q7_t) A >> 8 */ - /* convert from q15 to q7 and then store the results in the destination buffer */ - *pDst++ = (q7_t) (*pIn++ >> 8); - *pDst++ = (q7_t) (*pIn++ >> 8); - *pDst++ = (q7_t) (*pIn++ >> 8); - *pDst++ = (q7_t) (*pIn++ >> 8); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q7_t) A >> 8 */ - /* convert from q15 to q7 and then store the results in the destination buffer */ - *pDst++ = (q7_t) (*pIn++ >> 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q15_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_q15_to_q7.c +* +* Description: Converts the elements of the Q15 vector to Q7 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup q15_to_x + * @{ + */ + + +/** + * @brief Converts the elements of the Q15 vector to Q7 vector. + * @param[in] *pSrc points to the Q15 input vector + * @param[out] *pDst points to the Q7 output vector + * @param[in] blockSize length of the input vector + * @return none. + * + * \par Description: + * + * The equation used for the conversion process is: + * + *
   
+ * 	pDst[n] = (q7_t) pSrc[n] >> 8;   0 <= n < blockSize.   
+ * 
+ * + */ + + +void arm_q15_to_q7( + q15_t * pSrc, + q7_t * pDst, + uint32_t blockSize) +{ + q15_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (q7_t) A >> 8 */ + /* convert from q15 to q7 and then store the results in the destination buffer */ + *pDst++ = (q7_t) (*pIn++ >> 8); + *pDst++ = (q7_t) (*pIn++ >> 8); + *pDst++ = (q7_t) (*pIn++ >> 8); + *pDst++ = (q7_t) (*pIn++ >> 8); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (q7_t) A >> 8 */ + /* convert from q15 to q7 and then store the results in the destination buffer */ + *pDst++ = (q7_t) (*pIn++ >> 8); + + /* Decrement the loop counter */ + blkCnt--; + } + +} + +/** + * @} end of q15_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_float.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_float.c index 3475044e8..48a76946a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_float.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_float.c @@ -1,120 +1,120 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_q31_to_float.c -* -* Description: Converts the elements of the Q31 vector to floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup q31_to_x Convert 32-bit Integer value - */ - -/** - * @addtogroup q31_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q31 vector to floating-point vector. - * @param[in] *pSrc points to the Q31 input vector - * @param[out] *pDst points to the floating-point output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
   
- * 	pDst[n] = (float32_t) pSrc[n] / 2147483648;   0 <= n < blockSize.   
- * 
- * - */ - - -void arm_q31_to_float( - q31_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - q31_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (float32_t) A / 2147483648 */ - /* convert from q31 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); - *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); - *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); - *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (float32_t) A / 2147483648 */ - /* convert from q31 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of q31_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_q31_to_float.c +* +* Description: Converts the elements of the Q31 vector to floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @defgroup q31_to_x Convert 32-bit Integer value + */ + +/** + * @addtogroup q31_to_x + * @{ + */ + +/** + * @brief Converts the elements of the Q31 vector to floating-point vector. + * @param[in] *pSrc points to the Q31 input vector + * @param[out] *pDst points to the floating-point output vector + * @param[in] blockSize length of the input vector + * @return none. + * + * \par Description: + * + * The equation used for the conversion process is: + * + *
   
+ * 	pDst[n] = (float32_t) pSrc[n] / 2147483648;   0 <= n < blockSize.   
+ * 
+ * + */ + + +void arm_q31_to_float( + q31_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + q31_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (float32_t) A / 2147483648 */ + /* convert from q31 to float and then store the results in the destination buffer */ + *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); + *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); + *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); + *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (float32_t) A / 2147483648 */ + /* convert from q31 to float and then store the results in the destination buffer */ + *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of q31_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_q15.c index 54fc589e4..dafc1d888 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_q15.c @@ -1,116 +1,116 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_q31_to_q15.c -* -* Description: Converts the elements of the Q31 vector to Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q31_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q31 vector to Q15 vector. - * @param[in] *pSrc points to the Q31 input vector - * @param[out] *pDst points to the Q15 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
   
- * 	pDst[n] = (q15_t) pSrc[n] >> 16;   0 <= n < blockSize.   
- * 
- * - */ - - -void arm_q31_to_q15( - q31_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q31_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q15_t) A >> 16 */ - /* convert from q31 to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) (*pIn++ >> 16); - *pDst++ = (q15_t) (*pIn++ >> 16); - *pDst++ = (q15_t) (*pIn++ >> 16); - *pDst++ = (q15_t) (*pIn++ >> 16); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q15_t) A >> 16 */ - /* convert from q31 to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) (*pIn++ >> 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q31_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_q31_to_q15.c +* +* Description: Converts the elements of the Q31 vector to Q15 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup q31_to_x + * @{ + */ + +/** + * @brief Converts the elements of the Q31 vector to Q15 vector. + * @param[in] *pSrc points to the Q31 input vector + * @param[out] *pDst points to the Q15 output vector + * @param[in] blockSize length of the input vector + * @return none. + * + * \par Description: + * + * The equation used for the conversion process is: + * + *
   
+ * 	pDst[n] = (q15_t) pSrc[n] >> 16;   0 <= n < blockSize.   
+ * 
+ * + */ + + +void arm_q31_to_q15( + q31_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + q31_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (q15_t) A >> 16 */ + /* convert from q31 to q15 and then store the results in the destination buffer */ + *pDst++ = (q15_t) (*pIn++ >> 16); + *pDst++ = (q15_t) (*pIn++ >> 16); + *pDst++ = (q15_t) (*pIn++ >> 16); + *pDst++ = (q15_t) (*pIn++ >> 16); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (q15_t) A >> 16 */ + /* convert from q31 to q15 and then store the results in the destination buffer */ + *pDst++ = (q15_t) (*pIn++ >> 16); + + /* Decrement the loop counter */ + blkCnt--; + } + +} + +/** + * @} end of q31_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_q7.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_q7.c index 1e6bf4761..c7aedb04f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_q7.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q31_to_q7.c @@ -1,116 +1,116 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_q31_to_q7.c -* -* Description: Converts the elements of the Q31 vector to Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q31_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q31 vector to Q7 vector. - * @param[in] *pSrc points to the Q31 input vector - * @param[out] *pDst points to the Q7 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
   
- * 	pDst[n] = (q7_t) pSrc[n] >> 24;   0 <= n < blockSize.    
- * 
- * - */ - - -void arm_q31_to_q7( - q31_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - q31_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q7_t) A >> 24 */ - /* convert from q31 to q7 and then store the results in the destination buffer */ - *pDst++ = (q7_t) (*pIn++ >> 24); - *pDst++ = (q7_t) (*pIn++ >> 24); - *pDst++ = (q7_t) (*pIn++ >> 24); - *pDst++ = (q7_t) (*pIn++ >> 24); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q7_t) A >> 24 */ - /* convert from q31 to q7 and then store the results in the destination buffer */ - *pDst++ = (q7_t) (*pIn++ >> 24); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q31_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_q31_to_q7.c +* +* Description: Converts the elements of the Q31 vector to Q7 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup q31_to_x + * @{ + */ + +/** + * @brief Converts the elements of the Q31 vector to Q7 vector. + * @param[in] *pSrc points to the Q31 input vector + * @param[out] *pDst points to the Q7 output vector + * @param[in] blockSize length of the input vector + * @return none. + * + * \par Description: + * + * The equation used for the conversion process is: + * + *
   
+ * 	pDst[n] = (q7_t) pSrc[n] >> 24;   0 <= n < blockSize.    
+ * 
+ * + */ + + +void arm_q31_to_q7( + q31_t * pSrc, + q7_t * pDst, + uint32_t blockSize) +{ + q31_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (q7_t) A >> 24 */ + /* convert from q31 to q7 and then store the results in the destination buffer */ + *pDst++ = (q7_t) (*pIn++ >> 24); + *pDst++ = (q7_t) (*pIn++ >> 24); + *pDst++ = (q7_t) (*pIn++ >> 24); + *pDst++ = (q7_t) (*pIn++ >> 24); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (q7_t) A >> 24 */ + /* convert from q31 to q7 and then store the results in the destination buffer */ + *pDst++ = (q7_t) (*pIn++ >> 24); + + /* Decrement the loop counter */ + blkCnt--; + } + +} + +/** + * @} end of q31_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_float.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_float.c index 7a2d61208..866996925 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_float.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_float.c @@ -1,120 +1,120 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_q7_to_float.c -* -* Description: Converts the elements of the Q7 vector to floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup q7_to_x Convert 8-bit Integer value - */ - -/** - * @addtogroup q7_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q7 vector to floating-point vector. - * @param[in] *pSrc points to the Q7 input vector - * @param[out] *pDst points to the floating-point output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
   
- * 	pDst[n] = (float32_t) pSrc[n] / 128;   0 <= n < blockSize.   
- * 
- * - */ - - -void arm_q7_to_float( - q7_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - q7_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (float32_t) A / 128 */ - /* convert from q7 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 128.0f); - *pDst++ = ((float32_t) * pIn++ / 128.0f); - *pDst++ = ((float32_t) * pIn++ / 128.0f); - *pDst++ = ((float32_t) * pIn++ / 128.0f); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (float32_t) A / 128 */ - /* convert from q7 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 128.0f); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of q7_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_q7_to_float.c +* +* Description: Converts the elements of the Q7 vector to floating-point vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @defgroup q7_to_x Convert 8-bit Integer value + */ + +/** + * @addtogroup q7_to_x + * @{ + */ + +/** + * @brief Converts the elements of the Q7 vector to floating-point vector. + * @param[in] *pSrc points to the Q7 input vector + * @param[out] *pDst points to the floating-point output vector + * @param[in] blockSize length of the input vector + * @return none. + * + * \par Description: + * + * The equation used for the conversion process is: + * + *
   
+ * 	pDst[n] = (float32_t) pSrc[n] / 128;   0 <= n < blockSize.   
+ * 
+ * + */ + + +void arm_q7_to_float( + q7_t * pSrc, + float32_t * pDst, + uint32_t blockSize) +{ + q7_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (float32_t) A / 128 */ + /* convert from q7 to float and then store the results in the destination buffer */ + *pDst++ = ((float32_t) * pIn++ / 128.0f); + *pDst++ = ((float32_t) * pIn++ / 128.0f); + *pDst++ = ((float32_t) * pIn++ / 128.0f); + *pDst++ = ((float32_t) * pIn++ / 128.0f); + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (float32_t) A / 128 */ + /* convert from q7 to float and then store the results in the destination buffer */ + *pDst++ = ((float32_t) * pIn++ / 128.0f); + + /* Decrement the loop counter */ + blkCnt--; + } +} + +/** + * @} end of q7_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_q15.c index 4cba666fe..9d3b29283 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_q15.c @@ -1,119 +1,119 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_q7_to_q15.c -* -* Description: Converts the elements of the Q7 vector to Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q7_to_x - * @{ - */ - - - - -/** - * @brief Converts the elements of the Q7 vector to Q15 vector. - * @param[in] *pSrc points to the Q7 input vector - * @param[out] *pDst points to the Q15 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
   
- * 	pDst[n] = (q15_t) pSrc[n] << 8;   0 <= n < blockSize.   
- * 
- * - */ - - -void arm_q7_to_q15( - q7_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q7_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q15_t) A << 8 */ - /* convert from q7 to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) * pIn++ << 8; - *pDst++ = (q15_t) * pIn++ << 8; - *pDst++ = (q15_t) * pIn++ << 8; - *pDst++ = (q15_t) * pIn++ << 8; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q15_t) A << 8 */ - /* convert from q7 to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) * pIn++ << 8; - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q7_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_q7_to_q15.c +* +* Description: Converts the elements of the Q7 vector to Q15 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup q7_to_x + * @{ + */ + + + + +/** + * @brief Converts the elements of the Q7 vector to Q15 vector. + * @param[in] *pSrc points to the Q7 input vector + * @param[out] *pDst points to the Q15 output vector + * @param[in] blockSize length of the input vector + * @return none. + * + * \par Description: + * + * The equation used for the conversion process is: + * + *
   
+ * 	pDst[n] = (q15_t) pSrc[n] << 8;   0 <= n < blockSize.   
+ * 
+ * + */ + + +void arm_q7_to_q15( + q7_t * pSrc, + q15_t * pDst, + uint32_t blockSize) +{ + q7_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (q15_t) A << 8 */ + /* convert from q7 to q15 and then store the results in the destination buffer */ + *pDst++ = (q15_t) * pIn++ << 8; + *pDst++ = (q15_t) * pIn++ << 8; + *pDst++ = (q15_t) * pIn++ << 8; + *pDst++ = (q15_t) * pIn++ << 8; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (q15_t) A << 8 */ + /* convert from q7 to q15 and then store the results in the destination buffer */ + *pDst++ = (q15_t) * pIn++ << 8; + + /* Decrement the loop counter */ + blkCnt--; + } + +} + +/** + * @} end of q7_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_q31.c index 6f425935e..11f265619 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/SupportFunctions/arm_q7_to_q31.c @@ -1,116 +1,116 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_q7_to_q31.c -* -* Description: Converts the elements of the Q7 vector to Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q7_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q7 vector to Q31 vector. - * @param[in] *pSrc points to the Q7 input vector - * @param[out] *pDst points to the Q31 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
   
- * 	pDst[n] = (q31_t) pSrc[n] << 24;   0 <= n < blockSize.  
- * 
- * - */ - - -void arm_q7_to_q31( - q7_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q7_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q31_t) A << 24 */ - /* convert from q7 to q31 and then store the results in the destination buffer */ - *pDst++ = (q31_t) * pIn++ << 24; - *pDst++ = (q31_t) * pIn++ << 24; - *pDst++ = (q31_t) * pIn++ << 24; - *pDst++ = (q31_t) * pIn++ << 24; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q31_t) A << 24 */ - /* convert from q7 to q31 and then store the results in the destination buffer */ - *pDst++ = (q31_t) * pIn++ << 24; - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q7_to_x group - */ +/* ---------------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_q7_to_q31.c +* +* Description: Converts the elements of the Q7 vector to Q31 vector. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* ---------------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupSupport + */ + +/** + * @addtogroup q7_to_x + * @{ + */ + +/** + * @brief Converts the elements of the Q7 vector to Q31 vector. + * @param[in] *pSrc points to the Q7 input vector + * @param[out] *pDst points to the Q31 output vector + * @param[in] blockSize length of the input vector + * @return none. + * + * \par Description: + * + * The equation used for the conversion process is: + * + *
   
+ * 	pDst[n] = (q31_t) pSrc[n] << 24;   0 <= n < blockSize.  
+ * 
+ * + */ + + +void arm_q7_to_q31( + q7_t * pSrc, + q31_t * pDst, + uint32_t blockSize) +{ + q7_t *pIn = pSrc; /* Src pointer */ + uint32_t blkCnt; /* loop counter */ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /*loop Unrolling */ + blkCnt = blockSize >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + while(blkCnt > 0u) + { + /* C = (q31_t) A << 24 */ + /* convert from q7 to q31 and then store the results in the destination buffer */ + *pDst++ = (q31_t) * pIn++ << 24; + *pDst++ = (q31_t) * pIn++ << 24; + *pDst++ = (q31_t) * pIn++ << 24; + *pDst++ = (q31_t) * pIn++ << 24; + + /* Decrement the loop counter */ + blkCnt--; + } + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + blkCnt = blockSize % 0x4u; + +#else + + /* Run the below code for Cortex-M0 */ + + /* Loop over blockSize number of values */ + blkCnt = blockSize; + +#endif /* #ifndef ARM_MATH_CM0 */ + + while(blkCnt > 0u) + { + /* C = (q31_t) A << 24 */ + /* convert from q7 to q31 and then store the results in the destination buffer */ + *pDst++ = (q31_t) * pIn++ << 24; + + /* Decrement the loop counter */ + blkCnt--; + } + +} + +/** + * @} end of q7_to_x group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_f32.c index 24099506d..7dfe4c349 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_f32.c @@ -1,1236 +1,1236 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_f32.c -* -* Description: Radix-4 Decimation in Frequency CFFT & CIFFT Floating point processing function -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @defgroup CFFT_CIFFT Complex FFT Functions - * - * \par - * Complex Fast Fourier Transform(CFFT) and Complex Inverse Fast Fourier Transform(CIFFT) is an efficient algorithm to compute Discrete Fourier Transform(DFT) and Inverse Discrete Fourier Transform(IDFT). - * Computational complexity of CFFT reduces drastically when compared to DFT. - * \par - * This set of functions implements CFFT/CIFFT - * for Q15, Q31, and floating-point data types. The functions operates on in-place buffer which uses same buffer for input and output. - * Complex input is stored in input buffer in an interleaved fashion. - * - * \par - * The functions operate on blocks of input and output data and each call to the function processes - * 2*fftLen samples through the transform. pSrc points to In-place arrays containing 2*fftLen values. - * \par - * The pSrc points to the array of in-place buffer of size 2*fftLen and inputs and outputs are stored in an interleaved fashion as shown below. - *
 {real[0], imag[0], real[1], imag[1],..} 
- * - * \par Lengths supported by the transform: - * \par - * Internally, the function utilize a radix-4 decimation in frequency(DIF) algorithm - * and the size of the FFT supported are of the lengths [16, 64, 256, 1024]. - * - * - * \par Algorithm: - * - * Complex Fast Fourier Transform: - * \par - * Input real and imaginary data: - *
   
- * x(n) = xa + j * ya   
- * x(n+N/4 ) = xb + j * yb   
- * x(n+N/2 ) = xc + j * yc   
- * x(n+3N 4) = xd + j * yd   
- * 
- * where N is length of FFT - * \par - * Output real and imaginary data: - *
   
- * X(4r) = xa'+ j * ya'   
- * X(4r+1) = xb'+ j * yb'   
- * X(4r+2) = xc'+ j * yc'   
- * X(4r+3) = xd'+ j * yd'   
- * 
- * \par - * Twiddle factors for radix-4 FFT: - *
   
- * Wn = co1 + j * (- si1)   
- * W2n = co2 + j * (- si2)   
- * W3n = co3 + j * (- si3)   
- * 
- * - * \par - * \image html CFFT.gif "Radix-4 Decimation-in Frequency Complex Fast Fourier Transform" - * - * \par - * Output from Radix-4 CFFT Results in Digit reversal order. Interchange middle two branches of every butterfly results in Bit reversed output. - * \par - * Butterfly CFFT equations: - *
   
- * xa' = xa + xb + xc + xd   
- * ya' = ya + yb + yc + yd   
- * xc' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1)   
- * yc' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1)   
- * xb' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2)   
- * yb' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2)   
- * xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3)   
- * yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3)   
- * 
- * - * - * Complex Inverse Fast Fourier Transform: - * \par - * CIFFT uses same twiddle factor table as CFFT with modifications in the design equation as shown below. - * - * \par - * Modified Butterfly CIFFT equations: - *
   
- * xa' = xa + xb + xc + xd   
- * ya' = ya + yb + yc + yd   
- * xc' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1)   
- * yc' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1)   
- * xb' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2)   
- * yb' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2)   
- * xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3)   
- * yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3)   
- * 
- * - * \par Instance Structure - * A separate instance structure must be defined for each Instance but the twiddle factors and bit reversal tables can be reused. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Initializes twiddle factor table and bit reversal table pointers - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Manually initialize the instance structure as follows: - *
   
- *arm_cfft_radix4_instance_f32 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor, onebyfftLen};   
- *arm_cfft_radix4_instance_q31 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor};   
- *arm_cfft_radix4_instance_q15 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor};   
- * 
- * \par - * where fftLen length of CFFT/CIFFT; ifftFlag Flag for selection of CFFT or CIFFT(Set ifftFlag to calculate CIFFT otherwise calculates CFFT); - * bitReverseFlag Flag for selection of output order(Set bitReverseFlag to output in normal order otherwise output in bit reversed order); - * pTwiddlepoints to array of twiddle coefficients; pBitRevTable points to the array of bit reversal table. - * twidCoefModifier modifier for twiddle factor table which supports all FFT lengths with same table; - * pBitRevTable modifier for bit reversal table which supports all FFT lengths with same table. - * onebyfftLen value of 1/fftLen to calculate CIFFT; - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the CFFT/CIFFT function. - * Refer to the function specific documentation below for usage guidelines. - */ - - -/** - * @addtogroup CFFT_CIFFT - * @{ - */ - -/** - * @details - * @brief Processing function for the floating-point CFFT/CIFFT. - * @param[in] *S points to an instance of the floating-point CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer of size 2*fftLen. Processing occurs in-place. - * @return none. - */ - -void arm_cfft_radix4_f32( - const arm_cfft_radix4_instance_f32 * S, - float32_t * pSrc) -{ - - if(S->ifftFlag == 1u) - { - /* Complex IFFT radix-4 */ - arm_radix4_butterfly_inverse_f32(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier, S->onebyfftLen); - } - else - { - /* Complex FFT radix-4 */ - arm_radix4_butterfly_f32(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - - if(S->bitReverseFlag == 1u) - { - /* Bit Reversal */ - arm_bitreversal_f32(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); - } - -} - - -/** - * @} end of CFFT_CIFFT group - */ - - - -/* ---------------------------------------------------------------------- -** Internal helper function used by the FFTs -** ------------------------------------------------------------------- */ - -/* - * @brief Core function for the floating-point CFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to the twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_radix4_butterfly_f32( - float32_t * pSrc, - uint16_t fftLen, - float32_t * pCoef, - uint16_t twidCoefModifier) -{ - - float32_t co1, co2, co3, si1, si2, si3; - float32_t t1, t2, r1, r2, s1, s2; - uint32_t ia1, ia2, ia3; - uint32_t i0, i1, i2, i3; - uint32_t n1, n2, j, k; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - i0 = 0u; - ia1 = 0u; - - j = n2; - - /* Calculation of first stage */ - do - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - - /* xa + xc */ - r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; - - /* xa - xc */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = r1 + t1; - - /* (xa + xc) - (xb + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = s1 + t2; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* yb - yd */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* xb - xd */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (r1 * co2) + (s1 * si2); - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (s1 * co2) - (r1 * si2); - - /* (xa - xc) + (yb - yd) */ - r1 = r2 + t1; - - /* (xa - xc) - (yb - yd) */ - r2 = r2 - t1; - - /* (ya - yc) - (xb - xd) */ - s1 = s2 - t2; - - /* (ya - yc) + (xb - xd) */ - s2 = s2 + t2; - - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (r1 * co1) + (s1 * si1); - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (s1 * co1) - (r1 * si1); - - /* index calculation for the coefficients */ - ia3 = ia2 + ia1; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (r2 * co3) + (s2 * si3); - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (s2 * co3) - (r2 * si3); - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } - while(--j); - - twidCoefModifier <<= 2u; - - /* Calculation of second stage to excluding last stage */ - for (k = fftLen / 4; k > 4u; k >>= 2u) - { - /* Initializations for the first stage */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - /* Calculation of first stage */ - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* xa + xc */ - r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; - - /* xa - xc */ - r2 = pSrc[(2u * i0)] - pSrc[(2u * i2)]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = r1 + t1; - - /* xa + xc -(xb + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = s1 + t2; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb - yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* (xb - xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (r1 * co2) + (s1 * si2); - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (s1 * co2) - (r1 * si2); - - /* (xa - xc) + (yb - yd) */ - r1 = r2 + t1; - - /* (xa - xc) - (yb - yd) */ - r2 = r2 - t1; - - /* (ya - yc) - (xb - xd) */ - s1 = s2 - t2; - - /* (ya - yc) + (xb - xd) */ - s2 = s2 + t2; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (r1 * co1) + (s1 * si1); - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (s1 * co1) - (r1 * si1); - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (r2 * co3) + (s2 * si3); - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (s2 * co3) - (r2 * si3); - } - } - twidCoefModifier <<= 2u; - } - - /* Initializations of last stage */ - n1 = n2; - n2 >>= 2u; - - /* Calculations of last stage */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - - /* xa + xb */ - r1 = pSrc[2u * i0] + pSrc[2u * i2]; - - /* xa - xb */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xc + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = r1 + t1; - - /* (xa + xb) - (xc + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = s1 + t2; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb-yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* (xb-xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = r1; - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = s1; - - /* (xa+yb-xc-yd) */ - r1 = r2 + t1; - - /* (xa-yb-xc+yd) */ - r2 = r2 - t1; - - /* (ya-xb-yc+xd) */ - s1 = s2 - t2; - - /* (ya+xb-yc-xd) */ - s2 = s2 + t2; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = r1; - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = s1; - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = r2; - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = s2; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initializations for the fft calculation */ - n2 = fftLen; - n1 = n2; - for (k = fftLen; k > 1u; k >>= 2u) - { - /* Initializations for the fft calculation */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - /* FFT Calculation */ - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* xa + xc */ - r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; - - /* xa - xc */ - r2 = pSrc[(2u * i0)] - pSrc[(2u * i2)]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = r1 + t1; - - /* xa + xc -(xb + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = s1 + t2; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb - yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* (xb - xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (r1 * co2) + (s1 * si2); - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (s1 * co2) - (r1 * si2); - - /* (xa - xc) + (yb - yd) */ - r1 = r2 + t1; - - /* (xa - xc) - (yb - yd) */ - r2 = r2 - t1; - - /* (ya - yc) - (xb - xd) */ - s1 = s2 - t2; - - /* (ya - yc) + (xb - xd) */ - s2 = s2 + t2; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (r1 * co1) + (s1 * si1); - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (s1 * co1) - (r1 * si1); - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (r2 * co3) + (s2 * si3); - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (s2 * co3) - (r2 * si3); - } - } - twidCoefModifier <<= 2u; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/* - * @brief Core function for the floating-point CIFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @param[in] onebyfftLen value of 1/fftLen. - * @return none. - */ - -void arm_radix4_butterfly_inverse_f32( - float32_t * pSrc, - uint16_t fftLen, - float32_t * pCoef, - uint16_t twidCoefModifier, - float32_t onebyfftLen) -{ - float32_t co1, co2, co3, si1, si2, si3; - float32_t t1, t2, r1, r2, s1, s2; - uint32_t ia1, ia2, ia3; - uint32_t i0, i1, i2, i3; - uint32_t n1, n2, j, k; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - i0 = 0u; - ia1 = 0u; - - j = n2; - - /* Calculation of first stage */ - do - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; - - /* xa - xc */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = r1 + t1; - - /* (xa + xc) - (xb + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = s1 + t2; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* yb - yd */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* xb - xd */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (r1 * co2) - (s1 * si2); - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (s1 * co2) + (r1 * si2); - - /* (xa - xc) - (yb - yd) */ - r1 = r2 - t1; - - /* (xa - xc) + (yb - yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb - xd) */ - s1 = s2 + t2; - - /* (ya - yc) - (xb - xd) */ - s2 = s2 - t2; - - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (r1 * co1) - (s1 * si1); - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (s1 * co1) + (r1 * si1); - - /* index calculation for the coefficients */ - ia3 = ia2 + ia1; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (r2 * co3) - (s2 * si3); - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (s2 * co3) + (r2 * si3); - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } - while(--j); - - twidCoefModifier <<= 2u; - - /* Calculation of second stage to excluding last stage */ - for (k = fftLen / 4; k > 4u; k >>= 2u) - { - /* Initializations for the first stage */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - /* Calculation of first stage */ - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* xa + xc */ - r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; - - /* xa - xc */ - r2 = pSrc[(2u * i0)] - pSrc[(2u * i2)]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = r1 + t1; - - /* xa + xc -(xb + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = s1 + t2; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb - yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* (xb - xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (r1 * co2) - (s1 * si2); - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (s1 * co2) + (r1 * si2); - - /* (xa - xc) - (yb - yd) */ - r1 = r2 - t1; - - /* (xa - xc) + (yb - yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb - xd) */ - s1 = s2 + t2; - - /* (ya - yc) - (xb - xd) */ - s2 = s2 - t2; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (r1 * co1) - (s1 * si1); - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (s1 * co1) + (r1 * si1); - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (r2 * co3) - (s2 * si3); - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (s2 * co3) + (r2 * si3); - } - } - twidCoefModifier <<= 2u; - } - - /* Initializations of last stage */ - n1 = n2; - n2 >>= 2u; - - /* Calculations of last stage */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = pSrc[2u * i0] + pSrc[2u * i2]; - - /* xa - xc */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xc + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1) * onebyfftLen; - - /* (xa + xb) - (xc + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2) * onebyfftLen; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb-yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* (xb-xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = r1 * onebyfftLen; - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = s1 * onebyfftLen; - - - /* (xa - xc) - (yb-yd) */ - r1 = r2 - t1; - - /* (xa - xc) + (yb-yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb-xd) */ - s1 = s2 + t2; - - /* (ya - yc) - (xb-xd) */ - s2 = s2 - t2; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = r1 * onebyfftLen; - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = s1 * onebyfftLen; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = r2 * onebyfftLen; - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = s2 * onebyfftLen; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* Calculation of first stage */ - for (k = fftLen; k > 4u; k >>= 2u) - { - /* Initializations for the first stage */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - /* Calculation of first stage */ - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* xa + xc */ - r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; - - /* xa - xc */ - r2 = pSrc[(2u * i0)] - pSrc[(2u * i2)]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = r1 + t1; - - /* xa + xc -(xb + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = s1 + t2; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb - yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* (xb - xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (r1 * co2) - (s1 * si2); - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (s1 * co2) + (r1 * si2); - - /* (xa - xc) - (yb - yd) */ - r1 = r2 - t1; - - /* (xa - xc) + (yb - yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb - xd) */ - s1 = s2 + t2; - - /* (ya - yc) - (xb - xd) */ - s2 = s2 - t2; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (r1 * co1) - (s1 * si1); - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (s1 * co1) + (r1 * si1); - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (r2 * co3) - (s2 * si3); - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (s2 * co3) + (r2 * si3); - } - } - twidCoefModifier <<= 2u; - } - /* Initializations of last stage */ - n1 = n2; - n2 >>= 2u; - - /* Calculations of last stage */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = pSrc[2u * i0] + pSrc[2u * i2]; - - /* xa - xc */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xc + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1) * onebyfftLen; - - /* (xa + xb) - (xc + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2) * onebyfftLen; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb-yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* (xb-xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = r1 * onebyfftLen; - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = s1 * onebyfftLen; - - - /* (xa - xc) - (yb-yd) */ - r1 = r2 - t1; - - /* (xa - xc) + (yb-yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb-xd) */ - s1 = s2 + t2; - - /* (ya - yc) - (xb-xd) */ - s2 = s2 - t2; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = r1 * onebyfftLen; - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = s1 * onebyfftLen; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = r2 * onebyfftLen; - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = s2 * onebyfftLen; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/* - * @brief In-place bit reversal function. - * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. - * @param[in] fftSize length of the FFT. - * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table. - * @param[in] *pBitRevTab points to the bit reversal table. - * @return none. - */ - -void arm_bitreversal_f32( - float32_t * pSrc, - uint16_t fftSize, - uint16_t bitRevFactor, - uint16_t * pBitRevTab) -{ - uint16_t fftLenBy2, fftLenBy2p1; - uint16_t i, j; - float32_t in; - - /* Initializations */ - j = 0u; - fftLenBy2 = fftSize >> 1u; - fftLenBy2p1 = (fftSize >> 1u) + 1u; - - /* Bit Reversal Implementation */ - for (i = 0u; i <= (fftLenBy2 - 2u); i += 2u) - { - if(i < j) - { - /* pSrc[i] <-> pSrc[j]; */ - in = pSrc[2u * i]; - pSrc[2u * i] = pSrc[2u * j]; - pSrc[2u * j] = in; - - /* pSrc[i+1u] <-> pSrc[j+1u] */ - in = pSrc[(2u * i) + 1u]; - pSrc[(2u * i) + 1u] = pSrc[(2u * j) + 1u]; - pSrc[(2u * j) + 1u] = in; - - /* pSrc[i+fftLenBy2p1] <-> pSrc[j+fftLenBy2p1] */ - in = pSrc[2u * (i + fftLenBy2p1)]; - pSrc[2u * (i + fftLenBy2p1)] = pSrc[2u * (j + fftLenBy2p1)]; - pSrc[2u * (j + fftLenBy2p1)] = in; - - /* pSrc[i+fftLenBy2p1+1u] <-> pSrc[j+fftLenBy2p1+1u] */ - in = pSrc[(2u * (i + fftLenBy2p1)) + 1u]; - pSrc[(2u * (i + fftLenBy2p1)) + 1u] = - pSrc[(2u * (j + fftLenBy2p1)) + 1u]; - pSrc[(2u * (j + fftLenBy2p1)) + 1u] = in; - - } - - /* pSrc[i+1u] <-> pSrc[j+1u] */ - in = pSrc[2u * (i + 1u)]; - pSrc[2u * (i + 1u)] = pSrc[2u * (j + fftLenBy2)]; - pSrc[2u * (j + fftLenBy2)] = in; - - /* pSrc[i+2u] <-> pSrc[j+2u] */ - in = pSrc[(2u * (i + 1u)) + 1u]; - pSrc[(2u * (i + 1u)) + 1u] = pSrc[(2u * (j + fftLenBy2)) + 1u]; - pSrc[(2u * (j + fftLenBy2)) + 1u] = in; - - /* Reading the index for the bit reversal */ - j = *pBitRevTab; - - /* Updating the bit reversal index depending on the fft length */ - pBitRevTab += bitRevFactor; - } -} +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_cfft_radix4_f32.c +* +* Description: Radix-4 Decimation in Frequency CFFT & CIFFT Floating point processing function +* +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @defgroup CFFT_CIFFT Complex FFT Functions + * + * \par + * Complex Fast Fourier Transform(CFFT) and Complex Inverse Fast Fourier Transform(CIFFT) is an efficient algorithm to compute Discrete Fourier Transform(DFT) and Inverse Discrete Fourier Transform(IDFT). + * Computational complexity of CFFT reduces drastically when compared to DFT. + * \par + * This set of functions implements CFFT/CIFFT + * for Q15, Q31, and floating-point data types. The functions operates on in-place buffer which uses same buffer for input and output. + * Complex input is stored in input buffer in an interleaved fashion. + * + * \par + * The functions operate on blocks of input and output data and each call to the function processes + * 2*fftLen samples through the transform. pSrc points to In-place arrays containing 2*fftLen values. + * \par + * The pSrc points to the array of in-place buffer of size 2*fftLen and inputs and outputs are stored in an interleaved fashion as shown below. + *
 {real[0], imag[0], real[1], imag[1],..} 
+ * + * \par Lengths supported by the transform: + * \par + * Internally, the function utilize a radix-4 decimation in frequency(DIF) algorithm + * and the size of the FFT supported are of the lengths [16, 64, 256, 1024]. + * + * + * \par Algorithm: + * + * Complex Fast Fourier Transform: + * \par + * Input real and imaginary data: + *
   
+ * x(n) = xa + j * ya   
+ * x(n+N/4 ) = xb + j * yb   
+ * x(n+N/2 ) = xc + j * yc   
+ * x(n+3N 4) = xd + j * yd   
+ * 
+ * where N is length of FFT + * \par + * Output real and imaginary data: + *
   
+ * X(4r) = xa'+ j * ya'   
+ * X(4r+1) = xb'+ j * yb'   
+ * X(4r+2) = xc'+ j * yc'   
+ * X(4r+3) = xd'+ j * yd'   
+ * 
+ * \par + * Twiddle factors for radix-4 FFT: + *
   
+ * Wn = co1 + j * (- si1)   
+ * W2n = co2 + j * (- si2)   
+ * W3n = co3 + j * (- si3)   
+ * 
+ * + * \par + * \image html CFFT.gif "Radix-4 Decimation-in Frequency Complex Fast Fourier Transform" + * + * \par + * Output from Radix-4 CFFT Results in Digit reversal order. Interchange middle two branches of every butterfly results in Bit reversed output. + * \par + * Butterfly CFFT equations: + *
   
+ * xa' = xa + xb + xc + xd   
+ * ya' = ya + yb + yc + yd   
+ * xc' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1)   
+ * yc' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1)   
+ * xb' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2)   
+ * yb' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2)   
+ * xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3)   
+ * yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3)   
+ * 
+ * + * + * Complex Inverse Fast Fourier Transform: + * \par + * CIFFT uses same twiddle factor table as CFFT with modifications in the design equation as shown below. + * + * \par + * Modified Butterfly CIFFT equations: + *
   
+ * xa' = xa + xb + xc + xd   
+ * ya' = ya + yb + yc + yd   
+ * xc' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1)   
+ * yc' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1)   
+ * xb' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2)   
+ * yb' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2)   
+ * xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3)   
+ * yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3)   
+ * 
+ * + * \par Instance Structure + * A separate instance structure must be defined for each Instance but the twiddle factors and bit reversal tables can be reused. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Initializes twiddle factor table and bit reversal table pointers + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Manually initialize the instance structure as follows: + *
   
+ *arm_cfft_radix4_instance_f32 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor, onebyfftLen};   
+ *arm_cfft_radix4_instance_q31 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor};   
+ *arm_cfft_radix4_instance_q15 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor};   
+ * 
+ * \par + * where fftLen length of CFFT/CIFFT; ifftFlag Flag for selection of CFFT or CIFFT(Set ifftFlag to calculate CIFFT otherwise calculates CFFT); + * bitReverseFlag Flag for selection of output order(Set bitReverseFlag to output in normal order otherwise output in bit reversed order); + * pTwiddlepoints to array of twiddle coefficients; pBitRevTable points to the array of bit reversal table. + * twidCoefModifier modifier for twiddle factor table which supports all FFT lengths with same table; + * pBitRevTable modifier for bit reversal table which supports all FFT lengths with same table. + * onebyfftLen value of 1/fftLen to calculate CIFFT; + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the CFFT/CIFFT function. + * Refer to the function specific documentation below for usage guidelines. + */ + + +/** + * @addtogroup CFFT_CIFFT + * @{ + */ + +/** + * @details + * @brief Processing function for the floating-point CFFT/CIFFT. + * @param[in] *S points to an instance of the floating-point CFFT/CIFFT structure. + * @param[in, out] *pSrc points to the complex data buffer of size 2*fftLen. Processing occurs in-place. + * @return none. + */ + +void arm_cfft_radix4_f32( + const arm_cfft_radix4_instance_f32 * S, + float32_t * pSrc) +{ + + if(S->ifftFlag == 1u) + { + /* Complex IFFT radix-4 */ + arm_radix4_butterfly_inverse_f32(pSrc, S->fftLen, S->pTwiddle, + S->twidCoefModifier, S->onebyfftLen); + } + else + { + /* Complex FFT radix-4 */ + arm_radix4_butterfly_f32(pSrc, S->fftLen, S->pTwiddle, + S->twidCoefModifier); + } + + if(S->bitReverseFlag == 1u) + { + /* Bit Reversal */ + arm_bitreversal_f32(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); + } + +} + + +/** + * @} end of CFFT_CIFFT group + */ + + + +/* ---------------------------------------------------------------------- +** Internal helper function used by the FFTs +** ------------------------------------------------------------------- */ + +/* + * @brief Core function for the floating-point CFFT butterfly process. + * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef points to the twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + +void arm_radix4_butterfly_f32( + float32_t * pSrc, + uint16_t fftLen, + float32_t * pCoef, + uint16_t twidCoefModifier) +{ + + float32_t co1, co2, co3, si1, si2, si3; + float32_t t1, t2, r1, r2, s1, s2; + uint32_t ia1, ia2, ia3; + uint32_t i0, i1, i2, i3; + uint32_t n1, n2, j, k; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Initializations for the first stage */ + n2 = fftLen; + n1 = n2; + + /* n2 = fftLen/4 */ + n2 >>= 2u; + i0 = 0u; + ia1 = 0u; + + j = n2; + + /* Calculation of first stage */ + do + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Butterfly implementation */ + + /* xa + xc */ + r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; + + /* xa - xc */ + r2 = pSrc[2u * i0] - pSrc[2u * i2]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xb + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = r1 + t1; + + /* (xa + xc) - (xb + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = s1 + t2; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* yb - yd */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + + /* xb - xd */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* index calculation for the coefficients */ + ia2 = ia1 + ia1; + co2 = pCoef[ia2 * 2u]; + si2 = pCoef[(ia2 * 2u) + 1u]; + + /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = (r1 * co2) + (s1 * si2); + + /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = (s1 * co2) - (r1 * si2); + + /* (xa - xc) + (yb - yd) */ + r1 = r2 + t1; + + /* (xa - xc) - (yb - yd) */ + r2 = r2 - t1; + + /* (ya - yc) - (xb - xd) */ + s1 = s2 - t2; + + /* (ya - yc) + (xb - xd) */ + s2 = s2 + t2; + + co1 = pCoef[ia1 * 2u]; + si1 = pCoef[(ia1 * 2u) + 1u]; + + /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = (r1 * co1) + (s1 * si1); + + /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = (s1 * co1) - (r1 * si1); + + /* index calculation for the coefficients */ + ia3 = ia2 + ia1; + co3 = pCoef[ia3 * 2u]; + si3 = pCoef[(ia3 * 2u) + 1u]; + + + /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = (r2 * co3) + (s2 * si3); + + /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = (s2 * co3) - (r2 * si3); + + /* Twiddle coefficients index modifier */ + ia1 = ia1 + twidCoefModifier; + + /* Updating input index */ + i0 = i0 + 1u; + + } + while(--j); + + twidCoefModifier <<= 2u; + + /* Calculation of second stage to excluding last stage */ + for (k = fftLen / 4; k > 4u; k >>= 2u) + { + /* Initializations for the first stage */ + n1 = n2; + n2 >>= 2u; + ia1 = 0u; + + /* Calculation of first stage */ + for (j = 0u; j <= (n2 - 1u); j++) + { + /* index calculation for the coefficients */ + ia2 = ia1 + ia1; + ia3 = ia2 + ia1; + co1 = pCoef[ia1 * 2u]; + si1 = pCoef[(ia1 * 2u) + 1u]; + co2 = pCoef[ia2 * 2u]; + si2 = pCoef[(ia2 * 2u) + 1u]; + co3 = pCoef[ia3 * 2u]; + si3 = pCoef[(ia3 * 2u) + 1u]; + + /* Twiddle coefficients index modifier */ + ia1 = ia1 + twidCoefModifier; + + for (i0 = j; i0 < fftLen; i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* xa + xc */ + r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; + + /* xa - xc */ + r2 = pSrc[(2u * i0)] - pSrc[(2u * i2)]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xb + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = r1 + t1; + + /* xa + xc -(xb + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = s1 + t2; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb - yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + + /* (xb - xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = (r1 * co2) + (s1 * si2); + + /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = (s1 * co2) - (r1 * si2); + + /* (xa - xc) + (yb - yd) */ + r1 = r2 + t1; + + /* (xa - xc) - (yb - yd) */ + r2 = r2 - t1; + + /* (ya - yc) - (xb - xd) */ + s1 = s2 - t2; + + /* (ya - yc) + (xb - xd) */ + s2 = s2 + t2; + + /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = (r1 * co1) + (s1 * si1); + + /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = (s1 * co1) - (r1 * si1); + + /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = (r2 * co3) + (s2 * si3); + + /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = (s2 * co3) - (r2 * si3); + } + } + twidCoefModifier <<= 2u; + } + + /* Initializations of last stage */ + n1 = n2; + n2 >>= 2u; + + /* Calculations of last stage */ + for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Butterfly implementation */ + + /* xa + xb */ + r1 = pSrc[2u * i0] + pSrc[2u * i2]; + + /* xa - xb */ + r2 = pSrc[2u * i0] - pSrc[2u * i2]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xc + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = r1 + t1; + + /* (xa + xb) - (xc + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = s1 + t2; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb-yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + + /* (xb-xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = r1; + + /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = s1; + + /* (xa+yb-xc-yd) */ + r1 = r2 + t1; + + /* (xa-yb-xc+yd) */ + r2 = r2 - t1; + + /* (ya-xb-yc+xd) */ + s1 = s2 - t2; + + /* (ya+xb-yc-xd) */ + s2 = s2 + t2; + + /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = r1; + + /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = s1; + + /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = r2; + + /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = s2; + } + + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initializations for the fft calculation */ + n2 = fftLen; + n1 = n2; + for (k = fftLen; k > 1u; k >>= 2u) + { + /* Initializations for the fft calculation */ + n1 = n2; + n2 >>= 2u; + ia1 = 0u; + + /* FFT Calculation */ + for (j = 0u; j <= (n2 - 1u); j++) + { + /* index calculation for the coefficients */ + ia2 = ia1 + ia1; + ia3 = ia2 + ia1; + co1 = pCoef[ia1 * 2u]; + si1 = pCoef[(ia1 * 2u) + 1u]; + co2 = pCoef[ia2 * 2u]; + si2 = pCoef[(ia2 * 2u) + 1u]; + co3 = pCoef[ia3 * 2u]; + si3 = pCoef[(ia3 * 2u) + 1u]; + + /* Twiddle coefficients index modifier */ + ia1 = ia1 + twidCoefModifier; + + for (i0 = j; i0 < fftLen; i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* xa + xc */ + r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; + + /* xa - xc */ + r2 = pSrc[(2u * i0)] - pSrc[(2u * i2)]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xb + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = r1 + t1; + + /* xa + xc -(xb + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = s1 + t2; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb - yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + + /* (xb - xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = (r1 * co2) + (s1 * si2); + + /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = (s1 * co2) - (r1 * si2); + + /* (xa - xc) + (yb - yd) */ + r1 = r2 + t1; + + /* (xa - xc) - (yb - yd) */ + r2 = r2 - t1; + + /* (ya - yc) - (xb - xd) */ + s1 = s2 - t2; + + /* (ya - yc) + (xb - xd) */ + s2 = s2 + t2; + + /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = (r1 * co1) + (s1 * si1); + + /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = (s1 * co1) - (r1 * si1); + + /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = (r2 * co3) + (s2 * si3); + + /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = (s2 * co3) - (r2 * si3); + } + } + twidCoefModifier <<= 2u; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/* + * @brief Core function for the floating-point CIFFT butterfly process. + * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef points to twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @param[in] onebyfftLen value of 1/fftLen. + * @return none. + */ + +void arm_radix4_butterfly_inverse_f32( + float32_t * pSrc, + uint16_t fftLen, + float32_t * pCoef, + uint16_t twidCoefModifier, + float32_t onebyfftLen) +{ + float32_t co1, co2, co3, si1, si2, si3; + float32_t t1, t2, r1, r2, s1, s2; + uint32_t ia1, ia2, ia3; + uint32_t i0, i1, i2, i3; + uint32_t n1, n2, j, k; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Initializations for the first stage */ + n2 = fftLen; + n1 = n2; + + /* n2 = fftLen/4 */ + n2 >>= 2u; + i0 = 0u; + ia1 = 0u; + + j = n2; + + /* Calculation of first stage */ + do + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Butterfly implementation */ + /* xa + xc */ + r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; + + /* xa - xc */ + r2 = pSrc[2u * i0] - pSrc[2u * i2]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xb + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = r1 + t1; + + /* (xa + xc) - (xb + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = s1 + t2; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* yb - yd */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + + /* xb - xd */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* index calculation for the coefficients */ + ia2 = ia1 + ia1; + co2 = pCoef[ia2 * 2u]; + si2 = pCoef[(ia2 * 2u) + 1u]; + + /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = (r1 * co2) - (s1 * si2); + + /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = (s1 * co2) + (r1 * si2); + + /* (xa - xc) - (yb - yd) */ + r1 = r2 - t1; + + /* (xa - xc) + (yb - yd) */ + r2 = r2 + t1; + + /* (ya - yc) + (xb - xd) */ + s1 = s2 + t2; + + /* (ya - yc) - (xb - xd) */ + s2 = s2 - t2; + + co1 = pCoef[ia1 * 2u]; + si1 = pCoef[(ia1 * 2u) + 1u]; + + /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = (r1 * co1) - (s1 * si1); + + /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = (s1 * co1) + (r1 * si1); + + /* index calculation for the coefficients */ + ia3 = ia2 + ia1; + co3 = pCoef[ia3 * 2u]; + si3 = pCoef[(ia3 * 2u) + 1u]; + + /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = (r2 * co3) - (s2 * si3); + + /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = (s2 * co3) + (r2 * si3); + + /* Twiddle coefficients index modifier */ + ia1 = ia1 + twidCoefModifier; + + /* Updating input index */ + i0 = i0 + 1u; + + } + while(--j); + + twidCoefModifier <<= 2u; + + /* Calculation of second stage to excluding last stage */ + for (k = fftLen / 4; k > 4u; k >>= 2u) + { + /* Initializations for the first stage */ + n1 = n2; + n2 >>= 2u; + ia1 = 0u; + + /* Calculation of first stage */ + for (j = 0u; j <= (n2 - 1u); j++) + { + /* index calculation for the coefficients */ + ia2 = ia1 + ia1; + ia3 = ia2 + ia1; + co1 = pCoef[ia1 * 2u]; + si1 = pCoef[(ia1 * 2u) + 1u]; + co2 = pCoef[ia2 * 2u]; + si2 = pCoef[(ia2 * 2u) + 1u]; + co3 = pCoef[ia3 * 2u]; + si3 = pCoef[(ia3 * 2u) + 1u]; + + /* Twiddle coefficients index modifier */ + ia1 = ia1 + twidCoefModifier; + + for (i0 = j; i0 < fftLen; i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* xa + xc */ + r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; + + /* xa - xc */ + r2 = pSrc[(2u * i0)] - pSrc[(2u * i2)]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xb + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = r1 + t1; + + /* xa + xc -(xb + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = s1 + t2; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb - yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + + /* (xb - xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = (r1 * co2) - (s1 * si2); + + /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = (s1 * co2) + (r1 * si2); + + /* (xa - xc) - (yb - yd) */ + r1 = r2 - t1; + + /* (xa - xc) + (yb - yd) */ + r2 = r2 + t1; + + /* (ya - yc) + (xb - xd) */ + s1 = s2 + t2; + + /* (ya - yc) - (xb - xd) */ + s2 = s2 - t2; + + /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = (r1 * co1) - (s1 * si1); + + /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = (s1 * co1) + (r1 * si1); + + /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = (r2 * co3) - (s2 * si3); + + /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = (s2 * co3) + (r2 * si3); + } + } + twidCoefModifier <<= 2u; + } + + /* Initializations of last stage */ + n1 = n2; + n2 >>= 2u; + + /* Calculations of last stage */ + for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Butterfly implementation */ + /* xa + xc */ + r1 = pSrc[2u * i0] + pSrc[2u * i2]; + + /* xa - xc */ + r2 = pSrc[2u * i0] - pSrc[2u * i2]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xc + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = (r1 + t1) * onebyfftLen; + + /* (xa + xb) - (xc + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = (s1 + t2) * onebyfftLen; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb-yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + + /* (xb-xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = r1 * onebyfftLen; + + /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = s1 * onebyfftLen; + + + /* (xa - xc) - (yb-yd) */ + r1 = r2 - t1; + + /* (xa - xc) + (yb-yd) */ + r2 = r2 + t1; + + /* (ya - yc) + (xb-xd) */ + s1 = s2 + t2; + + /* (ya - yc) - (xb-xd) */ + s2 = s2 - t2; + + /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = r1 * onebyfftLen; + + /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = s1 * onebyfftLen; + + /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = r2 * onebyfftLen; + + /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = s2 * onebyfftLen; + } + + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initializations for the first stage */ + n2 = fftLen; + n1 = n2; + + /* Calculation of first stage */ + for (k = fftLen; k > 4u; k >>= 2u) + { + /* Initializations for the first stage */ + n1 = n2; + n2 >>= 2u; + ia1 = 0u; + + /* Calculation of first stage */ + for (j = 0u; j <= (n2 - 1u); j++) + { + /* index calculation for the coefficients */ + ia2 = ia1 + ia1; + ia3 = ia2 + ia1; + co1 = pCoef[ia1 * 2u]; + si1 = pCoef[(ia1 * 2u) + 1u]; + co2 = pCoef[ia2 * 2u]; + si2 = pCoef[(ia2 * 2u) + 1u]; + co3 = pCoef[ia3 * 2u]; + si3 = pCoef[(ia3 * 2u) + 1u]; + + /* Twiddle coefficients index modifier */ + ia1 = ia1 + twidCoefModifier; + + for (i0 = j; i0 < fftLen; i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* xa + xc */ + r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; + + /* xa - xc */ + r2 = pSrc[(2u * i0)] - pSrc[(2u * i2)]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xb + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = r1 + t1; + + /* xa + xc -(xb + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = s1 + t2; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb - yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + + /* (xb - xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = (r1 * co2) - (s1 * si2); + + /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = (s1 * co2) + (r1 * si2); + + /* (xa - xc) - (yb - yd) */ + r1 = r2 - t1; + + /* (xa - xc) + (yb - yd) */ + r2 = r2 + t1; + + /* (ya - yc) + (xb - xd) */ + s1 = s2 + t2; + + /* (ya - yc) - (xb - xd) */ + s2 = s2 - t2; + + /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = (r1 * co1) - (s1 * si1); + + /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = (s1 * co1) + (r1 * si1); + + /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = (r2 * co3) - (s2 * si3); + + /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = (s2 * co3) + (r2 * si3); + } + } + twidCoefModifier <<= 2u; + } + /* Initializations of last stage */ + n1 = n2; + n2 >>= 2u; + + /* Calculations of last stage */ + for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Butterfly implementation */ + /* xa + xc */ + r1 = pSrc[2u * i0] + pSrc[2u * i2]; + + /* xa - xc */ + r2 = pSrc[2u * i0] - pSrc[2u * i2]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xc + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = (r1 + t1) * onebyfftLen; + + /* (xa + xb) - (xc + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = (s1 + t2) * onebyfftLen; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb-yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + + /* (xb-xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = r1 * onebyfftLen; + + /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = s1 * onebyfftLen; + + + /* (xa - xc) - (yb-yd) */ + r1 = r2 - t1; + + /* (xa - xc) + (yb-yd) */ + r2 = r2 + t1; + + /* (ya - yc) + (xb-xd) */ + s1 = s2 + t2; + + /* (ya - yc) - (xb-xd) */ + s2 = s2 - t2; + + /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = r1 * onebyfftLen; + + /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = s1 * onebyfftLen; + + /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = r2 * onebyfftLen; + + /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = s2 * onebyfftLen; + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/* + * @brief In-place bit reversal function. + * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. + * @param[in] fftSize length of the FFT. + * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table. + * @param[in] *pBitRevTab points to the bit reversal table. + * @return none. + */ + +void arm_bitreversal_f32( + float32_t * pSrc, + uint16_t fftSize, + uint16_t bitRevFactor, + uint16_t * pBitRevTab) +{ + uint16_t fftLenBy2, fftLenBy2p1; + uint16_t i, j; + float32_t in; + + /* Initializations */ + j = 0u; + fftLenBy2 = fftSize >> 1u; + fftLenBy2p1 = (fftSize >> 1u) + 1u; + + /* Bit Reversal Implementation */ + for (i = 0u; i <= (fftLenBy2 - 2u); i += 2u) + { + if(i < j) + { + /* pSrc[i] <-> pSrc[j]; */ + in = pSrc[2u * i]; + pSrc[2u * i] = pSrc[2u * j]; + pSrc[2u * j] = in; + + /* pSrc[i+1u] <-> pSrc[j+1u] */ + in = pSrc[(2u * i) + 1u]; + pSrc[(2u * i) + 1u] = pSrc[(2u * j) + 1u]; + pSrc[(2u * j) + 1u] = in; + + /* pSrc[i+fftLenBy2p1] <-> pSrc[j+fftLenBy2p1] */ + in = pSrc[2u * (i + fftLenBy2p1)]; + pSrc[2u * (i + fftLenBy2p1)] = pSrc[2u * (j + fftLenBy2p1)]; + pSrc[2u * (j + fftLenBy2p1)] = in; + + /* pSrc[i+fftLenBy2p1+1u] <-> pSrc[j+fftLenBy2p1+1u] */ + in = pSrc[(2u * (i + fftLenBy2p1)) + 1u]; + pSrc[(2u * (i + fftLenBy2p1)) + 1u] = + pSrc[(2u * (j + fftLenBy2p1)) + 1u]; + pSrc[(2u * (j + fftLenBy2p1)) + 1u] = in; + + } + + /* pSrc[i+1u] <-> pSrc[j+1u] */ + in = pSrc[2u * (i + 1u)]; + pSrc[2u * (i + 1u)] = pSrc[2u * (j + fftLenBy2)]; + pSrc[2u * (j + fftLenBy2)] = in; + + /* pSrc[i+2u] <-> pSrc[j+2u] */ + in = pSrc[(2u * (i + 1u)) + 1u]; + pSrc[(2u * (i + 1u)) + 1u] = pSrc[(2u * (j + fftLenBy2)) + 1u]; + pSrc[(2u * (j + fftLenBy2)) + 1u] = in; + + /* Reading the index for the bit reversal */ + j = *pBitRevTab; + + /* Updating the bit reversal index depending on the fft length */ + pBitRevTab += bitRevFactor; + } +} diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_f32.c index 07be8920b..85ab9a9e5 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_f32.c @@ -1,1193 +1,1193 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_init_f32.c -* -* Description: Radix-4 Decimation in Frequency Floating-point CFFT & CIFFT Initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup CFFT_CIFFT - * @{ - */ - -/* -* @brief Floating-point Twiddle factors Table Generation -*/ - - -/** -* \par -* Example code for Floating-point Twiddle factors Generation: -* \par -*
for(i = 0; i< N; i++)   
-* {   
-*	twiddleCoef[2*i]= cos(i * 2*PI/(float)N);   
-*	twiddleCoef[2*i+1]= sin(i * 2*PI/(float)N);   
-* } 
-* \par -* where N = 1024 and PI = 3.14159265358979 -* \par -* Cos and Sin values are in interleaved fashion -* -*/ - -static const float32_t twiddleCoef[2048] = { - 1.000000000000000000f, 0.000000000000000000f, - 0.999981175282601110f, 0.006135884649154475f, - 0.999924701839144500f, 0.012271538285719925f, - 0.999830581795823400f, 0.018406729905804820f, - 0.999698818696204250f, 0.024541228522912288f, - 0.999529417501093140f, 0.030674803176636626f, - 0.999322384588349540f, 0.036807222941358832f, - 0.999077727752645360f, 0.042938256934940820f, - 0.998795456205172410f, 0.049067674327418015f, - 0.998475580573294770f, 0.055195244349689934f, - 0.998118112900149180f, 0.061320736302208578f, - 0.997723066644191640f, 0.067443919563664051f, - 0.997290456678690210f, 0.073564563599667426f, - 0.996820299291165670f, 0.079682437971430126f, - 0.996312612182778000f, 0.085797312344439894f, - 0.995767414467659820f, 0.091908956497132724f, - 0.995184726672196930f, 0.098017140329560604f, - 0.994564570734255420f, 0.104121633872054590f, - 0.993906970002356060f, 0.110222207293883060f, - 0.993211949234794500f, 0.116318630911904750f, - 0.992479534598709970f, 0.122410675199216200f, - 0.991709753669099530f, 0.128498110793793170f, - 0.990902635427780010f, 0.134580708507126170f, - 0.990058210262297120f, 0.140658239332849210f, - 0.989176509964781010f, 0.146730474455361750f, - 0.988257567730749460f, 0.152797185258443440f, - 0.987301418157858430f, 0.158858143333861450f, - 0.986308097244598670f, 0.164913120489969890f, - 0.985277642388941220f, 0.170961888760301220f, - 0.984210092386929030f, 0.177004220412148750f, - 0.983105487431216290f, 0.183039887955140950f, - 0.981963869109555240f, 0.189068664149806190f, - 0.980785280403230430f, 0.195090322016128250f, - 0.979569765685440520f, 0.201104634842091900f, - 0.978317370719627650f, 0.207111376192218560f, - 0.977028142657754390f, 0.213110319916091360f, - 0.975702130038528570f, 0.219101240156869800f, - 0.974339382785575860f, 0.225083911359792830f, - 0.972939952205560180f, 0.231058108280671110f, - 0.971503890986251780f, 0.237023605994367200f, - 0.970031253194543970f, 0.242980179903263870f, - 0.968522094274417380f, 0.248927605745720150f, - 0.966976471044852070f, 0.254865659604514570f, - 0.965394441697689400f, 0.260794117915275510f, - 0.963776065795439840f, 0.266712757474898370f, - 0.962121404269041580f, 0.272621355449948980f, - 0.960430519415565790f, 0.278519689385053060f, - 0.958703474895871600f, 0.284407537211271880f, - 0.956940335732208820f, 0.290284677254462330f, - 0.955141168305770780f, 0.296150888243623790f, - 0.953306040354193860f, 0.302005949319228080f, - 0.951435020969008340f, 0.307849640041534870f, - 0.949528180593036670f, 0.313681740398891520f, - 0.947585591017741090f, 0.319502030816015690f, - 0.945607325380521280f, 0.325310292162262930f, - 0.943593458161960390f, 0.331106305759876430f, - 0.941544065183020810f, 0.336889853392220050f, - 0.939459223602189920f, 0.342660717311994380f, - 0.937339011912574960f, 0.348418680249434560f, - 0.935183509938947610f, 0.354163525420490340f, - 0.932992798834738960f, 0.359895036534988110f, - 0.930766961078983710f, 0.365612997804773850f, - 0.928506080473215590f, 0.371317193951837540f, - 0.926210242138311380f, 0.377007410216418260f, - 0.923879532511286740f, 0.382683432365089780f, - 0.921514039342042010f, 0.388345046698826250f, - 0.919113851690057770f, 0.393992040061048100f, - 0.916679059921042700f, 0.399624199845646790f, - 0.914209755703530690f, 0.405241314004989860f, - 0.911706032005429880f, 0.410843171057903910f, - 0.909167983090522380f, 0.416429560097637150f, - 0.906595704514915330f, 0.422000270799799680f, - 0.903989293123443340f, 0.427555093430282080f, - 0.901348847046022030f, 0.433093818853151960f, - 0.898674465693953820f, 0.438616238538527660f, - 0.895966249756185220f, 0.444122144570429200f, - 0.893224301195515320f, 0.449611329654606540f, - 0.890448723244757880f, 0.455083587126343840f, - 0.887639620402853930f, 0.460538710958240010f, - 0.884797098430937790f, 0.465976495767966180f, - 0.881921264348355050f, 0.471396736825997640f, - 0.879012226428633530f, 0.476799230063322090f, - 0.876070094195406600f, 0.482183772079122720f, - 0.873094978418290090f, 0.487550160148436000f, - 0.870086991108711460f, 0.492898192229784040f, - 0.867046245515692650f, 0.498227666972781870f, - 0.863972856121586810f, 0.503538383725717580f, - 0.860866938637767310f, 0.508830142543106990f, - 0.857728610000272120f, 0.514102744193221660f, - 0.854557988365400530f, 0.519355990165589640f, - 0.851355193105265200f, 0.524589682678468950f, - 0.848120344803297230f, 0.529803624686294610f, - 0.844853565249707120f, 0.534997619887097150f, - 0.841554977436898440f, 0.540171472729892850f, - 0.838224705554838080f, 0.545324988422046460f, - 0.834862874986380010f, 0.550457972936604810f, - 0.831469612302545240f, 0.555570233019602180f, - 0.828045045257755800f, 0.560661576197336030f, - 0.824589302785025290f, 0.565731810783613120f, - 0.821102514991104650f, 0.570780745886967260f, - 0.817584813151583710f, 0.575808191417845340f, - 0.814036329705948410f, 0.580813958095764530f, - 0.810457198252594770f, 0.585797857456438860f, - 0.806847553543799330f, 0.590759701858874160f, - 0.803207531480644940f, 0.595699304492433360f, - 0.799537269107905010f, 0.600616479383868970f, - 0.795836904608883570f, 0.605511041404325550f, - 0.792106577300212390f, 0.610382806276309480f, - 0.788346427626606340f, 0.615231590580626820f, - 0.784556597155575240f, 0.620057211763289100f, - 0.780737228572094490f, 0.624859488142386340f, - 0.776888465673232440f, 0.629638238914926980f, - 0.773010453362736990f, 0.634393284163645490f, - 0.769103337645579700f, 0.639124444863775730f, - 0.765167265622458960f, 0.643831542889791390f, - 0.761202385484261780f, 0.648514401022112440f, - 0.757208846506484570f, 0.653172842953776760f, - 0.753186799043612520f, 0.657806693297078640f, - 0.749136394523459370f, 0.662415777590171780f, - 0.745057785441466060f, 0.666999922303637470f, - 0.740951125354959110f, 0.671558954847018330f, - 0.736816568877369900f, 0.676092703575315920f, - 0.732654271672412820f, 0.680600997795453020f, - 0.728464390448225200f, 0.685083667772700360f, - 0.724247082951467000f, 0.689540544737066830f, - 0.720002507961381650f, 0.693971460889654000f, - 0.715730825283818590f, 0.698376249408972920f, - 0.711432195745216430f, 0.702754744457225300f, - 0.707106781186547570f, 0.707106781186547460f, - 0.702754744457225300f, 0.711432195745216430f, - 0.698376249408972920f, 0.715730825283818590f, - 0.693971460889654000f, 0.720002507961381650f, - 0.689540544737066940f, 0.724247082951466890f, - 0.685083667772700360f, 0.728464390448225200f, - 0.680600997795453130f, 0.732654271672412820f, - 0.676092703575316030f, 0.736816568877369790f, - 0.671558954847018330f, 0.740951125354959110f, - 0.666999922303637470f, 0.745057785441465950f, - 0.662415777590171780f, 0.749136394523459260f, - 0.657806693297078640f, 0.753186799043612410f, - 0.653172842953776760f, 0.757208846506484460f, - 0.648514401022112550f, 0.761202385484261780f, - 0.643831542889791500f, 0.765167265622458960f, - 0.639124444863775730f, 0.769103337645579590f, - 0.634393284163645490f, 0.773010453362736990f, - 0.629638238914927100f, 0.776888465673232440f, - 0.624859488142386450f, 0.780737228572094380f, - 0.620057211763289210f, 0.784556597155575240f, - 0.615231590580626820f, 0.788346427626606230f, - 0.610382806276309480f, 0.792106577300212390f, - 0.605511041404325550f, 0.795836904608883460f, - 0.600616479383868970f, 0.799537269107905010f, - 0.595699304492433470f, 0.803207531480644830f, - 0.590759701858874280f, 0.806847553543799220f, - 0.585797857456438860f, 0.810457198252594770f, - 0.580813958095764530f, 0.814036329705948300f, - 0.575808191417845340f, 0.817584813151583710f, - 0.570780745886967370f, 0.821102514991104650f, - 0.565731810783613230f, 0.824589302785025290f, - 0.560661576197336030f, 0.828045045257755800f, - 0.555570233019602290f, 0.831469612302545240f, - 0.550457972936604810f, 0.834862874986380010f, - 0.545324988422046460f, 0.838224705554837970f, - 0.540171472729892970f, 0.841554977436898330f, - 0.534997619887097260f, 0.844853565249707010f, - 0.529803624686294830f, 0.848120344803297120f, - 0.524589682678468840f, 0.851355193105265200f, - 0.519355990165589530f, 0.854557988365400530f, - 0.514102744193221660f, 0.857728610000272120f, - 0.508830142543106990f, 0.860866938637767310f, - 0.503538383725717580f, 0.863972856121586700f, - 0.498227666972781870f, 0.867046245515692650f, - 0.492898192229784090f, 0.870086991108711350f, - 0.487550160148436050f, 0.873094978418290090f, - 0.482183772079122830f, 0.876070094195406600f, - 0.476799230063322250f, 0.879012226428633410f, - 0.471396736825997810f, 0.881921264348354940f, - 0.465976495767966130f, 0.884797098430937790f, - 0.460538710958240010f, 0.887639620402853930f, - 0.455083587126343840f, 0.890448723244757880f, - 0.449611329654606600f, 0.893224301195515320f, - 0.444122144570429260f, 0.895966249756185110f, - 0.438616238538527710f, 0.898674465693953820f, - 0.433093818853152010f, 0.901348847046022030f, - 0.427555093430282200f, 0.903989293123443340f, - 0.422000270799799790f, 0.906595704514915330f, - 0.416429560097637320f, 0.909167983090522270f, - 0.410843171057903910f, 0.911706032005429880f, - 0.405241314004989860f, 0.914209755703530690f, - 0.399624199845646790f, 0.916679059921042700f, - 0.393992040061048100f, 0.919113851690057770f, - 0.388345046698826300f, 0.921514039342041900f, - 0.382683432365089840f, 0.923879532511286740f, - 0.377007410216418310f, 0.926210242138311270f, - 0.371317193951837600f, 0.928506080473215480f, - 0.365612997804773960f, 0.930766961078983710f, - 0.359895036534988280f, 0.932992798834738850f, - 0.354163525420490510f, 0.935183509938947500f, - 0.348418680249434510f, 0.937339011912574960f, - 0.342660717311994380f, 0.939459223602189920f, - 0.336889853392220050f, 0.941544065183020810f, - 0.331106305759876430f, 0.943593458161960390f, - 0.325310292162262980f, 0.945607325380521280f, - 0.319502030816015750f, 0.947585591017741090f, - 0.313681740398891570f, 0.949528180593036670f, - 0.307849640041534980f, 0.951435020969008340f, - 0.302005949319228200f, 0.953306040354193750f, - 0.296150888243623960f, 0.955141168305770670f, - 0.290284677254462330f, 0.956940335732208940f, - 0.284407537211271820f, 0.958703474895871600f, - 0.278519689385053060f, 0.960430519415565790f, - 0.272621355449948980f, 0.962121404269041580f, - 0.266712757474898420f, 0.963776065795439840f, - 0.260794117915275570f, 0.965394441697689400f, - 0.254865659604514630f, 0.966976471044852070f, - 0.248927605745720260f, 0.968522094274417270f, - 0.242980179903263980f, 0.970031253194543970f, - 0.237023605994367340f, 0.971503890986251780f, - 0.231058108280671280f, 0.972939952205560070f, - 0.225083911359792780f, 0.974339382785575860f, - 0.219101240156869770f, 0.975702130038528570f, - 0.213110319916091360f, 0.977028142657754390f, - 0.207111376192218560f, 0.978317370719627650f, - 0.201104634842091960f, 0.979569765685440520f, - 0.195090322016128330f, 0.980785280403230430f, - 0.189068664149806280f, 0.981963869109555240f, - 0.183039887955141060f, 0.983105487431216290f, - 0.177004220412148860f, 0.984210092386929030f, - 0.170961888760301360f, 0.985277642388941220f, - 0.164913120489970090f, 0.986308097244598670f, - 0.158858143333861390f, 0.987301418157858430f, - 0.152797185258443410f, 0.988257567730749460f, - 0.146730474455361750f, 0.989176509964781010f, - 0.140658239332849240f, 0.990058210262297120f, - 0.134580708507126220f, 0.990902635427780010f, - 0.128498110793793220f, 0.991709753669099530f, - 0.122410675199216280f, 0.992479534598709970f, - 0.116318630911904880f, 0.993211949234794500f, - 0.110222207293883180f, 0.993906970002356060f, - 0.104121633872054730f, 0.994564570734255420f, - 0.098017140329560770f, 0.995184726672196820f, - 0.091908956497132696f, 0.995767414467659820f, - 0.085797312344439880f, 0.996312612182778000f, - 0.079682437971430126f, 0.996820299291165670f, - 0.073564563599667454f, 0.997290456678690210f, - 0.067443919563664106f, 0.997723066644191640f, - 0.061320736302208648f, 0.998118112900149180f, - 0.055195244349690031f, 0.998475580573294770f, - 0.049067674327418126f, 0.998795456205172410f, - 0.042938256934940959f, 0.999077727752645360f, - 0.036807222941358991f, 0.999322384588349540f, - 0.030674803176636581f, 0.999529417501093140f, - 0.024541228522912264f, 0.999698818696204250f, - 0.018406729905804820f, 0.999830581795823400f, - 0.012271538285719944f, 0.999924701839144500f, - 0.006135884649154515f, 0.999981175282601110f, - 0.000000000000000061f, 1.000000000000000000f, - -0.006135884649154393f, 0.999981175282601110f, - -0.012271538285719823f, 0.999924701839144500f, - -0.018406729905804695f, 0.999830581795823400f, - -0.024541228522912142f, 0.999698818696204250f, - -0.030674803176636459f, 0.999529417501093140f, - -0.036807222941358866f, 0.999322384588349540f, - -0.042938256934940834f, 0.999077727752645360f, - -0.049067674327418008f, 0.998795456205172410f, - -0.055195244349689913f, 0.998475580573294770f, - -0.061320736302208530f, 0.998118112900149180f, - -0.067443919563663982f, 0.997723066644191640f, - -0.073564563599667329f, 0.997290456678690210f, - -0.079682437971430015f, 0.996820299291165780f, - -0.085797312344439755f, 0.996312612182778000f, - -0.091908956497132571f, 0.995767414467659820f, - -0.098017140329560645f, 0.995184726672196930f, - -0.104121633872054600f, 0.994564570734255420f, - -0.110222207293883060f, 0.993906970002356060f, - -0.116318630911904750f, 0.993211949234794500f, - -0.122410675199216150f, 0.992479534598709970f, - -0.128498110793793110f, 0.991709753669099530f, - -0.134580708507126110f, 0.990902635427780010f, - -0.140658239332849130f, 0.990058210262297120f, - -0.146730474455361640f, 0.989176509964781010f, - -0.152797185258443300f, 0.988257567730749460f, - -0.158858143333861280f, 0.987301418157858430f, - -0.164913120489969950f, 0.986308097244598670f, - -0.170961888760301240f, 0.985277642388941220f, - -0.177004220412148750f, 0.984210092386929030f, - -0.183039887955140920f, 0.983105487431216290f, - -0.189068664149806160f, 0.981963869109555240f, - -0.195090322016128190f, 0.980785280403230430f, - -0.201104634842091820f, 0.979569765685440520f, - -0.207111376192218450f, 0.978317370719627650f, - -0.213110319916091250f, 0.977028142657754390f, - -0.219101240156869660f, 0.975702130038528570f, - -0.225083911359792670f, 0.974339382785575860f, - -0.231058108280671140f, 0.972939952205560180f, - -0.237023605994367230f, 0.971503890986251780f, - -0.242980179903263870f, 0.970031253194543970f, - -0.248927605745720120f, 0.968522094274417380f, - -0.254865659604514520f, 0.966976471044852070f, - -0.260794117915275460f, 0.965394441697689400f, - -0.266712757474898310f, 0.963776065795439840f, - -0.272621355449948870f, 0.962121404269041580f, - -0.278519689385052950f, 0.960430519415565900f, - -0.284407537211271710f, 0.958703474895871600f, - -0.290284677254462160f, 0.956940335732208940f, - -0.296150888243623840f, 0.955141168305770670f, - -0.302005949319228080f, 0.953306040354193860f, - -0.307849640041534870f, 0.951435020969008340f, - -0.313681740398891410f, 0.949528180593036670f, - -0.319502030816015640f, 0.947585591017741200f, - -0.325310292162262870f, 0.945607325380521390f, - -0.331106305759876320f, 0.943593458161960390f, - -0.336889853392219940f, 0.941544065183020810f, - -0.342660717311994270f, 0.939459223602189920f, - -0.348418680249434400f, 0.937339011912574960f, - -0.354163525420490400f, 0.935183509938947610f, - -0.359895036534988170f, 0.932992798834738850f, - -0.365612997804773850f, 0.930766961078983710f, - -0.371317193951837490f, 0.928506080473215590f, - -0.377007410216418200f, 0.926210242138311380f, - -0.382683432365089730f, 0.923879532511286740f, - -0.388345046698826190f, 0.921514039342042010f, - -0.393992040061047990f, 0.919113851690057770f, - -0.399624199845646680f, 0.916679059921042700f, - -0.405241314004989750f, 0.914209755703530690f, - -0.410843171057903800f, 0.911706032005429880f, - -0.416429560097636990f, 0.909167983090522490f, - -0.422000270799799680f, 0.906595704514915330f, - -0.427555093430281860f, 0.903989293123443450f, - -0.433093818853151900f, 0.901348847046022030f, - -0.438616238538527380f, 0.898674465693953930f, - -0.444122144570429140f, 0.895966249756185220f, - -0.449611329654606710f, 0.893224301195515210f, - -0.455083587126343720f, 0.890448723244757990f, - -0.460538710958240060f, 0.887639620402853930f, - -0.465976495767966010f, 0.884797098430937900f, - -0.471396736825997700f, 0.881921264348355050f, - -0.476799230063321920f, 0.879012226428633530f, - -0.482183772079122720f, 0.876070094195406600f, - -0.487550160148435720f, 0.873094978418290200f, - -0.492898192229783980f, 0.870086991108711460f, - -0.498227666972781590f, 0.867046245515692760f, - -0.503538383725717460f, 0.863972856121586810f, - -0.508830142543107100f, 0.860866938637767200f, - -0.514102744193221660f, 0.857728610000272120f, - -0.519355990165589640f, 0.854557988365400530f, - -0.524589682678468730f, 0.851355193105265200f, - -0.529803624686294720f, 0.848120344803297230f, - -0.534997619887097040f, 0.844853565249707230f, - -0.540171472729892850f, 0.841554977436898440f, - -0.545324988422046240f, 0.838224705554838190f, - -0.550457972936604700f, 0.834862874986380120f, - -0.555570233019601960f, 0.831469612302545460f, - -0.560661576197335920f, 0.828045045257755800f, - -0.565731810783613230f, 0.824589302785025180f, - -0.570780745886967140f, 0.821102514991104760f, - -0.575808191417845340f, 0.817584813151583710f, - -0.580813958095764420f, 0.814036329705948520f, - -0.585797857456438860f, 0.810457198252594770f, - -0.590759701858874050f, 0.806847553543799450f, - -0.595699304492433360f, 0.803207531480644940f, - -0.600616479383868750f, 0.799537269107905240f, - -0.605511041404325430f, 0.795836904608883570f, - -0.610382806276309590f, 0.792106577300212280f, - -0.615231590580626710f, 0.788346427626606340f, - -0.620057211763289210f, 0.784556597155575130f, - -0.624859488142386230f, 0.780737228572094600f, - -0.629638238914927100f, 0.776888465673232440f, - -0.634393284163645380f, 0.773010453362737100f, - -0.639124444863775730f, 0.769103337645579590f, - -0.643831542889791280f, 0.765167265622459070f, - -0.648514401022112440f, 0.761202385484261890f, - -0.653172842953776530f, 0.757208846506484680f, - -0.657806693297078640f, 0.753186799043612520f, - -0.662415777590171890f, 0.749136394523459260f, - -0.666999922303637360f, 0.745057785441466060f, - -0.671558954847018440f, 0.740951125354958990f, - -0.676092703575315810f, 0.736816568877370020f, - -0.680600997795453020f, 0.732654271672412820f, - -0.685083667772700240f, 0.728464390448225310f, - -0.689540544737066940f, 0.724247082951466890f, - -0.693971460889653780f, 0.720002507961381770f, - -0.698376249408972800f, 0.715730825283818710f, - -0.702754744457225080f, 0.711432195745216660f, - -0.707106781186547460f, 0.707106781186547570f, - -0.711432195745216540f, 0.702754744457225190f, - -0.715730825283818590f, 0.698376249408972920f, - -0.720002507961381650f, 0.693971460889654000f, - -0.724247082951466780f, 0.689540544737067050f, - -0.728464390448225200f, 0.685083667772700360f, - -0.732654271672412700f, 0.680600997795453240f, - -0.736816568877369900f, 0.676092703575315920f, - -0.740951125354958880f, 0.671558954847018550f, - -0.745057785441465950f, 0.666999922303637580f, - -0.749136394523459150f, 0.662415777590172010f, - -0.753186799043612410f, 0.657806693297078750f, - -0.757208846506484570f, 0.653172842953776640f, - -0.761202385484261670f, 0.648514401022112550f, - -0.765167265622458960f, 0.643831542889791390f, - -0.769103337645579480f, 0.639124444863775840f, - -0.773010453362736990f, 0.634393284163645490f, - -0.776888465673232330f, 0.629638238914927210f, - -0.780737228572094490f, 0.624859488142386340f, - -0.784556597155575020f, 0.620057211763289430f, - -0.788346427626606230f, 0.615231590580626930f, - -0.792106577300212170f, 0.610382806276309700f, - -0.795836904608883460f, 0.605511041404325660f, - -0.799537269107905120f, 0.600616479383868860f, - -0.803207531480644830f, 0.595699304492433470f, - -0.806847553543799330f, 0.590759701858874160f, - -0.810457198252594660f, 0.585797857456438980f, - -0.814036329705948410f, 0.580813958095764530f, - -0.817584813151583600f, 0.575808191417845450f, - -0.821102514991104650f, 0.570780745886967260f, - -0.824589302785025070f, 0.565731810783613450f, - -0.828045045257755690f, 0.560661576197336140f, - -0.831469612302545350f, 0.555570233019602180f, - -0.834862874986380010f, 0.550457972936604920f, - -0.838224705554838080f, 0.545324988422046350f, - -0.841554977436898330f, 0.540171472729892970f, - -0.844853565249707120f, 0.534997619887097150f, - -0.848120344803297120f, 0.529803624686294830f, - -0.851355193105265200f, 0.524589682678468950f, - -0.854557988365400420f, 0.519355990165589750f, - -0.857728610000272010f, 0.514102744193221770f, - -0.860866938637767090f, 0.508830142543107320f, - -0.863972856121586700f, 0.503538383725717690f, - -0.867046245515692760f, 0.498227666972781760f, - -0.870086991108711350f, 0.492898192229784150f, - -0.873094978418290090f, 0.487550160148435880f, - -0.876070094195406490f, 0.482183772079122890f, - -0.879012226428633530f, 0.476799230063322090f, - -0.881921264348354940f, 0.471396736825997860f, - -0.884797098430937790f, 0.465976495767966180f, - -0.887639620402853820f, 0.460538710958240230f, - -0.890448723244757880f, 0.455083587126343890f, - -0.893224301195515210f, 0.449611329654606870f, - -0.895966249756185110f, 0.444122144570429310f, - -0.898674465693953930f, 0.438616238538527550f, - -0.901348847046021920f, 0.433093818853152070f, - -0.903989293123443340f, 0.427555093430282030f, - -0.906595704514915330f, 0.422000270799799850f, - -0.909167983090522380f, 0.416429560097637150f, - -0.911706032005429770f, 0.410843171057904130f, - -0.914209755703530690f, 0.405241314004989920f, - -0.916679059921042590f, 0.399624199845647070f, - -0.919113851690057770f, 0.393992040061048150f, - -0.921514039342041790f, 0.388345046698826580f, - -0.923879532511286740f, 0.382683432365089890f, - -0.926210242138311380f, 0.377007410216418150f, - -0.928506080473215480f, 0.371317193951837710f, - -0.930766961078983710f, 0.365612997804773800f, - -0.932992798834738850f, 0.359895036534988330f, - -0.935183509938947610f, 0.354163525420490400f, - -0.937339011912574850f, 0.348418680249434790f, - -0.939459223602189920f, 0.342660717311994430f, - -0.941544065183020700f, 0.336889853392220330f, - -0.943593458161960390f, 0.331106305759876480f, - -0.945607325380521170f, 0.325310292162263260f, - -0.947585591017741090f, 0.319502030816015800f, - -0.949528180593036670f, 0.313681740398891410f, - -0.951435020969008340f, 0.307849640041535030f, - -0.953306040354193860f, 0.302005949319228030f, - -0.955141168305770670f, 0.296150888243624010f, - -0.956940335732208820f, 0.290284677254462390f, - -0.958703474895871490f, 0.284407537211272100f, - -0.960430519415565790f, 0.278519689385053170f, - -0.962121404269041470f, 0.272621355449949250f, - -0.963776065795439840f, 0.266712757474898480f, - -0.965394441697689290f, 0.260794117915275850f, - -0.966976471044852070f, 0.254865659604514680f, - -0.968522094274417380f, 0.248927605745720090f, - -0.970031253194543970f, 0.242980179903264070f, - -0.971503890986251780f, 0.237023605994367170f, - -0.972939952205560070f, 0.231058108280671330f, - -0.974339382785575860f, 0.225083911359792830f, - -0.975702130038528460f, 0.219101240156870050f, - -0.977028142657754390f, 0.213110319916091420f, - -0.978317370719627540f, 0.207111376192218840f, - -0.979569765685440520f, 0.201104634842092010f, - -0.980785280403230430f, 0.195090322016128610f, - -0.981963869109555240f, 0.189068664149806360f, - -0.983105487431216290f, 0.183039887955140900f, - -0.984210092386929030f, 0.177004220412148940f, - -0.985277642388941220f, 0.170961888760301220f, - -0.986308097244598560f, 0.164913120489970140f, - -0.987301418157858430f, 0.158858143333861470f, - -0.988257567730749460f, 0.152797185258443690f, - -0.989176509964781010f, 0.146730474455361800f, - -0.990058210262297010f, 0.140658239332849540f, - -0.990902635427780010f, 0.134580708507126280f, - -0.991709753669099530f, 0.128498110793793090f, - -0.992479534598709970f, 0.122410675199216350f, - -0.993211949234794500f, 0.116318630911904710f, - -0.993906970002356060f, 0.110222207293883240f, - -0.994564570734255420f, 0.104121633872054570f, - -0.995184726672196820f, 0.098017140329560826f, - -0.995767414467659820f, 0.091908956497132752f, - -0.996312612182778000f, 0.085797312344440158f, - -0.996820299291165670f, 0.079682437971430195f, - -0.997290456678690210f, 0.073564563599667732f, - -0.997723066644191640f, 0.067443919563664176f, - -0.998118112900149180f, 0.061320736302208488f, - -0.998475580573294770f, 0.055195244349690094f, - -0.998795456205172410f, 0.049067674327417966f, - -0.999077727752645360f, 0.042938256934941021f, - -0.999322384588349540f, 0.036807222941358832f, - -0.999529417501093140f, 0.030674803176636865f, - -0.999698818696204250f, 0.024541228522912326f, - -0.999830581795823400f, 0.018406729905805101f, - -0.999924701839144500f, 0.012271538285720007f, - -0.999981175282601110f, 0.006135884649154799f, - -1.000000000000000000f, 0.000000000000000122f, - -0.999981175282601110f, -0.006135884649154554f, - -0.999924701839144500f, -0.012271538285719762f, - -0.999830581795823400f, -0.018406729905804858f, - -0.999698818696204250f, -0.024541228522912080f, - -0.999529417501093140f, -0.030674803176636619f, - -0.999322384588349540f, -0.036807222941358582f, - -0.999077727752645360f, -0.042938256934940779f, - -0.998795456205172410f, -0.049067674327417724f, - -0.998475580573294770f, -0.055195244349689851f, - -0.998118112900149180f, -0.061320736302208245f, - -0.997723066644191640f, -0.067443919563663926f, - -0.997290456678690210f, -0.073564563599667496f, - -0.996820299291165780f, -0.079682437971429945f, - -0.996312612182778000f, -0.085797312344439922f, - -0.995767414467659820f, -0.091908956497132516f, - -0.995184726672196930f, -0.098017140329560590f, - -0.994564570734255530f, -0.104121633872054320f, - -0.993906970002356060f, -0.110222207293883000f, - -0.993211949234794610f, -0.116318630911904470f, - -0.992479534598709970f, -0.122410675199216100f, - -0.991709753669099530f, -0.128498110793792840f, - -0.990902635427780010f, -0.134580708507126060f, - -0.990058210262297120f, -0.140658239332849290f, - -0.989176509964781010f, -0.146730474455361580f, - -0.988257567730749460f, -0.152797185258443440f, - -0.987301418157858430f, -0.158858143333861220f, - -0.986308097244598670f, -0.164913120489969890f, - -0.985277642388941330f, -0.170961888760300970f, - -0.984210092386929140f, -0.177004220412148690f, - -0.983105487431216400f, -0.183039887955140650f, - -0.981963869109555240f, -0.189068664149806110f, - -0.980785280403230430f, -0.195090322016128360f, - -0.979569765685440520f, -0.201104634842091760f, - -0.978317370719627650f, -0.207111376192218590f, - -0.977028142657754390f, -0.213110319916091200f, - -0.975702130038528570f, -0.219101240156869800f, - -0.974339382785575860f, -0.225083911359792610f, - -0.972939952205560180f, -0.231058108280671080f, - -0.971503890986251890f, -0.237023605994366950f, - -0.970031253194543970f, -0.242980179903263820f, - -0.968522094274417380f, -0.248927605745719870f, - -0.966976471044852180f, -0.254865659604514460f, - -0.965394441697689400f, -0.260794117915275630f, - -0.963776065795439950f, -0.266712757474898250f, - -0.962121404269041580f, -0.272621355449949030f, - -0.960430519415565900f, -0.278519689385052890f, - -0.958703474895871600f, -0.284407537211271820f, - -0.956940335732208940f, -0.290284677254462110f, - -0.955141168305770780f, -0.296150888243623790f, - -0.953306040354193970f, -0.302005949319227810f, - -0.951435020969008450f, -0.307849640041534810f, - -0.949528180593036790f, -0.313681740398891180f, - -0.947585591017741200f, -0.319502030816015580f, - -0.945607325380521280f, -0.325310292162262980f, - -0.943593458161960390f, -0.331106305759876260f, - -0.941544065183020810f, -0.336889853392220110f, - -0.939459223602190030f, -0.342660717311994210f, - -0.937339011912574960f, -0.348418680249434560f, - -0.935183509938947720f, -0.354163525420490120f, - -0.932992798834738960f, -0.359895036534988110f, - -0.930766961078983820f, -0.365612997804773580f, - -0.928506080473215590f, -0.371317193951837430f, - -0.926210242138311490f, -0.377007410216417930f, - -0.923879532511286850f, -0.382683432365089670f, - -0.921514039342041900f, -0.388345046698826360f, - -0.919113851690057770f, -0.393992040061047930f, - -0.916679059921042700f, -0.399624199845646840f, - -0.914209755703530690f, -0.405241314004989690f, - -0.911706032005429880f, -0.410843171057903910f, - -0.909167983090522490f, -0.416429560097636930f, - -0.906595704514915450f, -0.422000270799799630f, - -0.903989293123443450f, -0.427555093430281810f, - -0.901348847046022030f, -0.433093818853151850f, - -0.898674465693954040f, -0.438616238538527330f, - -0.895966249756185220f, -0.444122144570429090f, - -0.893224301195515320f, -0.449611329654606650f, - -0.890448723244757990f, -0.455083587126343670f, - -0.887639620402853930f, -0.460538710958240060f, - -0.884797098430937900f, -0.465976495767965960f, - -0.881921264348355050f, -0.471396736825997640f, - -0.879012226428633640f, -0.476799230063321870f, - -0.876070094195406600f, -0.482183772079122660f, - -0.873094978418290200f, -0.487550160148435660f, - -0.870086991108711460f, -0.492898192229783930f, - -0.867046245515692870f, -0.498227666972781540f, - -0.863972856121586810f, -0.503538383725717460f, - -0.860866938637767310f, -0.508830142543107100f, - -0.857728610000272120f, -0.514102744193221550f, - -0.854557988365400530f, -0.519355990165589640f, - -0.851355193105265310f, -0.524589682678468730f, - -0.848120344803297230f, -0.529803624686294610f, - -0.844853565249707230f, -0.534997619887096930f, - -0.841554977436898440f, -0.540171472729892850f, - -0.838224705554838190f, -0.545324988422046130f, - -0.834862874986380120f, -0.550457972936604700f, - -0.831469612302545460f, -0.555570233019601960f, - -0.828045045257755800f, -0.560661576197335920f, - -0.824589302785025290f, -0.565731810783613230f, - -0.821102514991104760f, -0.570780745886967140f, - -0.817584813151583710f, -0.575808191417845340f, - -0.814036329705948520f, -0.580813958095764300f, - -0.810457198252594770f, -0.585797857456438860f, - -0.806847553543799450f, -0.590759701858873940f, - -0.803207531480644940f, -0.595699304492433250f, - -0.799537269107905240f, -0.600616479383868640f, - -0.795836904608883570f, -0.605511041404325430f, - -0.792106577300212280f, -0.610382806276309480f, - -0.788346427626606340f, -0.615231590580626710f, - -0.784556597155575240f, -0.620057211763289210f, - -0.780737228572094600f, -0.624859488142386230f, - -0.776888465673232440f, -0.629638238914926980f, - -0.773010453362737100f, -0.634393284163645270f, - -0.769103337645579700f, -0.639124444863775730f, - -0.765167265622459070f, -0.643831542889791280f, - -0.761202385484261890f, -0.648514401022112330f, - -0.757208846506484790f, -0.653172842953776530f, - -0.753186799043612630f, -0.657806693297078530f, - -0.749136394523459260f, -0.662415777590171780f, - -0.745057785441466060f, -0.666999922303637360f, - -0.740951125354959110f, -0.671558954847018440f, - -0.736816568877370020f, -0.676092703575315810f, - -0.732654271672412820f, -0.680600997795453020f, - -0.728464390448225420f, -0.685083667772700130f, - -0.724247082951467000f, -0.689540544737066830f, - -0.720002507961381880f, -0.693971460889653780f, - -0.715730825283818710f, -0.698376249408972800f, - -0.711432195745216660f, -0.702754744457225080f, - -0.707106781186547680f, -0.707106781186547460f, - -0.702754744457225300f, -0.711432195745216430f, - -0.698376249408973030f, -0.715730825283818480f, - -0.693971460889654000f, -0.720002507961381650f, - -0.689540544737067050f, -0.724247082951466780f, - -0.685083667772700360f, -0.728464390448225200f, - -0.680600997795453240f, -0.732654271672412590f, - -0.676092703575316030f, -0.736816568877369790f, - -0.671558954847018660f, -0.740951125354958880f, - -0.666999922303637580f, -0.745057785441465840f, - -0.662415777590172010f, -0.749136394523459040f, - -0.657806693297078750f, -0.753186799043612410f, - -0.653172842953777090f, -0.757208846506484230f, - -0.648514401022112220f, -0.761202385484262000f, - -0.643831542889791500f, -0.765167265622458960f, - -0.639124444863775950f, -0.769103337645579480f, - -0.634393284163645930f, -0.773010453362736660f, - -0.629638238914926870f, -0.776888465673232550f, - -0.624859488142386450f, -0.780737228572094380f, - -0.620057211763289430f, -0.784556597155575020f, - -0.615231590580627260f, -0.788346427626605890f, - -0.610382806276309360f, -0.792106577300212390f, - -0.605511041404325660f, -0.795836904608883460f, - -0.600616479383869310f, -0.799537269107904790f, - -0.595699304492433130f, -0.803207531480645050f, - -0.590759701858874280f, -0.806847553543799220f, - -0.585797857456439090f, -0.810457198252594660f, - -0.580813958095764970f, -0.814036329705948080f, - -0.575808191417845230f, -0.817584813151583820f, - -0.570780745886967370f, -0.821102514991104650f, - -0.565731810783613450f, -0.824589302785025070f, - -0.560661576197336480f, -0.828045045257755460f, - -0.555570233019602180f, -0.831469612302545240f, - -0.550457972936604920f, -0.834862874986380010f, - -0.545324988422046800f, -0.838224705554837860f, - -0.540171472729892740f, -0.841554977436898550f, - -0.534997619887097260f, -0.844853565249707010f, - -0.529803624686294940f, -0.848120344803297120f, - -0.524589682678469390f, -0.851355193105264860f, - -0.519355990165589420f, -0.854557988365400640f, - -0.514102744193221770f, -0.857728610000272010f, - -0.508830142543107320f, -0.860866938637767090f, - -0.503538383725718020f, -0.863972856121586470f, - -0.498227666972781810f, -0.867046245515692650f, - -0.492898192229784200f, -0.870086991108711350f, - -0.487550160148436330f, -0.873094978418289870f, - -0.482183772079122550f, -0.876070094195406710f, - -0.476799230063322140f, -0.879012226428633410f, - -0.471396736825997860f, -0.881921264348354940f, - -0.465976495767966630f, -0.884797098430937570f, - -0.460538710958239890f, -0.887639620402854050f, - -0.455083587126343950f, -0.890448723244757880f, - -0.449611329654606930f, -0.893224301195515210f, - -0.444122144570429760f, -0.895966249756184880f, - -0.438616238538527600f, -0.898674465693953820f, - -0.433093818853152120f, -0.901348847046021920f, - -0.427555093430282470f, -0.903989293123443120f, - -0.422000270799799520f, -0.906595704514915450f, - -0.416429560097637210f, -0.909167983090522380f, - -0.410843171057904190f, -0.911706032005429770f, - -0.405241314004990360f, -0.914209755703530470f, - -0.399624199845646730f, -0.916679059921042700f, - -0.393992040061048210f, -0.919113851690057660f, - -0.388345046698826630f, -0.921514039342041790f, - -0.382683432365090340f, -0.923879532511286520f, - -0.377007410216418200f, -0.926210242138311380f, - -0.371317193951837770f, -0.928506080473215480f, - -0.365612997804774300f, -0.930766961078983600f, - -0.359895036534987940f, -0.932992798834738960f, - -0.354163525420490450f, -0.935183509938947610f, - -0.348418680249434840f, -0.937339011912574850f, - -0.342660717311994880f, -0.939459223602189700f, - -0.336889853392219940f, -0.941544065183020810f, - -0.331106305759876540f, -0.943593458161960270f, - -0.325310292162263310f, -0.945607325380521170f, - -0.319502030816015410f, -0.947585591017741200f, - -0.313681740398891460f, -0.949528180593036670f, - -0.307849640041535090f, -0.951435020969008340f, - -0.302005949319228530f, -0.953306040354193750f, - -0.296150888243623680f, -0.955141168305770780f, - -0.290284677254462440f, -0.956940335732208820f, - -0.284407537211272150f, -0.958703474895871490f, - -0.278519689385053610f, -0.960430519415565680f, - -0.272621355449948870f, -0.962121404269041580f, - -0.266712757474898530f, -0.963776065795439840f, - -0.260794117915275900f, -0.965394441697689290f, - -0.254865659604514350f, -0.966976471044852180f, - -0.248927605745720150f, -0.968522094274417270f, - -0.242980179903264120f, -0.970031253194543970f, - -0.237023605994367670f, -0.971503890986251670f, - -0.231058108280670940f, -0.972939952205560180f, - -0.225083911359792920f, -0.974339382785575860f, - -0.219101240156870100f, -0.975702130038528460f, - -0.213110319916091920f, -0.977028142657754280f, - -0.207111376192218480f, -0.978317370719627650f, - -0.201104634842092070f, -0.979569765685440520f, - -0.195090322016128660f, -0.980785280403230320f, - -0.189068664149805970f, -0.981963869109555350f, - -0.183039887955140950f, -0.983105487431216290f, - -0.177004220412149000f, -0.984210092386929030f, - -0.170961888760301690f, -0.985277642388941110f, - -0.164913120489969760f, -0.986308097244598670f, - -0.158858143333861530f, -0.987301418157858320f, - -0.152797185258443740f, -0.988257567730749460f, - -0.146730474455362300f, -0.989176509964780900f, - -0.140658239332849160f, -0.990058210262297120f, - -0.134580708507126360f, -0.990902635427780010f, - -0.128498110793793590f, -0.991709753669099530f, - -0.122410675199215960f, -0.992479534598710080f, - -0.116318630911904770f, -0.993211949234794500f, - -0.110222207293883310f, -0.993906970002356060f, - -0.104121633872055070f, -0.994564570734255420f, - -0.098017140329560451f, -0.995184726672196930f, - -0.091908956497132821f, -0.995767414467659820f, - -0.085797312344440227f, -0.996312612182778000f, - -0.079682437971430695f, -0.996820299291165670f, - -0.073564563599667357f, -0.997290456678690210f, - -0.067443919563664231f, -0.997723066644191640f, - -0.061320736302208995f, -0.998118112900149180f, - -0.055195244349689712f, -0.998475580573294770f, - -0.049067674327418029f, -0.998795456205172410f, - -0.042938256934941084f, -0.999077727752645360f, - -0.036807222941359331f, -0.999322384588349430f, - -0.030674803176636484f, -0.999529417501093140f, - -0.024541228522912389f, -0.999698818696204250f, - -0.018406729905805164f, -0.999830581795823400f, - -0.012271538285720512f, -0.999924701839144500f, - -0.006135884649154416f, -0.999981175282601110f, - -0.000000000000000184f, -1.000000000000000000f, - 0.006135884649154049f, -0.999981175282601110f, - 0.012271538285720144f, -0.999924701839144500f, - 0.018406729905804796f, -0.999830581795823400f, - 0.024541228522912021f, -0.999698818696204250f, - 0.030674803176636116f, -0.999529417501093140f, - 0.036807222941358964f, -0.999322384588349540f, - 0.042938256934940716f, -0.999077727752645360f, - 0.049067674327417661f, -0.998795456205172410f, - 0.055195244349689344f, -0.998475580573294770f, - 0.061320736302208627f, -0.998118112900149180f, - 0.067443919563663871f, -0.997723066644191640f, - 0.073564563599666982f, -0.997290456678690210f, - 0.079682437971430334f, -0.996820299291165670f, - 0.085797312344439852f, -0.996312612182778000f, - 0.091908956497132446f, -0.995767414467659820f, - 0.098017140329560090f, -0.995184726672196930f, - 0.104121633872054700f, -0.994564570734255420f, - 0.110222207293882930f, -0.993906970002356060f, - 0.116318630911904410f, -0.993211949234794610f, - 0.122410675199215600f, -0.992479534598710080f, - 0.128498110793793220f, -0.991709753669099530f, - 0.134580708507125970f, -0.990902635427780010f, - 0.140658239332848790f, -0.990058210262297120f, - 0.146730474455361940f, -0.989176509964780900f, - 0.152797185258443380f, -0.988257567730749460f, - 0.158858143333861170f, -0.987301418157858430f, - 0.164913120489969390f, -0.986308097244598780f, - 0.170961888760301330f, -0.985277642388941220f, - 0.177004220412148640f, -0.984210092386929140f, - 0.183039887955140590f, -0.983105487431216400f, - 0.189068664149805610f, -0.981963869109555350f, - 0.195090322016128300f, -0.980785280403230430f, - 0.201104634842091710f, -0.979569765685440630f, - 0.207111376192218120f, -0.978317370719627770f, - 0.213110319916091560f, -0.977028142657754280f, - 0.219101240156869740f, -0.975702130038528570f, - 0.225083911359792550f, -0.974339382785575970f, - 0.231058108280670580f, -0.972939952205560290f, - 0.237023605994367310f, -0.971503890986251780f, - 0.242980179903263760f, -0.970031253194543970f, - 0.248927605745719790f, -0.968522094274417380f, - 0.254865659604513960f, -0.966976471044852290f, - 0.260794117915275510f, -0.965394441697689400f, - 0.266712757474898200f, -0.963776065795439950f, - 0.272621355449948530f, -0.962121404269041690f, - 0.278519689385053280f, -0.960430519415565790f, - 0.284407537211271770f, -0.958703474895871600f, - 0.290284677254462050f, -0.956940335732208940f, - 0.296150888243623290f, -0.955141168305770890f, - 0.302005949319228140f, -0.953306040354193860f, - 0.307849640041534760f, -0.951435020969008450f, - 0.313681740398891130f, -0.949528180593036790f, - 0.319502030816015080f, -0.947585591017741310f, - 0.325310292162262930f, -0.945607325380521280f, - 0.331106305759876210f, -0.943593458161960390f, - 0.336889853392219610f, -0.941544065183020920f, - 0.342660717311994540f, -0.939459223602189810f, - 0.348418680249434510f, -0.937339011912574960f, - 0.354163525420490070f, -0.935183509938947720f, - 0.359895036534987610f, -0.932992798834739070f, - 0.365612997804773960f, -0.930766961078983710f, - 0.371317193951837380f, -0.928506080473215590f, - 0.377007410216417870f, -0.926210242138311490f, - 0.382683432365090000f, -0.923879532511286630f, - 0.388345046698826300f, -0.921514039342041900f, - 0.393992040061047880f, -0.919113851690057880f, - 0.399624199845646400f, -0.916679059921042820f, - 0.405241314004990030f, -0.914209755703530580f, - 0.410843171057903860f, -0.911706032005429880f, - 0.416429560097636870f, -0.909167983090522490f, - 0.422000270799799180f, -0.906595704514915560f, - 0.427555093430282140f, -0.903989293123443340f, - 0.433093818853151790f, -0.901348847046022140f, - 0.438616238538527270f, -0.898674465693954040f, - 0.444122144570429420f, -0.895966249756185000f, - 0.449611329654606600f, -0.893224301195515320f, - 0.455083587126343610f, -0.890448723244757990f, - 0.460538710958239560f, -0.887639620402854160f, - 0.465976495767966290f, -0.884797098430937680f, - 0.471396736825997590f, -0.881921264348355050f, - 0.476799230063321870f, -0.879012226428633640f, - 0.482183772079122220f, -0.876070094195406930f, - 0.487550160148436000f, -0.873094978418290090f, - 0.492898192229783870f, -0.870086991108711460f, - 0.498227666972781480f, -0.867046245515692870f, - 0.503538383725717800f, -0.863972856121586590f, - 0.508830142543106990f, -0.860866938637767310f, - 0.514102744193221550f, -0.857728610000272230f, - 0.519355990165589200f, -0.854557988365400760f, - 0.524589682678469060f, -0.851355193105265080f, - 0.529803624686294610f, -0.848120344803297340f, - 0.534997619887096930f, -0.844853565249707230f, - 0.540171472729892410f, -0.841554977436898780f, - 0.545324988422046460f, -0.838224705554837970f, - 0.550457972936604700f, -0.834862874986380120f, - 0.555570233019601840f, -0.831469612302545460f, - 0.560661576197336250f, -0.828045045257755690f, - 0.565731810783613120f, -0.824589302785025290f, - 0.570780745886967030f, -0.821102514991104870f, - 0.575808191417844890f, -0.817584813151584040f, - 0.580813958095764640f, -0.814036329705948300f, - 0.585797857456438750f, -0.810457198252594880f, - 0.590759701858873940f, -0.806847553543799450f, - 0.595699304492432910f, -0.803207531480645280f, - 0.600616479383868970f, -0.799537269107905010f, - 0.605511041404325320f, -0.795836904608883680f, - 0.610382806276309140f, -0.792106577300212610f, - 0.615231590580627040f, -0.788346427626606120f, - 0.620057211763289100f, -0.784556597155575240f, - 0.624859488142386120f, -0.780737228572094600f, - 0.629638238914926650f, -0.776888465673232780f, - 0.634393284163645600f, -0.773010453362736880f, - 0.639124444863775620f, -0.769103337645579700f, - 0.643831542889791160f, -0.765167265622459180f, - 0.648514401022112000f, -0.761202385484262220f, - 0.653172842953776760f, -0.757208846506484570f, - 0.657806693297078530f, -0.753186799043612630f, - 0.662415777590171450f, -0.749136394523459590f, - 0.666999922303637690f, -0.745057785441465840f, - 0.671558954847018330f, -0.740951125354959110f, - 0.676092703575315700f, -0.736816568877370020f, - 0.680600997795452690f, -0.732654271672413150f, - 0.685083667772700470f, -0.728464390448225090f, - 0.689540544737066830f, -0.724247082951467000f, - 0.693971460889653780f, -0.720002507961381880f, - 0.698376249408972360f, -0.715730825283819040f, - 0.702754744457225300f, -0.711432195745216430f, - 0.707106781186547350f, -0.707106781186547680f, - 0.711432195745216100f, -0.702754744457225630f, - 0.715730825283818820f, -0.698376249408972690f, - 0.720002507961381540f, -0.693971460889654000f, - 0.724247082951466670f, -0.689540544737067160f, - 0.728464390448224860f, -0.685083667772700800f, - 0.732654271672412930f, -0.680600997795453020f, - 0.736816568877369790f, -0.676092703575316030f, - 0.740951125354958880f, -0.671558954847018660f, - 0.745057785441465500f, -0.666999922303638030f, - 0.749136394523459370f, -0.662415777590171780f, - 0.753186799043612300f, -0.657806693297078860f, - 0.757208846506484230f, -0.653172842953777090f, - 0.761202385484261890f, -0.648514401022112330f, - 0.765167265622458850f, -0.643831542889791500f, - 0.769103337645579480f, -0.639124444863775950f, - 0.773010453362736660f, -0.634393284163645930f, - 0.776888465673232550f, -0.629638238914926980f, - 0.780737228572094380f, -0.624859488142386450f, - 0.784556597155575020f, -0.620057211763289540f, - 0.788346427626605890f, -0.615231590580627370f, - 0.792106577300212390f, -0.610382806276309480f, - 0.795836904608883340f, -0.605511041404325660f, - 0.799537269107904790f, -0.600616479383869310f, - 0.803207531480645050f, -0.595699304492433250f, - 0.806847553543799220f, -0.590759701858874280f, - 0.810457198252594660f, -0.585797857456439090f, - 0.814036329705948080f, -0.580813958095764970f, - 0.817584813151583710f, -0.575808191417845230f, - 0.821102514991104540f, -0.570780745886967370f, - 0.824589302785025070f, -0.565731810783613560f, - 0.828045045257755350f, -0.560661576197336590f, - 0.831469612302545240f, -0.555570233019602180f, - 0.834862874986379900f, -0.550457972936605030f, - 0.838224705554837750f, -0.545324988422046800f, - 0.841554977436898440f, -0.540171472729892740f, - 0.844853565249707010f, -0.534997619887097260f, - 0.848120344803297120f, -0.529803624686294940f, - 0.851355193105264860f, -0.524589682678469390f, - 0.854557988365400530f, -0.519355990165589530f, - 0.857728610000272010f, -0.514102744193221880f, - 0.860866938637767090f, -0.508830142543107430f, - 0.863972856121586360f, -0.503538383725718130f, - 0.867046245515692650f, -0.498227666972781870f, - 0.870086991108711350f, -0.492898192229784260f, - 0.873094978418289870f, -0.487550160148436380f, - 0.876070094195406710f, -0.482183772079122610f, - 0.879012226428633410f, -0.476799230063322200f, - 0.881921264348354830f, -0.471396736825997920f, - 0.884797098430937460f, -0.465976495767966680f, - 0.887639620402853930f, -0.460538710958239950f, - 0.890448723244757770f, -0.455083587126344000f, - 0.893224301195515100f, -0.449611329654606980f, - 0.895966249756184880f, -0.444122144570429810f, - 0.898674465693953820f, -0.438616238538527660f, - 0.901348847046021920f, -0.433093818853152180f, - 0.903989293123443120f, -0.427555093430282530f, - 0.906595704514915450f, -0.422000270799799570f, - 0.909167983090522380f, -0.416429560097637260f, - 0.911706032005429660f, -0.410843171057904240f, - 0.914209755703530470f, -0.405241314004990420f, - 0.916679059921042700f, -0.399624199845646790f, - 0.919113851690057660f, -0.393992040061048270f, - 0.921514039342041790f, -0.388345046698826690f, - 0.923879532511286520f, -0.382683432365090390f, - 0.926210242138311380f, -0.377007410216418260f, - 0.928506080473215480f, -0.371317193951837820f, - 0.930766961078983490f, -0.365612997804774350f, - 0.932992798834738960f, -0.359895036534988000f, - 0.935183509938947500f, -0.354163525420490510f, - 0.937339011912574850f, -0.348418680249434900f, - 0.939459223602189700f, -0.342660717311994930f, - 0.941544065183020810f, -0.336889853392220000f, - 0.943593458161960270f, -0.331106305759876600f, - 0.945607325380521170f, -0.325310292162263370f, - 0.947585591017741200f, -0.319502030816015470f, - 0.949528180593036670f, -0.313681740398891520f, - 0.951435020969008340f, -0.307849640041535140f, - 0.953306040354193640f, -0.302005949319228580f, - 0.955141168305770780f, -0.296150888243623730f, - 0.956940335732208820f, -0.290284677254462500f, - 0.958703474895871490f, -0.284407537211272210f, - 0.960430519415565680f, -0.278519689385053670f, - 0.962121404269041580f, -0.272621355449948980f, - 0.963776065795439840f, -0.266712757474898590f, - 0.965394441697689290f, -0.260794117915275960f, - 0.966976471044852180f, -0.254865659604514410f, - 0.968522094274417270f, -0.248927605745720200f, - 0.970031253194543970f, -0.242980179903264180f, - 0.971503890986251670f, -0.237023605994367730f, - 0.972939952205560180f, -0.231058108280671000f, - 0.974339382785575860f, -0.225083911359792970f, - 0.975702130038528460f, -0.219101240156870160f, - 0.977028142657754170f, -0.213110319916091970f, - 0.978317370719627650f, -0.207111376192218530f, - 0.979569765685440520f, -0.201104634842092120f, - 0.980785280403230320f, -0.195090322016128720f, - 0.981963869109555350f, -0.189068664149806030f, - 0.983105487431216290f, -0.183039887955141010f, - 0.984210092386929030f, -0.177004220412149050f, - 0.985277642388941110f, -0.170961888760301770f, - 0.986308097244598670f, -0.164913120489969810f, - 0.987301418157858320f, -0.158858143333861580f, - 0.988257567730749460f, -0.152797185258443800f, - 0.989176509964780900f, -0.146730474455362390f, - 0.990058210262297120f, -0.140658239332849210f, - 0.990902635427780010f, -0.134580708507126420f, - 0.991709753669099410f, -0.128498110793793640f, - 0.992479534598709970f, -0.122410675199216030f, - 0.993211949234794500f, -0.116318630911904840f, - 0.993906970002356060f, -0.110222207293883360f, - 0.994564570734255420f, -0.104121633872055130f, - 0.995184726672196930f, -0.098017140329560506f, - 0.995767414467659820f, -0.091908956497132877f, - 0.996312612182778000f, -0.085797312344440282f, - 0.996820299291165670f, -0.079682437971430750f, - 0.997290456678690210f, -0.073564563599667412f, - 0.997723066644191640f, -0.067443919563664287f, - 0.998118112900149180f, -0.061320736302209057f, - 0.998475580573294770f, -0.055195244349689775f, - 0.998795456205172410f, -0.049067674327418091f, - 0.999077727752645360f, -0.042938256934941139f, - 0.999322384588349430f, -0.036807222941359394f, - 0.999529417501093140f, -0.030674803176636543f, - 0.999698818696204250f, -0.024541228522912448f, - 0.999830581795823400f, -0.018406729905805226f, - 0.999924701839144500f, -0.012271538285720572f, - 0.999981175282601110f, -0.006135884649154477f -}; - -/** -* @brief Initialization function for the floating-point CFFT/CIFFT. -* @param[in,out] *S points to an instance of the floating-point CFFT/CIFFT structure. -* @param[in] fftLen length of the FFT. -* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. -* -* \par Description: -* \par -* The parameter ifftFlag controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. -* \par -* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. -*/ - -arm_status arm_cfft_radix4_init_f32( - arm_cfft_radix4_instance_f32 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialise the FFT length */ - S->fftLen = fftLen; - - /* Initialise the Twiddle coefficient pointer */ - S->pTwiddle = (float32_t *) twiddleCoef; - - /* Initialise the Flag for selection of CFFT or CIFFT */ - S->ifftFlag = ifftFlag; - - /* Initialise the Flag for calculation Bit reversal or not */ - S->bitReverseFlag = bitReverseFlag; - - /* Initializations of structure parameters depending on the FFT length */ - switch (S->fftLen) - { - - case 1024u: - /* Initializations of structure parameters for 1024 point FFT */ - - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 1u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 1u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = armBitRevTable; - /* Initialise the 1/fftLen Value */ - S->onebyfftLen = 0.0009765625f; - break; - - - case 256u: - /* Initializations of structure parameters for 256 point FFT */ - S->twidCoefModifier = 4u; - S->bitRevFactor = 4u; - S->pBitRevTable = &armBitRevTable[3]; - S->onebyfftLen = 0.00390625f; - break; - - case 64u: - /* Initializations of structure parameters for 64 point FFT */ - S->twidCoefModifier = 16u; - S->bitRevFactor = 16u; - S->pBitRevTable = &armBitRevTable[15]; - S->onebyfftLen = 0.015625f; - break; - - case 16u: - /* Initializations of structure parameters for 16 point FFT */ - S->twidCoefModifier = 64u; - S->bitRevFactor = 64u; - S->pBitRevTable = &armBitRevTable[63]; - S->onebyfftLen = 0.0625f; - break; - - - default: - /* Reporting argument error if fftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - return (status); -} - -/** - * @} end of CFFT_CIFFT group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_cfft_radix4_init_f32.c +* +* Description: Radix-4 Decimation in Frequency Floating-point CFFT & CIFFT Initialization function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + + +#include "arm_math.h" +#include "arm_common_tables.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup CFFT_CIFFT + * @{ + */ + +/* +* @brief Floating-point Twiddle factors Table Generation +*/ + + +/** +* \par +* Example code for Floating-point Twiddle factors Generation: +* \par +*
for(i = 0; i< N; i++)   
+* {   
+*	twiddleCoef[2*i]= cos(i * 2*PI/(float)N);   
+*	twiddleCoef[2*i+1]= sin(i * 2*PI/(float)N);   
+* } 
+* \par +* where N = 1024 and PI = 3.14159265358979 +* \par +* Cos and Sin values are in interleaved fashion +* +*/ + +static const float32_t twiddleCoef[2048] = { + 1.000000000000000000f, 0.000000000000000000f, + 0.999981175282601110f, 0.006135884649154475f, + 0.999924701839144500f, 0.012271538285719925f, + 0.999830581795823400f, 0.018406729905804820f, + 0.999698818696204250f, 0.024541228522912288f, + 0.999529417501093140f, 0.030674803176636626f, + 0.999322384588349540f, 0.036807222941358832f, + 0.999077727752645360f, 0.042938256934940820f, + 0.998795456205172410f, 0.049067674327418015f, + 0.998475580573294770f, 0.055195244349689934f, + 0.998118112900149180f, 0.061320736302208578f, + 0.997723066644191640f, 0.067443919563664051f, + 0.997290456678690210f, 0.073564563599667426f, + 0.996820299291165670f, 0.079682437971430126f, + 0.996312612182778000f, 0.085797312344439894f, + 0.995767414467659820f, 0.091908956497132724f, + 0.995184726672196930f, 0.098017140329560604f, + 0.994564570734255420f, 0.104121633872054590f, + 0.993906970002356060f, 0.110222207293883060f, + 0.993211949234794500f, 0.116318630911904750f, + 0.992479534598709970f, 0.122410675199216200f, + 0.991709753669099530f, 0.128498110793793170f, + 0.990902635427780010f, 0.134580708507126170f, + 0.990058210262297120f, 0.140658239332849210f, + 0.989176509964781010f, 0.146730474455361750f, + 0.988257567730749460f, 0.152797185258443440f, + 0.987301418157858430f, 0.158858143333861450f, + 0.986308097244598670f, 0.164913120489969890f, + 0.985277642388941220f, 0.170961888760301220f, + 0.984210092386929030f, 0.177004220412148750f, + 0.983105487431216290f, 0.183039887955140950f, + 0.981963869109555240f, 0.189068664149806190f, + 0.980785280403230430f, 0.195090322016128250f, + 0.979569765685440520f, 0.201104634842091900f, + 0.978317370719627650f, 0.207111376192218560f, + 0.977028142657754390f, 0.213110319916091360f, + 0.975702130038528570f, 0.219101240156869800f, + 0.974339382785575860f, 0.225083911359792830f, + 0.972939952205560180f, 0.231058108280671110f, + 0.971503890986251780f, 0.237023605994367200f, + 0.970031253194543970f, 0.242980179903263870f, + 0.968522094274417380f, 0.248927605745720150f, + 0.966976471044852070f, 0.254865659604514570f, + 0.965394441697689400f, 0.260794117915275510f, + 0.963776065795439840f, 0.266712757474898370f, + 0.962121404269041580f, 0.272621355449948980f, + 0.960430519415565790f, 0.278519689385053060f, + 0.958703474895871600f, 0.284407537211271880f, + 0.956940335732208820f, 0.290284677254462330f, + 0.955141168305770780f, 0.296150888243623790f, + 0.953306040354193860f, 0.302005949319228080f, + 0.951435020969008340f, 0.307849640041534870f, + 0.949528180593036670f, 0.313681740398891520f, + 0.947585591017741090f, 0.319502030816015690f, + 0.945607325380521280f, 0.325310292162262930f, + 0.943593458161960390f, 0.331106305759876430f, + 0.941544065183020810f, 0.336889853392220050f, + 0.939459223602189920f, 0.342660717311994380f, + 0.937339011912574960f, 0.348418680249434560f, + 0.935183509938947610f, 0.354163525420490340f, + 0.932992798834738960f, 0.359895036534988110f, + 0.930766961078983710f, 0.365612997804773850f, + 0.928506080473215590f, 0.371317193951837540f, + 0.926210242138311380f, 0.377007410216418260f, + 0.923879532511286740f, 0.382683432365089780f, + 0.921514039342042010f, 0.388345046698826250f, + 0.919113851690057770f, 0.393992040061048100f, + 0.916679059921042700f, 0.399624199845646790f, + 0.914209755703530690f, 0.405241314004989860f, + 0.911706032005429880f, 0.410843171057903910f, + 0.909167983090522380f, 0.416429560097637150f, + 0.906595704514915330f, 0.422000270799799680f, + 0.903989293123443340f, 0.427555093430282080f, + 0.901348847046022030f, 0.433093818853151960f, + 0.898674465693953820f, 0.438616238538527660f, + 0.895966249756185220f, 0.444122144570429200f, + 0.893224301195515320f, 0.449611329654606540f, + 0.890448723244757880f, 0.455083587126343840f, + 0.887639620402853930f, 0.460538710958240010f, + 0.884797098430937790f, 0.465976495767966180f, + 0.881921264348355050f, 0.471396736825997640f, + 0.879012226428633530f, 0.476799230063322090f, + 0.876070094195406600f, 0.482183772079122720f, + 0.873094978418290090f, 0.487550160148436000f, + 0.870086991108711460f, 0.492898192229784040f, + 0.867046245515692650f, 0.498227666972781870f, + 0.863972856121586810f, 0.503538383725717580f, + 0.860866938637767310f, 0.508830142543106990f, + 0.857728610000272120f, 0.514102744193221660f, + 0.854557988365400530f, 0.519355990165589640f, + 0.851355193105265200f, 0.524589682678468950f, + 0.848120344803297230f, 0.529803624686294610f, + 0.844853565249707120f, 0.534997619887097150f, + 0.841554977436898440f, 0.540171472729892850f, + 0.838224705554838080f, 0.545324988422046460f, + 0.834862874986380010f, 0.550457972936604810f, + 0.831469612302545240f, 0.555570233019602180f, + 0.828045045257755800f, 0.560661576197336030f, + 0.824589302785025290f, 0.565731810783613120f, + 0.821102514991104650f, 0.570780745886967260f, + 0.817584813151583710f, 0.575808191417845340f, + 0.814036329705948410f, 0.580813958095764530f, + 0.810457198252594770f, 0.585797857456438860f, + 0.806847553543799330f, 0.590759701858874160f, + 0.803207531480644940f, 0.595699304492433360f, + 0.799537269107905010f, 0.600616479383868970f, + 0.795836904608883570f, 0.605511041404325550f, + 0.792106577300212390f, 0.610382806276309480f, + 0.788346427626606340f, 0.615231590580626820f, + 0.784556597155575240f, 0.620057211763289100f, + 0.780737228572094490f, 0.624859488142386340f, + 0.776888465673232440f, 0.629638238914926980f, + 0.773010453362736990f, 0.634393284163645490f, + 0.769103337645579700f, 0.639124444863775730f, + 0.765167265622458960f, 0.643831542889791390f, + 0.761202385484261780f, 0.648514401022112440f, + 0.757208846506484570f, 0.653172842953776760f, + 0.753186799043612520f, 0.657806693297078640f, + 0.749136394523459370f, 0.662415777590171780f, + 0.745057785441466060f, 0.666999922303637470f, + 0.740951125354959110f, 0.671558954847018330f, + 0.736816568877369900f, 0.676092703575315920f, + 0.732654271672412820f, 0.680600997795453020f, + 0.728464390448225200f, 0.685083667772700360f, + 0.724247082951467000f, 0.689540544737066830f, + 0.720002507961381650f, 0.693971460889654000f, + 0.715730825283818590f, 0.698376249408972920f, + 0.711432195745216430f, 0.702754744457225300f, + 0.707106781186547570f, 0.707106781186547460f, + 0.702754744457225300f, 0.711432195745216430f, + 0.698376249408972920f, 0.715730825283818590f, + 0.693971460889654000f, 0.720002507961381650f, + 0.689540544737066940f, 0.724247082951466890f, + 0.685083667772700360f, 0.728464390448225200f, + 0.680600997795453130f, 0.732654271672412820f, + 0.676092703575316030f, 0.736816568877369790f, + 0.671558954847018330f, 0.740951125354959110f, + 0.666999922303637470f, 0.745057785441465950f, + 0.662415777590171780f, 0.749136394523459260f, + 0.657806693297078640f, 0.753186799043612410f, + 0.653172842953776760f, 0.757208846506484460f, + 0.648514401022112550f, 0.761202385484261780f, + 0.643831542889791500f, 0.765167265622458960f, + 0.639124444863775730f, 0.769103337645579590f, + 0.634393284163645490f, 0.773010453362736990f, + 0.629638238914927100f, 0.776888465673232440f, + 0.624859488142386450f, 0.780737228572094380f, + 0.620057211763289210f, 0.784556597155575240f, + 0.615231590580626820f, 0.788346427626606230f, + 0.610382806276309480f, 0.792106577300212390f, + 0.605511041404325550f, 0.795836904608883460f, + 0.600616479383868970f, 0.799537269107905010f, + 0.595699304492433470f, 0.803207531480644830f, + 0.590759701858874280f, 0.806847553543799220f, + 0.585797857456438860f, 0.810457198252594770f, + 0.580813958095764530f, 0.814036329705948300f, + 0.575808191417845340f, 0.817584813151583710f, + 0.570780745886967370f, 0.821102514991104650f, + 0.565731810783613230f, 0.824589302785025290f, + 0.560661576197336030f, 0.828045045257755800f, + 0.555570233019602290f, 0.831469612302545240f, + 0.550457972936604810f, 0.834862874986380010f, + 0.545324988422046460f, 0.838224705554837970f, + 0.540171472729892970f, 0.841554977436898330f, + 0.534997619887097260f, 0.844853565249707010f, + 0.529803624686294830f, 0.848120344803297120f, + 0.524589682678468840f, 0.851355193105265200f, + 0.519355990165589530f, 0.854557988365400530f, + 0.514102744193221660f, 0.857728610000272120f, + 0.508830142543106990f, 0.860866938637767310f, + 0.503538383725717580f, 0.863972856121586700f, + 0.498227666972781870f, 0.867046245515692650f, + 0.492898192229784090f, 0.870086991108711350f, + 0.487550160148436050f, 0.873094978418290090f, + 0.482183772079122830f, 0.876070094195406600f, + 0.476799230063322250f, 0.879012226428633410f, + 0.471396736825997810f, 0.881921264348354940f, + 0.465976495767966130f, 0.884797098430937790f, + 0.460538710958240010f, 0.887639620402853930f, + 0.455083587126343840f, 0.890448723244757880f, + 0.449611329654606600f, 0.893224301195515320f, + 0.444122144570429260f, 0.895966249756185110f, + 0.438616238538527710f, 0.898674465693953820f, + 0.433093818853152010f, 0.901348847046022030f, + 0.427555093430282200f, 0.903989293123443340f, + 0.422000270799799790f, 0.906595704514915330f, + 0.416429560097637320f, 0.909167983090522270f, + 0.410843171057903910f, 0.911706032005429880f, + 0.405241314004989860f, 0.914209755703530690f, + 0.399624199845646790f, 0.916679059921042700f, + 0.393992040061048100f, 0.919113851690057770f, + 0.388345046698826300f, 0.921514039342041900f, + 0.382683432365089840f, 0.923879532511286740f, + 0.377007410216418310f, 0.926210242138311270f, + 0.371317193951837600f, 0.928506080473215480f, + 0.365612997804773960f, 0.930766961078983710f, + 0.359895036534988280f, 0.932992798834738850f, + 0.354163525420490510f, 0.935183509938947500f, + 0.348418680249434510f, 0.937339011912574960f, + 0.342660717311994380f, 0.939459223602189920f, + 0.336889853392220050f, 0.941544065183020810f, + 0.331106305759876430f, 0.943593458161960390f, + 0.325310292162262980f, 0.945607325380521280f, + 0.319502030816015750f, 0.947585591017741090f, + 0.313681740398891570f, 0.949528180593036670f, + 0.307849640041534980f, 0.951435020969008340f, + 0.302005949319228200f, 0.953306040354193750f, + 0.296150888243623960f, 0.955141168305770670f, + 0.290284677254462330f, 0.956940335732208940f, + 0.284407537211271820f, 0.958703474895871600f, + 0.278519689385053060f, 0.960430519415565790f, + 0.272621355449948980f, 0.962121404269041580f, + 0.266712757474898420f, 0.963776065795439840f, + 0.260794117915275570f, 0.965394441697689400f, + 0.254865659604514630f, 0.966976471044852070f, + 0.248927605745720260f, 0.968522094274417270f, + 0.242980179903263980f, 0.970031253194543970f, + 0.237023605994367340f, 0.971503890986251780f, + 0.231058108280671280f, 0.972939952205560070f, + 0.225083911359792780f, 0.974339382785575860f, + 0.219101240156869770f, 0.975702130038528570f, + 0.213110319916091360f, 0.977028142657754390f, + 0.207111376192218560f, 0.978317370719627650f, + 0.201104634842091960f, 0.979569765685440520f, + 0.195090322016128330f, 0.980785280403230430f, + 0.189068664149806280f, 0.981963869109555240f, + 0.183039887955141060f, 0.983105487431216290f, + 0.177004220412148860f, 0.984210092386929030f, + 0.170961888760301360f, 0.985277642388941220f, + 0.164913120489970090f, 0.986308097244598670f, + 0.158858143333861390f, 0.987301418157858430f, + 0.152797185258443410f, 0.988257567730749460f, + 0.146730474455361750f, 0.989176509964781010f, + 0.140658239332849240f, 0.990058210262297120f, + 0.134580708507126220f, 0.990902635427780010f, + 0.128498110793793220f, 0.991709753669099530f, + 0.122410675199216280f, 0.992479534598709970f, + 0.116318630911904880f, 0.993211949234794500f, + 0.110222207293883180f, 0.993906970002356060f, + 0.104121633872054730f, 0.994564570734255420f, + 0.098017140329560770f, 0.995184726672196820f, + 0.091908956497132696f, 0.995767414467659820f, + 0.085797312344439880f, 0.996312612182778000f, + 0.079682437971430126f, 0.996820299291165670f, + 0.073564563599667454f, 0.997290456678690210f, + 0.067443919563664106f, 0.997723066644191640f, + 0.061320736302208648f, 0.998118112900149180f, + 0.055195244349690031f, 0.998475580573294770f, + 0.049067674327418126f, 0.998795456205172410f, + 0.042938256934940959f, 0.999077727752645360f, + 0.036807222941358991f, 0.999322384588349540f, + 0.030674803176636581f, 0.999529417501093140f, + 0.024541228522912264f, 0.999698818696204250f, + 0.018406729905804820f, 0.999830581795823400f, + 0.012271538285719944f, 0.999924701839144500f, + 0.006135884649154515f, 0.999981175282601110f, + 0.000000000000000061f, 1.000000000000000000f, + -0.006135884649154393f, 0.999981175282601110f, + -0.012271538285719823f, 0.999924701839144500f, + -0.018406729905804695f, 0.999830581795823400f, + -0.024541228522912142f, 0.999698818696204250f, + -0.030674803176636459f, 0.999529417501093140f, + -0.036807222941358866f, 0.999322384588349540f, + -0.042938256934940834f, 0.999077727752645360f, + -0.049067674327418008f, 0.998795456205172410f, + -0.055195244349689913f, 0.998475580573294770f, + -0.061320736302208530f, 0.998118112900149180f, + -0.067443919563663982f, 0.997723066644191640f, + -0.073564563599667329f, 0.997290456678690210f, + -0.079682437971430015f, 0.996820299291165780f, + -0.085797312344439755f, 0.996312612182778000f, + -0.091908956497132571f, 0.995767414467659820f, + -0.098017140329560645f, 0.995184726672196930f, + -0.104121633872054600f, 0.994564570734255420f, + -0.110222207293883060f, 0.993906970002356060f, + -0.116318630911904750f, 0.993211949234794500f, + -0.122410675199216150f, 0.992479534598709970f, + -0.128498110793793110f, 0.991709753669099530f, + -0.134580708507126110f, 0.990902635427780010f, + -0.140658239332849130f, 0.990058210262297120f, + -0.146730474455361640f, 0.989176509964781010f, + -0.152797185258443300f, 0.988257567730749460f, + -0.158858143333861280f, 0.987301418157858430f, + -0.164913120489969950f, 0.986308097244598670f, + -0.170961888760301240f, 0.985277642388941220f, + -0.177004220412148750f, 0.984210092386929030f, + -0.183039887955140920f, 0.983105487431216290f, + -0.189068664149806160f, 0.981963869109555240f, + -0.195090322016128190f, 0.980785280403230430f, + -0.201104634842091820f, 0.979569765685440520f, + -0.207111376192218450f, 0.978317370719627650f, + -0.213110319916091250f, 0.977028142657754390f, + -0.219101240156869660f, 0.975702130038528570f, + -0.225083911359792670f, 0.974339382785575860f, + -0.231058108280671140f, 0.972939952205560180f, + -0.237023605994367230f, 0.971503890986251780f, + -0.242980179903263870f, 0.970031253194543970f, + -0.248927605745720120f, 0.968522094274417380f, + -0.254865659604514520f, 0.966976471044852070f, + -0.260794117915275460f, 0.965394441697689400f, + -0.266712757474898310f, 0.963776065795439840f, + -0.272621355449948870f, 0.962121404269041580f, + -0.278519689385052950f, 0.960430519415565900f, + -0.284407537211271710f, 0.958703474895871600f, + -0.290284677254462160f, 0.956940335732208940f, + -0.296150888243623840f, 0.955141168305770670f, + -0.302005949319228080f, 0.953306040354193860f, + -0.307849640041534870f, 0.951435020969008340f, + -0.313681740398891410f, 0.949528180593036670f, + -0.319502030816015640f, 0.947585591017741200f, + -0.325310292162262870f, 0.945607325380521390f, + -0.331106305759876320f, 0.943593458161960390f, + -0.336889853392219940f, 0.941544065183020810f, + -0.342660717311994270f, 0.939459223602189920f, + -0.348418680249434400f, 0.937339011912574960f, + -0.354163525420490400f, 0.935183509938947610f, + -0.359895036534988170f, 0.932992798834738850f, + -0.365612997804773850f, 0.930766961078983710f, + -0.371317193951837490f, 0.928506080473215590f, + -0.377007410216418200f, 0.926210242138311380f, + -0.382683432365089730f, 0.923879532511286740f, + -0.388345046698826190f, 0.921514039342042010f, + -0.393992040061047990f, 0.919113851690057770f, + -0.399624199845646680f, 0.916679059921042700f, + -0.405241314004989750f, 0.914209755703530690f, + -0.410843171057903800f, 0.911706032005429880f, + -0.416429560097636990f, 0.909167983090522490f, + -0.422000270799799680f, 0.906595704514915330f, + -0.427555093430281860f, 0.903989293123443450f, + -0.433093818853151900f, 0.901348847046022030f, + -0.438616238538527380f, 0.898674465693953930f, + -0.444122144570429140f, 0.895966249756185220f, + -0.449611329654606710f, 0.893224301195515210f, + -0.455083587126343720f, 0.890448723244757990f, + -0.460538710958240060f, 0.887639620402853930f, + -0.465976495767966010f, 0.884797098430937900f, + -0.471396736825997700f, 0.881921264348355050f, + -0.476799230063321920f, 0.879012226428633530f, + -0.482183772079122720f, 0.876070094195406600f, + -0.487550160148435720f, 0.873094978418290200f, + -0.492898192229783980f, 0.870086991108711460f, + -0.498227666972781590f, 0.867046245515692760f, + -0.503538383725717460f, 0.863972856121586810f, + -0.508830142543107100f, 0.860866938637767200f, + -0.514102744193221660f, 0.857728610000272120f, + -0.519355990165589640f, 0.854557988365400530f, + -0.524589682678468730f, 0.851355193105265200f, + -0.529803624686294720f, 0.848120344803297230f, + -0.534997619887097040f, 0.844853565249707230f, + -0.540171472729892850f, 0.841554977436898440f, + -0.545324988422046240f, 0.838224705554838190f, + -0.550457972936604700f, 0.834862874986380120f, + -0.555570233019601960f, 0.831469612302545460f, + -0.560661576197335920f, 0.828045045257755800f, + -0.565731810783613230f, 0.824589302785025180f, + -0.570780745886967140f, 0.821102514991104760f, + -0.575808191417845340f, 0.817584813151583710f, + -0.580813958095764420f, 0.814036329705948520f, + -0.585797857456438860f, 0.810457198252594770f, + -0.590759701858874050f, 0.806847553543799450f, + -0.595699304492433360f, 0.803207531480644940f, + -0.600616479383868750f, 0.799537269107905240f, + -0.605511041404325430f, 0.795836904608883570f, + -0.610382806276309590f, 0.792106577300212280f, + -0.615231590580626710f, 0.788346427626606340f, + -0.620057211763289210f, 0.784556597155575130f, + -0.624859488142386230f, 0.780737228572094600f, + -0.629638238914927100f, 0.776888465673232440f, + -0.634393284163645380f, 0.773010453362737100f, + -0.639124444863775730f, 0.769103337645579590f, + -0.643831542889791280f, 0.765167265622459070f, + -0.648514401022112440f, 0.761202385484261890f, + -0.653172842953776530f, 0.757208846506484680f, + -0.657806693297078640f, 0.753186799043612520f, + -0.662415777590171890f, 0.749136394523459260f, + -0.666999922303637360f, 0.745057785441466060f, + -0.671558954847018440f, 0.740951125354958990f, + -0.676092703575315810f, 0.736816568877370020f, + -0.680600997795453020f, 0.732654271672412820f, + -0.685083667772700240f, 0.728464390448225310f, + -0.689540544737066940f, 0.724247082951466890f, + -0.693971460889653780f, 0.720002507961381770f, + -0.698376249408972800f, 0.715730825283818710f, + -0.702754744457225080f, 0.711432195745216660f, + -0.707106781186547460f, 0.707106781186547570f, + -0.711432195745216540f, 0.702754744457225190f, + -0.715730825283818590f, 0.698376249408972920f, + -0.720002507961381650f, 0.693971460889654000f, + -0.724247082951466780f, 0.689540544737067050f, + -0.728464390448225200f, 0.685083667772700360f, + -0.732654271672412700f, 0.680600997795453240f, + -0.736816568877369900f, 0.676092703575315920f, + -0.740951125354958880f, 0.671558954847018550f, + -0.745057785441465950f, 0.666999922303637580f, + -0.749136394523459150f, 0.662415777590172010f, + -0.753186799043612410f, 0.657806693297078750f, + -0.757208846506484570f, 0.653172842953776640f, + -0.761202385484261670f, 0.648514401022112550f, + -0.765167265622458960f, 0.643831542889791390f, + -0.769103337645579480f, 0.639124444863775840f, + -0.773010453362736990f, 0.634393284163645490f, + -0.776888465673232330f, 0.629638238914927210f, + -0.780737228572094490f, 0.624859488142386340f, + -0.784556597155575020f, 0.620057211763289430f, + -0.788346427626606230f, 0.615231590580626930f, + -0.792106577300212170f, 0.610382806276309700f, + -0.795836904608883460f, 0.605511041404325660f, + -0.799537269107905120f, 0.600616479383868860f, + -0.803207531480644830f, 0.595699304492433470f, + -0.806847553543799330f, 0.590759701858874160f, + -0.810457198252594660f, 0.585797857456438980f, + -0.814036329705948410f, 0.580813958095764530f, + -0.817584813151583600f, 0.575808191417845450f, + -0.821102514991104650f, 0.570780745886967260f, + -0.824589302785025070f, 0.565731810783613450f, + -0.828045045257755690f, 0.560661576197336140f, + -0.831469612302545350f, 0.555570233019602180f, + -0.834862874986380010f, 0.550457972936604920f, + -0.838224705554838080f, 0.545324988422046350f, + -0.841554977436898330f, 0.540171472729892970f, + -0.844853565249707120f, 0.534997619887097150f, + -0.848120344803297120f, 0.529803624686294830f, + -0.851355193105265200f, 0.524589682678468950f, + -0.854557988365400420f, 0.519355990165589750f, + -0.857728610000272010f, 0.514102744193221770f, + -0.860866938637767090f, 0.508830142543107320f, + -0.863972856121586700f, 0.503538383725717690f, + -0.867046245515692760f, 0.498227666972781760f, + -0.870086991108711350f, 0.492898192229784150f, + -0.873094978418290090f, 0.487550160148435880f, + -0.876070094195406490f, 0.482183772079122890f, + -0.879012226428633530f, 0.476799230063322090f, + -0.881921264348354940f, 0.471396736825997860f, + -0.884797098430937790f, 0.465976495767966180f, + -0.887639620402853820f, 0.460538710958240230f, + -0.890448723244757880f, 0.455083587126343890f, + -0.893224301195515210f, 0.449611329654606870f, + -0.895966249756185110f, 0.444122144570429310f, + -0.898674465693953930f, 0.438616238538527550f, + -0.901348847046021920f, 0.433093818853152070f, + -0.903989293123443340f, 0.427555093430282030f, + -0.906595704514915330f, 0.422000270799799850f, + -0.909167983090522380f, 0.416429560097637150f, + -0.911706032005429770f, 0.410843171057904130f, + -0.914209755703530690f, 0.405241314004989920f, + -0.916679059921042590f, 0.399624199845647070f, + -0.919113851690057770f, 0.393992040061048150f, + -0.921514039342041790f, 0.388345046698826580f, + -0.923879532511286740f, 0.382683432365089890f, + -0.926210242138311380f, 0.377007410216418150f, + -0.928506080473215480f, 0.371317193951837710f, + -0.930766961078983710f, 0.365612997804773800f, + -0.932992798834738850f, 0.359895036534988330f, + -0.935183509938947610f, 0.354163525420490400f, + -0.937339011912574850f, 0.348418680249434790f, + -0.939459223602189920f, 0.342660717311994430f, + -0.941544065183020700f, 0.336889853392220330f, + -0.943593458161960390f, 0.331106305759876480f, + -0.945607325380521170f, 0.325310292162263260f, + -0.947585591017741090f, 0.319502030816015800f, + -0.949528180593036670f, 0.313681740398891410f, + -0.951435020969008340f, 0.307849640041535030f, + -0.953306040354193860f, 0.302005949319228030f, + -0.955141168305770670f, 0.296150888243624010f, + -0.956940335732208820f, 0.290284677254462390f, + -0.958703474895871490f, 0.284407537211272100f, + -0.960430519415565790f, 0.278519689385053170f, + -0.962121404269041470f, 0.272621355449949250f, + -0.963776065795439840f, 0.266712757474898480f, + -0.965394441697689290f, 0.260794117915275850f, + -0.966976471044852070f, 0.254865659604514680f, + -0.968522094274417380f, 0.248927605745720090f, + -0.970031253194543970f, 0.242980179903264070f, + -0.971503890986251780f, 0.237023605994367170f, + -0.972939952205560070f, 0.231058108280671330f, + -0.974339382785575860f, 0.225083911359792830f, + -0.975702130038528460f, 0.219101240156870050f, + -0.977028142657754390f, 0.213110319916091420f, + -0.978317370719627540f, 0.207111376192218840f, + -0.979569765685440520f, 0.201104634842092010f, + -0.980785280403230430f, 0.195090322016128610f, + -0.981963869109555240f, 0.189068664149806360f, + -0.983105487431216290f, 0.183039887955140900f, + -0.984210092386929030f, 0.177004220412148940f, + -0.985277642388941220f, 0.170961888760301220f, + -0.986308097244598560f, 0.164913120489970140f, + -0.987301418157858430f, 0.158858143333861470f, + -0.988257567730749460f, 0.152797185258443690f, + -0.989176509964781010f, 0.146730474455361800f, + -0.990058210262297010f, 0.140658239332849540f, + -0.990902635427780010f, 0.134580708507126280f, + -0.991709753669099530f, 0.128498110793793090f, + -0.992479534598709970f, 0.122410675199216350f, + -0.993211949234794500f, 0.116318630911904710f, + -0.993906970002356060f, 0.110222207293883240f, + -0.994564570734255420f, 0.104121633872054570f, + -0.995184726672196820f, 0.098017140329560826f, + -0.995767414467659820f, 0.091908956497132752f, + -0.996312612182778000f, 0.085797312344440158f, + -0.996820299291165670f, 0.079682437971430195f, + -0.997290456678690210f, 0.073564563599667732f, + -0.997723066644191640f, 0.067443919563664176f, + -0.998118112900149180f, 0.061320736302208488f, + -0.998475580573294770f, 0.055195244349690094f, + -0.998795456205172410f, 0.049067674327417966f, + -0.999077727752645360f, 0.042938256934941021f, + -0.999322384588349540f, 0.036807222941358832f, + -0.999529417501093140f, 0.030674803176636865f, + -0.999698818696204250f, 0.024541228522912326f, + -0.999830581795823400f, 0.018406729905805101f, + -0.999924701839144500f, 0.012271538285720007f, + -0.999981175282601110f, 0.006135884649154799f, + -1.000000000000000000f, 0.000000000000000122f, + -0.999981175282601110f, -0.006135884649154554f, + -0.999924701839144500f, -0.012271538285719762f, + -0.999830581795823400f, -0.018406729905804858f, + -0.999698818696204250f, -0.024541228522912080f, + -0.999529417501093140f, -0.030674803176636619f, + -0.999322384588349540f, -0.036807222941358582f, + -0.999077727752645360f, -0.042938256934940779f, + -0.998795456205172410f, -0.049067674327417724f, + -0.998475580573294770f, -0.055195244349689851f, + -0.998118112900149180f, -0.061320736302208245f, + -0.997723066644191640f, -0.067443919563663926f, + -0.997290456678690210f, -0.073564563599667496f, + -0.996820299291165780f, -0.079682437971429945f, + -0.996312612182778000f, -0.085797312344439922f, + -0.995767414467659820f, -0.091908956497132516f, + -0.995184726672196930f, -0.098017140329560590f, + -0.994564570734255530f, -0.104121633872054320f, + -0.993906970002356060f, -0.110222207293883000f, + -0.993211949234794610f, -0.116318630911904470f, + -0.992479534598709970f, -0.122410675199216100f, + -0.991709753669099530f, -0.128498110793792840f, + -0.990902635427780010f, -0.134580708507126060f, + -0.990058210262297120f, -0.140658239332849290f, + -0.989176509964781010f, -0.146730474455361580f, + -0.988257567730749460f, -0.152797185258443440f, + -0.987301418157858430f, -0.158858143333861220f, + -0.986308097244598670f, -0.164913120489969890f, + -0.985277642388941330f, -0.170961888760300970f, + -0.984210092386929140f, -0.177004220412148690f, + -0.983105487431216400f, -0.183039887955140650f, + -0.981963869109555240f, -0.189068664149806110f, + -0.980785280403230430f, -0.195090322016128360f, + -0.979569765685440520f, -0.201104634842091760f, + -0.978317370719627650f, -0.207111376192218590f, + -0.977028142657754390f, -0.213110319916091200f, + -0.975702130038528570f, -0.219101240156869800f, + -0.974339382785575860f, -0.225083911359792610f, + -0.972939952205560180f, -0.231058108280671080f, + -0.971503890986251890f, -0.237023605994366950f, + -0.970031253194543970f, -0.242980179903263820f, + -0.968522094274417380f, -0.248927605745719870f, + -0.966976471044852180f, -0.254865659604514460f, + -0.965394441697689400f, -0.260794117915275630f, + -0.963776065795439950f, -0.266712757474898250f, + -0.962121404269041580f, -0.272621355449949030f, + -0.960430519415565900f, -0.278519689385052890f, + -0.958703474895871600f, -0.284407537211271820f, + -0.956940335732208940f, -0.290284677254462110f, + -0.955141168305770780f, -0.296150888243623790f, + -0.953306040354193970f, -0.302005949319227810f, + -0.951435020969008450f, -0.307849640041534810f, + -0.949528180593036790f, -0.313681740398891180f, + -0.947585591017741200f, -0.319502030816015580f, + -0.945607325380521280f, -0.325310292162262980f, + -0.943593458161960390f, -0.331106305759876260f, + -0.941544065183020810f, -0.336889853392220110f, + -0.939459223602190030f, -0.342660717311994210f, + -0.937339011912574960f, -0.348418680249434560f, + -0.935183509938947720f, -0.354163525420490120f, + -0.932992798834738960f, -0.359895036534988110f, + -0.930766961078983820f, -0.365612997804773580f, + -0.928506080473215590f, -0.371317193951837430f, + -0.926210242138311490f, -0.377007410216417930f, + -0.923879532511286850f, -0.382683432365089670f, + -0.921514039342041900f, -0.388345046698826360f, + -0.919113851690057770f, -0.393992040061047930f, + -0.916679059921042700f, -0.399624199845646840f, + -0.914209755703530690f, -0.405241314004989690f, + -0.911706032005429880f, -0.410843171057903910f, + -0.909167983090522490f, -0.416429560097636930f, + -0.906595704514915450f, -0.422000270799799630f, + -0.903989293123443450f, -0.427555093430281810f, + -0.901348847046022030f, -0.433093818853151850f, + -0.898674465693954040f, -0.438616238538527330f, + -0.895966249756185220f, -0.444122144570429090f, + -0.893224301195515320f, -0.449611329654606650f, + -0.890448723244757990f, -0.455083587126343670f, + -0.887639620402853930f, -0.460538710958240060f, + -0.884797098430937900f, -0.465976495767965960f, + -0.881921264348355050f, -0.471396736825997640f, + -0.879012226428633640f, -0.476799230063321870f, + -0.876070094195406600f, -0.482183772079122660f, + -0.873094978418290200f, -0.487550160148435660f, + -0.870086991108711460f, -0.492898192229783930f, + -0.867046245515692870f, -0.498227666972781540f, + -0.863972856121586810f, -0.503538383725717460f, + -0.860866938637767310f, -0.508830142543107100f, + -0.857728610000272120f, -0.514102744193221550f, + -0.854557988365400530f, -0.519355990165589640f, + -0.851355193105265310f, -0.524589682678468730f, + -0.848120344803297230f, -0.529803624686294610f, + -0.844853565249707230f, -0.534997619887096930f, + -0.841554977436898440f, -0.540171472729892850f, + -0.838224705554838190f, -0.545324988422046130f, + -0.834862874986380120f, -0.550457972936604700f, + -0.831469612302545460f, -0.555570233019601960f, + -0.828045045257755800f, -0.560661576197335920f, + -0.824589302785025290f, -0.565731810783613230f, + -0.821102514991104760f, -0.570780745886967140f, + -0.817584813151583710f, -0.575808191417845340f, + -0.814036329705948520f, -0.580813958095764300f, + -0.810457198252594770f, -0.585797857456438860f, + -0.806847553543799450f, -0.590759701858873940f, + -0.803207531480644940f, -0.595699304492433250f, + -0.799537269107905240f, -0.600616479383868640f, + -0.795836904608883570f, -0.605511041404325430f, + -0.792106577300212280f, -0.610382806276309480f, + -0.788346427626606340f, -0.615231590580626710f, + -0.784556597155575240f, -0.620057211763289210f, + -0.780737228572094600f, -0.624859488142386230f, + -0.776888465673232440f, -0.629638238914926980f, + -0.773010453362737100f, -0.634393284163645270f, + -0.769103337645579700f, -0.639124444863775730f, + -0.765167265622459070f, -0.643831542889791280f, + -0.761202385484261890f, -0.648514401022112330f, + -0.757208846506484790f, -0.653172842953776530f, + -0.753186799043612630f, -0.657806693297078530f, + -0.749136394523459260f, -0.662415777590171780f, + -0.745057785441466060f, -0.666999922303637360f, + -0.740951125354959110f, -0.671558954847018440f, + -0.736816568877370020f, -0.676092703575315810f, + -0.732654271672412820f, -0.680600997795453020f, + -0.728464390448225420f, -0.685083667772700130f, + -0.724247082951467000f, -0.689540544737066830f, + -0.720002507961381880f, -0.693971460889653780f, + -0.715730825283818710f, -0.698376249408972800f, + -0.711432195745216660f, -0.702754744457225080f, + -0.707106781186547680f, -0.707106781186547460f, + -0.702754744457225300f, -0.711432195745216430f, + -0.698376249408973030f, -0.715730825283818480f, + -0.693971460889654000f, -0.720002507961381650f, + -0.689540544737067050f, -0.724247082951466780f, + -0.685083667772700360f, -0.728464390448225200f, + -0.680600997795453240f, -0.732654271672412590f, + -0.676092703575316030f, -0.736816568877369790f, + -0.671558954847018660f, -0.740951125354958880f, + -0.666999922303637580f, -0.745057785441465840f, + -0.662415777590172010f, -0.749136394523459040f, + -0.657806693297078750f, -0.753186799043612410f, + -0.653172842953777090f, -0.757208846506484230f, + -0.648514401022112220f, -0.761202385484262000f, + -0.643831542889791500f, -0.765167265622458960f, + -0.639124444863775950f, -0.769103337645579480f, + -0.634393284163645930f, -0.773010453362736660f, + -0.629638238914926870f, -0.776888465673232550f, + -0.624859488142386450f, -0.780737228572094380f, + -0.620057211763289430f, -0.784556597155575020f, + -0.615231590580627260f, -0.788346427626605890f, + -0.610382806276309360f, -0.792106577300212390f, + -0.605511041404325660f, -0.795836904608883460f, + -0.600616479383869310f, -0.799537269107904790f, + -0.595699304492433130f, -0.803207531480645050f, + -0.590759701858874280f, -0.806847553543799220f, + -0.585797857456439090f, -0.810457198252594660f, + -0.580813958095764970f, -0.814036329705948080f, + -0.575808191417845230f, -0.817584813151583820f, + -0.570780745886967370f, -0.821102514991104650f, + -0.565731810783613450f, -0.824589302785025070f, + -0.560661576197336480f, -0.828045045257755460f, + -0.555570233019602180f, -0.831469612302545240f, + -0.550457972936604920f, -0.834862874986380010f, + -0.545324988422046800f, -0.838224705554837860f, + -0.540171472729892740f, -0.841554977436898550f, + -0.534997619887097260f, -0.844853565249707010f, + -0.529803624686294940f, -0.848120344803297120f, + -0.524589682678469390f, -0.851355193105264860f, + -0.519355990165589420f, -0.854557988365400640f, + -0.514102744193221770f, -0.857728610000272010f, + -0.508830142543107320f, -0.860866938637767090f, + -0.503538383725718020f, -0.863972856121586470f, + -0.498227666972781810f, -0.867046245515692650f, + -0.492898192229784200f, -0.870086991108711350f, + -0.487550160148436330f, -0.873094978418289870f, + -0.482183772079122550f, -0.876070094195406710f, + -0.476799230063322140f, -0.879012226428633410f, + -0.471396736825997860f, -0.881921264348354940f, + -0.465976495767966630f, -0.884797098430937570f, + -0.460538710958239890f, -0.887639620402854050f, + -0.455083587126343950f, -0.890448723244757880f, + -0.449611329654606930f, -0.893224301195515210f, + -0.444122144570429760f, -0.895966249756184880f, + -0.438616238538527600f, -0.898674465693953820f, + -0.433093818853152120f, -0.901348847046021920f, + -0.427555093430282470f, -0.903989293123443120f, + -0.422000270799799520f, -0.906595704514915450f, + -0.416429560097637210f, -0.909167983090522380f, + -0.410843171057904190f, -0.911706032005429770f, + -0.405241314004990360f, -0.914209755703530470f, + -0.399624199845646730f, -0.916679059921042700f, + -0.393992040061048210f, -0.919113851690057660f, + -0.388345046698826630f, -0.921514039342041790f, + -0.382683432365090340f, -0.923879532511286520f, + -0.377007410216418200f, -0.926210242138311380f, + -0.371317193951837770f, -0.928506080473215480f, + -0.365612997804774300f, -0.930766961078983600f, + -0.359895036534987940f, -0.932992798834738960f, + -0.354163525420490450f, -0.935183509938947610f, + -0.348418680249434840f, -0.937339011912574850f, + -0.342660717311994880f, -0.939459223602189700f, + -0.336889853392219940f, -0.941544065183020810f, + -0.331106305759876540f, -0.943593458161960270f, + -0.325310292162263310f, -0.945607325380521170f, + -0.319502030816015410f, -0.947585591017741200f, + -0.313681740398891460f, -0.949528180593036670f, + -0.307849640041535090f, -0.951435020969008340f, + -0.302005949319228530f, -0.953306040354193750f, + -0.296150888243623680f, -0.955141168305770780f, + -0.290284677254462440f, -0.956940335732208820f, + -0.284407537211272150f, -0.958703474895871490f, + -0.278519689385053610f, -0.960430519415565680f, + -0.272621355449948870f, -0.962121404269041580f, + -0.266712757474898530f, -0.963776065795439840f, + -0.260794117915275900f, -0.965394441697689290f, + -0.254865659604514350f, -0.966976471044852180f, + -0.248927605745720150f, -0.968522094274417270f, + -0.242980179903264120f, -0.970031253194543970f, + -0.237023605994367670f, -0.971503890986251670f, + -0.231058108280670940f, -0.972939952205560180f, + -0.225083911359792920f, -0.974339382785575860f, + -0.219101240156870100f, -0.975702130038528460f, + -0.213110319916091920f, -0.977028142657754280f, + -0.207111376192218480f, -0.978317370719627650f, + -0.201104634842092070f, -0.979569765685440520f, + -0.195090322016128660f, -0.980785280403230320f, + -0.189068664149805970f, -0.981963869109555350f, + -0.183039887955140950f, -0.983105487431216290f, + -0.177004220412149000f, -0.984210092386929030f, + -0.170961888760301690f, -0.985277642388941110f, + -0.164913120489969760f, -0.986308097244598670f, + -0.158858143333861530f, -0.987301418157858320f, + -0.152797185258443740f, -0.988257567730749460f, + -0.146730474455362300f, -0.989176509964780900f, + -0.140658239332849160f, -0.990058210262297120f, + -0.134580708507126360f, -0.990902635427780010f, + -0.128498110793793590f, -0.991709753669099530f, + -0.122410675199215960f, -0.992479534598710080f, + -0.116318630911904770f, -0.993211949234794500f, + -0.110222207293883310f, -0.993906970002356060f, + -0.104121633872055070f, -0.994564570734255420f, + -0.098017140329560451f, -0.995184726672196930f, + -0.091908956497132821f, -0.995767414467659820f, + -0.085797312344440227f, -0.996312612182778000f, + -0.079682437971430695f, -0.996820299291165670f, + -0.073564563599667357f, -0.997290456678690210f, + -0.067443919563664231f, -0.997723066644191640f, + -0.061320736302208995f, -0.998118112900149180f, + -0.055195244349689712f, -0.998475580573294770f, + -0.049067674327418029f, -0.998795456205172410f, + -0.042938256934941084f, -0.999077727752645360f, + -0.036807222941359331f, -0.999322384588349430f, + -0.030674803176636484f, -0.999529417501093140f, + -0.024541228522912389f, -0.999698818696204250f, + -0.018406729905805164f, -0.999830581795823400f, + -0.012271538285720512f, -0.999924701839144500f, + -0.006135884649154416f, -0.999981175282601110f, + -0.000000000000000184f, -1.000000000000000000f, + 0.006135884649154049f, -0.999981175282601110f, + 0.012271538285720144f, -0.999924701839144500f, + 0.018406729905804796f, -0.999830581795823400f, + 0.024541228522912021f, -0.999698818696204250f, + 0.030674803176636116f, -0.999529417501093140f, + 0.036807222941358964f, -0.999322384588349540f, + 0.042938256934940716f, -0.999077727752645360f, + 0.049067674327417661f, -0.998795456205172410f, + 0.055195244349689344f, -0.998475580573294770f, + 0.061320736302208627f, -0.998118112900149180f, + 0.067443919563663871f, -0.997723066644191640f, + 0.073564563599666982f, -0.997290456678690210f, + 0.079682437971430334f, -0.996820299291165670f, + 0.085797312344439852f, -0.996312612182778000f, + 0.091908956497132446f, -0.995767414467659820f, + 0.098017140329560090f, -0.995184726672196930f, + 0.104121633872054700f, -0.994564570734255420f, + 0.110222207293882930f, -0.993906970002356060f, + 0.116318630911904410f, -0.993211949234794610f, + 0.122410675199215600f, -0.992479534598710080f, + 0.128498110793793220f, -0.991709753669099530f, + 0.134580708507125970f, -0.990902635427780010f, + 0.140658239332848790f, -0.990058210262297120f, + 0.146730474455361940f, -0.989176509964780900f, + 0.152797185258443380f, -0.988257567730749460f, + 0.158858143333861170f, -0.987301418157858430f, + 0.164913120489969390f, -0.986308097244598780f, + 0.170961888760301330f, -0.985277642388941220f, + 0.177004220412148640f, -0.984210092386929140f, + 0.183039887955140590f, -0.983105487431216400f, + 0.189068664149805610f, -0.981963869109555350f, + 0.195090322016128300f, -0.980785280403230430f, + 0.201104634842091710f, -0.979569765685440630f, + 0.207111376192218120f, -0.978317370719627770f, + 0.213110319916091560f, -0.977028142657754280f, + 0.219101240156869740f, -0.975702130038528570f, + 0.225083911359792550f, -0.974339382785575970f, + 0.231058108280670580f, -0.972939952205560290f, + 0.237023605994367310f, -0.971503890986251780f, + 0.242980179903263760f, -0.970031253194543970f, + 0.248927605745719790f, -0.968522094274417380f, + 0.254865659604513960f, -0.966976471044852290f, + 0.260794117915275510f, -0.965394441697689400f, + 0.266712757474898200f, -0.963776065795439950f, + 0.272621355449948530f, -0.962121404269041690f, + 0.278519689385053280f, -0.960430519415565790f, + 0.284407537211271770f, -0.958703474895871600f, + 0.290284677254462050f, -0.956940335732208940f, + 0.296150888243623290f, -0.955141168305770890f, + 0.302005949319228140f, -0.953306040354193860f, + 0.307849640041534760f, -0.951435020969008450f, + 0.313681740398891130f, -0.949528180593036790f, + 0.319502030816015080f, -0.947585591017741310f, + 0.325310292162262930f, -0.945607325380521280f, + 0.331106305759876210f, -0.943593458161960390f, + 0.336889853392219610f, -0.941544065183020920f, + 0.342660717311994540f, -0.939459223602189810f, + 0.348418680249434510f, -0.937339011912574960f, + 0.354163525420490070f, -0.935183509938947720f, + 0.359895036534987610f, -0.932992798834739070f, + 0.365612997804773960f, -0.930766961078983710f, + 0.371317193951837380f, -0.928506080473215590f, + 0.377007410216417870f, -0.926210242138311490f, + 0.382683432365090000f, -0.923879532511286630f, + 0.388345046698826300f, -0.921514039342041900f, + 0.393992040061047880f, -0.919113851690057880f, + 0.399624199845646400f, -0.916679059921042820f, + 0.405241314004990030f, -0.914209755703530580f, + 0.410843171057903860f, -0.911706032005429880f, + 0.416429560097636870f, -0.909167983090522490f, + 0.422000270799799180f, -0.906595704514915560f, + 0.427555093430282140f, -0.903989293123443340f, + 0.433093818853151790f, -0.901348847046022140f, + 0.438616238538527270f, -0.898674465693954040f, + 0.444122144570429420f, -0.895966249756185000f, + 0.449611329654606600f, -0.893224301195515320f, + 0.455083587126343610f, -0.890448723244757990f, + 0.460538710958239560f, -0.887639620402854160f, + 0.465976495767966290f, -0.884797098430937680f, + 0.471396736825997590f, -0.881921264348355050f, + 0.476799230063321870f, -0.879012226428633640f, + 0.482183772079122220f, -0.876070094195406930f, + 0.487550160148436000f, -0.873094978418290090f, + 0.492898192229783870f, -0.870086991108711460f, + 0.498227666972781480f, -0.867046245515692870f, + 0.503538383725717800f, -0.863972856121586590f, + 0.508830142543106990f, -0.860866938637767310f, + 0.514102744193221550f, -0.857728610000272230f, + 0.519355990165589200f, -0.854557988365400760f, + 0.524589682678469060f, -0.851355193105265080f, + 0.529803624686294610f, -0.848120344803297340f, + 0.534997619887096930f, -0.844853565249707230f, + 0.540171472729892410f, -0.841554977436898780f, + 0.545324988422046460f, -0.838224705554837970f, + 0.550457972936604700f, -0.834862874986380120f, + 0.555570233019601840f, -0.831469612302545460f, + 0.560661576197336250f, -0.828045045257755690f, + 0.565731810783613120f, -0.824589302785025290f, + 0.570780745886967030f, -0.821102514991104870f, + 0.575808191417844890f, -0.817584813151584040f, + 0.580813958095764640f, -0.814036329705948300f, + 0.585797857456438750f, -0.810457198252594880f, + 0.590759701858873940f, -0.806847553543799450f, + 0.595699304492432910f, -0.803207531480645280f, + 0.600616479383868970f, -0.799537269107905010f, + 0.605511041404325320f, -0.795836904608883680f, + 0.610382806276309140f, -0.792106577300212610f, + 0.615231590580627040f, -0.788346427626606120f, + 0.620057211763289100f, -0.784556597155575240f, + 0.624859488142386120f, -0.780737228572094600f, + 0.629638238914926650f, -0.776888465673232780f, + 0.634393284163645600f, -0.773010453362736880f, + 0.639124444863775620f, -0.769103337645579700f, + 0.643831542889791160f, -0.765167265622459180f, + 0.648514401022112000f, -0.761202385484262220f, + 0.653172842953776760f, -0.757208846506484570f, + 0.657806693297078530f, -0.753186799043612630f, + 0.662415777590171450f, -0.749136394523459590f, + 0.666999922303637690f, -0.745057785441465840f, + 0.671558954847018330f, -0.740951125354959110f, + 0.676092703575315700f, -0.736816568877370020f, + 0.680600997795452690f, -0.732654271672413150f, + 0.685083667772700470f, -0.728464390448225090f, + 0.689540544737066830f, -0.724247082951467000f, + 0.693971460889653780f, -0.720002507961381880f, + 0.698376249408972360f, -0.715730825283819040f, + 0.702754744457225300f, -0.711432195745216430f, + 0.707106781186547350f, -0.707106781186547680f, + 0.711432195745216100f, -0.702754744457225630f, + 0.715730825283818820f, -0.698376249408972690f, + 0.720002507961381540f, -0.693971460889654000f, + 0.724247082951466670f, -0.689540544737067160f, + 0.728464390448224860f, -0.685083667772700800f, + 0.732654271672412930f, -0.680600997795453020f, + 0.736816568877369790f, -0.676092703575316030f, + 0.740951125354958880f, -0.671558954847018660f, + 0.745057785441465500f, -0.666999922303638030f, + 0.749136394523459370f, -0.662415777590171780f, + 0.753186799043612300f, -0.657806693297078860f, + 0.757208846506484230f, -0.653172842953777090f, + 0.761202385484261890f, -0.648514401022112330f, + 0.765167265622458850f, -0.643831542889791500f, + 0.769103337645579480f, -0.639124444863775950f, + 0.773010453362736660f, -0.634393284163645930f, + 0.776888465673232550f, -0.629638238914926980f, + 0.780737228572094380f, -0.624859488142386450f, + 0.784556597155575020f, -0.620057211763289540f, + 0.788346427626605890f, -0.615231590580627370f, + 0.792106577300212390f, -0.610382806276309480f, + 0.795836904608883340f, -0.605511041404325660f, + 0.799537269107904790f, -0.600616479383869310f, + 0.803207531480645050f, -0.595699304492433250f, + 0.806847553543799220f, -0.590759701858874280f, + 0.810457198252594660f, -0.585797857456439090f, + 0.814036329705948080f, -0.580813958095764970f, + 0.817584813151583710f, -0.575808191417845230f, + 0.821102514991104540f, -0.570780745886967370f, + 0.824589302785025070f, -0.565731810783613560f, + 0.828045045257755350f, -0.560661576197336590f, + 0.831469612302545240f, -0.555570233019602180f, + 0.834862874986379900f, -0.550457972936605030f, + 0.838224705554837750f, -0.545324988422046800f, + 0.841554977436898440f, -0.540171472729892740f, + 0.844853565249707010f, -0.534997619887097260f, + 0.848120344803297120f, -0.529803624686294940f, + 0.851355193105264860f, -0.524589682678469390f, + 0.854557988365400530f, -0.519355990165589530f, + 0.857728610000272010f, -0.514102744193221880f, + 0.860866938637767090f, -0.508830142543107430f, + 0.863972856121586360f, -0.503538383725718130f, + 0.867046245515692650f, -0.498227666972781870f, + 0.870086991108711350f, -0.492898192229784260f, + 0.873094978418289870f, -0.487550160148436380f, + 0.876070094195406710f, -0.482183772079122610f, + 0.879012226428633410f, -0.476799230063322200f, + 0.881921264348354830f, -0.471396736825997920f, + 0.884797098430937460f, -0.465976495767966680f, + 0.887639620402853930f, -0.460538710958239950f, + 0.890448723244757770f, -0.455083587126344000f, + 0.893224301195515100f, -0.449611329654606980f, + 0.895966249756184880f, -0.444122144570429810f, + 0.898674465693953820f, -0.438616238538527660f, + 0.901348847046021920f, -0.433093818853152180f, + 0.903989293123443120f, -0.427555093430282530f, + 0.906595704514915450f, -0.422000270799799570f, + 0.909167983090522380f, -0.416429560097637260f, + 0.911706032005429660f, -0.410843171057904240f, + 0.914209755703530470f, -0.405241314004990420f, + 0.916679059921042700f, -0.399624199845646790f, + 0.919113851690057660f, -0.393992040061048270f, + 0.921514039342041790f, -0.388345046698826690f, + 0.923879532511286520f, -0.382683432365090390f, + 0.926210242138311380f, -0.377007410216418260f, + 0.928506080473215480f, -0.371317193951837820f, + 0.930766961078983490f, -0.365612997804774350f, + 0.932992798834738960f, -0.359895036534988000f, + 0.935183509938947500f, -0.354163525420490510f, + 0.937339011912574850f, -0.348418680249434900f, + 0.939459223602189700f, -0.342660717311994930f, + 0.941544065183020810f, -0.336889853392220000f, + 0.943593458161960270f, -0.331106305759876600f, + 0.945607325380521170f, -0.325310292162263370f, + 0.947585591017741200f, -0.319502030816015470f, + 0.949528180593036670f, -0.313681740398891520f, + 0.951435020969008340f, -0.307849640041535140f, + 0.953306040354193640f, -0.302005949319228580f, + 0.955141168305770780f, -0.296150888243623730f, + 0.956940335732208820f, -0.290284677254462500f, + 0.958703474895871490f, -0.284407537211272210f, + 0.960430519415565680f, -0.278519689385053670f, + 0.962121404269041580f, -0.272621355449948980f, + 0.963776065795439840f, -0.266712757474898590f, + 0.965394441697689290f, -0.260794117915275960f, + 0.966976471044852180f, -0.254865659604514410f, + 0.968522094274417270f, -0.248927605745720200f, + 0.970031253194543970f, -0.242980179903264180f, + 0.971503890986251670f, -0.237023605994367730f, + 0.972939952205560180f, -0.231058108280671000f, + 0.974339382785575860f, -0.225083911359792970f, + 0.975702130038528460f, -0.219101240156870160f, + 0.977028142657754170f, -0.213110319916091970f, + 0.978317370719627650f, -0.207111376192218530f, + 0.979569765685440520f, -0.201104634842092120f, + 0.980785280403230320f, -0.195090322016128720f, + 0.981963869109555350f, -0.189068664149806030f, + 0.983105487431216290f, -0.183039887955141010f, + 0.984210092386929030f, -0.177004220412149050f, + 0.985277642388941110f, -0.170961888760301770f, + 0.986308097244598670f, -0.164913120489969810f, + 0.987301418157858320f, -0.158858143333861580f, + 0.988257567730749460f, -0.152797185258443800f, + 0.989176509964780900f, -0.146730474455362390f, + 0.990058210262297120f, -0.140658239332849210f, + 0.990902635427780010f, -0.134580708507126420f, + 0.991709753669099410f, -0.128498110793793640f, + 0.992479534598709970f, -0.122410675199216030f, + 0.993211949234794500f, -0.116318630911904840f, + 0.993906970002356060f, -0.110222207293883360f, + 0.994564570734255420f, -0.104121633872055130f, + 0.995184726672196930f, -0.098017140329560506f, + 0.995767414467659820f, -0.091908956497132877f, + 0.996312612182778000f, -0.085797312344440282f, + 0.996820299291165670f, -0.079682437971430750f, + 0.997290456678690210f, -0.073564563599667412f, + 0.997723066644191640f, -0.067443919563664287f, + 0.998118112900149180f, -0.061320736302209057f, + 0.998475580573294770f, -0.055195244349689775f, + 0.998795456205172410f, -0.049067674327418091f, + 0.999077727752645360f, -0.042938256934941139f, + 0.999322384588349430f, -0.036807222941359394f, + 0.999529417501093140f, -0.030674803176636543f, + 0.999698818696204250f, -0.024541228522912448f, + 0.999830581795823400f, -0.018406729905805226f, + 0.999924701839144500f, -0.012271538285720572f, + 0.999981175282601110f, -0.006135884649154477f +}; + +/** +* @brief Initialization function for the floating-point CFFT/CIFFT. +* @param[in,out] *S points to an instance of the floating-point CFFT/CIFFT structure. +* @param[in] fftLen length of the FFT. +* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. +* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. +* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. +* +* \par Description: +* \par +* The parameter ifftFlag controls whether a forward or inverse transform is computed. +* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated +* \par +* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. +* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. +* \par +* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. +* \par +* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. +*/ + +arm_status arm_cfft_radix4_init_f32( + arm_cfft_radix4_instance_f32 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag) +{ + /* Initialise the default arm status */ + arm_status status = ARM_MATH_SUCCESS; + + /* Initialise the FFT length */ + S->fftLen = fftLen; + + /* Initialise the Twiddle coefficient pointer */ + S->pTwiddle = (float32_t *) twiddleCoef; + + /* Initialise the Flag for selection of CFFT or CIFFT */ + S->ifftFlag = ifftFlag; + + /* Initialise the Flag for calculation Bit reversal or not */ + S->bitReverseFlag = bitReverseFlag; + + /* Initializations of structure parameters depending on the FFT length */ + switch (S->fftLen) + { + + case 1024u: + /* Initializations of structure parameters for 1024 point FFT */ + + /* Initialise the twiddle coef modifier value */ + S->twidCoefModifier = 1u; + /* Initialise the bit reversal table modifier */ + S->bitRevFactor = 1u; + /* Initialise the bit reversal table pointer */ + S->pBitRevTable = armBitRevTable; + /* Initialise the 1/fftLen Value */ + S->onebyfftLen = 0.0009765625f; + break; + + + case 256u: + /* Initializations of structure parameters for 256 point FFT */ + S->twidCoefModifier = 4u; + S->bitRevFactor = 4u; + S->pBitRevTable = &armBitRevTable[3]; + S->onebyfftLen = 0.00390625f; + break; + + case 64u: + /* Initializations of structure parameters for 64 point FFT */ + S->twidCoefModifier = 16u; + S->bitRevFactor = 16u; + S->pBitRevTable = &armBitRevTable[15]; + S->onebyfftLen = 0.015625f; + break; + + case 16u: + /* Initializations of structure parameters for 16 point FFT */ + S->twidCoefModifier = 64u; + S->bitRevFactor = 64u; + S->pBitRevTable = &armBitRevTable[63]; + S->onebyfftLen = 0.0625f; + break; + + + default: + /* Reporting argument error if fftSize is not valid value */ + status = ARM_MATH_ARGUMENT_ERROR; + break; + } + + return (status); +} + +/** + * @} end of CFFT_CIFFT group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q15.c index 3bb11df37..96ae68202 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q15.c @@ -1,415 +1,415 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_init_q15.c -* -* Description: Radix-4 Decimation in Frequency Q15 FFT & IFFT initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupTransforms - */ - - -/** - * @addtogroup CFFT_CIFFT - * @{ - */ - -/* -* @brief Twiddle factors Table -*/ - -/** -* \par -* Example code for Q15 Twiddle factors Generation:: -* \par -*
for(i = 0; i< N; i++)   
-* {   
-*	twiddleCoefQ15[2*i]= cos(i * 2*PI/(float)N);   
-*	twiddleCoefQ15[2*i+1]= sin(i * 2*PI/(float)N);   
-* } 
-* \par -* where N = 1024 and PI = 3.14159265358979 -* \par -* Cos and Sin values are interleaved fashion -* \par -* Convert Floating point to Q15(Fixed point 1.15): -* round(twiddleCoefQ15(i) * pow(2, 15)) -* -*/ - -static const q15_t twiddleCoefQ15[2048] = { - 0x7fff, 0x0, 0x7fff, 0xc9, 0x7ffe, 0x192, 0x7ffa, 0x25b, - 0x7ff6, 0x324, 0x7ff1, 0x3ed, 0x7fea, 0x4b6, 0x7fe2, 0x57f, - 0x7fd9, 0x648, 0x7fce, 0x711, 0x7fc2, 0x7d9, 0x7fb5, 0x8a2, - 0x7fa7, 0x96b, 0x7f98, 0xa33, 0x7f87, 0xafb, 0x7f75, 0xbc4, - 0x7f62, 0xc8c, 0x7f4e, 0xd54, 0x7f38, 0xe1c, 0x7f22, 0xee4, - 0x7f0a, 0xfab, 0x7ef0, 0x1073, 0x7ed6, 0x113a, 0x7eba, 0x1201, - 0x7e9d, 0x12c8, 0x7e7f, 0x138f, 0x7e60, 0x1455, 0x7e3f, 0x151c, - 0x7e1e, 0x15e2, 0x7dfb, 0x16a8, 0x7dd6, 0x176e, 0x7db1, 0x1833, - 0x7d8a, 0x18f9, 0x7d63, 0x19be, 0x7d3a, 0x1a83, 0x7d0f, 0x1b47, - 0x7ce4, 0x1c0c, 0x7cb7, 0x1cd0, 0x7c89, 0x1d93, 0x7c5a, 0x1e57, - 0x7c2a, 0x1f1a, 0x7bf9, 0x1fdd, 0x7bc6, 0x209f, 0x7b92, 0x2162, - 0x7b5d, 0x2224, 0x7b27, 0x22e5, 0x7aef, 0x23a7, 0x7ab7, 0x2467, - 0x7a7d, 0x2528, 0x7a42, 0x25e8, 0x7a06, 0x26a8, 0x79c9, 0x2768, - 0x798a, 0x2827, 0x794a, 0x28e5, 0x790a, 0x29a4, 0x78c8, 0x2a62, - 0x7885, 0x2b1f, 0x7840, 0x2bdc, 0x77fb, 0x2c99, 0x77b4, 0x2d55, - 0x776c, 0x2e11, 0x7723, 0x2ecc, 0x76d9, 0x2f87, 0x768e, 0x3042, - 0x7642, 0x30fc, 0x75f4, 0x31b5, 0x75a6, 0x326e, 0x7556, 0x3327, - 0x7505, 0x33df, 0x74b3, 0x3497, 0x7460, 0x354e, 0x740b, 0x3604, - 0x73b6, 0x36ba, 0x735f, 0x3770, 0x7308, 0x3825, 0x72af, 0x38d9, - 0x7255, 0x398d, 0x71fa, 0x3a40, 0x719e, 0x3af3, 0x7141, 0x3ba5, - 0x70e3, 0x3c57, 0x7083, 0x3d08, 0x7023, 0x3db8, 0x6fc2, 0x3e68, - 0x6f5f, 0x3f17, 0x6efb, 0x3fc6, 0x6e97, 0x4074, 0x6e31, 0x4121, - 0x6dca, 0x41ce, 0x6d62, 0x427a, 0x6cf9, 0x4326, 0x6c8f, 0x43d1, - 0x6c24, 0x447b, 0x6bb8, 0x4524, 0x6b4b, 0x45cd, 0x6add, 0x4675, - 0x6a6e, 0x471d, 0x69fd, 0x47c4, 0x698c, 0x486a, 0x691a, 0x490f, - 0x68a7, 0x49b4, 0x6832, 0x4a58, 0x67bd, 0x4afb, 0x6747, 0x4b9e, - 0x66d0, 0x4c40, 0x6657, 0x4ce1, 0x65de, 0x4d81, 0x6564, 0x4e21, - 0x64e9, 0x4ec0, 0x646c, 0x4f5e, 0x63ef, 0x4ffb, 0x6371, 0x5098, - 0x62f2, 0x5134, 0x6272, 0x51cf, 0x61f1, 0x5269, 0x616f, 0x5303, - 0x60ec, 0x539b, 0x6068, 0x5433, 0x5fe4, 0x54ca, 0x5f5e, 0x5560, - 0x5ed7, 0x55f6, 0x5e50, 0x568a, 0x5dc8, 0x571e, 0x5d3e, 0x57b1, - 0x5cb4, 0x5843, 0x5c29, 0x58d4, 0x5b9d, 0x5964, 0x5b10, 0x59f4, - 0x5a82, 0x5a82, 0x59f4, 0x5b10, 0x5964, 0x5b9d, 0x58d4, 0x5c29, - 0x5843, 0x5cb4, 0x57b1, 0x5d3e, 0x571e, 0x5dc8, 0x568a, 0x5e50, - 0x55f6, 0x5ed7, 0x5560, 0x5f5e, 0x54ca, 0x5fe4, 0x5433, 0x6068, - 0x539b, 0x60ec, 0x5303, 0x616f, 0x5269, 0x61f1, 0x51cf, 0x6272, - 0x5134, 0x62f2, 0x5098, 0x6371, 0x4ffb, 0x63ef, 0x4f5e, 0x646c, - 0x4ec0, 0x64e9, 0x4e21, 0x6564, 0x4d81, 0x65de, 0x4ce1, 0x6657, - 0x4c40, 0x66d0, 0x4b9e, 0x6747, 0x4afb, 0x67bd, 0x4a58, 0x6832, - 0x49b4, 0x68a7, 0x490f, 0x691a, 0x486a, 0x698c, 0x47c4, 0x69fd, - 0x471d, 0x6a6e, 0x4675, 0x6add, 0x45cd, 0x6b4b, 0x4524, 0x6bb8, - 0x447b, 0x6c24, 0x43d1, 0x6c8f, 0x4326, 0x6cf9, 0x427a, 0x6d62, - 0x41ce, 0x6dca, 0x4121, 0x6e31, 0x4074, 0x6e97, 0x3fc6, 0x6efb, - 0x3f17, 0x6f5f, 0x3e68, 0x6fc2, 0x3db8, 0x7023, 0x3d08, 0x7083, - 0x3c57, 0x70e3, 0x3ba5, 0x7141, 0x3af3, 0x719e, 0x3a40, 0x71fa, - 0x398d, 0x7255, 0x38d9, 0x72af, 0x3825, 0x7308, 0x3770, 0x735f, - 0x36ba, 0x73b6, 0x3604, 0x740b, 0x354e, 0x7460, 0x3497, 0x74b3, - 0x33df, 0x7505, 0x3327, 0x7556, 0x326e, 0x75a6, 0x31b5, 0x75f4, - 0x30fc, 0x7642, 0x3042, 0x768e, 0x2f87, 0x76d9, 0x2ecc, 0x7723, - 0x2e11, 0x776c, 0x2d55, 0x77b4, 0x2c99, 0x77fb, 0x2bdc, 0x7840, - 0x2b1f, 0x7885, 0x2a62, 0x78c8, 0x29a4, 0x790a, 0x28e5, 0x794a, - 0x2827, 0x798a, 0x2768, 0x79c9, 0x26a8, 0x7a06, 0x25e8, 0x7a42, - 0x2528, 0x7a7d, 0x2467, 0x7ab7, 0x23a7, 0x7aef, 0x22e5, 0x7b27, - 0x2224, 0x7b5d, 0x2162, 0x7b92, 0x209f, 0x7bc6, 0x1fdd, 0x7bf9, - 0x1f1a, 0x7c2a, 0x1e57, 0x7c5a, 0x1d93, 0x7c89, 0x1cd0, 0x7cb7, - 0x1c0c, 0x7ce4, 0x1b47, 0x7d0f, 0x1a83, 0x7d3a, 0x19be, 0x7d63, - 0x18f9, 0x7d8a, 0x1833, 0x7db1, 0x176e, 0x7dd6, 0x16a8, 0x7dfb, - 0x15e2, 0x7e1e, 0x151c, 0x7e3f, 0x1455, 0x7e60, 0x138f, 0x7e7f, - 0x12c8, 0x7e9d, 0x1201, 0x7eba, 0x113a, 0x7ed6, 0x1073, 0x7ef0, - 0xfab, 0x7f0a, 0xee4, 0x7f22, 0xe1c, 0x7f38, 0xd54, 0x7f4e, - 0xc8c, 0x7f62, 0xbc4, 0x7f75, 0xafb, 0x7f87, 0xa33, 0x7f98, - 0x96b, 0x7fa7, 0x8a2, 0x7fb5, 0x7d9, 0x7fc2, 0x711, 0x7fce, - 0x648, 0x7fd9, 0x57f, 0x7fe2, 0x4b6, 0x7fea, 0x3ed, 0x7ff1, - 0x324, 0x7ff6, 0x25b, 0x7ffa, 0x192, 0x7ffe, 0xc9, 0x7fff, - 0x0, 0x7fff, 0xff37, 0x7fff, 0xfe6e, 0x7ffe, 0xfda5, 0x7ffa, - 0xfcdc, 0x7ff6, 0xfc13, 0x7ff1, 0xfb4a, 0x7fea, 0xfa81, 0x7fe2, - 0xf9b8, 0x7fd9, 0xf8ef, 0x7fce, 0xf827, 0x7fc2, 0xf75e, 0x7fb5, - 0xf695, 0x7fa7, 0xf5cd, 0x7f98, 0xf505, 0x7f87, 0xf43c, 0x7f75, - 0xf374, 0x7f62, 0xf2ac, 0x7f4e, 0xf1e4, 0x7f38, 0xf11c, 0x7f22, - 0xf055, 0x7f0a, 0xef8d, 0x7ef0, 0xeec6, 0x7ed6, 0xedff, 0x7eba, - 0xed38, 0x7e9d, 0xec71, 0x7e7f, 0xebab, 0x7e60, 0xeae4, 0x7e3f, - 0xea1e, 0x7e1e, 0xe958, 0x7dfb, 0xe892, 0x7dd6, 0xe7cd, 0x7db1, - 0xe707, 0x7d8a, 0xe642, 0x7d63, 0xe57d, 0x7d3a, 0xe4b9, 0x7d0f, - 0xe3f4, 0x7ce4, 0xe330, 0x7cb7, 0xe26d, 0x7c89, 0xe1a9, 0x7c5a, - 0xe0e6, 0x7c2a, 0xe023, 0x7bf9, 0xdf61, 0x7bc6, 0xde9e, 0x7b92, - 0xdddc, 0x7b5d, 0xdd1b, 0x7b27, 0xdc59, 0x7aef, 0xdb99, 0x7ab7, - 0xdad8, 0x7a7d, 0xda18, 0x7a42, 0xd958, 0x7a06, 0xd898, 0x79c9, - 0xd7d9, 0x798a, 0xd71b, 0x794a, 0xd65c, 0x790a, 0xd59e, 0x78c8, - 0xd4e1, 0x7885, 0xd424, 0x7840, 0xd367, 0x77fb, 0xd2ab, 0x77b4, - 0xd1ef, 0x776c, 0xd134, 0x7723, 0xd079, 0x76d9, 0xcfbe, 0x768e, - 0xcf04, 0x7642, 0xce4b, 0x75f4, 0xcd92, 0x75a6, 0xccd9, 0x7556, - 0xcc21, 0x7505, 0xcb69, 0x74b3, 0xcab2, 0x7460, 0xc9fc, 0x740b, - 0xc946, 0x73b6, 0xc890, 0x735f, 0xc7db, 0x7308, 0xc727, 0x72af, - 0xc673, 0x7255, 0xc5c0, 0x71fa, 0xc50d, 0x719e, 0xc45b, 0x7141, - 0xc3a9, 0x70e3, 0xc2f8, 0x7083, 0xc248, 0x7023, 0xc198, 0x6fc2, - 0xc0e9, 0x6f5f, 0xc03a, 0x6efb, 0xbf8c, 0x6e97, 0xbedf, 0x6e31, - 0xbe32, 0x6dca, 0xbd86, 0x6d62, 0xbcda, 0x6cf9, 0xbc2f, 0x6c8f, - 0xbb85, 0x6c24, 0xbadc, 0x6bb8, 0xba33, 0x6b4b, 0xb98b, 0x6add, - 0xb8e3, 0x6a6e, 0xb83c, 0x69fd, 0xb796, 0x698c, 0xb6f1, 0x691a, - 0xb64c, 0x68a7, 0xb5a8, 0x6832, 0xb505, 0x67bd, 0xb462, 0x6747, - 0xb3c0, 0x66d0, 0xb31f, 0x6657, 0xb27f, 0x65de, 0xb1df, 0x6564, - 0xb140, 0x64e9, 0xb0a2, 0x646c, 0xb005, 0x63ef, 0xaf68, 0x6371, - 0xaecc, 0x62f2, 0xae31, 0x6272, 0xad97, 0x61f1, 0xacfd, 0x616f, - 0xac65, 0x60ec, 0xabcd, 0x6068, 0xab36, 0x5fe4, 0xaaa0, 0x5f5e, - 0xaa0a, 0x5ed7, 0xa976, 0x5e50, 0xa8e2, 0x5dc8, 0xa84f, 0x5d3e, - 0xa7bd, 0x5cb4, 0xa72c, 0x5c29, 0xa69c, 0x5b9d, 0xa60c, 0x5b10, - 0xa57e, 0x5a82, 0xa4f0, 0x59f4, 0xa463, 0x5964, 0xa3d7, 0x58d4, - 0xa34c, 0x5843, 0xa2c2, 0x57b1, 0xa238, 0x571e, 0xa1b0, 0x568a, - 0xa129, 0x55f6, 0xa0a2, 0x5560, 0xa01c, 0x54ca, 0x9f98, 0x5433, - 0x9f14, 0x539b, 0x9e91, 0x5303, 0x9e0f, 0x5269, 0x9d8e, 0x51cf, - 0x9d0e, 0x5134, 0x9c8f, 0x5098, 0x9c11, 0x4ffb, 0x9b94, 0x4f5e, - 0x9b17, 0x4ec0, 0x9a9c, 0x4e21, 0x9a22, 0x4d81, 0x99a9, 0x4ce1, - 0x9930, 0x4c40, 0x98b9, 0x4b9e, 0x9843, 0x4afb, 0x97ce, 0x4a58, - 0x9759, 0x49b4, 0x96e6, 0x490f, 0x9674, 0x486a, 0x9603, 0x47c4, - 0x9592, 0x471d, 0x9523, 0x4675, 0x94b5, 0x45cd, 0x9448, 0x4524, - 0x93dc, 0x447b, 0x9371, 0x43d1, 0x9307, 0x4326, 0x929e, 0x427a, - 0x9236, 0x41ce, 0x91cf, 0x4121, 0x9169, 0x4074, 0x9105, 0x3fc6, - 0x90a1, 0x3f17, 0x903e, 0x3e68, 0x8fdd, 0x3db8, 0x8f7d, 0x3d08, - 0x8f1d, 0x3c57, 0x8ebf, 0x3ba5, 0x8e62, 0x3af3, 0x8e06, 0x3a40, - 0x8dab, 0x398d, 0x8d51, 0x38d9, 0x8cf8, 0x3825, 0x8ca1, 0x3770, - 0x8c4a, 0x36ba, 0x8bf5, 0x3604, 0x8ba0, 0x354e, 0x8b4d, 0x3497, - 0x8afb, 0x33df, 0x8aaa, 0x3327, 0x8a5a, 0x326e, 0x8a0c, 0x31b5, - 0x89be, 0x30fc, 0x8972, 0x3042, 0x8927, 0x2f87, 0x88dd, 0x2ecc, - 0x8894, 0x2e11, 0x884c, 0x2d55, 0x8805, 0x2c99, 0x87c0, 0x2bdc, - 0x877b, 0x2b1f, 0x8738, 0x2a62, 0x86f6, 0x29a4, 0x86b6, 0x28e5, - 0x8676, 0x2827, 0x8637, 0x2768, 0x85fa, 0x26a8, 0x85be, 0x25e8, - 0x8583, 0x2528, 0x8549, 0x2467, 0x8511, 0x23a7, 0x84d9, 0x22e5, - 0x84a3, 0x2224, 0x846e, 0x2162, 0x843a, 0x209f, 0x8407, 0x1fdd, - 0x83d6, 0x1f1a, 0x83a6, 0x1e57, 0x8377, 0x1d93, 0x8349, 0x1cd0, - 0x831c, 0x1c0c, 0x82f1, 0x1b47, 0x82c6, 0x1a83, 0x829d, 0x19be, - 0x8276, 0x18f9, 0x824f, 0x1833, 0x822a, 0x176e, 0x8205, 0x16a8, - 0x81e2, 0x15e2, 0x81c1, 0x151c, 0x81a0, 0x1455, 0x8181, 0x138f, - 0x8163, 0x12c8, 0x8146, 0x1201, 0x812a, 0x113a, 0x8110, 0x1073, - 0x80f6, 0xfab, 0x80de, 0xee4, 0x80c8, 0xe1c, 0x80b2, 0xd54, - 0x809e, 0xc8c, 0x808b, 0xbc4, 0x8079, 0xafb, 0x8068, 0xa33, - 0x8059, 0x96b, 0x804b, 0x8a2, 0x803e, 0x7d9, 0x8032, 0x711, - 0x8027, 0x648, 0x801e, 0x57f, 0x8016, 0x4b6, 0x800f, 0x3ed, - 0x800a, 0x324, 0x8006, 0x25b, 0x8002, 0x192, 0x8001, 0xc9, - 0x8000, 0x0, 0x8001, 0xff37, 0x8002, 0xfe6e, 0x8006, 0xfda5, - 0x800a, 0xfcdc, 0x800f, 0xfc13, 0x8016, 0xfb4a, 0x801e, 0xfa81, - 0x8027, 0xf9b8, 0x8032, 0xf8ef, 0x803e, 0xf827, 0x804b, 0xf75e, - 0x8059, 0xf695, 0x8068, 0xf5cd, 0x8079, 0xf505, 0x808b, 0xf43c, - 0x809e, 0xf374, 0x80b2, 0xf2ac, 0x80c8, 0xf1e4, 0x80de, 0xf11c, - 0x80f6, 0xf055, 0x8110, 0xef8d, 0x812a, 0xeec6, 0x8146, 0xedff, - 0x8163, 0xed38, 0x8181, 0xec71, 0x81a0, 0xebab, 0x81c1, 0xeae4, - 0x81e2, 0xea1e, 0x8205, 0xe958, 0x822a, 0xe892, 0x824f, 0xe7cd, - 0x8276, 0xe707, 0x829d, 0xe642, 0x82c6, 0xe57d, 0x82f1, 0xe4b9, - 0x831c, 0xe3f4, 0x8349, 0xe330, 0x8377, 0xe26d, 0x83a6, 0xe1a9, - 0x83d6, 0xe0e6, 0x8407, 0xe023, 0x843a, 0xdf61, 0x846e, 0xde9e, - 0x84a3, 0xdddc, 0x84d9, 0xdd1b, 0x8511, 0xdc59, 0x8549, 0xdb99, - 0x8583, 0xdad8, 0x85be, 0xda18, 0x85fa, 0xd958, 0x8637, 0xd898, - 0x8676, 0xd7d9, 0x86b6, 0xd71b, 0x86f6, 0xd65c, 0x8738, 0xd59e, - 0x877b, 0xd4e1, 0x87c0, 0xd424, 0x8805, 0xd367, 0x884c, 0xd2ab, - 0x8894, 0xd1ef, 0x88dd, 0xd134, 0x8927, 0xd079, 0x8972, 0xcfbe, - 0x89be, 0xcf04, 0x8a0c, 0xce4b, 0x8a5a, 0xcd92, 0x8aaa, 0xccd9, - 0x8afb, 0xcc21, 0x8b4d, 0xcb69, 0x8ba0, 0xcab2, 0x8bf5, 0xc9fc, - 0x8c4a, 0xc946, 0x8ca1, 0xc890, 0x8cf8, 0xc7db, 0x8d51, 0xc727, - 0x8dab, 0xc673, 0x8e06, 0xc5c0, 0x8e62, 0xc50d, 0x8ebf, 0xc45b, - 0x8f1d, 0xc3a9, 0x8f7d, 0xc2f8, 0x8fdd, 0xc248, 0x903e, 0xc198, - 0x90a1, 0xc0e9, 0x9105, 0xc03a, 0x9169, 0xbf8c, 0x91cf, 0xbedf, - 0x9236, 0xbe32, 0x929e, 0xbd86, 0x9307, 0xbcda, 0x9371, 0xbc2f, - 0x93dc, 0xbb85, 0x9448, 0xbadc, 0x94b5, 0xba33, 0x9523, 0xb98b, - 0x9592, 0xb8e3, 0x9603, 0xb83c, 0x9674, 0xb796, 0x96e6, 0xb6f1, - 0x9759, 0xb64c, 0x97ce, 0xb5a8, 0x9843, 0xb505, 0x98b9, 0xb462, - 0x9930, 0xb3c0, 0x99a9, 0xb31f, 0x9a22, 0xb27f, 0x9a9c, 0xb1df, - 0x9b17, 0xb140, 0x9b94, 0xb0a2, 0x9c11, 0xb005, 0x9c8f, 0xaf68, - 0x9d0e, 0xaecc, 0x9d8e, 0xae31, 0x9e0f, 0xad97, 0x9e91, 0xacfd, - 0x9f14, 0xac65, 0x9f98, 0xabcd, 0xa01c, 0xab36, 0xa0a2, 0xaaa0, - 0xa129, 0xaa0a, 0xa1b0, 0xa976, 0xa238, 0xa8e2, 0xa2c2, 0xa84f, - 0xa34c, 0xa7bd, 0xa3d7, 0xa72c, 0xa463, 0xa69c, 0xa4f0, 0xa60c, - 0xa57e, 0xa57e, 0xa60c, 0xa4f0, 0xa69c, 0xa463, 0xa72c, 0xa3d7, - 0xa7bd, 0xa34c, 0xa84f, 0xa2c2, 0xa8e2, 0xa238, 0xa976, 0xa1b0, - 0xaa0a, 0xa129, 0xaaa0, 0xa0a2, 0xab36, 0xa01c, 0xabcd, 0x9f98, - 0xac65, 0x9f14, 0xacfd, 0x9e91, 0xad97, 0x9e0f, 0xae31, 0x9d8e, - 0xaecc, 0x9d0e, 0xaf68, 0x9c8f, 0xb005, 0x9c11, 0xb0a2, 0x9b94, - 0xb140, 0x9b17, 0xb1df, 0x9a9c, 0xb27f, 0x9a22, 0xb31f, 0x99a9, - 0xb3c0, 0x9930, 0xb462, 0x98b9, 0xb505, 0x9843, 0xb5a8, 0x97ce, - 0xb64c, 0x9759, 0xb6f1, 0x96e6, 0xb796, 0x9674, 0xb83c, 0x9603, - 0xb8e3, 0x9592, 0xb98b, 0x9523, 0xba33, 0x94b5, 0xbadc, 0x9448, - 0xbb85, 0x93dc, 0xbc2f, 0x9371, 0xbcda, 0x9307, 0xbd86, 0x929e, - 0xbe32, 0x9236, 0xbedf, 0x91cf, 0xbf8c, 0x9169, 0xc03a, 0x9105, - 0xc0e9, 0x90a1, 0xc198, 0x903e, 0xc248, 0x8fdd, 0xc2f8, 0x8f7d, - 0xc3a9, 0x8f1d, 0xc45b, 0x8ebf, 0xc50d, 0x8e62, 0xc5c0, 0x8e06, - 0xc673, 0x8dab, 0xc727, 0x8d51, 0xc7db, 0x8cf8, 0xc890, 0x8ca1, - 0xc946, 0x8c4a, 0xc9fc, 0x8bf5, 0xcab2, 0x8ba0, 0xcb69, 0x8b4d, - 0xcc21, 0x8afb, 0xccd9, 0x8aaa, 0xcd92, 0x8a5a, 0xce4b, 0x8a0c, - 0xcf04, 0x89be, 0xcfbe, 0x8972, 0xd079, 0x8927, 0xd134, 0x88dd, - 0xd1ef, 0x8894, 0xd2ab, 0x884c, 0xd367, 0x8805, 0xd424, 0x87c0, - 0xd4e1, 0x877b, 0xd59e, 0x8738, 0xd65c, 0x86f6, 0xd71b, 0x86b6, - 0xd7d9, 0x8676, 0xd898, 0x8637, 0xd958, 0x85fa, 0xda18, 0x85be, - 0xdad8, 0x8583, 0xdb99, 0x8549, 0xdc59, 0x8511, 0xdd1b, 0x84d9, - 0xdddc, 0x84a3, 0xde9e, 0x846e, 0xdf61, 0x843a, 0xe023, 0x8407, - 0xe0e6, 0x83d6, 0xe1a9, 0x83a6, 0xe26d, 0x8377, 0xe330, 0x8349, - 0xe3f4, 0x831c, 0xe4b9, 0x82f1, 0xe57d, 0x82c6, 0xe642, 0x829d, - 0xe707, 0x8276, 0xe7cd, 0x824f, 0xe892, 0x822a, 0xe958, 0x8205, - 0xea1e, 0x81e2, 0xeae4, 0x81c1, 0xebab, 0x81a0, 0xec71, 0x8181, - 0xed38, 0x8163, 0xedff, 0x8146, 0xeec6, 0x812a, 0xef8d, 0x8110, - 0xf055, 0x80f6, 0xf11c, 0x80de, 0xf1e4, 0x80c8, 0xf2ac, 0x80b2, - 0xf374, 0x809e, 0xf43c, 0x808b, 0xf505, 0x8079, 0xf5cd, 0x8068, - 0xf695, 0x8059, 0xf75e, 0x804b, 0xf827, 0x803e, 0xf8ef, 0x8032, - 0xf9b8, 0x8027, 0xfa81, 0x801e, 0xfb4a, 0x8016, 0xfc13, 0x800f, - 0xfcdc, 0x800a, 0xfda5, 0x8006, 0xfe6e, 0x8002, 0xff37, 0x8001, - 0x0, 0x8000, 0xc9, 0x8001, 0x192, 0x8002, 0x25b, 0x8006, - 0x324, 0x800a, 0x3ed, 0x800f, 0x4b6, 0x8016, 0x57f, 0x801e, - 0x648, 0x8027, 0x711, 0x8032, 0x7d9, 0x803e, 0x8a2, 0x804b, - 0x96b, 0x8059, 0xa33, 0x8068, 0xafb, 0x8079, 0xbc4, 0x808b, - 0xc8c, 0x809e, 0xd54, 0x80b2, 0xe1c, 0x80c8, 0xee4, 0x80de, - 0xfab, 0x80f6, 0x1073, 0x8110, 0x113a, 0x812a, 0x1201, 0x8146, - 0x12c8, 0x8163, 0x138f, 0x8181, 0x1455, 0x81a0, 0x151c, 0x81c1, - 0x15e2, 0x81e2, 0x16a8, 0x8205, 0x176e, 0x822a, 0x1833, 0x824f, - 0x18f9, 0x8276, 0x19be, 0x829d, 0x1a83, 0x82c6, 0x1b47, 0x82f1, - 0x1c0c, 0x831c, 0x1cd0, 0x8349, 0x1d93, 0x8377, 0x1e57, 0x83a6, - 0x1f1a, 0x83d6, 0x1fdd, 0x8407, 0x209f, 0x843a, 0x2162, 0x846e, - 0x2224, 0x84a3, 0x22e5, 0x84d9, 0x23a7, 0x8511, 0x2467, 0x8549, - 0x2528, 0x8583, 0x25e8, 0x85be, 0x26a8, 0x85fa, 0x2768, 0x8637, - 0x2827, 0x8676, 0x28e5, 0x86b6, 0x29a4, 0x86f6, 0x2a62, 0x8738, - 0x2b1f, 0x877b, 0x2bdc, 0x87c0, 0x2c99, 0x8805, 0x2d55, 0x884c, - 0x2e11, 0x8894, 0x2ecc, 0x88dd, 0x2f87, 0x8927, 0x3042, 0x8972, - 0x30fc, 0x89be, 0x31b5, 0x8a0c, 0x326e, 0x8a5a, 0x3327, 0x8aaa, - 0x33df, 0x8afb, 0x3497, 0x8b4d, 0x354e, 0x8ba0, 0x3604, 0x8bf5, - 0x36ba, 0x8c4a, 0x3770, 0x8ca1, 0x3825, 0x8cf8, 0x38d9, 0x8d51, - 0x398d, 0x8dab, 0x3a40, 0x8e06, 0x3af3, 0x8e62, 0x3ba5, 0x8ebf, - 0x3c57, 0x8f1d, 0x3d08, 0x8f7d, 0x3db8, 0x8fdd, 0x3e68, 0x903e, - 0x3f17, 0x90a1, 0x3fc6, 0x9105, 0x4074, 0x9169, 0x4121, 0x91cf, - 0x41ce, 0x9236, 0x427a, 0x929e, 0x4326, 0x9307, 0x43d1, 0x9371, - 0x447b, 0x93dc, 0x4524, 0x9448, 0x45cd, 0x94b5, 0x4675, 0x9523, - 0x471d, 0x9592, 0x47c4, 0x9603, 0x486a, 0x9674, 0x490f, 0x96e6, - 0x49b4, 0x9759, 0x4a58, 0x97ce, 0x4afb, 0x9843, 0x4b9e, 0x98b9, - 0x4c40, 0x9930, 0x4ce1, 0x99a9, 0x4d81, 0x9a22, 0x4e21, 0x9a9c, - 0x4ec0, 0x9b17, 0x4f5e, 0x9b94, 0x4ffb, 0x9c11, 0x5098, 0x9c8f, - 0x5134, 0x9d0e, 0x51cf, 0x9d8e, 0x5269, 0x9e0f, 0x5303, 0x9e91, - 0x539b, 0x9f14, 0x5433, 0x9f98, 0x54ca, 0xa01c, 0x5560, 0xa0a2, - 0x55f6, 0xa129, 0x568a, 0xa1b0, 0x571e, 0xa238, 0x57b1, 0xa2c2, - 0x5843, 0xa34c, 0x58d4, 0xa3d7, 0x5964, 0xa463, 0x59f4, 0xa4f0, - 0x5a82, 0xa57e, 0x5b10, 0xa60c, 0x5b9d, 0xa69c, 0x5c29, 0xa72c, - 0x5cb4, 0xa7bd, 0x5d3e, 0xa84f, 0x5dc8, 0xa8e2, 0x5e50, 0xa976, - 0x5ed7, 0xaa0a, 0x5f5e, 0xaaa0, 0x5fe4, 0xab36, 0x6068, 0xabcd, - 0x60ec, 0xac65, 0x616f, 0xacfd, 0x61f1, 0xad97, 0x6272, 0xae31, - 0x62f2, 0xaecc, 0x6371, 0xaf68, 0x63ef, 0xb005, 0x646c, 0xb0a2, - 0x64e9, 0xb140, 0x6564, 0xb1df, 0x65de, 0xb27f, 0x6657, 0xb31f, - 0x66d0, 0xb3c0, 0x6747, 0xb462, 0x67bd, 0xb505, 0x6832, 0xb5a8, - 0x68a7, 0xb64c, 0x691a, 0xb6f1, 0x698c, 0xb796, 0x69fd, 0xb83c, - 0x6a6e, 0xb8e3, 0x6add, 0xb98b, 0x6b4b, 0xba33, 0x6bb8, 0xbadc, - 0x6c24, 0xbb85, 0x6c8f, 0xbc2f, 0x6cf9, 0xbcda, 0x6d62, 0xbd86, - 0x6dca, 0xbe32, 0x6e31, 0xbedf, 0x6e97, 0xbf8c, 0x6efb, 0xc03a, - 0x6f5f, 0xc0e9, 0x6fc2, 0xc198, 0x7023, 0xc248, 0x7083, 0xc2f8, - 0x70e3, 0xc3a9, 0x7141, 0xc45b, 0x719e, 0xc50d, 0x71fa, 0xc5c0, - 0x7255, 0xc673, 0x72af, 0xc727, 0x7308, 0xc7db, 0x735f, 0xc890, - 0x73b6, 0xc946, 0x740b, 0xc9fc, 0x7460, 0xcab2, 0x74b3, 0xcb69, - 0x7505, 0xcc21, 0x7556, 0xccd9, 0x75a6, 0xcd92, 0x75f4, 0xce4b, - 0x7642, 0xcf04, 0x768e, 0xcfbe, 0x76d9, 0xd079, 0x7723, 0xd134, - 0x776c, 0xd1ef, 0x77b4, 0xd2ab, 0x77fb, 0xd367, 0x7840, 0xd424, - 0x7885, 0xd4e1, 0x78c8, 0xd59e, 0x790a, 0xd65c, 0x794a, 0xd71b, - 0x798a, 0xd7d9, 0x79c9, 0xd898, 0x7a06, 0xd958, 0x7a42, 0xda18, - 0x7a7d, 0xdad8, 0x7ab7, 0xdb99, 0x7aef, 0xdc59, 0x7b27, 0xdd1b, - 0x7b5d, 0xdddc, 0x7b92, 0xde9e, 0x7bc6, 0xdf61, 0x7bf9, 0xe023, - 0x7c2a, 0xe0e6, 0x7c5a, 0xe1a9, 0x7c89, 0xe26d, 0x7cb7, 0xe330, - 0x7ce4, 0xe3f4, 0x7d0f, 0xe4b9, 0x7d3a, 0xe57d, 0x7d63, 0xe642, - 0x7d8a, 0xe707, 0x7db1, 0xe7cd, 0x7dd6, 0xe892, 0x7dfb, 0xe958, - 0x7e1e, 0xea1e, 0x7e3f, 0xeae4, 0x7e60, 0xebab, 0x7e7f, 0xec71, - 0x7e9d, 0xed38, 0x7eba, 0xedff, 0x7ed6, 0xeec6, 0x7ef0, 0xef8d, - 0x7f0a, 0xf055, 0x7f22, 0xf11c, 0x7f38, 0xf1e4, 0x7f4e, 0xf2ac, - 0x7f62, 0xf374, 0x7f75, 0xf43c, 0x7f87, 0xf505, 0x7f98, 0xf5cd, - 0x7fa7, 0xf695, 0x7fb5, 0xf75e, 0x7fc2, 0xf827, 0x7fce, 0xf8ef, - 0x7fd9, 0xf9b8, 0x7fe2, 0xfa81, 0x7fea, 0xfb4a, 0x7ff1, 0xfc13, - 0x7ff6, 0xfcdc, 0x7ffa, 0xfda5, 0x7ffe, 0xfe6e, 0x7fff, 0xff37 -}; - - -/** -* @brief Initialization function for the Q15 CFFT/CIFFT. -* @param[in,out] *S points to an instance of the Q15 CFFT/CIFFT structure. -* @param[in] fftLen length of the FFT. -* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. -* -* \par Description: -* \par -* The parameter ifftFlag controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. -* \par -* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. -*/ - -arm_status arm_cfft_radix4_init_q15( - arm_cfft_radix4_instance_q15 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - /* Initialise the FFT length */ - S->fftLen = fftLen; - /* Initialise the Twiddle coefficient pointer */ - S->pTwiddle = (q15_t *) twiddleCoefQ15; - /* Initialise the Flag for selection of CFFT or CIFFT */ - S->ifftFlag = ifftFlag; - /* Initialise the Flag for calculation Bit reversal or not */ - S->bitReverseFlag = bitReverseFlag; - - /* Initializations of structure parameters depending on the FFT length */ - switch (S->fftLen) - { - /* Initializations of structure parameters for 1024 point FFT */ - case 1024u: - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 1u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 1u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = armBitRevTable; - - break; - case 256u: - /* Initializations of structure parameters for 2566 point FFT */ - S->twidCoefModifier = 4u; - S->bitRevFactor = 4u; - S->pBitRevTable = &armBitRevTable[3]; - - break; - case 64u: - /* Initializations of structure parameters for 64 point FFT */ - S->twidCoefModifier = 16u; - S->bitRevFactor = 16u; - S->pBitRevTable = &armBitRevTable[15]; - - break; - case 16u: - /* Initializations of structure parameters for 16 point FFT */ - S->twidCoefModifier = 64u; - S->bitRevFactor = 64u; - S->pBitRevTable = &armBitRevTable[63]; - - break; - default: - /* Reporting argument error if fftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - return (status); -} - -/** - * @} end of CFFT_CIFFT group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_cfft_radix4_init_q15.c +* +* Description: Radix-4 Decimation in Frequency Q15 FFT & IFFT initialization function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" +#include "arm_common_tables.h" + +/** + * @ingroup groupTransforms + */ + + +/** + * @addtogroup CFFT_CIFFT + * @{ + */ + +/* +* @brief Twiddle factors Table +*/ + +/** +* \par +* Example code for Q15 Twiddle factors Generation:: +* \par +*
for(i = 0; i< N; i++)   
+* {   
+*	twiddleCoefQ15[2*i]= cos(i * 2*PI/(float)N);   
+*	twiddleCoefQ15[2*i+1]= sin(i * 2*PI/(float)N);   
+* } 
+* \par +* where N = 1024 and PI = 3.14159265358979 +* \par +* Cos and Sin values are interleaved fashion +* \par +* Convert Floating point to Q15(Fixed point 1.15): +* round(twiddleCoefQ15(i) * pow(2, 15)) +* +*/ + +static const q15_t twiddleCoefQ15[2048] = { + 0x7fff, 0x0, 0x7fff, 0xc9, 0x7ffe, 0x192, 0x7ffa, 0x25b, + 0x7ff6, 0x324, 0x7ff1, 0x3ed, 0x7fea, 0x4b6, 0x7fe2, 0x57f, + 0x7fd9, 0x648, 0x7fce, 0x711, 0x7fc2, 0x7d9, 0x7fb5, 0x8a2, + 0x7fa7, 0x96b, 0x7f98, 0xa33, 0x7f87, 0xafb, 0x7f75, 0xbc4, + 0x7f62, 0xc8c, 0x7f4e, 0xd54, 0x7f38, 0xe1c, 0x7f22, 0xee4, + 0x7f0a, 0xfab, 0x7ef0, 0x1073, 0x7ed6, 0x113a, 0x7eba, 0x1201, + 0x7e9d, 0x12c8, 0x7e7f, 0x138f, 0x7e60, 0x1455, 0x7e3f, 0x151c, + 0x7e1e, 0x15e2, 0x7dfb, 0x16a8, 0x7dd6, 0x176e, 0x7db1, 0x1833, + 0x7d8a, 0x18f9, 0x7d63, 0x19be, 0x7d3a, 0x1a83, 0x7d0f, 0x1b47, + 0x7ce4, 0x1c0c, 0x7cb7, 0x1cd0, 0x7c89, 0x1d93, 0x7c5a, 0x1e57, + 0x7c2a, 0x1f1a, 0x7bf9, 0x1fdd, 0x7bc6, 0x209f, 0x7b92, 0x2162, + 0x7b5d, 0x2224, 0x7b27, 0x22e5, 0x7aef, 0x23a7, 0x7ab7, 0x2467, + 0x7a7d, 0x2528, 0x7a42, 0x25e8, 0x7a06, 0x26a8, 0x79c9, 0x2768, + 0x798a, 0x2827, 0x794a, 0x28e5, 0x790a, 0x29a4, 0x78c8, 0x2a62, + 0x7885, 0x2b1f, 0x7840, 0x2bdc, 0x77fb, 0x2c99, 0x77b4, 0x2d55, + 0x776c, 0x2e11, 0x7723, 0x2ecc, 0x76d9, 0x2f87, 0x768e, 0x3042, + 0x7642, 0x30fc, 0x75f4, 0x31b5, 0x75a6, 0x326e, 0x7556, 0x3327, + 0x7505, 0x33df, 0x74b3, 0x3497, 0x7460, 0x354e, 0x740b, 0x3604, + 0x73b6, 0x36ba, 0x735f, 0x3770, 0x7308, 0x3825, 0x72af, 0x38d9, + 0x7255, 0x398d, 0x71fa, 0x3a40, 0x719e, 0x3af3, 0x7141, 0x3ba5, + 0x70e3, 0x3c57, 0x7083, 0x3d08, 0x7023, 0x3db8, 0x6fc2, 0x3e68, + 0x6f5f, 0x3f17, 0x6efb, 0x3fc6, 0x6e97, 0x4074, 0x6e31, 0x4121, + 0x6dca, 0x41ce, 0x6d62, 0x427a, 0x6cf9, 0x4326, 0x6c8f, 0x43d1, + 0x6c24, 0x447b, 0x6bb8, 0x4524, 0x6b4b, 0x45cd, 0x6add, 0x4675, + 0x6a6e, 0x471d, 0x69fd, 0x47c4, 0x698c, 0x486a, 0x691a, 0x490f, + 0x68a7, 0x49b4, 0x6832, 0x4a58, 0x67bd, 0x4afb, 0x6747, 0x4b9e, + 0x66d0, 0x4c40, 0x6657, 0x4ce1, 0x65de, 0x4d81, 0x6564, 0x4e21, + 0x64e9, 0x4ec0, 0x646c, 0x4f5e, 0x63ef, 0x4ffb, 0x6371, 0x5098, + 0x62f2, 0x5134, 0x6272, 0x51cf, 0x61f1, 0x5269, 0x616f, 0x5303, + 0x60ec, 0x539b, 0x6068, 0x5433, 0x5fe4, 0x54ca, 0x5f5e, 0x5560, + 0x5ed7, 0x55f6, 0x5e50, 0x568a, 0x5dc8, 0x571e, 0x5d3e, 0x57b1, + 0x5cb4, 0x5843, 0x5c29, 0x58d4, 0x5b9d, 0x5964, 0x5b10, 0x59f4, + 0x5a82, 0x5a82, 0x59f4, 0x5b10, 0x5964, 0x5b9d, 0x58d4, 0x5c29, + 0x5843, 0x5cb4, 0x57b1, 0x5d3e, 0x571e, 0x5dc8, 0x568a, 0x5e50, + 0x55f6, 0x5ed7, 0x5560, 0x5f5e, 0x54ca, 0x5fe4, 0x5433, 0x6068, + 0x539b, 0x60ec, 0x5303, 0x616f, 0x5269, 0x61f1, 0x51cf, 0x6272, + 0x5134, 0x62f2, 0x5098, 0x6371, 0x4ffb, 0x63ef, 0x4f5e, 0x646c, + 0x4ec0, 0x64e9, 0x4e21, 0x6564, 0x4d81, 0x65de, 0x4ce1, 0x6657, + 0x4c40, 0x66d0, 0x4b9e, 0x6747, 0x4afb, 0x67bd, 0x4a58, 0x6832, + 0x49b4, 0x68a7, 0x490f, 0x691a, 0x486a, 0x698c, 0x47c4, 0x69fd, + 0x471d, 0x6a6e, 0x4675, 0x6add, 0x45cd, 0x6b4b, 0x4524, 0x6bb8, + 0x447b, 0x6c24, 0x43d1, 0x6c8f, 0x4326, 0x6cf9, 0x427a, 0x6d62, + 0x41ce, 0x6dca, 0x4121, 0x6e31, 0x4074, 0x6e97, 0x3fc6, 0x6efb, + 0x3f17, 0x6f5f, 0x3e68, 0x6fc2, 0x3db8, 0x7023, 0x3d08, 0x7083, + 0x3c57, 0x70e3, 0x3ba5, 0x7141, 0x3af3, 0x719e, 0x3a40, 0x71fa, + 0x398d, 0x7255, 0x38d9, 0x72af, 0x3825, 0x7308, 0x3770, 0x735f, + 0x36ba, 0x73b6, 0x3604, 0x740b, 0x354e, 0x7460, 0x3497, 0x74b3, + 0x33df, 0x7505, 0x3327, 0x7556, 0x326e, 0x75a6, 0x31b5, 0x75f4, + 0x30fc, 0x7642, 0x3042, 0x768e, 0x2f87, 0x76d9, 0x2ecc, 0x7723, + 0x2e11, 0x776c, 0x2d55, 0x77b4, 0x2c99, 0x77fb, 0x2bdc, 0x7840, + 0x2b1f, 0x7885, 0x2a62, 0x78c8, 0x29a4, 0x790a, 0x28e5, 0x794a, + 0x2827, 0x798a, 0x2768, 0x79c9, 0x26a8, 0x7a06, 0x25e8, 0x7a42, + 0x2528, 0x7a7d, 0x2467, 0x7ab7, 0x23a7, 0x7aef, 0x22e5, 0x7b27, + 0x2224, 0x7b5d, 0x2162, 0x7b92, 0x209f, 0x7bc6, 0x1fdd, 0x7bf9, + 0x1f1a, 0x7c2a, 0x1e57, 0x7c5a, 0x1d93, 0x7c89, 0x1cd0, 0x7cb7, + 0x1c0c, 0x7ce4, 0x1b47, 0x7d0f, 0x1a83, 0x7d3a, 0x19be, 0x7d63, + 0x18f9, 0x7d8a, 0x1833, 0x7db1, 0x176e, 0x7dd6, 0x16a8, 0x7dfb, + 0x15e2, 0x7e1e, 0x151c, 0x7e3f, 0x1455, 0x7e60, 0x138f, 0x7e7f, + 0x12c8, 0x7e9d, 0x1201, 0x7eba, 0x113a, 0x7ed6, 0x1073, 0x7ef0, + 0xfab, 0x7f0a, 0xee4, 0x7f22, 0xe1c, 0x7f38, 0xd54, 0x7f4e, + 0xc8c, 0x7f62, 0xbc4, 0x7f75, 0xafb, 0x7f87, 0xa33, 0x7f98, + 0x96b, 0x7fa7, 0x8a2, 0x7fb5, 0x7d9, 0x7fc2, 0x711, 0x7fce, + 0x648, 0x7fd9, 0x57f, 0x7fe2, 0x4b6, 0x7fea, 0x3ed, 0x7ff1, + 0x324, 0x7ff6, 0x25b, 0x7ffa, 0x192, 0x7ffe, 0xc9, 0x7fff, + 0x0, 0x7fff, 0xff37, 0x7fff, 0xfe6e, 0x7ffe, 0xfda5, 0x7ffa, + 0xfcdc, 0x7ff6, 0xfc13, 0x7ff1, 0xfb4a, 0x7fea, 0xfa81, 0x7fe2, + 0xf9b8, 0x7fd9, 0xf8ef, 0x7fce, 0xf827, 0x7fc2, 0xf75e, 0x7fb5, + 0xf695, 0x7fa7, 0xf5cd, 0x7f98, 0xf505, 0x7f87, 0xf43c, 0x7f75, + 0xf374, 0x7f62, 0xf2ac, 0x7f4e, 0xf1e4, 0x7f38, 0xf11c, 0x7f22, + 0xf055, 0x7f0a, 0xef8d, 0x7ef0, 0xeec6, 0x7ed6, 0xedff, 0x7eba, + 0xed38, 0x7e9d, 0xec71, 0x7e7f, 0xebab, 0x7e60, 0xeae4, 0x7e3f, + 0xea1e, 0x7e1e, 0xe958, 0x7dfb, 0xe892, 0x7dd6, 0xe7cd, 0x7db1, + 0xe707, 0x7d8a, 0xe642, 0x7d63, 0xe57d, 0x7d3a, 0xe4b9, 0x7d0f, + 0xe3f4, 0x7ce4, 0xe330, 0x7cb7, 0xe26d, 0x7c89, 0xe1a9, 0x7c5a, + 0xe0e6, 0x7c2a, 0xe023, 0x7bf9, 0xdf61, 0x7bc6, 0xde9e, 0x7b92, + 0xdddc, 0x7b5d, 0xdd1b, 0x7b27, 0xdc59, 0x7aef, 0xdb99, 0x7ab7, + 0xdad8, 0x7a7d, 0xda18, 0x7a42, 0xd958, 0x7a06, 0xd898, 0x79c9, + 0xd7d9, 0x798a, 0xd71b, 0x794a, 0xd65c, 0x790a, 0xd59e, 0x78c8, + 0xd4e1, 0x7885, 0xd424, 0x7840, 0xd367, 0x77fb, 0xd2ab, 0x77b4, + 0xd1ef, 0x776c, 0xd134, 0x7723, 0xd079, 0x76d9, 0xcfbe, 0x768e, + 0xcf04, 0x7642, 0xce4b, 0x75f4, 0xcd92, 0x75a6, 0xccd9, 0x7556, + 0xcc21, 0x7505, 0xcb69, 0x74b3, 0xcab2, 0x7460, 0xc9fc, 0x740b, + 0xc946, 0x73b6, 0xc890, 0x735f, 0xc7db, 0x7308, 0xc727, 0x72af, + 0xc673, 0x7255, 0xc5c0, 0x71fa, 0xc50d, 0x719e, 0xc45b, 0x7141, + 0xc3a9, 0x70e3, 0xc2f8, 0x7083, 0xc248, 0x7023, 0xc198, 0x6fc2, + 0xc0e9, 0x6f5f, 0xc03a, 0x6efb, 0xbf8c, 0x6e97, 0xbedf, 0x6e31, + 0xbe32, 0x6dca, 0xbd86, 0x6d62, 0xbcda, 0x6cf9, 0xbc2f, 0x6c8f, + 0xbb85, 0x6c24, 0xbadc, 0x6bb8, 0xba33, 0x6b4b, 0xb98b, 0x6add, + 0xb8e3, 0x6a6e, 0xb83c, 0x69fd, 0xb796, 0x698c, 0xb6f1, 0x691a, + 0xb64c, 0x68a7, 0xb5a8, 0x6832, 0xb505, 0x67bd, 0xb462, 0x6747, + 0xb3c0, 0x66d0, 0xb31f, 0x6657, 0xb27f, 0x65de, 0xb1df, 0x6564, + 0xb140, 0x64e9, 0xb0a2, 0x646c, 0xb005, 0x63ef, 0xaf68, 0x6371, + 0xaecc, 0x62f2, 0xae31, 0x6272, 0xad97, 0x61f1, 0xacfd, 0x616f, + 0xac65, 0x60ec, 0xabcd, 0x6068, 0xab36, 0x5fe4, 0xaaa0, 0x5f5e, + 0xaa0a, 0x5ed7, 0xa976, 0x5e50, 0xa8e2, 0x5dc8, 0xa84f, 0x5d3e, + 0xa7bd, 0x5cb4, 0xa72c, 0x5c29, 0xa69c, 0x5b9d, 0xa60c, 0x5b10, + 0xa57e, 0x5a82, 0xa4f0, 0x59f4, 0xa463, 0x5964, 0xa3d7, 0x58d4, + 0xa34c, 0x5843, 0xa2c2, 0x57b1, 0xa238, 0x571e, 0xa1b0, 0x568a, + 0xa129, 0x55f6, 0xa0a2, 0x5560, 0xa01c, 0x54ca, 0x9f98, 0x5433, + 0x9f14, 0x539b, 0x9e91, 0x5303, 0x9e0f, 0x5269, 0x9d8e, 0x51cf, + 0x9d0e, 0x5134, 0x9c8f, 0x5098, 0x9c11, 0x4ffb, 0x9b94, 0x4f5e, + 0x9b17, 0x4ec0, 0x9a9c, 0x4e21, 0x9a22, 0x4d81, 0x99a9, 0x4ce1, + 0x9930, 0x4c40, 0x98b9, 0x4b9e, 0x9843, 0x4afb, 0x97ce, 0x4a58, + 0x9759, 0x49b4, 0x96e6, 0x490f, 0x9674, 0x486a, 0x9603, 0x47c4, + 0x9592, 0x471d, 0x9523, 0x4675, 0x94b5, 0x45cd, 0x9448, 0x4524, + 0x93dc, 0x447b, 0x9371, 0x43d1, 0x9307, 0x4326, 0x929e, 0x427a, + 0x9236, 0x41ce, 0x91cf, 0x4121, 0x9169, 0x4074, 0x9105, 0x3fc6, + 0x90a1, 0x3f17, 0x903e, 0x3e68, 0x8fdd, 0x3db8, 0x8f7d, 0x3d08, + 0x8f1d, 0x3c57, 0x8ebf, 0x3ba5, 0x8e62, 0x3af3, 0x8e06, 0x3a40, + 0x8dab, 0x398d, 0x8d51, 0x38d9, 0x8cf8, 0x3825, 0x8ca1, 0x3770, + 0x8c4a, 0x36ba, 0x8bf5, 0x3604, 0x8ba0, 0x354e, 0x8b4d, 0x3497, + 0x8afb, 0x33df, 0x8aaa, 0x3327, 0x8a5a, 0x326e, 0x8a0c, 0x31b5, + 0x89be, 0x30fc, 0x8972, 0x3042, 0x8927, 0x2f87, 0x88dd, 0x2ecc, + 0x8894, 0x2e11, 0x884c, 0x2d55, 0x8805, 0x2c99, 0x87c0, 0x2bdc, + 0x877b, 0x2b1f, 0x8738, 0x2a62, 0x86f6, 0x29a4, 0x86b6, 0x28e5, + 0x8676, 0x2827, 0x8637, 0x2768, 0x85fa, 0x26a8, 0x85be, 0x25e8, + 0x8583, 0x2528, 0x8549, 0x2467, 0x8511, 0x23a7, 0x84d9, 0x22e5, + 0x84a3, 0x2224, 0x846e, 0x2162, 0x843a, 0x209f, 0x8407, 0x1fdd, + 0x83d6, 0x1f1a, 0x83a6, 0x1e57, 0x8377, 0x1d93, 0x8349, 0x1cd0, + 0x831c, 0x1c0c, 0x82f1, 0x1b47, 0x82c6, 0x1a83, 0x829d, 0x19be, + 0x8276, 0x18f9, 0x824f, 0x1833, 0x822a, 0x176e, 0x8205, 0x16a8, + 0x81e2, 0x15e2, 0x81c1, 0x151c, 0x81a0, 0x1455, 0x8181, 0x138f, + 0x8163, 0x12c8, 0x8146, 0x1201, 0x812a, 0x113a, 0x8110, 0x1073, + 0x80f6, 0xfab, 0x80de, 0xee4, 0x80c8, 0xe1c, 0x80b2, 0xd54, + 0x809e, 0xc8c, 0x808b, 0xbc4, 0x8079, 0xafb, 0x8068, 0xa33, + 0x8059, 0x96b, 0x804b, 0x8a2, 0x803e, 0x7d9, 0x8032, 0x711, + 0x8027, 0x648, 0x801e, 0x57f, 0x8016, 0x4b6, 0x800f, 0x3ed, + 0x800a, 0x324, 0x8006, 0x25b, 0x8002, 0x192, 0x8001, 0xc9, + 0x8000, 0x0, 0x8001, 0xff37, 0x8002, 0xfe6e, 0x8006, 0xfda5, + 0x800a, 0xfcdc, 0x800f, 0xfc13, 0x8016, 0xfb4a, 0x801e, 0xfa81, + 0x8027, 0xf9b8, 0x8032, 0xf8ef, 0x803e, 0xf827, 0x804b, 0xf75e, + 0x8059, 0xf695, 0x8068, 0xf5cd, 0x8079, 0xf505, 0x808b, 0xf43c, + 0x809e, 0xf374, 0x80b2, 0xf2ac, 0x80c8, 0xf1e4, 0x80de, 0xf11c, + 0x80f6, 0xf055, 0x8110, 0xef8d, 0x812a, 0xeec6, 0x8146, 0xedff, + 0x8163, 0xed38, 0x8181, 0xec71, 0x81a0, 0xebab, 0x81c1, 0xeae4, + 0x81e2, 0xea1e, 0x8205, 0xe958, 0x822a, 0xe892, 0x824f, 0xe7cd, + 0x8276, 0xe707, 0x829d, 0xe642, 0x82c6, 0xe57d, 0x82f1, 0xe4b9, + 0x831c, 0xe3f4, 0x8349, 0xe330, 0x8377, 0xe26d, 0x83a6, 0xe1a9, + 0x83d6, 0xe0e6, 0x8407, 0xe023, 0x843a, 0xdf61, 0x846e, 0xde9e, + 0x84a3, 0xdddc, 0x84d9, 0xdd1b, 0x8511, 0xdc59, 0x8549, 0xdb99, + 0x8583, 0xdad8, 0x85be, 0xda18, 0x85fa, 0xd958, 0x8637, 0xd898, + 0x8676, 0xd7d9, 0x86b6, 0xd71b, 0x86f6, 0xd65c, 0x8738, 0xd59e, + 0x877b, 0xd4e1, 0x87c0, 0xd424, 0x8805, 0xd367, 0x884c, 0xd2ab, + 0x8894, 0xd1ef, 0x88dd, 0xd134, 0x8927, 0xd079, 0x8972, 0xcfbe, + 0x89be, 0xcf04, 0x8a0c, 0xce4b, 0x8a5a, 0xcd92, 0x8aaa, 0xccd9, + 0x8afb, 0xcc21, 0x8b4d, 0xcb69, 0x8ba0, 0xcab2, 0x8bf5, 0xc9fc, + 0x8c4a, 0xc946, 0x8ca1, 0xc890, 0x8cf8, 0xc7db, 0x8d51, 0xc727, + 0x8dab, 0xc673, 0x8e06, 0xc5c0, 0x8e62, 0xc50d, 0x8ebf, 0xc45b, + 0x8f1d, 0xc3a9, 0x8f7d, 0xc2f8, 0x8fdd, 0xc248, 0x903e, 0xc198, + 0x90a1, 0xc0e9, 0x9105, 0xc03a, 0x9169, 0xbf8c, 0x91cf, 0xbedf, + 0x9236, 0xbe32, 0x929e, 0xbd86, 0x9307, 0xbcda, 0x9371, 0xbc2f, + 0x93dc, 0xbb85, 0x9448, 0xbadc, 0x94b5, 0xba33, 0x9523, 0xb98b, + 0x9592, 0xb8e3, 0x9603, 0xb83c, 0x9674, 0xb796, 0x96e6, 0xb6f1, + 0x9759, 0xb64c, 0x97ce, 0xb5a8, 0x9843, 0xb505, 0x98b9, 0xb462, + 0x9930, 0xb3c0, 0x99a9, 0xb31f, 0x9a22, 0xb27f, 0x9a9c, 0xb1df, + 0x9b17, 0xb140, 0x9b94, 0xb0a2, 0x9c11, 0xb005, 0x9c8f, 0xaf68, + 0x9d0e, 0xaecc, 0x9d8e, 0xae31, 0x9e0f, 0xad97, 0x9e91, 0xacfd, + 0x9f14, 0xac65, 0x9f98, 0xabcd, 0xa01c, 0xab36, 0xa0a2, 0xaaa0, + 0xa129, 0xaa0a, 0xa1b0, 0xa976, 0xa238, 0xa8e2, 0xa2c2, 0xa84f, + 0xa34c, 0xa7bd, 0xa3d7, 0xa72c, 0xa463, 0xa69c, 0xa4f0, 0xa60c, + 0xa57e, 0xa57e, 0xa60c, 0xa4f0, 0xa69c, 0xa463, 0xa72c, 0xa3d7, + 0xa7bd, 0xa34c, 0xa84f, 0xa2c2, 0xa8e2, 0xa238, 0xa976, 0xa1b0, + 0xaa0a, 0xa129, 0xaaa0, 0xa0a2, 0xab36, 0xa01c, 0xabcd, 0x9f98, + 0xac65, 0x9f14, 0xacfd, 0x9e91, 0xad97, 0x9e0f, 0xae31, 0x9d8e, + 0xaecc, 0x9d0e, 0xaf68, 0x9c8f, 0xb005, 0x9c11, 0xb0a2, 0x9b94, + 0xb140, 0x9b17, 0xb1df, 0x9a9c, 0xb27f, 0x9a22, 0xb31f, 0x99a9, + 0xb3c0, 0x9930, 0xb462, 0x98b9, 0xb505, 0x9843, 0xb5a8, 0x97ce, + 0xb64c, 0x9759, 0xb6f1, 0x96e6, 0xb796, 0x9674, 0xb83c, 0x9603, + 0xb8e3, 0x9592, 0xb98b, 0x9523, 0xba33, 0x94b5, 0xbadc, 0x9448, + 0xbb85, 0x93dc, 0xbc2f, 0x9371, 0xbcda, 0x9307, 0xbd86, 0x929e, + 0xbe32, 0x9236, 0xbedf, 0x91cf, 0xbf8c, 0x9169, 0xc03a, 0x9105, + 0xc0e9, 0x90a1, 0xc198, 0x903e, 0xc248, 0x8fdd, 0xc2f8, 0x8f7d, + 0xc3a9, 0x8f1d, 0xc45b, 0x8ebf, 0xc50d, 0x8e62, 0xc5c0, 0x8e06, + 0xc673, 0x8dab, 0xc727, 0x8d51, 0xc7db, 0x8cf8, 0xc890, 0x8ca1, + 0xc946, 0x8c4a, 0xc9fc, 0x8bf5, 0xcab2, 0x8ba0, 0xcb69, 0x8b4d, + 0xcc21, 0x8afb, 0xccd9, 0x8aaa, 0xcd92, 0x8a5a, 0xce4b, 0x8a0c, + 0xcf04, 0x89be, 0xcfbe, 0x8972, 0xd079, 0x8927, 0xd134, 0x88dd, + 0xd1ef, 0x8894, 0xd2ab, 0x884c, 0xd367, 0x8805, 0xd424, 0x87c0, + 0xd4e1, 0x877b, 0xd59e, 0x8738, 0xd65c, 0x86f6, 0xd71b, 0x86b6, + 0xd7d9, 0x8676, 0xd898, 0x8637, 0xd958, 0x85fa, 0xda18, 0x85be, + 0xdad8, 0x8583, 0xdb99, 0x8549, 0xdc59, 0x8511, 0xdd1b, 0x84d9, + 0xdddc, 0x84a3, 0xde9e, 0x846e, 0xdf61, 0x843a, 0xe023, 0x8407, + 0xe0e6, 0x83d6, 0xe1a9, 0x83a6, 0xe26d, 0x8377, 0xe330, 0x8349, + 0xe3f4, 0x831c, 0xe4b9, 0x82f1, 0xe57d, 0x82c6, 0xe642, 0x829d, + 0xe707, 0x8276, 0xe7cd, 0x824f, 0xe892, 0x822a, 0xe958, 0x8205, + 0xea1e, 0x81e2, 0xeae4, 0x81c1, 0xebab, 0x81a0, 0xec71, 0x8181, + 0xed38, 0x8163, 0xedff, 0x8146, 0xeec6, 0x812a, 0xef8d, 0x8110, + 0xf055, 0x80f6, 0xf11c, 0x80de, 0xf1e4, 0x80c8, 0xf2ac, 0x80b2, + 0xf374, 0x809e, 0xf43c, 0x808b, 0xf505, 0x8079, 0xf5cd, 0x8068, + 0xf695, 0x8059, 0xf75e, 0x804b, 0xf827, 0x803e, 0xf8ef, 0x8032, + 0xf9b8, 0x8027, 0xfa81, 0x801e, 0xfb4a, 0x8016, 0xfc13, 0x800f, + 0xfcdc, 0x800a, 0xfda5, 0x8006, 0xfe6e, 0x8002, 0xff37, 0x8001, + 0x0, 0x8000, 0xc9, 0x8001, 0x192, 0x8002, 0x25b, 0x8006, + 0x324, 0x800a, 0x3ed, 0x800f, 0x4b6, 0x8016, 0x57f, 0x801e, + 0x648, 0x8027, 0x711, 0x8032, 0x7d9, 0x803e, 0x8a2, 0x804b, + 0x96b, 0x8059, 0xa33, 0x8068, 0xafb, 0x8079, 0xbc4, 0x808b, + 0xc8c, 0x809e, 0xd54, 0x80b2, 0xe1c, 0x80c8, 0xee4, 0x80de, + 0xfab, 0x80f6, 0x1073, 0x8110, 0x113a, 0x812a, 0x1201, 0x8146, + 0x12c8, 0x8163, 0x138f, 0x8181, 0x1455, 0x81a0, 0x151c, 0x81c1, + 0x15e2, 0x81e2, 0x16a8, 0x8205, 0x176e, 0x822a, 0x1833, 0x824f, + 0x18f9, 0x8276, 0x19be, 0x829d, 0x1a83, 0x82c6, 0x1b47, 0x82f1, + 0x1c0c, 0x831c, 0x1cd0, 0x8349, 0x1d93, 0x8377, 0x1e57, 0x83a6, + 0x1f1a, 0x83d6, 0x1fdd, 0x8407, 0x209f, 0x843a, 0x2162, 0x846e, + 0x2224, 0x84a3, 0x22e5, 0x84d9, 0x23a7, 0x8511, 0x2467, 0x8549, + 0x2528, 0x8583, 0x25e8, 0x85be, 0x26a8, 0x85fa, 0x2768, 0x8637, + 0x2827, 0x8676, 0x28e5, 0x86b6, 0x29a4, 0x86f6, 0x2a62, 0x8738, + 0x2b1f, 0x877b, 0x2bdc, 0x87c0, 0x2c99, 0x8805, 0x2d55, 0x884c, + 0x2e11, 0x8894, 0x2ecc, 0x88dd, 0x2f87, 0x8927, 0x3042, 0x8972, + 0x30fc, 0x89be, 0x31b5, 0x8a0c, 0x326e, 0x8a5a, 0x3327, 0x8aaa, + 0x33df, 0x8afb, 0x3497, 0x8b4d, 0x354e, 0x8ba0, 0x3604, 0x8bf5, + 0x36ba, 0x8c4a, 0x3770, 0x8ca1, 0x3825, 0x8cf8, 0x38d9, 0x8d51, + 0x398d, 0x8dab, 0x3a40, 0x8e06, 0x3af3, 0x8e62, 0x3ba5, 0x8ebf, + 0x3c57, 0x8f1d, 0x3d08, 0x8f7d, 0x3db8, 0x8fdd, 0x3e68, 0x903e, + 0x3f17, 0x90a1, 0x3fc6, 0x9105, 0x4074, 0x9169, 0x4121, 0x91cf, + 0x41ce, 0x9236, 0x427a, 0x929e, 0x4326, 0x9307, 0x43d1, 0x9371, + 0x447b, 0x93dc, 0x4524, 0x9448, 0x45cd, 0x94b5, 0x4675, 0x9523, + 0x471d, 0x9592, 0x47c4, 0x9603, 0x486a, 0x9674, 0x490f, 0x96e6, + 0x49b4, 0x9759, 0x4a58, 0x97ce, 0x4afb, 0x9843, 0x4b9e, 0x98b9, + 0x4c40, 0x9930, 0x4ce1, 0x99a9, 0x4d81, 0x9a22, 0x4e21, 0x9a9c, + 0x4ec0, 0x9b17, 0x4f5e, 0x9b94, 0x4ffb, 0x9c11, 0x5098, 0x9c8f, + 0x5134, 0x9d0e, 0x51cf, 0x9d8e, 0x5269, 0x9e0f, 0x5303, 0x9e91, + 0x539b, 0x9f14, 0x5433, 0x9f98, 0x54ca, 0xa01c, 0x5560, 0xa0a2, + 0x55f6, 0xa129, 0x568a, 0xa1b0, 0x571e, 0xa238, 0x57b1, 0xa2c2, + 0x5843, 0xa34c, 0x58d4, 0xa3d7, 0x5964, 0xa463, 0x59f4, 0xa4f0, + 0x5a82, 0xa57e, 0x5b10, 0xa60c, 0x5b9d, 0xa69c, 0x5c29, 0xa72c, + 0x5cb4, 0xa7bd, 0x5d3e, 0xa84f, 0x5dc8, 0xa8e2, 0x5e50, 0xa976, + 0x5ed7, 0xaa0a, 0x5f5e, 0xaaa0, 0x5fe4, 0xab36, 0x6068, 0xabcd, + 0x60ec, 0xac65, 0x616f, 0xacfd, 0x61f1, 0xad97, 0x6272, 0xae31, + 0x62f2, 0xaecc, 0x6371, 0xaf68, 0x63ef, 0xb005, 0x646c, 0xb0a2, + 0x64e9, 0xb140, 0x6564, 0xb1df, 0x65de, 0xb27f, 0x6657, 0xb31f, + 0x66d0, 0xb3c0, 0x6747, 0xb462, 0x67bd, 0xb505, 0x6832, 0xb5a8, + 0x68a7, 0xb64c, 0x691a, 0xb6f1, 0x698c, 0xb796, 0x69fd, 0xb83c, + 0x6a6e, 0xb8e3, 0x6add, 0xb98b, 0x6b4b, 0xba33, 0x6bb8, 0xbadc, + 0x6c24, 0xbb85, 0x6c8f, 0xbc2f, 0x6cf9, 0xbcda, 0x6d62, 0xbd86, + 0x6dca, 0xbe32, 0x6e31, 0xbedf, 0x6e97, 0xbf8c, 0x6efb, 0xc03a, + 0x6f5f, 0xc0e9, 0x6fc2, 0xc198, 0x7023, 0xc248, 0x7083, 0xc2f8, + 0x70e3, 0xc3a9, 0x7141, 0xc45b, 0x719e, 0xc50d, 0x71fa, 0xc5c0, + 0x7255, 0xc673, 0x72af, 0xc727, 0x7308, 0xc7db, 0x735f, 0xc890, + 0x73b6, 0xc946, 0x740b, 0xc9fc, 0x7460, 0xcab2, 0x74b3, 0xcb69, + 0x7505, 0xcc21, 0x7556, 0xccd9, 0x75a6, 0xcd92, 0x75f4, 0xce4b, + 0x7642, 0xcf04, 0x768e, 0xcfbe, 0x76d9, 0xd079, 0x7723, 0xd134, + 0x776c, 0xd1ef, 0x77b4, 0xd2ab, 0x77fb, 0xd367, 0x7840, 0xd424, + 0x7885, 0xd4e1, 0x78c8, 0xd59e, 0x790a, 0xd65c, 0x794a, 0xd71b, + 0x798a, 0xd7d9, 0x79c9, 0xd898, 0x7a06, 0xd958, 0x7a42, 0xda18, + 0x7a7d, 0xdad8, 0x7ab7, 0xdb99, 0x7aef, 0xdc59, 0x7b27, 0xdd1b, + 0x7b5d, 0xdddc, 0x7b92, 0xde9e, 0x7bc6, 0xdf61, 0x7bf9, 0xe023, + 0x7c2a, 0xe0e6, 0x7c5a, 0xe1a9, 0x7c89, 0xe26d, 0x7cb7, 0xe330, + 0x7ce4, 0xe3f4, 0x7d0f, 0xe4b9, 0x7d3a, 0xe57d, 0x7d63, 0xe642, + 0x7d8a, 0xe707, 0x7db1, 0xe7cd, 0x7dd6, 0xe892, 0x7dfb, 0xe958, + 0x7e1e, 0xea1e, 0x7e3f, 0xeae4, 0x7e60, 0xebab, 0x7e7f, 0xec71, + 0x7e9d, 0xed38, 0x7eba, 0xedff, 0x7ed6, 0xeec6, 0x7ef0, 0xef8d, + 0x7f0a, 0xf055, 0x7f22, 0xf11c, 0x7f38, 0xf1e4, 0x7f4e, 0xf2ac, + 0x7f62, 0xf374, 0x7f75, 0xf43c, 0x7f87, 0xf505, 0x7f98, 0xf5cd, + 0x7fa7, 0xf695, 0x7fb5, 0xf75e, 0x7fc2, 0xf827, 0x7fce, 0xf8ef, + 0x7fd9, 0xf9b8, 0x7fe2, 0xfa81, 0x7fea, 0xfb4a, 0x7ff1, 0xfc13, + 0x7ff6, 0xfcdc, 0x7ffa, 0xfda5, 0x7ffe, 0xfe6e, 0x7fff, 0xff37 +}; + + +/** +* @brief Initialization function for the Q15 CFFT/CIFFT. +* @param[in,out] *S points to an instance of the Q15 CFFT/CIFFT structure. +* @param[in] fftLen length of the FFT. +* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. +* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. +* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. +* +* \par Description: +* \par +* The parameter ifftFlag controls whether a forward or inverse transform is computed. +* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated +* \par +* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. +* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. +* \par +* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. +* \par +* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. +*/ + +arm_status arm_cfft_radix4_init_q15( + arm_cfft_radix4_instance_q15 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag) +{ + /* Initialise the default arm status */ + arm_status status = ARM_MATH_SUCCESS; + /* Initialise the FFT length */ + S->fftLen = fftLen; + /* Initialise the Twiddle coefficient pointer */ + S->pTwiddle = (q15_t *) twiddleCoefQ15; + /* Initialise the Flag for selection of CFFT or CIFFT */ + S->ifftFlag = ifftFlag; + /* Initialise the Flag for calculation Bit reversal or not */ + S->bitReverseFlag = bitReverseFlag; + + /* Initializations of structure parameters depending on the FFT length */ + switch (S->fftLen) + { + /* Initializations of structure parameters for 1024 point FFT */ + case 1024u: + /* Initialise the twiddle coef modifier value */ + S->twidCoefModifier = 1u; + /* Initialise the bit reversal table modifier */ + S->bitRevFactor = 1u; + /* Initialise the bit reversal table pointer */ + S->pBitRevTable = armBitRevTable; + + break; + case 256u: + /* Initializations of structure parameters for 2566 point FFT */ + S->twidCoefModifier = 4u; + S->bitRevFactor = 4u; + S->pBitRevTable = &armBitRevTable[3]; + + break; + case 64u: + /* Initializations of structure parameters for 64 point FFT */ + S->twidCoefModifier = 16u; + S->bitRevFactor = 16u; + S->pBitRevTable = &armBitRevTable[15]; + + break; + case 16u: + /* Initializations of structure parameters for 16 point FFT */ + S->twidCoefModifier = 64u; + S->bitRevFactor = 64u; + S->pBitRevTable = &armBitRevTable[63]; + + break; + default: + /* Reporting argument error if fftSize is not valid value */ + status = ARM_MATH_ARGUMENT_ERROR; + break; + } + + return (status); +} + +/** + * @} end of CFFT_CIFFT group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q31.c index eba07ed54..a90529aee 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q31.c @@ -1,670 +1,670 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_init_q31.c -* -* Description: Radix-4 Decimation in Frequency Q31 FFT & IFFT initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup CFFT_CIFFT - * @{ - */ - -/* -* @brief Twiddle factors Table -*/ - -/** -* \par -* Example code for Q31 Twiddle factors Generation:: -* \par -*
for(i = 0; i< N; i++)   
-* {   
-*    twiddleCoefQ31[2*i]= cos(i * 2*PI/(float)N);   
-*    twiddleCoefQ31[2*i+1]= sin(i * 2*PI/(float)N);   
-* } 
-* \par -* where N = 1024 and PI = 3.14159265358979 -* \par -* Cos and Sin values are interleaved fashion -* \par -* Convert Floating point to Q31(Fixed point 1.31): -* round(twiddleCoefQ31(i) * pow(2, 31)) -* -*/ - -static const q31_t twiddleCoefQ31[2048] = { - 0x7fffffff, 0x0, 0x7fff6216, 0xc90f88, 0x7ffd885a, 0x1921d20, 0x7ffa72d1, - 0x25b26d7, - 0x7ff62182, 0x3242abf, 0x7ff09478, 0x3ed26e6, 0x7fe9cbc0, 0x4b6195d, - 0x7fe1c76b, 0x57f0035, - 0x7fd8878e, 0x647d97c, 0x7fce0c3e, 0x710a345, 0x7fc25596, 0x7d95b9e, - 0x7fb563b3, 0x8a2009a, - 0x7fa736b4, 0x96a9049, 0x7f97cebd, 0xa3308bd, 0x7f872bf3, 0xafb6805, - 0x7f754e80, 0xbc3ac35, - 0x7f62368f, 0xc8bd35e, 0x7f4de451, 0xd53db92, 0x7f3857f6, 0xe1bc2e4, - 0x7f2191b4, 0xee38766, - 0x7f0991c4, 0xfab272b, 0x7ef05860, 0x1072a048, 0x7ed5e5c6, 0x1139f0cf, - 0x7eba3a39, 0x120116d5, - 0x7e9d55fc, 0x12c8106f, 0x7e7f3957, 0x138edbb1, 0x7e5fe493, 0x145576b1, - 0x7e3f57ff, 0x151bdf86, - 0x7e1d93ea, 0x15e21445, 0x7dfa98a8, 0x16a81305, 0x7dd6668f, 0x176dd9de, - 0x7db0fdf8, 0x183366e9, - 0x7d8a5f40, 0x18f8b83c, 0x7d628ac6, 0x19bdcbf3, 0x7d3980ec, 0x1a82a026, - 0x7d0f4218, 0x1b4732ef, - 0x7ce3ceb2, 0x1c0b826a, 0x7cb72724, 0x1ccf8cb3, 0x7c894bde, 0x1d934fe5, - 0x7c5a3d50, 0x1e56ca1e, - 0x7c29fbee, 0x1f19f97b, 0x7bf88830, 0x1fdcdc1b, 0x7bc5e290, 0x209f701c, - 0x7b920b89, 0x2161b3a0, - 0x7b5d039e, 0x2223a4c5, 0x7b26cb4f, 0x22e541af, 0x7aef6323, 0x23a6887f, - 0x7ab6cba4, 0x24677758, - 0x7a7d055b, 0x25280c5e, 0x7a4210d8, 0x25e845b6, 0x7a05eead, 0x26a82186, - 0x79c89f6e, 0x27679df4, - 0x798a23b1, 0x2826b928, 0x794a7c12, 0x28e5714b, 0x7909a92d, 0x29a3c485, - 0x78c7aba2, 0x2a61b101, - 0x78848414, 0x2b1f34eb, 0x78403329, 0x2bdc4e6f, 0x77fab989, 0x2c98fbba, - 0x77b417df, 0x2d553afc, - 0x776c4edb, 0x2e110a62, 0x77235f2d, 0x2ecc681e, 0x76d94989, 0x2f875262, - 0x768e0ea6, 0x3041c761, - 0x7641af3d, 0x30fbc54d, 0x75f42c0b, 0x31b54a5e, 0x75a585cf, 0x326e54c7, - 0x7555bd4c, 0x3326e2c3, - 0x7504d345, 0x33def287, 0x74b2c884, 0x34968250, 0x745f9dd1, 0x354d9057, - 0x740b53fb, 0x36041ad9, - 0x73b5ebd1, 0x36ba2014, 0x735f6626, 0x376f9e46, 0x7307c3d0, 0x382493b0, - 0x72af05a7, 0x38d8fe93, - 0x72552c85, 0x398cdd32, 0x71fa3949, 0x3a402dd2, 0x719e2cd2, 0x3af2eeb7, - 0x71410805, 0x3ba51e29, - 0x70e2cbc6, 0x3c56ba70, 0x708378ff, 0x3d07c1d6, 0x7023109a, 0x3db832a6, - 0x6fc19385, 0x3e680b2c, - 0x6f5f02b2, 0x3f1749b8, 0x6efb5f12, 0x3fc5ec98, 0x6e96a99d, 0x4073f21d, - 0x6e30e34a, 0x4121589b, - 0x6dca0d14, 0x41ce1e65, 0x6d6227fa, 0x427a41d0, 0x6cf934fc, 0x4325c135, - 0x6c8f351c, 0x43d09aed, - 0x6c242960, 0x447acd50, 0x6bb812d1, 0x452456bd, 0x6b4af279, 0x45cd358f, - 0x6adcc964, 0x46756828, - 0x6a6d98a4, 0x471cece7, 0x69fd614a, 0x47c3c22f, 0x698c246c, 0x4869e665, - 0x6919e320, 0x490f57ee, - 0x68a69e81, 0x49b41533, 0x683257ab, 0x4a581c9e, 0x67bd0fbd, 0x4afb6c98, - 0x6746c7d8, 0x4b9e0390, - 0x66cf8120, 0x4c3fdff4, 0x66573cbb, 0x4ce10034, 0x65ddfbd3, 0x4d8162c4, - 0x6563bf92, 0x4e210617, - 0x64e88926, 0x4ebfe8a5, 0x646c59bf, 0x4f5e08e3, 0x63ef3290, 0x4ffb654d, - 0x637114cc, 0x5097fc5e, - 0x62f201ac, 0x5133cc94, 0x6271fa69, 0x51ced46e, 0x61f1003f, 0x5269126e, - 0x616f146c, 0x53028518, - 0x60ec3830, 0x539b2af0, 0x60686ccf, 0x5433027d, 0x5fe3b38d, 0x54ca0a4b, - 0x5f5e0db3, 0x556040e2, - 0x5ed77c8a, 0x55f5a4d2, 0x5e50015d, 0x568a34a9, 0x5dc79d7c, 0x571deefa, - 0x5d3e5237, 0x57b0d256, - 0x5cb420e0, 0x5842dd54, 0x5c290acc, 0x58d40e8c, 0x5b9d1154, 0x59646498, - 0x5b1035cf, 0x59f3de12, - 0x5a82799a, 0x5a82799a, 0x59f3de12, 0x5b1035cf, 0x59646498, 0x5b9d1154, - 0x58d40e8c, 0x5c290acc, - 0x5842dd54, 0x5cb420e0, 0x57b0d256, 0x5d3e5237, 0x571deefa, 0x5dc79d7c, - 0x568a34a9, 0x5e50015d, - 0x55f5a4d2, 0x5ed77c8a, 0x556040e2, 0x5f5e0db3, 0x54ca0a4b, 0x5fe3b38d, - 0x5433027d, 0x60686ccf, - 0x539b2af0, 0x60ec3830, 0x53028518, 0x616f146c, 0x5269126e, 0x61f1003f, - 0x51ced46e, 0x6271fa69, - 0x5133cc94, 0x62f201ac, 0x5097fc5e, 0x637114cc, 0x4ffb654d, 0x63ef3290, - 0x4f5e08e3, 0x646c59bf, - 0x4ebfe8a5, 0x64e88926, 0x4e210617, 0x6563bf92, 0x4d8162c4, 0x65ddfbd3, - 0x4ce10034, 0x66573cbb, - 0x4c3fdff4, 0x66cf8120, 0x4b9e0390, 0x6746c7d8, 0x4afb6c98, 0x67bd0fbd, - 0x4a581c9e, 0x683257ab, - 0x49b41533, 0x68a69e81, 0x490f57ee, 0x6919e320, 0x4869e665, 0x698c246c, - 0x47c3c22f, 0x69fd614a, - 0x471cece7, 0x6a6d98a4, 0x46756828, 0x6adcc964, 0x45cd358f, 0x6b4af279, - 0x452456bd, 0x6bb812d1, - 0x447acd50, 0x6c242960, 0x43d09aed, 0x6c8f351c, 0x4325c135, 0x6cf934fc, - 0x427a41d0, 0x6d6227fa, - 0x41ce1e65, 0x6dca0d14, 0x4121589b, 0x6e30e34a, 0x4073f21d, 0x6e96a99d, - 0x3fc5ec98, 0x6efb5f12, - 0x3f1749b8, 0x6f5f02b2, 0x3e680b2c, 0x6fc19385, 0x3db832a6, 0x7023109a, - 0x3d07c1d6, 0x708378ff, - 0x3c56ba70, 0x70e2cbc6, 0x3ba51e29, 0x71410805, 0x3af2eeb7, 0x719e2cd2, - 0x3a402dd2, 0x71fa3949, - 0x398cdd32, 0x72552c85, 0x38d8fe93, 0x72af05a7, 0x382493b0, 0x7307c3d0, - 0x376f9e46, 0x735f6626, - 0x36ba2014, 0x73b5ebd1, 0x36041ad9, 0x740b53fb, 0x354d9057, 0x745f9dd1, - 0x34968250, 0x74b2c884, - 0x33def287, 0x7504d345, 0x3326e2c3, 0x7555bd4c, 0x326e54c7, 0x75a585cf, - 0x31b54a5e, 0x75f42c0b, - 0x30fbc54d, 0x7641af3d, 0x3041c761, 0x768e0ea6, 0x2f875262, 0x76d94989, - 0x2ecc681e, 0x77235f2d, - 0x2e110a62, 0x776c4edb, 0x2d553afc, 0x77b417df, 0x2c98fbba, 0x77fab989, - 0x2bdc4e6f, 0x78403329, - 0x2b1f34eb, 0x78848414, 0x2a61b101, 0x78c7aba2, 0x29a3c485, 0x7909a92d, - 0x28e5714b, 0x794a7c12, - 0x2826b928, 0x798a23b1, 0x27679df4, 0x79c89f6e, 0x26a82186, 0x7a05eead, - 0x25e845b6, 0x7a4210d8, - 0x25280c5e, 0x7a7d055b, 0x24677758, 0x7ab6cba4, 0x23a6887f, 0x7aef6323, - 0x22e541af, 0x7b26cb4f, - 0x2223a4c5, 0x7b5d039e, 0x2161b3a0, 0x7b920b89, 0x209f701c, 0x7bc5e290, - 0x1fdcdc1b, 0x7bf88830, - 0x1f19f97b, 0x7c29fbee, 0x1e56ca1e, 0x7c5a3d50, 0x1d934fe5, 0x7c894bde, - 0x1ccf8cb3, 0x7cb72724, - 0x1c0b826a, 0x7ce3ceb2, 0x1b4732ef, 0x7d0f4218, 0x1a82a026, 0x7d3980ec, - 0x19bdcbf3, 0x7d628ac6, - 0x18f8b83c, 0x7d8a5f40, 0x183366e9, 0x7db0fdf8, 0x176dd9de, 0x7dd6668f, - 0x16a81305, 0x7dfa98a8, - 0x15e21445, 0x7e1d93ea, 0x151bdf86, 0x7e3f57ff, 0x145576b1, 0x7e5fe493, - 0x138edbb1, 0x7e7f3957, - 0x12c8106f, 0x7e9d55fc, 0x120116d5, 0x7eba3a39, 0x1139f0cf, 0x7ed5e5c6, - 0x1072a048, 0x7ef05860, - 0xfab272b, 0x7f0991c4, 0xee38766, 0x7f2191b4, 0xe1bc2e4, 0x7f3857f6, - 0xd53db92, 0x7f4de451, - 0xc8bd35e, 0x7f62368f, 0xbc3ac35, 0x7f754e80, 0xafb6805, 0x7f872bf3, - 0xa3308bd, 0x7f97cebd, - 0x96a9049, 0x7fa736b4, 0x8a2009a, 0x7fb563b3, 0x7d95b9e, 0x7fc25596, - 0x710a345, 0x7fce0c3e, - 0x647d97c, 0x7fd8878e, 0x57f0035, 0x7fe1c76b, 0x4b6195d, 0x7fe9cbc0, - 0x3ed26e6, 0x7ff09478, - 0x3242abf, 0x7ff62182, 0x25b26d7, 0x7ffa72d1, 0x1921d20, 0x7ffd885a, - 0xc90f88, 0x7fff6216, - 0x0, 0x7fffffff, 0xff36f078, 0x7fff6216, 0xfe6de2e0, 0x7ffd885a, 0xfda4d929, - 0x7ffa72d1, - 0xfcdbd541, 0x7ff62182, 0xfc12d91a, 0x7ff09478, 0xfb49e6a3, 0x7fe9cbc0, - 0xfa80ffcb, 0x7fe1c76b, - 0xf9b82684, 0x7fd8878e, 0xf8ef5cbb, 0x7fce0c3e, 0xf826a462, 0x7fc25596, - 0xf75dff66, 0x7fb563b3, - 0xf6956fb7, 0x7fa736b4, 0xf5ccf743, 0x7f97cebd, 0xf50497fb, 0x7f872bf3, - 0xf43c53cb, 0x7f754e80, - 0xf3742ca2, 0x7f62368f, 0xf2ac246e, 0x7f4de451, 0xf1e43d1c, 0x7f3857f6, - 0xf11c789a, 0x7f2191b4, - 0xf054d8d5, 0x7f0991c4, 0xef8d5fb8, 0x7ef05860, 0xeec60f31, 0x7ed5e5c6, - 0xedfee92b, 0x7eba3a39, - 0xed37ef91, 0x7e9d55fc, 0xec71244f, 0x7e7f3957, 0xebaa894f, 0x7e5fe493, - 0xeae4207a, 0x7e3f57ff, - 0xea1debbb, 0x7e1d93ea, 0xe957ecfb, 0x7dfa98a8, 0xe8922622, 0x7dd6668f, - 0xe7cc9917, 0x7db0fdf8, - 0xe70747c4, 0x7d8a5f40, 0xe642340d, 0x7d628ac6, 0xe57d5fda, 0x7d3980ec, - 0xe4b8cd11, 0x7d0f4218, - 0xe3f47d96, 0x7ce3ceb2, 0xe330734d, 0x7cb72724, 0xe26cb01b, 0x7c894bde, - 0xe1a935e2, 0x7c5a3d50, - 0xe0e60685, 0x7c29fbee, 0xe02323e5, 0x7bf88830, 0xdf608fe4, 0x7bc5e290, - 0xde9e4c60, 0x7b920b89, - 0xdddc5b3b, 0x7b5d039e, 0xdd1abe51, 0x7b26cb4f, 0xdc597781, 0x7aef6323, - 0xdb9888a8, 0x7ab6cba4, - 0xdad7f3a2, 0x7a7d055b, 0xda17ba4a, 0x7a4210d8, 0xd957de7a, 0x7a05eead, - 0xd898620c, 0x79c89f6e, - 0xd7d946d8, 0x798a23b1, 0xd71a8eb5, 0x794a7c12, 0xd65c3b7b, 0x7909a92d, - 0xd59e4eff, 0x78c7aba2, - 0xd4e0cb15, 0x78848414, 0xd423b191, 0x78403329, 0xd3670446, 0x77fab989, - 0xd2aac504, 0x77b417df, - 0xd1eef59e, 0x776c4edb, 0xd13397e2, 0x77235f2d, 0xd078ad9e, 0x76d94989, - 0xcfbe389f, 0x768e0ea6, - 0xcf043ab3, 0x7641af3d, 0xce4ab5a2, 0x75f42c0b, 0xcd91ab39, 0x75a585cf, - 0xccd91d3d, 0x7555bd4c, - 0xcc210d79, 0x7504d345, 0xcb697db0, 0x74b2c884, 0xcab26fa9, 0x745f9dd1, - 0xc9fbe527, 0x740b53fb, - 0xc945dfec, 0x73b5ebd1, 0xc89061ba, 0x735f6626, 0xc7db6c50, 0x7307c3d0, - 0xc727016d, 0x72af05a7, - 0xc67322ce, 0x72552c85, 0xc5bfd22e, 0x71fa3949, 0xc50d1149, 0x719e2cd2, - 0xc45ae1d7, 0x71410805, - 0xc3a94590, 0x70e2cbc6, 0xc2f83e2a, 0x708378ff, 0xc247cd5a, 0x7023109a, - 0xc197f4d4, 0x6fc19385, - 0xc0e8b648, 0x6f5f02b2, 0xc03a1368, 0x6efb5f12, 0xbf8c0de3, 0x6e96a99d, - 0xbedea765, 0x6e30e34a, - 0xbe31e19b, 0x6dca0d14, 0xbd85be30, 0x6d6227fa, 0xbcda3ecb, 0x6cf934fc, - 0xbc2f6513, 0x6c8f351c, - 0xbb8532b0, 0x6c242960, 0xbadba943, 0x6bb812d1, 0xba32ca71, 0x6b4af279, - 0xb98a97d8, 0x6adcc964, - 0xb8e31319, 0x6a6d98a4, 0xb83c3dd1, 0x69fd614a, 0xb796199b, 0x698c246c, - 0xb6f0a812, 0x6919e320, - 0xb64beacd, 0x68a69e81, 0xb5a7e362, 0x683257ab, 0xb5049368, 0x67bd0fbd, - 0xb461fc70, 0x6746c7d8, - 0xb3c0200c, 0x66cf8120, 0xb31effcc, 0x66573cbb, 0xb27e9d3c, 0x65ddfbd3, - 0xb1def9e9, 0x6563bf92, - 0xb140175b, 0x64e88926, 0xb0a1f71d, 0x646c59bf, 0xb0049ab3, 0x63ef3290, - 0xaf6803a2, 0x637114cc, - 0xaecc336c, 0x62f201ac, 0xae312b92, 0x6271fa69, 0xad96ed92, 0x61f1003f, - 0xacfd7ae8, 0x616f146c, - 0xac64d510, 0x60ec3830, 0xabccfd83, 0x60686ccf, 0xab35f5b5, 0x5fe3b38d, - 0xaa9fbf1e, 0x5f5e0db3, - 0xaa0a5b2e, 0x5ed77c8a, 0xa975cb57, 0x5e50015d, 0xa8e21106, 0x5dc79d7c, - 0xa84f2daa, 0x5d3e5237, - 0xa7bd22ac, 0x5cb420e0, 0xa72bf174, 0x5c290acc, 0xa69b9b68, 0x5b9d1154, - 0xa60c21ee, 0x5b1035cf, - 0xa57d8666, 0x5a82799a, 0xa4efca31, 0x59f3de12, 0xa462eeac, 0x59646498, - 0xa3d6f534, 0x58d40e8c, - 0xa34bdf20, 0x5842dd54, 0xa2c1adc9, 0x57b0d256, 0xa2386284, 0x571deefa, - 0xa1affea3, 0x568a34a9, - 0xa1288376, 0x55f5a4d2, 0xa0a1f24d, 0x556040e2, 0xa01c4c73, 0x54ca0a4b, - 0x9f979331, 0x5433027d, - 0x9f13c7d0, 0x539b2af0, 0x9e90eb94, 0x53028518, 0x9e0effc1, 0x5269126e, - 0x9d8e0597, 0x51ced46e, - 0x9d0dfe54, 0x5133cc94, 0x9c8eeb34, 0x5097fc5e, 0x9c10cd70, 0x4ffb654d, - 0x9b93a641, 0x4f5e08e3, - 0x9b1776da, 0x4ebfe8a5, 0x9a9c406e, 0x4e210617, 0x9a22042d, 0x4d8162c4, - 0x99a8c345, 0x4ce10034, - 0x99307ee0, 0x4c3fdff4, 0x98b93828, 0x4b9e0390, 0x9842f043, 0x4afb6c98, - 0x97cda855, 0x4a581c9e, - 0x9759617f, 0x49b41533, 0x96e61ce0, 0x490f57ee, 0x9673db94, 0x4869e665, - 0x96029eb6, 0x47c3c22f, - 0x9592675c, 0x471cece7, 0x9523369c, 0x46756828, 0x94b50d87, 0x45cd358f, - 0x9447ed2f, 0x452456bd, - 0x93dbd6a0, 0x447acd50, 0x9370cae4, 0x43d09aed, 0x9306cb04, 0x4325c135, - 0x929dd806, 0x427a41d0, - 0x9235f2ec, 0x41ce1e65, 0x91cf1cb6, 0x4121589b, 0x91695663, 0x4073f21d, - 0x9104a0ee, 0x3fc5ec98, - 0x90a0fd4e, 0x3f1749b8, 0x903e6c7b, 0x3e680b2c, 0x8fdcef66, 0x3db832a6, - 0x8f7c8701, 0x3d07c1d6, - 0x8f1d343a, 0x3c56ba70, 0x8ebef7fb, 0x3ba51e29, 0x8e61d32e, 0x3af2eeb7, - 0x8e05c6b7, 0x3a402dd2, - 0x8daad37b, 0x398cdd32, 0x8d50fa59, 0x38d8fe93, 0x8cf83c30, 0x382493b0, - 0x8ca099da, 0x376f9e46, - 0x8c4a142f, 0x36ba2014, 0x8bf4ac05, 0x36041ad9, 0x8ba0622f, 0x354d9057, - 0x8b4d377c, 0x34968250, - 0x8afb2cbb, 0x33def287, 0x8aaa42b4, 0x3326e2c3, 0x8a5a7a31, 0x326e54c7, - 0x8a0bd3f5, 0x31b54a5e, - 0x89be50c3, 0x30fbc54d, 0x8971f15a, 0x3041c761, 0x8926b677, 0x2f875262, - 0x88dca0d3, 0x2ecc681e, - 0x8893b125, 0x2e110a62, 0x884be821, 0x2d553afc, 0x88054677, 0x2c98fbba, - 0x87bfccd7, 0x2bdc4e6f, - 0x877b7bec, 0x2b1f34eb, 0x8738545e, 0x2a61b101, 0x86f656d3, 0x29a3c485, - 0x86b583ee, 0x28e5714b, - 0x8675dc4f, 0x2826b928, 0x86376092, 0x27679df4, 0x85fa1153, 0x26a82186, - 0x85bdef28, 0x25e845b6, - 0x8582faa5, 0x25280c5e, 0x8549345c, 0x24677758, 0x85109cdd, 0x23a6887f, - 0x84d934b1, 0x22e541af, - 0x84a2fc62, 0x2223a4c5, 0x846df477, 0x2161b3a0, 0x843a1d70, 0x209f701c, - 0x840777d0, 0x1fdcdc1b, - 0x83d60412, 0x1f19f97b, 0x83a5c2b0, 0x1e56ca1e, 0x8376b422, 0x1d934fe5, - 0x8348d8dc, 0x1ccf8cb3, - 0x831c314e, 0x1c0b826a, 0x82f0bde8, 0x1b4732ef, 0x82c67f14, 0x1a82a026, - 0x829d753a, 0x19bdcbf3, - 0x8275a0c0, 0x18f8b83c, 0x824f0208, 0x183366e9, 0x82299971, 0x176dd9de, - 0x82056758, 0x16a81305, - 0x81e26c16, 0x15e21445, 0x81c0a801, 0x151bdf86, 0x81a01b6d, 0x145576b1, - 0x8180c6a9, 0x138edbb1, - 0x8162aa04, 0x12c8106f, 0x8145c5c7, 0x120116d5, 0x812a1a3a, 0x1139f0cf, - 0x810fa7a0, 0x1072a048, - 0x80f66e3c, 0xfab272b, 0x80de6e4c, 0xee38766, 0x80c7a80a, 0xe1bc2e4, - 0x80b21baf, 0xd53db92, - 0x809dc971, 0xc8bd35e, 0x808ab180, 0xbc3ac35, 0x8078d40d, 0xafb6805, - 0x80683143, 0xa3308bd, - 0x8058c94c, 0x96a9049, 0x804a9c4d, 0x8a2009a, 0x803daa6a, 0x7d95b9e, - 0x8031f3c2, 0x710a345, - 0x80277872, 0x647d97c, 0x801e3895, 0x57f0035, 0x80163440, 0x4b6195d, - 0x800f6b88, 0x3ed26e6, - 0x8009de7e, 0x3242abf, 0x80058d2f, 0x25b26d7, 0x800277a6, 0x1921d20, - 0x80009dea, 0xc90f88, - 0x80000000, 0x0, 0x80009dea, 0xff36f078, 0x800277a6, 0xfe6de2e0, 0x80058d2f, - 0xfda4d929, - 0x8009de7e, 0xfcdbd541, 0x800f6b88, 0xfc12d91a, 0x80163440, 0xfb49e6a3, - 0x801e3895, 0xfa80ffcb, - 0x80277872, 0xf9b82684, 0x8031f3c2, 0xf8ef5cbb, 0x803daa6a, 0xf826a462, - 0x804a9c4d, 0xf75dff66, - 0x8058c94c, 0xf6956fb7, 0x80683143, 0xf5ccf743, 0x8078d40d, 0xf50497fb, - 0x808ab180, 0xf43c53cb, - 0x809dc971, 0xf3742ca2, 0x80b21baf, 0xf2ac246e, 0x80c7a80a, 0xf1e43d1c, - 0x80de6e4c, 0xf11c789a, - 0x80f66e3c, 0xf054d8d5, 0x810fa7a0, 0xef8d5fb8, 0x812a1a3a, 0xeec60f31, - 0x8145c5c7, 0xedfee92b, - 0x8162aa04, 0xed37ef91, 0x8180c6a9, 0xec71244f, 0x81a01b6d, 0xebaa894f, - 0x81c0a801, 0xeae4207a, - 0x81e26c16, 0xea1debbb, 0x82056758, 0xe957ecfb, 0x82299971, 0xe8922622, - 0x824f0208, 0xe7cc9917, - 0x8275a0c0, 0xe70747c4, 0x829d753a, 0xe642340d, 0x82c67f14, 0xe57d5fda, - 0x82f0bde8, 0xe4b8cd11, - 0x831c314e, 0xe3f47d96, 0x8348d8dc, 0xe330734d, 0x8376b422, 0xe26cb01b, - 0x83a5c2b0, 0xe1a935e2, - 0x83d60412, 0xe0e60685, 0x840777d0, 0xe02323e5, 0x843a1d70, 0xdf608fe4, - 0x846df477, 0xde9e4c60, - 0x84a2fc62, 0xdddc5b3b, 0x84d934b1, 0xdd1abe51, 0x85109cdd, 0xdc597781, - 0x8549345c, 0xdb9888a8, - 0x8582faa5, 0xdad7f3a2, 0x85bdef28, 0xda17ba4a, 0x85fa1153, 0xd957de7a, - 0x86376092, 0xd898620c, - 0x8675dc4f, 0xd7d946d8, 0x86b583ee, 0xd71a8eb5, 0x86f656d3, 0xd65c3b7b, - 0x8738545e, 0xd59e4eff, - 0x877b7bec, 0xd4e0cb15, 0x87bfccd7, 0xd423b191, 0x88054677, 0xd3670446, - 0x884be821, 0xd2aac504, - 0x8893b125, 0xd1eef59e, 0x88dca0d3, 0xd13397e2, 0x8926b677, 0xd078ad9e, - 0x8971f15a, 0xcfbe389f, - 0x89be50c3, 0xcf043ab3, 0x8a0bd3f5, 0xce4ab5a2, 0x8a5a7a31, 0xcd91ab39, - 0x8aaa42b4, 0xccd91d3d, - 0x8afb2cbb, 0xcc210d79, 0x8b4d377c, 0xcb697db0, 0x8ba0622f, 0xcab26fa9, - 0x8bf4ac05, 0xc9fbe527, - 0x8c4a142f, 0xc945dfec, 0x8ca099da, 0xc89061ba, 0x8cf83c30, 0xc7db6c50, - 0x8d50fa59, 0xc727016d, - 0x8daad37b, 0xc67322ce, 0x8e05c6b7, 0xc5bfd22e, 0x8e61d32e, 0xc50d1149, - 0x8ebef7fb, 0xc45ae1d7, - 0x8f1d343a, 0xc3a94590, 0x8f7c8701, 0xc2f83e2a, 0x8fdcef66, 0xc247cd5a, - 0x903e6c7b, 0xc197f4d4, - 0x90a0fd4e, 0xc0e8b648, 0x9104a0ee, 0xc03a1368, 0x91695663, 0xbf8c0de3, - 0x91cf1cb6, 0xbedea765, - 0x9235f2ec, 0xbe31e19b, 0x929dd806, 0xbd85be30, 0x9306cb04, 0xbcda3ecb, - 0x9370cae4, 0xbc2f6513, - 0x93dbd6a0, 0xbb8532b0, 0x9447ed2f, 0xbadba943, 0x94b50d87, 0xba32ca71, - 0x9523369c, 0xb98a97d8, - 0x9592675c, 0xb8e31319, 0x96029eb6, 0xb83c3dd1, 0x9673db94, 0xb796199b, - 0x96e61ce0, 0xb6f0a812, - 0x9759617f, 0xb64beacd, 0x97cda855, 0xb5a7e362, 0x9842f043, 0xb5049368, - 0x98b93828, 0xb461fc70, - 0x99307ee0, 0xb3c0200c, 0x99a8c345, 0xb31effcc, 0x9a22042d, 0xb27e9d3c, - 0x9a9c406e, 0xb1def9e9, - 0x9b1776da, 0xb140175b, 0x9b93a641, 0xb0a1f71d, 0x9c10cd70, 0xb0049ab3, - 0x9c8eeb34, 0xaf6803a2, - 0x9d0dfe54, 0xaecc336c, 0x9d8e0597, 0xae312b92, 0x9e0effc1, 0xad96ed92, - 0x9e90eb94, 0xacfd7ae8, - 0x9f13c7d0, 0xac64d510, 0x9f979331, 0xabccfd83, 0xa01c4c73, 0xab35f5b5, - 0xa0a1f24d, 0xaa9fbf1e, - 0xa1288376, 0xaa0a5b2e, 0xa1affea3, 0xa975cb57, 0xa2386284, 0xa8e21106, - 0xa2c1adc9, 0xa84f2daa, - 0xa34bdf20, 0xa7bd22ac, 0xa3d6f534, 0xa72bf174, 0xa462eeac, 0xa69b9b68, - 0xa4efca31, 0xa60c21ee, - 0xa57d8666, 0xa57d8666, 0xa60c21ee, 0xa4efca31, 0xa69b9b68, 0xa462eeac, - 0xa72bf174, 0xa3d6f534, - 0xa7bd22ac, 0xa34bdf20, 0xa84f2daa, 0xa2c1adc9, 0xa8e21106, 0xa2386284, - 0xa975cb57, 0xa1affea3, - 0xaa0a5b2e, 0xa1288376, 0xaa9fbf1e, 0xa0a1f24d, 0xab35f5b5, 0xa01c4c73, - 0xabccfd83, 0x9f979331, - 0xac64d510, 0x9f13c7d0, 0xacfd7ae8, 0x9e90eb94, 0xad96ed92, 0x9e0effc1, - 0xae312b92, 0x9d8e0597, - 0xaecc336c, 0x9d0dfe54, 0xaf6803a2, 0x9c8eeb34, 0xb0049ab3, 0x9c10cd70, - 0xb0a1f71d, 0x9b93a641, - 0xb140175b, 0x9b1776da, 0xb1def9e9, 0x9a9c406e, 0xb27e9d3c, 0x9a22042d, - 0xb31effcc, 0x99a8c345, - 0xb3c0200c, 0x99307ee0, 0xb461fc70, 0x98b93828, 0xb5049368, 0x9842f043, - 0xb5a7e362, 0x97cda855, - 0xb64beacd, 0x9759617f, 0xb6f0a812, 0x96e61ce0, 0xb796199b, 0x9673db94, - 0xb83c3dd1, 0x96029eb6, - 0xb8e31319, 0x9592675c, 0xb98a97d8, 0x9523369c, 0xba32ca71, 0x94b50d87, - 0xbadba943, 0x9447ed2f, - 0xbb8532b0, 0x93dbd6a0, 0xbc2f6513, 0x9370cae4, 0xbcda3ecb, 0x9306cb04, - 0xbd85be30, 0x929dd806, - 0xbe31e19b, 0x9235f2ec, 0xbedea765, 0x91cf1cb6, 0xbf8c0de3, 0x91695663, - 0xc03a1368, 0x9104a0ee, - 0xc0e8b648, 0x90a0fd4e, 0xc197f4d4, 0x903e6c7b, 0xc247cd5a, 0x8fdcef66, - 0xc2f83e2a, 0x8f7c8701, - 0xc3a94590, 0x8f1d343a, 0xc45ae1d7, 0x8ebef7fb, 0xc50d1149, 0x8e61d32e, - 0xc5bfd22e, 0x8e05c6b7, - 0xc67322ce, 0x8daad37b, 0xc727016d, 0x8d50fa59, 0xc7db6c50, 0x8cf83c30, - 0xc89061ba, 0x8ca099da, - 0xc945dfec, 0x8c4a142f, 0xc9fbe527, 0x8bf4ac05, 0xcab26fa9, 0x8ba0622f, - 0xcb697db0, 0x8b4d377c, - 0xcc210d79, 0x8afb2cbb, 0xccd91d3d, 0x8aaa42b4, 0xcd91ab39, 0x8a5a7a31, - 0xce4ab5a2, 0x8a0bd3f5, - 0xcf043ab3, 0x89be50c3, 0xcfbe389f, 0x8971f15a, 0xd078ad9e, 0x8926b677, - 0xd13397e2, 0x88dca0d3, - 0xd1eef59e, 0x8893b125, 0xd2aac504, 0x884be821, 0xd3670446, 0x88054677, - 0xd423b191, 0x87bfccd7, - 0xd4e0cb15, 0x877b7bec, 0xd59e4eff, 0x8738545e, 0xd65c3b7b, 0x86f656d3, - 0xd71a8eb5, 0x86b583ee, - 0xd7d946d8, 0x8675dc4f, 0xd898620c, 0x86376092, 0xd957de7a, 0x85fa1153, - 0xda17ba4a, 0x85bdef28, - 0xdad7f3a2, 0x8582faa5, 0xdb9888a8, 0x8549345c, 0xdc597781, 0x85109cdd, - 0xdd1abe51, 0x84d934b1, - 0xdddc5b3b, 0x84a2fc62, 0xde9e4c60, 0x846df477, 0xdf608fe4, 0x843a1d70, - 0xe02323e5, 0x840777d0, - 0xe0e60685, 0x83d60412, 0xe1a935e2, 0x83a5c2b0, 0xe26cb01b, 0x8376b422, - 0xe330734d, 0x8348d8dc, - 0xe3f47d96, 0x831c314e, 0xe4b8cd11, 0x82f0bde8, 0xe57d5fda, 0x82c67f14, - 0xe642340d, 0x829d753a, - 0xe70747c4, 0x8275a0c0, 0xe7cc9917, 0x824f0208, 0xe8922622, 0x82299971, - 0xe957ecfb, 0x82056758, - 0xea1debbb, 0x81e26c16, 0xeae4207a, 0x81c0a801, 0xebaa894f, 0x81a01b6d, - 0xec71244f, 0x8180c6a9, - 0xed37ef91, 0x8162aa04, 0xedfee92b, 0x8145c5c7, 0xeec60f31, 0x812a1a3a, - 0xef8d5fb8, 0x810fa7a0, - 0xf054d8d5, 0x80f66e3c, 0xf11c789a, 0x80de6e4c, 0xf1e43d1c, 0x80c7a80a, - 0xf2ac246e, 0x80b21baf, - 0xf3742ca2, 0x809dc971, 0xf43c53cb, 0x808ab180, 0xf50497fb, 0x8078d40d, - 0xf5ccf743, 0x80683143, - 0xf6956fb7, 0x8058c94c, 0xf75dff66, 0x804a9c4d, 0xf826a462, 0x803daa6a, - 0xf8ef5cbb, 0x8031f3c2, - 0xf9b82684, 0x80277872, 0xfa80ffcb, 0x801e3895, 0xfb49e6a3, 0x80163440, - 0xfc12d91a, 0x800f6b88, - 0xfcdbd541, 0x8009de7e, 0xfda4d929, 0x80058d2f, 0xfe6de2e0, 0x800277a6, - 0xff36f078, 0x80009dea, - 0x0, 0x80000000, 0xc90f88, 0x80009dea, 0x1921d20, 0x800277a6, 0x25b26d7, - 0x80058d2f, - 0x3242abf, 0x8009de7e, 0x3ed26e6, 0x800f6b88, 0x4b6195d, 0x80163440, - 0x57f0035, 0x801e3895, - 0x647d97c, 0x80277872, 0x710a345, 0x8031f3c2, 0x7d95b9e, 0x803daa6a, - 0x8a2009a, 0x804a9c4d, - 0x96a9049, 0x8058c94c, 0xa3308bd, 0x80683143, 0xafb6805, 0x8078d40d, - 0xbc3ac35, 0x808ab180, - 0xc8bd35e, 0x809dc971, 0xd53db92, 0x80b21baf, 0xe1bc2e4, 0x80c7a80a, - 0xee38766, 0x80de6e4c, - 0xfab272b, 0x80f66e3c, 0x1072a048, 0x810fa7a0, 0x1139f0cf, 0x812a1a3a, - 0x120116d5, 0x8145c5c7, - 0x12c8106f, 0x8162aa04, 0x138edbb1, 0x8180c6a9, 0x145576b1, 0x81a01b6d, - 0x151bdf86, 0x81c0a801, - 0x15e21445, 0x81e26c16, 0x16a81305, 0x82056758, 0x176dd9de, 0x82299971, - 0x183366e9, 0x824f0208, - 0x18f8b83c, 0x8275a0c0, 0x19bdcbf3, 0x829d753a, 0x1a82a026, 0x82c67f14, - 0x1b4732ef, 0x82f0bde8, - 0x1c0b826a, 0x831c314e, 0x1ccf8cb3, 0x8348d8dc, 0x1d934fe5, 0x8376b422, - 0x1e56ca1e, 0x83a5c2b0, - 0x1f19f97b, 0x83d60412, 0x1fdcdc1b, 0x840777d0, 0x209f701c, 0x843a1d70, - 0x2161b3a0, 0x846df477, - 0x2223a4c5, 0x84a2fc62, 0x22e541af, 0x84d934b1, 0x23a6887f, 0x85109cdd, - 0x24677758, 0x8549345c, - 0x25280c5e, 0x8582faa5, 0x25e845b6, 0x85bdef28, 0x26a82186, 0x85fa1153, - 0x27679df4, 0x86376092, - 0x2826b928, 0x8675dc4f, 0x28e5714b, 0x86b583ee, 0x29a3c485, 0x86f656d3, - 0x2a61b101, 0x8738545e, - 0x2b1f34eb, 0x877b7bec, 0x2bdc4e6f, 0x87bfccd7, 0x2c98fbba, 0x88054677, - 0x2d553afc, 0x884be821, - 0x2e110a62, 0x8893b125, 0x2ecc681e, 0x88dca0d3, 0x2f875262, 0x8926b677, - 0x3041c761, 0x8971f15a, - 0x30fbc54d, 0x89be50c3, 0x31b54a5e, 0x8a0bd3f5, 0x326e54c7, 0x8a5a7a31, - 0x3326e2c3, 0x8aaa42b4, - 0x33def287, 0x8afb2cbb, 0x34968250, 0x8b4d377c, 0x354d9057, 0x8ba0622f, - 0x36041ad9, 0x8bf4ac05, - 0x36ba2014, 0x8c4a142f, 0x376f9e46, 0x8ca099da, 0x382493b0, 0x8cf83c30, - 0x38d8fe93, 0x8d50fa59, - 0x398cdd32, 0x8daad37b, 0x3a402dd2, 0x8e05c6b7, 0x3af2eeb7, 0x8e61d32e, - 0x3ba51e29, 0x8ebef7fb, - 0x3c56ba70, 0x8f1d343a, 0x3d07c1d6, 0x8f7c8701, 0x3db832a6, 0x8fdcef66, - 0x3e680b2c, 0x903e6c7b, - 0x3f1749b8, 0x90a0fd4e, 0x3fc5ec98, 0x9104a0ee, 0x4073f21d, 0x91695663, - 0x4121589b, 0x91cf1cb6, - 0x41ce1e65, 0x9235f2ec, 0x427a41d0, 0x929dd806, 0x4325c135, 0x9306cb04, - 0x43d09aed, 0x9370cae4, - 0x447acd50, 0x93dbd6a0, 0x452456bd, 0x9447ed2f, 0x45cd358f, 0x94b50d87, - 0x46756828, 0x9523369c, - 0x471cece7, 0x9592675c, 0x47c3c22f, 0x96029eb6, 0x4869e665, 0x9673db94, - 0x490f57ee, 0x96e61ce0, - 0x49b41533, 0x9759617f, 0x4a581c9e, 0x97cda855, 0x4afb6c98, 0x9842f043, - 0x4b9e0390, 0x98b93828, - 0x4c3fdff4, 0x99307ee0, 0x4ce10034, 0x99a8c345, 0x4d8162c4, 0x9a22042d, - 0x4e210617, 0x9a9c406e, - 0x4ebfe8a5, 0x9b1776da, 0x4f5e08e3, 0x9b93a641, 0x4ffb654d, 0x9c10cd70, - 0x5097fc5e, 0x9c8eeb34, - 0x5133cc94, 0x9d0dfe54, 0x51ced46e, 0x9d8e0597, 0x5269126e, 0x9e0effc1, - 0x53028518, 0x9e90eb94, - 0x539b2af0, 0x9f13c7d0, 0x5433027d, 0x9f979331, 0x54ca0a4b, 0xa01c4c73, - 0x556040e2, 0xa0a1f24d, - 0x55f5a4d2, 0xa1288376, 0x568a34a9, 0xa1affea3, 0x571deefa, 0xa2386284, - 0x57b0d256, 0xa2c1adc9, - 0x5842dd54, 0xa34bdf20, 0x58d40e8c, 0xa3d6f534, 0x59646498, 0xa462eeac, - 0x59f3de12, 0xa4efca31, - 0x5a82799a, 0xa57d8666, 0x5b1035cf, 0xa60c21ee, 0x5b9d1154, 0xa69b9b68, - 0x5c290acc, 0xa72bf174, - 0x5cb420e0, 0xa7bd22ac, 0x5d3e5237, 0xa84f2daa, 0x5dc79d7c, 0xa8e21106, - 0x5e50015d, 0xa975cb57, - 0x5ed77c8a, 0xaa0a5b2e, 0x5f5e0db3, 0xaa9fbf1e, 0x5fe3b38d, 0xab35f5b5, - 0x60686ccf, 0xabccfd83, - 0x60ec3830, 0xac64d510, 0x616f146c, 0xacfd7ae8, 0x61f1003f, 0xad96ed92, - 0x6271fa69, 0xae312b92, - 0x62f201ac, 0xaecc336c, 0x637114cc, 0xaf6803a2, 0x63ef3290, 0xb0049ab3, - 0x646c59bf, 0xb0a1f71d, - 0x64e88926, 0xb140175b, 0x6563bf92, 0xb1def9e9, 0x65ddfbd3, 0xb27e9d3c, - 0x66573cbb, 0xb31effcc, - 0x66cf8120, 0xb3c0200c, 0x6746c7d8, 0xb461fc70, 0x67bd0fbd, 0xb5049368, - 0x683257ab, 0xb5a7e362, - 0x68a69e81, 0xb64beacd, 0x6919e320, 0xb6f0a812, 0x698c246c, 0xb796199b, - 0x69fd614a, 0xb83c3dd1, - 0x6a6d98a4, 0xb8e31319, 0x6adcc964, 0xb98a97d8, 0x6b4af279, 0xba32ca71, - 0x6bb812d1, 0xbadba943, - 0x6c242960, 0xbb8532b0, 0x6c8f351c, 0xbc2f6513, 0x6cf934fc, 0xbcda3ecb, - 0x6d6227fa, 0xbd85be30, - 0x6dca0d14, 0xbe31e19b, 0x6e30e34a, 0xbedea765, 0x6e96a99d, 0xbf8c0de3, - 0x6efb5f12, 0xc03a1368, - 0x6f5f02b2, 0xc0e8b648, 0x6fc19385, 0xc197f4d4, 0x7023109a, 0xc247cd5a, - 0x708378ff, 0xc2f83e2a, - 0x70e2cbc6, 0xc3a94590, 0x71410805, 0xc45ae1d7, 0x719e2cd2, 0xc50d1149, - 0x71fa3949, 0xc5bfd22e, - 0x72552c85, 0xc67322ce, 0x72af05a7, 0xc727016d, 0x7307c3d0, 0xc7db6c50, - 0x735f6626, 0xc89061ba, - 0x73b5ebd1, 0xc945dfec, 0x740b53fb, 0xc9fbe527, 0x745f9dd1, 0xcab26fa9, - 0x74b2c884, 0xcb697db0, - 0x7504d345, 0xcc210d79, 0x7555bd4c, 0xccd91d3d, 0x75a585cf, 0xcd91ab39, - 0x75f42c0b, 0xce4ab5a2, - 0x7641af3d, 0xcf043ab3, 0x768e0ea6, 0xcfbe389f, 0x76d94989, 0xd078ad9e, - 0x77235f2d, 0xd13397e2, - 0x776c4edb, 0xd1eef59e, 0x77b417df, 0xd2aac504, 0x77fab989, 0xd3670446, - 0x78403329, 0xd423b191, - 0x78848414, 0xd4e0cb15, 0x78c7aba2, 0xd59e4eff, 0x7909a92d, 0xd65c3b7b, - 0x794a7c12, 0xd71a8eb5, - 0x798a23b1, 0xd7d946d8, 0x79c89f6e, 0xd898620c, 0x7a05eead, 0xd957de7a, - 0x7a4210d8, 0xda17ba4a, - 0x7a7d055b, 0xdad7f3a2, 0x7ab6cba4, 0xdb9888a8, 0x7aef6323, 0xdc597781, - 0x7b26cb4f, 0xdd1abe51, - 0x7b5d039e, 0xdddc5b3b, 0x7b920b89, 0xde9e4c60, 0x7bc5e290, 0xdf608fe4, - 0x7bf88830, 0xe02323e5, - 0x7c29fbee, 0xe0e60685, 0x7c5a3d50, 0xe1a935e2, 0x7c894bde, 0xe26cb01b, - 0x7cb72724, 0xe330734d, - 0x7ce3ceb2, 0xe3f47d96, 0x7d0f4218, 0xe4b8cd11, 0x7d3980ec, 0xe57d5fda, - 0x7d628ac6, 0xe642340d, - 0x7d8a5f40, 0xe70747c4, 0x7db0fdf8, 0xe7cc9917, 0x7dd6668f, 0xe8922622, - 0x7dfa98a8, 0xe957ecfb, - 0x7e1d93ea, 0xea1debbb, 0x7e3f57ff, 0xeae4207a, 0x7e5fe493, 0xebaa894f, - 0x7e7f3957, 0xec71244f, - 0x7e9d55fc, 0xed37ef91, 0x7eba3a39, 0xedfee92b, 0x7ed5e5c6, 0xeec60f31, - 0x7ef05860, 0xef8d5fb8, - 0x7f0991c4, 0xf054d8d5, 0x7f2191b4, 0xf11c789a, 0x7f3857f6, 0xf1e43d1c, - 0x7f4de451, 0xf2ac246e, - 0x7f62368f, 0xf3742ca2, 0x7f754e80, 0xf43c53cb, 0x7f872bf3, 0xf50497fb, - 0x7f97cebd, 0xf5ccf743, - 0x7fa736b4, 0xf6956fb7, 0x7fb563b3, 0xf75dff66, 0x7fc25596, 0xf826a462, - 0x7fce0c3e, 0xf8ef5cbb, - 0x7fd8878e, 0xf9b82684, 0x7fe1c76b, 0xfa80ffcb, 0x7fe9cbc0, 0xfb49e6a3, - 0x7ff09478, 0xfc12d91a, - 0x7ff62182, 0xfcdbd541, 0x7ffa72d1, 0xfda4d929, 0x7ffd885a, 0xfe6de2e0, - 0x7fff6216, 0xff36f078 -}; - -/** -* -* @brief Initialization function for the Q31 CFFT/CIFFT. -* @param[in,out] *S points to an instance of the Q31 CFFT/CIFFT structure. -* @param[in] fftLen length of the FFT. -* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. -* -* \par Description: -* \par -* The parameter ifftFlag controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. -* \par -* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. -*/ - -arm_status arm_cfft_radix4_init_q31( - arm_cfft_radix4_instance_q31 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - /* Initialise the FFT length */ - S->fftLen = fftLen; - /* Initialise the Twiddle coefficient pointer */ - S->pTwiddle = (q31_t *) twiddleCoefQ31; - /* Initialise the Flag for selection of CFFT or CIFFT */ - S->ifftFlag = ifftFlag; - /* Initialise the Flag for calculation Bit reversal or not */ - S->bitReverseFlag = bitReverseFlag; - - /* Initializations of Instance structure depending on the FFT length */ - switch (S->fftLen) - { - /* Initializations of structure parameters for 1024 point FFT */ - case 1024u: - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 1u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 1u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = armBitRevTable; - break; - - case 256u: - /* Initializations of structure parameters for 256 point FFT */ - S->twidCoefModifier = 4u; - S->bitRevFactor = 4u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[3]; - break; - - case 64u: - /* Initializations of structure parameters for 64 point FFT */ - S->twidCoefModifier = 16u; - S->bitRevFactor = 16u; - S->pBitRevTable = &armBitRevTable[15]; - break; - - case 16u: - /* Initializations of structure parameters for 16 point FFT */ - S->twidCoefModifier = 64u; - S->bitRevFactor = 64u; - S->pBitRevTable = &armBitRevTable[63]; - break; - - default: - /* Reporting argument error if fftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - return (status); -} - -/** - * @} end of CFFT_CIFFT group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_cfft_radix4_init_q31.c +* +* Description: Radix-4 Decimation in Frequency Q31 FFT & IFFT initialization function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" +#include "arm_common_tables.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup CFFT_CIFFT + * @{ + */ + +/* +* @brief Twiddle factors Table +*/ + +/** +* \par +* Example code for Q31 Twiddle factors Generation:: +* \par +*
for(i = 0; i< N; i++)   
+* {   
+*    twiddleCoefQ31[2*i]= cos(i * 2*PI/(float)N);   
+*    twiddleCoefQ31[2*i+1]= sin(i * 2*PI/(float)N);   
+* } 
+* \par +* where N = 1024 and PI = 3.14159265358979 +* \par +* Cos and Sin values are interleaved fashion +* \par +* Convert Floating point to Q31(Fixed point 1.31): +* round(twiddleCoefQ31(i) * pow(2, 31)) +* +*/ + +static const q31_t twiddleCoefQ31[2048] = { + 0x7fffffff, 0x0, 0x7fff6216, 0xc90f88, 0x7ffd885a, 0x1921d20, 0x7ffa72d1, + 0x25b26d7, + 0x7ff62182, 0x3242abf, 0x7ff09478, 0x3ed26e6, 0x7fe9cbc0, 0x4b6195d, + 0x7fe1c76b, 0x57f0035, + 0x7fd8878e, 0x647d97c, 0x7fce0c3e, 0x710a345, 0x7fc25596, 0x7d95b9e, + 0x7fb563b3, 0x8a2009a, + 0x7fa736b4, 0x96a9049, 0x7f97cebd, 0xa3308bd, 0x7f872bf3, 0xafb6805, + 0x7f754e80, 0xbc3ac35, + 0x7f62368f, 0xc8bd35e, 0x7f4de451, 0xd53db92, 0x7f3857f6, 0xe1bc2e4, + 0x7f2191b4, 0xee38766, + 0x7f0991c4, 0xfab272b, 0x7ef05860, 0x1072a048, 0x7ed5e5c6, 0x1139f0cf, + 0x7eba3a39, 0x120116d5, + 0x7e9d55fc, 0x12c8106f, 0x7e7f3957, 0x138edbb1, 0x7e5fe493, 0x145576b1, + 0x7e3f57ff, 0x151bdf86, + 0x7e1d93ea, 0x15e21445, 0x7dfa98a8, 0x16a81305, 0x7dd6668f, 0x176dd9de, + 0x7db0fdf8, 0x183366e9, + 0x7d8a5f40, 0x18f8b83c, 0x7d628ac6, 0x19bdcbf3, 0x7d3980ec, 0x1a82a026, + 0x7d0f4218, 0x1b4732ef, + 0x7ce3ceb2, 0x1c0b826a, 0x7cb72724, 0x1ccf8cb3, 0x7c894bde, 0x1d934fe5, + 0x7c5a3d50, 0x1e56ca1e, + 0x7c29fbee, 0x1f19f97b, 0x7bf88830, 0x1fdcdc1b, 0x7bc5e290, 0x209f701c, + 0x7b920b89, 0x2161b3a0, + 0x7b5d039e, 0x2223a4c5, 0x7b26cb4f, 0x22e541af, 0x7aef6323, 0x23a6887f, + 0x7ab6cba4, 0x24677758, + 0x7a7d055b, 0x25280c5e, 0x7a4210d8, 0x25e845b6, 0x7a05eead, 0x26a82186, + 0x79c89f6e, 0x27679df4, + 0x798a23b1, 0x2826b928, 0x794a7c12, 0x28e5714b, 0x7909a92d, 0x29a3c485, + 0x78c7aba2, 0x2a61b101, + 0x78848414, 0x2b1f34eb, 0x78403329, 0x2bdc4e6f, 0x77fab989, 0x2c98fbba, + 0x77b417df, 0x2d553afc, + 0x776c4edb, 0x2e110a62, 0x77235f2d, 0x2ecc681e, 0x76d94989, 0x2f875262, + 0x768e0ea6, 0x3041c761, + 0x7641af3d, 0x30fbc54d, 0x75f42c0b, 0x31b54a5e, 0x75a585cf, 0x326e54c7, + 0x7555bd4c, 0x3326e2c3, + 0x7504d345, 0x33def287, 0x74b2c884, 0x34968250, 0x745f9dd1, 0x354d9057, + 0x740b53fb, 0x36041ad9, + 0x73b5ebd1, 0x36ba2014, 0x735f6626, 0x376f9e46, 0x7307c3d0, 0x382493b0, + 0x72af05a7, 0x38d8fe93, + 0x72552c85, 0x398cdd32, 0x71fa3949, 0x3a402dd2, 0x719e2cd2, 0x3af2eeb7, + 0x71410805, 0x3ba51e29, + 0x70e2cbc6, 0x3c56ba70, 0x708378ff, 0x3d07c1d6, 0x7023109a, 0x3db832a6, + 0x6fc19385, 0x3e680b2c, + 0x6f5f02b2, 0x3f1749b8, 0x6efb5f12, 0x3fc5ec98, 0x6e96a99d, 0x4073f21d, + 0x6e30e34a, 0x4121589b, + 0x6dca0d14, 0x41ce1e65, 0x6d6227fa, 0x427a41d0, 0x6cf934fc, 0x4325c135, + 0x6c8f351c, 0x43d09aed, + 0x6c242960, 0x447acd50, 0x6bb812d1, 0x452456bd, 0x6b4af279, 0x45cd358f, + 0x6adcc964, 0x46756828, + 0x6a6d98a4, 0x471cece7, 0x69fd614a, 0x47c3c22f, 0x698c246c, 0x4869e665, + 0x6919e320, 0x490f57ee, + 0x68a69e81, 0x49b41533, 0x683257ab, 0x4a581c9e, 0x67bd0fbd, 0x4afb6c98, + 0x6746c7d8, 0x4b9e0390, + 0x66cf8120, 0x4c3fdff4, 0x66573cbb, 0x4ce10034, 0x65ddfbd3, 0x4d8162c4, + 0x6563bf92, 0x4e210617, + 0x64e88926, 0x4ebfe8a5, 0x646c59bf, 0x4f5e08e3, 0x63ef3290, 0x4ffb654d, + 0x637114cc, 0x5097fc5e, + 0x62f201ac, 0x5133cc94, 0x6271fa69, 0x51ced46e, 0x61f1003f, 0x5269126e, + 0x616f146c, 0x53028518, + 0x60ec3830, 0x539b2af0, 0x60686ccf, 0x5433027d, 0x5fe3b38d, 0x54ca0a4b, + 0x5f5e0db3, 0x556040e2, + 0x5ed77c8a, 0x55f5a4d2, 0x5e50015d, 0x568a34a9, 0x5dc79d7c, 0x571deefa, + 0x5d3e5237, 0x57b0d256, + 0x5cb420e0, 0x5842dd54, 0x5c290acc, 0x58d40e8c, 0x5b9d1154, 0x59646498, + 0x5b1035cf, 0x59f3de12, + 0x5a82799a, 0x5a82799a, 0x59f3de12, 0x5b1035cf, 0x59646498, 0x5b9d1154, + 0x58d40e8c, 0x5c290acc, + 0x5842dd54, 0x5cb420e0, 0x57b0d256, 0x5d3e5237, 0x571deefa, 0x5dc79d7c, + 0x568a34a9, 0x5e50015d, + 0x55f5a4d2, 0x5ed77c8a, 0x556040e2, 0x5f5e0db3, 0x54ca0a4b, 0x5fe3b38d, + 0x5433027d, 0x60686ccf, + 0x539b2af0, 0x60ec3830, 0x53028518, 0x616f146c, 0x5269126e, 0x61f1003f, + 0x51ced46e, 0x6271fa69, + 0x5133cc94, 0x62f201ac, 0x5097fc5e, 0x637114cc, 0x4ffb654d, 0x63ef3290, + 0x4f5e08e3, 0x646c59bf, + 0x4ebfe8a5, 0x64e88926, 0x4e210617, 0x6563bf92, 0x4d8162c4, 0x65ddfbd3, + 0x4ce10034, 0x66573cbb, + 0x4c3fdff4, 0x66cf8120, 0x4b9e0390, 0x6746c7d8, 0x4afb6c98, 0x67bd0fbd, + 0x4a581c9e, 0x683257ab, + 0x49b41533, 0x68a69e81, 0x490f57ee, 0x6919e320, 0x4869e665, 0x698c246c, + 0x47c3c22f, 0x69fd614a, + 0x471cece7, 0x6a6d98a4, 0x46756828, 0x6adcc964, 0x45cd358f, 0x6b4af279, + 0x452456bd, 0x6bb812d1, + 0x447acd50, 0x6c242960, 0x43d09aed, 0x6c8f351c, 0x4325c135, 0x6cf934fc, + 0x427a41d0, 0x6d6227fa, + 0x41ce1e65, 0x6dca0d14, 0x4121589b, 0x6e30e34a, 0x4073f21d, 0x6e96a99d, + 0x3fc5ec98, 0x6efb5f12, + 0x3f1749b8, 0x6f5f02b2, 0x3e680b2c, 0x6fc19385, 0x3db832a6, 0x7023109a, + 0x3d07c1d6, 0x708378ff, + 0x3c56ba70, 0x70e2cbc6, 0x3ba51e29, 0x71410805, 0x3af2eeb7, 0x719e2cd2, + 0x3a402dd2, 0x71fa3949, + 0x398cdd32, 0x72552c85, 0x38d8fe93, 0x72af05a7, 0x382493b0, 0x7307c3d0, + 0x376f9e46, 0x735f6626, + 0x36ba2014, 0x73b5ebd1, 0x36041ad9, 0x740b53fb, 0x354d9057, 0x745f9dd1, + 0x34968250, 0x74b2c884, + 0x33def287, 0x7504d345, 0x3326e2c3, 0x7555bd4c, 0x326e54c7, 0x75a585cf, + 0x31b54a5e, 0x75f42c0b, + 0x30fbc54d, 0x7641af3d, 0x3041c761, 0x768e0ea6, 0x2f875262, 0x76d94989, + 0x2ecc681e, 0x77235f2d, + 0x2e110a62, 0x776c4edb, 0x2d553afc, 0x77b417df, 0x2c98fbba, 0x77fab989, + 0x2bdc4e6f, 0x78403329, + 0x2b1f34eb, 0x78848414, 0x2a61b101, 0x78c7aba2, 0x29a3c485, 0x7909a92d, + 0x28e5714b, 0x794a7c12, + 0x2826b928, 0x798a23b1, 0x27679df4, 0x79c89f6e, 0x26a82186, 0x7a05eead, + 0x25e845b6, 0x7a4210d8, + 0x25280c5e, 0x7a7d055b, 0x24677758, 0x7ab6cba4, 0x23a6887f, 0x7aef6323, + 0x22e541af, 0x7b26cb4f, + 0x2223a4c5, 0x7b5d039e, 0x2161b3a0, 0x7b920b89, 0x209f701c, 0x7bc5e290, + 0x1fdcdc1b, 0x7bf88830, + 0x1f19f97b, 0x7c29fbee, 0x1e56ca1e, 0x7c5a3d50, 0x1d934fe5, 0x7c894bde, + 0x1ccf8cb3, 0x7cb72724, + 0x1c0b826a, 0x7ce3ceb2, 0x1b4732ef, 0x7d0f4218, 0x1a82a026, 0x7d3980ec, + 0x19bdcbf3, 0x7d628ac6, + 0x18f8b83c, 0x7d8a5f40, 0x183366e9, 0x7db0fdf8, 0x176dd9de, 0x7dd6668f, + 0x16a81305, 0x7dfa98a8, + 0x15e21445, 0x7e1d93ea, 0x151bdf86, 0x7e3f57ff, 0x145576b1, 0x7e5fe493, + 0x138edbb1, 0x7e7f3957, + 0x12c8106f, 0x7e9d55fc, 0x120116d5, 0x7eba3a39, 0x1139f0cf, 0x7ed5e5c6, + 0x1072a048, 0x7ef05860, + 0xfab272b, 0x7f0991c4, 0xee38766, 0x7f2191b4, 0xe1bc2e4, 0x7f3857f6, + 0xd53db92, 0x7f4de451, + 0xc8bd35e, 0x7f62368f, 0xbc3ac35, 0x7f754e80, 0xafb6805, 0x7f872bf3, + 0xa3308bd, 0x7f97cebd, + 0x96a9049, 0x7fa736b4, 0x8a2009a, 0x7fb563b3, 0x7d95b9e, 0x7fc25596, + 0x710a345, 0x7fce0c3e, + 0x647d97c, 0x7fd8878e, 0x57f0035, 0x7fe1c76b, 0x4b6195d, 0x7fe9cbc0, + 0x3ed26e6, 0x7ff09478, + 0x3242abf, 0x7ff62182, 0x25b26d7, 0x7ffa72d1, 0x1921d20, 0x7ffd885a, + 0xc90f88, 0x7fff6216, + 0x0, 0x7fffffff, 0xff36f078, 0x7fff6216, 0xfe6de2e0, 0x7ffd885a, 0xfda4d929, + 0x7ffa72d1, + 0xfcdbd541, 0x7ff62182, 0xfc12d91a, 0x7ff09478, 0xfb49e6a3, 0x7fe9cbc0, + 0xfa80ffcb, 0x7fe1c76b, + 0xf9b82684, 0x7fd8878e, 0xf8ef5cbb, 0x7fce0c3e, 0xf826a462, 0x7fc25596, + 0xf75dff66, 0x7fb563b3, + 0xf6956fb7, 0x7fa736b4, 0xf5ccf743, 0x7f97cebd, 0xf50497fb, 0x7f872bf3, + 0xf43c53cb, 0x7f754e80, + 0xf3742ca2, 0x7f62368f, 0xf2ac246e, 0x7f4de451, 0xf1e43d1c, 0x7f3857f6, + 0xf11c789a, 0x7f2191b4, + 0xf054d8d5, 0x7f0991c4, 0xef8d5fb8, 0x7ef05860, 0xeec60f31, 0x7ed5e5c6, + 0xedfee92b, 0x7eba3a39, + 0xed37ef91, 0x7e9d55fc, 0xec71244f, 0x7e7f3957, 0xebaa894f, 0x7e5fe493, + 0xeae4207a, 0x7e3f57ff, + 0xea1debbb, 0x7e1d93ea, 0xe957ecfb, 0x7dfa98a8, 0xe8922622, 0x7dd6668f, + 0xe7cc9917, 0x7db0fdf8, + 0xe70747c4, 0x7d8a5f40, 0xe642340d, 0x7d628ac6, 0xe57d5fda, 0x7d3980ec, + 0xe4b8cd11, 0x7d0f4218, + 0xe3f47d96, 0x7ce3ceb2, 0xe330734d, 0x7cb72724, 0xe26cb01b, 0x7c894bde, + 0xe1a935e2, 0x7c5a3d50, + 0xe0e60685, 0x7c29fbee, 0xe02323e5, 0x7bf88830, 0xdf608fe4, 0x7bc5e290, + 0xde9e4c60, 0x7b920b89, + 0xdddc5b3b, 0x7b5d039e, 0xdd1abe51, 0x7b26cb4f, 0xdc597781, 0x7aef6323, + 0xdb9888a8, 0x7ab6cba4, + 0xdad7f3a2, 0x7a7d055b, 0xda17ba4a, 0x7a4210d8, 0xd957de7a, 0x7a05eead, + 0xd898620c, 0x79c89f6e, + 0xd7d946d8, 0x798a23b1, 0xd71a8eb5, 0x794a7c12, 0xd65c3b7b, 0x7909a92d, + 0xd59e4eff, 0x78c7aba2, + 0xd4e0cb15, 0x78848414, 0xd423b191, 0x78403329, 0xd3670446, 0x77fab989, + 0xd2aac504, 0x77b417df, + 0xd1eef59e, 0x776c4edb, 0xd13397e2, 0x77235f2d, 0xd078ad9e, 0x76d94989, + 0xcfbe389f, 0x768e0ea6, + 0xcf043ab3, 0x7641af3d, 0xce4ab5a2, 0x75f42c0b, 0xcd91ab39, 0x75a585cf, + 0xccd91d3d, 0x7555bd4c, + 0xcc210d79, 0x7504d345, 0xcb697db0, 0x74b2c884, 0xcab26fa9, 0x745f9dd1, + 0xc9fbe527, 0x740b53fb, + 0xc945dfec, 0x73b5ebd1, 0xc89061ba, 0x735f6626, 0xc7db6c50, 0x7307c3d0, + 0xc727016d, 0x72af05a7, + 0xc67322ce, 0x72552c85, 0xc5bfd22e, 0x71fa3949, 0xc50d1149, 0x719e2cd2, + 0xc45ae1d7, 0x71410805, + 0xc3a94590, 0x70e2cbc6, 0xc2f83e2a, 0x708378ff, 0xc247cd5a, 0x7023109a, + 0xc197f4d4, 0x6fc19385, + 0xc0e8b648, 0x6f5f02b2, 0xc03a1368, 0x6efb5f12, 0xbf8c0de3, 0x6e96a99d, + 0xbedea765, 0x6e30e34a, + 0xbe31e19b, 0x6dca0d14, 0xbd85be30, 0x6d6227fa, 0xbcda3ecb, 0x6cf934fc, + 0xbc2f6513, 0x6c8f351c, + 0xbb8532b0, 0x6c242960, 0xbadba943, 0x6bb812d1, 0xba32ca71, 0x6b4af279, + 0xb98a97d8, 0x6adcc964, + 0xb8e31319, 0x6a6d98a4, 0xb83c3dd1, 0x69fd614a, 0xb796199b, 0x698c246c, + 0xb6f0a812, 0x6919e320, + 0xb64beacd, 0x68a69e81, 0xb5a7e362, 0x683257ab, 0xb5049368, 0x67bd0fbd, + 0xb461fc70, 0x6746c7d8, + 0xb3c0200c, 0x66cf8120, 0xb31effcc, 0x66573cbb, 0xb27e9d3c, 0x65ddfbd3, + 0xb1def9e9, 0x6563bf92, + 0xb140175b, 0x64e88926, 0xb0a1f71d, 0x646c59bf, 0xb0049ab3, 0x63ef3290, + 0xaf6803a2, 0x637114cc, + 0xaecc336c, 0x62f201ac, 0xae312b92, 0x6271fa69, 0xad96ed92, 0x61f1003f, + 0xacfd7ae8, 0x616f146c, + 0xac64d510, 0x60ec3830, 0xabccfd83, 0x60686ccf, 0xab35f5b5, 0x5fe3b38d, + 0xaa9fbf1e, 0x5f5e0db3, + 0xaa0a5b2e, 0x5ed77c8a, 0xa975cb57, 0x5e50015d, 0xa8e21106, 0x5dc79d7c, + 0xa84f2daa, 0x5d3e5237, + 0xa7bd22ac, 0x5cb420e0, 0xa72bf174, 0x5c290acc, 0xa69b9b68, 0x5b9d1154, + 0xa60c21ee, 0x5b1035cf, + 0xa57d8666, 0x5a82799a, 0xa4efca31, 0x59f3de12, 0xa462eeac, 0x59646498, + 0xa3d6f534, 0x58d40e8c, + 0xa34bdf20, 0x5842dd54, 0xa2c1adc9, 0x57b0d256, 0xa2386284, 0x571deefa, + 0xa1affea3, 0x568a34a9, + 0xa1288376, 0x55f5a4d2, 0xa0a1f24d, 0x556040e2, 0xa01c4c73, 0x54ca0a4b, + 0x9f979331, 0x5433027d, + 0x9f13c7d0, 0x539b2af0, 0x9e90eb94, 0x53028518, 0x9e0effc1, 0x5269126e, + 0x9d8e0597, 0x51ced46e, + 0x9d0dfe54, 0x5133cc94, 0x9c8eeb34, 0x5097fc5e, 0x9c10cd70, 0x4ffb654d, + 0x9b93a641, 0x4f5e08e3, + 0x9b1776da, 0x4ebfe8a5, 0x9a9c406e, 0x4e210617, 0x9a22042d, 0x4d8162c4, + 0x99a8c345, 0x4ce10034, + 0x99307ee0, 0x4c3fdff4, 0x98b93828, 0x4b9e0390, 0x9842f043, 0x4afb6c98, + 0x97cda855, 0x4a581c9e, + 0x9759617f, 0x49b41533, 0x96e61ce0, 0x490f57ee, 0x9673db94, 0x4869e665, + 0x96029eb6, 0x47c3c22f, + 0x9592675c, 0x471cece7, 0x9523369c, 0x46756828, 0x94b50d87, 0x45cd358f, + 0x9447ed2f, 0x452456bd, + 0x93dbd6a0, 0x447acd50, 0x9370cae4, 0x43d09aed, 0x9306cb04, 0x4325c135, + 0x929dd806, 0x427a41d0, + 0x9235f2ec, 0x41ce1e65, 0x91cf1cb6, 0x4121589b, 0x91695663, 0x4073f21d, + 0x9104a0ee, 0x3fc5ec98, + 0x90a0fd4e, 0x3f1749b8, 0x903e6c7b, 0x3e680b2c, 0x8fdcef66, 0x3db832a6, + 0x8f7c8701, 0x3d07c1d6, + 0x8f1d343a, 0x3c56ba70, 0x8ebef7fb, 0x3ba51e29, 0x8e61d32e, 0x3af2eeb7, + 0x8e05c6b7, 0x3a402dd2, + 0x8daad37b, 0x398cdd32, 0x8d50fa59, 0x38d8fe93, 0x8cf83c30, 0x382493b0, + 0x8ca099da, 0x376f9e46, + 0x8c4a142f, 0x36ba2014, 0x8bf4ac05, 0x36041ad9, 0x8ba0622f, 0x354d9057, + 0x8b4d377c, 0x34968250, + 0x8afb2cbb, 0x33def287, 0x8aaa42b4, 0x3326e2c3, 0x8a5a7a31, 0x326e54c7, + 0x8a0bd3f5, 0x31b54a5e, + 0x89be50c3, 0x30fbc54d, 0x8971f15a, 0x3041c761, 0x8926b677, 0x2f875262, + 0x88dca0d3, 0x2ecc681e, + 0x8893b125, 0x2e110a62, 0x884be821, 0x2d553afc, 0x88054677, 0x2c98fbba, + 0x87bfccd7, 0x2bdc4e6f, + 0x877b7bec, 0x2b1f34eb, 0x8738545e, 0x2a61b101, 0x86f656d3, 0x29a3c485, + 0x86b583ee, 0x28e5714b, + 0x8675dc4f, 0x2826b928, 0x86376092, 0x27679df4, 0x85fa1153, 0x26a82186, + 0x85bdef28, 0x25e845b6, + 0x8582faa5, 0x25280c5e, 0x8549345c, 0x24677758, 0x85109cdd, 0x23a6887f, + 0x84d934b1, 0x22e541af, + 0x84a2fc62, 0x2223a4c5, 0x846df477, 0x2161b3a0, 0x843a1d70, 0x209f701c, + 0x840777d0, 0x1fdcdc1b, + 0x83d60412, 0x1f19f97b, 0x83a5c2b0, 0x1e56ca1e, 0x8376b422, 0x1d934fe5, + 0x8348d8dc, 0x1ccf8cb3, + 0x831c314e, 0x1c0b826a, 0x82f0bde8, 0x1b4732ef, 0x82c67f14, 0x1a82a026, + 0x829d753a, 0x19bdcbf3, + 0x8275a0c0, 0x18f8b83c, 0x824f0208, 0x183366e9, 0x82299971, 0x176dd9de, + 0x82056758, 0x16a81305, + 0x81e26c16, 0x15e21445, 0x81c0a801, 0x151bdf86, 0x81a01b6d, 0x145576b1, + 0x8180c6a9, 0x138edbb1, + 0x8162aa04, 0x12c8106f, 0x8145c5c7, 0x120116d5, 0x812a1a3a, 0x1139f0cf, + 0x810fa7a0, 0x1072a048, + 0x80f66e3c, 0xfab272b, 0x80de6e4c, 0xee38766, 0x80c7a80a, 0xe1bc2e4, + 0x80b21baf, 0xd53db92, + 0x809dc971, 0xc8bd35e, 0x808ab180, 0xbc3ac35, 0x8078d40d, 0xafb6805, + 0x80683143, 0xa3308bd, + 0x8058c94c, 0x96a9049, 0x804a9c4d, 0x8a2009a, 0x803daa6a, 0x7d95b9e, + 0x8031f3c2, 0x710a345, + 0x80277872, 0x647d97c, 0x801e3895, 0x57f0035, 0x80163440, 0x4b6195d, + 0x800f6b88, 0x3ed26e6, + 0x8009de7e, 0x3242abf, 0x80058d2f, 0x25b26d7, 0x800277a6, 0x1921d20, + 0x80009dea, 0xc90f88, + 0x80000000, 0x0, 0x80009dea, 0xff36f078, 0x800277a6, 0xfe6de2e0, 0x80058d2f, + 0xfda4d929, + 0x8009de7e, 0xfcdbd541, 0x800f6b88, 0xfc12d91a, 0x80163440, 0xfb49e6a3, + 0x801e3895, 0xfa80ffcb, + 0x80277872, 0xf9b82684, 0x8031f3c2, 0xf8ef5cbb, 0x803daa6a, 0xf826a462, + 0x804a9c4d, 0xf75dff66, + 0x8058c94c, 0xf6956fb7, 0x80683143, 0xf5ccf743, 0x8078d40d, 0xf50497fb, + 0x808ab180, 0xf43c53cb, + 0x809dc971, 0xf3742ca2, 0x80b21baf, 0xf2ac246e, 0x80c7a80a, 0xf1e43d1c, + 0x80de6e4c, 0xf11c789a, + 0x80f66e3c, 0xf054d8d5, 0x810fa7a0, 0xef8d5fb8, 0x812a1a3a, 0xeec60f31, + 0x8145c5c7, 0xedfee92b, + 0x8162aa04, 0xed37ef91, 0x8180c6a9, 0xec71244f, 0x81a01b6d, 0xebaa894f, + 0x81c0a801, 0xeae4207a, + 0x81e26c16, 0xea1debbb, 0x82056758, 0xe957ecfb, 0x82299971, 0xe8922622, + 0x824f0208, 0xe7cc9917, + 0x8275a0c0, 0xe70747c4, 0x829d753a, 0xe642340d, 0x82c67f14, 0xe57d5fda, + 0x82f0bde8, 0xe4b8cd11, + 0x831c314e, 0xe3f47d96, 0x8348d8dc, 0xe330734d, 0x8376b422, 0xe26cb01b, + 0x83a5c2b0, 0xe1a935e2, + 0x83d60412, 0xe0e60685, 0x840777d0, 0xe02323e5, 0x843a1d70, 0xdf608fe4, + 0x846df477, 0xde9e4c60, + 0x84a2fc62, 0xdddc5b3b, 0x84d934b1, 0xdd1abe51, 0x85109cdd, 0xdc597781, + 0x8549345c, 0xdb9888a8, + 0x8582faa5, 0xdad7f3a2, 0x85bdef28, 0xda17ba4a, 0x85fa1153, 0xd957de7a, + 0x86376092, 0xd898620c, + 0x8675dc4f, 0xd7d946d8, 0x86b583ee, 0xd71a8eb5, 0x86f656d3, 0xd65c3b7b, + 0x8738545e, 0xd59e4eff, + 0x877b7bec, 0xd4e0cb15, 0x87bfccd7, 0xd423b191, 0x88054677, 0xd3670446, + 0x884be821, 0xd2aac504, + 0x8893b125, 0xd1eef59e, 0x88dca0d3, 0xd13397e2, 0x8926b677, 0xd078ad9e, + 0x8971f15a, 0xcfbe389f, + 0x89be50c3, 0xcf043ab3, 0x8a0bd3f5, 0xce4ab5a2, 0x8a5a7a31, 0xcd91ab39, + 0x8aaa42b4, 0xccd91d3d, + 0x8afb2cbb, 0xcc210d79, 0x8b4d377c, 0xcb697db0, 0x8ba0622f, 0xcab26fa9, + 0x8bf4ac05, 0xc9fbe527, + 0x8c4a142f, 0xc945dfec, 0x8ca099da, 0xc89061ba, 0x8cf83c30, 0xc7db6c50, + 0x8d50fa59, 0xc727016d, + 0x8daad37b, 0xc67322ce, 0x8e05c6b7, 0xc5bfd22e, 0x8e61d32e, 0xc50d1149, + 0x8ebef7fb, 0xc45ae1d7, + 0x8f1d343a, 0xc3a94590, 0x8f7c8701, 0xc2f83e2a, 0x8fdcef66, 0xc247cd5a, + 0x903e6c7b, 0xc197f4d4, + 0x90a0fd4e, 0xc0e8b648, 0x9104a0ee, 0xc03a1368, 0x91695663, 0xbf8c0de3, + 0x91cf1cb6, 0xbedea765, + 0x9235f2ec, 0xbe31e19b, 0x929dd806, 0xbd85be30, 0x9306cb04, 0xbcda3ecb, + 0x9370cae4, 0xbc2f6513, + 0x93dbd6a0, 0xbb8532b0, 0x9447ed2f, 0xbadba943, 0x94b50d87, 0xba32ca71, + 0x9523369c, 0xb98a97d8, + 0x9592675c, 0xb8e31319, 0x96029eb6, 0xb83c3dd1, 0x9673db94, 0xb796199b, + 0x96e61ce0, 0xb6f0a812, + 0x9759617f, 0xb64beacd, 0x97cda855, 0xb5a7e362, 0x9842f043, 0xb5049368, + 0x98b93828, 0xb461fc70, + 0x99307ee0, 0xb3c0200c, 0x99a8c345, 0xb31effcc, 0x9a22042d, 0xb27e9d3c, + 0x9a9c406e, 0xb1def9e9, + 0x9b1776da, 0xb140175b, 0x9b93a641, 0xb0a1f71d, 0x9c10cd70, 0xb0049ab3, + 0x9c8eeb34, 0xaf6803a2, + 0x9d0dfe54, 0xaecc336c, 0x9d8e0597, 0xae312b92, 0x9e0effc1, 0xad96ed92, + 0x9e90eb94, 0xacfd7ae8, + 0x9f13c7d0, 0xac64d510, 0x9f979331, 0xabccfd83, 0xa01c4c73, 0xab35f5b5, + 0xa0a1f24d, 0xaa9fbf1e, + 0xa1288376, 0xaa0a5b2e, 0xa1affea3, 0xa975cb57, 0xa2386284, 0xa8e21106, + 0xa2c1adc9, 0xa84f2daa, + 0xa34bdf20, 0xa7bd22ac, 0xa3d6f534, 0xa72bf174, 0xa462eeac, 0xa69b9b68, + 0xa4efca31, 0xa60c21ee, + 0xa57d8666, 0xa57d8666, 0xa60c21ee, 0xa4efca31, 0xa69b9b68, 0xa462eeac, + 0xa72bf174, 0xa3d6f534, + 0xa7bd22ac, 0xa34bdf20, 0xa84f2daa, 0xa2c1adc9, 0xa8e21106, 0xa2386284, + 0xa975cb57, 0xa1affea3, + 0xaa0a5b2e, 0xa1288376, 0xaa9fbf1e, 0xa0a1f24d, 0xab35f5b5, 0xa01c4c73, + 0xabccfd83, 0x9f979331, + 0xac64d510, 0x9f13c7d0, 0xacfd7ae8, 0x9e90eb94, 0xad96ed92, 0x9e0effc1, + 0xae312b92, 0x9d8e0597, + 0xaecc336c, 0x9d0dfe54, 0xaf6803a2, 0x9c8eeb34, 0xb0049ab3, 0x9c10cd70, + 0xb0a1f71d, 0x9b93a641, + 0xb140175b, 0x9b1776da, 0xb1def9e9, 0x9a9c406e, 0xb27e9d3c, 0x9a22042d, + 0xb31effcc, 0x99a8c345, + 0xb3c0200c, 0x99307ee0, 0xb461fc70, 0x98b93828, 0xb5049368, 0x9842f043, + 0xb5a7e362, 0x97cda855, + 0xb64beacd, 0x9759617f, 0xb6f0a812, 0x96e61ce0, 0xb796199b, 0x9673db94, + 0xb83c3dd1, 0x96029eb6, + 0xb8e31319, 0x9592675c, 0xb98a97d8, 0x9523369c, 0xba32ca71, 0x94b50d87, + 0xbadba943, 0x9447ed2f, + 0xbb8532b0, 0x93dbd6a0, 0xbc2f6513, 0x9370cae4, 0xbcda3ecb, 0x9306cb04, + 0xbd85be30, 0x929dd806, + 0xbe31e19b, 0x9235f2ec, 0xbedea765, 0x91cf1cb6, 0xbf8c0de3, 0x91695663, + 0xc03a1368, 0x9104a0ee, + 0xc0e8b648, 0x90a0fd4e, 0xc197f4d4, 0x903e6c7b, 0xc247cd5a, 0x8fdcef66, + 0xc2f83e2a, 0x8f7c8701, + 0xc3a94590, 0x8f1d343a, 0xc45ae1d7, 0x8ebef7fb, 0xc50d1149, 0x8e61d32e, + 0xc5bfd22e, 0x8e05c6b7, + 0xc67322ce, 0x8daad37b, 0xc727016d, 0x8d50fa59, 0xc7db6c50, 0x8cf83c30, + 0xc89061ba, 0x8ca099da, + 0xc945dfec, 0x8c4a142f, 0xc9fbe527, 0x8bf4ac05, 0xcab26fa9, 0x8ba0622f, + 0xcb697db0, 0x8b4d377c, + 0xcc210d79, 0x8afb2cbb, 0xccd91d3d, 0x8aaa42b4, 0xcd91ab39, 0x8a5a7a31, + 0xce4ab5a2, 0x8a0bd3f5, + 0xcf043ab3, 0x89be50c3, 0xcfbe389f, 0x8971f15a, 0xd078ad9e, 0x8926b677, + 0xd13397e2, 0x88dca0d3, + 0xd1eef59e, 0x8893b125, 0xd2aac504, 0x884be821, 0xd3670446, 0x88054677, + 0xd423b191, 0x87bfccd7, + 0xd4e0cb15, 0x877b7bec, 0xd59e4eff, 0x8738545e, 0xd65c3b7b, 0x86f656d3, + 0xd71a8eb5, 0x86b583ee, + 0xd7d946d8, 0x8675dc4f, 0xd898620c, 0x86376092, 0xd957de7a, 0x85fa1153, + 0xda17ba4a, 0x85bdef28, + 0xdad7f3a2, 0x8582faa5, 0xdb9888a8, 0x8549345c, 0xdc597781, 0x85109cdd, + 0xdd1abe51, 0x84d934b1, + 0xdddc5b3b, 0x84a2fc62, 0xde9e4c60, 0x846df477, 0xdf608fe4, 0x843a1d70, + 0xe02323e5, 0x840777d0, + 0xe0e60685, 0x83d60412, 0xe1a935e2, 0x83a5c2b0, 0xe26cb01b, 0x8376b422, + 0xe330734d, 0x8348d8dc, + 0xe3f47d96, 0x831c314e, 0xe4b8cd11, 0x82f0bde8, 0xe57d5fda, 0x82c67f14, + 0xe642340d, 0x829d753a, + 0xe70747c4, 0x8275a0c0, 0xe7cc9917, 0x824f0208, 0xe8922622, 0x82299971, + 0xe957ecfb, 0x82056758, + 0xea1debbb, 0x81e26c16, 0xeae4207a, 0x81c0a801, 0xebaa894f, 0x81a01b6d, + 0xec71244f, 0x8180c6a9, + 0xed37ef91, 0x8162aa04, 0xedfee92b, 0x8145c5c7, 0xeec60f31, 0x812a1a3a, + 0xef8d5fb8, 0x810fa7a0, + 0xf054d8d5, 0x80f66e3c, 0xf11c789a, 0x80de6e4c, 0xf1e43d1c, 0x80c7a80a, + 0xf2ac246e, 0x80b21baf, + 0xf3742ca2, 0x809dc971, 0xf43c53cb, 0x808ab180, 0xf50497fb, 0x8078d40d, + 0xf5ccf743, 0x80683143, + 0xf6956fb7, 0x8058c94c, 0xf75dff66, 0x804a9c4d, 0xf826a462, 0x803daa6a, + 0xf8ef5cbb, 0x8031f3c2, + 0xf9b82684, 0x80277872, 0xfa80ffcb, 0x801e3895, 0xfb49e6a3, 0x80163440, + 0xfc12d91a, 0x800f6b88, + 0xfcdbd541, 0x8009de7e, 0xfda4d929, 0x80058d2f, 0xfe6de2e0, 0x800277a6, + 0xff36f078, 0x80009dea, + 0x0, 0x80000000, 0xc90f88, 0x80009dea, 0x1921d20, 0x800277a6, 0x25b26d7, + 0x80058d2f, + 0x3242abf, 0x8009de7e, 0x3ed26e6, 0x800f6b88, 0x4b6195d, 0x80163440, + 0x57f0035, 0x801e3895, + 0x647d97c, 0x80277872, 0x710a345, 0x8031f3c2, 0x7d95b9e, 0x803daa6a, + 0x8a2009a, 0x804a9c4d, + 0x96a9049, 0x8058c94c, 0xa3308bd, 0x80683143, 0xafb6805, 0x8078d40d, + 0xbc3ac35, 0x808ab180, + 0xc8bd35e, 0x809dc971, 0xd53db92, 0x80b21baf, 0xe1bc2e4, 0x80c7a80a, + 0xee38766, 0x80de6e4c, + 0xfab272b, 0x80f66e3c, 0x1072a048, 0x810fa7a0, 0x1139f0cf, 0x812a1a3a, + 0x120116d5, 0x8145c5c7, + 0x12c8106f, 0x8162aa04, 0x138edbb1, 0x8180c6a9, 0x145576b1, 0x81a01b6d, + 0x151bdf86, 0x81c0a801, + 0x15e21445, 0x81e26c16, 0x16a81305, 0x82056758, 0x176dd9de, 0x82299971, + 0x183366e9, 0x824f0208, + 0x18f8b83c, 0x8275a0c0, 0x19bdcbf3, 0x829d753a, 0x1a82a026, 0x82c67f14, + 0x1b4732ef, 0x82f0bde8, + 0x1c0b826a, 0x831c314e, 0x1ccf8cb3, 0x8348d8dc, 0x1d934fe5, 0x8376b422, + 0x1e56ca1e, 0x83a5c2b0, + 0x1f19f97b, 0x83d60412, 0x1fdcdc1b, 0x840777d0, 0x209f701c, 0x843a1d70, + 0x2161b3a0, 0x846df477, + 0x2223a4c5, 0x84a2fc62, 0x22e541af, 0x84d934b1, 0x23a6887f, 0x85109cdd, + 0x24677758, 0x8549345c, + 0x25280c5e, 0x8582faa5, 0x25e845b6, 0x85bdef28, 0x26a82186, 0x85fa1153, + 0x27679df4, 0x86376092, + 0x2826b928, 0x8675dc4f, 0x28e5714b, 0x86b583ee, 0x29a3c485, 0x86f656d3, + 0x2a61b101, 0x8738545e, + 0x2b1f34eb, 0x877b7bec, 0x2bdc4e6f, 0x87bfccd7, 0x2c98fbba, 0x88054677, + 0x2d553afc, 0x884be821, + 0x2e110a62, 0x8893b125, 0x2ecc681e, 0x88dca0d3, 0x2f875262, 0x8926b677, + 0x3041c761, 0x8971f15a, + 0x30fbc54d, 0x89be50c3, 0x31b54a5e, 0x8a0bd3f5, 0x326e54c7, 0x8a5a7a31, + 0x3326e2c3, 0x8aaa42b4, + 0x33def287, 0x8afb2cbb, 0x34968250, 0x8b4d377c, 0x354d9057, 0x8ba0622f, + 0x36041ad9, 0x8bf4ac05, + 0x36ba2014, 0x8c4a142f, 0x376f9e46, 0x8ca099da, 0x382493b0, 0x8cf83c30, + 0x38d8fe93, 0x8d50fa59, + 0x398cdd32, 0x8daad37b, 0x3a402dd2, 0x8e05c6b7, 0x3af2eeb7, 0x8e61d32e, + 0x3ba51e29, 0x8ebef7fb, + 0x3c56ba70, 0x8f1d343a, 0x3d07c1d6, 0x8f7c8701, 0x3db832a6, 0x8fdcef66, + 0x3e680b2c, 0x903e6c7b, + 0x3f1749b8, 0x90a0fd4e, 0x3fc5ec98, 0x9104a0ee, 0x4073f21d, 0x91695663, + 0x4121589b, 0x91cf1cb6, + 0x41ce1e65, 0x9235f2ec, 0x427a41d0, 0x929dd806, 0x4325c135, 0x9306cb04, + 0x43d09aed, 0x9370cae4, + 0x447acd50, 0x93dbd6a0, 0x452456bd, 0x9447ed2f, 0x45cd358f, 0x94b50d87, + 0x46756828, 0x9523369c, + 0x471cece7, 0x9592675c, 0x47c3c22f, 0x96029eb6, 0x4869e665, 0x9673db94, + 0x490f57ee, 0x96e61ce0, + 0x49b41533, 0x9759617f, 0x4a581c9e, 0x97cda855, 0x4afb6c98, 0x9842f043, + 0x4b9e0390, 0x98b93828, + 0x4c3fdff4, 0x99307ee0, 0x4ce10034, 0x99a8c345, 0x4d8162c4, 0x9a22042d, + 0x4e210617, 0x9a9c406e, + 0x4ebfe8a5, 0x9b1776da, 0x4f5e08e3, 0x9b93a641, 0x4ffb654d, 0x9c10cd70, + 0x5097fc5e, 0x9c8eeb34, + 0x5133cc94, 0x9d0dfe54, 0x51ced46e, 0x9d8e0597, 0x5269126e, 0x9e0effc1, + 0x53028518, 0x9e90eb94, + 0x539b2af0, 0x9f13c7d0, 0x5433027d, 0x9f979331, 0x54ca0a4b, 0xa01c4c73, + 0x556040e2, 0xa0a1f24d, + 0x55f5a4d2, 0xa1288376, 0x568a34a9, 0xa1affea3, 0x571deefa, 0xa2386284, + 0x57b0d256, 0xa2c1adc9, + 0x5842dd54, 0xa34bdf20, 0x58d40e8c, 0xa3d6f534, 0x59646498, 0xa462eeac, + 0x59f3de12, 0xa4efca31, + 0x5a82799a, 0xa57d8666, 0x5b1035cf, 0xa60c21ee, 0x5b9d1154, 0xa69b9b68, + 0x5c290acc, 0xa72bf174, + 0x5cb420e0, 0xa7bd22ac, 0x5d3e5237, 0xa84f2daa, 0x5dc79d7c, 0xa8e21106, + 0x5e50015d, 0xa975cb57, + 0x5ed77c8a, 0xaa0a5b2e, 0x5f5e0db3, 0xaa9fbf1e, 0x5fe3b38d, 0xab35f5b5, + 0x60686ccf, 0xabccfd83, + 0x60ec3830, 0xac64d510, 0x616f146c, 0xacfd7ae8, 0x61f1003f, 0xad96ed92, + 0x6271fa69, 0xae312b92, + 0x62f201ac, 0xaecc336c, 0x637114cc, 0xaf6803a2, 0x63ef3290, 0xb0049ab3, + 0x646c59bf, 0xb0a1f71d, + 0x64e88926, 0xb140175b, 0x6563bf92, 0xb1def9e9, 0x65ddfbd3, 0xb27e9d3c, + 0x66573cbb, 0xb31effcc, + 0x66cf8120, 0xb3c0200c, 0x6746c7d8, 0xb461fc70, 0x67bd0fbd, 0xb5049368, + 0x683257ab, 0xb5a7e362, + 0x68a69e81, 0xb64beacd, 0x6919e320, 0xb6f0a812, 0x698c246c, 0xb796199b, + 0x69fd614a, 0xb83c3dd1, + 0x6a6d98a4, 0xb8e31319, 0x6adcc964, 0xb98a97d8, 0x6b4af279, 0xba32ca71, + 0x6bb812d1, 0xbadba943, + 0x6c242960, 0xbb8532b0, 0x6c8f351c, 0xbc2f6513, 0x6cf934fc, 0xbcda3ecb, + 0x6d6227fa, 0xbd85be30, + 0x6dca0d14, 0xbe31e19b, 0x6e30e34a, 0xbedea765, 0x6e96a99d, 0xbf8c0de3, + 0x6efb5f12, 0xc03a1368, + 0x6f5f02b2, 0xc0e8b648, 0x6fc19385, 0xc197f4d4, 0x7023109a, 0xc247cd5a, + 0x708378ff, 0xc2f83e2a, + 0x70e2cbc6, 0xc3a94590, 0x71410805, 0xc45ae1d7, 0x719e2cd2, 0xc50d1149, + 0x71fa3949, 0xc5bfd22e, + 0x72552c85, 0xc67322ce, 0x72af05a7, 0xc727016d, 0x7307c3d0, 0xc7db6c50, + 0x735f6626, 0xc89061ba, + 0x73b5ebd1, 0xc945dfec, 0x740b53fb, 0xc9fbe527, 0x745f9dd1, 0xcab26fa9, + 0x74b2c884, 0xcb697db0, + 0x7504d345, 0xcc210d79, 0x7555bd4c, 0xccd91d3d, 0x75a585cf, 0xcd91ab39, + 0x75f42c0b, 0xce4ab5a2, + 0x7641af3d, 0xcf043ab3, 0x768e0ea6, 0xcfbe389f, 0x76d94989, 0xd078ad9e, + 0x77235f2d, 0xd13397e2, + 0x776c4edb, 0xd1eef59e, 0x77b417df, 0xd2aac504, 0x77fab989, 0xd3670446, + 0x78403329, 0xd423b191, + 0x78848414, 0xd4e0cb15, 0x78c7aba2, 0xd59e4eff, 0x7909a92d, 0xd65c3b7b, + 0x794a7c12, 0xd71a8eb5, + 0x798a23b1, 0xd7d946d8, 0x79c89f6e, 0xd898620c, 0x7a05eead, 0xd957de7a, + 0x7a4210d8, 0xda17ba4a, + 0x7a7d055b, 0xdad7f3a2, 0x7ab6cba4, 0xdb9888a8, 0x7aef6323, 0xdc597781, + 0x7b26cb4f, 0xdd1abe51, + 0x7b5d039e, 0xdddc5b3b, 0x7b920b89, 0xde9e4c60, 0x7bc5e290, 0xdf608fe4, + 0x7bf88830, 0xe02323e5, + 0x7c29fbee, 0xe0e60685, 0x7c5a3d50, 0xe1a935e2, 0x7c894bde, 0xe26cb01b, + 0x7cb72724, 0xe330734d, + 0x7ce3ceb2, 0xe3f47d96, 0x7d0f4218, 0xe4b8cd11, 0x7d3980ec, 0xe57d5fda, + 0x7d628ac6, 0xe642340d, + 0x7d8a5f40, 0xe70747c4, 0x7db0fdf8, 0xe7cc9917, 0x7dd6668f, 0xe8922622, + 0x7dfa98a8, 0xe957ecfb, + 0x7e1d93ea, 0xea1debbb, 0x7e3f57ff, 0xeae4207a, 0x7e5fe493, 0xebaa894f, + 0x7e7f3957, 0xec71244f, + 0x7e9d55fc, 0xed37ef91, 0x7eba3a39, 0xedfee92b, 0x7ed5e5c6, 0xeec60f31, + 0x7ef05860, 0xef8d5fb8, + 0x7f0991c4, 0xf054d8d5, 0x7f2191b4, 0xf11c789a, 0x7f3857f6, 0xf1e43d1c, + 0x7f4de451, 0xf2ac246e, + 0x7f62368f, 0xf3742ca2, 0x7f754e80, 0xf43c53cb, 0x7f872bf3, 0xf50497fb, + 0x7f97cebd, 0xf5ccf743, + 0x7fa736b4, 0xf6956fb7, 0x7fb563b3, 0xf75dff66, 0x7fc25596, 0xf826a462, + 0x7fce0c3e, 0xf8ef5cbb, + 0x7fd8878e, 0xf9b82684, 0x7fe1c76b, 0xfa80ffcb, 0x7fe9cbc0, 0xfb49e6a3, + 0x7ff09478, 0xfc12d91a, + 0x7ff62182, 0xfcdbd541, 0x7ffa72d1, 0xfda4d929, 0x7ffd885a, 0xfe6de2e0, + 0x7fff6216, 0xff36f078 +}; + +/** +* +* @brief Initialization function for the Q31 CFFT/CIFFT. +* @param[in,out] *S points to an instance of the Q31 CFFT/CIFFT structure. +* @param[in] fftLen length of the FFT. +* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. +* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. +* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. +* +* \par Description: +* \par +* The parameter ifftFlag controls whether a forward or inverse transform is computed. +* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated +* \par +* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. +* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. +* \par +* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. +* \par +* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. +*/ + +arm_status arm_cfft_radix4_init_q31( + arm_cfft_radix4_instance_q31 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag) +{ + /* Initialise the default arm status */ + arm_status status = ARM_MATH_SUCCESS; + /* Initialise the FFT length */ + S->fftLen = fftLen; + /* Initialise the Twiddle coefficient pointer */ + S->pTwiddle = (q31_t *) twiddleCoefQ31; + /* Initialise the Flag for selection of CFFT or CIFFT */ + S->ifftFlag = ifftFlag; + /* Initialise the Flag for calculation Bit reversal or not */ + S->bitReverseFlag = bitReverseFlag; + + /* Initializations of Instance structure depending on the FFT length */ + switch (S->fftLen) + { + /* Initializations of structure parameters for 1024 point FFT */ + case 1024u: + /* Initialise the twiddle coef modifier value */ + S->twidCoefModifier = 1u; + /* Initialise the bit reversal table modifier */ + S->bitRevFactor = 1u; + /* Initialise the bit reversal table pointer */ + S->pBitRevTable = armBitRevTable; + break; + + case 256u: + /* Initializations of structure parameters for 256 point FFT */ + S->twidCoefModifier = 4u; + S->bitRevFactor = 4u; + S->pBitRevTable = (uint16_t *) & armBitRevTable[3]; + break; + + case 64u: + /* Initializations of structure parameters for 64 point FFT */ + S->twidCoefModifier = 16u; + S->bitRevFactor = 16u; + S->pBitRevTable = &armBitRevTable[15]; + break; + + case 16u: + /* Initializations of structure parameters for 16 point FFT */ + S->twidCoefModifier = 64u; + S->bitRevFactor = 64u; + S->pBitRevTable = &armBitRevTable[63]; + break; + + default: + /* Reporting argument error if fftSize is not valid value */ + status = ARM_MATH_ARGUMENT_ERROR; + break; + } + + return (status); +} + +/** + * @} end of CFFT_CIFFT group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q15.c index 0f45b5255..d855a10e0 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q15.c @@ -1,1952 +1,1952 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_q15.c -* -* Description: This file has function definition of Radix-4 FFT & IFFT function and -* In-place bit reversal using bit reversal table -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup CFFT_CIFFT - * @{ - */ - - -/** - * @details - * @brief Processing function for the Q15 CFFT/CIFFT. - * @param[in] *S points to an instance of the Q15 CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. - * @return none. - * - * \par Input and output formats: - * \par - * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. - * Hence the output format is different for different FFT sizes. - * The input and output formats for different FFT sizes and number of bits to upscale are mentioned in the tables below for CFFT and CIFFT: - * \par - * \image html CFFTQ15.gif "Input and Output Formats for Q15 CFFT" - * \image html CIFFTQ15.gif "Input and Output Formats for Q15 CIFFT" - */ - -void arm_cfft_radix4_q15( - const arm_cfft_radix4_instance_q15 * S, - q15_t * pSrc) -{ - if(S->ifftFlag == 1u) - { - /* Complex IFFT radix-4 */ - arm_radix4_butterfly_inverse_q15(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - else - { - /* Complex FFT radix-4 */ - arm_radix4_butterfly_q15(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - - if(S->bitReverseFlag == 1u) - { - /* Bit Reversal */ - arm_bitreversal_q15(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); - } - -} - -/** - * @} end of CFFT_CIFFT group - */ - -/* -* Radix-4 FFT algorithm used is : -* -* Input real and imaginary data: -* x(n) = xa + j * ya -* x(n+N/4 ) = xb + j * yb -* x(n+N/2 ) = xc + j * yc -* x(n+3N 4) = xd + j * yd -* -* -* Output real and imaginary data: -* x(4r) = xa'+ j * ya' -* x(4r+1) = xb'+ j * yb' -* x(4r+2) = xc'+ j * yc' -* x(4r+3) = xd'+ j * yd' -* -* -* Twiddle factors for radix-4 FFT: -* Wn = co1 + j * (- si1) -* W2n = co2 + j * (- si2) -* W3n = co3 + j * (- si3) - -* The real and imaginary output values for the radix-4 butterfly are -* xa' = xa + xb + xc + xd -* ya' = ya + yb + yc + yd -* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) -* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) -* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) -* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) -* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) -* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) -* -*/ - -/** - * @brief Core function for the Q15 CFFT butterfly process. - * @param[in, out] *pSrc16 points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef16 points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_radix4_butterfly_q15( - q15_t * pSrc16, - uint32_t fftLen, - q15_t * pCoef16, - uint32_t twidCoefModifier) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t R, S, T, U; - q31_t C1, C2, C3, out1, out2; - q31_t *pSrc, *pCoeff; - uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; - q15_t in; - - /* Total process is divided into three stages */ - - /* process first stage, middle stages, & last stage */ - - /* pointer initializations for SIMD calculations */ - pSrc = (q31_t *) pSrc16; - pCoeff = (q31_t *) pCoef16; - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - - /* Index for twiddle coefficient */ - ic = 0u; - - /* Index for input read and output write */ - i0 = 0u; - j = n2; - - /* Input is in 1.15(q15) format */ - - /* start of first stage process */ - do - { - /* Butterfly implementation */ - - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T = pSrc[i0]; - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - /* Read yc (real), xc(imag) input */ - S = pSrc[i2]; - in = ((int16_t) (S & 0xFFFF)) >> 2; - S = ((S >> 2) & 0xFFFF0000) | (in & 0xFFFF); - /* R = packed((ya + yc), (xa + xc) ) */ - R = __QADD16(T, S); - /* S = packed((ya - yc), (xa - xc) ) */ - S = __QSUB16(T, S); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T = pSrc[i1]; - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - /* Read yd (real), xd(imag) input */ - U = pSrc[i3]; - in = ((int16_t) (U & 0xFFFF)) >> 2; - U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); - /* T = packed((yb + yd), (xb + xd) ) */ - T = __QADD16(T, U); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc[i0] = __SHADD16(R, T); - - /* R = packed((ya + yc) - (yb + yd), (xa + xc)- (xb + xd)) */ - R = __QSUB16(R, T); - - /* co2 & si2 are read from SIMD Coefficient pointer */ - C2 = pCoeff[2u * ic]; - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - out1 = __SMUAD(C2, R) >> 16u; - /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out2 = __SMUSDX(C2, R); - -#else - - /* xc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out1 = __SMUSDX(R, C2) >> 16u; - /* yc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - out2 = __SMUAD(C2, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Reading i0+fftLen/4 */ - /* T = packed(yb, xb) */ - T = pSrc[i1]; - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* writing output(xc', yc') in little endian format */ - pSrc[i1] = (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly calculations */ - /* U = packed(yd, xd) */ - U = pSrc[i3]; - in = ((int16_t) (U & 0xFFFF)) >> 2; - U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); - /* T = packed(yb-yd, xb-xd) */ - T = __QSUB16(T, U); - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __QASX(S, T); - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __QSAX(S, T); - -#else - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __QSAX(S, T); - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __QASX(S, T); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* co1 & si1 are read from SIMD Coefficient pointer */ - C1 = pCoeff[ic]; - /* Butterfly process for the i0+fftLen/2 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - out1 = __SMUAD(C1, S) >> 16u; - /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - out2 = __SMUSDX(C1, S); - -#else - - /* xb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - out1 = __SMUSDX(S, C1) >> 16u; - /* yb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - out2 = __SMUAD(C1, S); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* writing output(xb', yb') in little endian format */ - pSrc[i2] = ((out2) & 0xFFFF0000) | ((out1) & 0x0000FFFF); - - - /* co3 & si3 are read from SIMD Coefficient pointer */ - C3 = pCoeff[3u * ic]; - /* Butterfly process for the i0+3fftLen/4 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ - out1 = __SMUAD(C3, R) >> 16u; - /* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ - out2 = __SMUSDX(C3, R); - -#else - - /* xd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ - out1 = __SMUSDX(R, C3) >> 16u; - /* yd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ - out2 = __SMUAD(C3, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* writing output(xd', yd') in little endian format */ - pSrc[i3] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - /* data is in 4.11(q11) format */ - - /* end of first stage process */ - - - /* start of middle stage process */ - - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - - /* Calculation of Middle stage */ - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the middle stage */ - n1 = n2; - n2 >>= 2u; - ic = 0u; - - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - C1 = pCoeff[ic]; - C2 = pCoeff[2u * ic]; - C3 = pCoeff[3u * ic]; - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Butterfly implementation */ - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T = pSrc[i0]; - - /* Read yc (real), xc(imag) input */ - S = pSrc[i2]; - - /* R = packed( (ya + yc), (xa + xc)) */ - R = __QADD16(T, S); - - /* S = packed((ya - yc), (xa - xc)) */ - S = __QSUB16(T, S); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T = pSrc[i1]; - - /* Read yd (real), xd(imag) input */ - U = pSrc[i3]; - - - /* T = packed( (yb + yd), (xb + xd)) */ - T = __QADD16(T, U); - - - /* writing the butterfly processed i0 sample */ - - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - out1 = __SHADD16(R, T); - in = ((int16_t) (out1 & 0xFFFF)) >> 1; - out1 = ((out1 >> 1) & 0xFFFF0000) | (in & 0xFFFF); - pSrc[i0] = out1; - - /* R = packed( (ya + yc) - (yb + yd), (xa + xc) - (xb + xd)) */ - R = __SHSUB16(R, T); - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ - out1 = __SMUAD(C2, R) >> 16u; - - /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out2 = __SMUSDX(C2, R); - -#else - - /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out1 = __SMUSDX(R, C2) >> 16u; - - /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ - out2 = __SMUAD(C2, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Reading i0+3fftLen/4 */ - /* Read yb (real), xb(imag) input */ - T = pSrc[i1]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - pSrc[i1] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly calculations */ - - /* Read yd (real), xd(imag) input */ - U = pSrc[i3]; - - /* T = packed(yb-yd, xb-xd) */ - T = __QSUB16(T, U); - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __SHASX(S, T); - - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __SHSAX(S, T); - - - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = __SMUAD(C1, S) >> 16u; - out2 = __SMUSDX(C1, S); - -#else - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __SHSAX(S, T); - - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __SHASX(S, T); - - - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = __SMUSDX(S, C1) >> 16u; - out2 = __SMUAD(C1, S); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - pSrc[i2] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly process for the i0+3fftLen/4 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUAD(C3, R) >> 16u; - out2 = __SMUSDX(C3, R); - -#else - - out1 = __SMUSDX(R, C3) >> 16u; - out2 = __SMUAD(C3, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ - /* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ - pSrc[i3] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - } - } - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - } - /* end of middle stage process */ - - - /* data is in 10.6(q6) format for the 1024 point */ - /* data is in 8.8(q8) format for the 256 point */ - /* data is in 6.10(q10) format for the 64 point */ - /* data is in 4.12(q12) format for the 16 point */ - - /* Initializations for the last stage */ - n1 = n2; - n2 >>= 2u; - - /* start of last stage process */ - - /* Butterfly implementation */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T = pSrc[i0]; - /* Read yc (real), xc(imag) input */ - S = pSrc[i2]; - - /* R = packed((ya + yc), (xa + xc)) */ - R = __QADD16(T, S); - /* S = packed((ya - yc), (xa - xc)) */ - S = __QSUB16(T, S); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T = pSrc[i1]; - /* Read yd (real), xd(imag) input */ - U = pSrc[i3]; - - /* T = packed((yb + yd), (xb + xd)) */ - T = __QADD16(T, U); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc[i0] = __SHADD16(R, T); - - /* R = packed((ya + yc) - (yb + yd), (xa + xc) - (xb + xd)) */ - R = __SHSUB16(R, T); - - /* Read yb (real), xb(imag) input */ - T = pSrc[i1]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd) */ - /* yc' = (ya-yb+yc-yd) */ - pSrc[i1] = R; - - /* Read yd (real), xd(imag) input */ - U = pSrc[i3]; - /* T = packed( (yb - yd), (xb - xd)) */ - T = __QSUB16(T, U); - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* writing the butterfly processed i0 + fftLen/2 sample */ - /* xb' = (xa+yb-xc-yd) */ - /* yb' = (ya-xb-yc+xd) */ - pSrc[i2] = __SHSAX(S, T); - - /* writing the butterfly processed i0 + 3fftLen/4 sample */ - /* xd' = (xa-yb-xc+yd) */ - /* yd' = (ya+xb-yc-xd) */ - pSrc[i3] = __SHASX(S, T); - -#else - - /* writing the butterfly processed i0 + fftLen/2 sample */ - /* xb' = (xa+yb-xc-yd) */ - /* yb' = (ya-xb-yc+xd) */ - pSrc[i2] = __SHASX(S, T); - - /* writing the butterfly processed i0 + 3fftLen/4 sample */ - /* xd' = (xa-yb-xc+yd) */ - /* yd' = (ya+xb-yc-xd) */ - pSrc[i3] = __SHSAX(S, T); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - } - - /* end of last stage process */ - - /* output is in 11.5(q5) format for the 1024 point */ - /* output is in 9.7(q7) format for the 256 point */ - /* output is in 7.9(q9) format for the 64 point */ - /* output is in 5.11(q11) format for the 16 point */ - - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t R0, R1, S0, S1, T0, T1, U0, U1; - q15_t Co1, Si1, Co2, Si2, Co3, Si3, out1, out2; - uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; - - /* Total process is divided into three stages */ - - /* process first stage, middle stages, & last stage */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - - /* Index for twiddle coefficient */ - ic = 0u; - - /* Index for input read and output write */ - i0 = 0u; - j = n2; - - /* Input is in 1.15(q15) format */ - - /* start of first stage process */ - do - { - /* Butterfly implementation */ - - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - - /* input is down scale by 4 to avoid overflow */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u] >> 2u; - T1 = pSrc16[(i0 * 2u) + 1u] >> 2u; - - /* input is down scale by 4 to avoid overflow */ - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u] >> 2u; - S1 = pSrc16[(i2 * 2u) + 1u] >> 2u; - - /* R0 = (ya + yc) */ - R0 = __SSAT(T0 + S0, 16u); - /* R1 = (xa + xc) */ - R1 = __SSAT(T1 + S1, 16u); - - /* S0 = (ya - yc) */ - S0 = __SSAT(T0 - S0, 16); - /* S1 = (xa - xc) */ - S1 = __SSAT(T1 - S1, 16); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* input is down scale by 4 to avoid overflow */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u] >> 2u; - T1 = pSrc16[(i1 * 2u) + 1u] >> 2u; - - /* input is down scale by 4 to avoid overflow */ - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u] >> 2u; - U1 = pSrc16[(i3 * 2u) + 1] >> 2u; - - /* T0 = (yb + yd) */ - T0 = __SSAT(T0 + U0, 16u); - /* T1 = (xb + xd) */ - T1 = __SSAT(T1 + U1, 16u); - - /* writing the butterfly processed i0 sample */ - /* ya' = ya + yb + yc + yd */ - /* xa' = xa + xb + xc + xd */ - pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); - pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); - - /* R0 = (ya + yc) - (yb + yd) */ - /* R1 = (xa + xc) - (xb + xd) */ - R0 = __SSAT(R0 - T0, 16u); - R1 = __SSAT(R1 - T1, 16u); - - /* co2 & si2 are read from Coefficient pointer */ - Co2 = pCoef16[2u * ic * 2u]; - Si2 = pCoef16[(2u * ic * 2u) + 1]; - - /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - out1 = (short) ((Co2 * R0 + Si2 * R1) >> 16u); - /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out2 = (short) ((-Si2 * R0 + Co2 * R1) >> 16u); - - /* Reading i0+fftLen/4 */ - /* input is down scale by 4 to avoid overflow */ - /* T0 = yb, T1 = xb */ - T0 = pSrc16[i1 * 2u] >> 2; - T1 = pSrc16[(i1 * 2u) + 1] >> 2; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* writing output(xc', yc') in little endian format */ - pSrc16[i1 * 2u] = out1; - pSrc16[(i1 * 2u) + 1] = out2; - - /* Butterfly calculations */ - /* input is down scale by 4 to avoid overflow */ - /* U0 = yd, U1 = xd */ - U0 = pSrc16[i3 * 2u] >> 2; - U1 = pSrc16[(i3 * 2u) + 1] >> 2; - /* T0 = yb-yd */ - T0 = __SSAT(T0 - U0, 16); - /* T1 = xb-xd */ - T1 = __SSAT(T1 - U1, 16); - - /* R1 = (ya-yc) + (xb- xd), R0 = (xa-xc) - (yb-yd)) */ - R0 = (short) __SSAT((q31_t) (S0 - T1), 16); - R1 = (short) __SSAT((q31_t) (S1 + T0), 16); - - /* S1 = (ya-yc) - (xb- xd), S0 = (xa-xc) + (yb-yd)) */ - S0 = (short) __SSAT(((q31_t) S0 + T1), 16u); - S1 = (short) __SSAT(((q31_t) S1 - T0), 16u); - - /* co1 & si1 are read from Coefficient pointer */ - Co1 = pCoef16[ic * 2u]; - Si1 = pCoef16[(ic * 2u) + 1]; - /* Butterfly process for the i0+fftLen/2 sample */ - /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - out1 = (short) ((Si1 * S1 + Co1 * S0) >> 16); - /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - out2 = (short) ((-Si1 * S0 + Co1 * S1) >> 16); - - /* writing output(xb', yb') in little endian format */ - pSrc16[i2 * 2u] = out1; - pSrc16[(i2 * 2u) + 1] = out2; - - /* Co3 & si3 are read from Coefficient pointer */ - Co3 = pCoef16[3u * (ic * 2u)]; - Si3 = pCoef16[(3u * (ic * 2u)) + 1]; - /* Butterfly process for the i0+3fftLen/4 sample */ - /* xd' = (xa-yb-xc+yd)* Co3 + (ya+xb-yc-xd)* (si3) */ - out1 = (short) ((Si3 * R1 + Co3 * R0) >> 16u); - /* yd' = (ya+xb-yc-xd)* Co3 - (xa-yb-xc+yd)* (si3) */ - out2 = (short) ((-Si3 * R0 + Co3 * R1) >> 16u); - /* writing output(xd', yd') in little endian format */ - pSrc16[i3 * 2u] = out1; - pSrc16[(i3 * 2u) + 1] = out2; - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - /* data is in 4.11(q11) format */ - - /* end of first stage process */ - - - /* start of middle stage process */ - - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - - /* Calculation of Middle stage */ - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the middle stage */ - n1 = n2; - n2 >>= 2u; - ic = 0u; - - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - Co1 = pCoef16[ic * 2u]; - Si1 = pCoef16[(ic * 2u) + 1u]; - Co2 = pCoef16[2u * (ic * 2u)]; - Si2 = pCoef16[(2u * (ic * 2u)) + 1u]; - Co3 = pCoef16[3u * (ic * 2u)]; - Si3 = pCoef16[(3u * (ic * 2u)) + 1u]; - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Butterfly implementation */ - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u]; - T1 = pSrc16[(i0 * 2u) + 1u]; - - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u]; - S1 = pSrc16[(i2 * 2u) + 1u]; - - /* R0 = (ya + yc), R1 = (xa + xc) */ - R0 = __SSAT(T0 + S0, 16); - R1 = __SSAT(T1 + S1, 16); - - /* S0 = (ya - yc), S1 =(xa - xc) */ - S0 = __SSAT(T0 - S0, 16); - S1 = __SSAT(T1 - S1, 16); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - - /* T0 = (yb + yd), T1 = (xb + xd) */ - T0 = __SSAT(T0 + U0, 16); - T1 = __SSAT(T1 + U1, 16); - - /* writing the butterfly processed i0 sample */ - - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - out1 = ((R0 >> 1u) + (T0 >> 1u)) >> 1u; - out2 = ((R1 >> 1u) + (T1 >> 1u)) >> 1u; - - pSrc16[i0 * 2u] = out1; - pSrc16[(2u * i0) + 1u] = out2; - - /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ - R0 = (R0 >> 1u) - (T0 >> 1u); - R1 = (R1 >> 1u) - (T1 >> 1u); - - /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ - out1 = (short) ((Co2 * R0 + Si2 * R1) >> 16u); - - /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out2 = (short) ((-Si2 * R0 + Co2 * R1) >> 16u); - - /* Reading i0+3fftLen/4 */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - pSrc16[i1 * 2u] = out1; - pSrc16[(i1 * 2u) + 1u] = out2; - - /* Butterfly calculations */ - - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - /* T0 = yb-yd, T1 = xb-xd */ - T0 = __SSAT(T0 - U0, 16); - T1 = __SSAT(T1 - U1, 16); - - /* R0 = (ya-yc) + (xb- xd), R1 = (xa-xc) - (yb-yd)) */ - R0 = (S0 >> 1u) - (T1 >> 1u); - R1 = (S1 >> 1u) + (T0 >> 1u); - - /* S0 = (ya-yc) - (xb- xd), S1 = (xa-xc) + (yb-yd)) */ - S0 = (S0 >> 1u) + (T1 >> 1u); - S1 = (S1 >> 1u) - (T0 >> 1u); - - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = (short) ((Co1 * S0 + Si1 * S1) >> 16u); - - out2 = (short) ((-Si1 * S0 + Co1 * S1) >> 16u); - - /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - pSrc16[i2 * 2u] = out1; - pSrc16[(i2 * 2u) + 1u] = out2; - - /* Butterfly process for the i0+3fftLen/4 sample */ - out1 = (short) ((Si3 * R1 + Co3 * R0) >> 16u); - - out2 = (short) ((-Si3 * R0 + Co3 * R1) >> 16u); - /* xd' = (xa-yb-xc+yd)* Co3 + (ya+xb-yc-xd)* (si3) */ - /* yd' = (ya+xb-yc-xd)* Co3 - (xa-yb-xc+yd)* (si3) */ - pSrc16[i3 * 2u] = out1; - pSrc16[(i3 * 2u) + 1u] = out2; - } - } - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - } - /* end of middle stage process */ - - - /* data is in 10.6(q6) format for the 1024 point */ - /* data is in 8.8(q8) format for the 256 point */ - /* data is in 6.10(q10) format for the 64 point */ - /* data is in 4.12(q12) format for the 16 point */ - - /* Initializations for the last stage */ - n1 = n2; - n2 >>= 2u; - - /* start of last stage process */ - - /* Butterfly implementation */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u]; - T1 = pSrc16[(i0 * 2u) + 1u]; - - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u]; - S1 = pSrc16[(i2 * 2u) + 1u]; - - /* R0 = (ya + yc), R1 = (xa + xc) */ - R0 = __SSAT(T0 + S0, 16u); - R1 = __SSAT(T1 + S1, 16u); - - /* S0 = (ya - yc), S1 = (xa - xc) */ - S0 = __SSAT(T0 - S0, 16u); - S1 = __SSAT(T1 - S1, 16u); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - /* T0 = (yb + yd), T1 = (xb + xd)) */ - T0 = __SSAT(T0 + U0, 16u); - T1 = __SSAT(T1 + U1, 16u); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); - pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); - - /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ - R0 = (R0 >> 1u) - (T0 >> 1u); - R1 = (R1 >> 1u) - (T1 >> 1u); - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd) */ - /* yc' = (ya-yb+yc-yd) */ - pSrc16[i1 * 2u] = R0; - pSrc16[(i1 * 2u) + 1u] = R1; - - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - /* T0 = (yb - yd), T1 = (xb - xd) */ - T0 = __SSAT(T0 - U0, 16u); - T1 = __SSAT(T1 - U1, 16u); - - /* writing the butterfly processed i0 + fftLen/2 sample */ - /* xb' = (xa+yb-xc-yd) */ - /* yb' = (ya-xb-yc+xd) */ - pSrc16[i2 * 2u] = (S0 >> 1u) + (T1 >> 1u); - pSrc16[(i2 * 2u) + 1u] = (S1 >> 1u) - (T0 >> 1u); - - /* writing the butterfly processed i0 + 3fftLen/4 sample */ - /* xd' = (xa-yb-xc+yd) */ - /* yd' = (ya+xb-yc-xd) */ - pSrc16[i3 * 2u] = (S0 >> 1u) - (T1 >> 1u); - pSrc16[(i3 * 2u) + 1u] = (S1 >> 1u) + (T0 >> 1u); - - } - - /* end of last stage process */ - - /* output is in 11.5(q5) format for the 1024 point */ - /* output is in 9.7(q7) format for the 256 point */ - /* output is in 7.9(q9) format for the 64 point */ - /* output is in 5.11(q11) format for the 16 point */ - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - -/** - * @brief Core function for the Q15 CIFFT butterfly process. - * @param[in, out] *pSrc16 points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef16 points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -/* -* Radix-4 IFFT algorithm used is : -* -* CIFFT uses same twiddle coefficients as CFFT function -* x[k] = x[n] + (j)k * x[n + fftLen/4] + (-1)k * x[n+fftLen/2] + (-j)k * x[n+3*fftLen/4] -* -* -* IFFT is implemented with following changes in equations from FFT -* -* Input real and imaginary data: -* x(n) = xa + j * ya -* x(n+N/4 ) = xb + j * yb -* x(n+N/2 ) = xc + j * yc -* x(n+3N 4) = xd + j * yd -* -* -* Output real and imaginary data: -* x(4r) = xa'+ j * ya' -* x(4r+1) = xb'+ j * yb' -* x(4r+2) = xc'+ j * yc' -* x(4r+3) = xd'+ j * yd' -* -* -* Twiddle factors for radix-4 IFFT: -* Wn = co1 + j * (si1) -* W2n = co2 + j * (si2) -* W3n = co3 + j * (si3) - -* The real and imaginary output values for the radix-4 butterfly are -* xa' = xa + xb + xc + xd -* ya' = ya + yb + yc + yd -* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) -* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) -* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) -* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) -* xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) -* yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) -* -*/ - -void arm_radix4_butterfly_inverse_q15( - q15_t * pSrc16, - uint32_t fftLen, - q15_t * pCoef16, - uint32_t twidCoefModifier) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t R, S, T, U; - q31_t C1, C2, C3, out1, out2; - q31_t *pSrc, *pCoeff; - uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; - q15_t in; - - /* Total process is divided into three stages */ - - /* process first stage, middle stages, & last stage */ - - /* pointer initializations for SIMD calculations */ - pSrc = (q31_t *) pSrc16; - pCoeff = (q31_t *) pCoef16; - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - - /* Index for twiddle coefficient */ - ic = 0u; - - /* Index for input read and output write */ - i0 = 0u; - - j = n2; - - /* Input is in 1.15(q15) format */ - - /* Start of first stage process */ - do - { - /* Butterfly implementation */ - - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T = pSrc[i0]; - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - /* Read yc (real), xc(imag) input */ - S = pSrc[i2]; - in = ((int16_t) (S & 0xFFFF)) >> 2; - S = ((S >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* R = packed((ya + yc), (xa + xc) ) */ - R = __QADD16(T, S); - /* S = packed((ya - yc), (xa - xc) ) */ - S = __QSUB16(T, S); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T = pSrc[i1]; - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - /* Read yd (real), xd(imag) input */ - U = pSrc[i3]; - in = ((int16_t) (U & 0xFFFF)) >> 2; - U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* T = packed((yb + yd), (xb + xd) ) */ - T = __QADD16(T, U); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc[i0] = __SHADD16(R, T); - - /* R = packed((ya + yc) - (yb + yd), (xa + xc)- (xb + xd)) */ - R = __QSUB16(R, T); - /* co2 & si2 are read from SIMD Coefficient pointer */ - C2 = pCoeff[2u * ic]; - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ - out1 = __SMUSD(C2, R) >> 16u; - /* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - out2 = __SMUADX(C2, R); - -#else - - /* xc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - out1 = __SMUADX(C2, R) >> 16u; - /* yc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ - out2 = __SMUSD(-C2, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Reading i0+fftLen/4 */ - /* T = packed(yb, xb) */ - T = pSrc[i1]; - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* writing output(xc', yc') in little endian format */ - pSrc[i1] = (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly calculations */ - /* U = packed(yd, xd) */ - U = pSrc[i3]; - in = ((int16_t) (U & 0xFFFF)) >> 2; - U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* T = packed(yb-yd, xb-xd) */ - T = __QSUB16(T, U); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* R = packed((ya-yc) - (xb- xd) , (xa-xc) + (yb-yd)) */ - R = __QSAX(S, T); - /* S = packed((ya-yc) + (xb- xd), (xa-xc) - (yb-yd)) */ - S = __QASX(S, T); - -#else - - /* R = packed((ya-yc) - (xb- xd) , (xa-xc) + (yb-yd)) */ - R = __QASX(S, T); - /* S = packed((ya-yc) + (xb- xd), (xa-xc) - (yb-yd)) */ - S = __QSAX(S, T); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* co1 & si1 are read from SIMD Coefficient pointer */ - C1 = pCoeff[ic]; - /* Butterfly process for the i0+fftLen/2 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ - out1 = __SMUSD(C1, S) >> 16u; - /* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ - out2 = __SMUADX(C1, S); - -#else - - /* xb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ - out1 = __SMUADX(C1, S) >> 16u; - /* yb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ - out2 = __SMUSD(-C1, S); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* writing output(xb', yb') in little endian format */ - pSrc[i2] = ((out2) & 0xFFFF0000) | ((out1) & 0x0000FFFF); - - /* co3 & si3 are read from SIMD Coefficient pointer */ - C3 = pCoeff[3u * ic]; - /* Butterfly process for the i0+3fftLen/4 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) */ - out1 = __SMUSD(C3, R) >> 16u; - /* yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) */ - out2 = __SMUADX(C3, R); - -#else - - /* xd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) */ - out1 = __SMUADX(C3, R) >> 16u; - /* yd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) */ - out2 = __SMUSD(-C3, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* writing output(xd', yd') in little endian format */ - pSrc[i3] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - - /* End of first stage process */ - - /* data is in 4.11(q11) format */ - - - /* Start of Middle stage process */ - - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - - /* Calculation of Middle stage */ - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the middle stage */ - n1 = n2; - n2 >>= 2u; - ic = 0u; - - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - C1 = pCoeff[ic]; - C2 = pCoeff[2u * ic]; - C3 = pCoeff[3u * ic]; - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Butterfly implementation */ - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T = pSrc[i0]; - - /* Read yc (real), xc(imag) input */ - S = pSrc[i2]; - - - /* R = packed( (ya + yc), (xa + xc)) */ - R = __QADD16(T, S); - /* S = packed((ya - yc), (xa - xc)) */ - S = __QSUB16(T, S); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T = pSrc[i1]; - - /* Read yd (real), xd(imag) input */ - U = pSrc[i3]; - - - /* T = packed( (yb + yd), (xb + xd)) */ - T = __QADD16(T, U); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - out1 = __SHADD16(R, T); - in = ((int16_t) (out1 & 0xFFFF)) >> 1; - out1 = ((out1 >> 1) & 0xFFFF0000) | (in & 0xFFFF); - pSrc[i0] = out1; - - - - /* R = packed( (ya + yc) - (yb + yd), (xa + xc) - (xb + xd)) */ - R = __SHSUB16(R, T); - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* (ya-yb+yc-yd)* (si2) - (xa-xb+xc-xd)* co2 */ - out1 = __SMUSD(C2, R) >> 16u; - /* (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - out2 = __SMUADX(C2, R); - -#else - - /* (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - out1 = __SMUADX(R, C2) >> 16u; - /* (ya-yb+yc-yd)* (si2) - (xa-xb+xc-xd)* co2 */ - out2 = __SMUSD(-C2, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Reading i0+3fftLen/4 */ - /* Read yb (real), xb(imag) input */ - T = pSrc[i1]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ - /* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - pSrc[i1] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly calculations */ - /* Read yd (real), xd(imag) input */ - U = pSrc[i3]; - - /* T = packed(yb-yd, xb-xd) */ - T = __QSUB16(T, U); - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* R = packed((ya-yc) - (xb- xd) , (xa-xc) + (yb-yd)) */ - R = __SHSAX(S, T); - - /* S = packed((ya-yc) + (xb- xd), (xa-xc) - (yb-yd)) */ - S = __SHASX(S, T); - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = __SMUSD(C1, S) >> 16u; - out2 = __SMUADX(C1, S); - -#else - - /* R = packed((ya-yc) - (xb- xd) , (xa-xc) + (yb-yd)) */ - R = __SHASX(S, T); - - /* S = packed((ya-yc) + (xb- xd), (xa-xc) - (yb-yd)) */ - S = __SHSAX(S, T); - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = __SMUADX(S, C1) >> 16u; - out2 = __SMUSD(-C1, S); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ - /* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ - pSrc[i2] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly process for the i0+3fftLen/4 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUSD(C3, R) >> 16u; - out2 = __SMUADX(C3, R); - -#else - - out1 = __SMUADX(C3, R) >> 16u; - out2 = __SMUSD(-C3, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) */ - /* yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) */ - pSrc[i3] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - - } - } - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - } - /* End of Middle stages process */ - - - /* data is in 10.6(q6) format for the 1024 point */ - /* data is in 8.8(q8) format for the 256 point */ - /* data is in 6.10(q10) format for the 64 point */ - /* data is in 4.12(q12) format for the 16 point */ - - /* start of last stage process */ - - - /* Initializations for the last stage */ - n1 = n2; - n2 >>= 2u; - - /* Butterfly implementation */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T = pSrc[i0]; - /* Read yc (real), xc(imag) input */ - S = pSrc[i2]; - - /* R = packed((ya + yc), (xa + xc)) */ - R = __QADD16(T, S); - /* S = packed((ya - yc), (xa - xc)) */ - S = __QSUB16(T, S); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T = pSrc[i1]; - /* Read yd (real), xd(imag) input */ - U = pSrc[i3]; - - /* T = packed((yb + yd), (xb + xd)) */ - T = __QADD16(T, U); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc[i0] = __SHADD16(R, T); - - /* R = packed((ya + yc) - (yb + yd), (xa + xc) - (xb + xd)) */ - R = __SHSUB16(R, T); - - /* Read yb (real), xb(imag) input */ - T = pSrc[i1]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd) */ - /* yc' = (ya-yb+yc-yd) */ - pSrc[i1] = R; - - /* Read yd (real), xd(imag) input */ - U = pSrc[i3]; - /* T = packed( (yb - yd), (xb - xd)) */ - T = __QSUB16(T, U); - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* writing the butterfly processed i0 + fftLen/2 sample */ - /* xb' = (xa-yb-xc+yd) */ - /* yb' = (ya+xb-yc-xd) */ - pSrc[i2] = __SHASX(S, T); - - /* writing the butterfly processed i0 + 3fftLen/4 sample */ - /* xd' = (xa+yb-xc-yd) */ - /* yd' = (ya-xb-yc+xd) */ - pSrc[i3] = __SHSAX(S, T); - - -#else - - /* writing the butterfly processed i0 + fftLen/2 sample */ - /* xb' = (xa-yb-xc+yd) */ - /* yb' = (ya+xb-yc-xd) */ - pSrc[i2] = __SHSAX(S, T); - - /* writing the butterfly processed i0 + 3fftLen/4 sample */ - /* xd' = (xa+yb-xc-yd) */ - /* yd' = (ya-xb-yc+xd) */ - pSrc[i3] = __SHASX(S, T); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - } - /* end of last stage process */ - - /* output is in 11.5(q5) format for the 1024 point */ - /* output is in 9.7(q7) format for the 256 point */ - /* output is in 7.9(q9) format for the 64 point */ - /* output is in 5.11(q11) format for the 16 point */ - - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t R0, R1, S0, S1, T0, T1, U0, U1; - q15_t Co1, Si1, Co2, Si2, Co3, Si3, out1, out2; - uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; - - /* Total process is divided into three stages */ - - /* process first stage, middle stages, & last stage */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - - /* Index for twiddle coefficient */ - ic = 0u; - - /* Index for input read and output write */ - i0 = 0u; - - j = n2; - - /* Input is in 1.15(q15) format */ - - /* Start of first stage process */ - do - { - /* Butterfly implementation */ - - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* input is down scale by 4 to avoid overflow */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u] >> 2u; - T1 = pSrc16[(i0 * 2u) + 1u] >> 2u; - /* input is down scale by 4 to avoid overflow */ - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u] >> 2u; - S1 = pSrc16[(i2 * 2u) + 1u] >> 2u; - - /* R0 = (ya + yc), R1 = (xa + xc) */ - R0 = __SSAT(T0 + S0, 16u); - R1 = __SSAT(T1 + S1, 16u); - /* S0 = (ya - yc), S1 = (xa - xc) */ - S0 = __SSAT(T0 - S0, 16u); - S1 = __SSAT(T1 - S1, 16u); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* input is down scale by 4 to avoid overflow */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u] >> 2u; - T1 = pSrc16[(i1 * 2u) + 1u] >> 2u; - /* Read yd (real), xd(imag) input */ - /* input is down scale by 4 to avoid overflow */ - U0 = pSrc16[i3 * 2u] >> 2u; - U1 = pSrc16[(i3 * 2u) + 1u] >> 2u; - - /* T0 = (yb + yd), T1 = (xb + xd) */ - T0 = __SSAT(T0 + U0, 16u); - T1 = __SSAT(T1 + U1, 16u); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); - pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); - - /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc)- (xb + xd) */ - R0 = __SSAT(R0 - T0, 16u); - R1 = __SSAT(R1 - T1, 16u); - /* co2 & si2 are read from Coefficient pointer */ - Co2 = pCoef16[2u * ic * 2u]; - Si2 = pCoef16[(2u * ic * 2u) + 1u]; - /* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ - out1 = (short) ((Co2 * R0 - Si2 * R1) >> 16u); - /* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - out2 = (short) ((Si2 * R0 + Co2 * R1) >> 16u); - - /* Reading i0+fftLen/4 */ - /* input is down scale by 4 to avoid overflow */ - /* T0 = yb, T1 = xb */ - T0 = pSrc16[i1 * 2u] >> 2u; - T1 = pSrc16[(i1 * 2u) + 1u] >> 2u; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* writing output(xc', yc') in little endian format */ - pSrc16[i1 * 2u] = out1; - pSrc16[(i1 * 2u) + 1u] = out2; - - /* Butterfly calculations */ - /* input is down scale by 4 to avoid overflow */ - /* U0 = yd, U1 = xd) */ - U0 = pSrc16[i3 * 2u] >> 2u; - U1 = pSrc16[(i3 * 2u) + 1u] >> 2u; - - /* T0 = yb-yd, T1 = xb-xd) */ - T0 = __SSAT(T0 - U0, 16u); - T1 = __SSAT(T1 - U1, 16u); - /* R0 = (ya-yc) - (xb- xd) , R1 = (xa-xc) + (yb-yd) */ - R0 = (short) __SSAT((q31_t) (S0 + T1), 16); - R1 = (short) __SSAT((q31_t) (S1 - T0), 16); - /* S = (ya-yc) + (xb- xd), S1 = (xa-xc) - (yb-yd) */ - S0 = (short) __SSAT((q31_t) (S0 - T1), 16); - S1 = (short) __SSAT((q31_t) (S1 + T0), 16); - - /* co1 & si1 are read from Coefficient pointer */ - Co1 = pCoef16[ic * 2u]; - Si1 = pCoef16[(ic * 2u) + 1u]; - /* Butterfly process for the i0+fftLen/2 sample */ - /* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ - out1 = (short) ((Co1 * S0 - Si1 * S1) >> 16u); - /* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ - out2 = (short) ((Si1 * S0 + Co1 * S1) >> 16u); - /* writing output(xb', yb') in little endian format */ - pSrc16[i2 * 2u] = out1; - pSrc16[(i2 * 2u) + 1u] = out2; - - /* Co3 & si3 are read from Coefficient pointer */ - Co3 = pCoef16[3u * ic * 2u]; - Si3 = pCoef16[(3u * ic * 2u) + 1u]; - /* Butterfly process for the i0+3fftLen/4 sample */ - /* xd' = (xa+yb-xc-yd)* Co3 - (ya-xb-yc+xd)* (si3) */ - out1 = (short) ((Co3 * R0 - Si3 * R1) >> 16u); - /* yd' = (ya-xb-yc+xd)* Co3 + (xa+yb-xc-yd)* (si3) */ - out2 = (short) ((Si3 * R0 + Co3 * R1) >> 16u); - /* writing output(xd', yd') in little endian format */ - pSrc16[i3 * 2u] = out1; - pSrc16[(i3 * 2u) + 1u] = out2; - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - - /* End of first stage process */ - - /* data is in 4.11(q11) format */ - - - /* Start of Middle stage process */ - - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - - /* Calculation of Middle stage */ - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the middle stage */ - n1 = n2; - n2 >>= 2u; - ic = 0u; - - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - Co1 = pCoef16[ic * 2u]; - Si1 = pCoef16[(ic * 2u) + 1u]; - Co2 = pCoef16[2u * ic * 2u]; - Si2 = pCoef16[2u * ic * 2u + 1u]; - Co3 = pCoef16[3u * ic * 2u]; - Si3 = pCoef16[(3u * ic * 2u) + 1u]; - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Butterfly implementation */ - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u]; - T1 = pSrc16[(i0 * 2u) + 1u]; - - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u]; - S1 = pSrc16[(i2 * 2u) + 1u]; - - - /* R0 = (ya + yc), R1 = (xa + xc) */ - R0 = __SSAT(T0 + S0, 16u); - R1 = __SSAT(T1 + S1, 16u); - /* S0 = (ya - yc), S1 = (xa - xc) */ - S0 = __SSAT(T0 - S0, 16u); - S1 = __SSAT(T1 - S1, 16u); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - /* T0 = (yb + yd), T1 = (xb + xd) */ - T0 = __SSAT(T0 + U0, 16u); - T1 = __SSAT(T1 + U1, 16u); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc16[i0 * 2u] = ((R0 >> 1u) + (T0 >> 1u)) >> 1u; - pSrc16[(i0 * 2u) + 1u] = ((R1 >> 1u) + (T1 >> 1u)) >> 1u; - - /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ - R0 = (R0 >> 1u) - (T0 >> 1u); - R1 = (R1 >> 1u) - (T1 >> 1u); - - /* (ya-yb+yc-yd)* (si2) - (xa-xb+xc-xd)* co2 */ - out1 = (short) ((Co2 * R0 - Si2 * R1) >> 16); - /* (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - out2 = (short) ((Si2 * R0 + Co2 * R1) >> 16); - - /* Reading i0+3fftLen/4 */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ - /* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - pSrc16[i1 * 2u] = out1; - pSrc16[(i1 * 2u) + 1u] = out2; - - /* Butterfly calculations */ - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - /* T0 = yb-yd, T1 = xb-xd) */ - T0 = __SSAT(T0 - U0, 16u); - T1 = __SSAT(T1 - U1, 16u); - - /* R0 = (ya-yc) - (xb- xd) , R1 = (xa-xc) + (yb-yd) */ - R0 = (S0 >> 1u) + (T1 >> 1u); - R1 = (S1 >> 1u) - (T0 >> 1u); - - /* S1 = (ya-yc) + (xb- xd), S1 = (xa-xc) - (yb-yd) */ - S0 = (S0 >> 1u) - (T1 >> 1u); - S1 = (S1 >> 1u) + (T0 >> 1u); - - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = (short) ((Co1 * S0 - Si1 * S1) >> 16u); - out2 = (short) ((Si1 * S0 + Co1 * S1) >> 16u); - /* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ - /* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ - pSrc16[i2 * 2u] = out1; - pSrc16[(i2 * 2u) + 1u] = out2; - - /* Butterfly process for the i0+3fftLen/4 sample */ - out1 = (short) ((Co3 * R0 - Si3 * R1) >> 16u); - - out2 = (short) ((Si3 * R0 + Co3 * R1) >> 16u); - /* xd' = (xa+yb-xc-yd)* Co3 - (ya-xb-yc+xd)* (si3) */ - /* yd' = (ya-xb-yc+xd)* Co3 + (xa+yb-xc-yd)* (si3) */ - pSrc16[i3 * 2u] = out1; - pSrc16[(i3 * 2u) + 1u] = out2; - - - } - } - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - } - /* End of Middle stages process */ - - - /* data is in 10.6(q6) format for the 1024 point */ - /* data is in 8.8(q8) format for the 256 point */ - /* data is in 6.10(q10) format for the 64 point */ - /* data is in 4.12(q12) format for the 16 point */ - - /* start of last stage process */ - - - /* Initializations for the last stage */ - n1 = n2; - n2 >>= 2u; - - /* Butterfly implementation */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u]; - T1 = pSrc16[(i0 * 2u) + 1u]; - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u]; - S1 = pSrc16[(i2 * 2u) + 1u]; - - /* R0 = (ya + yc), R1 = (xa + xc) */ - R0 = __SSAT(T0 + S0, 16u); - R1 = __SSAT(T1 + S1, 16u); - /* S0 = (ya - yc), S1 = (xa - xc) */ - S0 = __SSAT(T0 - S0, 16u); - S1 = __SSAT(T1 - S1, 16u); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - /* T0 = (yb + yd), T1 = (xb + xd) */ - T0 = __SSAT(T0 + U0, 16u); - T1 = __SSAT(T1 + U1, 16u); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); - pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); - - /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ - R0 = (R0 >> 1u) - (T0 >> 1u); - R1 = (R1 >> 1u) - (T1 >> 1u); - - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd) */ - /* yc' = (ya-yb+yc-yd) */ - pSrc16[i1 * 2u] = R0; - pSrc16[(i1 * 2u) + 1u] = R1; - - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - /* T0 = (yb - yd), T1 = (xb - xd) */ - T0 = __SSAT(T0 - U0, 16u); - T1 = __SSAT(T1 - U1, 16u); - - /* writing the butterfly processed i0 + fftLen/2 sample */ - /* xb' = (xa-yb-xc+yd) */ - /* yb' = (ya+xb-yc-xd) */ - pSrc16[i2 * 2u] = (S0 >> 1u) - (T1 >> 1u); - pSrc16[(i2 * 2u) + 1u] = (S1 >> 1u) + (T0 >> 1u); - - - /* writing the butterfly processed i0 + 3fftLen/4 sample */ - /* xd' = (xa+yb-xc-yd) */ - /* yd' = (ya-xb-yc+xd) */ - pSrc16[i3 * 2u] = (S0 >> 1u) + (T1 >> 1u); - pSrc16[(i3 * 2u) + 1u] = (S1 >> 1u) - (T0 >> 1u); - } - /* end of last stage process */ - - /* output is in 11.5(q5) format for the 1024 point */ - /* output is in 9.7(q7) format for the 256 point */ - /* output is in 7.9(q9) format for the 64 point */ - /* output is in 5.11(q11) format for the 16 point */ - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - -/* - * @brief In-place bit reversal function. - * @param[in, out] *pSrc points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table - * @param[in] *pBitRevTab points to bit reversal table. - * @return none. - */ - -void arm_bitreversal_q15( - q15_t * pSrc16, - uint32_t fftLen, - uint16_t bitRevFactor, - uint16_t * pBitRevTab) -{ - q31_t *pSrc = (q31_t *) pSrc16; - q31_t in; - uint32_t fftLenBy2, fftLenBy2p1; - uint32_t i, j; - - /* Initializations */ - j = 0u; - fftLenBy2 = fftLen / 2u; - fftLenBy2p1 = (fftLen / 2u) + 1u; - - /* Bit Reversal Implementation */ - for (i = 0u; i <= (fftLenBy2 - 2u); i += 2u) - { - if(i < j) - { - /* pSrc[i] <-> pSrc[j]; */ - /* pSrc[i+1u] <-> pSrc[j+1u] */ - in = pSrc[i]; - pSrc[i] = pSrc[j]; - pSrc[j] = in; - - /* pSrc[i + fftLenBy2p1] <-> pSrc[j + fftLenBy2p1]; */ - /* pSrc[i + fftLenBy2p1+1u] <-> pSrc[j + fftLenBy2p1+1u] */ - in = pSrc[i + fftLenBy2p1]; - pSrc[i + fftLenBy2p1] = pSrc[j + fftLenBy2p1]; - pSrc[j + fftLenBy2p1] = in; - } - - /* pSrc[i+1u] <-> pSrc[j+fftLenBy2]; */ - /* pSrc[i+2] <-> pSrc[j+fftLenBy2+1u] */ - in = pSrc[i + 1u]; - pSrc[i + 1u] = pSrc[j + fftLenBy2]; - pSrc[j + fftLenBy2] = in; - - /* Reading the index for the bit reversal */ - j = *pBitRevTab; - - /* Updating the bit reversal index depending on the fft length */ - pBitRevTab += bitRevFactor; - } -} +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_cfft_radix4_q15.c +* +* Description: This file has function definition of Radix-4 FFT & IFFT function and +* In-place bit reversal using bit reversal table +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup CFFT_CIFFT + * @{ + */ + + +/** + * @details + * @brief Processing function for the Q15 CFFT/CIFFT. + * @param[in] *S points to an instance of the Q15 CFFT/CIFFT structure. + * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. + * @return none. + * + * \par Input and output formats: + * \par + * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. + * Hence the output format is different for different FFT sizes. + * The input and output formats for different FFT sizes and number of bits to upscale are mentioned in the tables below for CFFT and CIFFT: + * \par + * \image html CFFTQ15.gif "Input and Output Formats for Q15 CFFT" + * \image html CIFFTQ15.gif "Input and Output Formats for Q15 CIFFT" + */ + +void arm_cfft_radix4_q15( + const arm_cfft_radix4_instance_q15 * S, + q15_t * pSrc) +{ + if(S->ifftFlag == 1u) + { + /* Complex IFFT radix-4 */ + arm_radix4_butterfly_inverse_q15(pSrc, S->fftLen, S->pTwiddle, + S->twidCoefModifier); + } + else + { + /* Complex FFT radix-4 */ + arm_radix4_butterfly_q15(pSrc, S->fftLen, S->pTwiddle, + S->twidCoefModifier); + } + + if(S->bitReverseFlag == 1u) + { + /* Bit Reversal */ + arm_bitreversal_q15(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); + } + +} + +/** + * @} end of CFFT_CIFFT group + */ + +/* +* Radix-4 FFT algorithm used is : +* +* Input real and imaginary data: +* x(n) = xa + j * ya +* x(n+N/4 ) = xb + j * yb +* x(n+N/2 ) = xc + j * yc +* x(n+3N 4) = xd + j * yd +* +* +* Output real and imaginary data: +* x(4r) = xa'+ j * ya' +* x(4r+1) = xb'+ j * yb' +* x(4r+2) = xc'+ j * yc' +* x(4r+3) = xd'+ j * yd' +* +* +* Twiddle factors for radix-4 FFT: +* Wn = co1 + j * (- si1) +* W2n = co2 + j * (- si2) +* W3n = co3 + j * (- si3) + +* The real and imaginary output values for the radix-4 butterfly are +* xa' = xa + xb + xc + xd +* ya' = ya + yb + yc + yd +* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) +* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) +* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) +* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) +* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) +* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) +* +*/ + +/** + * @brief Core function for the Q15 CFFT butterfly process. + * @param[in, out] *pSrc16 points to the in-place buffer of Q15 data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef16 points to twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + +void arm_radix4_butterfly_q15( + q15_t * pSrc16, + uint32_t fftLen, + q15_t * pCoef16, + uint32_t twidCoefModifier) +{ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t R, S, T, U; + q31_t C1, C2, C3, out1, out2; + q31_t *pSrc, *pCoeff; + uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; + q15_t in; + + /* Total process is divided into three stages */ + + /* process first stage, middle stages, & last stage */ + + /* pointer initializations for SIMD calculations */ + pSrc = (q31_t *) pSrc16; + pCoeff = (q31_t *) pCoef16; + + /* Initializations for the first stage */ + n2 = fftLen; + n1 = n2; + + /* n2 = fftLen/4 */ + n2 >>= 2u; + + /* Index for twiddle coefficient */ + ic = 0u; + + /* Index for input read and output write */ + i0 = 0u; + j = n2; + + /* Input is in 1.15(q15) format */ + + /* start of first stage process */ + do + { + /* Butterfly implementation */ + + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* Read ya (real), xa(imag) input */ + T = pSrc[i0]; + in = ((int16_t) (T & 0xFFFF)) >> 2; + T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); + /* Read yc (real), xc(imag) input */ + S = pSrc[i2]; + in = ((int16_t) (S & 0xFFFF)) >> 2; + S = ((S >> 2) & 0xFFFF0000) | (in & 0xFFFF); + /* R = packed((ya + yc), (xa + xc) ) */ + R = __QADD16(T, S); + /* S = packed((ya - yc), (xa - xc) ) */ + S = __QSUB16(T, S); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* Read yb (real), xb(imag) input */ + T = pSrc[i1]; + in = ((int16_t) (T & 0xFFFF)) >> 2; + T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); + /* Read yd (real), xd(imag) input */ + U = pSrc[i3]; + in = ((int16_t) (U & 0xFFFF)) >> 2; + U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); + /* T = packed((yb + yd), (xb + xd) ) */ + T = __QADD16(T, U); + + /* writing the butterfly processed i0 sample */ + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + pSrc[i0] = __SHADD16(R, T); + + /* R = packed((ya + yc) - (yb + yd), (xa + xc)- (xb + xd)) */ + R = __QSUB16(R, T); + + /* co2 & si2 are read from SIMD Coefficient pointer */ + C2 = pCoeff[2u * ic]; + + +#ifndef ARM_MATH_BIG_ENDIAN + + /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ + out1 = __SMUAD(C2, R) >> 16u; + /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ + out2 = __SMUSDX(C2, R); + +#else + + /* xc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ + out1 = __SMUSDX(R, C2) >> 16u; + /* yc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ + out2 = __SMUAD(C2, R); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Reading i0+fftLen/4 */ + /* T = packed(yb, xb) */ + T = pSrc[i1]; + in = ((int16_t) (T & 0xFFFF)) >> 2; + T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* writing output(xc', yc') in little endian format */ + pSrc[i1] = (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); + + /* Butterfly calculations */ + /* U = packed(yd, xd) */ + U = pSrc[i3]; + in = ((int16_t) (U & 0xFFFF)) >> 2; + U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); + /* T = packed(yb-yd, xb-xd) */ + T = __QSUB16(T, U); + + +#ifndef ARM_MATH_BIG_ENDIAN + + /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ + R = __QASX(S, T); + /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ + S = __QSAX(S, T); + +#else + + /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ + R = __QSAX(S, T); + /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ + S = __QASX(S, T); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* co1 & si1 are read from SIMD Coefficient pointer */ + C1 = pCoeff[ic]; + /* Butterfly process for the i0+fftLen/2 sample */ + +#ifndef ARM_MATH_BIG_ENDIAN + + /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ + out1 = __SMUAD(C1, S) >> 16u; + /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ + out2 = __SMUSDX(C1, S); + +#else + + /* xb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ + out1 = __SMUSDX(S, C1) >> 16u; + /* yb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ + out2 = __SMUAD(C1, S); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* writing output(xb', yb') in little endian format */ + pSrc[i2] = ((out2) & 0xFFFF0000) | ((out1) & 0x0000FFFF); + + + /* co3 & si3 are read from SIMD Coefficient pointer */ + C3 = pCoeff[3u * ic]; + /* Butterfly process for the i0+3fftLen/4 sample */ + +#ifndef ARM_MATH_BIG_ENDIAN + + /* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ + out1 = __SMUAD(C3, R) >> 16u; + /* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ + out2 = __SMUSDX(C3, R); + +#else + + /* xd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ + out1 = __SMUSDX(R, C3) >> 16u; + /* yd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ + out2 = __SMUAD(C3, R); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* writing output(xd', yd') in little endian format */ + pSrc[i3] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); + + /* Twiddle coefficients index modifier */ + ic = ic + twidCoefModifier; + + /* Updating input index */ + i0 = i0 + 1u; + + } while(--j); + /* data is in 4.11(q11) format */ + + /* end of first stage process */ + + + /* start of middle stage process */ + + /* Twiddle coefficients index modifier */ + twidCoefModifier <<= 2u; + + /* Calculation of Middle stage */ + for (k = fftLen / 4u; k > 4u; k >>= 2u) + { + /* Initializations for the middle stage */ + n1 = n2; + n2 >>= 2u; + ic = 0u; + + for (j = 0u; j <= (n2 - 1u); j++) + { + /* index calculation for the coefficients */ + C1 = pCoeff[ic]; + C2 = pCoeff[2u * ic]; + C3 = pCoeff[3u * ic]; + + /* Twiddle coefficients index modifier */ + ic = ic + twidCoefModifier; + + /* Butterfly implementation */ + for (i0 = j; i0 < fftLen; i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* Read ya (real), xa(imag) input */ + T = pSrc[i0]; + + /* Read yc (real), xc(imag) input */ + S = pSrc[i2]; + + /* R = packed( (ya + yc), (xa + xc)) */ + R = __QADD16(T, S); + + /* S = packed((ya - yc), (xa - xc)) */ + S = __QSUB16(T, S); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* Read yb (real), xb(imag) input */ + T = pSrc[i1]; + + /* Read yd (real), xd(imag) input */ + U = pSrc[i3]; + + + /* T = packed( (yb + yd), (xb + xd)) */ + T = __QADD16(T, U); + + + /* writing the butterfly processed i0 sample */ + + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + out1 = __SHADD16(R, T); + in = ((int16_t) (out1 & 0xFFFF)) >> 1; + out1 = ((out1 >> 1) & 0xFFFF0000) | (in & 0xFFFF); + pSrc[i0] = out1; + + /* R = packed( (ya + yc) - (yb + yd), (xa + xc) - (xb + xd)) */ + R = __SHSUB16(R, T); + + +#ifndef ARM_MATH_BIG_ENDIAN + + /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ + out1 = __SMUAD(C2, R) >> 16u; + + /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ + out2 = __SMUSDX(C2, R); + +#else + + /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ + out1 = __SMUSDX(R, C2) >> 16u; + + /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ + out2 = __SMUAD(C2, R); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Reading i0+3fftLen/4 */ + /* Read yb (real), xb(imag) input */ + T = pSrc[i1]; + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ + /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ + pSrc[i1] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); + + /* Butterfly calculations */ + + /* Read yd (real), xd(imag) input */ + U = pSrc[i3]; + + /* T = packed(yb-yd, xb-xd) */ + T = __QSUB16(T, U); + + +#ifndef ARM_MATH_BIG_ENDIAN + + /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ + R = __SHASX(S, T); + + /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ + S = __SHSAX(S, T); + + + /* Butterfly process for the i0+fftLen/2 sample */ + out1 = __SMUAD(C1, S) >> 16u; + out2 = __SMUSDX(C1, S); + +#else + + /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ + R = __SHSAX(S, T); + + /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ + S = __SHASX(S, T); + + + /* Butterfly process for the i0+fftLen/2 sample */ + out1 = __SMUSDX(S, C1) >> 16u; + out2 = __SMUAD(C1, S); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ + /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ + pSrc[i2] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); + + /* Butterfly process for the i0+3fftLen/4 sample */ + +#ifndef ARM_MATH_BIG_ENDIAN + + out1 = __SMUAD(C3, R) >> 16u; + out2 = __SMUSDX(C3, R); + +#else + + out1 = __SMUSDX(R, C3) >> 16u; + out2 = __SMUAD(C3, R); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ + /* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ + pSrc[i3] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); + } + } + /* Twiddle coefficients index modifier */ + twidCoefModifier <<= 2u; + } + /* end of middle stage process */ + + + /* data is in 10.6(q6) format for the 1024 point */ + /* data is in 8.8(q8) format for the 256 point */ + /* data is in 6.10(q10) format for the 64 point */ + /* data is in 4.12(q12) format for the 16 point */ + + /* Initializations for the last stage */ + n1 = n2; + n2 >>= 2u; + + /* start of last stage process */ + + /* Butterfly implementation */ + for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* Read ya (real), xa(imag) input */ + T = pSrc[i0]; + /* Read yc (real), xc(imag) input */ + S = pSrc[i2]; + + /* R = packed((ya + yc), (xa + xc)) */ + R = __QADD16(T, S); + /* S = packed((ya - yc), (xa - xc)) */ + S = __QSUB16(T, S); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* Read yb (real), xb(imag) input */ + T = pSrc[i1]; + /* Read yd (real), xd(imag) input */ + U = pSrc[i3]; + + /* T = packed((yb + yd), (xb + xd)) */ + T = __QADD16(T, U); + + /* writing the butterfly processed i0 sample */ + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + pSrc[i0] = __SHADD16(R, T); + + /* R = packed((ya + yc) - (yb + yd), (xa + xc) - (xb + xd)) */ + R = __SHSUB16(R, T); + + /* Read yb (real), xb(imag) input */ + T = pSrc[i1]; + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* xc' = (xa-xb+xc-xd) */ + /* yc' = (ya-yb+yc-yd) */ + pSrc[i1] = R; + + /* Read yd (real), xd(imag) input */ + U = pSrc[i3]; + /* T = packed( (yb - yd), (xb - xd)) */ + T = __QSUB16(T, U); + + +#ifndef ARM_MATH_BIG_ENDIAN + + /* writing the butterfly processed i0 + fftLen/2 sample */ + /* xb' = (xa+yb-xc-yd) */ + /* yb' = (ya-xb-yc+xd) */ + pSrc[i2] = __SHSAX(S, T); + + /* writing the butterfly processed i0 + 3fftLen/4 sample */ + /* xd' = (xa-yb-xc+yd) */ + /* yd' = (ya+xb-yc-xd) */ + pSrc[i3] = __SHASX(S, T); + +#else + + /* writing the butterfly processed i0 + fftLen/2 sample */ + /* xb' = (xa+yb-xc-yd) */ + /* yb' = (ya-xb-yc+xd) */ + pSrc[i2] = __SHASX(S, T); + + /* writing the butterfly processed i0 + 3fftLen/4 sample */ + /* xd' = (xa-yb-xc+yd) */ + /* yd' = (ya+xb-yc-xd) */ + pSrc[i3] = __SHSAX(S, T); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + } + + /* end of last stage process */ + + /* output is in 11.5(q5) format for the 1024 point */ + /* output is in 9.7(q7) format for the 256 point */ + /* output is in 7.9(q9) format for the 64 point */ + /* output is in 5.11(q11) format for the 16 point */ + + +#else + + /* Run the below code for Cortex-M0 */ + + q15_t R0, R1, S0, S1, T0, T1, U0, U1; + q15_t Co1, Si1, Co2, Si2, Co3, Si3, out1, out2; + uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; + + /* Total process is divided into three stages */ + + /* process first stage, middle stages, & last stage */ + + /* Initializations for the first stage */ + n2 = fftLen; + n1 = n2; + + /* n2 = fftLen/4 */ + n2 >>= 2u; + + /* Index for twiddle coefficient */ + ic = 0u; + + /* Index for input read and output write */ + i0 = 0u; + j = n2; + + /* Input is in 1.15(q15) format */ + + /* start of first stage process */ + do + { + /* Butterfly implementation */ + + /* index calculation for the input as, */ + /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + + /* input is down scale by 4 to avoid overflow */ + /* Read ya (real), xa(imag) input */ + T0 = pSrc16[i0 * 2u] >> 2u; + T1 = pSrc16[(i0 * 2u) + 1u] >> 2u; + + /* input is down scale by 4 to avoid overflow */ + /* Read yc (real), xc(imag) input */ + S0 = pSrc16[i2 * 2u] >> 2u; + S1 = pSrc16[(i2 * 2u) + 1u] >> 2u; + + /* R0 = (ya + yc) */ + R0 = __SSAT(T0 + S0, 16u); + /* R1 = (xa + xc) */ + R1 = __SSAT(T1 + S1, 16u); + + /* S0 = (ya - yc) */ + S0 = __SSAT(T0 - S0, 16); + /* S1 = (xa - xc) */ + S1 = __SSAT(T1 - S1, 16); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* input is down scale by 4 to avoid overflow */ + /* Read yb (real), xb(imag) input */ + T0 = pSrc16[i1 * 2u] >> 2u; + T1 = pSrc16[(i1 * 2u) + 1u] >> 2u; + + /* input is down scale by 4 to avoid overflow */ + /* Read yd (real), xd(imag) input */ + U0 = pSrc16[i3 * 2u] >> 2u; + U1 = pSrc16[(i3 * 2u) + 1] >> 2u; + + /* T0 = (yb + yd) */ + T0 = __SSAT(T0 + U0, 16u); + /* T1 = (xb + xd) */ + T1 = __SSAT(T1 + U1, 16u); + + /* writing the butterfly processed i0 sample */ + /* ya' = ya + yb + yc + yd */ + /* xa' = xa + xb + xc + xd */ + pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); + pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); + + /* R0 = (ya + yc) - (yb + yd) */ + /* R1 = (xa + xc) - (xb + xd) */ + R0 = __SSAT(R0 - T0, 16u); + R1 = __SSAT(R1 - T1, 16u); + + /* co2 & si2 are read from Coefficient pointer */ + Co2 = pCoef16[2u * ic * 2u]; + Si2 = pCoef16[(2u * ic * 2u) + 1]; + + /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ + out1 = (short) ((Co2 * R0 + Si2 * R1) >> 16u); + /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ + out2 = (short) ((-Si2 * R0 + Co2 * R1) >> 16u); + + /* Reading i0+fftLen/4 */ + /* input is down scale by 4 to avoid overflow */ + /* T0 = yb, T1 = xb */ + T0 = pSrc16[i1 * 2u] >> 2; + T1 = pSrc16[(i1 * 2u) + 1] >> 2; + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* writing output(xc', yc') in little endian format */ + pSrc16[i1 * 2u] = out1; + pSrc16[(i1 * 2u) + 1] = out2; + + /* Butterfly calculations */ + /* input is down scale by 4 to avoid overflow */ + /* U0 = yd, U1 = xd */ + U0 = pSrc16[i3 * 2u] >> 2; + U1 = pSrc16[(i3 * 2u) + 1] >> 2; + /* T0 = yb-yd */ + T0 = __SSAT(T0 - U0, 16); + /* T1 = xb-xd */ + T1 = __SSAT(T1 - U1, 16); + + /* R1 = (ya-yc) + (xb- xd), R0 = (xa-xc) - (yb-yd)) */ + R0 = (short) __SSAT((q31_t) (S0 - T1), 16); + R1 = (short) __SSAT((q31_t) (S1 + T0), 16); + + /* S1 = (ya-yc) - (xb- xd), S0 = (xa-xc) + (yb-yd)) */ + S0 = (short) __SSAT(((q31_t) S0 + T1), 16u); + S1 = (short) __SSAT(((q31_t) S1 - T0), 16u); + + /* co1 & si1 are read from Coefficient pointer */ + Co1 = pCoef16[ic * 2u]; + Si1 = pCoef16[(ic * 2u) + 1]; + /* Butterfly process for the i0+fftLen/2 sample */ + /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ + out1 = (short) ((Si1 * S1 + Co1 * S0) >> 16); + /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ + out2 = (short) ((-Si1 * S0 + Co1 * S1) >> 16); + + /* writing output(xb', yb') in little endian format */ + pSrc16[i2 * 2u] = out1; + pSrc16[(i2 * 2u) + 1] = out2; + + /* Co3 & si3 are read from Coefficient pointer */ + Co3 = pCoef16[3u * (ic * 2u)]; + Si3 = pCoef16[(3u * (ic * 2u)) + 1]; + /* Butterfly process for the i0+3fftLen/4 sample */ + /* xd' = (xa-yb-xc+yd)* Co3 + (ya+xb-yc-xd)* (si3) */ + out1 = (short) ((Si3 * R1 + Co3 * R0) >> 16u); + /* yd' = (ya+xb-yc-xd)* Co3 - (xa-yb-xc+yd)* (si3) */ + out2 = (short) ((-Si3 * R0 + Co3 * R1) >> 16u); + /* writing output(xd', yd') in little endian format */ + pSrc16[i3 * 2u] = out1; + pSrc16[(i3 * 2u) + 1] = out2; + + /* Twiddle coefficients index modifier */ + ic = ic + twidCoefModifier; + + /* Updating input index */ + i0 = i0 + 1u; + + } while(--j); + /* data is in 4.11(q11) format */ + + /* end of first stage process */ + + + /* start of middle stage process */ + + /* Twiddle coefficients index modifier */ + twidCoefModifier <<= 2u; + + /* Calculation of Middle stage */ + for (k = fftLen / 4u; k > 4u; k >>= 2u) + { + /* Initializations for the middle stage */ + n1 = n2; + n2 >>= 2u; + ic = 0u; + + for (j = 0u; j <= (n2 - 1u); j++) + { + /* index calculation for the coefficients */ + Co1 = pCoef16[ic * 2u]; + Si1 = pCoef16[(ic * 2u) + 1u]; + Co2 = pCoef16[2u * (ic * 2u)]; + Si2 = pCoef16[(2u * (ic * 2u)) + 1u]; + Co3 = pCoef16[3u * (ic * 2u)]; + Si3 = pCoef16[(3u * (ic * 2u)) + 1u]; + + /* Twiddle coefficients index modifier */ + ic = ic + twidCoefModifier; + + /* Butterfly implementation */ + for (i0 = j; i0 < fftLen; i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* Read ya (real), xa(imag) input */ + T0 = pSrc16[i0 * 2u]; + T1 = pSrc16[(i0 * 2u) + 1u]; + + /* Read yc (real), xc(imag) input */ + S0 = pSrc16[i2 * 2u]; + S1 = pSrc16[(i2 * 2u) + 1u]; + + /* R0 = (ya + yc), R1 = (xa + xc) */ + R0 = __SSAT(T0 + S0, 16); + R1 = __SSAT(T1 + S1, 16); + + /* S0 = (ya - yc), S1 =(xa - xc) */ + S0 = __SSAT(T0 - S0, 16); + S1 = __SSAT(T1 - S1, 16); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* Read yb (real), xb(imag) input */ + T0 = pSrc16[i1 * 2u]; + T1 = pSrc16[(i1 * 2u) + 1u]; + + /* Read yd (real), xd(imag) input */ + U0 = pSrc16[i3 * 2u]; + U1 = pSrc16[(i3 * 2u) + 1u]; + + + /* T0 = (yb + yd), T1 = (xb + xd) */ + T0 = __SSAT(T0 + U0, 16); + T1 = __SSAT(T1 + U1, 16); + + /* writing the butterfly processed i0 sample */ + + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + out1 = ((R0 >> 1u) + (T0 >> 1u)) >> 1u; + out2 = ((R1 >> 1u) + (T1 >> 1u)) >> 1u; + + pSrc16[i0 * 2u] = out1; + pSrc16[(2u * i0) + 1u] = out2; + + /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ + R0 = (R0 >> 1u) - (T0 >> 1u); + R1 = (R1 >> 1u) - (T1 >> 1u); + + /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ + out1 = (short) ((Co2 * R0 + Si2 * R1) >> 16u); + + /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ + out2 = (short) ((-Si2 * R0 + Co2 * R1) >> 16u); + + /* Reading i0+3fftLen/4 */ + /* Read yb (real), xb(imag) input */ + T0 = pSrc16[i1 * 2u]; + T1 = pSrc16[(i1 * 2u) + 1u]; + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ + /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ + pSrc16[i1 * 2u] = out1; + pSrc16[(i1 * 2u) + 1u] = out2; + + /* Butterfly calculations */ + + /* Read yd (real), xd(imag) input */ + U0 = pSrc16[i3 * 2u]; + U1 = pSrc16[(i3 * 2u) + 1u]; + + /* T0 = yb-yd, T1 = xb-xd */ + T0 = __SSAT(T0 - U0, 16); + T1 = __SSAT(T1 - U1, 16); + + /* R0 = (ya-yc) + (xb- xd), R1 = (xa-xc) - (yb-yd)) */ + R0 = (S0 >> 1u) - (T1 >> 1u); + R1 = (S1 >> 1u) + (T0 >> 1u); + + /* S0 = (ya-yc) - (xb- xd), S1 = (xa-xc) + (yb-yd)) */ + S0 = (S0 >> 1u) + (T1 >> 1u); + S1 = (S1 >> 1u) - (T0 >> 1u); + + /* Butterfly process for the i0+fftLen/2 sample */ + out1 = (short) ((Co1 * S0 + Si1 * S1) >> 16u); + + out2 = (short) ((-Si1 * S0 + Co1 * S1) >> 16u); + + /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ + /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ + pSrc16[i2 * 2u] = out1; + pSrc16[(i2 * 2u) + 1u] = out2; + + /* Butterfly process for the i0+3fftLen/4 sample */ + out1 = (short) ((Si3 * R1 + Co3 * R0) >> 16u); + + out2 = (short) ((-Si3 * R0 + Co3 * R1) >> 16u); + /* xd' = (xa-yb-xc+yd)* Co3 + (ya+xb-yc-xd)* (si3) */ + /* yd' = (ya+xb-yc-xd)* Co3 - (xa-yb-xc+yd)* (si3) */ + pSrc16[i3 * 2u] = out1; + pSrc16[(i3 * 2u) + 1u] = out2; + } + } + /* Twiddle coefficients index modifier */ + twidCoefModifier <<= 2u; + } + /* end of middle stage process */ + + + /* data is in 10.6(q6) format for the 1024 point */ + /* data is in 8.8(q8) format for the 256 point */ + /* data is in 6.10(q10) format for the 64 point */ + /* data is in 4.12(q12) format for the 16 point */ + + /* Initializations for the last stage */ + n1 = n2; + n2 >>= 2u; + + /* start of last stage process */ + + /* Butterfly implementation */ + for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* Read ya (real), xa(imag) input */ + T0 = pSrc16[i0 * 2u]; + T1 = pSrc16[(i0 * 2u) + 1u]; + + /* Read yc (real), xc(imag) input */ + S0 = pSrc16[i2 * 2u]; + S1 = pSrc16[(i2 * 2u) + 1u]; + + /* R0 = (ya + yc), R1 = (xa + xc) */ + R0 = __SSAT(T0 + S0, 16u); + R1 = __SSAT(T1 + S1, 16u); + + /* S0 = (ya - yc), S1 = (xa - xc) */ + S0 = __SSAT(T0 - S0, 16u); + S1 = __SSAT(T1 - S1, 16u); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* Read yb (real), xb(imag) input */ + T0 = pSrc16[i1 * 2u]; + T1 = pSrc16[(i1 * 2u) + 1u]; + /* Read yd (real), xd(imag) input */ + U0 = pSrc16[i3 * 2u]; + U1 = pSrc16[(i3 * 2u) + 1u]; + + /* T0 = (yb + yd), T1 = (xb + xd)) */ + T0 = __SSAT(T0 + U0, 16u); + T1 = __SSAT(T1 + U1, 16u); + + /* writing the butterfly processed i0 sample */ + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); + pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); + + /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ + R0 = (R0 >> 1u) - (T0 >> 1u); + R1 = (R1 >> 1u) - (T1 >> 1u); + /* Read yb (real), xb(imag) input */ + T0 = pSrc16[i1 * 2u]; + T1 = pSrc16[(i1 * 2u) + 1u]; + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* xc' = (xa-xb+xc-xd) */ + /* yc' = (ya-yb+yc-yd) */ + pSrc16[i1 * 2u] = R0; + pSrc16[(i1 * 2u) + 1u] = R1; + + /* Read yd (real), xd(imag) input */ + U0 = pSrc16[i3 * 2u]; + U1 = pSrc16[(i3 * 2u) + 1u]; + /* T0 = (yb - yd), T1 = (xb - xd) */ + T0 = __SSAT(T0 - U0, 16u); + T1 = __SSAT(T1 - U1, 16u); + + /* writing the butterfly processed i0 + fftLen/2 sample */ + /* xb' = (xa+yb-xc-yd) */ + /* yb' = (ya-xb-yc+xd) */ + pSrc16[i2 * 2u] = (S0 >> 1u) + (T1 >> 1u); + pSrc16[(i2 * 2u) + 1u] = (S1 >> 1u) - (T0 >> 1u); + + /* writing the butterfly processed i0 + 3fftLen/4 sample */ + /* xd' = (xa-yb-xc+yd) */ + /* yd' = (ya+xb-yc-xd) */ + pSrc16[i3 * 2u] = (S0 >> 1u) - (T1 >> 1u); + pSrc16[(i3 * 2u) + 1u] = (S1 >> 1u) + (T0 >> 1u); + + } + + /* end of last stage process */ + + /* output is in 11.5(q5) format for the 1024 point */ + /* output is in 9.7(q7) format for the 256 point */ + /* output is in 7.9(q9) format for the 64 point */ + /* output is in 5.11(q11) format for the 16 point */ + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + +/** + * @brief Core function for the Q15 CIFFT butterfly process. + * @param[in, out] *pSrc16 points to the in-place buffer of Q15 data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef16 points to twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + +/* +* Radix-4 IFFT algorithm used is : +* +* CIFFT uses same twiddle coefficients as CFFT function +* x[k] = x[n] + (j)k * x[n + fftLen/4] + (-1)k * x[n+fftLen/2] + (-j)k * x[n+3*fftLen/4] +* +* +* IFFT is implemented with following changes in equations from FFT +* +* Input real and imaginary data: +* x(n) = xa + j * ya +* x(n+N/4 ) = xb + j * yb +* x(n+N/2 ) = xc + j * yc +* x(n+3N 4) = xd + j * yd +* +* +* Output real and imaginary data: +* x(4r) = xa'+ j * ya' +* x(4r+1) = xb'+ j * yb' +* x(4r+2) = xc'+ j * yc' +* x(4r+3) = xd'+ j * yd' +* +* +* Twiddle factors for radix-4 IFFT: +* Wn = co1 + j * (si1) +* W2n = co2 + j * (si2) +* W3n = co3 + j * (si3) + +* The real and imaginary output values for the radix-4 butterfly are +* xa' = xa + xb + xc + xd +* ya' = ya + yb + yc + yd +* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) +* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) +* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) +* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) +* xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) +* yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) +* +*/ + +void arm_radix4_butterfly_inverse_q15( + q15_t * pSrc16, + uint32_t fftLen, + q15_t * pCoef16, + uint32_t twidCoefModifier) +{ + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + q31_t R, S, T, U; + q31_t C1, C2, C3, out1, out2; + q31_t *pSrc, *pCoeff; + uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; + q15_t in; + + /* Total process is divided into three stages */ + + /* process first stage, middle stages, & last stage */ + + /* pointer initializations for SIMD calculations */ + pSrc = (q31_t *) pSrc16; + pCoeff = (q31_t *) pCoef16; + + /* Initializations for the first stage */ + n2 = fftLen; + n1 = n2; + + /* n2 = fftLen/4 */ + n2 >>= 2u; + + /* Index for twiddle coefficient */ + ic = 0u; + + /* Index for input read and output write */ + i0 = 0u; + + j = n2; + + /* Input is in 1.15(q15) format */ + + /* Start of first stage process */ + do + { + /* Butterfly implementation */ + + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* Read ya (real), xa(imag) input */ + T = pSrc[i0]; + in = ((int16_t) (T & 0xFFFF)) >> 2; + T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); + /* Read yc (real), xc(imag) input */ + S = pSrc[i2]; + in = ((int16_t) (S & 0xFFFF)) >> 2; + S = ((S >> 2) & 0xFFFF0000) | (in & 0xFFFF); + + /* R = packed((ya + yc), (xa + xc) ) */ + R = __QADD16(T, S); + /* S = packed((ya - yc), (xa - xc) ) */ + S = __QSUB16(T, S); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* Read yb (real), xb(imag) input */ + T = pSrc[i1]; + in = ((int16_t) (T & 0xFFFF)) >> 2; + T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); + /* Read yd (real), xd(imag) input */ + U = pSrc[i3]; + in = ((int16_t) (U & 0xFFFF)) >> 2; + U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); + + /* T = packed((yb + yd), (xb + xd) ) */ + T = __QADD16(T, U); + + /* writing the butterfly processed i0 sample */ + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + pSrc[i0] = __SHADD16(R, T); + + /* R = packed((ya + yc) - (yb + yd), (xa + xc)- (xb + xd)) */ + R = __QSUB16(R, T); + /* co2 & si2 are read from SIMD Coefficient pointer */ + C2 = pCoeff[2u * ic]; + +#ifndef ARM_MATH_BIG_ENDIAN + + /* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ + out1 = __SMUSD(C2, R) >> 16u; + /* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ + out2 = __SMUADX(C2, R); + +#else + + /* xc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ + out1 = __SMUADX(C2, R) >> 16u; + /* yc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ + out2 = __SMUSD(-C2, R); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Reading i0+fftLen/4 */ + /* T = packed(yb, xb) */ + T = pSrc[i1]; + in = ((int16_t) (T & 0xFFFF)) >> 2; + T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* writing output(xc', yc') in little endian format */ + pSrc[i1] = (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); + + /* Butterfly calculations */ + /* U = packed(yd, xd) */ + U = pSrc[i3]; + in = ((int16_t) (U & 0xFFFF)) >> 2; + U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); + + /* T = packed(yb-yd, xb-xd) */ + T = __QSUB16(T, U); + +#ifndef ARM_MATH_BIG_ENDIAN + + /* R = packed((ya-yc) - (xb- xd) , (xa-xc) + (yb-yd)) */ + R = __QSAX(S, T); + /* S = packed((ya-yc) + (xb- xd), (xa-xc) - (yb-yd)) */ + S = __QASX(S, T); + +#else + + /* R = packed((ya-yc) - (xb- xd) , (xa-xc) + (yb-yd)) */ + R = __QASX(S, T); + /* S = packed((ya-yc) + (xb- xd), (xa-xc) - (yb-yd)) */ + S = __QSAX(S, T); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* co1 & si1 are read from SIMD Coefficient pointer */ + C1 = pCoeff[ic]; + /* Butterfly process for the i0+fftLen/2 sample */ + +#ifndef ARM_MATH_BIG_ENDIAN + + /* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ + out1 = __SMUSD(C1, S) >> 16u; + /* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ + out2 = __SMUADX(C1, S); + +#else + + /* xb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ + out1 = __SMUADX(C1, S) >> 16u; + /* yb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ + out2 = __SMUSD(-C1, S); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* writing output(xb', yb') in little endian format */ + pSrc[i2] = ((out2) & 0xFFFF0000) | ((out1) & 0x0000FFFF); + + /* co3 & si3 are read from SIMD Coefficient pointer */ + C3 = pCoeff[3u * ic]; + /* Butterfly process for the i0+3fftLen/4 sample */ + +#ifndef ARM_MATH_BIG_ENDIAN + + /* xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) */ + out1 = __SMUSD(C3, R) >> 16u; + /* yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) */ + out2 = __SMUADX(C3, R); + +#else + + /* xd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) */ + out1 = __SMUADX(C3, R) >> 16u; + /* yd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) */ + out2 = __SMUSD(-C3, R); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* writing output(xd', yd') in little endian format */ + pSrc[i3] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); + + /* Twiddle coefficients index modifier */ + ic = ic + twidCoefModifier; + + /* Updating input index */ + i0 = i0 + 1u; + + } while(--j); + + /* End of first stage process */ + + /* data is in 4.11(q11) format */ + + + /* Start of Middle stage process */ + + /* Twiddle coefficients index modifier */ + twidCoefModifier <<= 2u; + + /* Calculation of Middle stage */ + for (k = fftLen / 4u; k > 4u; k >>= 2u) + { + /* Initializations for the middle stage */ + n1 = n2; + n2 >>= 2u; + ic = 0u; + + for (j = 0u; j <= (n2 - 1u); j++) + { + /* index calculation for the coefficients */ + C1 = pCoeff[ic]; + C2 = pCoeff[2u * ic]; + C3 = pCoeff[3u * ic]; + + /* Twiddle coefficients index modifier */ + ic = ic + twidCoefModifier; + + /* Butterfly implementation */ + for (i0 = j; i0 < fftLen; i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* Read ya (real), xa(imag) input */ + T = pSrc[i0]; + + /* Read yc (real), xc(imag) input */ + S = pSrc[i2]; + + + /* R = packed( (ya + yc), (xa + xc)) */ + R = __QADD16(T, S); + /* S = packed((ya - yc), (xa - xc)) */ + S = __QSUB16(T, S); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* Read yb (real), xb(imag) input */ + T = pSrc[i1]; + + /* Read yd (real), xd(imag) input */ + U = pSrc[i3]; + + + /* T = packed( (yb + yd), (xb + xd)) */ + T = __QADD16(T, U); + + /* writing the butterfly processed i0 sample */ + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + out1 = __SHADD16(R, T); + in = ((int16_t) (out1 & 0xFFFF)) >> 1; + out1 = ((out1 >> 1) & 0xFFFF0000) | (in & 0xFFFF); + pSrc[i0] = out1; + + + + /* R = packed( (ya + yc) - (yb + yd), (xa + xc) - (xb + xd)) */ + R = __SHSUB16(R, T); + + +#ifndef ARM_MATH_BIG_ENDIAN + + /* (ya-yb+yc-yd)* (si2) - (xa-xb+xc-xd)* co2 */ + out1 = __SMUSD(C2, R) >> 16u; + /* (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ + out2 = __SMUADX(C2, R); + +#else + + /* (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ + out1 = __SMUADX(R, C2) >> 16u; + /* (ya-yb+yc-yd)* (si2) - (xa-xb+xc-xd)* co2 */ + out2 = __SMUSD(-C2, R); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* Reading i0+3fftLen/4 */ + /* Read yb (real), xb(imag) input */ + T = pSrc[i1]; + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ + /* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ + pSrc[i1] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); + + /* Butterfly calculations */ + /* Read yd (real), xd(imag) input */ + U = pSrc[i3]; + + /* T = packed(yb-yd, xb-xd) */ + T = __QSUB16(T, U); + + +#ifndef ARM_MATH_BIG_ENDIAN + + /* R = packed((ya-yc) - (xb- xd) , (xa-xc) + (yb-yd)) */ + R = __SHSAX(S, T); + + /* S = packed((ya-yc) + (xb- xd), (xa-xc) - (yb-yd)) */ + S = __SHASX(S, T); + /* Butterfly process for the i0+fftLen/2 sample */ + out1 = __SMUSD(C1, S) >> 16u; + out2 = __SMUADX(C1, S); + +#else + + /* R = packed((ya-yc) - (xb- xd) , (xa-xc) + (yb-yd)) */ + R = __SHASX(S, T); + + /* S = packed((ya-yc) + (xb- xd), (xa-xc) - (yb-yd)) */ + S = __SHSAX(S, T); + /* Butterfly process for the i0+fftLen/2 sample */ + out1 = __SMUADX(S, C1) >> 16u; + out2 = __SMUSD(-C1, S); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ + /* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ + pSrc[i2] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); + + /* Butterfly process for the i0+3fftLen/4 sample */ + +#ifndef ARM_MATH_BIG_ENDIAN + + out1 = __SMUSD(C3, R) >> 16u; + out2 = __SMUADX(C3, R); + +#else + + out1 = __SMUADX(C3, R) >> 16u; + out2 = __SMUSD(-C3, R); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) */ + /* yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) */ + pSrc[i3] = ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); + + + } + } + /* Twiddle coefficients index modifier */ + twidCoefModifier <<= 2u; + } + /* End of Middle stages process */ + + + /* data is in 10.6(q6) format for the 1024 point */ + /* data is in 8.8(q8) format for the 256 point */ + /* data is in 6.10(q10) format for the 64 point */ + /* data is in 4.12(q12) format for the 16 point */ + + /* start of last stage process */ + + + /* Initializations for the last stage */ + n1 = n2; + n2 >>= 2u; + + /* Butterfly implementation */ + for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* Read ya (real), xa(imag) input */ + T = pSrc[i0]; + /* Read yc (real), xc(imag) input */ + S = pSrc[i2]; + + /* R = packed((ya + yc), (xa + xc)) */ + R = __QADD16(T, S); + /* S = packed((ya - yc), (xa - xc)) */ + S = __QSUB16(T, S); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* Read yb (real), xb(imag) input */ + T = pSrc[i1]; + /* Read yd (real), xd(imag) input */ + U = pSrc[i3]; + + /* T = packed((yb + yd), (xb + xd)) */ + T = __QADD16(T, U); + + /* writing the butterfly processed i0 sample */ + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + pSrc[i0] = __SHADD16(R, T); + + /* R = packed((ya + yc) - (yb + yd), (xa + xc) - (xb + xd)) */ + R = __SHSUB16(R, T); + + /* Read yb (real), xb(imag) input */ + T = pSrc[i1]; + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* xc' = (xa-xb+xc-xd) */ + /* yc' = (ya-yb+yc-yd) */ + pSrc[i1] = R; + + /* Read yd (real), xd(imag) input */ + U = pSrc[i3]; + /* T = packed( (yb - yd), (xb - xd)) */ + T = __QSUB16(T, U); + + +#ifndef ARM_MATH_BIG_ENDIAN + + /* writing the butterfly processed i0 + fftLen/2 sample */ + /* xb' = (xa-yb-xc+yd) */ + /* yb' = (ya+xb-yc-xd) */ + pSrc[i2] = __SHASX(S, T); + + /* writing the butterfly processed i0 + 3fftLen/4 sample */ + /* xd' = (xa+yb-xc-yd) */ + /* yd' = (ya-xb-yc+xd) */ + pSrc[i3] = __SHSAX(S, T); + + +#else + + /* writing the butterfly processed i0 + fftLen/2 sample */ + /* xb' = (xa-yb-xc+yd) */ + /* yb' = (ya+xb-yc-xd) */ + pSrc[i2] = __SHSAX(S, T); + + /* writing the butterfly processed i0 + 3fftLen/4 sample */ + /* xd' = (xa+yb-xc-yd) */ + /* yd' = (ya-xb-yc+xd) */ + pSrc[i3] = __SHASX(S, T); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + } + /* end of last stage process */ + + /* output is in 11.5(q5) format for the 1024 point */ + /* output is in 9.7(q7) format for the 256 point */ + /* output is in 7.9(q9) format for the 64 point */ + /* output is in 5.11(q11) format for the 16 point */ + + +#else + + /* Run the below code for Cortex-M0 */ + + q15_t R0, R1, S0, S1, T0, T1, U0, U1; + q15_t Co1, Si1, Co2, Si2, Co3, Si3, out1, out2; + uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; + + /* Total process is divided into three stages */ + + /* process first stage, middle stages, & last stage */ + + /* Initializations for the first stage */ + n2 = fftLen; + n1 = n2; + + /* n2 = fftLen/4 */ + n2 >>= 2u; + + /* Index for twiddle coefficient */ + ic = 0u; + + /* Index for input read and output write */ + i0 = 0u; + + j = n2; + + /* Input is in 1.15(q15) format */ + + /* Start of first stage process */ + do + { + /* Butterfly implementation */ + + /* index calculation for the input as, */ + /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* input is down scale by 4 to avoid overflow */ + /* Read ya (real), xa(imag) input */ + T0 = pSrc16[i0 * 2u] >> 2u; + T1 = pSrc16[(i0 * 2u) + 1u] >> 2u; + /* input is down scale by 4 to avoid overflow */ + /* Read yc (real), xc(imag) input */ + S0 = pSrc16[i2 * 2u] >> 2u; + S1 = pSrc16[(i2 * 2u) + 1u] >> 2u; + + /* R0 = (ya + yc), R1 = (xa + xc) */ + R0 = __SSAT(T0 + S0, 16u); + R1 = __SSAT(T1 + S1, 16u); + /* S0 = (ya - yc), S1 = (xa - xc) */ + S0 = __SSAT(T0 - S0, 16u); + S1 = __SSAT(T1 - S1, 16u); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* input is down scale by 4 to avoid overflow */ + /* Read yb (real), xb(imag) input */ + T0 = pSrc16[i1 * 2u] >> 2u; + T1 = pSrc16[(i1 * 2u) + 1u] >> 2u; + /* Read yd (real), xd(imag) input */ + /* input is down scale by 4 to avoid overflow */ + U0 = pSrc16[i3 * 2u] >> 2u; + U1 = pSrc16[(i3 * 2u) + 1u] >> 2u; + + /* T0 = (yb + yd), T1 = (xb + xd) */ + T0 = __SSAT(T0 + U0, 16u); + T1 = __SSAT(T1 + U1, 16u); + + /* writing the butterfly processed i0 sample */ + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); + pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); + + /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc)- (xb + xd) */ + R0 = __SSAT(R0 - T0, 16u); + R1 = __SSAT(R1 - T1, 16u); + /* co2 & si2 are read from Coefficient pointer */ + Co2 = pCoef16[2u * ic * 2u]; + Si2 = pCoef16[(2u * ic * 2u) + 1u]; + /* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ + out1 = (short) ((Co2 * R0 - Si2 * R1) >> 16u); + /* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ + out2 = (short) ((Si2 * R0 + Co2 * R1) >> 16u); + + /* Reading i0+fftLen/4 */ + /* input is down scale by 4 to avoid overflow */ + /* T0 = yb, T1 = xb */ + T0 = pSrc16[i1 * 2u] >> 2u; + T1 = pSrc16[(i1 * 2u) + 1u] >> 2u; + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* writing output(xc', yc') in little endian format */ + pSrc16[i1 * 2u] = out1; + pSrc16[(i1 * 2u) + 1u] = out2; + + /* Butterfly calculations */ + /* input is down scale by 4 to avoid overflow */ + /* U0 = yd, U1 = xd) */ + U0 = pSrc16[i3 * 2u] >> 2u; + U1 = pSrc16[(i3 * 2u) + 1u] >> 2u; + + /* T0 = yb-yd, T1 = xb-xd) */ + T0 = __SSAT(T0 - U0, 16u); + T1 = __SSAT(T1 - U1, 16u); + /* R0 = (ya-yc) - (xb- xd) , R1 = (xa-xc) + (yb-yd) */ + R0 = (short) __SSAT((q31_t) (S0 + T1), 16); + R1 = (short) __SSAT((q31_t) (S1 - T0), 16); + /* S = (ya-yc) + (xb- xd), S1 = (xa-xc) - (yb-yd) */ + S0 = (short) __SSAT((q31_t) (S0 - T1), 16); + S1 = (short) __SSAT((q31_t) (S1 + T0), 16); + + /* co1 & si1 are read from Coefficient pointer */ + Co1 = pCoef16[ic * 2u]; + Si1 = pCoef16[(ic * 2u) + 1u]; + /* Butterfly process for the i0+fftLen/2 sample */ + /* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ + out1 = (short) ((Co1 * S0 - Si1 * S1) >> 16u); + /* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ + out2 = (short) ((Si1 * S0 + Co1 * S1) >> 16u); + /* writing output(xb', yb') in little endian format */ + pSrc16[i2 * 2u] = out1; + pSrc16[(i2 * 2u) + 1u] = out2; + + /* Co3 & si3 are read from Coefficient pointer */ + Co3 = pCoef16[3u * ic * 2u]; + Si3 = pCoef16[(3u * ic * 2u) + 1u]; + /* Butterfly process for the i0+3fftLen/4 sample */ + /* xd' = (xa+yb-xc-yd)* Co3 - (ya-xb-yc+xd)* (si3) */ + out1 = (short) ((Co3 * R0 - Si3 * R1) >> 16u); + /* yd' = (ya-xb-yc+xd)* Co3 + (xa+yb-xc-yd)* (si3) */ + out2 = (short) ((Si3 * R0 + Co3 * R1) >> 16u); + /* writing output(xd', yd') in little endian format */ + pSrc16[i3 * 2u] = out1; + pSrc16[(i3 * 2u) + 1u] = out2; + + /* Twiddle coefficients index modifier */ + ic = ic + twidCoefModifier; + + /* Updating input index */ + i0 = i0 + 1u; + + } while(--j); + + /* End of first stage process */ + + /* data is in 4.11(q11) format */ + + + /* Start of Middle stage process */ + + /* Twiddle coefficients index modifier */ + twidCoefModifier <<= 2u; + + /* Calculation of Middle stage */ + for (k = fftLen / 4u; k > 4u; k >>= 2u) + { + /* Initializations for the middle stage */ + n1 = n2; + n2 >>= 2u; + ic = 0u; + + for (j = 0u; j <= (n2 - 1u); j++) + { + /* index calculation for the coefficients */ + Co1 = pCoef16[ic * 2u]; + Si1 = pCoef16[(ic * 2u) + 1u]; + Co2 = pCoef16[2u * ic * 2u]; + Si2 = pCoef16[2u * ic * 2u + 1u]; + Co3 = pCoef16[3u * ic * 2u]; + Si3 = pCoef16[(3u * ic * 2u) + 1u]; + + /* Twiddle coefficients index modifier */ + ic = ic + twidCoefModifier; + + /* Butterfly implementation */ + for (i0 = j; i0 < fftLen; i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* Read ya (real), xa(imag) input */ + T0 = pSrc16[i0 * 2u]; + T1 = pSrc16[(i0 * 2u) + 1u]; + + /* Read yc (real), xc(imag) input */ + S0 = pSrc16[i2 * 2u]; + S1 = pSrc16[(i2 * 2u) + 1u]; + + + /* R0 = (ya + yc), R1 = (xa + xc) */ + R0 = __SSAT(T0 + S0, 16u); + R1 = __SSAT(T1 + S1, 16u); + /* S0 = (ya - yc), S1 = (xa - xc) */ + S0 = __SSAT(T0 - S0, 16u); + S1 = __SSAT(T1 - S1, 16u); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* Read yb (real), xb(imag) input */ + T0 = pSrc16[i1 * 2u]; + T1 = pSrc16[(i1 * 2u) + 1u]; + + /* Read yd (real), xd(imag) input */ + U0 = pSrc16[i3 * 2u]; + U1 = pSrc16[(i3 * 2u) + 1u]; + + /* T0 = (yb + yd), T1 = (xb + xd) */ + T0 = __SSAT(T0 + U0, 16u); + T1 = __SSAT(T1 + U1, 16u); + + /* writing the butterfly processed i0 sample */ + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + pSrc16[i0 * 2u] = ((R0 >> 1u) + (T0 >> 1u)) >> 1u; + pSrc16[(i0 * 2u) + 1u] = ((R1 >> 1u) + (T1 >> 1u)) >> 1u; + + /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ + R0 = (R0 >> 1u) - (T0 >> 1u); + R1 = (R1 >> 1u) - (T1 >> 1u); + + /* (ya-yb+yc-yd)* (si2) - (xa-xb+xc-xd)* co2 */ + out1 = (short) ((Co2 * R0 - Si2 * R1) >> 16); + /* (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ + out2 = (short) ((Si2 * R0 + Co2 * R1) >> 16); + + /* Reading i0+3fftLen/4 */ + /* Read yb (real), xb(imag) input */ + T0 = pSrc16[i1 * 2u]; + T1 = pSrc16[(i1 * 2u) + 1u]; + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ + /* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ + pSrc16[i1 * 2u] = out1; + pSrc16[(i1 * 2u) + 1u] = out2; + + /* Butterfly calculations */ + /* Read yd (real), xd(imag) input */ + U0 = pSrc16[i3 * 2u]; + U1 = pSrc16[(i3 * 2u) + 1u]; + + /* T0 = yb-yd, T1 = xb-xd) */ + T0 = __SSAT(T0 - U0, 16u); + T1 = __SSAT(T1 - U1, 16u); + + /* R0 = (ya-yc) - (xb- xd) , R1 = (xa-xc) + (yb-yd) */ + R0 = (S0 >> 1u) + (T1 >> 1u); + R1 = (S1 >> 1u) - (T0 >> 1u); + + /* S1 = (ya-yc) + (xb- xd), S1 = (xa-xc) - (yb-yd) */ + S0 = (S0 >> 1u) - (T1 >> 1u); + S1 = (S1 >> 1u) + (T0 >> 1u); + + /* Butterfly process for the i0+fftLen/2 sample */ + out1 = (short) ((Co1 * S0 - Si1 * S1) >> 16u); + out2 = (short) ((Si1 * S0 + Co1 * S1) >> 16u); + /* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ + /* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ + pSrc16[i2 * 2u] = out1; + pSrc16[(i2 * 2u) + 1u] = out2; + + /* Butterfly process for the i0+3fftLen/4 sample */ + out1 = (short) ((Co3 * R0 - Si3 * R1) >> 16u); + + out2 = (short) ((Si3 * R0 + Co3 * R1) >> 16u); + /* xd' = (xa+yb-xc-yd)* Co3 - (ya-xb-yc+xd)* (si3) */ + /* yd' = (ya-xb-yc+xd)* Co3 + (xa+yb-xc-yd)* (si3) */ + pSrc16[i3 * 2u] = out1; + pSrc16[(i3 * 2u) + 1u] = out2; + + + } + } + /* Twiddle coefficients index modifier */ + twidCoefModifier <<= 2u; + } + /* End of Middle stages process */ + + + /* data is in 10.6(q6) format for the 1024 point */ + /* data is in 8.8(q8) format for the 256 point */ + /* data is in 6.10(q10) format for the 64 point */ + /* data is in 4.12(q12) format for the 16 point */ + + /* start of last stage process */ + + + /* Initializations for the last stage */ + n1 = n2; + n2 >>= 2u; + + /* Butterfly implementation */ + for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Reading i0, i0+fftLen/2 inputs */ + /* Read ya (real), xa(imag) input */ + T0 = pSrc16[i0 * 2u]; + T1 = pSrc16[(i0 * 2u) + 1u]; + /* Read yc (real), xc(imag) input */ + S0 = pSrc16[i2 * 2u]; + S1 = pSrc16[(i2 * 2u) + 1u]; + + /* R0 = (ya + yc), R1 = (xa + xc) */ + R0 = __SSAT(T0 + S0, 16u); + R1 = __SSAT(T1 + S1, 16u); + /* S0 = (ya - yc), S1 = (xa - xc) */ + S0 = __SSAT(T0 - S0, 16u); + S1 = __SSAT(T1 - S1, 16u); + + /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ + /* Read yb (real), xb(imag) input */ + T0 = pSrc16[i1 * 2u]; + T1 = pSrc16[(i1 * 2u) + 1u]; + /* Read yd (real), xd(imag) input */ + U0 = pSrc16[i3 * 2u]; + U1 = pSrc16[(i3 * 2u) + 1u]; + + /* T0 = (yb + yd), T1 = (xb + xd) */ + T0 = __SSAT(T0 + U0, 16u); + T1 = __SSAT(T1 + U1, 16u); + + /* writing the butterfly processed i0 sample */ + /* xa' = xa + xb + xc + xd */ + /* ya' = ya + yb + yc + yd */ + pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); + pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); + + /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ + R0 = (R0 >> 1u) - (T0 >> 1u); + R1 = (R1 >> 1u) - (T1 >> 1u); + + /* Read yb (real), xb(imag) input */ + T0 = pSrc16[i1 * 2u]; + T1 = pSrc16[(i1 * 2u) + 1u]; + + /* writing the butterfly processed i0 + fftLen/4 sample */ + /* xc' = (xa-xb+xc-xd) */ + /* yc' = (ya-yb+yc-yd) */ + pSrc16[i1 * 2u] = R0; + pSrc16[(i1 * 2u) + 1u] = R1; + + /* Read yd (real), xd(imag) input */ + U0 = pSrc16[i3 * 2u]; + U1 = pSrc16[(i3 * 2u) + 1u]; + /* T0 = (yb - yd), T1 = (xb - xd) */ + T0 = __SSAT(T0 - U0, 16u); + T1 = __SSAT(T1 - U1, 16u); + + /* writing the butterfly processed i0 + fftLen/2 sample */ + /* xb' = (xa-yb-xc+yd) */ + /* yb' = (ya+xb-yc-xd) */ + pSrc16[i2 * 2u] = (S0 >> 1u) - (T1 >> 1u); + pSrc16[(i2 * 2u) + 1u] = (S1 >> 1u) + (T0 >> 1u); + + + /* writing the butterfly processed i0 + 3fftLen/4 sample */ + /* xd' = (xa+yb-xc-yd) */ + /* yd' = (ya-xb-yc+xd) */ + pSrc16[i3 * 2u] = (S0 >> 1u) + (T1 >> 1u); + pSrc16[(i3 * 2u) + 1u] = (S1 >> 1u) - (T0 >> 1u); + } + /* end of last stage process */ + + /* output is in 11.5(q5) format for the 1024 point */ + /* output is in 9.7(q7) format for the 256 point */ + /* output is in 7.9(q9) format for the 64 point */ + /* output is in 5.11(q11) format for the 16 point */ + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + +/* + * @brief In-place bit reversal function. + * @param[in, out] *pSrc points to the in-place buffer of Q15 data type. + * @param[in] fftLen length of the FFT. + * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table + * @param[in] *pBitRevTab points to bit reversal table. + * @return none. + */ + +void arm_bitreversal_q15( + q15_t * pSrc16, + uint32_t fftLen, + uint16_t bitRevFactor, + uint16_t * pBitRevTab) +{ + q31_t *pSrc = (q31_t *) pSrc16; + q31_t in; + uint32_t fftLenBy2, fftLenBy2p1; + uint32_t i, j; + + /* Initializations */ + j = 0u; + fftLenBy2 = fftLen / 2u; + fftLenBy2p1 = (fftLen / 2u) + 1u; + + /* Bit Reversal Implementation */ + for (i = 0u; i <= (fftLenBy2 - 2u); i += 2u) + { + if(i < j) + { + /* pSrc[i] <-> pSrc[j]; */ + /* pSrc[i+1u] <-> pSrc[j+1u] */ + in = pSrc[i]; + pSrc[i] = pSrc[j]; + pSrc[j] = in; + + /* pSrc[i + fftLenBy2p1] <-> pSrc[j + fftLenBy2p1]; */ + /* pSrc[i + fftLenBy2p1+1u] <-> pSrc[j + fftLenBy2p1+1u] */ + in = pSrc[i + fftLenBy2p1]; + pSrc[i + fftLenBy2p1] = pSrc[j + fftLenBy2p1]; + pSrc[j + fftLenBy2p1] = in; + } + + /* pSrc[i+1u] <-> pSrc[j+fftLenBy2]; */ + /* pSrc[i+2] <-> pSrc[j+fftLenBy2+1u] */ + in = pSrc[i + 1u]; + pSrc[i + 1u] = pSrc[j + fftLenBy2]; + pSrc[j + fftLenBy2] = in; + + /* Reading the index for the bit reversal */ + j = *pBitRevTab; + + /* Updating the bit reversal index depending on the fft length */ + pBitRevTab += bitRevFactor; + } +} diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q31.c index f61aa0892..ad0265616 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q31.c @@ -1,906 +1,906 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_q31.c -* -* Description: This file has function definition of Radix-4 FFT & IFFT function and -* In-place bit reversal using bit reversal table -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ -#include "arm_math.h" - - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup CFFT_CIFFT - * @{ - */ - -/** - * @details - * @brief Processing function for the Q31 CFFT/CIFFT. - * @param[in] *S points to an instance of the Q31 CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer of size 2*fftLen. Processing occurs in-place. - * @return none. - * - * \par Input and output formats: - * \par - * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. - * Hence the output format is different for different FFT sizes. - * The input and output formats for different FFT sizes and number of bits to upscale are mentioned in the tables below for CFFT and CIFFT: - * \par - * \image html CFFTQ31.gif "Input and Output Formats for Q31 CFFT" - * \image html CIFFTQ31.gif "Input and Output Formats for Q31 CIFFT" - * - */ - -void arm_cfft_radix4_q31( - const arm_cfft_radix4_instance_q31 * S, - q31_t * pSrc) -{ - if(S->ifftFlag == 1u) - { - /* Complex IFFT radix-4 */ - arm_radix4_butterfly_inverse_q31(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - else - { - /* Complex FFT radix-4 */ - arm_radix4_butterfly_q31(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - - - if(S->bitReverseFlag == 1u) - { - /* Bit Reversal */ - arm_bitreversal_q31(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); - } - -} - -/** - * @} end of CFFT_CIFFT group - */ - -/* -* Radix-4 FFT algorithm used is : -* -* Input real and imaginary data: -* x(n) = xa + j * ya -* x(n+N/4 ) = xb + j * yb -* x(n+N/2 ) = xc + j * yc -* x(n+3N 4) = xd + j * yd -* -* -* Output real and imaginary data: -* x(4r) = xa'+ j * ya' -* x(4r+1) = xb'+ j * yb' -* x(4r+2) = xc'+ j * yc' -* x(4r+3) = xd'+ j * yd' -* -* -* Twiddle factors for radix-4 FFT: -* Wn = co1 + j * (- si1) -* W2n = co2 + j * (- si2) -* W3n = co3 + j * (- si3) -* -* Butterfly implementation: -* xa' = xa + xb + xc + xd -* ya' = ya + yb + yc + yd -* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) -* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) -* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) -* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) -* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) -* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) -* -*/ - -/** - * @brief Core function for the Q31 CFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_radix4_butterfly_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pCoef, - uint32_t twidCoefModifier) -{ - uint32_t n1, n2, ia1, ia2, ia3, i0, i1, i2, i3, j, k; - q31_t t1, t2, r1, r2, s1, s2, co1, co2, co3, si1, si2, si3; - - - /* Total process is divided into three stages */ - - /* process first stage, middle stages, & last stage */ - - - /* start of first stage process */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - /* n2 = fftLen/4 */ - n2 >>= 2u; - i0 = 0u; - ia1 = 0u; - - j = n2; - - /* Calculation of first stage */ - do - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* input is in 1.31(q31) format and provide 4 guard bits for the input */ - - /* Butterfly implementation */ - /* xa + xc */ - r1 = (pSrc[(2u * i0)] >> 4u) + (pSrc[(2u * i2)] >> 4u); - /* xa - xc */ - r2 = (pSrc[2u * i0] >> 4u) - (pSrc[2u * i2] >> 4u); - - /* ya + yc */ - s1 = (pSrc[(2u * i0) + 1u] >> 4u) + (pSrc[(2u * i2) + 1u] >> 4u); - /* ya - yc */ - s2 = (pSrc[(2u * i0) + 1u] >> 4u) - (pSrc[(2u * i2) + 1u] >> 4u); - - /* xb + xd */ - t1 = (pSrc[2u * i1] >> 4u) + (pSrc[2u * i3] >> 4u); - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1); - /* (xa + xc) - (xb + xd) */ - r1 = r1 - t1; - /* yb + yd */ - t2 = (pSrc[(2u * i1) + 1u] >> 4u) + (pSrc[(2u * i3) + 1u] >> 4u); - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2); - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* yb - yd */ - t1 = (pSrc[(2u * i1) + 1u] >> 4u) - (pSrc[(2u * i3) + 1u] >> 4u); - /* xb - xd */ - t2 = (pSrc[2u * i1] >> 4u) - (pSrc[2u * i3] >> 4u); - - /* index calculation for the coefficients */ - ia2 = 2u * ia1; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32)) + - ((int32_t) (((q63_t) s1 * si2) >> 32))) << 1u; - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (((int32_t) (((q63_t) s1 * co2) >> 32)) - - ((int32_t) (((q63_t) r1 * si2) >> 32))) << 1u; - - /* (xa - xc) + (yb - yd) */ - r1 = r2 + t1; - /* (xa - xc) - (yb - yd) */ - r2 = r2 - t1; - - /* (ya - yc) - (xb - xd) */ - s1 = s2 - t2; - /* (ya - yc) + (xb - xd) */ - s2 = s2 + t2; - - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) + - ((int32_t) (((q63_t) s1 * si1) >> 32))) << 1u; - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) - - ((int32_t) (((q63_t) r1 * si1) >> 32))) << 1u; - - /* index calculation for the coefficients */ - ia3 = 3u * ia1; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (((int32_t) (((q63_t) r2 * co3) >> 32)) + - ((int32_t) (((q63_t) s2 * si3) >> 32))) << 1u; - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) - - ((int32_t) (((q63_t) r2 * si3) >> 32))) << 1u; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - - /* end of first stage process */ - - /* data is in 5.27(q27) format */ - - - /* start of Middle stages process */ - - - /* each stage in middle stages provides two down scaling of the input */ - - twidCoefModifier <<= 2u; - - - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the first stage */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - /* Calculation of first stage */ - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = pSrc[2u * i0] + pSrc[2u * i2]; - /* xa - xc */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1) >> 2u; - /* xa + xc -(xb + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2) >> 2u; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb - yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - /* (xb - xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32)) + - ((int32_t) (((q63_t) s1 * si2) >> 32))) >> 1u; - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (((int32_t) (((q63_t) s1 * co2) >> 32)) - - ((int32_t) (((q63_t) r1 * si2) >> 32))) >> 1u; - - /* (xa - xc) + (yb - yd) */ - r1 = r2 + t1; - /* (xa - xc) - (yb - yd) */ - r2 = r2 - t1; - - /* (ya - yc) - (xb - xd) */ - s1 = s2 - t2; - /* (ya - yc) + (xb - xd) */ - s2 = s2 + t2; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) + - ((int32_t) (((q63_t) s1 * si1) >> 32))) >> 1u; - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) - - ((int32_t) (((q63_t) r1 * si1) >> 32))) >> 1u; - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (((int32_t) (((q63_t) r2 * co3) >> 32)) + - ((int32_t) (((q63_t) s2 * si3) >> 32))) >> 1u; - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) - - ((int32_t) (((q63_t) r2 * si3) >> 32))) >> 1u; - } - } - twidCoefModifier <<= 2u; - } - - /* End of Middle stages process */ - - /* data is in 11.21(q21) format for the 1024 point as there are 3 middle stages */ - /* data is in 9.23(q23) format for the 256 point as there are 2 middle stages */ - /* data is in 7.25(q25) format for the 64 point as there are 1 middle stage */ - /* data is in 5.27(q27) format for the 16 point as there are no middle stages */ - - - /* start of Last stage process */ - - /* Initializations of last stage */ - n1 = n2; - n2 >>= 2u; - - /* Calculations of last stage */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xb */ - r1 = pSrc[2u * i0] + pSrc[2u * i2]; - /* xa - xb */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xc + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1); - /* (xa + xb) - (xc + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2); - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb-yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - /* (xb-xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = r1; - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = s1; - - /* (xa+yb-xc-yd) */ - r1 = r2 + t1; - /* (xa-yb-xc+yd) */ - r2 = r2 - t1; - - /* (ya-xb-yc+xd) */ - s1 = s2 - t2; - /* (ya+xb-yc-xd) */ - s2 = s2 + t2; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = r1; - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = s1; - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = r2; - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = s2; - - - } - - /* output is in 11.21(q21) format for the 1024 point */ - /* output is in 9.23(q23) format for the 256 point */ - /* output is in 7.25(q25) format for the 64 point */ - /* output is in 5.27(q27) format for the 16 point */ - - /* End of last stage process */ - -} - - -/** - * @brief Core function for the Q31 CIFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - -/* -* Radix-4 IFFT algorithm used is : -* -* CIFFT uses same twiddle coefficients as CFFT Function -* x[k] = x[n] + (j)k * x[n + fftLen/4] + (-1)k * x[n+fftLen/2] + (-j)k * x[n+3*fftLen/4] -* -* -* IFFT is implemented with following changes in equations from FFT -* -* Input real and imaginary data: -* x(n) = xa + j * ya -* x(n+N/4 ) = xb + j * yb -* x(n+N/2 ) = xc + j * yc -* x(n+3N 4) = xd + j * yd -* -* -* Output real and imaginary data: -* x(4r) = xa'+ j * ya' -* x(4r+1) = xb'+ j * yb' -* x(4r+2) = xc'+ j * yc' -* x(4r+3) = xd'+ j * yd' -* -* -* Twiddle factors for radix-4 IFFT: -* Wn = co1 + j * (si1) -* W2n = co2 + j * (si2) -* W3n = co3 + j * (si3) - -* The real and imaginary output values for the radix-4 butterfly are -* xa' = xa + xb + xc + xd -* ya' = ya + yb + yc + yd -* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) -* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) -* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) -* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) -* xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) -* yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) -* -*/ - -void arm_radix4_butterfly_inverse_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pCoef, - uint32_t twidCoefModifier) -{ - uint32_t n1, n2, ia1, ia2, ia3, i0, i1, i2, i3, j, k; - q31_t t1, t2, r1, r2, s1, s2, co1, co2, co3, si1, si2, si3; - - /* input is be 1.31(q31) format for all FFT sizes */ - /* Total process is divided into three stages */ - /* process first stage, middle stages, & last stage */ - - /* Start of first stage process */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - /* n2 = fftLen/4 */ - n2 >>= 2u; - i0 = 0u; - ia1 = 0u; - - j = n2; - - do - { - - /* input is in 1.31(q31) format and provide 4 guard bits for the input */ - - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = (pSrc[2u * i0] >> 4u) + (pSrc[2u * i2] >> 4u); - /* xa - xc */ - r2 = (pSrc[2u * i0] >> 4u) - (pSrc[2u * i2] >> 4u); - - /* ya + yc */ - s1 = (pSrc[(2u * i0) + 1u] >> 4u) + (pSrc[(2u * i2) + 1u] >> 4u); - /* ya - yc */ - s2 = (pSrc[(2u * i0) + 1u] >> 4u) - (pSrc[(2u * i2) + 1u] >> 4u); - - /* xb + xd */ - t1 = (pSrc[2u * i1] >> 4u) + (pSrc[2u * i3] >> 4u); - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1); - /* (xa + xc) - (xb + xd) */ - r1 = r1 - t1; - /* yb + yd */ - t2 = (pSrc[(2u * i1) + 1u] >> 4u) + (pSrc[(2u * i3) + 1u] >> 4u); - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2); - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* yb - yd */ - t1 = (pSrc[(2u * i1) + 1u] >> 4u) - (pSrc[(2u * i3) + 1u] >> 4u); - /* xb - xd */ - t2 = (pSrc[2u * i1] >> 4u) - (pSrc[2u * i3] >> 4u); - - /* index calculation for the coefficients */ - ia2 = 2u * ia1; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32)) - - ((int32_t) (((q63_t) s1 * si2) >> 32))) << 1u; - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[2u * i1 + 1u] = (((int32_t) (((q63_t) s1 * co2) >> 32)) + - ((int32_t) (((q63_t) r1 * si2) >> 32))) << 1u; - - /* (xa - xc) - (yb - yd) */ - r1 = r2 - t1; - /* (xa - xc) + (yb - yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb - xd) */ - s1 = s2 + t2; - /* (ya - yc) - (xb - xd) */ - s2 = s2 - t2; - - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) - - ((int32_t) (((q63_t) s1 * si1) >> 32))) << 1u; - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) + - ((int32_t) (((q63_t) r1 * si1) >> 32))) << 1u; - - /* index calculation for the coefficients */ - ia3 = 3u * ia1; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (((int32_t) (((q63_t) r2 * co3) >> 32)) - - ((int32_t) (((q63_t) s2 * si3) >> 32))) << 1u; - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) + - ((int32_t) (((q63_t) r2 * si3) >> 32))) << 1u; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - - /* data is in 5.27(q27) format */ - /* each stage provides two down scaling of the input */ - - - /* Start of Middle stages process */ - - twidCoefModifier <<= 2u; - - /* Calculation of second stage to excluding last stage */ - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the first stage */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - for (j = 0; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = pSrc[2u * i0] + pSrc[2u * i2]; - /* xa - xc */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1) >> 2u; - /* xa + xc -(xb + xd) */ - r1 = r1 - t1; - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2) >> 2u; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb - yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - /* (xb - xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32u)) - - ((int32_t) (((q63_t) s1 * si2) >> 32u))) >> 1u; - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = - (((int32_t) (((q63_t) s1 * co2) >> 32u)) + - ((int32_t) (((q63_t) r1 * si2) >> 32u))) >> 1u; - - /* (xa - xc) - (yb - yd) */ - r1 = r2 - t1; - /* (xa - xc) + (yb - yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb - xd) */ - s1 = s2 + t2; - /* (ya - yc) - (xb - xd) */ - s2 = s2 - t2; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) - - ((int32_t) (((q63_t) s1 * si1) >> 32))) >> 1u; - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) + - ((int32_t) (((q63_t) r1 * si1) >> 32))) >> 1u; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[(2u * i3)] = (((int32_t) (((q63_t) r2 * co3) >> 32)) - - ((int32_t) (((q63_t) s2 * si3) >> 32))) >> 1u; - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) + - ((int32_t) (((q63_t) r2 * si3) >> 32))) >> 1u; - } - } - twidCoefModifier <<= 2u; - } - - /* End of Middle stages process */ - - /* data is in 11.21(q21) format for the 1024 point as there are 3 middle stages */ - /* data is in 9.23(q23) format for the 256 point as there are 2 middle stages */ - /* data is in 7.25(q25) format for the 64 point as there are 1 middle stage */ - /* data is in 5.27(q27) format for the 16 point as there are no middle stages */ - - - /* Start of last stage process */ - - - /* Initializations of last stage */ - n1 = n2; - n2 >>= 2u; - - /* Calculations of last stage */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = pSrc[2u * i0] + pSrc[2u * i2]; - /* xa - xc */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xc + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1); - /* (xa + xb) - (xc + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2); - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb-yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - /* (xb-xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = r1; - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = s1; - - /* (xa - xc) - (yb-yd) */ - r1 = r2 - t1; - - /* (xa - xc) + (yb-yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb-xd) */ - s1 = s2 + t2; - - /* (ya - yc) - (xb-xd) */ - s2 = s2 - t2; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = r1; - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = s1; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = r2; - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = s2; - - } - - /* output is in 11.21(q21) format for the 1024 point */ - /* output is in 9.23(q23) format for the 256 point */ - /* output is in 7.25(q25) format for the 64 point */ - /* output is in 5.27(q27) format for the 16 point */ - - /* End of last stage process */ -} - - -/* - * @brief In-place bit reversal function. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table - * @param[in] *pBitRevTab points to bit reversal table. - * @return none. - */ - -void arm_bitreversal_q31( - q31_t * pSrc, - uint32_t fftLen, - uint16_t bitRevFactor, - uint16_t * pBitRevTable) -{ - uint32_t fftLenBy2, fftLenBy2p1, i, j; - q31_t in; - - /* Initializations */ - j = 0u; - fftLenBy2 = fftLen / 2u; - fftLenBy2p1 = (fftLen / 2u) + 1u; - - /* Bit Reversal Implementation */ - for (i = 0u; i <= (fftLenBy2 - 2u); i += 2u) - { - if(i < j) - { - /* pSrc[i] <-> pSrc[j]; */ - in = pSrc[2u * i]; - pSrc[2u * i] = pSrc[2u * j]; - pSrc[2u * j] = in; - - /* pSrc[i+1u] <-> pSrc[j+1u] */ - in = pSrc[(2u * i) + 1u]; - pSrc[(2u * i) + 1u] = pSrc[(2u * j) + 1u]; - pSrc[(2u * j) + 1u] = in; - - /* pSrc[i+fftLenBy2p1] <-> pSrc[j+fftLenBy2p1] */ - in = pSrc[2u * (i + fftLenBy2p1)]; - pSrc[2u * (i + fftLenBy2p1)] = pSrc[2u * (j + fftLenBy2p1)]; - pSrc[2u * (j + fftLenBy2p1)] = in; - - /* pSrc[i+fftLenBy2p1+1u] <-> pSrc[j+fftLenBy2p1+1u] */ - in = pSrc[(2u * (i + fftLenBy2p1)) + 1u]; - pSrc[(2u * (i + fftLenBy2p1)) + 1u] = - pSrc[(2u * (j + fftLenBy2p1)) + 1u]; - pSrc[(2u * (j + fftLenBy2p1)) + 1u] = in; - - } - - /* pSrc[i+1u] <-> pSrc[j+1u] */ - in = pSrc[2u * (i + 1u)]; - pSrc[2u * (i + 1u)] = pSrc[2u * (j + fftLenBy2)]; - pSrc[2u * (j + fftLenBy2)] = in; - - /* pSrc[i+2u] <-> pSrc[j+2u] */ - in = pSrc[(2u * (i + 1u)) + 1u]; - pSrc[(2u * (i + 1u)) + 1u] = pSrc[(2u * (j + fftLenBy2)) + 1u]; - pSrc[(2u * (j + fftLenBy2)) + 1u] = in; - - /* Reading the index for the bit reversal */ - j = *pBitRevTable; - - /* Updating the bit reversal index depending on the fft length */ - pBitRevTable += bitRevFactor; - } -} +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_cfft_radix4_q31.c +* +* Description: This file has function definition of Radix-4 FFT & IFFT function and +* In-place bit reversal using bit reversal table +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.5 2010/04/26 +* incorporated review comments and updated with latest CMSIS layer +* +* Version 0.0.3 2010/03/10 +* Initial version +* -------------------------------------------------------------------- */ +#include "arm_math.h" + + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup CFFT_CIFFT + * @{ + */ + +/** + * @details + * @brief Processing function for the Q31 CFFT/CIFFT. + * @param[in] *S points to an instance of the Q31 CFFT/CIFFT structure. + * @param[in, out] *pSrc points to the complex data buffer of size 2*fftLen. Processing occurs in-place. + * @return none. + * + * \par Input and output formats: + * \par + * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. + * Hence the output format is different for different FFT sizes. + * The input and output formats for different FFT sizes and number of bits to upscale are mentioned in the tables below for CFFT and CIFFT: + * \par + * \image html CFFTQ31.gif "Input and Output Formats for Q31 CFFT" + * \image html CIFFTQ31.gif "Input and Output Formats for Q31 CIFFT" + * + */ + +void arm_cfft_radix4_q31( + const arm_cfft_radix4_instance_q31 * S, + q31_t * pSrc) +{ + if(S->ifftFlag == 1u) + { + /* Complex IFFT radix-4 */ + arm_radix4_butterfly_inverse_q31(pSrc, S->fftLen, S->pTwiddle, + S->twidCoefModifier); + } + else + { + /* Complex FFT radix-4 */ + arm_radix4_butterfly_q31(pSrc, S->fftLen, S->pTwiddle, + S->twidCoefModifier); + } + + + if(S->bitReverseFlag == 1u) + { + /* Bit Reversal */ + arm_bitreversal_q31(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); + } + +} + +/** + * @} end of CFFT_CIFFT group + */ + +/* +* Radix-4 FFT algorithm used is : +* +* Input real and imaginary data: +* x(n) = xa + j * ya +* x(n+N/4 ) = xb + j * yb +* x(n+N/2 ) = xc + j * yc +* x(n+3N 4) = xd + j * yd +* +* +* Output real and imaginary data: +* x(4r) = xa'+ j * ya' +* x(4r+1) = xb'+ j * yb' +* x(4r+2) = xc'+ j * yc' +* x(4r+3) = xd'+ j * yd' +* +* +* Twiddle factors for radix-4 FFT: +* Wn = co1 + j * (- si1) +* W2n = co2 + j * (- si2) +* W3n = co3 + j * (- si3) +* +* Butterfly implementation: +* xa' = xa + xb + xc + xd +* ya' = ya + yb + yc + yd +* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) +* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) +* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) +* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) +* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) +* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) +* +*/ + +/** + * @brief Core function for the Q31 CFFT butterfly process. + * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef points to twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + +void arm_radix4_butterfly_q31( + q31_t * pSrc, + uint32_t fftLen, + q31_t * pCoef, + uint32_t twidCoefModifier) +{ + uint32_t n1, n2, ia1, ia2, ia3, i0, i1, i2, i3, j, k; + q31_t t1, t2, r1, r2, s1, s2, co1, co2, co3, si1, si2, si3; + + + /* Total process is divided into three stages */ + + /* process first stage, middle stages, & last stage */ + + + /* start of first stage process */ + + /* Initializations for the first stage */ + n2 = fftLen; + n1 = n2; + /* n2 = fftLen/4 */ + n2 >>= 2u; + i0 = 0u; + ia1 = 0u; + + j = n2; + + /* Calculation of first stage */ + do + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* input is in 1.31(q31) format and provide 4 guard bits for the input */ + + /* Butterfly implementation */ + /* xa + xc */ + r1 = (pSrc[(2u * i0)] >> 4u) + (pSrc[(2u * i2)] >> 4u); + /* xa - xc */ + r2 = (pSrc[2u * i0] >> 4u) - (pSrc[2u * i2] >> 4u); + + /* ya + yc */ + s1 = (pSrc[(2u * i0) + 1u] >> 4u) + (pSrc[(2u * i2) + 1u] >> 4u); + /* ya - yc */ + s2 = (pSrc[(2u * i0) + 1u] >> 4u) - (pSrc[(2u * i2) + 1u] >> 4u); + + /* xb + xd */ + t1 = (pSrc[2u * i1] >> 4u) + (pSrc[2u * i3] >> 4u); + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = (r1 + t1); + /* (xa + xc) - (xb + xd) */ + r1 = r1 - t1; + /* yb + yd */ + t2 = (pSrc[(2u * i1) + 1u] >> 4u) + (pSrc[(2u * i3) + 1u] >> 4u); + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = (s1 + t2); + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* yb - yd */ + t1 = (pSrc[(2u * i1) + 1u] >> 4u) - (pSrc[(2u * i3) + 1u] >> 4u); + /* xb - xd */ + t2 = (pSrc[2u * i1] >> 4u) - (pSrc[2u * i3] >> 4u); + + /* index calculation for the coefficients */ + ia2 = 2u * ia1; + co2 = pCoef[ia2 * 2u]; + si2 = pCoef[(ia2 * 2u) + 1u]; + + /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32)) + + ((int32_t) (((q63_t) s1 * si2) >> 32))) << 1u; + + /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = (((int32_t) (((q63_t) s1 * co2) >> 32)) - + ((int32_t) (((q63_t) r1 * si2) >> 32))) << 1u; + + /* (xa - xc) + (yb - yd) */ + r1 = r2 + t1; + /* (xa - xc) - (yb - yd) */ + r2 = r2 - t1; + + /* (ya - yc) - (xb - xd) */ + s1 = s2 - t2; + /* (ya - yc) + (xb - xd) */ + s2 = s2 + t2; + + co1 = pCoef[ia1 * 2u]; + si1 = pCoef[(ia1 * 2u) + 1u]; + + /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) + + ((int32_t) (((q63_t) s1 * si1) >> 32))) << 1u; + + /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) - + ((int32_t) (((q63_t) r1 * si1) >> 32))) << 1u; + + /* index calculation for the coefficients */ + ia3 = 3u * ia1; + co3 = pCoef[ia3 * 2u]; + si3 = pCoef[(ia3 * 2u) + 1u]; + + /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = (((int32_t) (((q63_t) r2 * co3) >> 32)) + + ((int32_t) (((q63_t) s2 * si3) >> 32))) << 1u; + + /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) - + ((int32_t) (((q63_t) r2 * si3) >> 32))) << 1u; + + /* Twiddle coefficients index modifier */ + ia1 = ia1 + twidCoefModifier; + + /* Updating input index */ + i0 = i0 + 1u; + + } while(--j); + + /* end of first stage process */ + + /* data is in 5.27(q27) format */ + + + /* start of Middle stages process */ + + + /* each stage in middle stages provides two down scaling of the input */ + + twidCoefModifier <<= 2u; + + + for (k = fftLen / 4u; k > 4u; k >>= 2u) + { + /* Initializations for the first stage */ + n1 = n2; + n2 >>= 2u; + ia1 = 0u; + + /* Calculation of first stage */ + for (j = 0u; j <= (n2 - 1u); j++) + { + /* index calculation for the coefficients */ + ia2 = ia1 + ia1; + ia3 = ia2 + ia1; + co1 = pCoef[ia1 * 2u]; + si1 = pCoef[(ia1 * 2u) + 1u]; + co2 = pCoef[ia2 * 2u]; + si2 = pCoef[(ia2 * 2u) + 1u]; + co3 = pCoef[ia3 * 2u]; + si3 = pCoef[(ia3 * 2u) + 1u]; + /* Twiddle coefficients index modifier */ + ia1 = ia1 + twidCoefModifier; + + for (i0 = j; i0 < fftLen; i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Butterfly implementation */ + /* xa + xc */ + r1 = pSrc[2u * i0] + pSrc[2u * i2]; + /* xa - xc */ + r2 = pSrc[2u * i0] - pSrc[2u * i2]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xb + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = (r1 + t1) >> 2u; + /* xa + xc -(xb + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = (s1 + t2) >> 2u; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb - yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + /* (xb - xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32)) + + ((int32_t) (((q63_t) s1 * si2) >> 32))) >> 1u; + + /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = (((int32_t) (((q63_t) s1 * co2) >> 32)) - + ((int32_t) (((q63_t) r1 * si2) >> 32))) >> 1u; + + /* (xa - xc) + (yb - yd) */ + r1 = r2 + t1; + /* (xa - xc) - (yb - yd) */ + r2 = r2 - t1; + + /* (ya - yc) - (xb - xd) */ + s1 = s2 - t2; + /* (ya - yc) + (xb - xd) */ + s2 = s2 + t2; + + /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) + + ((int32_t) (((q63_t) s1 * si1) >> 32))) >> 1u; + + /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) - + ((int32_t) (((q63_t) r1 * si1) >> 32))) >> 1u; + + /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = (((int32_t) (((q63_t) r2 * co3) >> 32)) + + ((int32_t) (((q63_t) s2 * si3) >> 32))) >> 1u; + + /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) - + ((int32_t) (((q63_t) r2 * si3) >> 32))) >> 1u; + } + } + twidCoefModifier <<= 2u; + } + + /* End of Middle stages process */ + + /* data is in 11.21(q21) format for the 1024 point as there are 3 middle stages */ + /* data is in 9.23(q23) format for the 256 point as there are 2 middle stages */ + /* data is in 7.25(q25) format for the 64 point as there are 1 middle stage */ + /* data is in 5.27(q27) format for the 16 point as there are no middle stages */ + + + /* start of Last stage process */ + + /* Initializations of last stage */ + n1 = n2; + n2 >>= 2u; + + /* Calculations of last stage */ + for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Butterfly implementation */ + /* xa + xb */ + r1 = pSrc[2u * i0] + pSrc[2u * i2]; + /* xa - xb */ + r2 = pSrc[2u * i0] - pSrc[2u * i2]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xc + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = (r1 + t1); + /* (xa + xb) - (xc + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = (s1 + t2); + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb-yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + /* (xb-xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = r1; + /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = s1; + + /* (xa+yb-xc-yd) */ + r1 = r2 + t1; + /* (xa-yb-xc+yd) */ + r2 = r2 - t1; + + /* (ya-xb-yc+xd) */ + s1 = s2 - t2; + /* (ya+xb-yc-xd) */ + s2 = s2 + t2; + + /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = r1; + /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = s1; + + /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = r2; + /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = s2; + + + } + + /* output is in 11.21(q21) format for the 1024 point */ + /* output is in 9.23(q23) format for the 256 point */ + /* output is in 7.25(q25) format for the 64 point */ + /* output is in 5.27(q27) format for the 16 point */ + + /* End of last stage process */ + +} + + +/** + * @brief Core function for the Q31 CIFFT butterfly process. + * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. + * @param[in] fftLen length of the FFT. + * @param[in] *pCoef points to twiddle coefficient buffer. + * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + + +/* +* Radix-4 IFFT algorithm used is : +* +* CIFFT uses same twiddle coefficients as CFFT Function +* x[k] = x[n] + (j)k * x[n + fftLen/4] + (-1)k * x[n+fftLen/2] + (-j)k * x[n+3*fftLen/4] +* +* +* IFFT is implemented with following changes in equations from FFT +* +* Input real and imaginary data: +* x(n) = xa + j * ya +* x(n+N/4 ) = xb + j * yb +* x(n+N/2 ) = xc + j * yc +* x(n+3N 4) = xd + j * yd +* +* +* Output real and imaginary data: +* x(4r) = xa'+ j * ya' +* x(4r+1) = xb'+ j * yb' +* x(4r+2) = xc'+ j * yc' +* x(4r+3) = xd'+ j * yd' +* +* +* Twiddle factors for radix-4 IFFT: +* Wn = co1 + j * (si1) +* W2n = co2 + j * (si2) +* W3n = co3 + j * (si3) + +* The real and imaginary output values for the radix-4 butterfly are +* xa' = xa + xb + xc + xd +* ya' = ya + yb + yc + yd +* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) +* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) +* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) +* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) +* xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) +* yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) +* +*/ + +void arm_radix4_butterfly_inverse_q31( + q31_t * pSrc, + uint32_t fftLen, + q31_t * pCoef, + uint32_t twidCoefModifier) +{ + uint32_t n1, n2, ia1, ia2, ia3, i0, i1, i2, i3, j, k; + q31_t t1, t2, r1, r2, s1, s2, co1, co2, co3, si1, si2, si3; + + /* input is be 1.31(q31) format for all FFT sizes */ + /* Total process is divided into three stages */ + /* process first stage, middle stages, & last stage */ + + /* Start of first stage process */ + + /* Initializations for the first stage */ + n2 = fftLen; + n1 = n2; + /* n2 = fftLen/4 */ + n2 >>= 2u; + i0 = 0u; + ia1 = 0u; + + j = n2; + + do + { + + /* input is in 1.31(q31) format and provide 4 guard bits for the input */ + + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Butterfly implementation */ + /* xa + xc */ + r1 = (pSrc[2u * i0] >> 4u) + (pSrc[2u * i2] >> 4u); + /* xa - xc */ + r2 = (pSrc[2u * i0] >> 4u) - (pSrc[2u * i2] >> 4u); + + /* ya + yc */ + s1 = (pSrc[(2u * i0) + 1u] >> 4u) + (pSrc[(2u * i2) + 1u] >> 4u); + /* ya - yc */ + s2 = (pSrc[(2u * i0) + 1u] >> 4u) - (pSrc[(2u * i2) + 1u] >> 4u); + + /* xb + xd */ + t1 = (pSrc[2u * i1] >> 4u) + (pSrc[2u * i3] >> 4u); + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = (r1 + t1); + /* (xa + xc) - (xb + xd) */ + r1 = r1 - t1; + /* yb + yd */ + t2 = (pSrc[(2u * i1) + 1u] >> 4u) + (pSrc[(2u * i3) + 1u] >> 4u); + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = (s1 + t2); + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* yb - yd */ + t1 = (pSrc[(2u * i1) + 1u] >> 4u) - (pSrc[(2u * i3) + 1u] >> 4u); + /* xb - xd */ + t2 = (pSrc[2u * i1] >> 4u) - (pSrc[2u * i3] >> 4u); + + /* index calculation for the coefficients */ + ia2 = 2u * ia1; + co2 = pCoef[ia2 * 2u]; + si2 = pCoef[(ia2 * 2u) + 1u]; + + /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32)) - + ((int32_t) (((q63_t) s1 * si2) >> 32))) << 1u; + + /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ + pSrc[2u * i1 + 1u] = (((int32_t) (((q63_t) s1 * co2) >> 32)) + + ((int32_t) (((q63_t) r1 * si2) >> 32))) << 1u; + + /* (xa - xc) - (yb - yd) */ + r1 = r2 - t1; + /* (xa - xc) + (yb - yd) */ + r2 = r2 + t1; + + /* (ya - yc) + (xb - xd) */ + s1 = s2 + t2; + /* (ya - yc) - (xb - xd) */ + s2 = s2 - t2; + + co1 = pCoef[ia1 * 2u]; + si1 = pCoef[(ia1 * 2u) + 1u]; + + /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) - + ((int32_t) (((q63_t) s1 * si1) >> 32))) << 1u; + + /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) + + ((int32_t) (((q63_t) r1 * si1) >> 32))) << 1u; + + /* index calculation for the coefficients */ + ia3 = 3u * ia1; + co3 = pCoef[ia3 * 2u]; + si3 = pCoef[(ia3 * 2u) + 1u]; + + /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = (((int32_t) (((q63_t) r2 * co3) >> 32)) - + ((int32_t) (((q63_t) s2 * si3) >> 32))) << 1u; + + /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) + + ((int32_t) (((q63_t) r2 * si3) >> 32))) << 1u; + + /* Twiddle coefficients index modifier */ + ia1 = ia1 + twidCoefModifier; + + /* Updating input index */ + i0 = i0 + 1u; + + } while(--j); + + /* data is in 5.27(q27) format */ + /* each stage provides two down scaling of the input */ + + + /* Start of Middle stages process */ + + twidCoefModifier <<= 2u; + + /* Calculation of second stage to excluding last stage */ + for (k = fftLen / 4u; k > 4u; k >>= 2u) + { + /* Initializations for the first stage */ + n1 = n2; + n2 >>= 2u; + ia1 = 0u; + + for (j = 0; j <= (n2 - 1u); j++) + { + /* index calculation for the coefficients */ + ia2 = ia1 + ia1; + ia3 = ia2 + ia1; + co1 = pCoef[ia1 * 2u]; + si1 = pCoef[(ia1 * 2u) + 1u]; + co2 = pCoef[ia2 * 2u]; + si2 = pCoef[(ia2 * 2u) + 1u]; + co3 = pCoef[ia3 * 2u]; + si3 = pCoef[(ia3 * 2u) + 1u]; + /* Twiddle coefficients index modifier */ + ia1 = ia1 + twidCoefModifier; + + for (i0 = j; i0 < fftLen; i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Butterfly implementation */ + /* xa + xc */ + r1 = pSrc[2u * i0] + pSrc[2u * i2]; + /* xa - xc */ + r2 = pSrc[2u * i0] - pSrc[2u * i2]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xb + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = (r1 + t1) >> 2u; + /* xa + xc -(xb + xd) */ + r1 = r1 - t1; + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = (s1 + t2) >> 2u; + + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb - yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + /* (xb - xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32u)) - + ((int32_t) (((q63_t) s1 * si2) >> 32u))) >> 1u; + + /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = + (((int32_t) (((q63_t) s1 * co2) >> 32u)) + + ((int32_t) (((q63_t) r1 * si2) >> 32u))) >> 1u; + + /* (xa - xc) - (yb - yd) */ + r1 = r2 - t1; + /* (xa - xc) + (yb - yd) */ + r2 = r2 + t1; + + /* (ya - yc) + (xb - xd) */ + s1 = s2 + t2; + /* (ya - yc) - (xb - xd) */ + s2 = s2 - t2; + + /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) - + ((int32_t) (((q63_t) s1 * si1) >> 32))) >> 1u; + + /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) + + ((int32_t) (((q63_t) r1 * si1) >> 32))) >> 1u; + + /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ + pSrc[(2u * i3)] = (((int32_t) (((q63_t) r2 * co3) >> 32)) - + ((int32_t) (((q63_t) s2 * si3) >> 32))) >> 1u; + + /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) + + ((int32_t) (((q63_t) r2 * si3) >> 32))) >> 1u; + } + } + twidCoefModifier <<= 2u; + } + + /* End of Middle stages process */ + + /* data is in 11.21(q21) format for the 1024 point as there are 3 middle stages */ + /* data is in 9.23(q23) format for the 256 point as there are 2 middle stages */ + /* data is in 7.25(q25) format for the 64 point as there are 1 middle stage */ + /* data is in 5.27(q27) format for the 16 point as there are no middle stages */ + + + /* Start of last stage process */ + + + /* Initializations of last stage */ + n1 = n2; + n2 >>= 2u; + + /* Calculations of last stage */ + for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) + { + /* index calculation for the input as, */ + /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ + i1 = i0 + n2; + i2 = i1 + n2; + i3 = i2 + n2; + + /* Butterfly implementation */ + /* xa + xc */ + r1 = pSrc[2u * i0] + pSrc[2u * i2]; + /* xa - xc */ + r2 = pSrc[2u * i0] - pSrc[2u * i2]; + + /* ya + yc */ + s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; + /* ya - yc */ + s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; + + /* xc + xd */ + t1 = pSrc[2u * i1] + pSrc[2u * i3]; + /* xa' = xa + xb + xc + xd */ + pSrc[2u * i0] = (r1 + t1); + /* (xa + xb) - (xc + xd) */ + r1 = r1 - t1; + + /* yb + yd */ + t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; + /* ya' = ya + yb + yc + yd */ + pSrc[(2u * i0) + 1u] = (s1 + t2); + /* (ya + yc) - (yb + yd) */ + s1 = s1 - t2; + + /* (yb-yd) */ + t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; + /* (xb-xd) */ + t2 = pSrc[2u * i1] - pSrc[2u * i3]; + + /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ + pSrc[2u * i1] = r1; + /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ + pSrc[(2u * i1) + 1u] = s1; + + /* (xa - xc) - (yb-yd) */ + r1 = r2 - t1; + + /* (xa - xc) + (yb-yd) */ + r2 = r2 + t1; + + /* (ya - yc) + (xb-xd) */ + s1 = s2 + t2; + + /* (ya - yc) - (xb-xd) */ + s2 = s2 - t2; + + /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ + pSrc[2u * i2] = r1; + /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ + pSrc[(2u * i2) + 1u] = s1; + + /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ + pSrc[2u * i3] = r2; + /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ + pSrc[(2u * i3) + 1u] = s2; + + } + + /* output is in 11.21(q21) format for the 1024 point */ + /* output is in 9.23(q23) format for the 256 point */ + /* output is in 7.25(q25) format for the 64 point */ + /* output is in 5.27(q27) format for the 16 point */ + + /* End of last stage process */ +} + + +/* + * @brief In-place bit reversal function. + * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. + * @param[in] fftLen length of the FFT. + * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table + * @param[in] *pBitRevTab points to bit reversal table. + * @return none. + */ + +void arm_bitreversal_q31( + q31_t * pSrc, + uint32_t fftLen, + uint16_t bitRevFactor, + uint16_t * pBitRevTable) +{ + uint32_t fftLenBy2, fftLenBy2p1, i, j; + q31_t in; + + /* Initializations */ + j = 0u; + fftLenBy2 = fftLen / 2u; + fftLenBy2p1 = (fftLen / 2u) + 1u; + + /* Bit Reversal Implementation */ + for (i = 0u; i <= (fftLenBy2 - 2u); i += 2u) + { + if(i < j) + { + /* pSrc[i] <-> pSrc[j]; */ + in = pSrc[2u * i]; + pSrc[2u * i] = pSrc[2u * j]; + pSrc[2u * j] = in; + + /* pSrc[i+1u] <-> pSrc[j+1u] */ + in = pSrc[(2u * i) + 1u]; + pSrc[(2u * i) + 1u] = pSrc[(2u * j) + 1u]; + pSrc[(2u * j) + 1u] = in; + + /* pSrc[i+fftLenBy2p1] <-> pSrc[j+fftLenBy2p1] */ + in = pSrc[2u * (i + fftLenBy2p1)]; + pSrc[2u * (i + fftLenBy2p1)] = pSrc[2u * (j + fftLenBy2p1)]; + pSrc[2u * (j + fftLenBy2p1)] = in; + + /* pSrc[i+fftLenBy2p1+1u] <-> pSrc[j+fftLenBy2p1+1u] */ + in = pSrc[(2u * (i + fftLenBy2p1)) + 1u]; + pSrc[(2u * (i + fftLenBy2p1)) + 1u] = + pSrc[(2u * (j + fftLenBy2p1)) + 1u]; + pSrc[(2u * (j + fftLenBy2p1)) + 1u] = in; + + } + + /* pSrc[i+1u] <-> pSrc[j+1u] */ + in = pSrc[2u * (i + 1u)]; + pSrc[2u * (i + 1u)] = pSrc[2u * (j + fftLenBy2)]; + pSrc[2u * (j + fftLenBy2)] = in; + + /* pSrc[i+2u] <-> pSrc[j+2u] */ + in = pSrc[(2u * (i + 1u)) + 1u]; + pSrc[(2u * (i + 1u)) + 1u] = pSrc[(2u * (j + fftLenBy2)) + 1u]; + pSrc[(2u * (j + fftLenBy2)) + 1u] = in; + + /* Reading the index for the bit reversal */ + j = *pBitRevTable; + + /* Updating the bit reversal index depending on the fft length */ + pBitRevTable += bitRevFactor; + } +} diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_f32.c index 2e94a19ab..c9a3ec5ad 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_f32.c @@ -1,450 +1,450 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_f32.c -* -* Description: Processing function of DCT4 & IDCT4 F32. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @defgroup DCT4_IDCT4 DCT Type IV Functions - * Representation of signals by minimum number of values is important for storage and transmission. - * The possibility of large discontinuity between the beginning and end of a period of a signal - * in DFT can be avoided by extending the signal so that it is even-symmetric. - * Discrete Cosine Transform (DCT) is constructed such that its energy is heavily concentrated in the lower part of the - * spectrum and is very widely used in signal and image coding applications. - * The family of DCTs (DCT type- 1,2,3,4) is the outcome of different combinations of homogeneous boundary conditions. - * DCT has an excellent energy-packing capability, hence has many applications and in data compression in particular. - * - * DCT is essentially the Discrete Fourier Transform(DFT) of an even-extended real signal. - * Reordering of the input data makes the computation of DCT just a problem of - * computing the DFT of a real signal with a few additional operations. - * This approach provides regular, simple, and very efficient DCT algorithms for practical hardware and software implementations. - * - * DCT type-II can be implemented using Fast fourier transform (FFT) internally, as the transform is applied on real values, Real FFT can be used. - * DCT4 is implemented using DCT2 as their implementations are similar except with some added pre-processing and post-processing. - * DCT2 implementation can be described in the following steps: - * - Re-ordering input - * - Calculating Real FFT - * - Multiplication of weights and Real FFT output and getting real part from the product. - * - * This process is explained by the block diagram below: - * \image html DCT4.gif "Discrete Cosine Transform - type-IV" - * - * \par Algorithm: - * The N-point type-IV DCT is defined as a real, linear transformation by the formula: - * \image html DCT4Equation.gif - * where k = 0,1,2,.....N-1 - *\par - * Its inverse is defined as follows: - * \image html IDCT4Equation.gif - * where n = 0,1,2,.....N-1 - *\par - * The DCT4 matrices become involutory (i.e. they are self-inverse) by multiplying with an overall scale factor of sqrt(2/N). - * The symmetry of the transform matrix indicates that the fast algorithms for the forward - * and inverse transform computation are identical. - * Note that the implementation of Inverse DCT4 and DCT4 is same, hence same process function can be used for both. - * - * \par Lengths supported by the transform: - * As DCT4 internally uses Real FFT, it supports all the lengths supported by arm_rfft_f32(). - * The library provides separate functions for Q15, Q31, and floating-point data types. - * \par Instance Structure - * The instances for Real FFT and FFT, cosine values table and twiddle factor table are stored in an instance data structure. - * A separate instance structure must be defined for each transform. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Initializes Real FFT as its process function is used internally in DCT4, by calling arm_rfft_init_f32(). - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Manually initialize the instance structure as follows: - *
   
- *arm_dct4_instance_f32 S = {N, Nby2, normalize, pTwiddle, pCosFactor, pRfft, pCfft};   
- *arm_dct4_instance_q31 S = {N, Nby2, normalize, pTwiddle, pCosFactor, pRfft, pCfft};  
- *arm_dct4_instance_q15 S = {N, Nby2, normalize, pTwiddle, pCosFactor, pRfft, pCfft};  
- * 
- * where \c N is the length of the DCT4; \c Nby2 is half of the length of the DCT4; - * \c normalize is normalizing factor used and is equal to sqrt(2/N); - * \c pTwiddle points to the twiddle factor table; - * \c pCosFactor points to the cosFactor table; - * \c pRfft points to the real FFT instance; - * \c pCfft points to the complex FFT instance; - * The CFFT and RFFT structures also needs to be initialized, refer to arm_cfft_radix4_f32() - * and arm_rfft_f32() respectively for details regarding static initialization. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the DCT4 transform functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/** - * @brief Processing function for the floating-point DCT4/IDCT4. - * @param[in] *S points to an instance of the floating-point DCT4/IDCT4 structure. - * @param[in] *pState points to state buffer. - * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. - * @return none. - */ - -void arm_dct4_f32( - const arm_dct4_instance_f32 * S, - float32_t * pState, - float32_t * pInlineBuffer) -{ - uint32_t i; /* Loop counter */ - float32_t *weights = S->pTwiddle; /* Pointer to the Weights table */ - float32_t *cosFact = S->pCosFactor; /* Pointer to the cos factors table */ - float32_t *pS1, *pS2, *pbuff; /* Temporary pointers for input buffer and pState buffer */ - float32_t in; /* Temporary variable */ - - - /* DCT4 computation involves DCT2 (which is calculated using RFFT) - * along with some pre-processing and post-processing. - * Computational procedure is explained as follows: - * (a) Pre-processing involves multiplying input with cos factor, - * r(n) = 2 * u(n) * cos(pi*(2*n+1)/(4*n)) - * where, - * r(n) -- output of preprocessing - * u(n) -- input to preprocessing(actual Source buffer) - * (b) Calculation of DCT2 using FFT is divided into three steps: - * Step1: Re-ordering of even and odd elements of input. - * Step2: Calculating FFT of the re-ordered input. - * Step3: Taking the real part of the product of FFT output and weights. - * (c) Post-processing - DCT4 can be obtained from DCT2 output using the following equation: - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * where, - * Y4 -- DCT4 output, Y2 -- DCT2 output - * (d) Multiplying the output with the normalizing factor sqrt(2/N). - */ - - /*-------- Pre-processing ------------*/ - /* Multiplying input with cos factor i.e. r(n) = 2 * x(n) * cos(pi*(2*n+1)/(4*n)) */ - arm_scale_f32(pInlineBuffer, 2.0f, pInlineBuffer, S->N); - arm_mult_f32(pInlineBuffer, cosFact, pInlineBuffer, S->N); - - /* ---------------------------------------------------------------- - * Step1: Re-ordering of even and odd elements as, - * pState[i] = pInlineBuffer[2*i] and - * pState[N-i-1] = pInlineBuffer[2*i+1] where i = 0 to N/2 - ---------------------------------------------------------------------*/ - - /* pS1 initialized to pState */ - pS1 = pState; - - /* pS2 initialized to pState+N-1, so that it points to the end of the state buffer */ - pS2 = pState + (S->N - 1u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Initializing the loop counter to N/2 >> 2 for loop unrolling by 4 */ - i = (uint32_t) S->Nby2 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = (uint32_t) S->N >> 2u; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. - * Compute 4 outputs at a time */ - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_f32(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_f32(pState, weights, pState, S->N); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* Initializing the loop counter to N >> 2 for loop unrolling by 4 */ - i = ((uint32_t) S->N - 1u) >> 2u; - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ * (float32_t) 0.5; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - i = ((uint32_t) S->N - 1u) % 0x4u; - - while(i > 0u) - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - /* Decrement the loop counter */ - i--; - } - - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = (uint32_t) S->N >> 2u; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. Compute 4 outputs at a time */ - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = in * S->normalize; - - in = *pbuff; - *pbuff++ = in * S->normalize; - - in = *pbuff; - *pbuff++ = in * S->normalize; - - in = *pbuff; - *pbuff++ = in * S->normalize; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initializing the loop counter to N/2 */ - i = (uint32_t) S->Nby2; - - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter */ - i = (uint32_t) S->N; - - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_f32(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_f32(pState, weights, pState, S->N); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ * (float32_t) 0.5; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - /* Initializing the loop counter */ - i = ((uint32_t) S->N - 1u); - - do - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter */ - i = (uint32_t) S->N; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = in * S->normalize; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of DCT4_IDCT4 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_dct4_f32.c +* +* Description: Processing function of DCT4 & IDCT4 F32. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @defgroup DCT4_IDCT4 DCT Type IV Functions + * Representation of signals by minimum number of values is important for storage and transmission. + * The possibility of large discontinuity between the beginning and end of a period of a signal + * in DFT can be avoided by extending the signal so that it is even-symmetric. + * Discrete Cosine Transform (DCT) is constructed such that its energy is heavily concentrated in the lower part of the + * spectrum and is very widely used in signal and image coding applications. + * The family of DCTs (DCT type- 1,2,3,4) is the outcome of different combinations of homogeneous boundary conditions. + * DCT has an excellent energy-packing capability, hence has many applications and in data compression in particular. + * + * DCT is essentially the Discrete Fourier Transform(DFT) of an even-extended real signal. + * Reordering of the input data makes the computation of DCT just a problem of + * computing the DFT of a real signal with a few additional operations. + * This approach provides regular, simple, and very efficient DCT algorithms for practical hardware and software implementations. + * + * DCT type-II can be implemented using Fast fourier transform (FFT) internally, as the transform is applied on real values, Real FFT can be used. + * DCT4 is implemented using DCT2 as their implementations are similar except with some added pre-processing and post-processing. + * DCT2 implementation can be described in the following steps: + * - Re-ordering input + * - Calculating Real FFT + * - Multiplication of weights and Real FFT output and getting real part from the product. + * + * This process is explained by the block diagram below: + * \image html DCT4.gif "Discrete Cosine Transform - type-IV" + * + * \par Algorithm: + * The N-point type-IV DCT is defined as a real, linear transformation by the formula: + * \image html DCT4Equation.gif + * where k = 0,1,2,.....N-1 + *\par + * Its inverse is defined as follows: + * \image html IDCT4Equation.gif + * where n = 0,1,2,.....N-1 + *\par + * The DCT4 matrices become involutory (i.e. they are self-inverse) by multiplying with an overall scale factor of sqrt(2/N). + * The symmetry of the transform matrix indicates that the fast algorithms for the forward + * and inverse transform computation are identical. + * Note that the implementation of Inverse DCT4 and DCT4 is same, hence same process function can be used for both. + * + * \par Lengths supported by the transform: + * As DCT4 internally uses Real FFT, it supports all the lengths supported by arm_rfft_f32(). + * The library provides separate functions for Q15, Q31, and floating-point data types. + * \par Instance Structure + * The instances for Real FFT and FFT, cosine values table and twiddle factor table are stored in an instance data structure. + * A separate instance structure must be defined for each transform. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Initializes Real FFT as its process function is used internally in DCT4, by calling arm_rfft_init_f32(). + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Manually initialize the instance structure as follows: + *
   
+ *arm_dct4_instance_f32 S = {N, Nby2, normalize, pTwiddle, pCosFactor, pRfft, pCfft};   
+ *arm_dct4_instance_q31 S = {N, Nby2, normalize, pTwiddle, pCosFactor, pRfft, pCfft};  
+ *arm_dct4_instance_q15 S = {N, Nby2, normalize, pTwiddle, pCosFactor, pRfft, pCfft};  
+ * 
+ * where \c N is the length of the DCT4; \c Nby2 is half of the length of the DCT4; + * \c normalize is normalizing factor used and is equal to sqrt(2/N); + * \c pTwiddle points to the twiddle factor table; + * \c pCosFactor points to the cosFactor table; + * \c pRfft points to the real FFT instance; + * \c pCfft points to the complex FFT instance; + * The CFFT and RFFT structures also needs to be initialized, refer to arm_cfft_radix4_f32() + * and arm_rfft_f32() respectively for details regarding static initialization. + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the DCT4 transform functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. + */ + + /** + * @addtogroup DCT4_IDCT4 + * @{ + */ + +/** + * @brief Processing function for the floating-point DCT4/IDCT4. + * @param[in] *S points to an instance of the floating-point DCT4/IDCT4 structure. + * @param[in] *pState points to state buffer. + * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. + * @return none. + */ + +void arm_dct4_f32( + const arm_dct4_instance_f32 * S, + float32_t * pState, + float32_t * pInlineBuffer) +{ + uint32_t i; /* Loop counter */ + float32_t *weights = S->pTwiddle; /* Pointer to the Weights table */ + float32_t *cosFact = S->pCosFactor; /* Pointer to the cos factors table */ + float32_t *pS1, *pS2, *pbuff; /* Temporary pointers for input buffer and pState buffer */ + float32_t in; /* Temporary variable */ + + + /* DCT4 computation involves DCT2 (which is calculated using RFFT) + * along with some pre-processing and post-processing. + * Computational procedure is explained as follows: + * (a) Pre-processing involves multiplying input with cos factor, + * r(n) = 2 * u(n) * cos(pi*(2*n+1)/(4*n)) + * where, + * r(n) -- output of preprocessing + * u(n) -- input to preprocessing(actual Source buffer) + * (b) Calculation of DCT2 using FFT is divided into three steps: + * Step1: Re-ordering of even and odd elements of input. + * Step2: Calculating FFT of the re-ordered input. + * Step3: Taking the real part of the product of FFT output and weights. + * (c) Post-processing - DCT4 can be obtained from DCT2 output using the following equation: + * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) + * where, + * Y4 -- DCT4 output, Y2 -- DCT2 output + * (d) Multiplying the output with the normalizing factor sqrt(2/N). + */ + + /*-------- Pre-processing ------------*/ + /* Multiplying input with cos factor i.e. r(n) = 2 * x(n) * cos(pi*(2*n+1)/(4*n)) */ + arm_scale_f32(pInlineBuffer, 2.0f, pInlineBuffer, S->N); + arm_mult_f32(pInlineBuffer, cosFact, pInlineBuffer, S->N); + + /* ---------------------------------------------------------------- + * Step1: Re-ordering of even and odd elements as, + * pState[i] = pInlineBuffer[2*i] and + * pState[N-i-1] = pInlineBuffer[2*i+1] where i = 0 to N/2 + ---------------------------------------------------------------------*/ + + /* pS1 initialized to pState */ + pS1 = pState; + + /* pS2 initialized to pState+N-1, so that it points to the end of the state buffer */ + pS2 = pState + (S->N - 1u); + + /* pbuff initialized to input buffer */ + pbuff = pInlineBuffer; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Initializing the loop counter to N/2 >> 2 for loop unrolling by 4 */ + i = (uint32_t) S->Nby2 >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + do + { + /* Re-ordering of even and odd elements */ + /* pState[i] = pInlineBuffer[2*i] */ + *pS1++ = *pbuff++; + /* pState[N-i-1] = pInlineBuffer[2*i+1] */ + *pS2-- = *pbuff++; + + *pS1++ = *pbuff++; + *pS2-- = *pbuff++; + + *pS1++ = *pbuff++; + *pS2-- = *pbuff++; + + *pS1++ = *pbuff++; + *pS2-- = *pbuff++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + /* pbuff initialized to input buffer */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Initializing the loop counter to N/4 instead of N for loop unrolling */ + i = (uint32_t) S->N >> 2u; + + /* Processing with loop unrolling 4 times as N is always multiple of 4. + * Compute 4 outputs at a time */ + do + { + /* Writing the re-ordered output back to inplace input buffer */ + *pbuff++ = *pS1++; + *pbuff++ = *pS1++; + *pbuff++ = *pS1++; + *pbuff++ = *pS1++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + + /* --------------------------------------------------------- + * Step2: Calculate RFFT for N-point input + * ---------------------------------------------------------- */ + /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ + arm_rfft_f32(S->pRfft, pInlineBuffer, pState); + + /*---------------------------------------------------------------------- + * Step3: Multiply the FFT output with the weights. + *----------------------------------------------------------------------*/ + arm_cmplx_mult_cmplx_f32(pState, weights, pState, S->N); + + /* ----------- Post-processing ---------- */ + /* DCT-IV can be obtained from DCT-II by the equation, + * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) + * Hence, Y4(0) = Y2(0)/2 */ + /* Getting only real part from the output and Converting to DCT-IV */ + + /* Initializing the loop counter to N >> 2 for loop unrolling by 4 */ + i = ((uint32_t) S->N - 1u) >> 2u; + + /* pbuff initialized to input buffer. */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ + in = *pS1++ * (float32_t) 0.5; + /* input buffer acts as inplace, so output values are stored in the input itself. */ + *pbuff++ = in; + + /* pState pointer is incremented twice as the real values are located alternatively in the array */ + pS1++; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + do + { + /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ + /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ + in = *pS1++ - in; + *pbuff++ = in; + /* points to the next real value */ + pS1++; + + in = *pS1++ - in; + *pbuff++ = in; + pS1++; + + in = *pS1++ - in; + *pbuff++ = in; + pS1++; + + in = *pS1++ - in; + *pbuff++ = in; + pS1++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + i = ((uint32_t) S->N - 1u) % 0x4u; + + while(i > 0u) + { + /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ + /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ + in = *pS1++ - in; + *pbuff++ = in; + /* points to the next real value */ + pS1++; + + /* Decrement the loop counter */ + i--; + } + + + /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ + + /* Initializing the loop counter to N/4 instead of N for loop unrolling */ + i = (uint32_t) S->N >> 2u; + + /* pbuff initialized to the pInlineBuffer(now contains the output values) */ + pbuff = pInlineBuffer; + + /* Processing with loop unrolling 4 times as N is always multiple of 4. Compute 4 outputs at a time */ + do + { + /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ + in = *pbuff; + *pbuff++ = in * S->normalize; + + in = *pbuff; + *pbuff++ = in * S->normalize; + + in = *pbuff; + *pbuff++ = in * S->normalize; + + in = *pbuff; + *pbuff++ = in * S->normalize; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initializing the loop counter to N/2 */ + i = (uint32_t) S->Nby2; + + do + { + /* Re-ordering of even and odd elements */ + /* pState[i] = pInlineBuffer[2*i] */ + *pS1++ = *pbuff++; + /* pState[N-i-1] = pInlineBuffer[2*i+1] */ + *pS2-- = *pbuff++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + /* pbuff initialized to input buffer */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Initializing the loop counter */ + i = (uint32_t) S->N; + + do + { + /* Writing the re-ordered output back to inplace input buffer */ + *pbuff++ = *pS1++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + + /* --------------------------------------------------------- + * Step2: Calculate RFFT for N-point input + * ---------------------------------------------------------- */ + /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ + arm_rfft_f32(S->pRfft, pInlineBuffer, pState); + + /*---------------------------------------------------------------------- + * Step3: Multiply the FFT output with the weights. + *----------------------------------------------------------------------*/ + arm_cmplx_mult_cmplx_f32(pState, weights, pState, S->N); + + /* ----------- Post-processing ---------- */ + /* DCT-IV can be obtained from DCT-II by the equation, + * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) + * Hence, Y4(0) = Y2(0)/2 */ + /* Getting only real part from the output and Converting to DCT-IV */ + + /* pbuff initialized to input buffer. */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ + in = *pS1++ * (float32_t) 0.5; + /* input buffer acts as inplace, so output values are stored in the input itself. */ + *pbuff++ = in; + + /* pState pointer is incremented twice as the real values are located alternatively in the array */ + pS1++; + + /* Initializing the loop counter */ + i = ((uint32_t) S->N - 1u); + + do + { + /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ + /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ + in = *pS1++ - in; + *pbuff++ = in; + /* points to the next real value */ + pS1++; + + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + + /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ + + /* Initializing the loop counter */ + i = (uint32_t) S->N; + + /* pbuff initialized to the pInlineBuffer(now contains the output values) */ + pbuff = pInlineBuffer; + + do + { + /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ + in = *pbuff; + *pbuff++ = in * S->normalize; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of DCT4_IDCT4 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_f32.c index 5c55d3579..af576f22a 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_f32.c @@ -1,4208 +1,4208 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_init_f32.c -* -* Description: Initialization function of DCT-4 & IDCT4 F32 -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/* -* @brief Weights Table -*/ - -/** -* \par -* Weights tables are generated using the formula :
weights[n] = e^(-j*n*pi/(2*N))
-* \par -* C command to generate the table -*
   
-* for(i = 0; i< N; i++)   
-* {   
-*    weights[2*i]= cos(i*c);   
-*    weights[(2*i)+1]= -sin(i * c);   
-* } 
-* \par -* Where N is the Number of weights to be calculated and c is pi/(2*N) -* \par -* In the tables below the real and imaginary values are placed alternatively, hence the -* array length is 2*N. -*/ - -static const float32_t Weights_128[256] = { - 1.000000000000000000f, 0.000000000000000000f, 0.999924701839144500f, - -0.012271538285719925f, - 0.999698818696204250f, -0.024541228522912288f, 0.999322384588349540f, - -0.036807222941358832f, - 0.998795456205172410f, -0.049067674327418015f, 0.998118112900149180f, - -0.061320736302208578f, - 0.997290456678690210f, -0.073564563599667426f, 0.996312612182778000f, - -0.085797312344439894f, - 0.995184726672196930f, -0.098017140329560604f, 0.993906970002356060f, - -0.110222207293883060f, - 0.992479534598709970f, -0.122410675199216200f, 0.990902635427780010f, - -0.134580708507126170f, - 0.989176509964781010f, -0.146730474455361750f, 0.987301418157858430f, - -0.158858143333861450f, - 0.985277642388941220f, -0.170961888760301220f, 0.983105487431216290f, - -0.183039887955140950f, - 0.980785280403230430f, -0.195090322016128250f, 0.978317370719627650f, - -0.207111376192218560f, - 0.975702130038528570f, -0.219101240156869800f, 0.972939952205560180f, - -0.231058108280671110f, - 0.970031253194543970f, -0.242980179903263870f, 0.966976471044852070f, - -0.254865659604514570f, - 0.963776065795439840f, -0.266712757474898370f, 0.960430519415565790f, - -0.278519689385053060f, - 0.956940335732208820f, -0.290284677254462330f, 0.953306040354193860f, - -0.302005949319228080f, - 0.949528180593036670f, -0.313681740398891520f, 0.945607325380521280f, - -0.325310292162262930f, - 0.941544065183020810f, -0.336889853392220050f, 0.937339011912574960f, - -0.348418680249434560f, - 0.932992798834738960f, -0.359895036534988110f, 0.928506080473215590f, - -0.371317193951837540f, - 0.923879532511286740f, -0.382683432365089780f, 0.919113851690057770f, - -0.393992040061048100f, - 0.914209755703530690f, -0.405241314004989860f, 0.909167983090522380f, - -0.416429560097637150f, - 0.903989293123443340f, -0.427555093430282080f, 0.898674465693953820f, - -0.438616238538527660f, - 0.893224301195515320f, -0.449611329654606540f, 0.887639620402853930f, - -0.460538710958240010f, - 0.881921264348355050f, -0.471396736825997640f, 0.876070094195406600f, - -0.482183772079122720f, - 0.870086991108711460f, -0.492898192229784040f, 0.863972856121586810f, - -0.503538383725717580f, - 0.857728610000272120f, -0.514102744193221660f, 0.851355193105265200f, - -0.524589682678468950f, - 0.844853565249707120f, -0.534997619887097150f, 0.838224705554838080f, - -0.545324988422046460f, - 0.831469612302545240f, -0.555570233019602180f, 0.824589302785025290f, - -0.565731810783613120f, - 0.817584813151583710f, -0.575808191417845340f, 0.810457198252594770f, - -0.585797857456438860f, - 0.803207531480644940f, -0.595699304492433360f, 0.795836904608883570f, - -0.605511041404325550f, - 0.788346427626606340f, -0.615231590580626820f, 0.780737228572094490f, - -0.624859488142386340f, - 0.773010453362736990f, -0.634393284163645490f, 0.765167265622458960f, - -0.643831542889791390f, - 0.757208846506484570f, -0.653172842953776760f, 0.749136394523459370f, - -0.662415777590171780f, - 0.740951125354959110f, -0.671558954847018330f, 0.732654271672412820f, - -0.680600997795453020f, - 0.724247082951467000f, -0.689540544737066830f, 0.715730825283818590f, - -0.698376249408972920f, - 0.707106781186547570f, -0.707106781186547460f, 0.698376249408972920f, - -0.715730825283818590f, - 0.689540544737066940f, -0.724247082951466890f, 0.680600997795453130f, - -0.732654271672412820f, - 0.671558954847018330f, -0.740951125354959110f, 0.662415777590171780f, - -0.749136394523459260f, - 0.653172842953776760f, -0.757208846506484460f, 0.643831542889791500f, - -0.765167265622458960f, - 0.634393284163645490f, -0.773010453362736990f, 0.624859488142386450f, - -0.780737228572094380f, - 0.615231590580626820f, -0.788346427626606230f, 0.605511041404325550f, - -0.795836904608883460f, - 0.595699304492433470f, -0.803207531480644830f, 0.585797857456438860f, - -0.810457198252594770f, - 0.575808191417845340f, -0.817584813151583710f, 0.565731810783613230f, - -0.824589302785025290f, - 0.555570233019602290f, -0.831469612302545240f, 0.545324988422046460f, - -0.838224705554837970f, - 0.534997619887097260f, -0.844853565249707010f, 0.524589682678468840f, - -0.851355193105265200f, - 0.514102744193221660f, -0.857728610000272120f, 0.503538383725717580f, - -0.863972856121586700f, - 0.492898192229784090f, -0.870086991108711350f, 0.482183772079122830f, - -0.876070094195406600f, - 0.471396736825997810f, -0.881921264348354940f, 0.460538710958240010f, - -0.887639620402853930f, - 0.449611329654606600f, -0.893224301195515320f, 0.438616238538527710f, - -0.898674465693953820f, - 0.427555093430282200f, -0.903989293123443340f, 0.416429560097637320f, - -0.909167983090522270f, - 0.405241314004989860f, -0.914209755703530690f, 0.393992040061048100f, - -0.919113851690057770f, - 0.382683432365089840f, -0.923879532511286740f, 0.371317193951837600f, - -0.928506080473215480f, - 0.359895036534988280f, -0.932992798834738850f, 0.348418680249434510f, - -0.937339011912574960f, - 0.336889853392220050f, -0.941544065183020810f, 0.325310292162262980f, - -0.945607325380521280f, - 0.313681740398891570f, -0.949528180593036670f, 0.302005949319228200f, - -0.953306040354193750f, - 0.290284677254462330f, -0.956940335732208940f, 0.278519689385053060f, - -0.960430519415565790f, - 0.266712757474898420f, -0.963776065795439840f, 0.254865659604514630f, - -0.966976471044852070f, - 0.242980179903263980f, -0.970031253194543970f, 0.231058108280671280f, - -0.972939952205560070f, - 0.219101240156869770f, -0.975702130038528570f, 0.207111376192218560f, - -0.978317370719627650f, - 0.195090322016128330f, -0.980785280403230430f, 0.183039887955141060f, - -0.983105487431216290f, - 0.170961888760301360f, -0.985277642388941220f, 0.158858143333861390f, - -0.987301418157858430f, - 0.146730474455361750f, -0.989176509964781010f, 0.134580708507126220f, - -0.990902635427780010f, - 0.122410675199216280f, -0.992479534598709970f, 0.110222207293883180f, - -0.993906970002356060f, - 0.098017140329560770f, -0.995184726672196820f, 0.085797312344439880f, - -0.996312612182778000f, - 0.073564563599667454f, -0.997290456678690210f, 0.061320736302208648f, - -0.998118112900149180f, - 0.049067674327418126f, -0.998795456205172410f, 0.036807222941358991f, - -0.999322384588349540f, - 0.024541228522912264f, -0.999698818696204250f, 0.012271538285719944f, - -0.999924701839144500f -}; - -static const float32_t Weights_512[1024] = { - 1.000000000000000000f, 0.000000000000000000f, 0.999995293809576190f, - -0.003067956762965976f, - 0.999981175282601110f, -0.006135884649154475f, 0.999957644551963900f, - -0.009203754782059819f, - 0.999924701839144500f, -0.012271538285719925f, 0.999882347454212560f, - -0.015339206284988100f, - 0.999830581795823400f, -0.018406729905804820f, 0.999769405351215280f, - -0.021474080275469508f, - 0.999698818696204250f, -0.024541228522912288f, 0.999618822495178640f, - -0.027608145778965740f, - 0.999529417501093140f, -0.030674803176636626f, 0.999430604555461730f, - -0.033741171851377580f, - 0.999322384588349540f, -0.036807222941358832f, 0.999204758618363890f, - -0.039872927587739811f, - 0.999077727752645360f, -0.042938256934940820f, 0.998941293186856870f, - -0.046003182130914623f, - 0.998795456205172410f, -0.049067674327418015f, 0.998640218180265270f, - -0.052131704680283324f, - 0.998475580573294770f, -0.055195244349689934f, 0.998301544933892890f, - -0.058258264500435752f, - 0.998118112900149180f, -0.061320736302208578f, 0.997925286198596000f, - -0.064382630929857465f, - 0.997723066644191640f, -0.067443919563664051f, 0.997511456140303450f, - -0.070504573389613856f, - 0.997290456678690210f, -0.073564563599667426f, 0.997060070339482960f, - -0.076623861392031492f, - 0.996820299291165670f, -0.079682437971430126f, 0.996571145790554840f, - -0.082740264549375692f, - 0.996312612182778000f, -0.085797312344439894f, 0.996044700901251970f, - -0.088853552582524600f, - 0.995767414467659820f, -0.091908956497132724f, 0.995480755491926940f, - -0.094963495329638992f, - 0.995184726672196930f, -0.098017140329560604f, 0.994879330794805620f, - -0.101069862754827820f, - 0.994564570734255420f, -0.104121633872054590f, 0.994240449453187900f, - -0.107172424956808840f, - 0.993906970002356060f, -0.110222207293883060f, 0.993564135520595300f, - -0.113270952177564350f, - 0.993211949234794500f, -0.116318630911904750f, 0.992850414459865100f, - -0.119365214810991350f, - 0.992479534598709970f, -0.122410675199216200f, 0.992099313142191800f, - -0.125454983411546230f, - 0.991709753669099530f, -0.128498110793793170f, 0.991310859846115440f, - -0.131540028702883120f, - 0.990902635427780010f, -0.134580708507126170f, 0.990485084256457090f, - -0.137620121586486040f, - 0.990058210262297120f, -0.140658239332849210f, 0.989622017463200890f, - -0.143695033150294470f, - 0.989176509964781010f, -0.146730474455361750f, 0.988721691960323780f, - -0.149764534677321510f, - 0.988257567730749460f, -0.152797185258443440f, 0.987784141644572180f, - -0.155828397654265230f, - 0.987301418157858430f, -0.158858143333861450f, 0.986809401814185530f, - -0.161886393780111830f, - 0.986308097244598670f, -0.164913120489969890f, 0.985797509167567480f, - -0.167938294974731170f, - 0.985277642388941220f, -0.170961888760301220f, 0.984748501801904210f, - -0.173983873387463820f, - 0.984210092386929030f, -0.177004220412148750f, 0.983662419211730250f, - -0.180022901405699510f, - 0.983105487431216290f, -0.183039887955140950f, 0.982539302287441240f, - -0.186055151663446630f, - 0.981963869109555240f, -0.189068664149806190f, 0.981379193313754560f, - -0.192080397049892440f, - 0.980785280403230430f, -0.195090322016128250f, 0.980182135968117430f, - -0.198098410717953560f, - 0.979569765685440520f, -0.201104634842091900f, 0.978948175319062200f, - -0.204108966092816870f, - 0.978317370719627650f, -0.207111376192218560f, 0.977677357824509930f, - -0.210111836880469610f, - 0.977028142657754390f, -0.213110319916091360f, 0.976369731330021140f, - -0.216106797076219520f, - 0.975702130038528570f, -0.219101240156869800f, 0.975025345066994120f, - -0.222093620973203510f, - 0.974339382785575860f, -0.225083911359792830f, 0.973644249650811980f, - -0.228072083170885730f, - 0.972939952205560180f, -0.231058108280671110f, 0.972226497078936270f, - -0.234041958583543430f, - 0.971503890986251780f, -0.237023605994367200f, 0.970772140728950350f, - -0.240003022448741500f, - 0.970031253194543970f, -0.242980179903263870f, 0.969281235356548530f, - -0.245955050335794590f, - 0.968522094274417380f, -0.248927605745720150f, 0.967753837093475510f, - -0.251897818154216970f, - 0.966976471044852070f, -0.254865659604514570f, 0.966190003445412500f, - -0.257831102162158990f, - 0.965394441697689400f, -0.260794117915275510f, 0.964589793289812760f, - -0.263754678974831350f, - 0.963776065795439840f, -0.266712757474898370f, 0.962953266873683880f, - -0.269668325572915090f, - 0.962121404269041580f, -0.272621355449948980f, 0.961280485811320640f, - -0.275571819310958140f, - 0.960430519415565790f, -0.278519689385053060f, 0.959571513081984520f, - -0.281464937925757940f, - 0.958703474895871600f, -0.284407537211271880f, 0.957826413027532910f, - -0.287347459544729510f, - 0.956940335732208820f, -0.290284677254462330f, 0.956045251349996410f, - -0.293219162694258630f, - 0.955141168305770780f, -0.296150888243623790f, 0.954228095109105670f, - -0.299079826308040480f, - 0.953306040354193860f, -0.302005949319228080f, 0.952375012719765880f, - -0.304929229735402370f, - 0.951435020969008340f, -0.307849640041534870f, 0.950486073949481700f, - -0.310767152749611470f, - 0.949528180593036670f, -0.313681740398891520f, 0.948561349915730270f, - -0.316593375556165850f, - 0.947585591017741090f, -0.319502030816015690f, 0.946600913083283530f, - -0.322407678801069850f, - 0.945607325380521280f, -0.325310292162262930f, 0.944604837261480260f, - -0.328209843579092500f, - 0.943593458161960390f, -0.331106305759876430f, 0.942573197601446870f, - -0.333999651442009380f, - 0.941544065183020810f, -0.336889853392220050f, 0.940506070593268300f, - -0.339776884406826850f, - 0.939459223602189920f, -0.342660717311994380f, 0.938403534063108060f, - -0.345541324963989090f, - 0.937339011912574960f, -0.348418680249434560f, 0.936265667170278260f, - -0.351292756085567090f, - 0.935183509938947610f, -0.354163525420490340f, 0.934092550404258980f, - -0.357030961233429980f, - 0.932992798834738960f, -0.359895036534988110f, 0.931884265581668150f, - -0.362755724367397230f, - 0.930766961078983710f, -0.365612997804773850f, 0.929640895843181330f, - -0.368466829953372320f, - 0.928506080473215590f, -0.371317193951837540f, 0.927362525650401110f, - -0.374164062971457930f, - 0.926210242138311380f, -0.377007410216418260f, 0.925049240782677580f, - -0.379847208924051160f, - 0.923879532511286740f, -0.382683432365089780f, 0.922701128333878630f, - -0.385516053843918850f, - 0.921514039342042010f, -0.388345046698826250f, 0.920318276709110590f, - -0.391170384302253870f, - 0.919113851690057770f, -0.393992040061048100f, 0.917900775621390500f, - -0.396809987416710310f, - 0.916679059921042700f, -0.399624199845646790f, 0.915448716088267830f, - -0.402434650859418430f, - 0.914209755703530690f, -0.405241314004989860f, 0.912962190428398210f, - -0.408044162864978690f, - 0.911706032005429880f, -0.410843171057903910f, 0.910441292258067250f, - -0.413638312238434500f, - 0.909167983090522380f, -0.416429560097637150f, 0.907886116487666260f, - -0.419216888363223910f, - 0.906595704514915330f, -0.422000270799799680f, 0.905296759318118820f, - -0.424779681209108810f, - 0.903989293123443340f, -0.427555093430282080f, 0.902673318237258830f, - -0.430326481340082610f, - 0.901348847046022030f, -0.433093818853151960f, 0.900015892016160280f, - -0.435857079922255470f, - 0.898674465693953820f, -0.438616238538527660f, 0.897324580705418320f, - -0.441371268731716670f, - 0.895966249756185220f, -0.444122144570429200f, 0.894599485631382700f, - -0.446868840162374160f, - 0.893224301195515320f, -0.449611329654606540f, 0.891840709392342720f, - -0.452349587233770890f, - 0.890448723244757880f, -0.455083587126343840f, 0.889048355854664570f, - -0.457813303598877170f, - 0.887639620402853930f, -0.460538710958240010f, 0.886222530148880640f, - -0.463259783551860150f, - 0.884797098430937790f, -0.465976495767966180f, 0.883363338665731580f, - -0.468688822035827900f, - 0.881921264348355050f, -0.471396736825997640f, 0.880470889052160750f, - -0.474100214650549970f, - 0.879012226428633530f, -0.476799230063322090f, 0.877545290207261350f, - -0.479493757660153010f, - 0.876070094195406600f, -0.482183772079122720f, 0.874586652278176110f, - -0.484869248000791060f, - 0.873094978418290090f, -0.487550160148436000f, 0.871595086655950980f, - -0.490226483288291160f, - 0.870086991108711460f, -0.492898192229784040f, 0.868570705971340900f, - -0.495565261825772540f, - 0.867046245515692650f, -0.498227666972781870f, 0.865513624090569090f, - -0.500885382611240710f, - 0.863972856121586810f, -0.503538383725717580f, 0.862423956111040610f, - -0.506186645345155230f, - 0.860866938637767310f, -0.508830142543106990f, 0.859301818357008470f, - -0.511468850437970300f, - 0.857728610000272120f, -0.514102744193221660f, 0.856147328375194470f, - -0.516731799017649870f, - 0.854557988365400530f, -0.519355990165589640f, 0.852960604930363630f, - -0.521975292937154390f, - 0.851355193105265200f, -0.524589682678468950f, 0.849741768000852550f, - -0.527199134781901280f, - 0.848120344803297230f, -0.529803624686294610f, 0.846490938774052130f, - -0.532403127877197900f, - 0.844853565249707120f, -0.534997619887097150f, 0.843208239641845440f, - -0.537587076295645390f, - 0.841554977436898440f, -0.540171472729892850f, 0.839893794195999520f, - -0.542750784864515890f, - 0.838224705554838080f, -0.545324988422046460f, 0.836547727223512010f, - -0.547894059173100190f, - 0.834862874986380010f, -0.550457972936604810f, 0.833170164701913190f, - -0.553016705580027470f, - 0.831469612302545240f, -0.555570233019602180f, 0.829761233794523050f, - -0.558118531220556100f, - 0.828045045257755800f, -0.560661576197336030f, 0.826321062845663530f, - -0.563199344013834090f, - 0.824589302785025290f, -0.565731810783613120f, 0.822849781375826430f, - -0.568258952670131490f, - 0.821102514991104650f, -0.570780745886967260f, 0.819347520076796900f, - -0.573297166698042200f, - 0.817584813151583710f, -0.575808191417845340f, 0.815814410806733780f, - -0.578313796411655590f, - 0.814036329705948410f, -0.580813958095764530f, 0.812250586585203880f, - -0.583308652937698290f, - 0.810457198252594770f, -0.585797857456438860f, 0.808656181588174980f, - -0.588281548222645220f, - 0.806847553543799330f, -0.590759701858874160f, 0.805031331142963660f, - -0.593232295039799800f, - 0.803207531480644940f, -0.595699304492433360f, 0.801376171723140240f, - -0.598160706996342270f, - 0.799537269107905010f, -0.600616479383868970f, 0.797690840943391160f, - -0.603066598540348160f, - 0.795836904608883570f, -0.605511041404325550f, 0.793975477554337170f, - -0.607949784967773630f, - 0.792106577300212390f, -0.610382806276309480f, 0.790230221437310030f, - -0.612810082429409710f, - 0.788346427626606340f, -0.615231590580626820f, 0.786455213599085770f, - -0.617647307937803870f, - 0.784556597155575240f, -0.620057211763289100f, 0.782650596166575730f, - -0.622461279374149970f, - 0.780737228572094490f, -0.624859488142386340f, 0.778816512381475980f, - -0.627251815495144080f, - 0.776888465673232440f, -0.629638238914926980f, 0.774953106594873930f, - -0.632018735939809060f, - 0.773010453362736990f, -0.634393284163645490f, 0.771060524261813820f, - -0.636761861236284200f, - 0.769103337645579700f, -0.639124444863775730f, 0.767138911935820400f, - -0.641481012808583160f, - 0.765167265622458960f, -0.643831542889791390f, 0.763188417263381270f, - -0.646176012983316280f, - 0.761202385484261780f, -0.648514401022112440f, 0.759209188978388070f, - -0.650846684996380880f, - 0.757208846506484570f, -0.653172842953776760f, 0.755201376896536550f, - -0.655492852999615350f, - 0.753186799043612520f, -0.657806693297078640f, 0.751165131909686480f, - -0.660114342067420480f, - 0.749136394523459370f, -0.662415777590171780f, 0.747100605980180130f, - -0.664710978203344790f, - 0.745057785441466060f, -0.666999922303637470f, 0.743007952135121720f, - -0.669282588346636010f, - 0.740951125354959110f, -0.671558954847018330f, 0.738887324460615110f, - -0.673829000378756040f, - 0.736816568877369900f, -0.676092703575315920f, 0.734738878095963500f, - -0.678350043129861470f, - 0.732654271672412820f, -0.680600997795453020f, 0.730562769227827590f, - -0.682845546385248080f, - 0.728464390448225200f, -0.685083667772700360f, 0.726359155084346010f, - -0.687315340891759050f, - 0.724247082951467000f, -0.689540544737066830f, 0.722128193929215350f, - -0.691759258364157750f, - 0.720002507961381650f, -0.693971460889654000f, 0.717870045055731710f, - -0.696177131491462990f, - 0.715730825283818590f, -0.698376249408972920f, 0.713584868780793640f, - -0.700568793943248340f, - 0.711432195745216430f, -0.702754744457225300f, 0.709272826438865690f, - -0.704934080375904880f, - 0.707106781186547570f, -0.707106781186547460f, 0.704934080375904990f, - -0.709272826438865580f, - 0.702754744457225300f, -0.711432195745216430f, 0.700568793943248450f, - -0.713584868780793520f, - 0.698376249408972920f, -0.715730825283818590f, 0.696177131491462990f, - -0.717870045055731710f, - 0.693971460889654000f, -0.720002507961381650f, 0.691759258364157750f, - -0.722128193929215350f, - 0.689540544737066940f, -0.724247082951466890f, 0.687315340891759160f, - -0.726359155084346010f, - 0.685083667772700360f, -0.728464390448225200f, 0.682845546385248080f, - -0.730562769227827590f, - 0.680600997795453130f, -0.732654271672412820f, 0.678350043129861580f, - -0.734738878095963390f, - 0.676092703575316030f, -0.736816568877369790f, 0.673829000378756150f, - -0.738887324460615110f, - 0.671558954847018330f, -0.740951125354959110f, 0.669282588346636010f, - -0.743007952135121720f, - 0.666999922303637470f, -0.745057785441465950f, 0.664710978203344900f, - -0.747100605980180130f, - 0.662415777590171780f, -0.749136394523459260f, 0.660114342067420480f, - -0.751165131909686370f, - 0.657806693297078640f, -0.753186799043612410f, 0.655492852999615460f, - -0.755201376896536550f, - 0.653172842953776760f, -0.757208846506484460f, 0.650846684996380990f, - -0.759209188978387960f, - 0.648514401022112550f, -0.761202385484261780f, 0.646176012983316390f, - -0.763188417263381270f, - 0.643831542889791500f, -0.765167265622458960f, 0.641481012808583160f, - -0.767138911935820400f, - 0.639124444863775730f, -0.769103337645579590f, 0.636761861236284200f, - -0.771060524261813710f, - 0.634393284163645490f, -0.773010453362736990f, 0.632018735939809060f, - -0.774953106594873820f, - 0.629638238914927100f, -0.776888465673232440f, 0.627251815495144190f, - -0.778816512381475870f, - 0.624859488142386450f, -0.780737228572094380f, 0.622461279374150080f, - -0.782650596166575730f, - 0.620057211763289210f, -0.784556597155575240f, 0.617647307937803980f, - -0.786455213599085770f, - 0.615231590580626820f, -0.788346427626606230f, 0.612810082429409710f, - -0.790230221437310030f, - 0.610382806276309480f, -0.792106577300212390f, 0.607949784967773740f, - -0.793975477554337170f, - 0.605511041404325550f, -0.795836904608883460f, 0.603066598540348280f, - -0.797690840943391040f, - 0.600616479383868970f, -0.799537269107905010f, 0.598160706996342380f, - -0.801376171723140130f, - 0.595699304492433470f, -0.803207531480644830f, 0.593232295039799800f, - -0.805031331142963660f, - 0.590759701858874280f, -0.806847553543799220f, 0.588281548222645330f, - -0.808656181588174980f, - 0.585797857456438860f, -0.810457198252594770f, 0.583308652937698290f, - -0.812250586585203880f, - 0.580813958095764530f, -0.814036329705948300f, 0.578313796411655590f, - -0.815814410806733780f, - 0.575808191417845340f, -0.817584813151583710f, 0.573297166698042320f, - -0.819347520076796900f, - 0.570780745886967370f, -0.821102514991104650f, 0.568258952670131490f, - -0.822849781375826320f, - 0.565731810783613230f, -0.824589302785025290f, 0.563199344013834090f, - -0.826321062845663420f, - 0.560661576197336030f, -0.828045045257755800f, 0.558118531220556100f, - -0.829761233794523050f, - 0.555570233019602290f, -0.831469612302545240f, 0.553016705580027580f, - -0.833170164701913190f, - 0.550457972936604810f, -0.834862874986380010f, 0.547894059173100190f, - -0.836547727223511890f, - 0.545324988422046460f, -0.838224705554837970f, 0.542750784864516000f, - -0.839893794195999410f, - 0.540171472729892970f, -0.841554977436898330f, 0.537587076295645510f, - -0.843208239641845440f, - 0.534997619887097260f, -0.844853565249707010f, 0.532403127877198010f, - -0.846490938774052020f, - 0.529803624686294830f, -0.848120344803297120f, 0.527199134781901390f, - -0.849741768000852440f, - 0.524589682678468840f, -0.851355193105265200f, 0.521975292937154390f, - -0.852960604930363630f, - 0.519355990165589530f, -0.854557988365400530f, 0.516731799017649980f, - -0.856147328375194470f, - 0.514102744193221660f, -0.857728610000272120f, 0.511468850437970520f, - -0.859301818357008360f, - 0.508830142543106990f, -0.860866938637767310f, 0.506186645345155450f, - -0.862423956111040500f, - 0.503538383725717580f, -0.863972856121586700f, 0.500885382611240940f, - -0.865513624090568980f, - 0.498227666972781870f, -0.867046245515692650f, 0.495565261825772490f, - -0.868570705971340900f, - 0.492898192229784090f, -0.870086991108711350f, 0.490226483288291100f, - -0.871595086655951090f, - 0.487550160148436050f, -0.873094978418290090f, 0.484869248000791120f, - -0.874586652278176110f, - 0.482183772079122830f, -0.876070094195406600f, 0.479493757660153010f, - -0.877545290207261240f, - 0.476799230063322250f, -0.879012226428633410f, 0.474100214650550020f, - -0.880470889052160750f, - 0.471396736825997810f, -0.881921264348354940f, 0.468688822035827960f, - -0.883363338665731580f, - 0.465976495767966130f, -0.884797098430937790f, 0.463259783551860260f, - -0.886222530148880640f, - 0.460538710958240010f, -0.887639620402853930f, 0.457813303598877290f, - -0.889048355854664570f, - 0.455083587126343840f, -0.890448723244757880f, 0.452349587233771000f, - -0.891840709392342720f, - 0.449611329654606600f, -0.893224301195515320f, 0.446868840162374330f, - -0.894599485631382580f, - 0.444122144570429260f, -0.895966249756185110f, 0.441371268731716620f, - -0.897324580705418320f, - 0.438616238538527710f, -0.898674465693953820f, 0.435857079922255470f, - -0.900015892016160280f, - 0.433093818853152010f, -0.901348847046022030f, 0.430326481340082610f, - -0.902673318237258830f, - 0.427555093430282200f, -0.903989293123443340f, 0.424779681209108810f, - -0.905296759318118820f, - 0.422000270799799790f, -0.906595704514915330f, 0.419216888363223960f, - -0.907886116487666150f, - 0.416429560097637320f, -0.909167983090522270f, 0.413638312238434560f, - -0.910441292258067140f, - 0.410843171057903910f, -0.911706032005429880f, 0.408044162864978740f, - -0.912962190428398100f, - 0.405241314004989860f, -0.914209755703530690f, 0.402434650859418540f, - -0.915448716088267830f, - 0.399624199845646790f, -0.916679059921042700f, 0.396809987416710420f, - -0.917900775621390390f, - 0.393992040061048100f, -0.919113851690057770f, 0.391170384302253980f, - -0.920318276709110480f, - 0.388345046698826300f, -0.921514039342041900f, 0.385516053843919020f, - -0.922701128333878520f, - 0.382683432365089840f, -0.923879532511286740f, 0.379847208924051110f, - -0.925049240782677580f, - 0.377007410216418310f, -0.926210242138311270f, 0.374164062971457990f, - -0.927362525650401110f, - 0.371317193951837600f, -0.928506080473215480f, 0.368466829953372320f, - -0.929640895843181330f, - 0.365612997804773960f, -0.930766961078983710f, 0.362755724367397230f, - -0.931884265581668150f, - 0.359895036534988280f, -0.932992798834738850f, 0.357030961233430030f, - -0.934092550404258870f, - 0.354163525420490510f, -0.935183509938947500f, 0.351292756085567150f, - -0.936265667170278260f, - 0.348418680249434510f, -0.937339011912574960f, 0.345541324963989150f, - -0.938403534063108060f, - 0.342660717311994380f, -0.939459223602189920f, 0.339776884406826960f, - -0.940506070593268300f, - 0.336889853392220050f, -0.941544065183020810f, 0.333999651442009490f, - -0.942573197601446870f, - 0.331106305759876430f, -0.943593458161960390f, 0.328209843579092660f, - -0.944604837261480260f, - 0.325310292162262980f, -0.945607325380521280f, 0.322407678801070020f, - -0.946600913083283530f, - 0.319502030816015750f, -0.947585591017741090f, 0.316593375556165850f, - -0.948561349915730270f, - 0.313681740398891570f, -0.949528180593036670f, 0.310767152749611470f, - -0.950486073949481700f, - 0.307849640041534980f, -0.951435020969008340f, 0.304929229735402430f, - -0.952375012719765880f, - 0.302005949319228200f, -0.953306040354193750f, 0.299079826308040480f, - -0.954228095109105670f, - 0.296150888243623960f, -0.955141168305770670f, 0.293219162694258680f, - -0.956045251349996410f, - 0.290284677254462330f, -0.956940335732208940f, 0.287347459544729570f, - -0.957826413027532910f, - 0.284407537211271820f, -0.958703474895871600f, 0.281464937925758050f, - -0.959571513081984520f, - 0.278519689385053060f, -0.960430519415565790f, 0.275571819310958250f, - -0.961280485811320640f, - 0.272621355449948980f, -0.962121404269041580f, 0.269668325572915200f, - -0.962953266873683880f, - 0.266712757474898420f, -0.963776065795439840f, 0.263754678974831510f, - -0.964589793289812650f, - 0.260794117915275570f, -0.965394441697689400f, 0.257831102162158930f, - -0.966190003445412620f, - 0.254865659604514630f, -0.966976471044852070f, 0.251897818154216910f, - -0.967753837093475510f, - 0.248927605745720260f, -0.968522094274417270f, 0.245955050335794590f, - -0.969281235356548530f, - 0.242980179903263980f, -0.970031253194543970f, 0.240003022448741500f, - -0.970772140728950350f, - 0.237023605994367340f, -0.971503890986251780f, 0.234041958583543460f, - -0.972226497078936270f, - 0.231058108280671280f, -0.972939952205560070f, 0.228072083170885790f, - -0.973644249650811870f, - 0.225083911359792780f, -0.974339382785575860f, 0.222093620973203590f, - -0.975025345066994120f, - 0.219101240156869770f, -0.975702130038528570f, 0.216106797076219600f, - -0.976369731330021140f, - 0.213110319916091360f, -0.977028142657754390f, 0.210111836880469720f, - -0.977677357824509930f, - 0.207111376192218560f, -0.978317370719627650f, 0.204108966092817010f, - -0.978948175319062200f, - 0.201104634842091960f, -0.979569765685440520f, 0.198098410717953730f, - -0.980182135968117320f, - 0.195090322016128330f, -0.980785280403230430f, 0.192080397049892380f, - -0.981379193313754560f, - 0.189068664149806280f, -0.981963869109555240f, 0.186055151663446630f, - -0.982539302287441240f, - 0.183039887955141060f, -0.983105487431216290f, 0.180022901405699510f, - -0.983662419211730250f, - 0.177004220412148860f, -0.984210092386929030f, 0.173983873387463850f, - -0.984748501801904210f, - 0.170961888760301360f, -0.985277642388941220f, 0.167938294974731230f, - -0.985797509167567370f, - 0.164913120489970090f, -0.986308097244598670f, 0.161886393780111910f, - -0.986809401814185420f, - 0.158858143333861390f, -0.987301418157858430f, 0.155828397654265320f, - -0.987784141644572180f, - 0.152797185258443410f, -0.988257567730749460f, 0.149764534677321620f, - -0.988721691960323780f, - 0.146730474455361750f, -0.989176509964781010f, 0.143695033150294580f, - -0.989622017463200780f, - 0.140658239332849240f, -0.990058210262297120f, 0.137620121586486180f, - -0.990485084256456980f, - 0.134580708507126220f, -0.990902635427780010f, 0.131540028702883280f, - -0.991310859846115440f, - 0.128498110793793220f, -0.991709753669099530f, 0.125454983411546210f, - -0.992099313142191800f, - 0.122410675199216280f, -0.992479534598709970f, 0.119365214810991350f, - -0.992850414459865100f, - 0.116318630911904880f, -0.993211949234794500f, 0.113270952177564360f, - -0.993564135520595300f, - 0.110222207293883180f, -0.993906970002356060f, 0.107172424956808870f, - -0.994240449453187900f, - 0.104121633872054730f, -0.994564570734255420f, 0.101069862754827880f, - -0.994879330794805620f, - 0.098017140329560770f, -0.995184726672196820f, 0.094963495329639061f, - -0.995480755491926940f, - 0.091908956497132696f, -0.995767414467659820f, 0.088853552582524684f, - -0.996044700901251970f, - 0.085797312344439880f, -0.996312612182778000f, 0.082740264549375803f, - -0.996571145790554840f, - 0.079682437971430126f, -0.996820299291165670f, 0.076623861392031617f, - -0.997060070339482960f, - 0.073564563599667454f, -0.997290456678690210f, 0.070504573389614009f, - -0.997511456140303450f, - 0.067443919563664106f, -0.997723066644191640f, 0.064382630929857410f, - -0.997925286198596000f, - 0.061320736302208648f, -0.998118112900149180f, 0.058258264500435732f, - -0.998301544933892890f, - 0.055195244349690031f, -0.998475580573294770f, 0.052131704680283317f, - -0.998640218180265270f, - 0.049067674327418126f, -0.998795456205172410f, 0.046003182130914644f, - -0.998941293186856870f, - 0.042938256934940959f, -0.999077727752645360f, 0.039872927587739845f, - -0.999204758618363890f, - 0.036807222941358991f, -0.999322384588349540f, 0.033741171851377642f, - -0.999430604555461730f, - 0.030674803176636581f, -0.999529417501093140f, 0.027608145778965820f, - -0.999618822495178640f, - 0.024541228522912264f, -0.999698818696204250f, 0.021474080275469605f, - -0.999769405351215280f, - 0.018406729905804820f, -0.999830581795823400f, 0.015339206284988220f, - -0.999882347454212560f, - 0.012271538285719944f, -0.999924701839144500f, 0.009203754782059960f, - -0.999957644551963900f, - 0.006135884649154515f, -0.999981175282601110f, 0.003067956762966138f, - -0.999995293809576190f -}; - -static const float32_t Weights_2048[4096] = { - 1.000000000000000000f, 0.000000000000000000f, 0.999999705862882230f, - -0.000766990318742704f, - 0.999998823451701880f, -0.001533980186284766f, 0.999997352766978210f, - -0.002300969151425805f, - 0.999995293809576190f, -0.003067956762965976f, 0.999992646580707190f, - -0.003834942569706228f, - 0.999989411081928400f, -0.004601926120448571f, 0.999985587315143200f, - -0.005368906963996343f, - 0.999981175282601110f, -0.006135884649154475f, 0.999976174986897610f, - -0.006902858724729756f, - 0.999970586430974140f, -0.007669828739531097f, 0.999964409618118280f, - -0.008436794242369799f, - 0.999957644551963900f, -0.009203754782059819f, 0.999950291236490480f, - -0.009970709907418031f, - 0.999942349676023910f, -0.010737659167264491f, 0.999933819875236000f, - -0.011504602110422714f, - 0.999924701839144500f, -0.012271538285719925f, 0.999914995573113470f, - -0.013038467241987334f, - 0.999904701082852900f, -0.013805388528060391f, 0.999893818374418490f, - -0.014572301692779064f, - 0.999882347454212560f, -0.015339206284988100f, 0.999870288328982950f, - -0.016106101853537287f, - 0.999857641005823860f, -0.016872987947281710f, 0.999844405492175240f, - -0.017639864115082053f, - 0.999830581795823400f, -0.018406729905804820f, 0.999816169924900410f, - -0.019173584868322623f, - 0.999801169887884260f, -0.019940428551514441f, 0.999785581693599210f, - -0.020707260504265895f, - 0.999769405351215280f, -0.021474080275469508f, 0.999752640870248840f, - -0.022240887414024961f, - 0.999735288260561680f, -0.023007681468839369f, 0.999717347532362190f, - -0.023774461988827555f, - 0.999698818696204250f, -0.024541228522912288f, 0.999679701762987930f, - -0.025307980620024571f, - 0.999659996743959220f, -0.026074717829103901f, 0.999639703650710200f, - -0.026841439699098531f, - 0.999618822495178640f, -0.027608145778965740f, 0.999597353289648380f, - -0.028374835617672099f, - 0.999575296046749220f, -0.029141508764193722f, 0.999552650779456990f, - -0.029908164767516555f, - 0.999529417501093140f, -0.030674803176636626f, 0.999505596225325310f, - -0.031441423540560301f, - 0.999481186966166950f, -0.032208025408304586f, 0.999456189737977340f, - -0.032974608328897335f, - 0.999430604555461730f, -0.033741171851377580f, 0.999404431433671300f, - -0.034507715524795750f, - 0.999377670388002850f, -0.035274238898213947f, 0.999350321434199440f, - -0.036040741520706229f, - 0.999322384588349540f, -0.036807222941358832f, 0.999293859866887790f, - -0.037573682709270494f, - 0.999264747286594420f, -0.038340120373552694f, 0.999235046864595850f, - -0.039106535483329888f, - 0.999204758618363890f, -0.039872927587739811f, 0.999173882565716380f, - -0.040639296235933736f, - 0.999142418724816910f, -0.041405640977076739f, 0.999110367114174890f, - -0.042171961360347947f, - 0.999077727752645360f, -0.042938256934940820f, 0.999044500659429290f, - -0.043704527250063421f, - 0.999010685854073380f, -0.044470771854938668f, 0.998976283356469820f, - -0.045236990298804590f, - 0.998941293186856870f, -0.046003182130914623f, 0.998905715365818290f, - -0.046769346900537863f, - 0.998869549914283560f, -0.047535484156959303f, 0.998832796853527990f, - -0.048301593449480144f, - 0.998795456205172410f, -0.049067674327418015f, 0.998757527991183340f, - -0.049833726340107277f, - 0.998719012233872940f, -0.050599749036899282f, 0.998679908955899090f, - -0.051365741967162593f, - 0.998640218180265270f, -0.052131704680283324f, 0.998599939930320370f, - -0.052897636725665324f, - 0.998559074229759310f, -0.053663537652730520f, 0.998517621102622210f, - -0.054429407010919133f, - 0.998475580573294770f, -0.055195244349689934f, 0.998432952666508440f, - -0.055961049218520569f, - 0.998389737407340160f, -0.056726821166907748f, 0.998345934821212370f, - -0.057492559744367566f, - 0.998301544933892890f, -0.058258264500435752f, 0.998256567771495180f, - -0.059023934984667931f, - 0.998211003360478190f, -0.059789570746639868f, 0.998164851727646240f, - -0.060555171335947788f, - 0.998118112900149180f, -0.061320736302208578f, 0.998070786905482340f, - -0.062086265195060088f, - 0.998022873771486240f, -0.062851757564161406f, 0.997974373526346990f, - -0.063617212959193106f, - 0.997925286198596000f, -0.064382630929857465f, 0.997875611817110150f, - -0.065148011025878833f, - 0.997825350411111640f, -0.065913352797003805f, 0.997774502010167820f, - -0.066678655793001557f, - 0.997723066644191640f, -0.067443919563664051f, 0.997671044343441000f, - -0.068209143658806329f, - 0.997618435138519550f, -0.068974327628266746f, 0.997565239060375750f, - -0.069739471021907307f, - 0.997511456140303450f, -0.070504573389613856f, 0.997457086409941910f, - -0.071269634281296401f, - 0.997402129901275300f, -0.072034653246889332f, 0.997346586646633230f, - -0.072799629836351673f, - 0.997290456678690210f, -0.073564563599667426f, 0.997233740030466280f, - -0.074329454086845756f, - 0.997176436735326190f, -0.075094300847921305f, 0.997118546826979980f, - -0.075859103432954447f, - 0.997060070339482960f, -0.076623861392031492f, 0.997001007307235290f, - -0.077388574275265049f, - 0.996941357764982160f, -0.078153241632794232f, 0.996881121747813850f, - -0.078917863014784942f, - 0.996820299291165670f, -0.079682437971430126f, 0.996758890430818000f, - -0.080446966052950014f, - 0.996696895202896060f, -0.081211446809592441f, 0.996634313643869900f, - -0.081975879791633066f, - 0.996571145790554840f, -0.082740264549375692f, 0.996507391680110820f, - -0.083504600633152432f, - 0.996443051350042630f, -0.084268887593324071f, 0.996378124838200210f, - -0.085033124980280275f, - 0.996312612182778000f, -0.085797312344439894f, 0.996246513422315520f, - -0.086561449236251170f, - 0.996179828595696980f, -0.087325535206192059f, 0.996112557742151130f, - -0.088089569804770507f, - 0.996044700901251970f, -0.088853552582524600f, 0.995976258112917790f, - -0.089617483090022959f, - 0.995907229417411720f, -0.090381360877864983f, 0.995837614855341610f, - -0.091145185496681005f, - 0.995767414467659820f, -0.091908956497132724f, 0.995696628295663520f, - -0.092672673429913310f, - 0.995625256380994310f, -0.093436335845747787f, 0.995553298765638470f, - -0.094199943295393204f, - 0.995480755491926940f, -0.094963495329638992f, 0.995407626602534900f, - -0.095726991499307162f, - 0.995333912140482280f, -0.096490431355252593f, 0.995259612149133390f, - -0.097253814448363271f, - 0.995184726672196930f, -0.098017140329560604f, 0.995109255753726110f, - -0.098780408549799623f, - 0.995033199438118630f, -0.099543618660069319f, 0.994956557770116380f, - -0.100306770211392860f, - 0.994879330794805620f, -0.101069862754827820f, 0.994801518557617110f, - -0.101832895841466530f, - 0.994723121104325700f, -0.102595869022436280f, 0.994644138481050710f, - -0.103358781848899610f, - 0.994564570734255420f, -0.104121633872054590f, 0.994484417910747600f, - -0.104884424643134970f, - 0.994403680057679100f, -0.105647153713410620f, 0.994322357222545810f, - -0.106409820634187680f, - 0.994240449453187900f, -0.107172424956808840f, 0.994157956797789730f, - -0.107934966232653650f, - 0.994074879304879370f, -0.108697444013138720f, 0.993991217023329380f, - -0.109459857849717980f, - 0.993906970002356060f, -0.110222207293883060f, 0.993822138291519660f, - -0.110984491897163390f, - 0.993736721940724600f, -0.111746711211126590f, 0.993650721000219120f, - -0.112508864787378690f, - 0.993564135520595300f, -0.113270952177564350f, 0.993476965552789190f, - -0.114032972933367200f, - 0.993389211148080650f, -0.114794926606510080f, 0.993300872358093280f, - -0.115556812748755260f, - 0.993211949234794500f, -0.116318630911904750f, 0.993122441830495580f, - -0.117080380647800590f, - 0.993032350197851410f, -0.117842061508324980f, 0.992941674389860470f, - -0.118603673045400720f, - 0.992850414459865100f, -0.119365214810991350f, 0.992758570461551140f, - -0.120126686357101500f, - 0.992666142448948020f, -0.120888087235777080f, 0.992573130476428810f, - -0.121649416999105530f, - 0.992479534598709970f, -0.122410675199216200f, 0.992385354870851670f, - -0.123171861388280480f, - 0.992290591348257370f, -0.123932975118512160f, 0.992195244086673920f, - -0.124694015942167640f, - 0.992099313142191800f, -0.125454983411546230f, 0.992002798571244520f, - -0.126215877078990350f, - 0.991905700430609330f, -0.126976696496885870f, 0.991808018777406430f, - -0.127737441217662310f, - 0.991709753669099530f, -0.128498110793793170f, 0.991610905163495370f, - -0.129258704777796140f, - 0.991511473318743900f, -0.130019222722233350f, 0.991411458193338540f, - -0.130779664179711710f, - 0.991310859846115440f, -0.131540028702883120f, 0.991209678336254060f, - -0.132300315844444650f, - 0.991107913723276890f, -0.133060525157139060f, 0.991005566067049370f, - -0.133820656193754720f, - 0.990902635427780010f, -0.134580708507126170f, 0.990799121866020370f, - -0.135340681650134210f, - 0.990695025442664630f, -0.136100575175706200f, 0.990590346218950150f, - -0.136860388636816380f, - 0.990485084256457090f, -0.137620121586486040f, 0.990379239617108160f, - -0.138379773577783890f, - 0.990272812363169110f, -0.139139344163826200f, 0.990165802557248400f, - -0.139898832897777210f, - 0.990058210262297120f, -0.140658239332849210f, 0.989950035541608990f, - -0.141417563022303020f, - 0.989841278458820530f, -0.142176803519448030f, 0.989731939077910570f, - -0.142935960377642670f, - 0.989622017463200890f, -0.143695033150294470f, 0.989511513679355190f, - -0.144454021390860470f, - 0.989400427791380380f, -0.145212924652847460f, 0.989288759864625170f, - -0.145971742489812210f, - 0.989176509964781010f, -0.146730474455361750f, 0.989063678157881540f, - -0.147489120103153570f, - 0.988950264510302990f, -0.148247678986896030f, 0.988836269088763540f, - -0.149006150660348450f, - 0.988721691960323780f, -0.149764534677321510f, 0.988606533192386450f, - -0.150522830591677400f, - 0.988490792852696590f, -0.151281037957330220f, 0.988374471009341280f, - -0.152039156328246050f, - 0.988257567730749460f, -0.152797185258443440f, 0.988140083085692570f, - -0.153555124301993450f, - 0.988022017143283530f, -0.154312973013020100f, 0.987903369972977790f, - -0.155070730945700510f, - 0.987784141644572180f, -0.155828397654265230f, 0.987664332228205710f, - -0.156585972692998430f, - 0.987543941794359230f, -0.157343455616238250f, 0.987422970413855410f, - -0.158100845978376980f, - 0.987301418157858430f, -0.158858143333861450f, 0.987179285097874340f, - -0.159615347237193060f, - 0.987056571305750970f, -0.160372457242928280f, 0.986933276853677710f, - -0.161129472905678810f, - 0.986809401814185530f, -0.161886393780111830f, 0.986684946260146690f, - -0.162643219420950310f, - 0.986559910264775410f, -0.163399949382973230f, 0.986434293901627180f, - -0.164156583221015810f, - 0.986308097244598670f, -0.164913120489969890f, 0.986181320367928270f, - -0.165669560744784120f, - 0.986053963346195440f, -0.166425903540464100f, 0.985926026254321130f, - -0.167182148432072940f, - 0.985797509167567480f, -0.167938294974731170f, 0.985668412161537550f, - -0.168694342723617330f, - 0.985538735312176060f, -0.169450291233967960f, 0.985408478695768420f, - -0.170206140061078070f, - 0.985277642388941220f, -0.170961888760301220f, 0.985146226468662230f, - -0.171717536887049970f, - 0.985014231012239840f, -0.172473083996795950f, 0.984881656097323700f, - -0.173228529645070320f, - 0.984748501801904210f, -0.173983873387463820f, 0.984614768204312600f, - -0.174739114779627200f, - 0.984480455383220930f, -0.175494253377271430f, 0.984345563417641900f, - -0.176249288736167880f, - 0.984210092386929030f, -0.177004220412148750f, 0.984074042370776450f, - -0.177759047961107170f, - 0.983937413449218920f, -0.178513770938997510f, 0.983800205702631600f, - -0.179268388901835750f, - 0.983662419211730250f, -0.180022901405699510f, 0.983524054057571260f, - -0.180777308006728590f, - 0.983385110321551180f, -0.181531608261124970f, 0.983245588085407070f, - -0.182285801725153300f, - 0.983105487431216290f, -0.183039887955140950f, 0.982964808441396440f, - -0.183793866507478450f, - 0.982823551198705240f, -0.184547736938619620f, 0.982681715786240860f, - -0.185301498805081900f, - 0.982539302287441240f, -0.186055151663446630f, 0.982396310786084690f, - -0.186808695070359270f, - 0.982252741366289370f, -0.187562128582529600f, 0.982108594112513610f, - -0.188315451756732120f, - 0.981963869109555240f, -0.189068664149806190f, 0.981818566442552500f, - -0.189821765318656410f, - 0.981672686196983110f, -0.190574754820252740f, 0.981526228458664770f, - -0.191327632211630900f, - 0.981379193313754560f, -0.192080397049892440f, 0.981231580848749730f, - -0.192833048892205230f, - 0.981083391150486710f, -0.193585587295803610f, 0.980934624306141640f, - -0.194338011817988600f, - 0.980785280403230430f, -0.195090322016128250f, 0.980635359529608120f, - -0.195842517447657850f, - 0.980484861773469380f, -0.196594597670080220f, 0.980333787223347960f, - -0.197346562240965920f, - 0.980182135968117430f, -0.198098410717953560f, 0.980029908096990090f, - -0.198850142658750090f, - 0.979877103699517640f, -0.199601757621130970f, 0.979723722865591170f, - -0.200353255162940450f, - 0.979569765685440520f, -0.201104634842091900f, 0.979415232249634780f, - -0.201855896216568050f, - 0.979260122649082020f, -0.202607038844421130f, 0.979104436975029250f, - -0.203358062283773320f, - 0.978948175319062200f, -0.204108966092816870f, 0.978791337773105670f, - -0.204859749829814420f, - 0.978633924429423210f, -0.205610413053099240f, 0.978475935380616830f, - -0.206360955321075510f, - 0.978317370719627650f, -0.207111376192218560f, 0.978158230539735050f, - -0.207861675225075070f, - 0.977998514934557140f, -0.208611851978263490f, 0.977838223998050430f, - -0.209361906010474160f, - 0.977677357824509930f, -0.210111836880469610f, 0.977515916508569280f, - -0.210861644147084860f, - 0.977353900145199960f, -0.211611327369227550f, 0.977191308829712280f, - -0.212360886105878420f, - 0.977028142657754390f, -0.213110319916091360f, 0.976864401725312640f, - -0.213859628358993750f, - 0.976700086128711840f, -0.214608810993786760f, 0.976535195964614470f, - -0.215357867379745550f, - 0.976369731330021140f, -0.216106797076219520f, 0.976203692322270560f, - -0.216855599642632620f, - 0.976037079039039020f, -0.217604274638483640f, 0.975869891578341030f, - -0.218352821623346320f, - 0.975702130038528570f, -0.219101240156869800f, 0.975533794518291360f, - -0.219849529798778700f, - 0.975364885116656980f, -0.220597690108873510f, 0.975195401932990370f, - -0.221345720647030810f, - 0.975025345066994120f, -0.222093620973203510f, 0.974854714618708430f, - -0.222841390647421120f, - 0.974683510688510670f, -0.223589029229789990f, 0.974511733377115720f, - -0.224336536280493600f, - 0.974339382785575860f, -0.225083911359792830f, 0.974166459015280320f, - -0.225831154028026170f, - 0.973992962167955830f, -0.226578263845610000f, 0.973818892345666100f, - -0.227325240373038860f, - 0.973644249650811980f, -0.228072083170885730f, 0.973469034186131070f, - -0.228818791799802220f, - 0.973293246054698250f, -0.229565365820518870f, 0.973116885359925130f, - -0.230311804793845440f, - 0.972939952205560180f, -0.231058108280671110f, 0.972762446695688570f, - -0.231804275841964780f, - 0.972584368934732210f, -0.232550307038775240f, 0.972405719027449770f, - -0.233296201432231590f, - 0.972226497078936270f, -0.234041958583543430f, 0.972046703194623500f, - -0.234787578054000970f, - 0.971866337480279400f, -0.235533059404975490f, 0.971685400042008540f, - -0.236278402197919570f, - 0.971503890986251780f, -0.237023605994367200f, 0.971321810419786160f, - -0.237768670355934190f, - 0.971139158449725090f, -0.238513594844318420f, 0.970955935183517970f, - -0.239258379021299980f, - 0.970772140728950350f, -0.240003022448741500f, 0.970587775194143630f, - -0.240747524688588430f, - 0.970402838687555500f, -0.241491885302869330f, 0.970217331317979160f, - -0.242236103853696010f, - 0.970031253194543970f, -0.242980179903263870f, 0.969844604426714830f, - -0.243724113013852160f, - 0.969657385124292450f, -0.244467902747824150f, 0.969469595397413060f, - -0.245211548667627540f, - 0.969281235356548530f, -0.245955050335794590f, 0.969092305112506210f, - -0.246698407314942410f, - 0.968902804776428870f, -0.247441619167773270f, 0.968712734459794780f, - -0.248184685457074780f, - 0.968522094274417380f, -0.248927605745720150f, 0.968330884332445190f, - -0.249670379596668570f, - 0.968139104746362440f, -0.250413006572965220f, 0.967946755628987800f, - -0.251155486237741920f, - 0.967753837093475510f, -0.251897818154216970f, 0.967560349253314360f, - -0.252640001885695520f, - 0.967366292222328510f, -0.253382036995570160f, 0.967171666114676640f, - -0.254123923047320620f, - 0.966976471044852070f, -0.254865659604514570f, 0.966780707127683270f, - -0.255607246230807380f, - 0.966584374478333120f, -0.256348682489942910f, 0.966387473212298900f, - -0.257089967945753120f, - 0.966190003445412500f, -0.257831102162158990f, 0.965991965293840570f, - -0.258572084703170340f, - 0.965793358874083680f, -0.259312915132886230f, 0.965594184302976830f, - -0.260053593015495190f, - 0.965394441697689400f, -0.260794117915275510f, 0.965194131175724720f, - -0.261534489396595520f, - 0.964993252854920320f, -0.262274707023913590f, 0.964791806853447900f, - -0.263014770361779000f, - 0.964589793289812760f, -0.263754678974831350f, 0.964387212282854290f, - -0.264494432427801630f, - 0.964184063951745830f, -0.265234030285511790f, 0.963980348415994110f, - -0.265973472112875590f, - 0.963776065795439840f, -0.266712757474898370f, 0.963571216210257320f, - -0.267451885936677620f, - 0.963365799780954050f, -0.268190857063403180f, 0.963159816628371360f, - -0.268929670420357260f, - 0.962953266873683880f, -0.269668325572915090f, 0.962746150638399410f, - -0.270406822086544820f, - 0.962538468044359160f, -0.271145159526808010f, 0.962330219213737400f, - -0.271883337459359720f, - 0.962121404269041580f, -0.272621355449948980f, 0.961912023333112210f, - -0.273359213064418680f, - 0.961702076529122540f, -0.274096909868706380f, 0.961491563980579000f, - -0.274834445428843940f, - 0.961280485811320640f, -0.275571819310958140f, 0.961068842145519350f, - -0.276309031081271080f, - 0.960856633107679660f, -0.277046080306099900f, 0.960643858822638590f, - -0.277782966551857690f, - 0.960430519415565790f, -0.278519689385053060f, 0.960216615011963430f, - -0.279256248372291180f, - 0.960002145737665960f, -0.279992643080273220f, 0.959787111718839900f, - -0.280728873075797190f, - 0.959571513081984520f, -0.281464937925757940f, 0.959355349953930790f, - -0.282200837197147560f, - 0.959138622461841890f, -0.282936570457055390f, 0.958921330733213170f, - -0.283672137272668430f, - 0.958703474895871600f, -0.284407537211271880f, 0.958485055077976100f, - -0.285142769840248670f, - 0.958266071408017670f, -0.285877834727080620f, 0.958046524014818600f, - -0.286612731439347790f, - 0.957826413027532910f, -0.287347459544729510f, 0.957605738575646350f, - -0.288082018611004130f, - 0.957384500788975860f, -0.288816408206049480f, 0.957162699797670210f, - -0.289550627897843030f, - 0.956940335732208820f, -0.290284677254462330f, 0.956717408723403050f, - -0.291018555844085090f, - 0.956493918902395100f, -0.291752263234989260f, 0.956269866400658030f, - -0.292485798995553880f, - 0.956045251349996410f, -0.293219162694258630f, 0.955820073882545420f, - -0.293952353899684660f, - 0.955594334130771110f, -0.294685372180514330f, 0.955368032227470350f, - -0.295418217105532010f, - 0.955141168305770780f, -0.296150888243623790f, 0.954913742499130520f, - -0.296883385163778270f, - 0.954685754941338340f, -0.297615707435086200f, 0.954457205766513490f, - -0.298347854626741400f, - 0.954228095109105670f, -0.299079826308040480f, 0.953998423103894490f, - -0.299811622048383350f, - 0.953768189885990330f, -0.300543241417273450f, 0.953537395590833280f, - -0.301274683984317950f, - 0.953306040354193860f, -0.302005949319228080f, 0.953074124312172200f, - -0.302737036991819140f, - 0.952841647601198720f, -0.303467946572011320f, 0.952608610358033350f, - -0.304198677629829110f, - 0.952375012719765880f, -0.304929229735402370f, 0.952140854823815830f, - -0.305659602458966120f, - 0.951906136807932350f, -0.306389795370860920f, 0.951670858810193860f, - -0.307119808041533100f, - 0.951435020969008340f, -0.307849640041534870f, 0.951198623423113230f, - -0.308579290941525090f, - 0.950961666311575080f, -0.309308760312268730f, 0.950724149773789610f, - -0.310038047724637890f, - 0.950486073949481700f, -0.310767152749611470f, 0.950247438978705230f, - -0.311496074958275910f, - 0.950008245001843000f, -0.312224813921824880f, 0.949768492159606680f, - -0.312953369211560200f, - 0.949528180593036670f, -0.313681740398891520f, 0.949287310443502120f, - -0.314409927055336660f, - 0.949045881852700560f, -0.315137928752522440f, 0.948803894962658490f, - -0.315865745062183960f, - 0.948561349915730270f, -0.316593375556165850f, 0.948318246854599090f, - -0.317320819806421740f, - 0.948074585922276230f, -0.318048077385014950f, 0.947830367262101010f, - -0.318775147864118480f, - 0.947585591017741090f, -0.319502030816015690f, 0.947340257333192050f, - -0.320228725813099860f, - 0.947094366352777220f, -0.320955232427875210f, 0.946847918221148000f, - -0.321681550232956580f, - 0.946600913083283530f, -0.322407678801069850f, 0.946353351084490590f, - -0.323133617705052330f, - 0.946105232370403450f, -0.323859366517852850f, 0.945856557086983910f, - -0.324584924812532150f, - 0.945607325380521280f, -0.325310292162262930f, 0.945357537397632290f, - -0.326035468140330240f, - 0.945107193285260610f, -0.326760452320131730f, 0.944856293190677210f, - -0.327485244275178000f, - 0.944604837261480260f, -0.328209843579092500f, 0.944352825645594750f, - -0.328934249805612200f, - 0.944100258491272660f, -0.329658462528587490f, 0.943847135947092690f, - -0.330382481321982780f, - 0.943593458161960390f, -0.331106305759876430f, 0.943339225285107720f, - -0.331829935416461110f, - 0.943084437466093490f, -0.332553369866044220f, 0.942829094854802710f, - -0.333276608683047930f, - 0.942573197601446870f, -0.333999651442009380f, 0.942316745856563780f, - -0.334722497717581220f, - 0.942059739771017310f, -0.335445147084531600f, 0.941802179495997650f, - -0.336167599117744520f, - 0.941544065183020810f, -0.336889853392220050f, 0.941285396983928660f, - -0.337611909483074620f, - 0.941026175050889260f, -0.338333766965541130f, 0.940766399536396070f, - -0.339055425414969640f, - 0.940506070593268300f, -0.339776884406826850f, 0.940245188374650880f, - -0.340498143516697160f, - 0.939983753034014050f, -0.341219202320282360f, 0.939721764725153340f, - -0.341940060393402190f, - 0.939459223602189920f, -0.342660717311994380f, 0.939196129819569900f, - -0.343381172652115040f, - 0.938932483532064600f, -0.344101425989938810f, 0.938668284894770170f, - -0.344821476901759290f, - 0.938403534063108060f, -0.345541324963989090f, 0.938138231192824360f, - -0.346260969753160010f, - 0.937872376439989890f, -0.346980410845923680f, 0.937605969960999990f, - -0.347699647819051380f, - 0.937339011912574960f, -0.348418680249434560f, 0.937071502451759190f, - -0.349137507714084970f, - 0.936803441735921560f, -0.349856129790134920f, 0.936534829922755500f, - -0.350574546054837510f, - 0.936265667170278260f, -0.351292756085567090f, 0.935995953636831410f, - -0.352010759459819080f, - 0.935725689481080370f, -0.352728555755210730f, 0.935454874862014620f, - -0.353446144549480810f, - 0.935183509938947610f, -0.354163525420490340f, 0.934911594871516090f, - -0.354880697946222790f, - 0.934639129819680780f, -0.355597661704783850f, 0.934366114943725790f, - -0.356314416274402410f, - 0.934092550404258980f, -0.357030961233429980f, 0.933818436362210960f, - -0.357747296160341900f, - 0.933543772978836170f, -0.358463420633736540f, 0.933268560415712050f, - -0.359179334232336500f, - 0.932992798834738960f, -0.359895036534988110f, 0.932716488398140250f, - -0.360610527120662270f, - 0.932439629268462360f, -0.361325805568454280f, 0.932162221608574430f, - -0.362040871457584180f, - 0.931884265581668150f, -0.362755724367397230f, 0.931605761351257830f, - -0.363470363877363760f, - 0.931326709081180430f, -0.364184789567079890f, 0.931047108935595280f, - -0.364899001016267320f, - 0.930766961078983710f, -0.365612997804773850f, 0.930486265676149780f, - -0.366326779512573590f, - 0.930205022892219070f, -0.367040345719767180f, 0.929923232892639670f, - -0.367753696006581980f, - 0.929640895843181330f, -0.368466829953372320f, 0.929358011909935500f, - -0.369179747140620020f, - 0.929074581259315860f, -0.369892447148934100f, 0.928790604058057020f, - -0.370604929559051670f, - 0.928506080473215590f, -0.371317193951837540f, 0.928221010672169440f, - -0.372029239908285010f, - 0.927935394822617890f, -0.372741067009515760f, 0.927649233092581180f, - -0.373452674836780300f, - 0.927362525650401110f, -0.374164062971457930f, 0.927075272664740100f, - -0.374875230995057540f, - 0.926787474304581750f, -0.375586178489217220f, 0.926499130739230510f, - -0.376296905035704790f, - 0.926210242138311380f, -0.377007410216418260f, 0.925920808671770070f, - -0.377717693613385640f, - 0.925630830509872720f, -0.378427754808765560f, 0.925340307823206310f, - -0.379137593384847320f, - 0.925049240782677580f, -0.379847208924051160f, 0.924757629559513910f, - -0.380556601008928520f, - 0.924465474325262600f, -0.381265769222162380f, 0.924172775251791200f, - -0.381974713146567220f, - 0.923879532511286740f, -0.382683432365089780f, 0.923585746276256670f, - -0.383391926460808660f, - 0.923291416719527640f, -0.384100195016935040f, 0.922996544014246250f, - -0.384808237616812880f, - 0.922701128333878630f, -0.385516053843918850f, 0.922405169852209880f, - -0.386223643281862980f, - 0.922108668743345180f, -0.386931005514388580f, 0.921811625181708120f, - -0.387638140125372730f, - 0.921514039342042010f, -0.388345046698826250f, 0.921215911399408730f, - -0.389051724818894380f, - 0.920917241529189520f, -0.389758174069856410f, 0.920618029907083970f, - -0.390464394036126590f, - 0.920318276709110590f, -0.391170384302253870f, 0.920017982111606570f, - -0.391876144452922350f, - 0.919717146291227360f, -0.392581674072951470f, 0.919415769424947070f, - -0.393286972747296400f, - 0.919113851690057770f, -0.393992040061048100f, 0.918811393264170050f, - -0.394696875599433560f, - 0.918508394325212250f, -0.395401478947816350f, 0.918204855051430900f, - -0.396105849691696270f, - 0.917900775621390500f, -0.396809987416710310f, 0.917596156213972950f, - -0.397513891708632330f, - 0.917290997008377910f, -0.398217562153373560f, 0.916985298184123000f, - -0.398920998336982910f, - 0.916679059921042700f, -0.399624199845646790f, 0.916372282399289140f, - -0.400327166265690090f, - 0.916064965799331720f, -0.401029897183575620f, 0.915757110301956720f, - -0.401732392185905010f, - 0.915448716088267830f, -0.402434650859418430f, 0.915139783339685260f, - -0.403136672790995300f, - 0.914830312237946200f, -0.403838457567654070f, 0.914520302965104450f, - -0.404540004776553000f, - 0.914209755703530690f, -0.405241314004989860f, 0.913898670635911680f, - -0.405942384840402510f, - 0.913587047945250810f, -0.406643216870369030f, 0.913274887814867760f, - -0.407343809682607970f, - 0.912962190428398210f, -0.408044162864978690f, 0.912648955969793900f, - -0.408744276005481360f, - 0.912335184623322750f, -0.409444148692257590f, 0.912020876573568340f, - -0.410143780513590240f, - 0.911706032005429880f, -0.410843171057903910f, 0.911390651104122430f, - -0.411542319913765220f, - 0.911074734055176360f, -0.412241226669882890f, 0.910758281044437570f, - -0.412939890915108080f, - 0.910441292258067250f, -0.413638312238434500f, 0.910123767882541680f, - -0.414336490228999100f, - 0.909805708104652220f, -0.415034424476081630f, 0.909487113111505430f, - -0.415732114569105360f, - 0.909167983090522380f, -0.416429560097637150f, 0.908848318229439120f, - -0.417126760651387870f, - 0.908528118716306120f, -0.417823715820212270f, 0.908207384739488700f, - -0.418520425194109700f, - 0.907886116487666260f, -0.419216888363223910f, 0.907564314149832630f, - -0.419913104917843620f, - 0.907241977915295820f, -0.420609074448402510f, 0.906919107973678140f, - -0.421304796545479640f, - 0.906595704514915330f, -0.422000270799799680f, 0.906271767729257660f, - -0.422695496802232950f, - 0.905947297807268460f, -0.423390474143796050f, 0.905622294939825270f, - -0.424085202415651560f, - 0.905296759318118820f, -0.424779681209108810f, 0.904970691133653250f, - -0.425473910115623800f, - 0.904644090578246240f, -0.426167888726799620f, 0.904316957844028320f, - -0.426861616634386430f, - 0.903989293123443340f, -0.427555093430282080f, 0.903661096609247980f, - -0.428248318706531960f, - 0.903332368494511820f, -0.428941292055329490f, 0.903003108972617150f, - -0.429634013069016380f, - 0.902673318237258830f, -0.430326481340082610f, 0.902342996482444200f, - -0.431018696461167030f, - 0.902012143902493180f, -0.431710658025057260f, 0.901680760692037730f, - -0.432402365624690140f, - 0.901348847046022030f, -0.433093818853151960f, 0.901016403159702330f, - -0.433785017303678520f, - 0.900683429228646970f, -0.434475960569655650f, 0.900349925448735600f, - -0.435166648244619260f, - 0.900015892016160280f, -0.435857079922255470f, 0.899681329127423930f, - -0.436547255196401200f, - 0.899346236979341570f, -0.437237173661044090f, 0.899010615769039070f, - -0.437926834910322860f, - 0.898674465693953820f, -0.438616238538527660f, 0.898337786951834310f, - -0.439305384140099950f, - 0.898000579740739880f, -0.439994271309633260f, 0.897662844259040860f, - -0.440682899641872900f, - 0.897324580705418320f, -0.441371268731716670f, 0.896985789278863970f, - -0.442059378174214700f, - 0.896646470178680150f, -0.442747227564570020f, 0.896306623604479550f, - -0.443434816498138480f, - 0.895966249756185220f, -0.444122144570429200f, 0.895625348834030110f, - -0.444809211377104880f, - 0.895283921038557580f, -0.445496016513981740f, 0.894941966570620750f, - -0.446182559577030070f, - 0.894599485631382700f, -0.446868840162374160f, 0.894256478422316040f, - -0.447554857866293010f, - 0.893912945145203250f, -0.448240612285219890f, 0.893568886002135910f, - -0.448926103015743260f, - 0.893224301195515320f, -0.449611329654606540f, 0.892879190928051680f, - -0.450296291798708610f, - 0.892533555402764580f, -0.450980989045103860f, 0.892187394822982480f, - -0.451665420991002490f, - 0.891840709392342720f, -0.452349587233770890f, 0.891493499314791380f, - -0.453033487370931580f, - 0.891145764794583180f, -0.453717121000163870f, 0.890797506036281490f, - -0.454400487719303580f, - 0.890448723244757880f, -0.455083587126343840f, 0.890099416625192320f, - -0.455766418819434640f, - 0.889749586383072780f, -0.456448982396883920f, 0.889399232724195520f, - -0.457131277457156980f, - 0.889048355854664570f, -0.457813303598877170f, 0.888696955980891600f, - -0.458495060420826270f, - 0.888345033309596350f, -0.459176547521944090f, 0.887992588047805560f, - -0.459857764501329540f, - 0.887639620402853930f, -0.460538710958240010f, 0.887286130582383150f, - -0.461219386492092380f, - 0.886932118794342190f, -0.461899790702462730f, 0.886577585246987040f, - -0.462579923189086810f, - 0.886222530148880640f, -0.463259783551860150f, 0.885866953708892790f, - -0.463939371390838520f, - 0.885510856136199950f, -0.464618686306237820f, 0.885154237640285110f, - -0.465297727898434600f, - 0.884797098430937790f, -0.465976495767966180f, 0.884439438718253810f, - -0.466654989515530920f, - 0.884081258712634990f, -0.467333208741988420f, 0.883722558624789660f, - -0.468011153048359830f, - 0.883363338665731580f, -0.468688822035827900f, 0.883003599046780830f, - -0.469366215305737520f, - 0.882643339979562790f, -0.470043332459595620f, 0.882282561676008710f, - -0.470720173099071600f, - 0.881921264348355050f, -0.471396736825997640f, 0.881559448209143780f, - -0.472073023242368660f, - 0.881197113471222090f, -0.472749031950342790f, 0.880834260347742040f, - -0.473424762552241530f, - 0.880470889052160750f, -0.474100214650549970f, 0.880106999798240360f, - -0.474775387847917120f, - 0.879742592800047410f, -0.475450281747155870f, 0.879377668271953290f, - -0.476124895951243580f, - 0.879012226428633530f, -0.476799230063322090f, 0.878646267485068130f, - -0.477473283686698060f, - 0.878279791656541580f, -0.478147056424843010f, 0.877912799158641840f, - -0.478820547881393890f, - 0.877545290207261350f, -0.479493757660153010f, 0.877177265018595940f, - -0.480166685365088390f, - 0.876808723809145650f, -0.480839330600333960f, 0.876439666795713610f, - -0.481511692970189860f, - 0.876070094195406600f, -0.482183772079122720f, 0.875700006225634600f, - -0.482855567531765670f, - 0.875329403104110890f, -0.483527078932918740f, 0.874958285048851650f, - -0.484198305887549030f, - 0.874586652278176110f, -0.484869248000791060f, 0.874214505010706300f, - -0.485539904877946960f, - 0.873841843465366860f, -0.486210276124486420f, 0.873468667861384880f, - -0.486880361346047340f, - 0.873094978418290090f, -0.487550160148436000f, 0.872720775355914300f, - -0.488219672137626790f, - 0.872346058894391540f, -0.488888896919763170f, 0.871970829254157810f, - -0.489557834101157440f, - 0.871595086655950980f, -0.490226483288291160f, 0.871218831320811020f, - -0.490894844087815090f, - 0.870842063470078980f, -0.491562916106549900f, 0.870464783325397670f, - -0.492230698951486020f, - 0.870086991108711460f, -0.492898192229784040f, 0.869708687042265670f, - -0.493565395548774770f, - 0.869329871348606840f, -0.494232308515959670f, 0.868950544250582380f, - -0.494898930739011260f, - 0.868570705971340900f, -0.495565261825772540f, 0.868190356734331310f, - -0.496231301384258250f, - 0.867809496763303320f, -0.496897049022654470f, 0.867428126282306920f, - -0.497562504349319150f, - 0.867046245515692650f, -0.498227666972781870f, 0.866663854688111130f, - -0.498892536501744590f, - 0.866280954024512990f, -0.499557112545081840f, 0.865897543750148820f, - -0.500221394711840680f, - 0.865513624090569090f, -0.500885382611240710f, 0.865129195271623800f, - -0.501549075852675390f, - 0.864744257519462380f, -0.502212474045710790f, 0.864358811060534030f, - -0.502875576800086990f, - 0.863972856121586810f, -0.503538383725717580f, 0.863586392929668100f, - -0.504200894432690340f, - 0.863199421712124160f, -0.504863108531267590f, 0.862811942696600330f, - -0.505525025631885390f, - 0.862423956111040610f, -0.506186645345155230f, 0.862035462183687210f, - -0.506847967281863210f, - 0.861646461143081300f, -0.507508991052970870f, 0.861256953218062170f, - -0.508169716269614600f, - 0.860866938637767310f, -0.508830142543106990f, 0.860476417631632070f, - -0.509490269484936360f, - 0.860085390429390140f, -0.510150096706766810f, 0.859693857261072610f, - -0.510809623820439040f, - 0.859301818357008470f, -0.511468850437970300f, 0.858909273947823900f, - -0.512127776171554690f, - 0.858516224264442740f, -0.512786400633562960f, 0.858122669538086140f, - -0.513444723436543460f, - 0.857728610000272120f, -0.514102744193221660f, 0.857334045882815590f, - -0.514760462516501200f, - 0.856938977417828760f, -0.515417878019462930f, 0.856543404837719960f, - -0.516074990315366630f, - 0.856147328375194470f, -0.516731799017649870f, 0.855750748263253920f, - -0.517388303739929060f, - 0.855353664735196030f, -0.518044504095999340f, 0.854956078024614930f, - -0.518700399699834950f, - 0.854557988365400530f, -0.519355990165589640f, 0.854159395991738850f, - -0.520011275107596040f, - 0.853760301138111410f, -0.520666254140367160f, 0.853360704039295430f, - -0.521320926878595660f, - 0.852960604930363630f, -0.521975292937154390f, 0.852560004046684080f, - -0.522629351931096610f, - 0.852158901623919830f, -0.523283103475656430f, 0.851757297898029120f, - -0.523936547186248600f, - 0.851355193105265200f, -0.524589682678468950f, 0.850952587482175730f, - -0.525242509568094710f, - 0.850549481265603480f, -0.525895027471084630f, 0.850145874692685210f, - -0.526547236003579440f, - 0.849741768000852550f, -0.527199134781901280f, 0.849337161427830780f, - -0.527850723422555230f, - 0.848932055211639610f, -0.528502001542228480f, 0.848526449590592650f, - -0.529152968757790610f, - 0.848120344803297230f, -0.529803624686294610f, 0.847713741088654380f, - -0.530453968944976320f, - 0.847306638685858320f, -0.531104001151255000f, 0.846899037834397240f, - -0.531753720922733320f, - 0.846490938774052130f, -0.532403127877197900f, 0.846082341744897050f, - -0.533052221632619450f, - 0.845673246987299070f, -0.533701001807152960f, 0.845263654741918220f, - -0.534349468019137520f, - 0.844853565249707120f, -0.534997619887097150f, 0.844442978751910660f, - -0.535645457029741090f, - 0.844031895490066410f, -0.536292979065963180f, 0.843620315706004150f, - -0.536940185614842910f, - 0.843208239641845440f, -0.537587076295645390f, 0.842795667540004120f, - -0.538233650727821700f, - 0.842382599643185850f, -0.538879908531008420f, 0.841969036194387680f, - -0.539525849325028890f, - 0.841554977436898440f, -0.540171472729892850f, 0.841140423614298080f, - -0.540816778365796670f, - 0.840725374970458070f, -0.541461765853123440f, 0.840309831749540770f, - -0.542106434812443920f, - 0.839893794195999520f, -0.542750784864515890f, 0.839477262554578550f, - -0.543394815630284800f, - 0.839060237070312740f, -0.544038526730883820f, 0.838642717988527300f, - -0.544681917787634530f, - 0.838224705554838080f, -0.545324988422046460f, 0.837806200015150940f, - -0.545967738255817570f, - 0.837387201615661940f, -0.546610166910834860f, 0.836967710602857020f, - -0.547252274009174090f, - 0.836547727223512010f, -0.547894059173100190f, 0.836127251724692270f, - -0.548535522025067390f, - 0.835706284353752600f, -0.549176662187719660f, 0.835284825358337370f, - -0.549817479283890910f, - 0.834862874986380010f, -0.550457972936604810f, 0.834440433486103190f, - -0.551098142769075430f, - 0.834017501106018130f, -0.551737988404707340f, 0.833594078094925140f, - -0.552377509467096070f, - 0.833170164701913190f, -0.553016705580027470f, 0.832745761176359460f, - -0.553655576367479310f, - 0.832320867767929680f, -0.554294121453620000f, 0.831895484726577590f, - -0.554932340462810370f, - 0.831469612302545240f, -0.555570233019602180f, 0.831043250746362320f, - -0.556207798748739930f, - 0.830616400308846310f, -0.556845037275160100f, 0.830189061241102370f, - -0.557481948223991550f, - 0.829761233794523050f, -0.558118531220556100f, 0.829332918220788250f, - -0.558754785890368310f, - 0.828904114771864870f, -0.559390711859136140f, 0.828474823700007130f, - -0.560026308752760380f, - 0.828045045257755800f, -0.560661576197336030f, 0.827614779697938400f, - -0.561296513819151470f, - 0.827184027273669130f, -0.561931121244689470f, 0.826752788238348520f, - -0.562565398100626560f, - 0.826321062845663530f, -0.563199344013834090f, 0.825888851349586780f, - -0.563832958611378170f, - 0.825456154004377550f, -0.564466241520519500f, 0.825022971064580220f, - -0.565099192368713980f, - 0.824589302785025290f, -0.565731810783613120f, 0.824155149420828570f, - -0.566364096393063840f, - 0.823720511227391430f, -0.566996048825108680f, 0.823285388460400110f, - -0.567627667707986230f, - 0.822849781375826430f, -0.568258952670131490f, 0.822413690229926390f, - -0.568889903340175860f, - 0.821977115279241550f, -0.569520519346947140f, 0.821540056780597610f, - -0.570150800319470300f, - 0.821102514991104650f, -0.570780745886967260f, 0.820664490168157460f, - -0.571410355678857230f, - 0.820225982569434690f, -0.572039629324757050f, 0.819786992452898990f, - -0.572668566454481160f, - 0.819347520076796900f, -0.573297166698042200f, 0.818907565699658950f, - -0.573925429685650750f, - 0.818467129580298660f, -0.574553355047715760f, 0.818026211977813440f, - -0.575180942414845080f, - 0.817584813151583710f, -0.575808191417845340f, 0.817142933361272970f, - -0.576435101687721830f, - 0.816700572866827850f, -0.577061672855679440f, 0.816257731928477390f, - -0.577687904553122800f, - 0.815814410806733780f, -0.578313796411655590f, 0.815370609762391290f, - -0.578939348063081780f, - 0.814926329056526620f, -0.579564559139405630f, 0.814481568950498610f, - -0.580189429272831680f, - 0.814036329705948410f, -0.580813958095764530f, 0.813590611584798510f, - -0.581438145240810170f, - 0.813144414849253590f, -0.582061990340775440f, 0.812697739761799490f, - -0.582685493028668460f, - 0.812250586585203880f, -0.583308652937698290f, 0.811802955582515470f, - -0.583931469701276180f, - 0.811354847017063730f, -0.584553942953015330f, 0.810906261152459670f, - -0.585176072326730410f, - 0.810457198252594770f, -0.585797857456438860f, 0.810007658581641140f, - -0.586419297976360500f, - 0.809557642404051260f, -0.587040393520917970f, 0.809107149984558240f, - -0.587661143724736660f, - 0.808656181588174980f, -0.588281548222645220f, 0.808204737480194720f, - -0.588901606649675720f, - 0.807752817926190360f, -0.589521318641063940f, 0.807300423192014450f, - -0.590140683832248820f, - 0.806847553543799330f, -0.590759701858874160f, 0.806394209247956240f, - -0.591378372356787580f, - 0.805940390571176280f, -0.591996694962040990f, 0.805486097780429230f, - -0.592614669310891130f, - 0.805031331142963660f, -0.593232295039799800f, 0.804576090926307110f, - -0.593849571785433630f, - 0.804120377398265810f, -0.594466499184664430f, 0.803664190826924090f, - -0.595083076874569960f, - 0.803207531480644940f, -0.595699304492433360f, 0.802750399628069160f, - -0.596315181675743710f, - 0.802292795538115720f, -0.596930708062196500f, 0.801834719479981310f, - -0.597545883289693160f, - 0.801376171723140240f, -0.598160706996342270f, 0.800917152537344300f, - -0.598775178820458720f, - 0.800457662192622820f, -0.599389298400564540f, 0.799997700959281910f, - -0.600003065375388940f, - 0.799537269107905010f, -0.600616479383868970f, 0.799076366909352350f, - -0.601229540065148500f, - 0.798614994634760820f, -0.601842247058580030f, 0.798153152555543750f, - -0.602454600003723750f, - 0.797690840943391160f, -0.603066598540348160f, 0.797228060070268810f, - -0.603678242308430370f, - 0.796764810208418830f, -0.604289530948155960f, 0.796301091630359110f, - -0.604900464099919820f, - 0.795836904608883570f, -0.605511041404325550f, 0.795372249417061310f, - -0.606121262502186120f, - 0.794907126328237010f, -0.606731127034524480f, 0.794441535616030590f, - -0.607340634642572930f, - 0.793975477554337170f, -0.607949784967773630f, 0.793508952417326660f, - -0.608558577651779450f, - 0.793041960479443640f, -0.609167012336453210f, 0.792574502015407690f, - -0.609775088663868430f, - 0.792106577300212390f, -0.610382806276309480f, 0.791638186609125880f, - -0.610990164816271660f, - 0.791169330217690200f, -0.611597163926461910f, 0.790700008401721610f, - -0.612203803249797950f, - 0.790230221437310030f, -0.612810082429409710f, 0.789759969600819070f, - -0.613416001108638590f, - 0.789289253168885650f, -0.614021558931038380f, 0.788818072418420280f, - -0.614626755540375050f, - 0.788346427626606340f, -0.615231590580626820f, 0.787874319070900220f, - -0.615836063695985090f, - 0.787401747029031430f, -0.616440174530853650f, 0.786928711779001810f, - -0.617043922729849760f, - 0.786455213599085770f, -0.617647307937803870f, 0.785981252767830150f, - -0.618250329799760250f, - 0.785506829564053930f, -0.618852987960976320f, 0.785031944266848080f, - -0.619455282066924020f, - 0.784556597155575240f, -0.620057211763289100f, 0.784080788509869950f, - -0.620658776695972140f, - 0.783604518609638200f, -0.621259976511087550f, 0.783127787735057310f, - -0.621860810854965360f, - 0.782650596166575730f, -0.622461279374149970f, 0.782172944184913010f, - -0.623061381715401260f, - 0.781694832071059390f, -0.623661117525694530f, 0.781216260106276090f, - -0.624260486452220650f, - 0.780737228572094490f, -0.624859488142386340f, 0.780257737750316590f, - -0.625458122243814360f, - 0.779777787923014550f, -0.626056388404343520f, 0.779297379372530300f, - -0.626654286272029350f, - 0.778816512381475980f, -0.627251815495144080f, 0.778335187232733210f, - -0.627848975722176460f, - 0.777853404209453150f, -0.628445766601832710f, 0.777371163595056310f, - -0.629042187783036000f, - 0.776888465673232440f, -0.629638238914926980f, 0.776405310727940390f, - -0.630233919646864370f, - 0.775921699043407690f, -0.630829229628424470f, 0.775437630904130540f, - -0.631424168509401860f, - 0.774953106594873930f, -0.632018735939809060f, 0.774468126400670860f, - -0.632612931569877410f, - 0.773982690606822900f, -0.633206755050057190f, 0.773496799498899050f, - -0.633800206031017280f, - 0.773010453362736990f, -0.634393284163645490f, 0.772523652484441330f, - -0.634985989099049460f, - 0.772036397150384520f, -0.635578320488556110f, 0.771548687647206300f, - -0.636170277983712170f, - 0.771060524261813820f, -0.636761861236284200f, 0.770571907281380810f, - -0.637353069898259130f, - 0.770082836993347900f, -0.637943903621844060f, 0.769593313685422940f, - -0.638534362059466790f, - 0.769103337645579700f, -0.639124444863775730f, 0.768612909162058380f, - -0.639714151687640450f, - 0.768122028523365420f, -0.640303482184151670f, 0.767630696018273380f, - -0.640892436006621380f, - 0.767138911935820400f, -0.641481012808583160f, 0.766646676565310380f, - -0.642069212243792540f, - 0.766153990196312920f, -0.642657033966226860f, 0.765660853118662500f, - -0.643244477630085850f, - 0.765167265622458960f, -0.643831542889791390f, 0.764673227998067140f, - -0.644418229399988380f, - 0.764178740536116670f, -0.645004536815543930f, 0.763683803527501870f, - -0.645590464791548690f, - 0.763188417263381270f, -0.646176012983316280f, 0.762692582035177980f, - -0.646761181046383920f, - 0.762196298134578900f, -0.647345968636512060f, 0.761699565853535380f, - -0.647930375409685340f, - 0.761202385484261780f, -0.648514401022112440f, 0.760704757319236920f, - -0.649098045130225950f, - 0.760206681651202420f, -0.649681307390683190f, 0.759708158773163440f, - -0.650264187460365850f, - 0.759209188978388070f, -0.650846684996380880f, 0.758709772560407390f, - -0.651428799656059820f, - 0.758209909813015280f, -0.652010531096959500f, 0.757709601030268080f, - -0.652591878976862440f, - 0.757208846506484570f, -0.653172842953776760f, 0.756707646536245670f, - -0.653753422685936060f, - 0.756206001414394540f, -0.654333617831800440f, 0.755703911436035880f, - -0.654913428050056030f, - 0.755201376896536550f, -0.655492852999615350f, 0.754698398091524500f, - -0.656071892339617600f, - 0.754194975316889170f, -0.656650545729428940f, 0.753691108868781210f, - -0.657228812828642540f, - 0.753186799043612520f, -0.657806693297078640f, 0.752682046138055340f, - -0.658384186794785050f, - 0.752176850449042810f, -0.658961292982037320f, 0.751671212273768430f, - -0.659538011519338660f, - 0.751165131909686480f, -0.660114342067420480f, 0.750658609654510700f, - -0.660690284287242300f, - 0.750151645806215070f, -0.661265837839992270f, 0.749644240663033480f, - -0.661841002387086870f, - 0.749136394523459370f, -0.662415777590171780f, 0.748628107686245440f, - -0.662990163111121470f, - 0.748119380450403600f, -0.663564158612039770f, 0.747610213115205150f, - -0.664137763755260010f, - 0.747100605980180130f, -0.664710978203344790f, 0.746590559345117310f, - -0.665283801619087180f, - 0.746080073510063780f, -0.665856233665509720f, 0.745569148775325430f, - -0.666428274005865240f, - 0.745057785441466060f, -0.666999922303637470f, 0.744545983809307370f, - -0.667571178222540310f, - 0.744033744179929290f, -0.668142041426518450f, 0.743521066854669120f, - -0.668712511579747980f, - 0.743007952135121720f, -0.669282588346636010f, 0.742494400323139180f, - -0.669852271391821020f, - 0.741980411720831070f, -0.670421560380173090f, 0.741465986630563290f, - -0.670990454976794220f, - 0.740951125354959110f, -0.671558954847018330f, 0.740435828196898020f, - -0.672127059656411730f, - 0.739920095459516200f, -0.672694769070772860f, 0.739403927446205760f, - -0.673262082756132970f, - 0.738887324460615110f, -0.673829000378756040f, 0.738370286806648620f, - -0.674395521605139050f, - 0.737852814788465980f, -0.674961646102011930f, 0.737334908710482910f, - -0.675527373536338520f, - 0.736816568877369900f, -0.676092703575315920f, 0.736297795594053170f, - -0.676657635886374950f, - 0.735778589165713590f, -0.677222170137180330f, 0.735258949897786840f, - -0.677786305995631500f, - 0.734738878095963500f, -0.678350043129861470f, 0.734218374066188280f, - -0.678913381208238410f, - 0.733697438114660370f, -0.679476319899364970f, 0.733176070547832740f, - -0.680038858872078930f, - 0.732654271672412820f, -0.680600997795453020f, 0.732132041795361290f, - -0.681162736338795430f, - 0.731609381223892630f, -0.681724074171649710f, 0.731086290265474340f, - -0.682285010963795570f, - 0.730562769227827590f, -0.682845546385248080f, 0.730038818418926260f, - -0.683405680106258680f, - 0.729514438146997010f, -0.683965411797315400f, 0.728989628720519420f, - -0.684524741129142300f, - 0.728464390448225200f, -0.685083667772700360f, 0.727938723639098620f, - -0.685642191399187470f, - 0.727412628602375770f, -0.686200311680038590f, 0.726886105647544970f, - -0.686758028286925890f, - 0.726359155084346010f, -0.687315340891759050f, 0.725831777222770370f, - -0.687872249166685550f, - 0.725303972373060770f, -0.688428752784090440f, 0.724775740845711280f, - -0.688984851416597040f, - 0.724247082951467000f, -0.689540544737066830f, 0.723717999001323500f, - -0.690095832418599950f, - 0.723188489306527460f, -0.690650714134534600f, 0.722658554178575610f, - -0.691205189558448450f, - 0.722128193929215350f, -0.691759258364157750f, 0.721597408870443770f, - -0.692312920225718220f, - 0.721066199314508110f, -0.692866174817424630f, 0.720534565573905270f, - -0.693419021813811760f, - 0.720002507961381650f, -0.693971460889654000f, 0.719470026789932990f, - -0.694523491719965520f, - 0.718937122372804490f, -0.695075113980000880f, 0.718403795023489830f, - -0.695626327345254870f, - 0.717870045055731710f, -0.696177131491462990f, 0.717335872783521730f, - -0.696727526094601200f, - 0.716801278521099540f, -0.697277510830886520f, 0.716266262582953120f, - -0.697827085376777290f, - 0.715730825283818590f, -0.698376249408972920f, 0.715194966938680120f, - -0.698925002604414150f, - 0.714658687862769090f, -0.699473344640283770f, 0.714121988371564820f, - -0.700021275194006250f, - 0.713584868780793640f, -0.700568793943248340f, 0.713047329406429340f, - -0.701115900565918660f, - 0.712509370564692320f, -0.701662594740168450f, 0.711970992572050100f, - -0.702208876144391870f, - 0.711432195745216430f, -0.702754744457225300f, 0.710892980401151680f, - -0.703300199357548730f, - 0.710353346857062420f, -0.703845240524484940f, 0.709813295430400840f, - -0.704389867637400410f, - 0.709272826438865690f, -0.704934080375904880f, 0.708731940200400650f, - -0.705477878419852100f, - 0.708190637033195400f, -0.706021261449339740f, 0.707648917255684350f, - -0.706564229144709510f, - 0.707106781186547570f, -0.707106781186547460f, 0.706564229144709620f, - -0.707648917255684350f, - 0.706021261449339740f, -0.708190637033195290f, 0.705477878419852210f, - -0.708731940200400650f, - 0.704934080375904990f, -0.709272826438865580f, 0.704389867637400410f, - -0.709813295430400840f, - 0.703845240524484940f, -0.710353346857062310f, 0.703300199357548730f, - -0.710892980401151680f, - 0.702754744457225300f, -0.711432195745216430f, 0.702208876144391870f, - -0.711970992572049990f, - 0.701662594740168570f, -0.712509370564692320f, 0.701115900565918660f, - -0.713047329406429230f, - 0.700568793943248450f, -0.713584868780793520f, 0.700021275194006360f, - -0.714121988371564710f, - 0.699473344640283770f, -0.714658687862768980f, 0.698925002604414150f, - -0.715194966938680010f, - 0.698376249408972920f, -0.715730825283818590f, 0.697827085376777290f, - -0.716266262582953120f, - 0.697277510830886630f, -0.716801278521099540f, 0.696727526094601200f, - -0.717335872783521730f, - 0.696177131491462990f, -0.717870045055731710f, 0.695626327345254870f, - -0.718403795023489720f, - 0.695075113980000880f, -0.718937122372804380f, 0.694523491719965520f, - -0.719470026789932990f, - 0.693971460889654000f, -0.720002507961381650f, 0.693419021813811880f, - -0.720534565573905270f, - 0.692866174817424740f, -0.721066199314508110f, 0.692312920225718220f, - -0.721597408870443660f, - 0.691759258364157750f, -0.722128193929215350f, 0.691205189558448450f, - -0.722658554178575610f, - 0.690650714134534720f, -0.723188489306527350f, 0.690095832418599950f, - -0.723717999001323390f, - 0.689540544737066940f, -0.724247082951466890f, 0.688984851416597150f, - -0.724775740845711280f, - 0.688428752784090550f, -0.725303972373060660f, 0.687872249166685550f, - -0.725831777222770370f, - 0.687315340891759160f, -0.726359155084346010f, 0.686758028286925890f, - -0.726886105647544970f, - 0.686200311680038700f, -0.727412628602375770f, 0.685642191399187470f, - -0.727938723639098620f, - 0.685083667772700360f, -0.728464390448225200f, 0.684524741129142300f, - -0.728989628720519310f, - 0.683965411797315510f, -0.729514438146996900f, 0.683405680106258790f, - -0.730038818418926150f, - 0.682845546385248080f, -0.730562769227827590f, 0.682285010963795570f, - -0.731086290265474230f, - 0.681724074171649820f, -0.731609381223892520f, 0.681162736338795430f, - -0.732132041795361290f, - 0.680600997795453130f, -0.732654271672412820f, 0.680038858872079040f, - -0.733176070547832740f, - 0.679476319899365080f, -0.733697438114660260f, 0.678913381208238410f, - -0.734218374066188170f, - 0.678350043129861580f, -0.734738878095963390f, 0.677786305995631500f, - -0.735258949897786730f, - 0.677222170137180450f, -0.735778589165713480f, 0.676657635886374950f, - -0.736297795594053060f, - 0.676092703575316030f, -0.736816568877369790f, 0.675527373536338630f, - -0.737334908710482790f, - 0.674961646102012040f, -0.737852814788465980f, 0.674395521605139050f, - -0.738370286806648510f, - 0.673829000378756150f, -0.738887324460615110f, 0.673262082756132970f, - -0.739403927446205760f, - 0.672694769070772970f, -0.739920095459516090f, 0.672127059656411840f, - -0.740435828196898020f, - 0.671558954847018330f, -0.740951125354959110f, 0.670990454976794220f, - -0.741465986630563290f, - 0.670421560380173090f, -0.741980411720830960f, 0.669852271391821130f, - -0.742494400323139180f, - 0.669282588346636010f, -0.743007952135121720f, 0.668712511579748090f, - -0.743521066854669120f, - 0.668142041426518560f, -0.744033744179929180f, 0.667571178222540310f, - -0.744545983809307250f, - 0.666999922303637470f, -0.745057785441465950f, 0.666428274005865350f, - -0.745569148775325430f, - 0.665856233665509720f, -0.746080073510063780f, 0.665283801619087180f, - -0.746590559345117310f, - 0.664710978203344900f, -0.747100605980180130f, 0.664137763755260010f, - -0.747610213115205150f, - 0.663564158612039880f, -0.748119380450403490f, 0.662990163111121470f, - -0.748628107686245330f, - 0.662415777590171780f, -0.749136394523459260f, 0.661841002387086870f, - -0.749644240663033480f, - 0.661265837839992270f, -0.750151645806214960f, 0.660690284287242300f, - -0.750658609654510590f, - 0.660114342067420480f, -0.751165131909686370f, 0.659538011519338770f, - -0.751671212273768430f, - 0.658961292982037320f, -0.752176850449042700f, 0.658384186794785050f, - -0.752682046138055230f, - 0.657806693297078640f, -0.753186799043612410f, 0.657228812828642650f, - -0.753691108868781210f, - 0.656650545729429050f, -0.754194975316889170f, 0.656071892339617710f, - -0.754698398091524390f, - 0.655492852999615460f, -0.755201376896536550f, 0.654913428050056150f, - -0.755703911436035880f, - 0.654333617831800550f, -0.756206001414394540f, 0.653753422685936170f, - -0.756707646536245670f, - 0.653172842953776760f, -0.757208846506484460f, 0.652591878976862550f, - -0.757709601030268080f, - 0.652010531096959500f, -0.758209909813015280f, 0.651428799656059820f, - -0.758709772560407390f, - 0.650846684996380990f, -0.759209188978387960f, 0.650264187460365960f, - -0.759708158773163440f, - 0.649681307390683190f, -0.760206681651202420f, 0.649098045130226060f, - -0.760704757319236920f, - 0.648514401022112550f, -0.761202385484261780f, 0.647930375409685460f, - -0.761699565853535270f, - 0.647345968636512060f, -0.762196298134578900f, 0.646761181046383920f, - -0.762692582035177870f, - 0.646176012983316390f, -0.763188417263381270f, 0.645590464791548800f, - -0.763683803527501870f, - 0.645004536815544040f, -0.764178740536116670f, 0.644418229399988380f, - -0.764673227998067140f, - 0.643831542889791500f, -0.765167265622458960f, 0.643244477630085850f, - -0.765660853118662390f, - 0.642657033966226860f, -0.766153990196312810f, 0.642069212243792540f, - -0.766646676565310380f, - 0.641481012808583160f, -0.767138911935820400f, 0.640892436006621380f, - -0.767630696018273270f, - 0.640303482184151670f, -0.768122028523365310f, 0.639714151687640450f, - -0.768612909162058270f, - 0.639124444863775730f, -0.769103337645579590f, 0.638534362059466790f, - -0.769593313685422940f, - 0.637943903621844170f, -0.770082836993347900f, 0.637353069898259130f, - -0.770571907281380700f, - 0.636761861236284200f, -0.771060524261813710f, 0.636170277983712170f, - -0.771548687647206300f, - 0.635578320488556230f, -0.772036397150384410f, 0.634985989099049460f, - -0.772523652484441330f, - 0.634393284163645490f, -0.773010453362736990f, 0.633800206031017280f, - -0.773496799498899050f, - 0.633206755050057190f, -0.773982690606822790f, 0.632612931569877520f, - -0.774468126400670860f, - 0.632018735939809060f, -0.774953106594873820f, 0.631424168509401860f, - -0.775437630904130430f, - 0.630829229628424470f, -0.775921699043407580f, 0.630233919646864480f, - -0.776405310727940390f, - 0.629638238914927100f, -0.776888465673232440f, 0.629042187783036000f, - -0.777371163595056200f, - 0.628445766601832710f, -0.777853404209453040f, 0.627848975722176570f, - -0.778335187232733090f, - 0.627251815495144190f, -0.778816512381475870f, 0.626654286272029460f, - -0.779297379372530300f, - 0.626056388404343520f, -0.779777787923014440f, 0.625458122243814360f, - -0.780257737750316590f, - 0.624859488142386450f, -0.780737228572094380f, 0.624260486452220650f, - -0.781216260106276090f, - 0.623661117525694640f, -0.781694832071059390f, 0.623061381715401370f, - -0.782172944184912900f, - 0.622461279374150080f, -0.782650596166575730f, 0.621860810854965360f, - -0.783127787735057310f, - 0.621259976511087660f, -0.783604518609638200f, 0.620658776695972140f, - -0.784080788509869950f, - 0.620057211763289210f, -0.784556597155575240f, 0.619455282066924020f, - -0.785031944266848080f, - 0.618852987960976320f, -0.785506829564053930f, 0.618250329799760250f, - -0.785981252767830150f, - 0.617647307937803980f, -0.786455213599085770f, 0.617043922729849760f, - -0.786928711779001700f, - 0.616440174530853650f, -0.787401747029031320f, 0.615836063695985090f, - -0.787874319070900110f, - 0.615231590580626820f, -0.788346427626606230f, 0.614626755540375050f, - -0.788818072418420170f, - 0.614021558931038490f, -0.789289253168885650f, 0.613416001108638590f, - -0.789759969600819070f, - 0.612810082429409710f, -0.790230221437310030f, 0.612203803249798060f, - -0.790700008401721610f, - 0.611597163926462020f, -0.791169330217690090f, 0.610990164816271770f, - -0.791638186609125770f, - 0.610382806276309480f, -0.792106577300212390f, 0.609775088663868430f, - -0.792574502015407580f, - 0.609167012336453210f, -0.793041960479443640f, 0.608558577651779450f, - -0.793508952417326660f, - 0.607949784967773740f, -0.793975477554337170f, 0.607340634642572930f, - -0.794441535616030590f, - 0.606731127034524480f, -0.794907126328237010f, 0.606121262502186230f, - -0.795372249417061190f, - 0.605511041404325550f, -0.795836904608883460f, 0.604900464099919930f, - -0.796301091630359110f, - 0.604289530948156070f, -0.796764810208418720f, 0.603678242308430370f, - -0.797228060070268700f, - 0.603066598540348280f, -0.797690840943391040f, 0.602454600003723860f, - -0.798153152555543750f, - 0.601842247058580030f, -0.798614994634760820f, 0.601229540065148620f, - -0.799076366909352350f, - 0.600616479383868970f, -0.799537269107905010f, 0.600003065375389060f, - -0.799997700959281910f, - 0.599389298400564540f, -0.800457662192622710f, 0.598775178820458720f, - -0.800917152537344300f, - 0.598160706996342380f, -0.801376171723140130f, 0.597545883289693270f, - -0.801834719479981310f, - 0.596930708062196500f, -0.802292795538115720f, 0.596315181675743820f, - -0.802750399628069160f, - 0.595699304492433470f, -0.803207531480644830f, 0.595083076874569960f, - -0.803664190826924090f, - 0.594466499184664540f, -0.804120377398265700f, 0.593849571785433630f, - -0.804576090926307000f, - 0.593232295039799800f, -0.805031331142963660f, 0.592614669310891130f, - -0.805486097780429120f, - 0.591996694962040990f, -0.805940390571176280f, 0.591378372356787580f, - -0.806394209247956240f, - 0.590759701858874280f, -0.806847553543799220f, 0.590140683832248940f, - -0.807300423192014450f, - 0.589521318641063940f, -0.807752817926190360f, 0.588901606649675840f, - -0.808204737480194720f, - 0.588281548222645330f, -0.808656181588174980f, 0.587661143724736770f, - -0.809107149984558130f, - 0.587040393520918080f, -0.809557642404051260f, 0.586419297976360500f, - -0.810007658581641140f, - 0.585797857456438860f, -0.810457198252594770f, 0.585176072326730410f, - -0.810906261152459670f, - 0.584553942953015330f, -0.811354847017063730f, 0.583931469701276300f, - -0.811802955582515360f, - 0.583308652937698290f, -0.812250586585203880f, 0.582685493028668460f, - -0.812697739761799490f, - 0.582061990340775550f, -0.813144414849253590f, 0.581438145240810280f, - -0.813590611584798510f, - 0.580813958095764530f, -0.814036329705948300f, 0.580189429272831680f, - -0.814481568950498610f, - 0.579564559139405740f, -0.814926329056526620f, 0.578939348063081890f, - -0.815370609762391290f, - 0.578313796411655590f, -0.815814410806733780f, 0.577687904553122800f, - -0.816257731928477390f, - 0.577061672855679550f, -0.816700572866827850f, 0.576435101687721830f, - -0.817142933361272970f, - 0.575808191417845340f, -0.817584813151583710f, 0.575180942414845190f, - -0.818026211977813440f, - 0.574553355047715760f, -0.818467129580298660f, 0.573925429685650750f, - -0.818907565699658950f, - 0.573297166698042320f, -0.819347520076796900f, 0.572668566454481160f, - -0.819786992452898990f, - 0.572039629324757050f, -0.820225982569434690f, 0.571410355678857340f, - -0.820664490168157460f, - 0.570780745886967370f, -0.821102514991104650f, 0.570150800319470300f, - -0.821540056780597610f, - 0.569520519346947250f, -0.821977115279241550f, 0.568889903340175970f, - -0.822413690229926390f, - 0.568258952670131490f, -0.822849781375826320f, 0.567627667707986230f, - -0.823285388460400110f, - 0.566996048825108680f, -0.823720511227391320f, 0.566364096393063950f, - -0.824155149420828570f, - 0.565731810783613230f, -0.824589302785025290f, 0.565099192368714090f, - -0.825022971064580220f, - 0.564466241520519500f, -0.825456154004377440f, 0.563832958611378170f, - -0.825888851349586780f, - 0.563199344013834090f, -0.826321062845663420f, 0.562565398100626560f, - -0.826752788238348520f, - 0.561931121244689470f, -0.827184027273669020f, 0.561296513819151470f, - -0.827614779697938400f, - 0.560661576197336030f, -0.828045045257755800f, 0.560026308752760380f, - -0.828474823700007130f, - 0.559390711859136140f, -0.828904114771864870f, 0.558754785890368310f, - -0.829332918220788250f, - 0.558118531220556100f, -0.829761233794523050f, 0.557481948223991660f, - -0.830189061241102370f, - 0.556845037275160100f, -0.830616400308846200f, 0.556207798748739930f, - -0.831043250746362320f, - 0.555570233019602290f, -0.831469612302545240f, 0.554932340462810370f, - -0.831895484726577590f, - 0.554294121453620110f, -0.832320867767929680f, 0.553655576367479310f, - -0.832745761176359460f, - 0.553016705580027580f, -0.833170164701913190f, 0.552377509467096070f, - -0.833594078094925140f, - 0.551737988404707450f, -0.834017501106018130f, 0.551098142769075430f, - -0.834440433486103190f, - 0.550457972936604810f, -0.834862874986380010f, 0.549817479283891020f, - -0.835284825358337370f, - 0.549176662187719770f, -0.835706284353752600f, 0.548535522025067390f, - -0.836127251724692160f, - 0.547894059173100190f, -0.836547727223511890f, 0.547252274009174090f, - -0.836967710602857020f, - 0.546610166910834860f, -0.837387201615661940f, 0.545967738255817680f, - -0.837806200015150940f, - 0.545324988422046460f, -0.838224705554837970f, 0.544681917787634530f, - -0.838642717988527300f, - 0.544038526730883930f, -0.839060237070312630f, 0.543394815630284800f, - -0.839477262554578550f, - 0.542750784864516000f, -0.839893794195999410f, 0.542106434812444030f, - -0.840309831749540770f, - 0.541461765853123560f, -0.840725374970458070f, 0.540816778365796670f, - -0.841140423614298080f, - 0.540171472729892970f, -0.841554977436898330f, 0.539525849325029010f, - -0.841969036194387680f, - 0.538879908531008420f, -0.842382599643185960f, 0.538233650727821700f, - -0.842795667540004120f, - 0.537587076295645510f, -0.843208239641845440f, 0.536940185614843020f, - -0.843620315706004040f, - 0.536292979065963180f, -0.844031895490066410f, 0.535645457029741090f, - -0.844442978751910660f, - 0.534997619887097260f, -0.844853565249707010f, 0.534349468019137520f, - -0.845263654741918220f, - 0.533701001807152960f, -0.845673246987299070f, 0.533052221632619670f, - -0.846082341744896940f, - 0.532403127877198010f, -0.846490938774052020f, 0.531753720922733320f, - -0.846899037834397350f, - 0.531104001151255000f, -0.847306638685858320f, 0.530453968944976320f, - -0.847713741088654270f, - 0.529803624686294830f, -0.848120344803297120f, 0.529152968757790720f, - -0.848526449590592650f, - 0.528502001542228480f, -0.848932055211639610f, 0.527850723422555460f, - -0.849337161427830670f, - 0.527199134781901390f, -0.849741768000852440f, 0.526547236003579330f, - -0.850145874692685210f, - 0.525895027471084740f, -0.850549481265603370f, 0.525242509568094710f, - -0.850952587482175730f, - 0.524589682678468840f, -0.851355193105265200f, 0.523936547186248600f, - -0.851757297898029120f, - 0.523283103475656430f, -0.852158901623919830f, 0.522629351931096720f, - -0.852560004046683970f, - 0.521975292937154390f, -0.852960604930363630f, 0.521320926878595550f, - -0.853360704039295430f, - 0.520666254140367270f, -0.853760301138111300f, 0.520011275107596040f, - -0.854159395991738730f, - 0.519355990165589530f, -0.854557988365400530f, 0.518700399699835170f, - -0.854956078024614820f, - 0.518044504095999340f, -0.855353664735196030f, 0.517388303739929060f, - -0.855750748263253920f, - 0.516731799017649980f, -0.856147328375194470f, 0.516074990315366630f, - -0.856543404837719960f, - 0.515417878019463150f, -0.856938977417828650f, 0.514760462516501200f, - -0.857334045882815590f, - 0.514102744193221660f, -0.857728610000272120f, 0.513444723436543570f, - -0.858122669538086020f, - 0.512786400633563070f, -0.858516224264442740f, 0.512127776171554690f, - -0.858909273947823900f, - 0.511468850437970520f, -0.859301818357008360f, 0.510809623820439040f, - -0.859693857261072610f, - 0.510150096706766700f, -0.860085390429390140f, 0.509490269484936360f, - -0.860476417631632070f, - 0.508830142543106990f, -0.860866938637767310f, 0.508169716269614710f, - -0.861256953218062060f, - 0.507508991052970870f, -0.861646461143081300f, 0.506847967281863320f, - -0.862035462183687210f, - 0.506186645345155450f, -0.862423956111040500f, 0.505525025631885510f, - -0.862811942696600330f, - 0.504863108531267480f, -0.863199421712124160f, 0.504200894432690560f, - -0.863586392929667990f, - 0.503538383725717580f, -0.863972856121586700f, 0.502875576800086880f, - -0.864358811060534030f, - 0.502212474045710900f, -0.864744257519462380f, 0.501549075852675390f, - -0.865129195271623690f, - 0.500885382611240940f, -0.865513624090568980f, 0.500221394711840680f, - -0.865897543750148820f, - 0.499557112545081890f, -0.866280954024512990f, 0.498892536501744750f, - -0.866663854688111020f, - 0.498227666972781870f, -0.867046245515692650f, 0.497562504349319090f, - -0.867428126282306920f, - 0.496897049022654640f, -0.867809496763303210f, 0.496231301384258310f, - -0.868190356734331310f, - 0.495565261825772490f, -0.868570705971340900f, 0.494898930739011310f, - -0.868950544250582380f, - 0.494232308515959730f, -0.869329871348606730f, 0.493565395548774880f, - -0.869708687042265560f, - 0.492898192229784090f, -0.870086991108711350f, 0.492230698951486080f, - -0.870464783325397670f, - 0.491562916106550060f, -0.870842063470078860f, 0.490894844087815140f, - -0.871218831320810900f, - 0.490226483288291100f, -0.871595086655951090f, 0.489557834101157550f, - -0.871970829254157700f, - 0.488888896919763230f, -0.872346058894391540f, 0.488219672137626740f, - -0.872720775355914300f, - 0.487550160148436050f, -0.873094978418290090f, 0.486880361346047400f, - -0.873468667861384880f, - 0.486210276124486530f, -0.873841843465366750f, 0.485539904877947020f, - -0.874214505010706300f, - 0.484869248000791120f, -0.874586652278176110f, 0.484198305887549140f, - -0.874958285048851540f, - 0.483527078932918740f, -0.875329403104110780f, 0.482855567531765670f, - -0.875700006225634600f, - 0.482183772079122830f, -0.876070094195406600f, 0.481511692970189920f, - -0.876439666795713610f, - 0.480839330600333900f, -0.876808723809145760f, 0.480166685365088440f, - -0.877177265018595940f, - 0.479493757660153010f, -0.877545290207261240f, 0.478820547881394050f, - -0.877912799158641730f, - 0.478147056424843120f, -0.878279791656541460f, 0.477473283686698060f, - -0.878646267485068130f, - 0.476799230063322250f, -0.879012226428633410f, 0.476124895951243630f, - -0.879377668271953180f, - 0.475450281747155870f, -0.879742592800047410f, 0.474775387847917230f, - -0.880106999798240360f, - 0.474100214650550020f, -0.880470889052160750f, 0.473424762552241530f, - -0.880834260347742040f, - 0.472749031950342900f, -0.881197113471221980f, 0.472073023242368660f, - -0.881559448209143780f, - 0.471396736825997810f, -0.881921264348354940f, 0.470720173099071710f, - -0.882282561676008600f, - 0.470043332459595620f, -0.882643339979562790f, 0.469366215305737630f, - -0.883003599046780720f, - 0.468688822035827960f, -0.883363338665731580f, 0.468011153048359830f, - -0.883722558624789660f, - 0.467333208741988530f, -0.884081258712634990f, 0.466654989515530970f, - -0.884439438718253700f, - 0.465976495767966130f, -0.884797098430937790f, 0.465297727898434650f, - -0.885154237640285110f, - 0.464618686306237820f, -0.885510856136199950f, 0.463939371390838460f, - -0.885866953708892790f, - 0.463259783551860260f, -0.886222530148880640f, 0.462579923189086810f, - -0.886577585246987040f, - 0.461899790702462840f, -0.886932118794342080f, 0.461219386492092430f, - -0.887286130582383150f, - 0.460538710958240010f, -0.887639620402853930f, 0.459857764501329650f, - -0.887992588047805560f, - 0.459176547521944150f, -0.888345033309596240f, 0.458495060420826220f, - -0.888696955980891710f, - 0.457813303598877290f, -0.889048355854664570f, 0.457131277457156980f, - -0.889399232724195520f, - 0.456448982396883860f, -0.889749586383072890f, 0.455766418819434750f, - -0.890099416625192210f, - 0.455083587126343840f, -0.890448723244757880f, 0.454400487719303750f, - -0.890797506036281490f, - 0.453717121000163930f, -0.891145764794583180f, 0.453033487370931580f, - -0.891493499314791380f, - 0.452349587233771000f, -0.891840709392342720f, 0.451665420991002540f, - -0.892187394822982480f, - 0.450980989045103810f, -0.892533555402764690f, 0.450296291798708730f, - -0.892879190928051680f, - 0.449611329654606600f, -0.893224301195515320f, 0.448926103015743260f, - -0.893568886002136020f, - 0.448240612285220000f, -0.893912945145203250f, 0.447554857866293010f, - -0.894256478422316040f, - 0.446868840162374330f, -0.894599485631382580f, 0.446182559577030120f, - -0.894941966570620750f, - 0.445496016513981740f, -0.895283921038557580f, 0.444809211377105000f, - -0.895625348834030000f, - 0.444122144570429260f, -0.895966249756185110f, 0.443434816498138430f, - -0.896306623604479660f, - 0.442747227564570130f, -0.896646470178680150f, 0.442059378174214760f, - -0.896985789278863970f, - 0.441371268731716620f, -0.897324580705418320f, 0.440682899641873020f, - -0.897662844259040750f, - 0.439994271309633260f, -0.898000579740739880f, 0.439305384140100060f, - -0.898337786951834190f, - 0.438616238538527710f, -0.898674465693953820f, 0.437926834910322860f, - -0.899010615769039070f, - 0.437237173661044200f, -0.899346236979341460f, 0.436547255196401250f, - -0.899681329127423930f, - 0.435857079922255470f, -0.900015892016160280f, 0.435166648244619370f, - -0.900349925448735600f, - 0.434475960569655710f, -0.900683429228646860f, 0.433785017303678520f, - -0.901016403159702330f, - 0.433093818853152010f, -0.901348847046022030f, 0.432402365624690140f, - -0.901680760692037730f, - 0.431710658025057370f, -0.902012143902493070f, 0.431018696461167080f, - -0.902342996482444200f, - 0.430326481340082610f, -0.902673318237258830f, 0.429634013069016500f, - -0.903003108972617040f, - 0.428941292055329550f, -0.903332368494511820f, 0.428248318706531910f, - -0.903661096609247980f, - 0.427555093430282200f, -0.903989293123443340f, 0.426861616634386490f, - -0.904316957844028320f, - 0.426167888726799620f, -0.904644090578246240f, 0.425473910115623910f, - -0.904970691133653250f, - 0.424779681209108810f, -0.905296759318118820f, 0.424085202415651670f, - -0.905622294939825160f, - 0.423390474143796100f, -0.905947297807268460f, 0.422695496802232950f, - -0.906271767729257660f, - 0.422000270799799790f, -0.906595704514915330f, 0.421304796545479700f, - -0.906919107973678030f, - 0.420609074448402510f, -0.907241977915295930f, 0.419913104917843730f, - -0.907564314149832520f, - 0.419216888363223960f, -0.907886116487666150f, 0.418520425194109700f, - -0.908207384739488700f, - 0.417823715820212380f, -0.908528118716306120f, 0.417126760651387870f, - -0.908848318229439120f, - 0.416429560097637320f, -0.909167983090522270f, 0.415732114569105420f, - -0.909487113111505430f, - 0.415034424476081630f, -0.909805708104652220f, 0.414336490228999210f, - -0.910123767882541570f, - 0.413638312238434560f, -0.910441292258067140f, 0.412939890915108020f, - -0.910758281044437570f, - 0.412241226669883000f, -0.911074734055176250f, 0.411542319913765280f, - -0.911390651104122320f, - 0.410843171057903910f, -0.911706032005429880f, 0.410143780513590350f, - -0.912020876573568230f, - 0.409444148692257590f, -0.912335184623322750f, 0.408744276005481520f, - -0.912648955969793900f, - 0.408044162864978740f, -0.912962190428398100f, 0.407343809682607970f, - -0.913274887814867760f, - 0.406643216870369140f, -0.913587047945250810f, 0.405942384840402570f, - -0.913898670635911680f, - 0.405241314004989860f, -0.914209755703530690f, 0.404540004776553110f, - -0.914520302965104450f, - 0.403838457567654130f, -0.914830312237946090f, 0.403136672790995240f, - -0.915139783339685260f, - 0.402434650859418540f, -0.915448716088267830f, 0.401732392185905010f, - -0.915757110301956720f, - 0.401029897183575790f, -0.916064965799331610f, 0.400327166265690150f, - -0.916372282399289140f, - 0.399624199845646790f, -0.916679059921042700f, 0.398920998336983020f, - -0.916985298184122890f, - 0.398217562153373620f, -0.917290997008377910f, 0.397513891708632330f, - -0.917596156213972950f, - 0.396809987416710420f, -0.917900775621390390f, 0.396105849691696320f, - -0.918204855051430900f, - 0.395401478947816300f, -0.918508394325212250f, 0.394696875599433670f, - -0.918811393264169940f, - 0.393992040061048100f, -0.919113851690057770f, 0.393286972747296570f, - -0.919415769424946960f, - 0.392581674072951530f, -0.919717146291227360f, 0.391876144452922350f, - -0.920017982111606570f, - 0.391170384302253980f, -0.920318276709110480f, 0.390464394036126650f, - -0.920618029907083860f, - 0.389758174069856410f, -0.920917241529189520f, 0.389051724818894500f, - -0.921215911399408730f, - 0.388345046698826300f, -0.921514039342041900f, 0.387638140125372680f, - -0.921811625181708120f, - 0.386931005514388690f, -0.922108668743345070f, 0.386223643281862980f, - -0.922405169852209880f, - 0.385516053843919020f, -0.922701128333878520f, 0.384808237616812930f, - -0.922996544014246250f, - 0.384100195016935040f, -0.923291416719527640f, 0.383391926460808770f, - -0.923585746276256560f, - 0.382683432365089840f, -0.923879532511286740f, 0.381974713146567220f, - -0.924172775251791200f, - 0.381265769222162490f, -0.924465474325262600f, 0.380556601008928570f, - -0.924757629559513910f, - 0.379847208924051110f, -0.925049240782677580f, 0.379137593384847430f, - -0.925340307823206200f, - 0.378427754808765620f, -0.925630830509872720f, 0.377717693613385810f, - -0.925920808671769960f, - 0.377007410216418310f, -0.926210242138311270f, 0.376296905035704790f, - -0.926499130739230510f, - 0.375586178489217330f, -0.926787474304581750f, 0.374875230995057600f, - -0.927075272664740100f, - 0.374164062971457990f, -0.927362525650401110f, 0.373452674836780410f, - -0.927649233092581180f, - 0.372741067009515810f, -0.927935394822617890f, 0.372029239908284960f, - -0.928221010672169440f, - 0.371317193951837600f, -0.928506080473215480f, 0.370604929559051670f, - -0.928790604058057020f, - 0.369892447148934270f, -0.929074581259315750f, 0.369179747140620070f, - -0.929358011909935500f, - 0.368466829953372320f, -0.929640895843181330f, 0.367753696006582090f, - -0.929923232892639560f, - 0.367040345719767240f, -0.930205022892219070f, 0.366326779512573590f, - -0.930486265676149780f, - 0.365612997804773960f, -0.930766961078983710f, 0.364899001016267380f, - -0.931047108935595170f, - 0.364184789567079840f, -0.931326709081180430f, 0.363470363877363870f, - -0.931605761351257830f, - 0.362755724367397230f, -0.931884265581668150f, 0.362040871457584350f, - -0.932162221608574320f, - 0.361325805568454340f, -0.932439629268462360f, 0.360610527120662270f, - -0.932716488398140250f, - 0.359895036534988280f, -0.932992798834738850f, 0.359179334232336560f, - -0.933268560415712050f, - 0.358463420633736540f, -0.933543772978836170f, 0.357747296160342010f, - -0.933818436362210960f, - 0.357030961233430030f, -0.934092550404258870f, 0.356314416274402360f, - -0.934366114943725900f, - 0.355597661704783960f, -0.934639129819680780f, 0.354880697946222790f, - -0.934911594871516090f, - 0.354163525420490510f, -0.935183509938947500f, 0.353446144549480870f, - -0.935454874862014620f, - 0.352728555755210730f, -0.935725689481080370f, 0.352010759459819240f, - -0.935995953636831300f, - 0.351292756085567150f, -0.936265667170278260f, 0.350574546054837570f, - -0.936534829922755500f, - 0.349856129790135030f, -0.936803441735921560f, 0.349137507714085030f, - -0.937071502451759190f, - 0.348418680249434510f, -0.937339011912574960f, 0.347699647819051490f, - -0.937605969960999990f, - 0.346980410845923680f, -0.937872376439989890f, 0.346260969753160170f, - -0.938138231192824360f, - 0.345541324963989150f, -0.938403534063108060f, 0.344821476901759290f, - -0.938668284894770170f, - 0.344101425989938980f, -0.938932483532064490f, 0.343381172652115100f, - -0.939196129819569900f, - 0.342660717311994380f, -0.939459223602189920f, 0.341940060393402300f, - -0.939721764725153340f, - 0.341219202320282410f, -0.939983753034013940f, 0.340498143516697100f, - -0.940245188374650880f, - 0.339776884406826960f, -0.940506070593268300f, 0.339055425414969640f, - -0.940766399536396070f, - 0.338333766965541290f, -0.941026175050889260f, 0.337611909483074680f, - -0.941285396983928660f, - 0.336889853392220050f, -0.941544065183020810f, 0.336167599117744690f, - -0.941802179495997650f, - 0.335445147084531660f, -0.942059739771017310f, 0.334722497717581220f, - -0.942316745856563780f, - 0.333999651442009490f, -0.942573197601446870f, 0.333276608683047980f, - -0.942829094854802710f, - 0.332553369866044220f, -0.943084437466093490f, 0.331829935416461220f, - -0.943339225285107720f, - 0.331106305759876430f, -0.943593458161960390f, 0.330382481321982950f, - -0.943847135947092690f, - 0.329658462528587550f, -0.944100258491272660f, 0.328934249805612200f, - -0.944352825645594750f, - 0.328209843579092660f, -0.944604837261480260f, 0.327485244275178060f, - -0.944856293190677210f, - 0.326760452320131790f, -0.945107193285260610f, 0.326035468140330350f, - -0.945357537397632290f, - 0.325310292162262980f, -0.945607325380521280f, 0.324584924812532150f, - -0.945856557086983910f, - 0.323859366517852960f, -0.946105232370403340f, 0.323133617705052330f, - -0.946353351084490590f, - 0.322407678801070020f, -0.946600913083283530f, 0.321681550232956640f, - -0.946847918221148000f, - 0.320955232427875210f, -0.947094366352777220f, 0.320228725813100020f, - -0.947340257333191940f, - 0.319502030816015750f, -0.947585591017741090f, 0.318775147864118480f, - -0.947830367262101010f, - 0.318048077385015060f, -0.948074585922276230f, 0.317320819806421790f, - -0.948318246854599090f, - 0.316593375556165850f, -0.948561349915730270f, 0.315865745062184070f, - -0.948803894962658380f, - 0.315137928752522440f, -0.949045881852700560f, 0.314409927055336820f, - -0.949287310443502010f, - 0.313681740398891570f, -0.949528180593036670f, 0.312953369211560200f, - -0.949768492159606680f, - 0.312224813921825050f, -0.950008245001843000f, 0.311496074958275970f, - -0.950247438978705230f, - 0.310767152749611470f, -0.950486073949481700f, 0.310038047724638000f, - -0.950724149773789610f, - 0.309308760312268780f, -0.950961666311575080f, 0.308579290941525030f, - -0.951198623423113230f, - 0.307849640041534980f, -0.951435020969008340f, 0.307119808041533100f, - -0.951670858810193860f, - 0.306389795370861080f, -0.951906136807932230f, 0.305659602458966230f, - -0.952140854823815830f, - 0.304929229735402430f, -0.952375012719765880f, 0.304198677629829270f, - -0.952608610358033240f, - 0.303467946572011370f, -0.952841647601198720f, 0.302737036991819140f, - -0.953074124312172200f, - 0.302005949319228200f, -0.953306040354193750f, 0.301274683984318000f, - -0.953537395590833280f, - 0.300543241417273400f, -0.953768189885990330f, 0.299811622048383460f, - -0.953998423103894490f, - 0.299079826308040480f, -0.954228095109105670f, 0.298347854626741570f, - -0.954457205766513490f, - 0.297615707435086310f, -0.954685754941338340f, 0.296883385163778270f, - -0.954913742499130520f, - 0.296150888243623960f, -0.955141168305770670f, 0.295418217105532070f, - -0.955368032227470240f, - 0.294685372180514330f, -0.955594334130771110f, 0.293952353899684770f, - -0.955820073882545420f, - 0.293219162694258680f, -0.956045251349996410f, 0.292485798995553830f, - -0.956269866400658140f, - 0.291752263234989370f, -0.956493918902394990f, 0.291018555844085090f, - -0.956717408723403050f, - 0.290284677254462330f, -0.956940335732208940f, 0.289550627897843140f, - -0.957162699797670100f, - 0.288816408206049480f, -0.957384500788975860f, 0.288082018611004300f, - -0.957605738575646240f, - 0.287347459544729570f, -0.957826413027532910f, 0.286612731439347790f, - -0.958046524014818600f, - 0.285877834727080730f, -0.958266071408017670f, 0.285142769840248720f, - -0.958485055077976100f, - 0.284407537211271820f, -0.958703474895871600f, 0.283672137272668550f, - -0.958921330733213060f, - 0.282936570457055390f, -0.959138622461841890f, 0.282200837197147500f, - -0.959355349953930790f, - 0.281464937925758050f, -0.959571513081984520f, 0.280728873075797190f, - -0.959787111718839900f, - 0.279992643080273380f, -0.960002145737665850f, 0.279256248372291240f, - -0.960216615011963430f, - 0.278519689385053060f, -0.960430519415565790f, 0.277782966551857800f, - -0.960643858822638470f, - 0.277046080306099950f, -0.960856633107679660f, 0.276309031081271030f, - -0.961068842145519350f, - 0.275571819310958250f, -0.961280485811320640f, 0.274834445428843940f, - -0.961491563980579000f, - 0.274096909868706330f, -0.961702076529122540f, 0.273359213064418790f, - -0.961912023333112100f, - 0.272621355449948980f, -0.962121404269041580f, 0.271883337459359890f, - -0.962330219213737400f, - 0.271145159526808070f, -0.962538468044359160f, 0.270406822086544820f, - -0.962746150638399410f, - 0.269668325572915200f, -0.962953266873683880f, 0.268929670420357310f, - -0.963159816628371360f, - 0.268190857063403180f, -0.963365799780954050f, 0.267451885936677740f, - -0.963571216210257210f, - 0.266712757474898420f, -0.963776065795439840f, 0.265973472112875530f, - -0.963980348415994110f, - 0.265234030285511900f, -0.964184063951745720f, 0.264494432427801630f, - -0.964387212282854290f, - 0.263754678974831510f, -0.964589793289812650f, 0.263014770361779060f, - -0.964791806853447900f, - 0.262274707023913590f, -0.964993252854920320f, 0.261534489396595630f, - -0.965194131175724720f, - 0.260794117915275570f, -0.965394441697689400f, 0.260053593015495130f, - -0.965594184302976830f, - 0.259312915132886350f, -0.965793358874083570f, 0.258572084703170390f, - -0.965991965293840570f, - 0.257831102162158930f, -0.966190003445412620f, 0.257089967945753230f, - -0.966387473212298790f, - 0.256348682489942910f, -0.966584374478333120f, 0.255607246230807550f, - -0.966780707127683270f, - 0.254865659604514630f, -0.966976471044852070f, 0.254123923047320620f, - -0.967171666114676640f, - 0.253382036995570270f, -0.967366292222328510f, 0.252640001885695580f, - -0.967560349253314360f, - 0.251897818154216910f, -0.967753837093475510f, 0.251155486237742030f, - -0.967946755628987800f, - 0.250413006572965280f, -0.968139104746362330f, 0.249670379596668520f, - -0.968330884332445300f, - 0.248927605745720260f, -0.968522094274417270f, 0.248184685457074780f, - -0.968712734459794780f, - 0.247441619167773440f, -0.968902804776428870f, 0.246698407314942500f, - -0.969092305112506100f, - 0.245955050335794590f, -0.969281235356548530f, 0.245211548667627680f, - -0.969469595397412950f, - 0.244467902747824210f, -0.969657385124292450f, 0.243724113013852130f, - -0.969844604426714830f, - 0.242980179903263980f, -0.970031253194543970f, 0.242236103853696070f, - -0.970217331317979160f, - 0.241491885302869300f, -0.970402838687555500f, 0.240747524688588540f, - -0.970587775194143630f, - 0.240003022448741500f, -0.970772140728950350f, 0.239258379021300120f, - -0.970955935183517970f, - 0.238513594844318500f, -0.971139158449725090f, 0.237768670355934210f, - -0.971321810419786160f, - 0.237023605994367340f, -0.971503890986251780f, 0.236278402197919620f, - -0.971685400042008540f, - 0.235533059404975460f, -0.971866337480279400f, 0.234787578054001080f, - -0.972046703194623500f, - 0.234041958583543460f, -0.972226497078936270f, 0.233296201432231560f, - -0.972405719027449770f, - 0.232550307038775330f, -0.972584368934732210f, 0.231804275841964780f, - -0.972762446695688570f, - 0.231058108280671280f, -0.972939952205560070f, 0.230311804793845530f, - -0.973116885359925130f, - 0.229565365820518870f, -0.973293246054698250f, 0.228818791799802360f, - -0.973469034186130950f, - 0.228072083170885790f, -0.973644249650811870f, 0.227325240373038830f, - -0.973818892345666100f, - 0.226578263845610110f, -0.973992962167955830f, 0.225831154028026200f, - -0.974166459015280320f, - 0.225083911359792780f, -0.974339382785575860f, 0.224336536280493690f, - -0.974511733377115720f, - 0.223589029229790020f, -0.974683510688510670f, 0.222841390647421280f, - -0.974854714618708430f, - 0.222093620973203590f, -0.975025345066994120f, 0.221345720647030810f, - -0.975195401932990370f, - 0.220597690108873650f, -0.975364885116656870f, 0.219849529798778750f, - -0.975533794518291360f, - 0.219101240156869770f, -0.975702130038528570f, 0.218352821623346430f, - -0.975869891578341030f, - 0.217604274638483670f, -0.976037079039039020f, 0.216855599642632570f, - -0.976203692322270560f, - 0.216106797076219600f, -0.976369731330021140f, 0.215357867379745550f, - -0.976535195964614470f, - 0.214608810993786920f, -0.976700086128711840f, 0.213859628358993830f, - -0.976864401725312640f, - 0.213110319916091360f, -0.977028142657754390f, 0.212360886105878580f, - -0.977191308829712280f, - 0.211611327369227610f, -0.977353900145199960f, 0.210861644147084830f, - -0.977515916508569280f, - 0.210111836880469720f, -0.977677357824509930f, 0.209361906010474190f, - -0.977838223998050430f, - 0.208611851978263460f, -0.977998514934557140f, 0.207861675225075150f, - -0.978158230539735050f, - 0.207111376192218560f, -0.978317370719627650f, 0.206360955321075680f, - -0.978475935380616830f, - 0.205610413053099320f, -0.978633924429423100f, 0.204859749829814420f, - -0.978791337773105670f, - 0.204108966092817010f, -0.978948175319062200f, 0.203358062283773370f, - -0.979104436975029250f, - 0.202607038844421110f, -0.979260122649082020f, 0.201855896216568160f, - -0.979415232249634780f, - 0.201104634842091960f, -0.979569765685440520f, 0.200353255162940420f, - -0.979723722865591170f, - 0.199601757621131050f, -0.979877103699517640f, 0.198850142658750120f, - -0.980029908096989980f, - 0.198098410717953730f, -0.980182135968117320f, 0.197346562240966000f, - -0.980333787223347960f, - 0.196594597670080220f, -0.980484861773469380f, 0.195842517447657990f, - -0.980635359529608120f, - 0.195090322016128330f, -0.980785280403230430f, 0.194338011817988600f, - -0.980934624306141640f, - 0.193585587295803750f, -0.981083391150486590f, 0.192833048892205290f, - -0.981231580848749730f, - 0.192080397049892380f, -0.981379193313754560f, 0.191327632211630990f, - -0.981526228458664660f, - 0.190574754820252800f, -0.981672686196983110f, 0.189821765318656580f, - -0.981818566442552500f, - 0.189068664149806280f, -0.981963869109555240f, 0.188315451756732120f, - -0.982108594112513610f, - 0.187562128582529740f, -0.982252741366289370f, 0.186808695070359330f, - -0.982396310786084690f, - 0.186055151663446630f, -0.982539302287441240f, 0.185301498805082040f, - -0.982681715786240860f, - 0.184547736938619640f, -0.982823551198705240f, 0.183793866507478390f, - -0.982964808441396440f, - 0.183039887955141060f, -0.983105487431216290f, 0.182285801725153320f, - -0.983245588085407070f, - 0.181531608261125130f, -0.983385110321551180f, 0.180777308006728670f, - -0.983524054057571260f, - 0.180022901405699510f, -0.983662419211730250f, 0.179268388901835880f, - -0.983800205702631490f, - 0.178513770938997590f, -0.983937413449218920f, 0.177759047961107140f, - -0.984074042370776450f, - 0.177004220412148860f, -0.984210092386929030f, 0.176249288736167940f, - -0.984345563417641900f, - 0.175494253377271400f, -0.984480455383220930f, 0.174739114779627310f, - -0.984614768204312600f, - 0.173983873387463850f, -0.984748501801904210f, 0.173228529645070490f, - -0.984881656097323700f, - 0.172473083996796030f, -0.985014231012239840f, 0.171717536887049970f, - -0.985146226468662230f, - 0.170961888760301360f, -0.985277642388941220f, 0.170206140061078120f, - -0.985408478695768420f, - 0.169450291233967930f, -0.985538735312176060f, 0.168694342723617440f, - -0.985668412161537550f, - 0.167938294974731230f, -0.985797509167567370f, 0.167182148432072880f, - -0.985926026254321130f, - 0.166425903540464220f, -0.986053963346195440f, 0.165669560744784140f, - -0.986181320367928270f, - 0.164913120489970090f, -0.986308097244598670f, 0.164156583221015890f, - -0.986434293901627070f, - 0.163399949382973230f, -0.986559910264775410f, 0.162643219420950450f, - -0.986684946260146690f, - 0.161886393780111910f, -0.986809401814185420f, 0.161129472905678780f, - -0.986933276853677710f, - 0.160372457242928400f, -0.987056571305750970f, 0.159615347237193090f, - -0.987179285097874340f, - 0.158858143333861390f, -0.987301418157858430f, 0.158100845978377090f, - -0.987422970413855410f, - 0.157343455616238280f, -0.987543941794359230f, 0.156585972692998590f, - -0.987664332228205710f, - 0.155828397654265320f, -0.987784141644572180f, 0.155070730945700510f, - -0.987903369972977790f, - 0.154312973013020240f, -0.988022017143283530f, 0.153555124301993500f, - -0.988140083085692570f, - 0.152797185258443410f, -0.988257567730749460f, 0.152039156328246160f, - -0.988374471009341280f, - 0.151281037957330250f, -0.988490792852696590f, 0.150522830591677370f, - -0.988606533192386450f, - 0.149764534677321620f, -0.988721691960323780f, 0.149006150660348470f, - -0.988836269088763540f, - 0.148247678986896200f, -0.988950264510302990f, 0.147489120103153680f, - -0.989063678157881540f, - 0.146730474455361750f, -0.989176509964781010f, 0.145971742489812370f, - -0.989288759864625170f, - 0.145212924652847520f, -0.989400427791380380f, 0.144454021390860440f, - -0.989511513679355190f, - 0.143695033150294580f, -0.989622017463200780f, 0.142935960377642700f, - -0.989731939077910570f, - 0.142176803519448000f, -0.989841278458820530f, 0.141417563022303130f, - -0.989950035541608990f, - 0.140658239332849240f, -0.990058210262297120f, 0.139898832897777380f, - -0.990165802557248400f, - 0.139139344163826280f, -0.990272812363169110f, 0.138379773577783890f, - -0.990379239617108160f, - 0.137620121586486180f, -0.990485084256456980f, 0.136860388636816430f, - -0.990590346218950150f, - 0.136100575175706200f, -0.990695025442664630f, 0.135340681650134330f, - -0.990799121866020370f, - 0.134580708507126220f, -0.990902635427780010f, 0.133820656193754690f, - -0.991005566067049370f, - 0.133060525157139180f, -0.991107913723276780f, 0.132300315844444680f, - -0.991209678336254060f, - 0.131540028702883280f, -0.991310859846115440f, 0.130779664179711790f, - -0.991411458193338540f, - 0.130019222722233350f, -0.991511473318743900f, 0.129258704777796270f, - -0.991610905163495370f, - 0.128498110793793220f, -0.991709753669099530f, 0.127737441217662280f, - -0.991808018777406430f, - 0.126976696496885980f, -0.991905700430609330f, 0.126215877078990400f, - -0.992002798571244520f, - 0.125454983411546210f, -0.992099313142191800f, 0.124694015942167770f, - -0.992195244086673920f, - 0.123932975118512200f, -0.992290591348257370f, 0.123171861388280650f, - -0.992385354870851670f, - 0.122410675199216280f, -0.992479534598709970f, 0.121649416999105540f, - -0.992573130476428810f, - 0.120888087235777220f, -0.992666142448948020f, 0.120126686357101580f, - -0.992758570461551140f, - 0.119365214810991350f, -0.992850414459865100f, 0.118603673045400840f, - -0.992941674389860470f, - 0.117842061508325020f, -0.993032350197851410f, 0.117080380647800550f, - -0.993122441830495580f, - 0.116318630911904880f, -0.993211949234794500f, 0.115556812748755290f, - -0.993300872358093280f, - 0.114794926606510250f, -0.993389211148080650f, 0.114032972933367300f, - -0.993476965552789190f, - 0.113270952177564360f, -0.993564135520595300f, 0.112508864787378830f, - -0.993650721000219120f, - 0.111746711211126660f, -0.993736721940724600f, 0.110984491897163380f, - -0.993822138291519660f, - 0.110222207293883180f, -0.993906970002356060f, 0.109459857849718030f, - -0.993991217023329380f, - 0.108697444013138670f, -0.994074879304879370f, 0.107934966232653760f, - -0.994157956797789730f, - 0.107172424956808870f, -0.994240449453187900f, 0.106409820634187840f, - -0.994322357222545810f, - 0.105647153713410700f, -0.994403680057679100f, 0.104884424643134970f, - -0.994484417910747600f, - 0.104121633872054730f, -0.994564570734255420f, 0.103358781848899700f, - -0.994644138481050710f, - 0.102595869022436280f, -0.994723121104325700f, 0.101832895841466670f, - -0.994801518557617110f, - 0.101069862754827880f, -0.994879330794805620f, 0.100306770211392820f, - -0.994956557770116380f, - 0.099543618660069444f, -0.995033199438118630f, 0.098780408549799664f, - -0.995109255753726110f, - 0.098017140329560770f, -0.995184726672196820f, 0.097253814448363354f, - -0.995259612149133390f, - 0.096490431355252607f, -0.995333912140482280f, 0.095726991499307315f, - -0.995407626602534900f, - 0.094963495329639061f, -0.995480755491926940f, 0.094199943295393190f, - -0.995553298765638470f, - 0.093436335845747912f, -0.995625256380994310f, 0.092672673429913366f, - -0.995696628295663520f, - 0.091908956497132696f, -0.995767414467659820f, 0.091145185496681130f, - -0.995837614855341610f, - 0.090381360877865011f, -0.995907229417411720f, 0.089617483090022917f, - -0.995976258112917790f, - 0.088853552582524684f, -0.996044700901251970f, 0.088089569804770507f, - -0.996112557742151130f, - 0.087325535206192226f, -0.996179828595696870f, 0.086561449236251239f, - -0.996246513422315520f, - 0.085797312344439880f, -0.996312612182778000f, 0.085033124980280414f, - -0.996378124838200210f, - 0.084268887593324127f, -0.996443051350042630f, 0.083504600633152404f, - -0.996507391680110820f, - 0.082740264549375803f, -0.996571145790554840f, 0.081975879791633108f, - -0.996634313643869900f, - 0.081211446809592386f, -0.996696895202896060f, 0.080446966052950097f, - -0.996758890430818000f, - 0.079682437971430126f, -0.996820299291165670f, 0.078917863014785095f, - -0.996881121747813850f, - 0.078153241632794315f, -0.996941357764982160f, 0.077388574275265049f, - -0.997001007307235290f, - 0.076623861392031617f, -0.997060070339482960f, 0.075859103432954503f, - -0.997118546826979980f, - 0.075094300847921291f, -0.997176436735326190f, 0.074329454086845867f, - -0.997233740030466160f, - 0.073564563599667454f, -0.997290456678690210f, 0.072799629836351618f, - -0.997346586646633230f, - 0.072034653246889416f, -0.997402129901275300f, 0.071269634281296415f, - -0.997457086409941910f, - 0.070504573389614009f, -0.997511456140303450f, 0.069739471021907376f, - -0.997565239060375750f, - 0.068974327628266732f, -0.997618435138519550f, 0.068209143658806454f, - -0.997671044343441000f, - 0.067443919563664106f, -0.997723066644191640f, 0.066678655793001543f, - -0.997774502010167820f, - 0.065913352797003930f, -0.997825350411111640f, 0.065148011025878860f, - -0.997875611817110150f, - 0.064382630929857410f, -0.997925286198596000f, 0.063617212959193190f, - -0.997974373526346990f, - 0.062851757564161420f, -0.998022873771486240f, 0.062086265195060247f, - -0.998070786905482340f, - 0.061320736302208648f, -0.998118112900149180f, 0.060555171335947781f, - -0.998164851727646240f, - 0.059789570746640007f, -0.998211003360478190f, 0.059023934984667986f, - -0.998256567771495180f, - 0.058258264500435732f, -0.998301544933892890f, 0.057492559744367684f, - -0.998345934821212370f, - 0.056726821166907783f, -0.998389737407340160f, 0.055961049218520520f, - -0.998432952666508440f, - 0.055195244349690031f, -0.998475580573294770f, 0.054429407010919147f, - -0.998517621102622210f, - 0.053663537652730679f, -0.998559074229759310f, 0.052897636725665401f, - -0.998599939930320370f, - 0.052131704680283317f, -0.998640218180265270f, 0.051365741967162731f, - -0.998679908955899090f, - 0.050599749036899337f, -0.998719012233872940f, 0.049833726340107257f, - -0.998757527991183340f, - 0.049067674327418126f, -0.998795456205172410f, 0.048301593449480172f, - -0.998832796853527990f, - 0.047535484156959261f, -0.998869549914283560f, 0.046769346900537960f, - -0.998905715365818290f, - 0.046003182130914644f, -0.998941293186856870f, 0.045236990298804750f, - -0.998976283356469820f, - 0.044470771854938744f, -0.999010685854073380f, 0.043704527250063421f, - -0.999044500659429290f, - 0.042938256934940959f, -0.999077727752645360f, 0.042171961360348002f, - -0.999110367114174890f, - 0.041405640977076712f, -0.999142418724816910f, 0.040639296235933854f, - -0.999173882565716380f, - 0.039872927587739845f, -0.999204758618363890f, 0.039106535483329839f, - -0.999235046864595850f, - 0.038340120373552791f, -0.999264747286594420f, 0.037573682709270514f, - -0.999293859866887790f, - 0.036807222941358991f, -0.999322384588349540f, 0.036040741520706299f, - -0.999350321434199440f, - 0.035274238898213947f, -0.999377670388002850f, 0.034507715524795889f, - -0.999404431433671300f, - 0.033741171851377642f, -0.999430604555461730f, 0.032974608328897315f, - -0.999456189737977340f, - 0.032208025408304704f, -0.999481186966166950f, 0.031441423540560343f, - -0.999505596225325310f, - 0.030674803176636581f, -0.999529417501093140f, 0.029908164767516655f, - -0.999552650779456990f, - 0.029141508764193740f, -0.999575296046749220f, 0.028374835617672258f, - -0.999597353289648380f, - 0.027608145778965820f, -0.999618822495178640f, 0.026841439699098527f, - -0.999639703650710200f, - 0.026074717829104040f, -0.999659996743959220f, 0.025307980620024630f, - -0.999679701762987930f, - 0.024541228522912264f, -0.999698818696204250f, 0.023774461988827676f, - -0.999717347532362190f, - 0.023007681468839410f, -0.999735288260561680f, 0.022240887414024919f, - -0.999752640870248840f, - 0.021474080275469605f, -0.999769405351215280f, 0.020707260504265912f, - -0.999785581693599210f, - 0.019940428551514598f, -0.999801169887884260f, 0.019173584868322699f, - -0.999816169924900410f, - 0.018406729905804820f, -0.999830581795823400f, 0.017639864115082195f, - -0.999844405492175240f, - 0.016872987947281773f, -0.999857641005823860f, 0.016106101853537263f, - -0.999870288328982950f, - 0.015339206284988220f, -0.999882347454212560f, 0.014572301692779104f, - -0.999893818374418490f, - 0.013805388528060349f, -0.999904701082852900f, 0.013038467241987433f, - -0.999914995573113470f, - 0.012271538285719944f, -0.999924701839144500f, 0.011504602110422875f, - -0.999933819875236000f, - 0.010737659167264572f, -0.999942349676023910f, 0.009970709907418029f, - -0.999950291236490480f, - 0.009203754782059960f, -0.999957644551963900f, 0.008436794242369860f, - -0.999964409618118280f, - 0.007669828739531077f, -0.999970586430974140f, 0.006902858724729877f, - -0.999976174986897610f, - 0.006135884649154515f, -0.999981175282601110f, 0.005368906963996303f, - -0.999985587315143200f, - 0.004601926120448672f, -0.999989411081928400f, 0.003834942569706248f, - -0.999992646580707190f, - 0.003067956762966138f, -0.999995293809576190f, 0.002300969151425887f, - -0.999997352766978210f, - 0.001533980186284766f, -0.999998823451701880f, 0.000766990318742846f, - -0.999999705862882230f -}; - -/** -* \par -* cosFactor tables are generated using the formula :
cos_factors[n] = 2 * cos((2n+1)*pi/(4*N))
-* \par -* C command to generate the table -* \par -*
 for(i = 0; i< N; i++)   
-* {   
-*    cos_factors[i]= 2 * cos((2*i+1)*c/2);   
-* } 
-* \par -* where N is the number of factors to generate and c is pi/(2*N) -*/ -static const float32_t cos_factors_128[128] = { - 0.999981175282601110f, 0.999830581795823400f, 0.999529417501093140f, - 0.999077727752645360f, - 0.998475580573294770f, 0.997723066644191640f, 0.996820299291165670f, - 0.995767414467659820f, - 0.994564570734255420f, 0.993211949234794500f, 0.991709753669099530f, - 0.990058210262297120f, - 0.988257567730749460f, 0.986308097244598670f, 0.984210092386929030f, - 0.981963869109555240f, - 0.979569765685440520f, 0.977028142657754390f, 0.974339382785575860f, - 0.971503890986251780f, - 0.968522094274417380f, 0.965394441697689400f, 0.962121404269041580f, - 0.958703474895871600f, - 0.955141168305770780f, 0.951435020969008340f, 0.947585591017741090f, - 0.943593458161960390f, - 0.939459223602189920f, 0.935183509938947610f, 0.930766961078983710f, - 0.926210242138311380f, - 0.921514039342042010f, 0.916679059921042700f, 0.911706032005429880f, - 0.906595704514915330f, - 0.901348847046022030f, 0.895966249756185220f, 0.890448723244757880f, - 0.884797098430937790f, - 0.879012226428633530f, 0.873094978418290090f, 0.867046245515692650f, - 0.860866938637767310f, - 0.854557988365400530f, 0.848120344803297230f, 0.841554977436898440f, - 0.834862874986380010f, - 0.828045045257755800f, 0.821102514991104650f, 0.814036329705948410f, - 0.806847553543799330f, - 0.799537269107905010f, 0.792106577300212390f, 0.784556597155575240f, - 0.776888465673232440f, - 0.769103337645579700f, 0.761202385484261780f, 0.753186799043612520f, - 0.745057785441466060f, - 0.736816568877369900f, 0.728464390448225200f, 0.720002507961381650f, - 0.711432195745216430f, - 0.702754744457225300f, 0.693971460889654000f, 0.685083667772700360f, - 0.676092703575316030f, - 0.666999922303637470f, 0.657806693297078640f, 0.648514401022112550f, - 0.639124444863775730f, - 0.629638238914927100f, 0.620057211763289210f, 0.610382806276309480f, - 0.600616479383868970f, - 0.590759701858874280f, 0.580813958095764530f, 0.570780745886967370f, - 0.560661576197336030f, - 0.550457972936604810f, 0.540171472729892970f, 0.529803624686294830f, - 0.519355990165589530f, - 0.508830142543106990f, 0.498227666972781870f, 0.487550160148436050f, - 0.476799230063322250f, - 0.465976495767966130f, 0.455083587126343840f, 0.444122144570429260f, - 0.433093818853152010f, - 0.422000270799799790f, 0.410843171057903910f, 0.399624199845646790f, - 0.388345046698826300f, - 0.377007410216418310f, 0.365612997804773960f, 0.354163525420490510f, - 0.342660717311994380f, - 0.331106305759876430f, 0.319502030816015750f, 0.307849640041534980f, - 0.296150888243623960f, - 0.284407537211271820f, 0.272621355449948980f, 0.260794117915275570f, - 0.248927605745720260f, - 0.237023605994367340f, 0.225083911359792780f, 0.213110319916091360f, - 0.201104634842091960f, - 0.189068664149806280f, 0.177004220412148860f, 0.164913120489970090f, - 0.152797185258443410f, - 0.140658239332849240f, 0.128498110793793220f, 0.116318630911904880f, - 0.104121633872054730f, - 0.091908956497132696f, 0.079682437971430126f, 0.067443919563664106f, - 0.055195244349690031f, - 0.042938256934940959f, 0.030674803176636581f, 0.018406729905804820f, - 0.006135884649154515f -}; - -static const float32_t cos_factors_512[512] = { - 0.999998823451701880f, 0.999989411081928400f, 0.999970586430974140f, - 0.999942349676023910f, - 0.999904701082852900f, 0.999857641005823860f, 0.999801169887884260f, - 0.999735288260561680f, - 0.999659996743959220f, 0.999575296046749220f, 0.999481186966166950f, - 0.999377670388002850f, - 0.999264747286594420f, 0.999142418724816910f, 0.999010685854073380f, - 0.998869549914283560f, - 0.998719012233872940f, 0.998559074229759310f, 0.998389737407340160f, - 0.998211003360478190f, - 0.998022873771486240f, 0.997825350411111640f, 0.997618435138519550f, - 0.997402129901275300f, - 0.997176436735326190f, 0.996941357764982160f, 0.996696895202896060f, - 0.996443051350042630f, - 0.996179828595696980f, 0.995907229417411720f, 0.995625256380994310f, - 0.995333912140482280f, - 0.995033199438118630f, 0.994723121104325700f, 0.994403680057679100f, - 0.994074879304879370f, - 0.993736721940724600f, 0.993389211148080650f, 0.993032350197851410f, - 0.992666142448948020f, - 0.992290591348257370f, 0.991905700430609330f, 0.991511473318743900f, - 0.991107913723276890f, - 0.990695025442664630f, 0.990272812363169110f, 0.989841278458820530f, - 0.989400427791380380f, - 0.988950264510302990f, 0.988490792852696590f, 0.988022017143283530f, - 0.987543941794359230f, - 0.987056571305750970f, 0.986559910264775410f, 0.986053963346195440f, - 0.985538735312176060f, - 0.985014231012239840f, 0.984480455383220930f, 0.983937413449218920f, - 0.983385110321551180f, - 0.982823551198705240f, 0.982252741366289370f, 0.981672686196983110f, - 0.981083391150486710f, - 0.980484861773469380f, 0.979877103699517640f, 0.979260122649082020f, - 0.978633924429423210f, - 0.977998514934557140f, 0.977353900145199960f, 0.976700086128711840f, - 0.976037079039039020f, - 0.975364885116656980f, 0.974683510688510670f, 0.973992962167955830f, - 0.973293246054698250f, - 0.972584368934732210f, 0.971866337480279400f, 0.971139158449725090f, - 0.970402838687555500f, - 0.969657385124292450f, 0.968902804776428870f, 0.968139104746362440f, - 0.967366292222328510f, - 0.966584374478333120f, 0.965793358874083680f, 0.964993252854920320f, - 0.964184063951745830f, - 0.963365799780954050f, 0.962538468044359160f, 0.961702076529122540f, - 0.960856633107679660f, - 0.960002145737665960f, 0.959138622461841890f, 0.958266071408017670f, - 0.957384500788975860f, - 0.956493918902395100f, 0.955594334130771110f, 0.954685754941338340f, - 0.953768189885990330f, - 0.952841647601198720f, 0.951906136807932350f, 0.950961666311575080f, - 0.950008245001843000f, - 0.949045881852700560f, 0.948074585922276230f, 0.947094366352777220f, - 0.946105232370403450f, - 0.945107193285260610f, 0.944100258491272660f, 0.943084437466093490f, - 0.942059739771017310f, - 0.941026175050889260f, 0.939983753034014050f, 0.938932483532064600f, - 0.937872376439989890f, - 0.936803441735921560f, 0.935725689481080370f, 0.934639129819680780f, - 0.933543772978836170f, - 0.932439629268462360f, 0.931326709081180430f, 0.930205022892219070f, - 0.929074581259315860f, - 0.927935394822617890f, 0.926787474304581750f, 0.925630830509872720f, - 0.924465474325262600f, - 0.923291416719527640f, 0.922108668743345180f, 0.920917241529189520f, - 0.919717146291227360f, - 0.918508394325212250f, 0.917290997008377910f, 0.916064965799331720f, - 0.914830312237946200f, - 0.913587047945250810f, 0.912335184623322750f, 0.911074734055176360f, - 0.909805708104652220f, - 0.908528118716306120f, 0.907241977915295820f, 0.905947297807268460f, - 0.904644090578246240f, - 0.903332368494511820f, 0.902012143902493180f, 0.900683429228646970f, - 0.899346236979341570f, - 0.898000579740739880f, 0.896646470178680150f, 0.895283921038557580f, - 0.893912945145203250f, - 0.892533555402764580f, 0.891145764794583180f, 0.889749586383072780f, - 0.888345033309596350f, - 0.886932118794342190f, 0.885510856136199950f, 0.884081258712634990f, - 0.882643339979562790f, - 0.881197113471222090f, 0.879742592800047410f, 0.878279791656541580f, - 0.876808723809145650f, - 0.875329403104110890f, 0.873841843465366860f, 0.872346058894391540f, - 0.870842063470078980f, - 0.869329871348606840f, 0.867809496763303320f, 0.866280954024512990f, - 0.864744257519462380f, - 0.863199421712124160f, 0.861646461143081300f, 0.860085390429390140f, - 0.858516224264442740f, - 0.856938977417828760f, 0.855353664735196030f, 0.853760301138111410f, - 0.852158901623919830f, - 0.850549481265603480f, 0.848932055211639610f, 0.847306638685858320f, - 0.845673246987299070f, - 0.844031895490066410f, 0.842382599643185850f, 0.840725374970458070f, - 0.839060237070312740f, - 0.837387201615661940f, 0.835706284353752600f, 0.834017501106018130f, - 0.832320867767929680f, - 0.830616400308846310f, 0.828904114771864870f, 0.827184027273669130f, - 0.825456154004377550f, - 0.823720511227391430f, 0.821977115279241550f, 0.820225982569434690f, - 0.818467129580298660f, - 0.816700572866827850f, 0.814926329056526620f, 0.813144414849253590f, - 0.811354847017063730f, - 0.809557642404051260f, 0.807752817926190360f, 0.805940390571176280f, - 0.804120377398265810f, - 0.802292795538115720f, 0.800457662192622820f, 0.798614994634760820f, - 0.796764810208418830f, - 0.794907126328237010f, 0.793041960479443640f, 0.791169330217690200f, - 0.789289253168885650f, - 0.787401747029031430f, 0.785506829564053930f, 0.783604518609638200f, - 0.781694832071059390f, - 0.779777787923014550f, 0.777853404209453150f, 0.775921699043407690f, - 0.773982690606822900f, - 0.772036397150384520f, 0.770082836993347900f, 0.768122028523365420f, - 0.766153990196312920f, - 0.764178740536116670f, 0.762196298134578900f, 0.760206681651202420f, - 0.758209909813015280f, - 0.756206001414394540f, 0.754194975316889170f, 0.752176850449042810f, - 0.750151645806215070f, - 0.748119380450403600f, 0.746080073510063780f, 0.744033744179929290f, - 0.741980411720831070f, - 0.739920095459516200f, 0.737852814788465980f, 0.735778589165713590f, - 0.733697438114660370f, - 0.731609381223892630f, 0.729514438146997010f, 0.727412628602375770f, - 0.725303972373060770f, - 0.723188489306527460f, 0.721066199314508110f, 0.718937122372804490f, - 0.716801278521099540f, - 0.714658687862769090f, 0.712509370564692320f, 0.710353346857062420f, - 0.708190637033195400f, - 0.706021261449339740f, 0.703845240524484940f, 0.701662594740168570f, - 0.699473344640283770f, - 0.697277510830886630f, 0.695075113980000880f, 0.692866174817424740f, - 0.690650714134534720f, - 0.688428752784090550f, 0.686200311680038700f, 0.683965411797315510f, - 0.681724074171649820f, - 0.679476319899365080f, 0.677222170137180450f, 0.674961646102012040f, - 0.672694769070772970f, - 0.670421560380173090f, 0.668142041426518560f, 0.665856233665509720f, - 0.663564158612039880f, - 0.661265837839992270f, 0.658961292982037320f, 0.656650545729429050f, - 0.654333617831800550f, - 0.652010531096959500f, 0.649681307390683190f, 0.647345968636512060f, - 0.645004536815544040f, - 0.642657033966226860f, 0.640303482184151670f, 0.637943903621844170f, - 0.635578320488556230f, - 0.633206755050057190f, 0.630829229628424470f, 0.628445766601832710f, - 0.626056388404343520f, - 0.623661117525694640f, 0.621259976511087660f, 0.618852987960976320f, - 0.616440174530853650f, - 0.614021558931038490f, 0.611597163926462020f, 0.609167012336453210f, - 0.606731127034524480f, - 0.604289530948156070f, 0.601842247058580030f, 0.599389298400564540f, - 0.596930708062196500f, - 0.594466499184664540f, 0.591996694962040990f, 0.589521318641063940f, - 0.587040393520918080f, - 0.584553942953015330f, 0.582061990340775550f, 0.579564559139405740f, - 0.577061672855679550f, - 0.574553355047715760f, 0.572039629324757050f, 0.569520519346947250f, - 0.566996048825108680f, - 0.564466241520519500f, 0.561931121244689470f, 0.559390711859136140f, - 0.556845037275160100f, - 0.554294121453620110f, 0.551737988404707450f, 0.549176662187719770f, - 0.546610166910834860f, - 0.544038526730883930f, 0.541461765853123560f, 0.538879908531008420f, - 0.536292979065963180f, - 0.533701001807152960f, 0.531104001151255000f, 0.528502001542228480f, - 0.525895027471084740f, - 0.523283103475656430f, 0.520666254140367270f, 0.518044504095999340f, - 0.515417878019463150f, - 0.512786400633563070f, 0.510150096706766700f, 0.507508991052970870f, - 0.504863108531267480f, - 0.502212474045710900f, 0.499557112545081890f, 0.496897049022654640f, - 0.494232308515959730f, - 0.491562916106550060f, 0.488888896919763230f, 0.486210276124486530f, - 0.483527078932918740f, - 0.480839330600333900f, 0.478147056424843120f, 0.475450281747155870f, - 0.472749031950342900f, - 0.470043332459595620f, 0.467333208741988530f, 0.464618686306237820f, - 0.461899790702462840f, - 0.459176547521944150f, 0.456448982396883860f, 0.453717121000163930f, - 0.450980989045103810f, - 0.448240612285220000f, 0.445496016513981740f, 0.442747227564570130f, - 0.439994271309633260f, - 0.437237173661044200f, 0.434475960569655710f, 0.431710658025057370f, - 0.428941292055329550f, - 0.426167888726799620f, 0.423390474143796100f, 0.420609074448402510f, - 0.417823715820212380f, - 0.415034424476081630f, 0.412241226669883000f, 0.409444148692257590f, - 0.406643216870369140f, - 0.403838457567654130f, 0.401029897183575790f, 0.398217562153373620f, - 0.395401478947816300f, - 0.392581674072951530f, 0.389758174069856410f, 0.386931005514388690f, - 0.384100195016935040f, - 0.381265769222162490f, 0.378427754808765620f, 0.375586178489217330f, - 0.372741067009515810f, - 0.369892447148934270f, 0.367040345719767240f, 0.364184789567079840f, - 0.361325805568454340f, - 0.358463420633736540f, 0.355597661704783960f, 0.352728555755210730f, - 0.349856129790135030f, - 0.346980410845923680f, 0.344101425989938980f, 0.341219202320282410f, - 0.338333766965541290f, - 0.335445147084531660f, 0.332553369866044220f, 0.329658462528587550f, - 0.326760452320131790f, - 0.323859366517852960f, 0.320955232427875210f, 0.318048077385015060f, - 0.315137928752522440f, - 0.312224813921825050f, 0.309308760312268780f, 0.306389795370861080f, - 0.303467946572011370f, - 0.300543241417273400f, 0.297615707435086310f, 0.294685372180514330f, - 0.291752263234989370f, - 0.288816408206049480f, 0.285877834727080730f, 0.282936570457055390f, - 0.279992643080273380f, - 0.277046080306099950f, 0.274096909868706330f, 0.271145159526808070f, - 0.268190857063403180f, - 0.265234030285511900f, 0.262274707023913590f, 0.259312915132886350f, - 0.256348682489942910f, - 0.253382036995570270f, 0.250413006572965280f, 0.247441619167773440f, - 0.244467902747824210f, - 0.241491885302869300f, 0.238513594844318500f, 0.235533059404975460f, - 0.232550307038775330f, - 0.229565365820518870f, 0.226578263845610110f, 0.223589029229790020f, - 0.220597690108873650f, - 0.217604274638483670f, 0.214608810993786920f, 0.211611327369227610f, - 0.208611851978263460f, - 0.205610413053099320f, 0.202607038844421110f, 0.199601757621131050f, - 0.196594597670080220f, - 0.193585587295803750f, 0.190574754820252800f, 0.187562128582529740f, - 0.184547736938619640f, - 0.181531608261125130f, 0.178513770938997590f, 0.175494253377271400f, - 0.172473083996796030f, - 0.169450291233967930f, 0.166425903540464220f, 0.163399949382973230f, - 0.160372457242928400f, - 0.157343455616238280f, 0.154312973013020240f, 0.151281037957330250f, - 0.148247678986896200f, - 0.145212924652847520f, 0.142176803519448000f, 0.139139344163826280f, - 0.136100575175706200f, - 0.133060525157139180f, 0.130019222722233350f, 0.126976696496885980f, - 0.123932975118512200f, - 0.120888087235777220f, 0.117842061508325020f, 0.114794926606510250f, - 0.111746711211126660f, - 0.108697444013138670f, 0.105647153713410700f, 0.102595869022436280f, - 0.099543618660069444f, - 0.096490431355252607f, 0.093436335845747912f, 0.090381360877865011f, - 0.087325535206192226f, - 0.084268887593324127f, 0.081211446809592386f, 0.078153241632794315f, - 0.075094300847921291f, - 0.072034653246889416f, 0.068974327628266732f, 0.065913352797003930f, - 0.062851757564161420f, - 0.059789570746640007f, 0.056726821166907783f, 0.053663537652730679f, - 0.050599749036899337f, - 0.047535484156959261f, 0.044470771854938744f, 0.041405640977076712f, - 0.038340120373552791f, - 0.035274238898213947f, 0.032208025408304704f, 0.029141508764193740f, - 0.026074717829104040f, - 0.023007681468839410f, 0.019940428551514598f, 0.016872987947281773f, - 0.013805388528060349f, - 0.010737659167264572f, 0.007669828739531077f, 0.004601926120448672f, - 0.001533980186284766f -}; - -static const float32_t cos_factors_2048[2048] = { - 0.999999926465717890f, 0.999999338191525530f, 0.999998161643486980f, - 0.999996396822294350f, - 0.999994043728985820f, 0.999991102364945590f, 0.999987572731904080f, - 0.999983454831937730f, - 0.999978748667468830f, 0.999973454241265940f, 0.999967571556443780f, - 0.999961100616462820f, - 0.999954041425129780f, 0.999946393986597460f, 0.999938158305364590f, - 0.999929334386276070f, - 0.999919922234522750f, 0.999909921855641540f, 0.999899333255515390f, - 0.999888156440373320f, - 0.999876391416790410f, 0.999864038191687680f, 0.999851096772332190f, - 0.999837567166337090f, - 0.999823449381661570f, 0.999808743426610520f, 0.999793449309835270f, - 0.999777567040332940f, - 0.999761096627446610f, 0.999744038080865430f, 0.999726391410624470f, - 0.999708156627104880f, - 0.999689333741033640f, 0.999669922763483760f, 0.999649923705874240f, - 0.999629336579970110f, - 0.999608161397882110f, 0.999586398172067070f, 0.999564046915327740f, - 0.999541107640812940f, - 0.999517580362016990f, 0.999493465092780590f, 0.999468761847290050f, - 0.999443470640077770f, - 0.999417591486021720f, 0.999391124400346050f, 0.999364069398620550f, - 0.999336426496761240f, - 0.999308195711029470f, 0.999279377058032710f, 0.999249970554724420f, - 0.999219976218403530f, - 0.999189394066714920f, 0.999158224117649430f, 0.999126466389543390f, - 0.999094120901079070f, - 0.999061187671284600f, 0.999027666719533690f, 0.998993558065545680f, - 0.998958861729386080f, - 0.998923577731465780f, 0.998887706092541290f, 0.998851246833715180f, - 0.998814199976435390f, - 0.998776565542495610f, 0.998738343554035230f, 0.998699534033539280f, - 0.998660137003838490f, - 0.998620152488108870f, 0.998579580509872500f, 0.998538421092996730f, - 0.998496674261694640f, - 0.998454340040524800f, 0.998411418454391300f, 0.998367909528543820f, - 0.998323813288577560f, - 0.998279129760433200f, 0.998233858970396850f, 0.998188000945100300f, - 0.998141555711520520f, - 0.998094523296980010f, 0.998046903729146840f, 0.997998697036034390f, - 0.997949903246001190f, - 0.997900522387751620f, 0.997850554490335110f, 0.997799999583146470f, - 0.997748857695925690f, - 0.997697128858758500f, 0.997644813102075420f, 0.997591910456652630f, - 0.997538420953611340f, - 0.997484344624417930f, 0.997429681500884180f, 0.997374431615167150f, - 0.997318594999768600f, - 0.997262171687536170f, 0.997205161711661850f, 0.997147565105683480f, - 0.997089381903483400f, - 0.997030612139289450f, 0.996971255847674320f, 0.996911313063555740f, - 0.996850783822196610f, - 0.996789668159204560f, 0.996727966110532490f, 0.996665677712478160f, - 0.996602803001684130f, - 0.996539342015137940f, 0.996475294790172160f, 0.996410661364464100f, - 0.996345441776035900f, - 0.996279636063254650f, 0.996213244264832040f, 0.996146266419824620f, - 0.996078702567633980f, - 0.996010552748005870f, 0.995941817001031350f, 0.995872495367145730f, - 0.995802587887129160f, - 0.995732094602106430f, 0.995661015553546910f, 0.995589350783264600f, - 0.995517100333418110f, - 0.995444264246510340f, 0.995370842565388990f, 0.995296835333246090f, - 0.995222242593618360f, - 0.995147064390386470f, 0.995071300767776170f, 0.994994951770357020f, - 0.994918017443043200f, - 0.994840497831093180f, 0.994762392980109930f, 0.994683702936040250f, - 0.994604427745175660f, - 0.994524567454151740f, 0.994444122109948040f, 0.994363091759888570f, - 0.994281476451641550f, - 0.994199276233218910f, 0.994116491152977070f, 0.994033121259616400f, - 0.993949166602181130f, - 0.993864627230059750f, 0.993779503192984580f, 0.993693794541031790f, - 0.993607501324621610f, - 0.993520623594518090f, 0.993433161401829360f, 0.993345114798006910f, - 0.993256483834846440f, - 0.993167268564487230f, 0.993077469039412300f, 0.992987085312448390f, - 0.992896117436765980f, - 0.992804565465879140f, 0.992712429453645460f, 0.992619709454266140f, - 0.992526405522286100f, - 0.992432517712593660f, 0.992338046080420420f, 0.992242990681341700f, - 0.992147351571276090f, - 0.992051128806485720f, 0.991954322443575950f, 0.991856932539495470f, - 0.991758959151536110f, - 0.991660402337333210f, 0.991561262154865290f, 0.991461538662453790f, - 0.991361231918763460f, - 0.991260341982802440f, 0.991158868913921350f, 0.991056812771814340f, - 0.990954173616518500f, - 0.990850951508413620f, 0.990747146508222710f, 0.990642758677011570f, - 0.990537788076188750f, - 0.990432234767505970f, 0.990326098813057330f, 0.990219380275280000f, - 0.990112079216953770f, - 0.990004195701200910f, 0.989895729791486660f, 0.989786681551618640f, - 0.989677051045747210f, - 0.989566838338365120f, 0.989456043494307710f, 0.989344666578752640f, - 0.989232707657220050f, - 0.989120166795572690f, 0.989007044060015270f, 0.988893339517095130f, - 0.988779053233701520f, - 0.988664185277066230f, 0.988548735714763200f, 0.988432704614708340f, - 0.988316092045159690f, - 0.988198898074717610f, 0.988081122772324070f, 0.987962766207263420f, - 0.987843828449161740f, - 0.987724309567986960f, 0.987604209634049160f, 0.987483528717999710f, - 0.987362266890832400f, - 0.987240424223882250f, 0.987118000788826280f, 0.986994996657682980f, - 0.986871411902812470f, - 0.986747246596916590f, 0.986622500813038480f, 0.986497174624562880f, - 0.986371268105216030f, - 0.986244781329065460f, 0.986117714370520090f, 0.985990067304330140f, - 0.985861840205586980f, - 0.985733033149723490f, 0.985603646212513400f, 0.985473679470071810f, - 0.985343132998854790f, - 0.985212006875659350f, 0.985080301177623800f, 0.984948015982227030f, - 0.984815151367289140f, - 0.984681707410970940f, 0.984547684191773960f, 0.984413081788540700f, - 0.984277900280454370f, - 0.984142139747038570f, 0.984005800268157870f, 0.983868881924017220f, - 0.983731384795162090f, - 0.983593308962478650f, 0.983454654507193270f, 0.983315421510872810f, - 0.983175610055424420f, - 0.983035220223095640f, 0.982894252096474070f, 0.982752705758487830f, - 0.982610581292404750f, - 0.982467878781833170f, 0.982324598310721280f, 0.982180739963357090f, - 0.982036303824369020f, - 0.981891289978725100f, 0.981745698511732990f, 0.981599529509040720f, - 0.981452783056635520f, - 0.981305459240844670f, 0.981157558148334830f, 0.981009079866112630f, - 0.980860024481523870f, - 0.980710392082253970f, 0.980560182756327840f, 0.980409396592109910f, - 0.980258033678303550f, - 0.980106094103951770f, 0.979953577958436740f, 0.979800485331479790f, - 0.979646816313141210f, - 0.979492570993820810f, 0.979337749464256780f, 0.979182351815526930f, - 0.979026378139047580f, - 0.978869828526574120f, 0.978712703070200420f, 0.978555001862359550f, - 0.978396724995823090f, - 0.978237872563701090f, 0.978078444659442380f, 0.977918441376834370f, - 0.977757862810002760f, - 0.977596709053411890f, 0.977434980201864260f, 0.977272676350500860f, - 0.977109797594800880f, - 0.976946344030581670f, 0.976782315753998650f, 0.976617712861545640f, - 0.976452535450054060f, - 0.976286783616693630f, 0.976120457458971910f, 0.975953557074734300f, - 0.975786082562163930f, - 0.975618034019781750f, 0.975449411546446380f, 0.975280215241354220f, - 0.975110445204038890f, - 0.974940101534371830f, 0.974769184332561770f, 0.974597693699155050f, - 0.974425629735034990f, - 0.974252992541422500f, 0.974079782219875680f, 0.973905998872289570f, - 0.973731642600896400f, - 0.973556713508265560f, 0.973381211697303290f, 0.973205137271252800f, - 0.973028490333694210f, - 0.972851270988544180f, 0.972673479340056430f, 0.972495115492821190f, - 0.972316179551765300f, - 0.972136671622152230f, 0.971956591809581720f, 0.971775940219990140f, - 0.971594716959650160f, - 0.971412922135170940f, 0.971230555853497380f, 0.971047618221911100f, - 0.970864109348029470f, - 0.970680029339806130f, 0.970495378305530560f, 0.970310156353828110f, - 0.970124363593660280f, - 0.969938000134323960f, 0.969751066085452140f, 0.969563561557013180f, - 0.969375486659311280f, - 0.969186841502985950f, 0.968997626199012420f, 0.968807840858700970f, - 0.968617485593697540f, - 0.968426560515983190f, 0.968235065737874320f, 0.968043001372022260f, - 0.967850367531413620f, - 0.967657164329369880f, 0.967463391879547550f, 0.967269050295937790f, - 0.967074139692867040f, - 0.966878660184995910f, 0.966682611887320080f, 0.966485994915169840f, - 0.966288809384209690f, - 0.966091055410438830f, 0.965892733110190860f, 0.965693842600133690f, - 0.965494383997269500f, - 0.965294357418934660f, 0.965093762982799590f, 0.964892600806868890f, - 0.964690871009481030f, - 0.964488573709308410f, 0.964285709025357480f, 0.964082277076968140f, - 0.963878277983814200f, - 0.963673711865903230f, 0.963468578843575950f, 0.963262879037507070f, - 0.963056612568704340f, - 0.962849779558509030f, 0.962642380128595710f, 0.962434414400972100f, - 0.962225882497979020f, - 0.962016784542290560f, 0.961807120656913540f, 0.961596890965187860f, - 0.961386095590786250f, - 0.961174734657714080f, 0.960962808290309780f, 0.960750316613243950f, - 0.960537259751520050f, - 0.960323637830473920f, 0.960109450975773940f, 0.959894699313420530f, - 0.959679382969746750f, - 0.959463502071417510f, 0.959247056745430090f, 0.959030047119113660f, - 0.958812473320129310f, - 0.958594335476470220f, 0.958375633716461170f, 0.958156368168758820f, - 0.957936538962351420f, - 0.957716146226558870f, 0.957495190091032570f, 0.957273670685755200f, - 0.957051588141040970f, - 0.956828942587535370f, 0.956605734156215080f, 0.956381962978387730f, - 0.956157629185692140f, - 0.955932732910098280f, 0.955707274283906560f, 0.955481253439748770f, - 0.955254670510586990f, - 0.955027525629714160f, 0.954799818930753720f, 0.954571550547659630f, - 0.954342720614716480f, - 0.954113329266538800f, 0.953883376638071770f, 0.953652862864590500f, - 0.953421788081700310f, - 0.953190152425336670f, 0.952957956031764700f, 0.952725199037579570f, - 0.952491881579706320f, - 0.952258003795399600f, 0.952023565822243570f, 0.951788567798152130f, - 0.951553009861368590f, - 0.951316892150465550f, 0.951080214804345010f, 0.950842977962238160f, - 0.950605181763705340f, - 0.950366826348635780f, 0.950127911857248100f, 0.949888438430089300f, - 0.949648406208035480f, - 0.949407815332291570f, 0.949166665944390700f, 0.948924958186195160f, - 0.948682692199895090f, - 0.948439868128009620f, 0.948196486113385580f, 0.947952546299198670f, - 0.947708048828952100f, - 0.947462993846477700f, 0.947217381495934820f, 0.946971211921810880f, - 0.946724485268921170f, - 0.946477201682408680f, 0.946229361307743820f, 0.945980964290724760f, - 0.945732010777477150f, - 0.945482500914453740f, 0.945232434848435000f, 0.944981812726528150f, - 0.944730634696167800f, - 0.944478900905115550f, 0.944226611501459810f, 0.943973766633615980f, - 0.943720366450326200f, - 0.943466411100659320f, 0.943211900734010620f, 0.942956835500102120f, - 0.942701215548981900f, - 0.942445041031024890f, 0.942188312096931770f, 0.941931028897729620f, - 0.941673191584771360f, - 0.941414800309736340f, 0.941155855224629190f, 0.940896356481780830f, - 0.940636304233847590f, - 0.940375698633811540f, 0.940114539834980280f, 0.939852827990986680f, - 0.939590563255789270f, - 0.939327745783671400f, 0.939064375729241950f, 0.938800453247434770f, - 0.938535978493508560f, - 0.938270951623047190f, 0.938005372791958840f, 0.937739242156476970f, - 0.937472559873159250f, - 0.937205326098887960f, 0.936937540990869900f, 0.936669204706636170f, - 0.936400317404042060f, - 0.936130879241267030f, 0.935860890376814640f, 0.935590350969512370f, - 0.935319261178511610f, - 0.935047621163287430f, 0.934775431083638700f, 0.934502691099687870f, - 0.934229401371880820f, - 0.933955562060986730f, 0.933681173328098410f, 0.933406235334631520f, - 0.933130748242325230f, - 0.932854712213241120f, 0.932578127409764420f, 0.932300993994602760f, - 0.932023312130786490f, - 0.931745081981668720f, 0.931466303710925090f, 0.931186977482553750f, - 0.930907103460875130f, - 0.930626681810531760f, 0.930345712696488470f, 0.930064196284032360f, - 0.929782132738772190f, - 0.929499522226638560f, 0.929216364913884040f, 0.928932660967082820f, - 0.928648410553130520f, - 0.928363613839244370f, 0.928078270992963140f, 0.927792382182146320f, - 0.927505947574975180f, - 0.927218967339951790f, 0.926931441645899130f, 0.926643370661961230f, - 0.926354754557602860f, - 0.926065593502609310f, 0.925775887667086740f, 0.925485637221461490f, - 0.925194842336480530f, - 0.924903503183210910f, 0.924611619933039970f, 0.924319192757675160f, - 0.924026221829143850f, - 0.923732707319793290f, 0.923438649402290370f, 0.923144048249621930f, - 0.922848904035094120f, - 0.922553216932332830f, 0.922256987115283030f, 0.921960214758209220f, - 0.921662900035694730f, - 0.921365043122642340f, 0.921066644194273640f, 0.920767703426128790f, - 0.920468220994067110f, - 0.920168197074266340f, 0.919867631843222950f, 0.919566525477751530f, - 0.919264878154985370f, - 0.918962690052375630f, 0.918659961347691900f, 0.918356692219021720f, - 0.918052882844770380f, - 0.917748533403661250f, 0.917443644074735220f, 0.917138215037350710f, - 0.916832246471183890f, - 0.916525738556228210f, 0.916218691472794220f, 0.915911105401509880f, - 0.915602980523320230f, - 0.915294317019487050f, 0.914985115071589310f, 0.914675374861522390f, - 0.914365096571498560f, - 0.914054280384046570f, 0.913742926482011390f, 0.913431035048554720f, - 0.913118606267154240f, - 0.912805640321603500f, 0.912492137396012650f, 0.912178097674807180f, - 0.911863521342728520f, - 0.911548408584833990f, 0.911232759586496190f, 0.910916574533403360f, - 0.910599853611558930f, - 0.910282597007281760f, 0.909964804907205660f, 0.909646477498279540f, - 0.909327614967767260f, - 0.909008217503247450f, 0.908688285292613360f, 0.908367818524072890f, - 0.908046817386148340f, - 0.907725282067676440f, 0.907403212757808110f, 0.907080609646008450f, - 0.906757472922056550f, - 0.906433802776045460f, 0.906109599398381980f, 0.905784862979786550f, - 0.905459593711293250f, - 0.905133791784249690f, 0.904807457390316540f, 0.904480590721468250f, - 0.904153191969991780f, - 0.903825261328487510f, 0.903496798989868450f, 0.903167805147360720f, - 0.902838279994502830f, - 0.902508223725145940f, 0.902177636533453620f, 0.901846518613901750f, - 0.901514870161278740f, - 0.901182691370684520f, 0.900849982437531450f, 0.900516743557543520f, - 0.900182974926756810f, - 0.899848676741518580f, 0.899513849198487980f, 0.899178492494635330f, - 0.898842606827242370f, - 0.898506192393901950f, 0.898169249392518080f, 0.897831778021305650f, - 0.897493778478790310f, - 0.897155250963808550f, 0.896816195675507300f, 0.896476612813344120f, - 0.896136502577086770f, - 0.895795865166813530f, 0.895454700782912450f, 0.895113009626081760f, - 0.894770791897329550f, - 0.894428047797973800f, 0.894084777529641990f, 0.893740981294271040f, - 0.893396659294107720f, - 0.893051811731707450f, 0.892706438809935390f, 0.892360540731965360f, - 0.892014117701280470f, - 0.891667169921672280f, 0.891319697597241390f, 0.890971700932396860f, - 0.890623180131855930f, - 0.890274135400644600f, 0.889924566944096720f, 0.889574474967854580f, - 0.889223859677868210f, - 0.888872721280395630f, 0.888521059982002260f, 0.888168875989561730f, - 0.887816169510254440f, - 0.887462940751568840f, 0.887109189921300170f, 0.886754917227550840f, - 0.886400122878730600f, - 0.886044807083555600f, 0.885688970051048960f, 0.885332611990540590f, - 0.884975733111666660f, - 0.884618333624369920f, 0.884260413738899190f, 0.883901973665809470f, - 0.883543013615961880f, - 0.883183533800523390f, 0.882823534430966620f, 0.882463015719070150f, - 0.882101977876917580f, - 0.881740421116898320f, 0.881378345651706920f, 0.881015751694342870f, - 0.880652639458111010f, - 0.880289009156621010f, 0.879924861003786860f, 0.879560195213827890f, - 0.879195012001267480f, - 0.878829311580933360f, 0.878463094167957870f, 0.878096359977777130f, - 0.877729109226131570f, - 0.877361342129065140f, 0.876993058902925890f, 0.876624259764365310f, - 0.876254944930338510f, - 0.875885114618103810f, 0.875514769045222850f, 0.875143908429560360f, - 0.874772532989284150f, - 0.874400642942864790f, 0.874028238509075740f, 0.873655319906992630f, - 0.873281887355994210f, - 0.872907941075761080f, 0.872533481286276170f, 0.872158508207824480f, - 0.871783022060993120f, - 0.871407023066670950f, 0.871030511446048260f, 0.870653487420617430f, - 0.870275951212171940f, - 0.869897903042806340f, 0.869519343134916860f, 0.869140271711200560f, - 0.868760688994655310f, - 0.868380595208579800f, 0.867999990576573510f, 0.867618875322536230f, - 0.867237249670668400f, - 0.866855113845470430f, 0.866472468071743050f, 0.866089312574586770f, - 0.865705647579402380f, - 0.865321473311889800f, 0.864936789998049020f, 0.864551597864179340f, - 0.864165897136879300f, - 0.863779688043046720f, 0.863392970809878420f, 0.863005745664870320f, - 0.862618012835816740f, - 0.862229772550811240f, 0.861841025038245330f, 0.861451770526809320f, - 0.861062009245491480f, - 0.860671741423578380f, 0.860280967290654510f, 0.859889687076602290f, - 0.859497901011601730f, - 0.859105609326130450f, 0.858712812250963520f, 0.858319510017173440f, - 0.857925702856129790f, - 0.857531390999499150f, 0.857136574679244980f, 0.856741254127627470f, - 0.856345429577203610f, - 0.855949101260826910f, 0.855552269411646860f, 0.855154934263109620f, - 0.854757096048957220f, - 0.854358755003227440f, 0.853959911360254180f, 0.853560565354666840f, - 0.853160717221390420f, - 0.852760367195645300f, 0.852359515512947090f, 0.851958162409106380f, - 0.851556308120228980f, - 0.851153952882715340f, 0.850751096933260790f, 0.850347740508854980f, - 0.849943883846782210f, - 0.849539527184620890f, 0.849134670760243630f, 0.848729314811817130f, - 0.848323459577801640f, - 0.847917105296951410f, 0.847510252208314330f, 0.847102900551231500f, - 0.846695050565337450f, - 0.846286702490559710f, 0.845877856567119000f, 0.845468513035528830f, - 0.845058672136595470f, - 0.844648334111417820f, 0.844237499201387020f, 0.843826167648186740f, - 0.843414339693792760f, - 0.843002015580472940f, 0.842589195550786710f, 0.842175879847585570f, - 0.841762068714012490f, - 0.841347762393501950f, 0.840932961129779780f, 0.840517665166862550f, - 0.840101874749058400f, - 0.839685590120966110f, 0.839268811527475230f, 0.838851539213765760f, - 0.838433773425308340f, - 0.838015514407863820f, 0.837596762407483040f, 0.837177517670507300f, - 0.836757780443567190f, - 0.836337550973583530f, 0.835916829507766360f, 0.835495616293615350f, - 0.835073911578919410f, - 0.834651715611756440f, 0.834229028640493420f, 0.833805850913786340f, - 0.833382182680579730f, - 0.832958024190106670f, 0.832533375691888680f, 0.832108237435735590f, - 0.831682609671745120f, - 0.831256492650303210f, 0.830829886622083570f, 0.830402791838047550f, - 0.829975208549443950f, - 0.829547137007808910f, 0.829118577464965980f, 0.828689530173025820f, - 0.828259995384385660f, - 0.827829973351729920f, 0.827399464328029470f, 0.826968468566541600f, - 0.826536986320809960f, - 0.826105017844664610f, 0.825672563392221390f, 0.825239623217882250f, - 0.824806197576334330f, - 0.824372286722551250f, 0.823937890911791370f, 0.823503010399598500f, - 0.823067645441801670f, - 0.822631796294514990f, 0.822195463214137170f, 0.821758646457351750f, - 0.821321346281126740f, - 0.820883562942714580f, 0.820445296699652050f, 0.820006547809759680f, - 0.819567316531142230f, - 0.819127603122188240f, 0.818687407841569680f, 0.818246730948242070f, - 0.817805572701444270f, - 0.817363933360698460f, 0.816921813185809480f, 0.816479212436865390f, - 0.816036131374236810f, - 0.815592570258576790f, 0.815148529350820830f, 0.814704008912187080f, - 0.814259009204175270f, - 0.813813530488567190f, 0.813367573027426570f, 0.812921137083098770f, - 0.812474222918210480f, - 0.812026830795669730f, 0.811578960978665890f, 0.811130613730669190f, - 0.810681789315430780f, - 0.810232487996982330f, 0.809782710039636530f, 0.809332455707985950f, - 0.808881725266903610f, - 0.808430518981542720f, 0.807978837117336310f, 0.807526679939997160f, - 0.807074047715517610f, - 0.806620940710169650f, 0.806167359190504420f, 0.805713303423352230f, - 0.805258773675822210f, - 0.804803770215302920f, 0.804348293309460780f, 0.803892343226241260f, - 0.803435920233868120f, - 0.802979024600843250f, 0.802521656595946430f, 0.802063816488235440f, - 0.801605504547046150f, - 0.801146721041991360f, 0.800687466242961610f, 0.800227740420124790f, - 0.799767543843925680f, - 0.799306876785086160f, 0.798845739514604580f, 0.798384132303756380f, - 0.797922055424093000f, - 0.797459509147442460f, 0.796996493745908750f, 0.796533009491872000f, - 0.796069056657987990f, - 0.795604635517188070f, 0.795139746342679590f, 0.794674389407944550f, - 0.794208564986740640f, - 0.793742273353100210f, 0.793275514781330630f, 0.792808289546014120f, - 0.792340597922007170f, - 0.791872440184440470f, 0.791403816608719500f, 0.790934727470523290f, - 0.790465173045804880f, - 0.789995153610791090f, 0.789524669441982190f, 0.789053720816151880f, - 0.788582308010347120f, - 0.788110431301888070f, 0.787638090968367450f, 0.787165287287651010f, - 0.786692020537876790f, - 0.786218290997455660f, 0.785744098945070360f, 0.785269444659675850f, - 0.784794328420499230f, - 0.784318750507038920f, 0.783842711199065230f, 0.783366210776619720f, - 0.782889249520015480f, - 0.782411827709836530f, 0.781933945626937630f, 0.781455603552444590f, - 0.780976801767753750f, - 0.780497540554531910f, 0.780017820194715990f, 0.779537640970513260f, - 0.779057003164400630f, - 0.778575907059125050f, 0.778094352937702790f, 0.777612341083420030f, - 0.777129871779831620f, - 0.776646945310762060f, 0.776163561960304340f, 0.775679722012820650f, - 0.775195425752941420f, - 0.774710673465565550f, 0.774225465435860680f, 0.773739801949261840f, - 0.773253683291472590f, - 0.772767109748463850f, 0.772280081606474320f, 0.771792599152010150f, - 0.771304662671844830f, - 0.770816272453018540f, 0.770327428782838890f, 0.769838131948879840f, - 0.769348382238982280f, - 0.768858179941253270f, 0.768367525344066270f, 0.767876418736060610f, - 0.767384860406141730f, - 0.766892850643480670f, 0.766400389737514230f, 0.765907477977944340f, - 0.765414115654738270f, - 0.764920303058128410f, 0.764426040478612070f, 0.763931328206951090f, - 0.763436166534172010f, - 0.762940555751565720f, 0.762444496150687210f, 0.761947988023355390f, - 0.761451031661653620f, - 0.760953627357928150f, 0.760455775404789260f, 0.759957476095110330f, - 0.759458729722028210f, - 0.758959536578942440f, 0.758459896959515430f, 0.757959811157672300f, - 0.757459279467600720f, - 0.756958302183750490f, 0.756456879600833740f, 0.755955012013824420f, - 0.755452699717958250f, - 0.754949943008732640f, 0.754446742181906440f, 0.753943097533499640f, - 0.753439009359793580f, - 0.752934477957330150f, 0.752429503622912390f, 0.751924086653603550f, - 0.751418227346727470f, - 0.750911925999867890f, 0.750405182910869330f, 0.749897998377835330f, - 0.749390372699129560f, - 0.748882306173375150f, 0.748373799099454560f, 0.747864851776509410f, - 0.747355464503940190f, - 0.746845637581406540f, 0.746335371308826320f, 0.745824665986376090f, - 0.745313521914490520f, - 0.744801939393862630f, 0.744289918725443260f, 0.743777460210440890f, - 0.743264564150321600f, - 0.742751230846809050f, 0.742237460601884000f, 0.741723253717784140f, - 0.741208610497004260f, - 0.740693531242295760f, 0.740178016256666240f, 0.739662065843380010f, - 0.739145680305957510f, - 0.738628859948174840f, 0.738111605074064260f, 0.737593915987913570f, - 0.737075792994265730f, - 0.736557236397919150f, 0.736038246503927350f, 0.735518823617598900f, - 0.734998968044496710f, - 0.734478680090438370f, 0.733957960061495940f, 0.733436808263995710f, - 0.732915225004517780f, - 0.732393210589896040f, 0.731870765327218290f, 0.731347889523825570f, - 0.730824583487312160f, - 0.730300847525525490f, 0.729776681946566090f, 0.729252087058786970f, - 0.728727063170793830f, - 0.728201610591444610f, 0.727675729629849610f, 0.727149420595371020f, - 0.726622683797622850f, - 0.726095519546471000f, 0.725567928152032300f, 0.725039909924675370f, - 0.724511465175019630f, - 0.723982594213935520f, 0.723453297352544380f, 0.722923574902217700f, - 0.722393427174577550f, - 0.721862854481496340f, 0.721331857135096290f, 0.720800435447749190f, - 0.720268589732077190f, - 0.719736320300951030f, 0.719203627467491220f, 0.718670511545067230f, - 0.718136972847297490f, - 0.717603011688049080f, 0.717068628381437480f, 0.716533823241826680f, - 0.715998596583828690f, - 0.715462948722303760f, 0.714926879972359490f, 0.714390390649351390f, - 0.713853481068882470f, - 0.713316151546802610f, 0.712778402399208980f, 0.712240233942445510f, - 0.711701646493102970f, - 0.711162640368018350f, 0.710623215884275020f, 0.710083373359202800f, - 0.709543113110376770f, - 0.709002435455618250f, 0.708461340712994160f, 0.707919829200816310f, - 0.707377901237642100f, - 0.706835557142273860f, 0.706292797233758480f, 0.705749621831387790f, - 0.705206031254697830f, - 0.704662025823468930f, 0.704117605857725430f, 0.703572771677735580f, - 0.703027523604011220f, - 0.702481861957308000f, 0.701935787058624360f, 0.701389299229202230f, - 0.700842398790526230f, - 0.700295086064323780f, 0.699747361372564990f, 0.699199225037462120f, - 0.698650677381469580f, - 0.698101718727283880f, 0.697552349397843270f, 0.697002569716327460f, - 0.696452380006157830f, - 0.695901780590996830f, 0.695350771794747800f, 0.694799353941554900f, - 0.694247527355803310f, - 0.693695292362118350f, 0.693142649285365510f, 0.692589598450650380f, - 0.692036140183318830f, - 0.691482274808955850f, 0.690928002653386280f, 0.690373324042674040f, - 0.689818239303122470f, - 0.689262748761273470f, 0.688706852743907750f, 0.688150551578044830f, - 0.687593845590942170f, - 0.687036735110095660f, 0.686479220463238950f, 0.685921301978343670f, - 0.685362979983618730f, - 0.684804254807510620f, 0.684245126778703080f, 0.683685596226116690f, - 0.683125663478908800f, - 0.682565328866473250f, 0.682004592718440830f, 0.681443455364677990f, - 0.680881917135287340f, - 0.680319978360607200f, 0.679757639371212030f, 0.679194900497911200f, - 0.678631762071749470f, - 0.678068224424006600f, 0.677504287886197430f, 0.676939952790071240f, - 0.676375219467611700f, - 0.675810088251037060f, 0.675244559472799270f, 0.674678633465584540f, - 0.674112310562312360f, - 0.673545591096136100f, 0.672978475400442090f, 0.672410963808849900f, - 0.671843056655211930f, - 0.671274754273613490f, 0.670706056998372160f, 0.670136965164037760f, - 0.669567479105392490f, - 0.668997599157450270f, 0.668427325655456820f, 0.667856658934889440f, - 0.667285599331456480f, - 0.666714147181097670f, 0.666142302819983540f, 0.665570066584515560f, - 0.664997438811325340f, - 0.664424419837275180f, 0.663851009999457340f, 0.663277209635194100f, - 0.662703019082037440f, - 0.662128438677768720f, 0.661553468760399000f, 0.660978109668168060f, - 0.660402361739545030f, - 0.659826225313227430f, 0.659249700728141490f, 0.658672788323441890f, - 0.658095488438511290f, - 0.657517801412960120f, 0.656939727586627110f, 0.656361267299578000f, - 0.655782420892106030f, - 0.655203188704731930f, 0.654623571078202680f, 0.654043568353492640f, - 0.653463180871802330f, - 0.652882408974558960f, 0.652301253003415460f, 0.651719713300251020f, - 0.651137790207170330f, - 0.650555484066503990f, 0.649972795220807530f, 0.649389724012861770f, - 0.648806270785672550f, - 0.648222435882470420f, 0.647638219646710420f, 0.647053622422071650f, - 0.646468644552457890f, - 0.645883286381996440f, 0.645297548255038380f, 0.644711430516158420f, - 0.644124933510154540f, - 0.643538057582047850f, 0.642950803077082080f, 0.642363170340724320f, - 0.641775159718663500f, - 0.641186771556811250f, 0.640598006201301030f, 0.640008863998488440f, - 0.639419345294950700f, - 0.638829450437486400f, 0.638239179773115390f, 0.637648533649078810f, - 0.637057512412838590f, - 0.636466116412077180f, 0.635874345994697720f, 0.635282201508823530f, - 0.634689683302797850f, - 0.634096791725183740f, 0.633503527124764320f, 0.632909889850541860f, - 0.632315880251737680f, - 0.631721498677792370f, 0.631126745478365340f, 0.630531621003334600f, - 0.629936125602796550f, - 0.629340259627065750f, 0.628744023426674790f, 0.628147417352374120f, - 0.627550441755131530f, - 0.626953096986132770f, 0.626355383396779990f, 0.625757301338692900f, - 0.625158851163707730f, - 0.624560033223877320f, 0.623960847871470770f, 0.623361295458973340f, - 0.622761376339086460f, - 0.622161090864726930f, 0.621560439389027270f, 0.620959422265335180f, - 0.620358039847213830f, - 0.619756292488440660f, 0.619154180543008410f, 0.618551704365123860f, - 0.617948864309208260f, - 0.617345660729896940f, 0.616742093982038830f, 0.616138164420696910f, - 0.615533872401147430f, - 0.614929218278879590f, 0.614324202409595950f, 0.613718825149211830f, - 0.613113086853854910f, - 0.612506987879865570f, 0.611900528583796070f, 0.611293709322411010f, - 0.610686530452686280f, - 0.610078992331809620f, 0.609471095317180240f, 0.608862839766408200f, - 0.608254226037314490f, - 0.607645254487930830f, 0.607035925476499760f, 0.606426239361473550f, - 0.605816196501515080f, - 0.605205797255496500f, 0.604595041982500360f, 0.603983931041818020f, - 0.603372464792950370f, - 0.602760643595607220f, 0.602148467809707320f, 0.601535937795377730f, - 0.600923053912954090f, - 0.600309816522980430f, 0.599696225986208310f, 0.599082282663597310f, - 0.598467986916314310f, - 0.597853339105733910f, 0.597238339593437530f, 0.596622988741213330f, - 0.596007286911056530f, - 0.595391234465168730f, 0.594774831765957580f, 0.594158079176036800f, - 0.593540977058226390f, - 0.592923525775551410f, 0.592305725691242400f, 0.591687577168735550f, - 0.591069080571671510f, - 0.590450236263895920f, 0.589831044609458900f, 0.589211505972615070f, - 0.588591620717822890f, - 0.587971389209745120f, 0.587350811813247660f, 0.586729888893400500f, - 0.586108620815476430f, - 0.585487007944951450f, 0.584865050647504490f, 0.584242749289016980f, - 0.583620104235572760f, - 0.582997115853457700f, 0.582373784509160220f, 0.581750110569369760f, - 0.581126094400977620f, - 0.580501736371076600f, 0.579877036846960350f, 0.579251996196123550f, - 0.578626614786261430f, - 0.578000892985269910f, 0.577374831161244880f, 0.576748429682482520f, - 0.576121688917478390f, - 0.575494609234928230f, 0.574867191003726740f, 0.574239434592967890f, - 0.573611340371944610f, - 0.572982908710148680f, 0.572354139977270030f, 0.571725034543197120f, - 0.571095592778016690f, - 0.570465815052012990f, 0.569835701735668110f, 0.569205253199661200f, - 0.568574469814869250f, - 0.567943351952365670f, 0.567311899983420800f, 0.566680114279501710f, - 0.566047995212271560f, - 0.565415543153589770f, 0.564782758475511400f, 0.564149641550287680f, - 0.563516192750364910f, - 0.562882412448384550f, 0.562248301017183150f, 0.561613858829792420f, - 0.560979086259438260f, - 0.560343983679540860f, 0.559708551463714790f, 0.559072789985768480f, - 0.558436699619704100f, - 0.557800280739717100f, 0.557163533720196340f, 0.556526458935723720f, - 0.555889056761073920f, - 0.555251327571214090f, 0.554613271741304040f, 0.553974889646695610f, - 0.553336181662932410f, - 0.552697148165749770f, 0.552057789531074980f, 0.551418106135026060f, - 0.550778098353912230f, - 0.550137766564233630f, 0.549497111142680960f, 0.548856132466135290f, - 0.548214830911667780f, - 0.547573206856539870f, 0.546931260678202190f, 0.546288992754295210f, - 0.545646403462648590f, - 0.545003493181281160f, 0.544360262288400400f, 0.543716711162402390f, - 0.543072840181871850f, - 0.542428649725581360f, 0.541784140172491660f, 0.541139311901750910f, - 0.540494165292695230f, - 0.539848700724847700f, 0.539202918577918240f, 0.538556819231804210f, - 0.537910403066588990f, - 0.537263670462542530f, 0.536616621800121150f, 0.535969257459966710f, - 0.535321577822907010f, - 0.534673583269955510f, 0.534025274182310380f, 0.533376650941355560f, - 0.532727713928658810f, - 0.532078463525973540f, 0.531428900115236910f, 0.530779024078570250f, - 0.530128835798278850f, - 0.529478335656852090f, 0.528827524036961980f, 0.528176401321464370f, - 0.527524967893398200f, - 0.526873224135984700f, 0.526221170432628170f, 0.525568807166914680f, - 0.524916134722612890f, - 0.524263153483673470f, 0.523609863834228030f, 0.522956266158590140f, - 0.522302360841254700f, - 0.521648148266897090f, 0.520993628820373810f, 0.520338802886721960f, - 0.519683670851158520f, - 0.519028233099080970f, 0.518372490016066220f, 0.517716441987871150f, - 0.517060089400432130f, - 0.516403432639863990f, 0.515746472092461380f, 0.515089208144697270f, - 0.514431641183222930f, - 0.513773771594868030f, 0.513115599766640560f, 0.512457126085725800f, - 0.511798350939487000f, - 0.511139274715464390f, 0.510479897801375700f, 0.509820220585115560f, - 0.509160243454754750f, - 0.508499966798540810f, 0.507839391004897940f, 0.507178516462425290f, - 0.506517343559898530f, - 0.505855872686268860f, 0.505194104230662240f, 0.504532038582380380f, - 0.503869676130898950f, - 0.503207017265869030f, 0.502544062377115800f, 0.501880811854638400f, - 0.501217266088609950f, - 0.500553425469377640f, 0.499889290387461380f, 0.499224861233555030f, - 0.498560138398525200f, - 0.497895122273410930f, 0.497229813249424340f, 0.496564211717949340f, - 0.495898318070542240f, - 0.495232132698931350f, 0.494565655995016010f, 0.493898888350867430f, - 0.493231830158728070f, - 0.492564481811010650f, 0.491896843700299240f, 0.491228916219348330f, - 0.490560699761082080f, - 0.489892194718595300f, 0.489223401485152030f, 0.488554320454186230f, - 0.487884952019301210f, - 0.487215296574268820f, 0.486545354513030270f, 0.485875126229695420f, - 0.485204612118541880f, - 0.484533812574016120f, 0.483862727990732320f, 0.483191358763471910f, - 0.482519705287184520f, - 0.481847767956986080f, 0.481175547168160360f, 0.480503043316157670f, - 0.479830256796594250f, - 0.479157188005253310f, 0.478483837338084080f, 0.477810205191201040f, - 0.477136291960884750f, - 0.476462098043581310f, 0.475787623835901120f, 0.475112869734620470f, - 0.474437836136679340f, - 0.473762523439182850f, 0.473086932039400220f, 0.472411062334764100f, - 0.471734914722871430f, - 0.471058489601482610f, 0.470381787368520710f, 0.469704808422072460f, - 0.469027553160387240f, - 0.468350021981876530f, 0.467672215285114710f, 0.466994133468838110f, - 0.466315776931944480f, - 0.465637146073493770f, 0.464958241292706740f, 0.464279062988965760f, - 0.463599611561814120f, - 0.462919887410955130f, 0.462239890936253280f, 0.461559622537733190f, - 0.460879082615578690f, - 0.460198271570134270f, 0.459517189801903590f, 0.458835837711549120f, - 0.458154215699893230f, - 0.457472324167916110f, 0.456790163516757220f, 0.456107734147714220f, - 0.455425036462242420f, - 0.454742070861955450f, 0.454058837748624540f, 0.453375337524177750f, - 0.452691570590700860f, - 0.452007537350436530f, 0.451323238205783520f, 0.450638673559297760f, - 0.449953843813690580f, - 0.449268749371829920f, 0.448583390636739300f, 0.447897768011597360f, - 0.447211881899738260f, - 0.446525732704651400f, 0.445839320829980350f, 0.445152646679523590f, - 0.444465710657234110f, - 0.443778513167218280f, 0.443091054613736990f, 0.442403335401204130f, - 0.441715355934187310f, - 0.441027116617407340f, 0.440338617855737300f, 0.439649860054203420f, - 0.438960843617984430f, - 0.438271568952410480f, 0.437582036462964340f, 0.436892246555280470f, - 0.436202199635143950f, - 0.435511896108492170f, 0.434821336381412350f, 0.434130520860143310f, - 0.433439449951074200f, - 0.432748124060743760f, 0.432056543595841450f, 0.431364708963206440f, - 0.430672620569826860f, - 0.429980278822840570f, 0.429287684129534720f, 0.428594836897344400f, - 0.427901737533854240f, - 0.427208386446796370f, 0.426514784044051520f, 0.425820930733648350f, - 0.425126826923762410f, - 0.424432473022717420f, 0.423737869438983950f, 0.423043016581179100f, - 0.422347914858067000f, - 0.421652564678558380f, 0.420956966451709440f, 0.420261120586723050f, - 0.419565027492946940f, - 0.418868687579875110f, 0.418172101257146430f, 0.417475268934544340f, - 0.416778191021997590f, - 0.416080867929579320f, 0.415383300067506290f, 0.414685487846140010f, - 0.413987431675985510f, - 0.413289131967690960f, 0.412590589132048380f, 0.411891803579992220f, - 0.411192775722600160f, - 0.410493505971092520f, 0.409793994736831200f, 0.409094242431320920f, - 0.408394249466208110f, - 0.407694016253280170f, 0.406993543204466460f, 0.406292830731837470f, - 0.405591879247603870f, - 0.404890689164117750f, 0.404189260893870750f, 0.403487594849495310f, - 0.402785691443763640f, - 0.402083551089587040f, 0.401381174200016790f, 0.400678561188243350f, - 0.399975712467595390f, - 0.399272628451540930f, 0.398569309553686360f, 0.397865756187775750f, - 0.397161968767691720f, - 0.396457947707453960f, 0.395753693421220080f, 0.395049206323284880f, - 0.394344486828079650f, - 0.393639535350172880f, 0.392934352304269600f, 0.392228938105210370f, - 0.391523293167972350f, - 0.390817417907668610f, 0.390111312739546910f, 0.389404978078991100f, - 0.388698414341519250f, - 0.387991621942784910f, 0.387284601298575890f, 0.386577352824813980f, - 0.385869876937555310f, - 0.385162174052989970f, 0.384454244587440870f, 0.383746088957365010f, - 0.383037707579352130f, - 0.382329100870124510f, 0.381620269246537520f, 0.380911213125578130f, - 0.380201932924366050f, - 0.379492429060152740f, 0.378782701950320600f, 0.378072752012383990f, - 0.377362579663988450f, - 0.376652185322909620f, 0.375941569407054420f, 0.375230732334460030f, - 0.374519674523293210f, - 0.373808396391851370f, 0.373096898358560690f, 0.372385180841977360f, - 0.371673244260786630f, - 0.370961089033802040f, 0.370248715579966360f, 0.369536124318350760f, - 0.368823315668153960f, - 0.368110290048703050f, 0.367397047879452820f, 0.366683589579984930f, - 0.365969915570008910f, - 0.365256026269360380f, 0.364541922098002180f, 0.363827603476023610f, - 0.363113070823639530f, - 0.362398324561191310f, 0.361683365109145950f, 0.360968192888095290f, - 0.360252808318756830f, - 0.359537211821973180f, 0.358821403818710860f, 0.358105384730061760f, - 0.357389154977241000f, - 0.356672714981588260f, 0.355956065164567010f, 0.355239205947763370f, - 0.354522137752887430f, - 0.353804861001772160f, 0.353087376116372530f, 0.352369683518766630f, - 0.351651783631154680f, - 0.350933676875858360f, 0.350215363675321740f, 0.349496844452109600f, - 0.348778119628908420f, - 0.348059189628525780f, 0.347340054873889190f, 0.346620715788047320f, - 0.345901172794169100f, - 0.345181426315542610f, 0.344461476775576480f, 0.343741324597798600f, - 0.343020970205855540f, - 0.342300414023513690f, 0.341579656474657210f, 0.340858697983289440f, - 0.340137538973531880f, - 0.339416179869623410f, 0.338694621095921190f, 0.337972863076899830f, - 0.337250906237150650f, - 0.336528751001382350f, 0.335806397794420560f, 0.335083847041206580f, - 0.334361099166798900f, - 0.333638154596370920f, 0.332915013755212650f, 0.332191677068729320f, - 0.331468144962440920f, - 0.330744417861982890f, 0.330020496193105530f, 0.329296380381672800f, - 0.328572070853663690f, - 0.327847568035170960f, 0.327122872352400510f, 0.326397984231672660f, - 0.325672904099419900f, - 0.324947632382188430f, 0.324222169506637130f, 0.323496515899536760f, - 0.322770671987770710f, - 0.322044638198334620f, 0.321318414958334910f, 0.320592002694990330f, - 0.319865401835630610f, - 0.319138612807695900f, 0.318411636038737960f, 0.317684471956418020f, - 0.316957120988508150f, - 0.316229583562890490f, 0.315501860107556040f, 0.314773951050606070f, - 0.314045856820250820f, - 0.313317577844809070f, 0.312589114552708660f, 0.311860467372486130f, - 0.311131636732785270f, - 0.310402623062358880f, 0.309673426790066490f, 0.308944048344875710f, - 0.308214488155861220f, - 0.307484746652204160f, 0.306754824263192780f, 0.306024721418221900f, - 0.305294438546791720f, - 0.304563976078509050f, 0.303833334443086470f, 0.303102514070341060f, - 0.302371515390196130f, - 0.301640338832678880f, 0.300908984827921890f, 0.300177453806162120f, - 0.299445746197739950f, - 0.298713862433100390f, 0.297981802942791920f, 0.297249568157465890f, - 0.296517158507877410f, - 0.295784574424884370f, 0.295051816339446720f, 0.294318884682627570f, - 0.293585779885591310f, - 0.292852502379604810f, 0.292119052596036540f, 0.291385430966355720f, - 0.290651637922133220f, - 0.289917673895040860f, 0.289183539316850310f, 0.288449234619434170f, - 0.287714760234765280f, - 0.286980116594915570f, 0.286245304132057120f, 0.285510323278461380f, - 0.284775174466498300f, - 0.284039858128637360f, 0.283304374697445790f, 0.282568724605589740f, - 0.281832908285833460f, - 0.281096926171038320f, 0.280360778694163810f, 0.279624466288266700f, - 0.278887989386500280f, - 0.278151348422115090f, 0.277414543828458200f, 0.276677576038972420f, - 0.275940445487197320f, - 0.275203152606767370f, 0.274465697831413220f, 0.273728081594960650f, - 0.272990304331329980f, - 0.272252366474536660f, 0.271514268458690810f, 0.270776010717996010f, - 0.270037593686750510f, - 0.269299017799346230f, 0.268560283490267890f, 0.267821391194094320f, - 0.267082341345496350f, - 0.266343134379238180f, 0.265603770730176440f, 0.264864250833259320f, - 0.264124575123527490f, - 0.263384744036113390f, 0.262644758006240100f, 0.261904617469222560f, - 0.261164322860466590f, - 0.260423874615468010f, 0.259683273169813930f, 0.258942518959180580f, - 0.258201612419334870f, - 0.257460553986133210f, 0.256719344095520720f, 0.255977983183532380f, - 0.255236471686291820f, - 0.254494810040010790f, 0.253752998680989940f, 0.253011038045617980f, - 0.252268928570370810f, - 0.251526670691812780f, 0.250784264846594550f, 0.250041711471454650f, - 0.249299011003218300f, - 0.248556163878796620f, 0.247813170535187620f, 0.247070031409475370f, - 0.246326746938829060f, - 0.245583317560504000f, 0.244839743711840750f, 0.244096025830264210f, - 0.243352164353284880f, - 0.242608159718496890f, 0.241864012363579210f, 0.241119722726294730f, - 0.240375291244489500f, - 0.239630718356093560f, 0.238886004499120170f, 0.238141150111664870f, - 0.237396155631906550f, - 0.236651021498106460f, 0.235905748148607370f, 0.235160336021834860f, - 0.234414785556295250f, - 0.233669097190576820f, 0.232923271363349120f, 0.232177308513361770f, - 0.231431209079445730f, - 0.230684973500512310f, 0.229938602215552260f, 0.229192095663636740f, - 0.228445454283916550f, - 0.227698678515621170f, 0.226951768798059980f, 0.226204725570620270f, - 0.225457549272768540f, - 0.224710240344049570f, 0.223962799224085520f, 0.223215226352576960f, - 0.222467522169301990f, - 0.221719687114115240f, 0.220971721626949060f, 0.220223626147812460f, - 0.219475401116790340f, - 0.218727046974044600f, 0.217978564159812290f, 0.217229953114406790f, - 0.216481214278216900f, - 0.215732348091705940f, 0.214983354995412820f, 0.214234235429951100f, - 0.213484989836008080f, - 0.212735618654345870f, 0.211986122325800410f, 0.211236501291280710f, - 0.210486755991769890f, - 0.209736886868323370f, 0.208986894362070070f, 0.208236778914211470f, - 0.207486540966020700f, - 0.206736180958843660f, 0.205985699334098050f, 0.205235096533272380f, - 0.204484372997927180f, - 0.203733529169694010f, 0.202982565490274460f, 0.202231482401441620f, - 0.201480280345037820f, - 0.200728959762976140f, 0.199977521097239290f, 0.199225964789878890f, - 0.198474291283016360f, - 0.197722501018842030f, 0.196970594439614370f, 0.196218571987660850f, - 0.195466434105377090f, - 0.194714181235225990f, 0.193961813819739010f, 0.193209332301514080f, - 0.192456737123216840f, - 0.191704028727579940f, 0.190951207557401860f, 0.190198274055548120f, - 0.189445228664950340f, - 0.188692071828605260f, 0.187938803989575850f, 0.187185425590990440f, - 0.186431937076041640f, - 0.185678338887987790f, 0.184924631470150870f, 0.184170815265917720f, - 0.183416890718739230f, - 0.182662858272129360f, 0.181908718369666160f, 0.181154471454990920f, - 0.180400117971807270f, - 0.179645658363882100f, 0.178891093075044830f, 0.178136422549186320f, - 0.177381647230260200f, - 0.176626767562280960f, 0.175871783989325040f, 0.175116696955530060f, - 0.174361506905093830f, - 0.173606214282275410f, 0.172850819531394200f, 0.172095323096829040f, - 0.171339725423019260f, - 0.170584026954463700f, 0.169828228135719880f, 0.169072329411405180f, - 0.168316331226194910f, - 0.167560234024823590f, 0.166804038252083870f, 0.166047744352825850f, - 0.165291352771957970f, - 0.164534863954446110f, 0.163778278345312690f, 0.163021596389637810f, - 0.162264818532558110f, - 0.161507945219266150f, 0.160750976895011390f, 0.159993914005098350f, - 0.159236756994887850f, - 0.158479506309796100f, 0.157722162395293690f, 0.156964725696906750f, - 0.156207196660216040f, - 0.155449575730855880f, 0.154691863354515400f, 0.153934059976937460f, - 0.153176166043917870f, - 0.152418182001306500f, 0.151660108295005400f, 0.150901945370970040f, - 0.150143693675208330f, - 0.149385353653779810f, 0.148626925752796540f, 0.147868410418422360f, - 0.147109808096871850f, - 0.146351119234411440f, 0.145592344277358450f, 0.144833483672080240f, - 0.144074537864995330f, - 0.143315507302571590f, 0.142556392431327340f, 0.141797193697830530f, - 0.141037911548697770f, - 0.140278546430595420f, 0.139519098790238600f, 0.138759569074390380f, - 0.137999957729862760f, - 0.137240265203515700f, 0.136480491942256310f, 0.135720638393040080f, - 0.134960705002868830f, - 0.134200692218792020f, 0.133440600487905820f, 0.132680430257352130f, - 0.131920181974319760f, - 0.131159856086043410f, 0.130399453039802740f, 0.129638973282923540f, - 0.128878417262776660f, - 0.128117785426777150f, 0.127357078222385570f, 0.126596296097105960f, - 0.125835439498487020f, - 0.125074508874121300f, 0.124313504671644300f, 0.123552427338735370f, - 0.122791277323116900f, - 0.122030055072553410f, 0.121268761034852550f, 0.120507395657864240f, - 0.119745959389479630f, - 0.118984452677632520f, 0.118222875970297250f, 0.117461229715489990f, - 0.116699514361267840f, - 0.115937730355727850f, 0.115175878147008180f, 0.114413958183287050f, - 0.113651970912781920f, - 0.112889916783750470f, 0.112127796244489750f, 0.111365609743335190f, - 0.110603357728661910f, - 0.109841040648882680f, 0.109078658952449240f, 0.108316213087851300f, - 0.107553703503615710f, - 0.106791130648307380f, 0.106028494970528530f, 0.105265796918917650f, - 0.104503036942150550f, - 0.103740215488939480f, 0.102977333008032250f, 0.102214389948213370f, - 0.101451386758302160f, - 0.100688323887153970f, 0.099925201783659226f, 0.099162020896742573f, - 0.098398781675363881f, - 0.097635484568517339f, 0.096872130025230527f, 0.096108718494565468f, - 0.095345250425617742f, - 0.094581726267515473f, 0.093818146469420494f, 0.093054511480527333f, - 0.092290821750062355f, - 0.091527077727284981f, 0.090763279861485704f, 0.089999428601987341f, - 0.089235524398144139f, - 0.088471567699340822f, 0.087707558954993645f, 0.086943498614549489f, - 0.086179387127484922f, - 0.085415224943307277f, 0.084651012511553700f, 0.083886750281790226f, - 0.083122438703613077f, - 0.082358078226646619f, 0.081593669300544638f, 0.080829212374989468f, - 0.080064707899690932f, - 0.079300156324387569f, 0.078535558098845590f, 0.077770913672857989f, - 0.077006223496245585f, - 0.076241488018856149f, 0.075476707690563416f, 0.074711882961268378f, - 0.073947014280897269f, - 0.073182102099402888f, 0.072417146866763538f, 0.071652149032982254f, - 0.070887109048087787f, - 0.070122027362133646f, 0.069356904425197236f, 0.068591740687380900f, - 0.067826536598810966f, - 0.067061292609636836f, 0.066296009170032283f, 0.065530686730193397f, - 0.064765325740339871f, - 0.063999926650714078f, 0.063234489911580136f, 0.062469015973224969f, - 0.061703505285957416f, - 0.060937958300107238f, 0.060172375466026218f, 0.059406757234087247f, - 0.058641104054683348f, - 0.057875416378229017f, 0.057109694655158132f, 0.056343939335925283f, - 0.055578150871004817f, - 0.054812329710889909f, 0.054046476306093640f, 0.053280591107148056f, - 0.052514674564603257f, - 0.051748727129028414f, 0.050982749251010900f, 0.050216741381155325f, - 0.049450703970084824f, - 0.048684637468439020f, 0.047918542326875327f, 0.047152418996068000f, - 0.046386267926707213f, - 0.045620089569500123f, 0.044853884375169933f, 0.044087652794454979f, - 0.043321395278109784f, - 0.042555112276904117f, 0.041788804241622082f, 0.041022471623063397f, - 0.040256114872041358f, - 0.039489734439384118f, 0.038723330775933762f, 0.037956904332545366f, - 0.037190455560088091f, - 0.036423984909444228f, 0.035657492831508264f, 0.034890979777187955f, - 0.034124446197403423f, - 0.033357892543086159f, 0.032591319265180385f, 0.031824726814640963f, - 0.031058115642434700f, - 0.030291486199539423f, 0.029524838936943035f, 0.028758174305644590f, - 0.027991492756653365f, - 0.027224794740987910f, 0.026458080709677145f, 0.025691351113759395f, - 0.024924606404281485f, - 0.024157847032300020f, 0.023391073448879338f, 0.022624286105092803f, - 0.021857485452021874f, - 0.021090671940755180f, 0.020323846022389572f, 0.019557008148029204f, - 0.018790158768784596f, - 0.018023298335773701f, 0.017256427300120978f, 0.016489546112956454f, - 0.015722655225417017f, - 0.014955755088644378f, 0.014188846153786343f, 0.013421928871995907f, - 0.012655003694430301f, - 0.011888071072252072f, 0.011121131456628141f, 0.010354185298728884f, - 0.009587233049729183f, - 0.008820275160807512f, 0.008053312083144991f, 0.007286344267926684f, - 0.006519372166339549f, - 0.005752396229573737f, 0.004985416908821652f, 0.004218434655277024f, - 0.003451449920135975f, - 0.002684463154596083f, 0.001917474809855460f, 0.001150485337113809f, - 0.000383495187571497f -}; - -/** - * @brief Initialization function for the floating-point DCT4/IDCT4. - * @param[in,out] *S points to an instance of floating-point DCT4/IDCT4 structure. - * @param[in] *S_RFFT points to an instance of floating-point RFFT/RIFFT structure. - * @param[in] *S_CFFT points to an instance of floating-point CFFT/CIFFT structure. - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported transform length. - * \par Normalizing factor: - * The normalizing factor is sqrt(2/N), which depends on the size of transform N. - * Floating-point normalizing factors are mentioned in the table below for different DCT sizes: - * \image html dct4NormalizingF32Table.gif - */ - -arm_status arm_dct4_init_f32( - arm_dct4_instance_f32 * S, - arm_rfft_instance_f32 * S_RFFT, - arm_cfft_radix4_instance_f32 * S_CFFT, - uint16_t N, - uint16_t Nby2, - float32_t normalize) -{ - /* Initialize the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initializing the pointer array with the weight table base addresses of different lengths */ - float32_t *twiddlePtr[3] = - { (float32_t *) Weights_128, (float32_t *) Weights_512, - (float32_t *) Weights_2048 - }; - - /* Initializing the pointer array with the cos factor table base addresses of different lengths */ - float32_t *pCosFactor[3] = - { (float32_t *) cos_factors_128, (float32_t *) cos_factors_512, - (float32_t *) cos_factors_2048 - }; - - /* Initialize the DCT4 length */ - S->N = N; - - /* Initialize the half of DCT4 length */ - S->Nby2 = Nby2; - - /* Initialize the DCT4 Normalizing factor */ - S->normalize = normalize; - - /* Initialize Real FFT Instance */ - S->pRfft = S_RFFT; - - /* Initialize Complex FFT Instance */ - S->pCfft = S_CFFT; - - switch (N) - { - /* Initialize the table modifier values */ - case 2048u: - S->pTwiddle = twiddlePtr[2]; - S->pCosFactor = pCosFactor[2]; - break; - case 512u: - S->pTwiddle = twiddlePtr[1]; - S->pCosFactor = pCosFactor[1]; - break; - case 128u: - S->pTwiddle = twiddlePtr[0]; - S->pCosFactor = pCosFactor[0]; - break; - default: - status = ARM_MATH_ARGUMENT_ERROR; - } - - /* Initialize the RFFT/RIFFT */ - arm_rfft_init_f32(S->pRfft, S->pCfft, S->N, 0u, 1u); - - /* return the status of DCT4 Init function */ - return (status); -} - -/** - * @} end of DCT4_IDCT4 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_dct4_init_f32.c +* +* Description: Initialization function of DCT-4 & IDCT4 F32 +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup DCT4_IDCT4 + * @{ + */ + +/* +* @brief Weights Table +*/ + +/** +* \par +* Weights tables are generated using the formula :
weights[n] = e^(-j*n*pi/(2*N))
+* \par +* C command to generate the table +*
   
+* for(i = 0; i< N; i++)   
+* {   
+*    weights[2*i]= cos(i*c);   
+*    weights[(2*i)+1]= -sin(i * c);   
+* } 
+* \par +* Where N is the Number of weights to be calculated and c is pi/(2*N) +* \par +* In the tables below the real and imaginary values are placed alternatively, hence the +* array length is 2*N. +*/ + +static const float32_t Weights_128[256] = { + 1.000000000000000000f, 0.000000000000000000f, 0.999924701839144500f, + -0.012271538285719925f, + 0.999698818696204250f, -0.024541228522912288f, 0.999322384588349540f, + -0.036807222941358832f, + 0.998795456205172410f, -0.049067674327418015f, 0.998118112900149180f, + -0.061320736302208578f, + 0.997290456678690210f, -0.073564563599667426f, 0.996312612182778000f, + -0.085797312344439894f, + 0.995184726672196930f, -0.098017140329560604f, 0.993906970002356060f, + -0.110222207293883060f, + 0.992479534598709970f, -0.122410675199216200f, 0.990902635427780010f, + -0.134580708507126170f, + 0.989176509964781010f, -0.146730474455361750f, 0.987301418157858430f, + -0.158858143333861450f, + 0.985277642388941220f, -0.170961888760301220f, 0.983105487431216290f, + -0.183039887955140950f, + 0.980785280403230430f, -0.195090322016128250f, 0.978317370719627650f, + -0.207111376192218560f, + 0.975702130038528570f, -0.219101240156869800f, 0.972939952205560180f, + -0.231058108280671110f, + 0.970031253194543970f, -0.242980179903263870f, 0.966976471044852070f, + -0.254865659604514570f, + 0.963776065795439840f, -0.266712757474898370f, 0.960430519415565790f, + -0.278519689385053060f, + 0.956940335732208820f, -0.290284677254462330f, 0.953306040354193860f, + -0.302005949319228080f, + 0.949528180593036670f, -0.313681740398891520f, 0.945607325380521280f, + -0.325310292162262930f, + 0.941544065183020810f, -0.336889853392220050f, 0.937339011912574960f, + -0.348418680249434560f, + 0.932992798834738960f, -0.359895036534988110f, 0.928506080473215590f, + -0.371317193951837540f, + 0.923879532511286740f, -0.382683432365089780f, 0.919113851690057770f, + -0.393992040061048100f, + 0.914209755703530690f, -0.405241314004989860f, 0.909167983090522380f, + -0.416429560097637150f, + 0.903989293123443340f, -0.427555093430282080f, 0.898674465693953820f, + -0.438616238538527660f, + 0.893224301195515320f, -0.449611329654606540f, 0.887639620402853930f, + -0.460538710958240010f, + 0.881921264348355050f, -0.471396736825997640f, 0.876070094195406600f, + -0.482183772079122720f, + 0.870086991108711460f, -0.492898192229784040f, 0.863972856121586810f, + -0.503538383725717580f, + 0.857728610000272120f, -0.514102744193221660f, 0.851355193105265200f, + -0.524589682678468950f, + 0.844853565249707120f, -0.534997619887097150f, 0.838224705554838080f, + -0.545324988422046460f, + 0.831469612302545240f, -0.555570233019602180f, 0.824589302785025290f, + -0.565731810783613120f, + 0.817584813151583710f, -0.575808191417845340f, 0.810457198252594770f, + -0.585797857456438860f, + 0.803207531480644940f, -0.595699304492433360f, 0.795836904608883570f, + -0.605511041404325550f, + 0.788346427626606340f, -0.615231590580626820f, 0.780737228572094490f, + -0.624859488142386340f, + 0.773010453362736990f, -0.634393284163645490f, 0.765167265622458960f, + -0.643831542889791390f, + 0.757208846506484570f, -0.653172842953776760f, 0.749136394523459370f, + -0.662415777590171780f, + 0.740951125354959110f, -0.671558954847018330f, 0.732654271672412820f, + -0.680600997795453020f, + 0.724247082951467000f, -0.689540544737066830f, 0.715730825283818590f, + -0.698376249408972920f, + 0.707106781186547570f, -0.707106781186547460f, 0.698376249408972920f, + -0.715730825283818590f, + 0.689540544737066940f, -0.724247082951466890f, 0.680600997795453130f, + -0.732654271672412820f, + 0.671558954847018330f, -0.740951125354959110f, 0.662415777590171780f, + -0.749136394523459260f, + 0.653172842953776760f, -0.757208846506484460f, 0.643831542889791500f, + -0.765167265622458960f, + 0.634393284163645490f, -0.773010453362736990f, 0.624859488142386450f, + -0.780737228572094380f, + 0.615231590580626820f, -0.788346427626606230f, 0.605511041404325550f, + -0.795836904608883460f, + 0.595699304492433470f, -0.803207531480644830f, 0.585797857456438860f, + -0.810457198252594770f, + 0.575808191417845340f, -0.817584813151583710f, 0.565731810783613230f, + -0.824589302785025290f, + 0.555570233019602290f, -0.831469612302545240f, 0.545324988422046460f, + -0.838224705554837970f, + 0.534997619887097260f, -0.844853565249707010f, 0.524589682678468840f, + -0.851355193105265200f, + 0.514102744193221660f, -0.857728610000272120f, 0.503538383725717580f, + -0.863972856121586700f, + 0.492898192229784090f, -0.870086991108711350f, 0.482183772079122830f, + -0.876070094195406600f, + 0.471396736825997810f, -0.881921264348354940f, 0.460538710958240010f, + -0.887639620402853930f, + 0.449611329654606600f, -0.893224301195515320f, 0.438616238538527710f, + -0.898674465693953820f, + 0.427555093430282200f, -0.903989293123443340f, 0.416429560097637320f, + -0.909167983090522270f, + 0.405241314004989860f, -0.914209755703530690f, 0.393992040061048100f, + -0.919113851690057770f, + 0.382683432365089840f, -0.923879532511286740f, 0.371317193951837600f, + -0.928506080473215480f, + 0.359895036534988280f, -0.932992798834738850f, 0.348418680249434510f, + -0.937339011912574960f, + 0.336889853392220050f, -0.941544065183020810f, 0.325310292162262980f, + -0.945607325380521280f, + 0.313681740398891570f, -0.949528180593036670f, 0.302005949319228200f, + -0.953306040354193750f, + 0.290284677254462330f, -0.956940335732208940f, 0.278519689385053060f, + -0.960430519415565790f, + 0.266712757474898420f, -0.963776065795439840f, 0.254865659604514630f, + -0.966976471044852070f, + 0.242980179903263980f, -0.970031253194543970f, 0.231058108280671280f, + -0.972939952205560070f, + 0.219101240156869770f, -0.975702130038528570f, 0.207111376192218560f, + -0.978317370719627650f, + 0.195090322016128330f, -0.980785280403230430f, 0.183039887955141060f, + -0.983105487431216290f, + 0.170961888760301360f, -0.985277642388941220f, 0.158858143333861390f, + -0.987301418157858430f, + 0.146730474455361750f, -0.989176509964781010f, 0.134580708507126220f, + -0.990902635427780010f, + 0.122410675199216280f, -0.992479534598709970f, 0.110222207293883180f, + -0.993906970002356060f, + 0.098017140329560770f, -0.995184726672196820f, 0.085797312344439880f, + -0.996312612182778000f, + 0.073564563599667454f, -0.997290456678690210f, 0.061320736302208648f, + -0.998118112900149180f, + 0.049067674327418126f, -0.998795456205172410f, 0.036807222941358991f, + -0.999322384588349540f, + 0.024541228522912264f, -0.999698818696204250f, 0.012271538285719944f, + -0.999924701839144500f +}; + +static const float32_t Weights_512[1024] = { + 1.000000000000000000f, 0.000000000000000000f, 0.999995293809576190f, + -0.003067956762965976f, + 0.999981175282601110f, -0.006135884649154475f, 0.999957644551963900f, + -0.009203754782059819f, + 0.999924701839144500f, -0.012271538285719925f, 0.999882347454212560f, + -0.015339206284988100f, + 0.999830581795823400f, -0.018406729905804820f, 0.999769405351215280f, + -0.021474080275469508f, + 0.999698818696204250f, -0.024541228522912288f, 0.999618822495178640f, + -0.027608145778965740f, + 0.999529417501093140f, -0.030674803176636626f, 0.999430604555461730f, + -0.033741171851377580f, + 0.999322384588349540f, -0.036807222941358832f, 0.999204758618363890f, + -0.039872927587739811f, + 0.999077727752645360f, -0.042938256934940820f, 0.998941293186856870f, + -0.046003182130914623f, + 0.998795456205172410f, -0.049067674327418015f, 0.998640218180265270f, + -0.052131704680283324f, + 0.998475580573294770f, -0.055195244349689934f, 0.998301544933892890f, + -0.058258264500435752f, + 0.998118112900149180f, -0.061320736302208578f, 0.997925286198596000f, + -0.064382630929857465f, + 0.997723066644191640f, -0.067443919563664051f, 0.997511456140303450f, + -0.070504573389613856f, + 0.997290456678690210f, -0.073564563599667426f, 0.997060070339482960f, + -0.076623861392031492f, + 0.996820299291165670f, -0.079682437971430126f, 0.996571145790554840f, + -0.082740264549375692f, + 0.996312612182778000f, -0.085797312344439894f, 0.996044700901251970f, + -0.088853552582524600f, + 0.995767414467659820f, -0.091908956497132724f, 0.995480755491926940f, + -0.094963495329638992f, + 0.995184726672196930f, -0.098017140329560604f, 0.994879330794805620f, + -0.101069862754827820f, + 0.994564570734255420f, -0.104121633872054590f, 0.994240449453187900f, + -0.107172424956808840f, + 0.993906970002356060f, -0.110222207293883060f, 0.993564135520595300f, + -0.113270952177564350f, + 0.993211949234794500f, -0.116318630911904750f, 0.992850414459865100f, + -0.119365214810991350f, + 0.992479534598709970f, -0.122410675199216200f, 0.992099313142191800f, + -0.125454983411546230f, + 0.991709753669099530f, -0.128498110793793170f, 0.991310859846115440f, + -0.131540028702883120f, + 0.990902635427780010f, -0.134580708507126170f, 0.990485084256457090f, + -0.137620121586486040f, + 0.990058210262297120f, -0.140658239332849210f, 0.989622017463200890f, + -0.143695033150294470f, + 0.989176509964781010f, -0.146730474455361750f, 0.988721691960323780f, + -0.149764534677321510f, + 0.988257567730749460f, -0.152797185258443440f, 0.987784141644572180f, + -0.155828397654265230f, + 0.987301418157858430f, -0.158858143333861450f, 0.986809401814185530f, + -0.161886393780111830f, + 0.986308097244598670f, -0.164913120489969890f, 0.985797509167567480f, + -0.167938294974731170f, + 0.985277642388941220f, -0.170961888760301220f, 0.984748501801904210f, + -0.173983873387463820f, + 0.984210092386929030f, -0.177004220412148750f, 0.983662419211730250f, + -0.180022901405699510f, + 0.983105487431216290f, -0.183039887955140950f, 0.982539302287441240f, + -0.186055151663446630f, + 0.981963869109555240f, -0.189068664149806190f, 0.981379193313754560f, + -0.192080397049892440f, + 0.980785280403230430f, -0.195090322016128250f, 0.980182135968117430f, + -0.198098410717953560f, + 0.979569765685440520f, -0.201104634842091900f, 0.978948175319062200f, + -0.204108966092816870f, + 0.978317370719627650f, -0.207111376192218560f, 0.977677357824509930f, + -0.210111836880469610f, + 0.977028142657754390f, -0.213110319916091360f, 0.976369731330021140f, + -0.216106797076219520f, + 0.975702130038528570f, -0.219101240156869800f, 0.975025345066994120f, + -0.222093620973203510f, + 0.974339382785575860f, -0.225083911359792830f, 0.973644249650811980f, + -0.228072083170885730f, + 0.972939952205560180f, -0.231058108280671110f, 0.972226497078936270f, + -0.234041958583543430f, + 0.971503890986251780f, -0.237023605994367200f, 0.970772140728950350f, + -0.240003022448741500f, + 0.970031253194543970f, -0.242980179903263870f, 0.969281235356548530f, + -0.245955050335794590f, + 0.968522094274417380f, -0.248927605745720150f, 0.967753837093475510f, + -0.251897818154216970f, + 0.966976471044852070f, -0.254865659604514570f, 0.966190003445412500f, + -0.257831102162158990f, + 0.965394441697689400f, -0.260794117915275510f, 0.964589793289812760f, + -0.263754678974831350f, + 0.963776065795439840f, -0.266712757474898370f, 0.962953266873683880f, + -0.269668325572915090f, + 0.962121404269041580f, -0.272621355449948980f, 0.961280485811320640f, + -0.275571819310958140f, + 0.960430519415565790f, -0.278519689385053060f, 0.959571513081984520f, + -0.281464937925757940f, + 0.958703474895871600f, -0.284407537211271880f, 0.957826413027532910f, + -0.287347459544729510f, + 0.956940335732208820f, -0.290284677254462330f, 0.956045251349996410f, + -0.293219162694258630f, + 0.955141168305770780f, -0.296150888243623790f, 0.954228095109105670f, + -0.299079826308040480f, + 0.953306040354193860f, -0.302005949319228080f, 0.952375012719765880f, + -0.304929229735402370f, + 0.951435020969008340f, -0.307849640041534870f, 0.950486073949481700f, + -0.310767152749611470f, + 0.949528180593036670f, -0.313681740398891520f, 0.948561349915730270f, + -0.316593375556165850f, + 0.947585591017741090f, -0.319502030816015690f, 0.946600913083283530f, + -0.322407678801069850f, + 0.945607325380521280f, -0.325310292162262930f, 0.944604837261480260f, + -0.328209843579092500f, + 0.943593458161960390f, -0.331106305759876430f, 0.942573197601446870f, + -0.333999651442009380f, + 0.941544065183020810f, -0.336889853392220050f, 0.940506070593268300f, + -0.339776884406826850f, + 0.939459223602189920f, -0.342660717311994380f, 0.938403534063108060f, + -0.345541324963989090f, + 0.937339011912574960f, -0.348418680249434560f, 0.936265667170278260f, + -0.351292756085567090f, + 0.935183509938947610f, -0.354163525420490340f, 0.934092550404258980f, + -0.357030961233429980f, + 0.932992798834738960f, -0.359895036534988110f, 0.931884265581668150f, + -0.362755724367397230f, + 0.930766961078983710f, -0.365612997804773850f, 0.929640895843181330f, + -0.368466829953372320f, + 0.928506080473215590f, -0.371317193951837540f, 0.927362525650401110f, + -0.374164062971457930f, + 0.926210242138311380f, -0.377007410216418260f, 0.925049240782677580f, + -0.379847208924051160f, + 0.923879532511286740f, -0.382683432365089780f, 0.922701128333878630f, + -0.385516053843918850f, + 0.921514039342042010f, -0.388345046698826250f, 0.920318276709110590f, + -0.391170384302253870f, + 0.919113851690057770f, -0.393992040061048100f, 0.917900775621390500f, + -0.396809987416710310f, + 0.916679059921042700f, -0.399624199845646790f, 0.915448716088267830f, + -0.402434650859418430f, + 0.914209755703530690f, -0.405241314004989860f, 0.912962190428398210f, + -0.408044162864978690f, + 0.911706032005429880f, -0.410843171057903910f, 0.910441292258067250f, + -0.413638312238434500f, + 0.909167983090522380f, -0.416429560097637150f, 0.907886116487666260f, + -0.419216888363223910f, + 0.906595704514915330f, -0.422000270799799680f, 0.905296759318118820f, + -0.424779681209108810f, + 0.903989293123443340f, -0.427555093430282080f, 0.902673318237258830f, + -0.430326481340082610f, + 0.901348847046022030f, -0.433093818853151960f, 0.900015892016160280f, + -0.435857079922255470f, + 0.898674465693953820f, -0.438616238538527660f, 0.897324580705418320f, + -0.441371268731716670f, + 0.895966249756185220f, -0.444122144570429200f, 0.894599485631382700f, + -0.446868840162374160f, + 0.893224301195515320f, -0.449611329654606540f, 0.891840709392342720f, + -0.452349587233770890f, + 0.890448723244757880f, -0.455083587126343840f, 0.889048355854664570f, + -0.457813303598877170f, + 0.887639620402853930f, -0.460538710958240010f, 0.886222530148880640f, + -0.463259783551860150f, + 0.884797098430937790f, -0.465976495767966180f, 0.883363338665731580f, + -0.468688822035827900f, + 0.881921264348355050f, -0.471396736825997640f, 0.880470889052160750f, + -0.474100214650549970f, + 0.879012226428633530f, -0.476799230063322090f, 0.877545290207261350f, + -0.479493757660153010f, + 0.876070094195406600f, -0.482183772079122720f, 0.874586652278176110f, + -0.484869248000791060f, + 0.873094978418290090f, -0.487550160148436000f, 0.871595086655950980f, + -0.490226483288291160f, + 0.870086991108711460f, -0.492898192229784040f, 0.868570705971340900f, + -0.495565261825772540f, + 0.867046245515692650f, -0.498227666972781870f, 0.865513624090569090f, + -0.500885382611240710f, + 0.863972856121586810f, -0.503538383725717580f, 0.862423956111040610f, + -0.506186645345155230f, + 0.860866938637767310f, -0.508830142543106990f, 0.859301818357008470f, + -0.511468850437970300f, + 0.857728610000272120f, -0.514102744193221660f, 0.856147328375194470f, + -0.516731799017649870f, + 0.854557988365400530f, -0.519355990165589640f, 0.852960604930363630f, + -0.521975292937154390f, + 0.851355193105265200f, -0.524589682678468950f, 0.849741768000852550f, + -0.527199134781901280f, + 0.848120344803297230f, -0.529803624686294610f, 0.846490938774052130f, + -0.532403127877197900f, + 0.844853565249707120f, -0.534997619887097150f, 0.843208239641845440f, + -0.537587076295645390f, + 0.841554977436898440f, -0.540171472729892850f, 0.839893794195999520f, + -0.542750784864515890f, + 0.838224705554838080f, -0.545324988422046460f, 0.836547727223512010f, + -0.547894059173100190f, + 0.834862874986380010f, -0.550457972936604810f, 0.833170164701913190f, + -0.553016705580027470f, + 0.831469612302545240f, -0.555570233019602180f, 0.829761233794523050f, + -0.558118531220556100f, + 0.828045045257755800f, -0.560661576197336030f, 0.826321062845663530f, + -0.563199344013834090f, + 0.824589302785025290f, -0.565731810783613120f, 0.822849781375826430f, + -0.568258952670131490f, + 0.821102514991104650f, -0.570780745886967260f, 0.819347520076796900f, + -0.573297166698042200f, + 0.817584813151583710f, -0.575808191417845340f, 0.815814410806733780f, + -0.578313796411655590f, + 0.814036329705948410f, -0.580813958095764530f, 0.812250586585203880f, + -0.583308652937698290f, + 0.810457198252594770f, -0.585797857456438860f, 0.808656181588174980f, + -0.588281548222645220f, + 0.806847553543799330f, -0.590759701858874160f, 0.805031331142963660f, + -0.593232295039799800f, + 0.803207531480644940f, -0.595699304492433360f, 0.801376171723140240f, + -0.598160706996342270f, + 0.799537269107905010f, -0.600616479383868970f, 0.797690840943391160f, + -0.603066598540348160f, + 0.795836904608883570f, -0.605511041404325550f, 0.793975477554337170f, + -0.607949784967773630f, + 0.792106577300212390f, -0.610382806276309480f, 0.790230221437310030f, + -0.612810082429409710f, + 0.788346427626606340f, -0.615231590580626820f, 0.786455213599085770f, + -0.617647307937803870f, + 0.784556597155575240f, -0.620057211763289100f, 0.782650596166575730f, + -0.622461279374149970f, + 0.780737228572094490f, -0.624859488142386340f, 0.778816512381475980f, + -0.627251815495144080f, + 0.776888465673232440f, -0.629638238914926980f, 0.774953106594873930f, + -0.632018735939809060f, + 0.773010453362736990f, -0.634393284163645490f, 0.771060524261813820f, + -0.636761861236284200f, + 0.769103337645579700f, -0.639124444863775730f, 0.767138911935820400f, + -0.641481012808583160f, + 0.765167265622458960f, -0.643831542889791390f, 0.763188417263381270f, + -0.646176012983316280f, + 0.761202385484261780f, -0.648514401022112440f, 0.759209188978388070f, + -0.650846684996380880f, + 0.757208846506484570f, -0.653172842953776760f, 0.755201376896536550f, + -0.655492852999615350f, + 0.753186799043612520f, -0.657806693297078640f, 0.751165131909686480f, + -0.660114342067420480f, + 0.749136394523459370f, -0.662415777590171780f, 0.747100605980180130f, + -0.664710978203344790f, + 0.745057785441466060f, -0.666999922303637470f, 0.743007952135121720f, + -0.669282588346636010f, + 0.740951125354959110f, -0.671558954847018330f, 0.738887324460615110f, + -0.673829000378756040f, + 0.736816568877369900f, -0.676092703575315920f, 0.734738878095963500f, + -0.678350043129861470f, + 0.732654271672412820f, -0.680600997795453020f, 0.730562769227827590f, + -0.682845546385248080f, + 0.728464390448225200f, -0.685083667772700360f, 0.726359155084346010f, + -0.687315340891759050f, + 0.724247082951467000f, -0.689540544737066830f, 0.722128193929215350f, + -0.691759258364157750f, + 0.720002507961381650f, -0.693971460889654000f, 0.717870045055731710f, + -0.696177131491462990f, + 0.715730825283818590f, -0.698376249408972920f, 0.713584868780793640f, + -0.700568793943248340f, + 0.711432195745216430f, -0.702754744457225300f, 0.709272826438865690f, + -0.704934080375904880f, + 0.707106781186547570f, -0.707106781186547460f, 0.704934080375904990f, + -0.709272826438865580f, + 0.702754744457225300f, -0.711432195745216430f, 0.700568793943248450f, + -0.713584868780793520f, + 0.698376249408972920f, -0.715730825283818590f, 0.696177131491462990f, + -0.717870045055731710f, + 0.693971460889654000f, -0.720002507961381650f, 0.691759258364157750f, + -0.722128193929215350f, + 0.689540544737066940f, -0.724247082951466890f, 0.687315340891759160f, + -0.726359155084346010f, + 0.685083667772700360f, -0.728464390448225200f, 0.682845546385248080f, + -0.730562769227827590f, + 0.680600997795453130f, -0.732654271672412820f, 0.678350043129861580f, + -0.734738878095963390f, + 0.676092703575316030f, -0.736816568877369790f, 0.673829000378756150f, + -0.738887324460615110f, + 0.671558954847018330f, -0.740951125354959110f, 0.669282588346636010f, + -0.743007952135121720f, + 0.666999922303637470f, -0.745057785441465950f, 0.664710978203344900f, + -0.747100605980180130f, + 0.662415777590171780f, -0.749136394523459260f, 0.660114342067420480f, + -0.751165131909686370f, + 0.657806693297078640f, -0.753186799043612410f, 0.655492852999615460f, + -0.755201376896536550f, + 0.653172842953776760f, -0.757208846506484460f, 0.650846684996380990f, + -0.759209188978387960f, + 0.648514401022112550f, -0.761202385484261780f, 0.646176012983316390f, + -0.763188417263381270f, + 0.643831542889791500f, -0.765167265622458960f, 0.641481012808583160f, + -0.767138911935820400f, + 0.639124444863775730f, -0.769103337645579590f, 0.636761861236284200f, + -0.771060524261813710f, + 0.634393284163645490f, -0.773010453362736990f, 0.632018735939809060f, + -0.774953106594873820f, + 0.629638238914927100f, -0.776888465673232440f, 0.627251815495144190f, + -0.778816512381475870f, + 0.624859488142386450f, -0.780737228572094380f, 0.622461279374150080f, + -0.782650596166575730f, + 0.620057211763289210f, -0.784556597155575240f, 0.617647307937803980f, + -0.786455213599085770f, + 0.615231590580626820f, -0.788346427626606230f, 0.612810082429409710f, + -0.790230221437310030f, + 0.610382806276309480f, -0.792106577300212390f, 0.607949784967773740f, + -0.793975477554337170f, + 0.605511041404325550f, -0.795836904608883460f, 0.603066598540348280f, + -0.797690840943391040f, + 0.600616479383868970f, -0.799537269107905010f, 0.598160706996342380f, + -0.801376171723140130f, + 0.595699304492433470f, -0.803207531480644830f, 0.593232295039799800f, + -0.805031331142963660f, + 0.590759701858874280f, -0.806847553543799220f, 0.588281548222645330f, + -0.808656181588174980f, + 0.585797857456438860f, -0.810457198252594770f, 0.583308652937698290f, + -0.812250586585203880f, + 0.580813958095764530f, -0.814036329705948300f, 0.578313796411655590f, + -0.815814410806733780f, + 0.575808191417845340f, -0.817584813151583710f, 0.573297166698042320f, + -0.819347520076796900f, + 0.570780745886967370f, -0.821102514991104650f, 0.568258952670131490f, + -0.822849781375826320f, + 0.565731810783613230f, -0.824589302785025290f, 0.563199344013834090f, + -0.826321062845663420f, + 0.560661576197336030f, -0.828045045257755800f, 0.558118531220556100f, + -0.829761233794523050f, + 0.555570233019602290f, -0.831469612302545240f, 0.553016705580027580f, + -0.833170164701913190f, + 0.550457972936604810f, -0.834862874986380010f, 0.547894059173100190f, + -0.836547727223511890f, + 0.545324988422046460f, -0.838224705554837970f, 0.542750784864516000f, + -0.839893794195999410f, + 0.540171472729892970f, -0.841554977436898330f, 0.537587076295645510f, + -0.843208239641845440f, + 0.534997619887097260f, -0.844853565249707010f, 0.532403127877198010f, + -0.846490938774052020f, + 0.529803624686294830f, -0.848120344803297120f, 0.527199134781901390f, + -0.849741768000852440f, + 0.524589682678468840f, -0.851355193105265200f, 0.521975292937154390f, + -0.852960604930363630f, + 0.519355990165589530f, -0.854557988365400530f, 0.516731799017649980f, + -0.856147328375194470f, + 0.514102744193221660f, -0.857728610000272120f, 0.511468850437970520f, + -0.859301818357008360f, + 0.508830142543106990f, -0.860866938637767310f, 0.506186645345155450f, + -0.862423956111040500f, + 0.503538383725717580f, -0.863972856121586700f, 0.500885382611240940f, + -0.865513624090568980f, + 0.498227666972781870f, -0.867046245515692650f, 0.495565261825772490f, + -0.868570705971340900f, + 0.492898192229784090f, -0.870086991108711350f, 0.490226483288291100f, + -0.871595086655951090f, + 0.487550160148436050f, -0.873094978418290090f, 0.484869248000791120f, + -0.874586652278176110f, + 0.482183772079122830f, -0.876070094195406600f, 0.479493757660153010f, + -0.877545290207261240f, + 0.476799230063322250f, -0.879012226428633410f, 0.474100214650550020f, + -0.880470889052160750f, + 0.471396736825997810f, -0.881921264348354940f, 0.468688822035827960f, + -0.883363338665731580f, + 0.465976495767966130f, -0.884797098430937790f, 0.463259783551860260f, + -0.886222530148880640f, + 0.460538710958240010f, -0.887639620402853930f, 0.457813303598877290f, + -0.889048355854664570f, + 0.455083587126343840f, -0.890448723244757880f, 0.452349587233771000f, + -0.891840709392342720f, + 0.449611329654606600f, -0.893224301195515320f, 0.446868840162374330f, + -0.894599485631382580f, + 0.444122144570429260f, -0.895966249756185110f, 0.441371268731716620f, + -0.897324580705418320f, + 0.438616238538527710f, -0.898674465693953820f, 0.435857079922255470f, + -0.900015892016160280f, + 0.433093818853152010f, -0.901348847046022030f, 0.430326481340082610f, + -0.902673318237258830f, + 0.427555093430282200f, -0.903989293123443340f, 0.424779681209108810f, + -0.905296759318118820f, + 0.422000270799799790f, -0.906595704514915330f, 0.419216888363223960f, + -0.907886116487666150f, + 0.416429560097637320f, -0.909167983090522270f, 0.413638312238434560f, + -0.910441292258067140f, + 0.410843171057903910f, -0.911706032005429880f, 0.408044162864978740f, + -0.912962190428398100f, + 0.405241314004989860f, -0.914209755703530690f, 0.402434650859418540f, + -0.915448716088267830f, + 0.399624199845646790f, -0.916679059921042700f, 0.396809987416710420f, + -0.917900775621390390f, + 0.393992040061048100f, -0.919113851690057770f, 0.391170384302253980f, + -0.920318276709110480f, + 0.388345046698826300f, -0.921514039342041900f, 0.385516053843919020f, + -0.922701128333878520f, + 0.382683432365089840f, -0.923879532511286740f, 0.379847208924051110f, + -0.925049240782677580f, + 0.377007410216418310f, -0.926210242138311270f, 0.374164062971457990f, + -0.927362525650401110f, + 0.371317193951837600f, -0.928506080473215480f, 0.368466829953372320f, + -0.929640895843181330f, + 0.365612997804773960f, -0.930766961078983710f, 0.362755724367397230f, + -0.931884265581668150f, + 0.359895036534988280f, -0.932992798834738850f, 0.357030961233430030f, + -0.934092550404258870f, + 0.354163525420490510f, -0.935183509938947500f, 0.351292756085567150f, + -0.936265667170278260f, + 0.348418680249434510f, -0.937339011912574960f, 0.345541324963989150f, + -0.938403534063108060f, + 0.342660717311994380f, -0.939459223602189920f, 0.339776884406826960f, + -0.940506070593268300f, + 0.336889853392220050f, -0.941544065183020810f, 0.333999651442009490f, + -0.942573197601446870f, + 0.331106305759876430f, -0.943593458161960390f, 0.328209843579092660f, + -0.944604837261480260f, + 0.325310292162262980f, -0.945607325380521280f, 0.322407678801070020f, + -0.946600913083283530f, + 0.319502030816015750f, -0.947585591017741090f, 0.316593375556165850f, + -0.948561349915730270f, + 0.313681740398891570f, -0.949528180593036670f, 0.310767152749611470f, + -0.950486073949481700f, + 0.307849640041534980f, -0.951435020969008340f, 0.304929229735402430f, + -0.952375012719765880f, + 0.302005949319228200f, -0.953306040354193750f, 0.299079826308040480f, + -0.954228095109105670f, + 0.296150888243623960f, -0.955141168305770670f, 0.293219162694258680f, + -0.956045251349996410f, + 0.290284677254462330f, -0.956940335732208940f, 0.287347459544729570f, + -0.957826413027532910f, + 0.284407537211271820f, -0.958703474895871600f, 0.281464937925758050f, + -0.959571513081984520f, + 0.278519689385053060f, -0.960430519415565790f, 0.275571819310958250f, + -0.961280485811320640f, + 0.272621355449948980f, -0.962121404269041580f, 0.269668325572915200f, + -0.962953266873683880f, + 0.266712757474898420f, -0.963776065795439840f, 0.263754678974831510f, + -0.964589793289812650f, + 0.260794117915275570f, -0.965394441697689400f, 0.257831102162158930f, + -0.966190003445412620f, + 0.254865659604514630f, -0.966976471044852070f, 0.251897818154216910f, + -0.967753837093475510f, + 0.248927605745720260f, -0.968522094274417270f, 0.245955050335794590f, + -0.969281235356548530f, + 0.242980179903263980f, -0.970031253194543970f, 0.240003022448741500f, + -0.970772140728950350f, + 0.237023605994367340f, -0.971503890986251780f, 0.234041958583543460f, + -0.972226497078936270f, + 0.231058108280671280f, -0.972939952205560070f, 0.228072083170885790f, + -0.973644249650811870f, + 0.225083911359792780f, -0.974339382785575860f, 0.222093620973203590f, + -0.975025345066994120f, + 0.219101240156869770f, -0.975702130038528570f, 0.216106797076219600f, + -0.976369731330021140f, + 0.213110319916091360f, -0.977028142657754390f, 0.210111836880469720f, + -0.977677357824509930f, + 0.207111376192218560f, -0.978317370719627650f, 0.204108966092817010f, + -0.978948175319062200f, + 0.201104634842091960f, -0.979569765685440520f, 0.198098410717953730f, + -0.980182135968117320f, + 0.195090322016128330f, -0.980785280403230430f, 0.192080397049892380f, + -0.981379193313754560f, + 0.189068664149806280f, -0.981963869109555240f, 0.186055151663446630f, + -0.982539302287441240f, + 0.183039887955141060f, -0.983105487431216290f, 0.180022901405699510f, + -0.983662419211730250f, + 0.177004220412148860f, -0.984210092386929030f, 0.173983873387463850f, + -0.984748501801904210f, + 0.170961888760301360f, -0.985277642388941220f, 0.167938294974731230f, + -0.985797509167567370f, + 0.164913120489970090f, -0.986308097244598670f, 0.161886393780111910f, + -0.986809401814185420f, + 0.158858143333861390f, -0.987301418157858430f, 0.155828397654265320f, + -0.987784141644572180f, + 0.152797185258443410f, -0.988257567730749460f, 0.149764534677321620f, + -0.988721691960323780f, + 0.146730474455361750f, -0.989176509964781010f, 0.143695033150294580f, + -0.989622017463200780f, + 0.140658239332849240f, -0.990058210262297120f, 0.137620121586486180f, + -0.990485084256456980f, + 0.134580708507126220f, -0.990902635427780010f, 0.131540028702883280f, + -0.991310859846115440f, + 0.128498110793793220f, -0.991709753669099530f, 0.125454983411546210f, + -0.992099313142191800f, + 0.122410675199216280f, -0.992479534598709970f, 0.119365214810991350f, + -0.992850414459865100f, + 0.116318630911904880f, -0.993211949234794500f, 0.113270952177564360f, + -0.993564135520595300f, + 0.110222207293883180f, -0.993906970002356060f, 0.107172424956808870f, + -0.994240449453187900f, + 0.104121633872054730f, -0.994564570734255420f, 0.101069862754827880f, + -0.994879330794805620f, + 0.098017140329560770f, -0.995184726672196820f, 0.094963495329639061f, + -0.995480755491926940f, + 0.091908956497132696f, -0.995767414467659820f, 0.088853552582524684f, + -0.996044700901251970f, + 0.085797312344439880f, -0.996312612182778000f, 0.082740264549375803f, + -0.996571145790554840f, + 0.079682437971430126f, -0.996820299291165670f, 0.076623861392031617f, + -0.997060070339482960f, + 0.073564563599667454f, -0.997290456678690210f, 0.070504573389614009f, + -0.997511456140303450f, + 0.067443919563664106f, -0.997723066644191640f, 0.064382630929857410f, + -0.997925286198596000f, + 0.061320736302208648f, -0.998118112900149180f, 0.058258264500435732f, + -0.998301544933892890f, + 0.055195244349690031f, -0.998475580573294770f, 0.052131704680283317f, + -0.998640218180265270f, + 0.049067674327418126f, -0.998795456205172410f, 0.046003182130914644f, + -0.998941293186856870f, + 0.042938256934940959f, -0.999077727752645360f, 0.039872927587739845f, + -0.999204758618363890f, + 0.036807222941358991f, -0.999322384588349540f, 0.033741171851377642f, + -0.999430604555461730f, + 0.030674803176636581f, -0.999529417501093140f, 0.027608145778965820f, + -0.999618822495178640f, + 0.024541228522912264f, -0.999698818696204250f, 0.021474080275469605f, + -0.999769405351215280f, + 0.018406729905804820f, -0.999830581795823400f, 0.015339206284988220f, + -0.999882347454212560f, + 0.012271538285719944f, -0.999924701839144500f, 0.009203754782059960f, + -0.999957644551963900f, + 0.006135884649154515f, -0.999981175282601110f, 0.003067956762966138f, + -0.999995293809576190f +}; + +static const float32_t Weights_2048[4096] = { + 1.000000000000000000f, 0.000000000000000000f, 0.999999705862882230f, + -0.000766990318742704f, + 0.999998823451701880f, -0.001533980186284766f, 0.999997352766978210f, + -0.002300969151425805f, + 0.999995293809576190f, -0.003067956762965976f, 0.999992646580707190f, + -0.003834942569706228f, + 0.999989411081928400f, -0.004601926120448571f, 0.999985587315143200f, + -0.005368906963996343f, + 0.999981175282601110f, -0.006135884649154475f, 0.999976174986897610f, + -0.006902858724729756f, + 0.999970586430974140f, -0.007669828739531097f, 0.999964409618118280f, + -0.008436794242369799f, + 0.999957644551963900f, -0.009203754782059819f, 0.999950291236490480f, + -0.009970709907418031f, + 0.999942349676023910f, -0.010737659167264491f, 0.999933819875236000f, + -0.011504602110422714f, + 0.999924701839144500f, -0.012271538285719925f, 0.999914995573113470f, + -0.013038467241987334f, + 0.999904701082852900f, -0.013805388528060391f, 0.999893818374418490f, + -0.014572301692779064f, + 0.999882347454212560f, -0.015339206284988100f, 0.999870288328982950f, + -0.016106101853537287f, + 0.999857641005823860f, -0.016872987947281710f, 0.999844405492175240f, + -0.017639864115082053f, + 0.999830581795823400f, -0.018406729905804820f, 0.999816169924900410f, + -0.019173584868322623f, + 0.999801169887884260f, -0.019940428551514441f, 0.999785581693599210f, + -0.020707260504265895f, + 0.999769405351215280f, -0.021474080275469508f, 0.999752640870248840f, + -0.022240887414024961f, + 0.999735288260561680f, -0.023007681468839369f, 0.999717347532362190f, + -0.023774461988827555f, + 0.999698818696204250f, -0.024541228522912288f, 0.999679701762987930f, + -0.025307980620024571f, + 0.999659996743959220f, -0.026074717829103901f, 0.999639703650710200f, + -0.026841439699098531f, + 0.999618822495178640f, -0.027608145778965740f, 0.999597353289648380f, + -0.028374835617672099f, + 0.999575296046749220f, -0.029141508764193722f, 0.999552650779456990f, + -0.029908164767516555f, + 0.999529417501093140f, -0.030674803176636626f, 0.999505596225325310f, + -0.031441423540560301f, + 0.999481186966166950f, -0.032208025408304586f, 0.999456189737977340f, + -0.032974608328897335f, + 0.999430604555461730f, -0.033741171851377580f, 0.999404431433671300f, + -0.034507715524795750f, + 0.999377670388002850f, -0.035274238898213947f, 0.999350321434199440f, + -0.036040741520706229f, + 0.999322384588349540f, -0.036807222941358832f, 0.999293859866887790f, + -0.037573682709270494f, + 0.999264747286594420f, -0.038340120373552694f, 0.999235046864595850f, + -0.039106535483329888f, + 0.999204758618363890f, -0.039872927587739811f, 0.999173882565716380f, + -0.040639296235933736f, + 0.999142418724816910f, -0.041405640977076739f, 0.999110367114174890f, + -0.042171961360347947f, + 0.999077727752645360f, -0.042938256934940820f, 0.999044500659429290f, + -0.043704527250063421f, + 0.999010685854073380f, -0.044470771854938668f, 0.998976283356469820f, + -0.045236990298804590f, + 0.998941293186856870f, -0.046003182130914623f, 0.998905715365818290f, + -0.046769346900537863f, + 0.998869549914283560f, -0.047535484156959303f, 0.998832796853527990f, + -0.048301593449480144f, + 0.998795456205172410f, -0.049067674327418015f, 0.998757527991183340f, + -0.049833726340107277f, + 0.998719012233872940f, -0.050599749036899282f, 0.998679908955899090f, + -0.051365741967162593f, + 0.998640218180265270f, -0.052131704680283324f, 0.998599939930320370f, + -0.052897636725665324f, + 0.998559074229759310f, -0.053663537652730520f, 0.998517621102622210f, + -0.054429407010919133f, + 0.998475580573294770f, -0.055195244349689934f, 0.998432952666508440f, + -0.055961049218520569f, + 0.998389737407340160f, -0.056726821166907748f, 0.998345934821212370f, + -0.057492559744367566f, + 0.998301544933892890f, -0.058258264500435752f, 0.998256567771495180f, + -0.059023934984667931f, + 0.998211003360478190f, -0.059789570746639868f, 0.998164851727646240f, + -0.060555171335947788f, + 0.998118112900149180f, -0.061320736302208578f, 0.998070786905482340f, + -0.062086265195060088f, + 0.998022873771486240f, -0.062851757564161406f, 0.997974373526346990f, + -0.063617212959193106f, + 0.997925286198596000f, -0.064382630929857465f, 0.997875611817110150f, + -0.065148011025878833f, + 0.997825350411111640f, -0.065913352797003805f, 0.997774502010167820f, + -0.066678655793001557f, + 0.997723066644191640f, -0.067443919563664051f, 0.997671044343441000f, + -0.068209143658806329f, + 0.997618435138519550f, -0.068974327628266746f, 0.997565239060375750f, + -0.069739471021907307f, + 0.997511456140303450f, -0.070504573389613856f, 0.997457086409941910f, + -0.071269634281296401f, + 0.997402129901275300f, -0.072034653246889332f, 0.997346586646633230f, + -0.072799629836351673f, + 0.997290456678690210f, -0.073564563599667426f, 0.997233740030466280f, + -0.074329454086845756f, + 0.997176436735326190f, -0.075094300847921305f, 0.997118546826979980f, + -0.075859103432954447f, + 0.997060070339482960f, -0.076623861392031492f, 0.997001007307235290f, + -0.077388574275265049f, + 0.996941357764982160f, -0.078153241632794232f, 0.996881121747813850f, + -0.078917863014784942f, + 0.996820299291165670f, -0.079682437971430126f, 0.996758890430818000f, + -0.080446966052950014f, + 0.996696895202896060f, -0.081211446809592441f, 0.996634313643869900f, + -0.081975879791633066f, + 0.996571145790554840f, -0.082740264549375692f, 0.996507391680110820f, + -0.083504600633152432f, + 0.996443051350042630f, -0.084268887593324071f, 0.996378124838200210f, + -0.085033124980280275f, + 0.996312612182778000f, -0.085797312344439894f, 0.996246513422315520f, + -0.086561449236251170f, + 0.996179828595696980f, -0.087325535206192059f, 0.996112557742151130f, + -0.088089569804770507f, + 0.996044700901251970f, -0.088853552582524600f, 0.995976258112917790f, + -0.089617483090022959f, + 0.995907229417411720f, -0.090381360877864983f, 0.995837614855341610f, + -0.091145185496681005f, + 0.995767414467659820f, -0.091908956497132724f, 0.995696628295663520f, + -0.092672673429913310f, + 0.995625256380994310f, -0.093436335845747787f, 0.995553298765638470f, + -0.094199943295393204f, + 0.995480755491926940f, -0.094963495329638992f, 0.995407626602534900f, + -0.095726991499307162f, + 0.995333912140482280f, -0.096490431355252593f, 0.995259612149133390f, + -0.097253814448363271f, + 0.995184726672196930f, -0.098017140329560604f, 0.995109255753726110f, + -0.098780408549799623f, + 0.995033199438118630f, -0.099543618660069319f, 0.994956557770116380f, + -0.100306770211392860f, + 0.994879330794805620f, -0.101069862754827820f, 0.994801518557617110f, + -0.101832895841466530f, + 0.994723121104325700f, -0.102595869022436280f, 0.994644138481050710f, + -0.103358781848899610f, + 0.994564570734255420f, -0.104121633872054590f, 0.994484417910747600f, + -0.104884424643134970f, + 0.994403680057679100f, -0.105647153713410620f, 0.994322357222545810f, + -0.106409820634187680f, + 0.994240449453187900f, -0.107172424956808840f, 0.994157956797789730f, + -0.107934966232653650f, + 0.994074879304879370f, -0.108697444013138720f, 0.993991217023329380f, + -0.109459857849717980f, + 0.993906970002356060f, -0.110222207293883060f, 0.993822138291519660f, + -0.110984491897163390f, + 0.993736721940724600f, -0.111746711211126590f, 0.993650721000219120f, + -0.112508864787378690f, + 0.993564135520595300f, -0.113270952177564350f, 0.993476965552789190f, + -0.114032972933367200f, + 0.993389211148080650f, -0.114794926606510080f, 0.993300872358093280f, + -0.115556812748755260f, + 0.993211949234794500f, -0.116318630911904750f, 0.993122441830495580f, + -0.117080380647800590f, + 0.993032350197851410f, -0.117842061508324980f, 0.992941674389860470f, + -0.118603673045400720f, + 0.992850414459865100f, -0.119365214810991350f, 0.992758570461551140f, + -0.120126686357101500f, + 0.992666142448948020f, -0.120888087235777080f, 0.992573130476428810f, + -0.121649416999105530f, + 0.992479534598709970f, -0.122410675199216200f, 0.992385354870851670f, + -0.123171861388280480f, + 0.992290591348257370f, -0.123932975118512160f, 0.992195244086673920f, + -0.124694015942167640f, + 0.992099313142191800f, -0.125454983411546230f, 0.992002798571244520f, + -0.126215877078990350f, + 0.991905700430609330f, -0.126976696496885870f, 0.991808018777406430f, + -0.127737441217662310f, + 0.991709753669099530f, -0.128498110793793170f, 0.991610905163495370f, + -0.129258704777796140f, + 0.991511473318743900f, -0.130019222722233350f, 0.991411458193338540f, + -0.130779664179711710f, + 0.991310859846115440f, -0.131540028702883120f, 0.991209678336254060f, + -0.132300315844444650f, + 0.991107913723276890f, -0.133060525157139060f, 0.991005566067049370f, + -0.133820656193754720f, + 0.990902635427780010f, -0.134580708507126170f, 0.990799121866020370f, + -0.135340681650134210f, + 0.990695025442664630f, -0.136100575175706200f, 0.990590346218950150f, + -0.136860388636816380f, + 0.990485084256457090f, -0.137620121586486040f, 0.990379239617108160f, + -0.138379773577783890f, + 0.990272812363169110f, -0.139139344163826200f, 0.990165802557248400f, + -0.139898832897777210f, + 0.990058210262297120f, -0.140658239332849210f, 0.989950035541608990f, + -0.141417563022303020f, + 0.989841278458820530f, -0.142176803519448030f, 0.989731939077910570f, + -0.142935960377642670f, + 0.989622017463200890f, -0.143695033150294470f, 0.989511513679355190f, + -0.144454021390860470f, + 0.989400427791380380f, -0.145212924652847460f, 0.989288759864625170f, + -0.145971742489812210f, + 0.989176509964781010f, -0.146730474455361750f, 0.989063678157881540f, + -0.147489120103153570f, + 0.988950264510302990f, -0.148247678986896030f, 0.988836269088763540f, + -0.149006150660348450f, + 0.988721691960323780f, -0.149764534677321510f, 0.988606533192386450f, + -0.150522830591677400f, + 0.988490792852696590f, -0.151281037957330220f, 0.988374471009341280f, + -0.152039156328246050f, + 0.988257567730749460f, -0.152797185258443440f, 0.988140083085692570f, + -0.153555124301993450f, + 0.988022017143283530f, -0.154312973013020100f, 0.987903369972977790f, + -0.155070730945700510f, + 0.987784141644572180f, -0.155828397654265230f, 0.987664332228205710f, + -0.156585972692998430f, + 0.987543941794359230f, -0.157343455616238250f, 0.987422970413855410f, + -0.158100845978376980f, + 0.987301418157858430f, -0.158858143333861450f, 0.987179285097874340f, + -0.159615347237193060f, + 0.987056571305750970f, -0.160372457242928280f, 0.986933276853677710f, + -0.161129472905678810f, + 0.986809401814185530f, -0.161886393780111830f, 0.986684946260146690f, + -0.162643219420950310f, + 0.986559910264775410f, -0.163399949382973230f, 0.986434293901627180f, + -0.164156583221015810f, + 0.986308097244598670f, -0.164913120489969890f, 0.986181320367928270f, + -0.165669560744784120f, + 0.986053963346195440f, -0.166425903540464100f, 0.985926026254321130f, + -0.167182148432072940f, + 0.985797509167567480f, -0.167938294974731170f, 0.985668412161537550f, + -0.168694342723617330f, + 0.985538735312176060f, -0.169450291233967960f, 0.985408478695768420f, + -0.170206140061078070f, + 0.985277642388941220f, -0.170961888760301220f, 0.985146226468662230f, + -0.171717536887049970f, + 0.985014231012239840f, -0.172473083996795950f, 0.984881656097323700f, + -0.173228529645070320f, + 0.984748501801904210f, -0.173983873387463820f, 0.984614768204312600f, + -0.174739114779627200f, + 0.984480455383220930f, -0.175494253377271430f, 0.984345563417641900f, + -0.176249288736167880f, + 0.984210092386929030f, -0.177004220412148750f, 0.984074042370776450f, + -0.177759047961107170f, + 0.983937413449218920f, -0.178513770938997510f, 0.983800205702631600f, + -0.179268388901835750f, + 0.983662419211730250f, -0.180022901405699510f, 0.983524054057571260f, + -0.180777308006728590f, + 0.983385110321551180f, -0.181531608261124970f, 0.983245588085407070f, + -0.182285801725153300f, + 0.983105487431216290f, -0.183039887955140950f, 0.982964808441396440f, + -0.183793866507478450f, + 0.982823551198705240f, -0.184547736938619620f, 0.982681715786240860f, + -0.185301498805081900f, + 0.982539302287441240f, -0.186055151663446630f, 0.982396310786084690f, + -0.186808695070359270f, + 0.982252741366289370f, -0.187562128582529600f, 0.982108594112513610f, + -0.188315451756732120f, + 0.981963869109555240f, -0.189068664149806190f, 0.981818566442552500f, + -0.189821765318656410f, + 0.981672686196983110f, -0.190574754820252740f, 0.981526228458664770f, + -0.191327632211630900f, + 0.981379193313754560f, -0.192080397049892440f, 0.981231580848749730f, + -0.192833048892205230f, + 0.981083391150486710f, -0.193585587295803610f, 0.980934624306141640f, + -0.194338011817988600f, + 0.980785280403230430f, -0.195090322016128250f, 0.980635359529608120f, + -0.195842517447657850f, + 0.980484861773469380f, -0.196594597670080220f, 0.980333787223347960f, + -0.197346562240965920f, + 0.980182135968117430f, -0.198098410717953560f, 0.980029908096990090f, + -0.198850142658750090f, + 0.979877103699517640f, -0.199601757621130970f, 0.979723722865591170f, + -0.200353255162940450f, + 0.979569765685440520f, -0.201104634842091900f, 0.979415232249634780f, + -0.201855896216568050f, + 0.979260122649082020f, -0.202607038844421130f, 0.979104436975029250f, + -0.203358062283773320f, + 0.978948175319062200f, -0.204108966092816870f, 0.978791337773105670f, + -0.204859749829814420f, + 0.978633924429423210f, -0.205610413053099240f, 0.978475935380616830f, + -0.206360955321075510f, + 0.978317370719627650f, -0.207111376192218560f, 0.978158230539735050f, + -0.207861675225075070f, + 0.977998514934557140f, -0.208611851978263490f, 0.977838223998050430f, + -0.209361906010474160f, + 0.977677357824509930f, -0.210111836880469610f, 0.977515916508569280f, + -0.210861644147084860f, + 0.977353900145199960f, -0.211611327369227550f, 0.977191308829712280f, + -0.212360886105878420f, + 0.977028142657754390f, -0.213110319916091360f, 0.976864401725312640f, + -0.213859628358993750f, + 0.976700086128711840f, -0.214608810993786760f, 0.976535195964614470f, + -0.215357867379745550f, + 0.976369731330021140f, -0.216106797076219520f, 0.976203692322270560f, + -0.216855599642632620f, + 0.976037079039039020f, -0.217604274638483640f, 0.975869891578341030f, + -0.218352821623346320f, + 0.975702130038528570f, -0.219101240156869800f, 0.975533794518291360f, + -0.219849529798778700f, + 0.975364885116656980f, -0.220597690108873510f, 0.975195401932990370f, + -0.221345720647030810f, + 0.975025345066994120f, -0.222093620973203510f, 0.974854714618708430f, + -0.222841390647421120f, + 0.974683510688510670f, -0.223589029229789990f, 0.974511733377115720f, + -0.224336536280493600f, + 0.974339382785575860f, -0.225083911359792830f, 0.974166459015280320f, + -0.225831154028026170f, + 0.973992962167955830f, -0.226578263845610000f, 0.973818892345666100f, + -0.227325240373038860f, + 0.973644249650811980f, -0.228072083170885730f, 0.973469034186131070f, + -0.228818791799802220f, + 0.973293246054698250f, -0.229565365820518870f, 0.973116885359925130f, + -0.230311804793845440f, + 0.972939952205560180f, -0.231058108280671110f, 0.972762446695688570f, + -0.231804275841964780f, + 0.972584368934732210f, -0.232550307038775240f, 0.972405719027449770f, + -0.233296201432231590f, + 0.972226497078936270f, -0.234041958583543430f, 0.972046703194623500f, + -0.234787578054000970f, + 0.971866337480279400f, -0.235533059404975490f, 0.971685400042008540f, + -0.236278402197919570f, + 0.971503890986251780f, -0.237023605994367200f, 0.971321810419786160f, + -0.237768670355934190f, + 0.971139158449725090f, -0.238513594844318420f, 0.970955935183517970f, + -0.239258379021299980f, + 0.970772140728950350f, -0.240003022448741500f, 0.970587775194143630f, + -0.240747524688588430f, + 0.970402838687555500f, -0.241491885302869330f, 0.970217331317979160f, + -0.242236103853696010f, + 0.970031253194543970f, -0.242980179903263870f, 0.969844604426714830f, + -0.243724113013852160f, + 0.969657385124292450f, -0.244467902747824150f, 0.969469595397413060f, + -0.245211548667627540f, + 0.969281235356548530f, -0.245955050335794590f, 0.969092305112506210f, + -0.246698407314942410f, + 0.968902804776428870f, -0.247441619167773270f, 0.968712734459794780f, + -0.248184685457074780f, + 0.968522094274417380f, -0.248927605745720150f, 0.968330884332445190f, + -0.249670379596668570f, + 0.968139104746362440f, -0.250413006572965220f, 0.967946755628987800f, + -0.251155486237741920f, + 0.967753837093475510f, -0.251897818154216970f, 0.967560349253314360f, + -0.252640001885695520f, + 0.967366292222328510f, -0.253382036995570160f, 0.967171666114676640f, + -0.254123923047320620f, + 0.966976471044852070f, -0.254865659604514570f, 0.966780707127683270f, + -0.255607246230807380f, + 0.966584374478333120f, -0.256348682489942910f, 0.966387473212298900f, + -0.257089967945753120f, + 0.966190003445412500f, -0.257831102162158990f, 0.965991965293840570f, + -0.258572084703170340f, + 0.965793358874083680f, -0.259312915132886230f, 0.965594184302976830f, + -0.260053593015495190f, + 0.965394441697689400f, -0.260794117915275510f, 0.965194131175724720f, + -0.261534489396595520f, + 0.964993252854920320f, -0.262274707023913590f, 0.964791806853447900f, + -0.263014770361779000f, + 0.964589793289812760f, -0.263754678974831350f, 0.964387212282854290f, + -0.264494432427801630f, + 0.964184063951745830f, -0.265234030285511790f, 0.963980348415994110f, + -0.265973472112875590f, + 0.963776065795439840f, -0.266712757474898370f, 0.963571216210257320f, + -0.267451885936677620f, + 0.963365799780954050f, -0.268190857063403180f, 0.963159816628371360f, + -0.268929670420357260f, + 0.962953266873683880f, -0.269668325572915090f, 0.962746150638399410f, + -0.270406822086544820f, + 0.962538468044359160f, -0.271145159526808010f, 0.962330219213737400f, + -0.271883337459359720f, + 0.962121404269041580f, -0.272621355449948980f, 0.961912023333112210f, + -0.273359213064418680f, + 0.961702076529122540f, -0.274096909868706380f, 0.961491563980579000f, + -0.274834445428843940f, + 0.961280485811320640f, -0.275571819310958140f, 0.961068842145519350f, + -0.276309031081271080f, + 0.960856633107679660f, -0.277046080306099900f, 0.960643858822638590f, + -0.277782966551857690f, + 0.960430519415565790f, -0.278519689385053060f, 0.960216615011963430f, + -0.279256248372291180f, + 0.960002145737665960f, -0.279992643080273220f, 0.959787111718839900f, + -0.280728873075797190f, + 0.959571513081984520f, -0.281464937925757940f, 0.959355349953930790f, + -0.282200837197147560f, + 0.959138622461841890f, -0.282936570457055390f, 0.958921330733213170f, + -0.283672137272668430f, + 0.958703474895871600f, -0.284407537211271880f, 0.958485055077976100f, + -0.285142769840248670f, + 0.958266071408017670f, -0.285877834727080620f, 0.958046524014818600f, + -0.286612731439347790f, + 0.957826413027532910f, -0.287347459544729510f, 0.957605738575646350f, + -0.288082018611004130f, + 0.957384500788975860f, -0.288816408206049480f, 0.957162699797670210f, + -0.289550627897843030f, + 0.956940335732208820f, -0.290284677254462330f, 0.956717408723403050f, + -0.291018555844085090f, + 0.956493918902395100f, -0.291752263234989260f, 0.956269866400658030f, + -0.292485798995553880f, + 0.956045251349996410f, -0.293219162694258630f, 0.955820073882545420f, + -0.293952353899684660f, + 0.955594334130771110f, -0.294685372180514330f, 0.955368032227470350f, + -0.295418217105532010f, + 0.955141168305770780f, -0.296150888243623790f, 0.954913742499130520f, + -0.296883385163778270f, + 0.954685754941338340f, -0.297615707435086200f, 0.954457205766513490f, + -0.298347854626741400f, + 0.954228095109105670f, -0.299079826308040480f, 0.953998423103894490f, + -0.299811622048383350f, + 0.953768189885990330f, -0.300543241417273450f, 0.953537395590833280f, + -0.301274683984317950f, + 0.953306040354193860f, -0.302005949319228080f, 0.953074124312172200f, + -0.302737036991819140f, + 0.952841647601198720f, -0.303467946572011320f, 0.952608610358033350f, + -0.304198677629829110f, + 0.952375012719765880f, -0.304929229735402370f, 0.952140854823815830f, + -0.305659602458966120f, + 0.951906136807932350f, -0.306389795370860920f, 0.951670858810193860f, + -0.307119808041533100f, + 0.951435020969008340f, -0.307849640041534870f, 0.951198623423113230f, + -0.308579290941525090f, + 0.950961666311575080f, -0.309308760312268730f, 0.950724149773789610f, + -0.310038047724637890f, + 0.950486073949481700f, -0.310767152749611470f, 0.950247438978705230f, + -0.311496074958275910f, + 0.950008245001843000f, -0.312224813921824880f, 0.949768492159606680f, + -0.312953369211560200f, + 0.949528180593036670f, -0.313681740398891520f, 0.949287310443502120f, + -0.314409927055336660f, + 0.949045881852700560f, -0.315137928752522440f, 0.948803894962658490f, + -0.315865745062183960f, + 0.948561349915730270f, -0.316593375556165850f, 0.948318246854599090f, + -0.317320819806421740f, + 0.948074585922276230f, -0.318048077385014950f, 0.947830367262101010f, + -0.318775147864118480f, + 0.947585591017741090f, -0.319502030816015690f, 0.947340257333192050f, + -0.320228725813099860f, + 0.947094366352777220f, -0.320955232427875210f, 0.946847918221148000f, + -0.321681550232956580f, + 0.946600913083283530f, -0.322407678801069850f, 0.946353351084490590f, + -0.323133617705052330f, + 0.946105232370403450f, -0.323859366517852850f, 0.945856557086983910f, + -0.324584924812532150f, + 0.945607325380521280f, -0.325310292162262930f, 0.945357537397632290f, + -0.326035468140330240f, + 0.945107193285260610f, -0.326760452320131730f, 0.944856293190677210f, + -0.327485244275178000f, + 0.944604837261480260f, -0.328209843579092500f, 0.944352825645594750f, + -0.328934249805612200f, + 0.944100258491272660f, -0.329658462528587490f, 0.943847135947092690f, + -0.330382481321982780f, + 0.943593458161960390f, -0.331106305759876430f, 0.943339225285107720f, + -0.331829935416461110f, + 0.943084437466093490f, -0.332553369866044220f, 0.942829094854802710f, + -0.333276608683047930f, + 0.942573197601446870f, -0.333999651442009380f, 0.942316745856563780f, + -0.334722497717581220f, + 0.942059739771017310f, -0.335445147084531600f, 0.941802179495997650f, + -0.336167599117744520f, + 0.941544065183020810f, -0.336889853392220050f, 0.941285396983928660f, + -0.337611909483074620f, + 0.941026175050889260f, -0.338333766965541130f, 0.940766399536396070f, + -0.339055425414969640f, + 0.940506070593268300f, -0.339776884406826850f, 0.940245188374650880f, + -0.340498143516697160f, + 0.939983753034014050f, -0.341219202320282360f, 0.939721764725153340f, + -0.341940060393402190f, + 0.939459223602189920f, -0.342660717311994380f, 0.939196129819569900f, + -0.343381172652115040f, + 0.938932483532064600f, -0.344101425989938810f, 0.938668284894770170f, + -0.344821476901759290f, + 0.938403534063108060f, -0.345541324963989090f, 0.938138231192824360f, + -0.346260969753160010f, + 0.937872376439989890f, -0.346980410845923680f, 0.937605969960999990f, + -0.347699647819051380f, + 0.937339011912574960f, -0.348418680249434560f, 0.937071502451759190f, + -0.349137507714084970f, + 0.936803441735921560f, -0.349856129790134920f, 0.936534829922755500f, + -0.350574546054837510f, + 0.936265667170278260f, -0.351292756085567090f, 0.935995953636831410f, + -0.352010759459819080f, + 0.935725689481080370f, -0.352728555755210730f, 0.935454874862014620f, + -0.353446144549480810f, + 0.935183509938947610f, -0.354163525420490340f, 0.934911594871516090f, + -0.354880697946222790f, + 0.934639129819680780f, -0.355597661704783850f, 0.934366114943725790f, + -0.356314416274402410f, + 0.934092550404258980f, -0.357030961233429980f, 0.933818436362210960f, + -0.357747296160341900f, + 0.933543772978836170f, -0.358463420633736540f, 0.933268560415712050f, + -0.359179334232336500f, + 0.932992798834738960f, -0.359895036534988110f, 0.932716488398140250f, + -0.360610527120662270f, + 0.932439629268462360f, -0.361325805568454280f, 0.932162221608574430f, + -0.362040871457584180f, + 0.931884265581668150f, -0.362755724367397230f, 0.931605761351257830f, + -0.363470363877363760f, + 0.931326709081180430f, -0.364184789567079890f, 0.931047108935595280f, + -0.364899001016267320f, + 0.930766961078983710f, -0.365612997804773850f, 0.930486265676149780f, + -0.366326779512573590f, + 0.930205022892219070f, -0.367040345719767180f, 0.929923232892639670f, + -0.367753696006581980f, + 0.929640895843181330f, -0.368466829953372320f, 0.929358011909935500f, + -0.369179747140620020f, + 0.929074581259315860f, -0.369892447148934100f, 0.928790604058057020f, + -0.370604929559051670f, + 0.928506080473215590f, -0.371317193951837540f, 0.928221010672169440f, + -0.372029239908285010f, + 0.927935394822617890f, -0.372741067009515760f, 0.927649233092581180f, + -0.373452674836780300f, + 0.927362525650401110f, -0.374164062971457930f, 0.927075272664740100f, + -0.374875230995057540f, + 0.926787474304581750f, -0.375586178489217220f, 0.926499130739230510f, + -0.376296905035704790f, + 0.926210242138311380f, -0.377007410216418260f, 0.925920808671770070f, + -0.377717693613385640f, + 0.925630830509872720f, -0.378427754808765560f, 0.925340307823206310f, + -0.379137593384847320f, + 0.925049240782677580f, -0.379847208924051160f, 0.924757629559513910f, + -0.380556601008928520f, + 0.924465474325262600f, -0.381265769222162380f, 0.924172775251791200f, + -0.381974713146567220f, + 0.923879532511286740f, -0.382683432365089780f, 0.923585746276256670f, + -0.383391926460808660f, + 0.923291416719527640f, -0.384100195016935040f, 0.922996544014246250f, + -0.384808237616812880f, + 0.922701128333878630f, -0.385516053843918850f, 0.922405169852209880f, + -0.386223643281862980f, + 0.922108668743345180f, -0.386931005514388580f, 0.921811625181708120f, + -0.387638140125372730f, + 0.921514039342042010f, -0.388345046698826250f, 0.921215911399408730f, + -0.389051724818894380f, + 0.920917241529189520f, -0.389758174069856410f, 0.920618029907083970f, + -0.390464394036126590f, + 0.920318276709110590f, -0.391170384302253870f, 0.920017982111606570f, + -0.391876144452922350f, + 0.919717146291227360f, -0.392581674072951470f, 0.919415769424947070f, + -0.393286972747296400f, + 0.919113851690057770f, -0.393992040061048100f, 0.918811393264170050f, + -0.394696875599433560f, + 0.918508394325212250f, -0.395401478947816350f, 0.918204855051430900f, + -0.396105849691696270f, + 0.917900775621390500f, -0.396809987416710310f, 0.917596156213972950f, + -0.397513891708632330f, + 0.917290997008377910f, -0.398217562153373560f, 0.916985298184123000f, + -0.398920998336982910f, + 0.916679059921042700f, -0.399624199845646790f, 0.916372282399289140f, + -0.400327166265690090f, + 0.916064965799331720f, -0.401029897183575620f, 0.915757110301956720f, + -0.401732392185905010f, + 0.915448716088267830f, -0.402434650859418430f, 0.915139783339685260f, + -0.403136672790995300f, + 0.914830312237946200f, -0.403838457567654070f, 0.914520302965104450f, + -0.404540004776553000f, + 0.914209755703530690f, -0.405241314004989860f, 0.913898670635911680f, + -0.405942384840402510f, + 0.913587047945250810f, -0.406643216870369030f, 0.913274887814867760f, + -0.407343809682607970f, + 0.912962190428398210f, -0.408044162864978690f, 0.912648955969793900f, + -0.408744276005481360f, + 0.912335184623322750f, -0.409444148692257590f, 0.912020876573568340f, + -0.410143780513590240f, + 0.911706032005429880f, -0.410843171057903910f, 0.911390651104122430f, + -0.411542319913765220f, + 0.911074734055176360f, -0.412241226669882890f, 0.910758281044437570f, + -0.412939890915108080f, + 0.910441292258067250f, -0.413638312238434500f, 0.910123767882541680f, + -0.414336490228999100f, + 0.909805708104652220f, -0.415034424476081630f, 0.909487113111505430f, + -0.415732114569105360f, + 0.909167983090522380f, -0.416429560097637150f, 0.908848318229439120f, + -0.417126760651387870f, + 0.908528118716306120f, -0.417823715820212270f, 0.908207384739488700f, + -0.418520425194109700f, + 0.907886116487666260f, -0.419216888363223910f, 0.907564314149832630f, + -0.419913104917843620f, + 0.907241977915295820f, -0.420609074448402510f, 0.906919107973678140f, + -0.421304796545479640f, + 0.906595704514915330f, -0.422000270799799680f, 0.906271767729257660f, + -0.422695496802232950f, + 0.905947297807268460f, -0.423390474143796050f, 0.905622294939825270f, + -0.424085202415651560f, + 0.905296759318118820f, -0.424779681209108810f, 0.904970691133653250f, + -0.425473910115623800f, + 0.904644090578246240f, -0.426167888726799620f, 0.904316957844028320f, + -0.426861616634386430f, + 0.903989293123443340f, -0.427555093430282080f, 0.903661096609247980f, + -0.428248318706531960f, + 0.903332368494511820f, -0.428941292055329490f, 0.903003108972617150f, + -0.429634013069016380f, + 0.902673318237258830f, -0.430326481340082610f, 0.902342996482444200f, + -0.431018696461167030f, + 0.902012143902493180f, -0.431710658025057260f, 0.901680760692037730f, + -0.432402365624690140f, + 0.901348847046022030f, -0.433093818853151960f, 0.901016403159702330f, + -0.433785017303678520f, + 0.900683429228646970f, -0.434475960569655650f, 0.900349925448735600f, + -0.435166648244619260f, + 0.900015892016160280f, -0.435857079922255470f, 0.899681329127423930f, + -0.436547255196401200f, + 0.899346236979341570f, -0.437237173661044090f, 0.899010615769039070f, + -0.437926834910322860f, + 0.898674465693953820f, -0.438616238538527660f, 0.898337786951834310f, + -0.439305384140099950f, + 0.898000579740739880f, -0.439994271309633260f, 0.897662844259040860f, + -0.440682899641872900f, + 0.897324580705418320f, -0.441371268731716670f, 0.896985789278863970f, + -0.442059378174214700f, + 0.896646470178680150f, -0.442747227564570020f, 0.896306623604479550f, + -0.443434816498138480f, + 0.895966249756185220f, -0.444122144570429200f, 0.895625348834030110f, + -0.444809211377104880f, + 0.895283921038557580f, -0.445496016513981740f, 0.894941966570620750f, + -0.446182559577030070f, + 0.894599485631382700f, -0.446868840162374160f, 0.894256478422316040f, + -0.447554857866293010f, + 0.893912945145203250f, -0.448240612285219890f, 0.893568886002135910f, + -0.448926103015743260f, + 0.893224301195515320f, -0.449611329654606540f, 0.892879190928051680f, + -0.450296291798708610f, + 0.892533555402764580f, -0.450980989045103860f, 0.892187394822982480f, + -0.451665420991002490f, + 0.891840709392342720f, -0.452349587233770890f, 0.891493499314791380f, + -0.453033487370931580f, + 0.891145764794583180f, -0.453717121000163870f, 0.890797506036281490f, + -0.454400487719303580f, + 0.890448723244757880f, -0.455083587126343840f, 0.890099416625192320f, + -0.455766418819434640f, + 0.889749586383072780f, -0.456448982396883920f, 0.889399232724195520f, + -0.457131277457156980f, + 0.889048355854664570f, -0.457813303598877170f, 0.888696955980891600f, + -0.458495060420826270f, + 0.888345033309596350f, -0.459176547521944090f, 0.887992588047805560f, + -0.459857764501329540f, + 0.887639620402853930f, -0.460538710958240010f, 0.887286130582383150f, + -0.461219386492092380f, + 0.886932118794342190f, -0.461899790702462730f, 0.886577585246987040f, + -0.462579923189086810f, + 0.886222530148880640f, -0.463259783551860150f, 0.885866953708892790f, + -0.463939371390838520f, + 0.885510856136199950f, -0.464618686306237820f, 0.885154237640285110f, + -0.465297727898434600f, + 0.884797098430937790f, -0.465976495767966180f, 0.884439438718253810f, + -0.466654989515530920f, + 0.884081258712634990f, -0.467333208741988420f, 0.883722558624789660f, + -0.468011153048359830f, + 0.883363338665731580f, -0.468688822035827900f, 0.883003599046780830f, + -0.469366215305737520f, + 0.882643339979562790f, -0.470043332459595620f, 0.882282561676008710f, + -0.470720173099071600f, + 0.881921264348355050f, -0.471396736825997640f, 0.881559448209143780f, + -0.472073023242368660f, + 0.881197113471222090f, -0.472749031950342790f, 0.880834260347742040f, + -0.473424762552241530f, + 0.880470889052160750f, -0.474100214650549970f, 0.880106999798240360f, + -0.474775387847917120f, + 0.879742592800047410f, -0.475450281747155870f, 0.879377668271953290f, + -0.476124895951243580f, + 0.879012226428633530f, -0.476799230063322090f, 0.878646267485068130f, + -0.477473283686698060f, + 0.878279791656541580f, -0.478147056424843010f, 0.877912799158641840f, + -0.478820547881393890f, + 0.877545290207261350f, -0.479493757660153010f, 0.877177265018595940f, + -0.480166685365088390f, + 0.876808723809145650f, -0.480839330600333960f, 0.876439666795713610f, + -0.481511692970189860f, + 0.876070094195406600f, -0.482183772079122720f, 0.875700006225634600f, + -0.482855567531765670f, + 0.875329403104110890f, -0.483527078932918740f, 0.874958285048851650f, + -0.484198305887549030f, + 0.874586652278176110f, -0.484869248000791060f, 0.874214505010706300f, + -0.485539904877946960f, + 0.873841843465366860f, -0.486210276124486420f, 0.873468667861384880f, + -0.486880361346047340f, + 0.873094978418290090f, -0.487550160148436000f, 0.872720775355914300f, + -0.488219672137626790f, + 0.872346058894391540f, -0.488888896919763170f, 0.871970829254157810f, + -0.489557834101157440f, + 0.871595086655950980f, -0.490226483288291160f, 0.871218831320811020f, + -0.490894844087815090f, + 0.870842063470078980f, -0.491562916106549900f, 0.870464783325397670f, + -0.492230698951486020f, + 0.870086991108711460f, -0.492898192229784040f, 0.869708687042265670f, + -0.493565395548774770f, + 0.869329871348606840f, -0.494232308515959670f, 0.868950544250582380f, + -0.494898930739011260f, + 0.868570705971340900f, -0.495565261825772540f, 0.868190356734331310f, + -0.496231301384258250f, + 0.867809496763303320f, -0.496897049022654470f, 0.867428126282306920f, + -0.497562504349319150f, + 0.867046245515692650f, -0.498227666972781870f, 0.866663854688111130f, + -0.498892536501744590f, + 0.866280954024512990f, -0.499557112545081840f, 0.865897543750148820f, + -0.500221394711840680f, + 0.865513624090569090f, -0.500885382611240710f, 0.865129195271623800f, + -0.501549075852675390f, + 0.864744257519462380f, -0.502212474045710790f, 0.864358811060534030f, + -0.502875576800086990f, + 0.863972856121586810f, -0.503538383725717580f, 0.863586392929668100f, + -0.504200894432690340f, + 0.863199421712124160f, -0.504863108531267590f, 0.862811942696600330f, + -0.505525025631885390f, + 0.862423956111040610f, -0.506186645345155230f, 0.862035462183687210f, + -0.506847967281863210f, + 0.861646461143081300f, -0.507508991052970870f, 0.861256953218062170f, + -0.508169716269614600f, + 0.860866938637767310f, -0.508830142543106990f, 0.860476417631632070f, + -0.509490269484936360f, + 0.860085390429390140f, -0.510150096706766810f, 0.859693857261072610f, + -0.510809623820439040f, + 0.859301818357008470f, -0.511468850437970300f, 0.858909273947823900f, + -0.512127776171554690f, + 0.858516224264442740f, -0.512786400633562960f, 0.858122669538086140f, + -0.513444723436543460f, + 0.857728610000272120f, -0.514102744193221660f, 0.857334045882815590f, + -0.514760462516501200f, + 0.856938977417828760f, -0.515417878019462930f, 0.856543404837719960f, + -0.516074990315366630f, + 0.856147328375194470f, -0.516731799017649870f, 0.855750748263253920f, + -0.517388303739929060f, + 0.855353664735196030f, -0.518044504095999340f, 0.854956078024614930f, + -0.518700399699834950f, + 0.854557988365400530f, -0.519355990165589640f, 0.854159395991738850f, + -0.520011275107596040f, + 0.853760301138111410f, -0.520666254140367160f, 0.853360704039295430f, + -0.521320926878595660f, + 0.852960604930363630f, -0.521975292937154390f, 0.852560004046684080f, + -0.522629351931096610f, + 0.852158901623919830f, -0.523283103475656430f, 0.851757297898029120f, + -0.523936547186248600f, + 0.851355193105265200f, -0.524589682678468950f, 0.850952587482175730f, + -0.525242509568094710f, + 0.850549481265603480f, -0.525895027471084630f, 0.850145874692685210f, + -0.526547236003579440f, + 0.849741768000852550f, -0.527199134781901280f, 0.849337161427830780f, + -0.527850723422555230f, + 0.848932055211639610f, -0.528502001542228480f, 0.848526449590592650f, + -0.529152968757790610f, + 0.848120344803297230f, -0.529803624686294610f, 0.847713741088654380f, + -0.530453968944976320f, + 0.847306638685858320f, -0.531104001151255000f, 0.846899037834397240f, + -0.531753720922733320f, + 0.846490938774052130f, -0.532403127877197900f, 0.846082341744897050f, + -0.533052221632619450f, + 0.845673246987299070f, -0.533701001807152960f, 0.845263654741918220f, + -0.534349468019137520f, + 0.844853565249707120f, -0.534997619887097150f, 0.844442978751910660f, + -0.535645457029741090f, + 0.844031895490066410f, -0.536292979065963180f, 0.843620315706004150f, + -0.536940185614842910f, + 0.843208239641845440f, -0.537587076295645390f, 0.842795667540004120f, + -0.538233650727821700f, + 0.842382599643185850f, -0.538879908531008420f, 0.841969036194387680f, + -0.539525849325028890f, + 0.841554977436898440f, -0.540171472729892850f, 0.841140423614298080f, + -0.540816778365796670f, + 0.840725374970458070f, -0.541461765853123440f, 0.840309831749540770f, + -0.542106434812443920f, + 0.839893794195999520f, -0.542750784864515890f, 0.839477262554578550f, + -0.543394815630284800f, + 0.839060237070312740f, -0.544038526730883820f, 0.838642717988527300f, + -0.544681917787634530f, + 0.838224705554838080f, -0.545324988422046460f, 0.837806200015150940f, + -0.545967738255817570f, + 0.837387201615661940f, -0.546610166910834860f, 0.836967710602857020f, + -0.547252274009174090f, + 0.836547727223512010f, -0.547894059173100190f, 0.836127251724692270f, + -0.548535522025067390f, + 0.835706284353752600f, -0.549176662187719660f, 0.835284825358337370f, + -0.549817479283890910f, + 0.834862874986380010f, -0.550457972936604810f, 0.834440433486103190f, + -0.551098142769075430f, + 0.834017501106018130f, -0.551737988404707340f, 0.833594078094925140f, + -0.552377509467096070f, + 0.833170164701913190f, -0.553016705580027470f, 0.832745761176359460f, + -0.553655576367479310f, + 0.832320867767929680f, -0.554294121453620000f, 0.831895484726577590f, + -0.554932340462810370f, + 0.831469612302545240f, -0.555570233019602180f, 0.831043250746362320f, + -0.556207798748739930f, + 0.830616400308846310f, -0.556845037275160100f, 0.830189061241102370f, + -0.557481948223991550f, + 0.829761233794523050f, -0.558118531220556100f, 0.829332918220788250f, + -0.558754785890368310f, + 0.828904114771864870f, -0.559390711859136140f, 0.828474823700007130f, + -0.560026308752760380f, + 0.828045045257755800f, -0.560661576197336030f, 0.827614779697938400f, + -0.561296513819151470f, + 0.827184027273669130f, -0.561931121244689470f, 0.826752788238348520f, + -0.562565398100626560f, + 0.826321062845663530f, -0.563199344013834090f, 0.825888851349586780f, + -0.563832958611378170f, + 0.825456154004377550f, -0.564466241520519500f, 0.825022971064580220f, + -0.565099192368713980f, + 0.824589302785025290f, -0.565731810783613120f, 0.824155149420828570f, + -0.566364096393063840f, + 0.823720511227391430f, -0.566996048825108680f, 0.823285388460400110f, + -0.567627667707986230f, + 0.822849781375826430f, -0.568258952670131490f, 0.822413690229926390f, + -0.568889903340175860f, + 0.821977115279241550f, -0.569520519346947140f, 0.821540056780597610f, + -0.570150800319470300f, + 0.821102514991104650f, -0.570780745886967260f, 0.820664490168157460f, + -0.571410355678857230f, + 0.820225982569434690f, -0.572039629324757050f, 0.819786992452898990f, + -0.572668566454481160f, + 0.819347520076796900f, -0.573297166698042200f, 0.818907565699658950f, + -0.573925429685650750f, + 0.818467129580298660f, -0.574553355047715760f, 0.818026211977813440f, + -0.575180942414845080f, + 0.817584813151583710f, -0.575808191417845340f, 0.817142933361272970f, + -0.576435101687721830f, + 0.816700572866827850f, -0.577061672855679440f, 0.816257731928477390f, + -0.577687904553122800f, + 0.815814410806733780f, -0.578313796411655590f, 0.815370609762391290f, + -0.578939348063081780f, + 0.814926329056526620f, -0.579564559139405630f, 0.814481568950498610f, + -0.580189429272831680f, + 0.814036329705948410f, -0.580813958095764530f, 0.813590611584798510f, + -0.581438145240810170f, + 0.813144414849253590f, -0.582061990340775440f, 0.812697739761799490f, + -0.582685493028668460f, + 0.812250586585203880f, -0.583308652937698290f, 0.811802955582515470f, + -0.583931469701276180f, + 0.811354847017063730f, -0.584553942953015330f, 0.810906261152459670f, + -0.585176072326730410f, + 0.810457198252594770f, -0.585797857456438860f, 0.810007658581641140f, + -0.586419297976360500f, + 0.809557642404051260f, -0.587040393520917970f, 0.809107149984558240f, + -0.587661143724736660f, + 0.808656181588174980f, -0.588281548222645220f, 0.808204737480194720f, + -0.588901606649675720f, + 0.807752817926190360f, -0.589521318641063940f, 0.807300423192014450f, + -0.590140683832248820f, + 0.806847553543799330f, -0.590759701858874160f, 0.806394209247956240f, + -0.591378372356787580f, + 0.805940390571176280f, -0.591996694962040990f, 0.805486097780429230f, + -0.592614669310891130f, + 0.805031331142963660f, -0.593232295039799800f, 0.804576090926307110f, + -0.593849571785433630f, + 0.804120377398265810f, -0.594466499184664430f, 0.803664190826924090f, + -0.595083076874569960f, + 0.803207531480644940f, -0.595699304492433360f, 0.802750399628069160f, + -0.596315181675743710f, + 0.802292795538115720f, -0.596930708062196500f, 0.801834719479981310f, + -0.597545883289693160f, + 0.801376171723140240f, -0.598160706996342270f, 0.800917152537344300f, + -0.598775178820458720f, + 0.800457662192622820f, -0.599389298400564540f, 0.799997700959281910f, + -0.600003065375388940f, + 0.799537269107905010f, -0.600616479383868970f, 0.799076366909352350f, + -0.601229540065148500f, + 0.798614994634760820f, -0.601842247058580030f, 0.798153152555543750f, + -0.602454600003723750f, + 0.797690840943391160f, -0.603066598540348160f, 0.797228060070268810f, + -0.603678242308430370f, + 0.796764810208418830f, -0.604289530948155960f, 0.796301091630359110f, + -0.604900464099919820f, + 0.795836904608883570f, -0.605511041404325550f, 0.795372249417061310f, + -0.606121262502186120f, + 0.794907126328237010f, -0.606731127034524480f, 0.794441535616030590f, + -0.607340634642572930f, + 0.793975477554337170f, -0.607949784967773630f, 0.793508952417326660f, + -0.608558577651779450f, + 0.793041960479443640f, -0.609167012336453210f, 0.792574502015407690f, + -0.609775088663868430f, + 0.792106577300212390f, -0.610382806276309480f, 0.791638186609125880f, + -0.610990164816271660f, + 0.791169330217690200f, -0.611597163926461910f, 0.790700008401721610f, + -0.612203803249797950f, + 0.790230221437310030f, -0.612810082429409710f, 0.789759969600819070f, + -0.613416001108638590f, + 0.789289253168885650f, -0.614021558931038380f, 0.788818072418420280f, + -0.614626755540375050f, + 0.788346427626606340f, -0.615231590580626820f, 0.787874319070900220f, + -0.615836063695985090f, + 0.787401747029031430f, -0.616440174530853650f, 0.786928711779001810f, + -0.617043922729849760f, + 0.786455213599085770f, -0.617647307937803870f, 0.785981252767830150f, + -0.618250329799760250f, + 0.785506829564053930f, -0.618852987960976320f, 0.785031944266848080f, + -0.619455282066924020f, + 0.784556597155575240f, -0.620057211763289100f, 0.784080788509869950f, + -0.620658776695972140f, + 0.783604518609638200f, -0.621259976511087550f, 0.783127787735057310f, + -0.621860810854965360f, + 0.782650596166575730f, -0.622461279374149970f, 0.782172944184913010f, + -0.623061381715401260f, + 0.781694832071059390f, -0.623661117525694530f, 0.781216260106276090f, + -0.624260486452220650f, + 0.780737228572094490f, -0.624859488142386340f, 0.780257737750316590f, + -0.625458122243814360f, + 0.779777787923014550f, -0.626056388404343520f, 0.779297379372530300f, + -0.626654286272029350f, + 0.778816512381475980f, -0.627251815495144080f, 0.778335187232733210f, + -0.627848975722176460f, + 0.777853404209453150f, -0.628445766601832710f, 0.777371163595056310f, + -0.629042187783036000f, + 0.776888465673232440f, -0.629638238914926980f, 0.776405310727940390f, + -0.630233919646864370f, + 0.775921699043407690f, -0.630829229628424470f, 0.775437630904130540f, + -0.631424168509401860f, + 0.774953106594873930f, -0.632018735939809060f, 0.774468126400670860f, + -0.632612931569877410f, + 0.773982690606822900f, -0.633206755050057190f, 0.773496799498899050f, + -0.633800206031017280f, + 0.773010453362736990f, -0.634393284163645490f, 0.772523652484441330f, + -0.634985989099049460f, + 0.772036397150384520f, -0.635578320488556110f, 0.771548687647206300f, + -0.636170277983712170f, + 0.771060524261813820f, -0.636761861236284200f, 0.770571907281380810f, + -0.637353069898259130f, + 0.770082836993347900f, -0.637943903621844060f, 0.769593313685422940f, + -0.638534362059466790f, + 0.769103337645579700f, -0.639124444863775730f, 0.768612909162058380f, + -0.639714151687640450f, + 0.768122028523365420f, -0.640303482184151670f, 0.767630696018273380f, + -0.640892436006621380f, + 0.767138911935820400f, -0.641481012808583160f, 0.766646676565310380f, + -0.642069212243792540f, + 0.766153990196312920f, -0.642657033966226860f, 0.765660853118662500f, + -0.643244477630085850f, + 0.765167265622458960f, -0.643831542889791390f, 0.764673227998067140f, + -0.644418229399988380f, + 0.764178740536116670f, -0.645004536815543930f, 0.763683803527501870f, + -0.645590464791548690f, + 0.763188417263381270f, -0.646176012983316280f, 0.762692582035177980f, + -0.646761181046383920f, + 0.762196298134578900f, -0.647345968636512060f, 0.761699565853535380f, + -0.647930375409685340f, + 0.761202385484261780f, -0.648514401022112440f, 0.760704757319236920f, + -0.649098045130225950f, + 0.760206681651202420f, -0.649681307390683190f, 0.759708158773163440f, + -0.650264187460365850f, + 0.759209188978388070f, -0.650846684996380880f, 0.758709772560407390f, + -0.651428799656059820f, + 0.758209909813015280f, -0.652010531096959500f, 0.757709601030268080f, + -0.652591878976862440f, + 0.757208846506484570f, -0.653172842953776760f, 0.756707646536245670f, + -0.653753422685936060f, + 0.756206001414394540f, -0.654333617831800440f, 0.755703911436035880f, + -0.654913428050056030f, + 0.755201376896536550f, -0.655492852999615350f, 0.754698398091524500f, + -0.656071892339617600f, + 0.754194975316889170f, -0.656650545729428940f, 0.753691108868781210f, + -0.657228812828642540f, + 0.753186799043612520f, -0.657806693297078640f, 0.752682046138055340f, + -0.658384186794785050f, + 0.752176850449042810f, -0.658961292982037320f, 0.751671212273768430f, + -0.659538011519338660f, + 0.751165131909686480f, -0.660114342067420480f, 0.750658609654510700f, + -0.660690284287242300f, + 0.750151645806215070f, -0.661265837839992270f, 0.749644240663033480f, + -0.661841002387086870f, + 0.749136394523459370f, -0.662415777590171780f, 0.748628107686245440f, + -0.662990163111121470f, + 0.748119380450403600f, -0.663564158612039770f, 0.747610213115205150f, + -0.664137763755260010f, + 0.747100605980180130f, -0.664710978203344790f, 0.746590559345117310f, + -0.665283801619087180f, + 0.746080073510063780f, -0.665856233665509720f, 0.745569148775325430f, + -0.666428274005865240f, + 0.745057785441466060f, -0.666999922303637470f, 0.744545983809307370f, + -0.667571178222540310f, + 0.744033744179929290f, -0.668142041426518450f, 0.743521066854669120f, + -0.668712511579747980f, + 0.743007952135121720f, -0.669282588346636010f, 0.742494400323139180f, + -0.669852271391821020f, + 0.741980411720831070f, -0.670421560380173090f, 0.741465986630563290f, + -0.670990454976794220f, + 0.740951125354959110f, -0.671558954847018330f, 0.740435828196898020f, + -0.672127059656411730f, + 0.739920095459516200f, -0.672694769070772860f, 0.739403927446205760f, + -0.673262082756132970f, + 0.738887324460615110f, -0.673829000378756040f, 0.738370286806648620f, + -0.674395521605139050f, + 0.737852814788465980f, -0.674961646102011930f, 0.737334908710482910f, + -0.675527373536338520f, + 0.736816568877369900f, -0.676092703575315920f, 0.736297795594053170f, + -0.676657635886374950f, + 0.735778589165713590f, -0.677222170137180330f, 0.735258949897786840f, + -0.677786305995631500f, + 0.734738878095963500f, -0.678350043129861470f, 0.734218374066188280f, + -0.678913381208238410f, + 0.733697438114660370f, -0.679476319899364970f, 0.733176070547832740f, + -0.680038858872078930f, + 0.732654271672412820f, -0.680600997795453020f, 0.732132041795361290f, + -0.681162736338795430f, + 0.731609381223892630f, -0.681724074171649710f, 0.731086290265474340f, + -0.682285010963795570f, + 0.730562769227827590f, -0.682845546385248080f, 0.730038818418926260f, + -0.683405680106258680f, + 0.729514438146997010f, -0.683965411797315400f, 0.728989628720519420f, + -0.684524741129142300f, + 0.728464390448225200f, -0.685083667772700360f, 0.727938723639098620f, + -0.685642191399187470f, + 0.727412628602375770f, -0.686200311680038590f, 0.726886105647544970f, + -0.686758028286925890f, + 0.726359155084346010f, -0.687315340891759050f, 0.725831777222770370f, + -0.687872249166685550f, + 0.725303972373060770f, -0.688428752784090440f, 0.724775740845711280f, + -0.688984851416597040f, + 0.724247082951467000f, -0.689540544737066830f, 0.723717999001323500f, + -0.690095832418599950f, + 0.723188489306527460f, -0.690650714134534600f, 0.722658554178575610f, + -0.691205189558448450f, + 0.722128193929215350f, -0.691759258364157750f, 0.721597408870443770f, + -0.692312920225718220f, + 0.721066199314508110f, -0.692866174817424630f, 0.720534565573905270f, + -0.693419021813811760f, + 0.720002507961381650f, -0.693971460889654000f, 0.719470026789932990f, + -0.694523491719965520f, + 0.718937122372804490f, -0.695075113980000880f, 0.718403795023489830f, + -0.695626327345254870f, + 0.717870045055731710f, -0.696177131491462990f, 0.717335872783521730f, + -0.696727526094601200f, + 0.716801278521099540f, -0.697277510830886520f, 0.716266262582953120f, + -0.697827085376777290f, + 0.715730825283818590f, -0.698376249408972920f, 0.715194966938680120f, + -0.698925002604414150f, + 0.714658687862769090f, -0.699473344640283770f, 0.714121988371564820f, + -0.700021275194006250f, + 0.713584868780793640f, -0.700568793943248340f, 0.713047329406429340f, + -0.701115900565918660f, + 0.712509370564692320f, -0.701662594740168450f, 0.711970992572050100f, + -0.702208876144391870f, + 0.711432195745216430f, -0.702754744457225300f, 0.710892980401151680f, + -0.703300199357548730f, + 0.710353346857062420f, -0.703845240524484940f, 0.709813295430400840f, + -0.704389867637400410f, + 0.709272826438865690f, -0.704934080375904880f, 0.708731940200400650f, + -0.705477878419852100f, + 0.708190637033195400f, -0.706021261449339740f, 0.707648917255684350f, + -0.706564229144709510f, + 0.707106781186547570f, -0.707106781186547460f, 0.706564229144709620f, + -0.707648917255684350f, + 0.706021261449339740f, -0.708190637033195290f, 0.705477878419852210f, + -0.708731940200400650f, + 0.704934080375904990f, -0.709272826438865580f, 0.704389867637400410f, + -0.709813295430400840f, + 0.703845240524484940f, -0.710353346857062310f, 0.703300199357548730f, + -0.710892980401151680f, + 0.702754744457225300f, -0.711432195745216430f, 0.702208876144391870f, + -0.711970992572049990f, + 0.701662594740168570f, -0.712509370564692320f, 0.701115900565918660f, + -0.713047329406429230f, + 0.700568793943248450f, -0.713584868780793520f, 0.700021275194006360f, + -0.714121988371564710f, + 0.699473344640283770f, -0.714658687862768980f, 0.698925002604414150f, + -0.715194966938680010f, + 0.698376249408972920f, -0.715730825283818590f, 0.697827085376777290f, + -0.716266262582953120f, + 0.697277510830886630f, -0.716801278521099540f, 0.696727526094601200f, + -0.717335872783521730f, + 0.696177131491462990f, -0.717870045055731710f, 0.695626327345254870f, + -0.718403795023489720f, + 0.695075113980000880f, -0.718937122372804380f, 0.694523491719965520f, + -0.719470026789932990f, + 0.693971460889654000f, -0.720002507961381650f, 0.693419021813811880f, + -0.720534565573905270f, + 0.692866174817424740f, -0.721066199314508110f, 0.692312920225718220f, + -0.721597408870443660f, + 0.691759258364157750f, -0.722128193929215350f, 0.691205189558448450f, + -0.722658554178575610f, + 0.690650714134534720f, -0.723188489306527350f, 0.690095832418599950f, + -0.723717999001323390f, + 0.689540544737066940f, -0.724247082951466890f, 0.688984851416597150f, + -0.724775740845711280f, + 0.688428752784090550f, -0.725303972373060660f, 0.687872249166685550f, + -0.725831777222770370f, + 0.687315340891759160f, -0.726359155084346010f, 0.686758028286925890f, + -0.726886105647544970f, + 0.686200311680038700f, -0.727412628602375770f, 0.685642191399187470f, + -0.727938723639098620f, + 0.685083667772700360f, -0.728464390448225200f, 0.684524741129142300f, + -0.728989628720519310f, + 0.683965411797315510f, -0.729514438146996900f, 0.683405680106258790f, + -0.730038818418926150f, + 0.682845546385248080f, -0.730562769227827590f, 0.682285010963795570f, + -0.731086290265474230f, + 0.681724074171649820f, -0.731609381223892520f, 0.681162736338795430f, + -0.732132041795361290f, + 0.680600997795453130f, -0.732654271672412820f, 0.680038858872079040f, + -0.733176070547832740f, + 0.679476319899365080f, -0.733697438114660260f, 0.678913381208238410f, + -0.734218374066188170f, + 0.678350043129861580f, -0.734738878095963390f, 0.677786305995631500f, + -0.735258949897786730f, + 0.677222170137180450f, -0.735778589165713480f, 0.676657635886374950f, + -0.736297795594053060f, + 0.676092703575316030f, -0.736816568877369790f, 0.675527373536338630f, + -0.737334908710482790f, + 0.674961646102012040f, -0.737852814788465980f, 0.674395521605139050f, + -0.738370286806648510f, + 0.673829000378756150f, -0.738887324460615110f, 0.673262082756132970f, + -0.739403927446205760f, + 0.672694769070772970f, -0.739920095459516090f, 0.672127059656411840f, + -0.740435828196898020f, + 0.671558954847018330f, -0.740951125354959110f, 0.670990454976794220f, + -0.741465986630563290f, + 0.670421560380173090f, -0.741980411720830960f, 0.669852271391821130f, + -0.742494400323139180f, + 0.669282588346636010f, -0.743007952135121720f, 0.668712511579748090f, + -0.743521066854669120f, + 0.668142041426518560f, -0.744033744179929180f, 0.667571178222540310f, + -0.744545983809307250f, + 0.666999922303637470f, -0.745057785441465950f, 0.666428274005865350f, + -0.745569148775325430f, + 0.665856233665509720f, -0.746080073510063780f, 0.665283801619087180f, + -0.746590559345117310f, + 0.664710978203344900f, -0.747100605980180130f, 0.664137763755260010f, + -0.747610213115205150f, + 0.663564158612039880f, -0.748119380450403490f, 0.662990163111121470f, + -0.748628107686245330f, + 0.662415777590171780f, -0.749136394523459260f, 0.661841002387086870f, + -0.749644240663033480f, + 0.661265837839992270f, -0.750151645806214960f, 0.660690284287242300f, + -0.750658609654510590f, + 0.660114342067420480f, -0.751165131909686370f, 0.659538011519338770f, + -0.751671212273768430f, + 0.658961292982037320f, -0.752176850449042700f, 0.658384186794785050f, + -0.752682046138055230f, + 0.657806693297078640f, -0.753186799043612410f, 0.657228812828642650f, + -0.753691108868781210f, + 0.656650545729429050f, -0.754194975316889170f, 0.656071892339617710f, + -0.754698398091524390f, + 0.655492852999615460f, -0.755201376896536550f, 0.654913428050056150f, + -0.755703911436035880f, + 0.654333617831800550f, -0.756206001414394540f, 0.653753422685936170f, + -0.756707646536245670f, + 0.653172842953776760f, -0.757208846506484460f, 0.652591878976862550f, + -0.757709601030268080f, + 0.652010531096959500f, -0.758209909813015280f, 0.651428799656059820f, + -0.758709772560407390f, + 0.650846684996380990f, -0.759209188978387960f, 0.650264187460365960f, + -0.759708158773163440f, + 0.649681307390683190f, -0.760206681651202420f, 0.649098045130226060f, + -0.760704757319236920f, + 0.648514401022112550f, -0.761202385484261780f, 0.647930375409685460f, + -0.761699565853535270f, + 0.647345968636512060f, -0.762196298134578900f, 0.646761181046383920f, + -0.762692582035177870f, + 0.646176012983316390f, -0.763188417263381270f, 0.645590464791548800f, + -0.763683803527501870f, + 0.645004536815544040f, -0.764178740536116670f, 0.644418229399988380f, + -0.764673227998067140f, + 0.643831542889791500f, -0.765167265622458960f, 0.643244477630085850f, + -0.765660853118662390f, + 0.642657033966226860f, -0.766153990196312810f, 0.642069212243792540f, + -0.766646676565310380f, + 0.641481012808583160f, -0.767138911935820400f, 0.640892436006621380f, + -0.767630696018273270f, + 0.640303482184151670f, -0.768122028523365310f, 0.639714151687640450f, + -0.768612909162058270f, + 0.639124444863775730f, -0.769103337645579590f, 0.638534362059466790f, + -0.769593313685422940f, + 0.637943903621844170f, -0.770082836993347900f, 0.637353069898259130f, + -0.770571907281380700f, + 0.636761861236284200f, -0.771060524261813710f, 0.636170277983712170f, + -0.771548687647206300f, + 0.635578320488556230f, -0.772036397150384410f, 0.634985989099049460f, + -0.772523652484441330f, + 0.634393284163645490f, -0.773010453362736990f, 0.633800206031017280f, + -0.773496799498899050f, + 0.633206755050057190f, -0.773982690606822790f, 0.632612931569877520f, + -0.774468126400670860f, + 0.632018735939809060f, -0.774953106594873820f, 0.631424168509401860f, + -0.775437630904130430f, + 0.630829229628424470f, -0.775921699043407580f, 0.630233919646864480f, + -0.776405310727940390f, + 0.629638238914927100f, -0.776888465673232440f, 0.629042187783036000f, + -0.777371163595056200f, + 0.628445766601832710f, -0.777853404209453040f, 0.627848975722176570f, + -0.778335187232733090f, + 0.627251815495144190f, -0.778816512381475870f, 0.626654286272029460f, + -0.779297379372530300f, + 0.626056388404343520f, -0.779777787923014440f, 0.625458122243814360f, + -0.780257737750316590f, + 0.624859488142386450f, -0.780737228572094380f, 0.624260486452220650f, + -0.781216260106276090f, + 0.623661117525694640f, -0.781694832071059390f, 0.623061381715401370f, + -0.782172944184912900f, + 0.622461279374150080f, -0.782650596166575730f, 0.621860810854965360f, + -0.783127787735057310f, + 0.621259976511087660f, -0.783604518609638200f, 0.620658776695972140f, + -0.784080788509869950f, + 0.620057211763289210f, -0.784556597155575240f, 0.619455282066924020f, + -0.785031944266848080f, + 0.618852987960976320f, -0.785506829564053930f, 0.618250329799760250f, + -0.785981252767830150f, + 0.617647307937803980f, -0.786455213599085770f, 0.617043922729849760f, + -0.786928711779001700f, + 0.616440174530853650f, -0.787401747029031320f, 0.615836063695985090f, + -0.787874319070900110f, + 0.615231590580626820f, -0.788346427626606230f, 0.614626755540375050f, + -0.788818072418420170f, + 0.614021558931038490f, -0.789289253168885650f, 0.613416001108638590f, + -0.789759969600819070f, + 0.612810082429409710f, -0.790230221437310030f, 0.612203803249798060f, + -0.790700008401721610f, + 0.611597163926462020f, -0.791169330217690090f, 0.610990164816271770f, + -0.791638186609125770f, + 0.610382806276309480f, -0.792106577300212390f, 0.609775088663868430f, + -0.792574502015407580f, + 0.609167012336453210f, -0.793041960479443640f, 0.608558577651779450f, + -0.793508952417326660f, + 0.607949784967773740f, -0.793975477554337170f, 0.607340634642572930f, + -0.794441535616030590f, + 0.606731127034524480f, -0.794907126328237010f, 0.606121262502186230f, + -0.795372249417061190f, + 0.605511041404325550f, -0.795836904608883460f, 0.604900464099919930f, + -0.796301091630359110f, + 0.604289530948156070f, -0.796764810208418720f, 0.603678242308430370f, + -0.797228060070268700f, + 0.603066598540348280f, -0.797690840943391040f, 0.602454600003723860f, + -0.798153152555543750f, + 0.601842247058580030f, -0.798614994634760820f, 0.601229540065148620f, + -0.799076366909352350f, + 0.600616479383868970f, -0.799537269107905010f, 0.600003065375389060f, + -0.799997700959281910f, + 0.599389298400564540f, -0.800457662192622710f, 0.598775178820458720f, + -0.800917152537344300f, + 0.598160706996342380f, -0.801376171723140130f, 0.597545883289693270f, + -0.801834719479981310f, + 0.596930708062196500f, -0.802292795538115720f, 0.596315181675743820f, + -0.802750399628069160f, + 0.595699304492433470f, -0.803207531480644830f, 0.595083076874569960f, + -0.803664190826924090f, + 0.594466499184664540f, -0.804120377398265700f, 0.593849571785433630f, + -0.804576090926307000f, + 0.593232295039799800f, -0.805031331142963660f, 0.592614669310891130f, + -0.805486097780429120f, + 0.591996694962040990f, -0.805940390571176280f, 0.591378372356787580f, + -0.806394209247956240f, + 0.590759701858874280f, -0.806847553543799220f, 0.590140683832248940f, + -0.807300423192014450f, + 0.589521318641063940f, -0.807752817926190360f, 0.588901606649675840f, + -0.808204737480194720f, + 0.588281548222645330f, -0.808656181588174980f, 0.587661143724736770f, + -0.809107149984558130f, + 0.587040393520918080f, -0.809557642404051260f, 0.586419297976360500f, + -0.810007658581641140f, + 0.585797857456438860f, -0.810457198252594770f, 0.585176072326730410f, + -0.810906261152459670f, + 0.584553942953015330f, -0.811354847017063730f, 0.583931469701276300f, + -0.811802955582515360f, + 0.583308652937698290f, -0.812250586585203880f, 0.582685493028668460f, + -0.812697739761799490f, + 0.582061990340775550f, -0.813144414849253590f, 0.581438145240810280f, + -0.813590611584798510f, + 0.580813958095764530f, -0.814036329705948300f, 0.580189429272831680f, + -0.814481568950498610f, + 0.579564559139405740f, -0.814926329056526620f, 0.578939348063081890f, + -0.815370609762391290f, + 0.578313796411655590f, -0.815814410806733780f, 0.577687904553122800f, + -0.816257731928477390f, + 0.577061672855679550f, -0.816700572866827850f, 0.576435101687721830f, + -0.817142933361272970f, + 0.575808191417845340f, -0.817584813151583710f, 0.575180942414845190f, + -0.818026211977813440f, + 0.574553355047715760f, -0.818467129580298660f, 0.573925429685650750f, + -0.818907565699658950f, + 0.573297166698042320f, -0.819347520076796900f, 0.572668566454481160f, + -0.819786992452898990f, + 0.572039629324757050f, -0.820225982569434690f, 0.571410355678857340f, + -0.820664490168157460f, + 0.570780745886967370f, -0.821102514991104650f, 0.570150800319470300f, + -0.821540056780597610f, + 0.569520519346947250f, -0.821977115279241550f, 0.568889903340175970f, + -0.822413690229926390f, + 0.568258952670131490f, -0.822849781375826320f, 0.567627667707986230f, + -0.823285388460400110f, + 0.566996048825108680f, -0.823720511227391320f, 0.566364096393063950f, + -0.824155149420828570f, + 0.565731810783613230f, -0.824589302785025290f, 0.565099192368714090f, + -0.825022971064580220f, + 0.564466241520519500f, -0.825456154004377440f, 0.563832958611378170f, + -0.825888851349586780f, + 0.563199344013834090f, -0.826321062845663420f, 0.562565398100626560f, + -0.826752788238348520f, + 0.561931121244689470f, -0.827184027273669020f, 0.561296513819151470f, + -0.827614779697938400f, + 0.560661576197336030f, -0.828045045257755800f, 0.560026308752760380f, + -0.828474823700007130f, + 0.559390711859136140f, -0.828904114771864870f, 0.558754785890368310f, + -0.829332918220788250f, + 0.558118531220556100f, -0.829761233794523050f, 0.557481948223991660f, + -0.830189061241102370f, + 0.556845037275160100f, -0.830616400308846200f, 0.556207798748739930f, + -0.831043250746362320f, + 0.555570233019602290f, -0.831469612302545240f, 0.554932340462810370f, + -0.831895484726577590f, + 0.554294121453620110f, -0.832320867767929680f, 0.553655576367479310f, + -0.832745761176359460f, + 0.553016705580027580f, -0.833170164701913190f, 0.552377509467096070f, + -0.833594078094925140f, + 0.551737988404707450f, -0.834017501106018130f, 0.551098142769075430f, + -0.834440433486103190f, + 0.550457972936604810f, -0.834862874986380010f, 0.549817479283891020f, + -0.835284825358337370f, + 0.549176662187719770f, -0.835706284353752600f, 0.548535522025067390f, + -0.836127251724692160f, + 0.547894059173100190f, -0.836547727223511890f, 0.547252274009174090f, + -0.836967710602857020f, + 0.546610166910834860f, -0.837387201615661940f, 0.545967738255817680f, + -0.837806200015150940f, + 0.545324988422046460f, -0.838224705554837970f, 0.544681917787634530f, + -0.838642717988527300f, + 0.544038526730883930f, -0.839060237070312630f, 0.543394815630284800f, + -0.839477262554578550f, + 0.542750784864516000f, -0.839893794195999410f, 0.542106434812444030f, + -0.840309831749540770f, + 0.541461765853123560f, -0.840725374970458070f, 0.540816778365796670f, + -0.841140423614298080f, + 0.540171472729892970f, -0.841554977436898330f, 0.539525849325029010f, + -0.841969036194387680f, + 0.538879908531008420f, -0.842382599643185960f, 0.538233650727821700f, + -0.842795667540004120f, + 0.537587076295645510f, -0.843208239641845440f, 0.536940185614843020f, + -0.843620315706004040f, + 0.536292979065963180f, -0.844031895490066410f, 0.535645457029741090f, + -0.844442978751910660f, + 0.534997619887097260f, -0.844853565249707010f, 0.534349468019137520f, + -0.845263654741918220f, + 0.533701001807152960f, -0.845673246987299070f, 0.533052221632619670f, + -0.846082341744896940f, + 0.532403127877198010f, -0.846490938774052020f, 0.531753720922733320f, + -0.846899037834397350f, + 0.531104001151255000f, -0.847306638685858320f, 0.530453968944976320f, + -0.847713741088654270f, + 0.529803624686294830f, -0.848120344803297120f, 0.529152968757790720f, + -0.848526449590592650f, + 0.528502001542228480f, -0.848932055211639610f, 0.527850723422555460f, + -0.849337161427830670f, + 0.527199134781901390f, -0.849741768000852440f, 0.526547236003579330f, + -0.850145874692685210f, + 0.525895027471084740f, -0.850549481265603370f, 0.525242509568094710f, + -0.850952587482175730f, + 0.524589682678468840f, -0.851355193105265200f, 0.523936547186248600f, + -0.851757297898029120f, + 0.523283103475656430f, -0.852158901623919830f, 0.522629351931096720f, + -0.852560004046683970f, + 0.521975292937154390f, -0.852960604930363630f, 0.521320926878595550f, + -0.853360704039295430f, + 0.520666254140367270f, -0.853760301138111300f, 0.520011275107596040f, + -0.854159395991738730f, + 0.519355990165589530f, -0.854557988365400530f, 0.518700399699835170f, + -0.854956078024614820f, + 0.518044504095999340f, -0.855353664735196030f, 0.517388303739929060f, + -0.855750748263253920f, + 0.516731799017649980f, -0.856147328375194470f, 0.516074990315366630f, + -0.856543404837719960f, + 0.515417878019463150f, -0.856938977417828650f, 0.514760462516501200f, + -0.857334045882815590f, + 0.514102744193221660f, -0.857728610000272120f, 0.513444723436543570f, + -0.858122669538086020f, + 0.512786400633563070f, -0.858516224264442740f, 0.512127776171554690f, + -0.858909273947823900f, + 0.511468850437970520f, -0.859301818357008360f, 0.510809623820439040f, + -0.859693857261072610f, + 0.510150096706766700f, -0.860085390429390140f, 0.509490269484936360f, + -0.860476417631632070f, + 0.508830142543106990f, -0.860866938637767310f, 0.508169716269614710f, + -0.861256953218062060f, + 0.507508991052970870f, -0.861646461143081300f, 0.506847967281863320f, + -0.862035462183687210f, + 0.506186645345155450f, -0.862423956111040500f, 0.505525025631885510f, + -0.862811942696600330f, + 0.504863108531267480f, -0.863199421712124160f, 0.504200894432690560f, + -0.863586392929667990f, + 0.503538383725717580f, -0.863972856121586700f, 0.502875576800086880f, + -0.864358811060534030f, + 0.502212474045710900f, -0.864744257519462380f, 0.501549075852675390f, + -0.865129195271623690f, + 0.500885382611240940f, -0.865513624090568980f, 0.500221394711840680f, + -0.865897543750148820f, + 0.499557112545081890f, -0.866280954024512990f, 0.498892536501744750f, + -0.866663854688111020f, + 0.498227666972781870f, -0.867046245515692650f, 0.497562504349319090f, + -0.867428126282306920f, + 0.496897049022654640f, -0.867809496763303210f, 0.496231301384258310f, + -0.868190356734331310f, + 0.495565261825772490f, -0.868570705971340900f, 0.494898930739011310f, + -0.868950544250582380f, + 0.494232308515959730f, -0.869329871348606730f, 0.493565395548774880f, + -0.869708687042265560f, + 0.492898192229784090f, -0.870086991108711350f, 0.492230698951486080f, + -0.870464783325397670f, + 0.491562916106550060f, -0.870842063470078860f, 0.490894844087815140f, + -0.871218831320810900f, + 0.490226483288291100f, -0.871595086655951090f, 0.489557834101157550f, + -0.871970829254157700f, + 0.488888896919763230f, -0.872346058894391540f, 0.488219672137626740f, + -0.872720775355914300f, + 0.487550160148436050f, -0.873094978418290090f, 0.486880361346047400f, + -0.873468667861384880f, + 0.486210276124486530f, -0.873841843465366750f, 0.485539904877947020f, + -0.874214505010706300f, + 0.484869248000791120f, -0.874586652278176110f, 0.484198305887549140f, + -0.874958285048851540f, + 0.483527078932918740f, -0.875329403104110780f, 0.482855567531765670f, + -0.875700006225634600f, + 0.482183772079122830f, -0.876070094195406600f, 0.481511692970189920f, + -0.876439666795713610f, + 0.480839330600333900f, -0.876808723809145760f, 0.480166685365088440f, + -0.877177265018595940f, + 0.479493757660153010f, -0.877545290207261240f, 0.478820547881394050f, + -0.877912799158641730f, + 0.478147056424843120f, -0.878279791656541460f, 0.477473283686698060f, + -0.878646267485068130f, + 0.476799230063322250f, -0.879012226428633410f, 0.476124895951243630f, + -0.879377668271953180f, + 0.475450281747155870f, -0.879742592800047410f, 0.474775387847917230f, + -0.880106999798240360f, + 0.474100214650550020f, -0.880470889052160750f, 0.473424762552241530f, + -0.880834260347742040f, + 0.472749031950342900f, -0.881197113471221980f, 0.472073023242368660f, + -0.881559448209143780f, + 0.471396736825997810f, -0.881921264348354940f, 0.470720173099071710f, + -0.882282561676008600f, + 0.470043332459595620f, -0.882643339979562790f, 0.469366215305737630f, + -0.883003599046780720f, + 0.468688822035827960f, -0.883363338665731580f, 0.468011153048359830f, + -0.883722558624789660f, + 0.467333208741988530f, -0.884081258712634990f, 0.466654989515530970f, + -0.884439438718253700f, + 0.465976495767966130f, -0.884797098430937790f, 0.465297727898434650f, + -0.885154237640285110f, + 0.464618686306237820f, -0.885510856136199950f, 0.463939371390838460f, + -0.885866953708892790f, + 0.463259783551860260f, -0.886222530148880640f, 0.462579923189086810f, + -0.886577585246987040f, + 0.461899790702462840f, -0.886932118794342080f, 0.461219386492092430f, + -0.887286130582383150f, + 0.460538710958240010f, -0.887639620402853930f, 0.459857764501329650f, + -0.887992588047805560f, + 0.459176547521944150f, -0.888345033309596240f, 0.458495060420826220f, + -0.888696955980891710f, + 0.457813303598877290f, -0.889048355854664570f, 0.457131277457156980f, + -0.889399232724195520f, + 0.456448982396883860f, -0.889749586383072890f, 0.455766418819434750f, + -0.890099416625192210f, + 0.455083587126343840f, -0.890448723244757880f, 0.454400487719303750f, + -0.890797506036281490f, + 0.453717121000163930f, -0.891145764794583180f, 0.453033487370931580f, + -0.891493499314791380f, + 0.452349587233771000f, -0.891840709392342720f, 0.451665420991002540f, + -0.892187394822982480f, + 0.450980989045103810f, -0.892533555402764690f, 0.450296291798708730f, + -0.892879190928051680f, + 0.449611329654606600f, -0.893224301195515320f, 0.448926103015743260f, + -0.893568886002136020f, + 0.448240612285220000f, -0.893912945145203250f, 0.447554857866293010f, + -0.894256478422316040f, + 0.446868840162374330f, -0.894599485631382580f, 0.446182559577030120f, + -0.894941966570620750f, + 0.445496016513981740f, -0.895283921038557580f, 0.444809211377105000f, + -0.895625348834030000f, + 0.444122144570429260f, -0.895966249756185110f, 0.443434816498138430f, + -0.896306623604479660f, + 0.442747227564570130f, -0.896646470178680150f, 0.442059378174214760f, + -0.896985789278863970f, + 0.441371268731716620f, -0.897324580705418320f, 0.440682899641873020f, + -0.897662844259040750f, + 0.439994271309633260f, -0.898000579740739880f, 0.439305384140100060f, + -0.898337786951834190f, + 0.438616238538527710f, -0.898674465693953820f, 0.437926834910322860f, + -0.899010615769039070f, + 0.437237173661044200f, -0.899346236979341460f, 0.436547255196401250f, + -0.899681329127423930f, + 0.435857079922255470f, -0.900015892016160280f, 0.435166648244619370f, + -0.900349925448735600f, + 0.434475960569655710f, -0.900683429228646860f, 0.433785017303678520f, + -0.901016403159702330f, + 0.433093818853152010f, -0.901348847046022030f, 0.432402365624690140f, + -0.901680760692037730f, + 0.431710658025057370f, -0.902012143902493070f, 0.431018696461167080f, + -0.902342996482444200f, + 0.430326481340082610f, -0.902673318237258830f, 0.429634013069016500f, + -0.903003108972617040f, + 0.428941292055329550f, -0.903332368494511820f, 0.428248318706531910f, + -0.903661096609247980f, + 0.427555093430282200f, -0.903989293123443340f, 0.426861616634386490f, + -0.904316957844028320f, + 0.426167888726799620f, -0.904644090578246240f, 0.425473910115623910f, + -0.904970691133653250f, + 0.424779681209108810f, -0.905296759318118820f, 0.424085202415651670f, + -0.905622294939825160f, + 0.423390474143796100f, -0.905947297807268460f, 0.422695496802232950f, + -0.906271767729257660f, + 0.422000270799799790f, -0.906595704514915330f, 0.421304796545479700f, + -0.906919107973678030f, + 0.420609074448402510f, -0.907241977915295930f, 0.419913104917843730f, + -0.907564314149832520f, + 0.419216888363223960f, -0.907886116487666150f, 0.418520425194109700f, + -0.908207384739488700f, + 0.417823715820212380f, -0.908528118716306120f, 0.417126760651387870f, + -0.908848318229439120f, + 0.416429560097637320f, -0.909167983090522270f, 0.415732114569105420f, + -0.909487113111505430f, + 0.415034424476081630f, -0.909805708104652220f, 0.414336490228999210f, + -0.910123767882541570f, + 0.413638312238434560f, -0.910441292258067140f, 0.412939890915108020f, + -0.910758281044437570f, + 0.412241226669883000f, -0.911074734055176250f, 0.411542319913765280f, + -0.911390651104122320f, + 0.410843171057903910f, -0.911706032005429880f, 0.410143780513590350f, + -0.912020876573568230f, + 0.409444148692257590f, -0.912335184623322750f, 0.408744276005481520f, + -0.912648955969793900f, + 0.408044162864978740f, -0.912962190428398100f, 0.407343809682607970f, + -0.913274887814867760f, + 0.406643216870369140f, -0.913587047945250810f, 0.405942384840402570f, + -0.913898670635911680f, + 0.405241314004989860f, -0.914209755703530690f, 0.404540004776553110f, + -0.914520302965104450f, + 0.403838457567654130f, -0.914830312237946090f, 0.403136672790995240f, + -0.915139783339685260f, + 0.402434650859418540f, -0.915448716088267830f, 0.401732392185905010f, + -0.915757110301956720f, + 0.401029897183575790f, -0.916064965799331610f, 0.400327166265690150f, + -0.916372282399289140f, + 0.399624199845646790f, -0.916679059921042700f, 0.398920998336983020f, + -0.916985298184122890f, + 0.398217562153373620f, -0.917290997008377910f, 0.397513891708632330f, + -0.917596156213972950f, + 0.396809987416710420f, -0.917900775621390390f, 0.396105849691696320f, + -0.918204855051430900f, + 0.395401478947816300f, -0.918508394325212250f, 0.394696875599433670f, + -0.918811393264169940f, + 0.393992040061048100f, -0.919113851690057770f, 0.393286972747296570f, + -0.919415769424946960f, + 0.392581674072951530f, -0.919717146291227360f, 0.391876144452922350f, + -0.920017982111606570f, + 0.391170384302253980f, -0.920318276709110480f, 0.390464394036126650f, + -0.920618029907083860f, + 0.389758174069856410f, -0.920917241529189520f, 0.389051724818894500f, + -0.921215911399408730f, + 0.388345046698826300f, -0.921514039342041900f, 0.387638140125372680f, + -0.921811625181708120f, + 0.386931005514388690f, -0.922108668743345070f, 0.386223643281862980f, + -0.922405169852209880f, + 0.385516053843919020f, -0.922701128333878520f, 0.384808237616812930f, + -0.922996544014246250f, + 0.384100195016935040f, -0.923291416719527640f, 0.383391926460808770f, + -0.923585746276256560f, + 0.382683432365089840f, -0.923879532511286740f, 0.381974713146567220f, + -0.924172775251791200f, + 0.381265769222162490f, -0.924465474325262600f, 0.380556601008928570f, + -0.924757629559513910f, + 0.379847208924051110f, -0.925049240782677580f, 0.379137593384847430f, + -0.925340307823206200f, + 0.378427754808765620f, -0.925630830509872720f, 0.377717693613385810f, + -0.925920808671769960f, + 0.377007410216418310f, -0.926210242138311270f, 0.376296905035704790f, + -0.926499130739230510f, + 0.375586178489217330f, -0.926787474304581750f, 0.374875230995057600f, + -0.927075272664740100f, + 0.374164062971457990f, -0.927362525650401110f, 0.373452674836780410f, + -0.927649233092581180f, + 0.372741067009515810f, -0.927935394822617890f, 0.372029239908284960f, + -0.928221010672169440f, + 0.371317193951837600f, -0.928506080473215480f, 0.370604929559051670f, + -0.928790604058057020f, + 0.369892447148934270f, -0.929074581259315750f, 0.369179747140620070f, + -0.929358011909935500f, + 0.368466829953372320f, -0.929640895843181330f, 0.367753696006582090f, + -0.929923232892639560f, + 0.367040345719767240f, -0.930205022892219070f, 0.366326779512573590f, + -0.930486265676149780f, + 0.365612997804773960f, -0.930766961078983710f, 0.364899001016267380f, + -0.931047108935595170f, + 0.364184789567079840f, -0.931326709081180430f, 0.363470363877363870f, + -0.931605761351257830f, + 0.362755724367397230f, -0.931884265581668150f, 0.362040871457584350f, + -0.932162221608574320f, + 0.361325805568454340f, -0.932439629268462360f, 0.360610527120662270f, + -0.932716488398140250f, + 0.359895036534988280f, -0.932992798834738850f, 0.359179334232336560f, + -0.933268560415712050f, + 0.358463420633736540f, -0.933543772978836170f, 0.357747296160342010f, + -0.933818436362210960f, + 0.357030961233430030f, -0.934092550404258870f, 0.356314416274402360f, + -0.934366114943725900f, + 0.355597661704783960f, -0.934639129819680780f, 0.354880697946222790f, + -0.934911594871516090f, + 0.354163525420490510f, -0.935183509938947500f, 0.353446144549480870f, + -0.935454874862014620f, + 0.352728555755210730f, -0.935725689481080370f, 0.352010759459819240f, + -0.935995953636831300f, + 0.351292756085567150f, -0.936265667170278260f, 0.350574546054837570f, + -0.936534829922755500f, + 0.349856129790135030f, -0.936803441735921560f, 0.349137507714085030f, + -0.937071502451759190f, + 0.348418680249434510f, -0.937339011912574960f, 0.347699647819051490f, + -0.937605969960999990f, + 0.346980410845923680f, -0.937872376439989890f, 0.346260969753160170f, + -0.938138231192824360f, + 0.345541324963989150f, -0.938403534063108060f, 0.344821476901759290f, + -0.938668284894770170f, + 0.344101425989938980f, -0.938932483532064490f, 0.343381172652115100f, + -0.939196129819569900f, + 0.342660717311994380f, -0.939459223602189920f, 0.341940060393402300f, + -0.939721764725153340f, + 0.341219202320282410f, -0.939983753034013940f, 0.340498143516697100f, + -0.940245188374650880f, + 0.339776884406826960f, -0.940506070593268300f, 0.339055425414969640f, + -0.940766399536396070f, + 0.338333766965541290f, -0.941026175050889260f, 0.337611909483074680f, + -0.941285396983928660f, + 0.336889853392220050f, -0.941544065183020810f, 0.336167599117744690f, + -0.941802179495997650f, + 0.335445147084531660f, -0.942059739771017310f, 0.334722497717581220f, + -0.942316745856563780f, + 0.333999651442009490f, -0.942573197601446870f, 0.333276608683047980f, + -0.942829094854802710f, + 0.332553369866044220f, -0.943084437466093490f, 0.331829935416461220f, + -0.943339225285107720f, + 0.331106305759876430f, -0.943593458161960390f, 0.330382481321982950f, + -0.943847135947092690f, + 0.329658462528587550f, -0.944100258491272660f, 0.328934249805612200f, + -0.944352825645594750f, + 0.328209843579092660f, -0.944604837261480260f, 0.327485244275178060f, + -0.944856293190677210f, + 0.326760452320131790f, -0.945107193285260610f, 0.326035468140330350f, + -0.945357537397632290f, + 0.325310292162262980f, -0.945607325380521280f, 0.324584924812532150f, + -0.945856557086983910f, + 0.323859366517852960f, -0.946105232370403340f, 0.323133617705052330f, + -0.946353351084490590f, + 0.322407678801070020f, -0.946600913083283530f, 0.321681550232956640f, + -0.946847918221148000f, + 0.320955232427875210f, -0.947094366352777220f, 0.320228725813100020f, + -0.947340257333191940f, + 0.319502030816015750f, -0.947585591017741090f, 0.318775147864118480f, + -0.947830367262101010f, + 0.318048077385015060f, -0.948074585922276230f, 0.317320819806421790f, + -0.948318246854599090f, + 0.316593375556165850f, -0.948561349915730270f, 0.315865745062184070f, + -0.948803894962658380f, + 0.315137928752522440f, -0.949045881852700560f, 0.314409927055336820f, + -0.949287310443502010f, + 0.313681740398891570f, -0.949528180593036670f, 0.312953369211560200f, + -0.949768492159606680f, + 0.312224813921825050f, -0.950008245001843000f, 0.311496074958275970f, + -0.950247438978705230f, + 0.310767152749611470f, -0.950486073949481700f, 0.310038047724638000f, + -0.950724149773789610f, + 0.309308760312268780f, -0.950961666311575080f, 0.308579290941525030f, + -0.951198623423113230f, + 0.307849640041534980f, -0.951435020969008340f, 0.307119808041533100f, + -0.951670858810193860f, + 0.306389795370861080f, -0.951906136807932230f, 0.305659602458966230f, + -0.952140854823815830f, + 0.304929229735402430f, -0.952375012719765880f, 0.304198677629829270f, + -0.952608610358033240f, + 0.303467946572011370f, -0.952841647601198720f, 0.302737036991819140f, + -0.953074124312172200f, + 0.302005949319228200f, -0.953306040354193750f, 0.301274683984318000f, + -0.953537395590833280f, + 0.300543241417273400f, -0.953768189885990330f, 0.299811622048383460f, + -0.953998423103894490f, + 0.299079826308040480f, -0.954228095109105670f, 0.298347854626741570f, + -0.954457205766513490f, + 0.297615707435086310f, -0.954685754941338340f, 0.296883385163778270f, + -0.954913742499130520f, + 0.296150888243623960f, -0.955141168305770670f, 0.295418217105532070f, + -0.955368032227470240f, + 0.294685372180514330f, -0.955594334130771110f, 0.293952353899684770f, + -0.955820073882545420f, + 0.293219162694258680f, -0.956045251349996410f, 0.292485798995553830f, + -0.956269866400658140f, + 0.291752263234989370f, -0.956493918902394990f, 0.291018555844085090f, + -0.956717408723403050f, + 0.290284677254462330f, -0.956940335732208940f, 0.289550627897843140f, + -0.957162699797670100f, + 0.288816408206049480f, -0.957384500788975860f, 0.288082018611004300f, + -0.957605738575646240f, + 0.287347459544729570f, -0.957826413027532910f, 0.286612731439347790f, + -0.958046524014818600f, + 0.285877834727080730f, -0.958266071408017670f, 0.285142769840248720f, + -0.958485055077976100f, + 0.284407537211271820f, -0.958703474895871600f, 0.283672137272668550f, + -0.958921330733213060f, + 0.282936570457055390f, -0.959138622461841890f, 0.282200837197147500f, + -0.959355349953930790f, + 0.281464937925758050f, -0.959571513081984520f, 0.280728873075797190f, + -0.959787111718839900f, + 0.279992643080273380f, -0.960002145737665850f, 0.279256248372291240f, + -0.960216615011963430f, + 0.278519689385053060f, -0.960430519415565790f, 0.277782966551857800f, + -0.960643858822638470f, + 0.277046080306099950f, -0.960856633107679660f, 0.276309031081271030f, + -0.961068842145519350f, + 0.275571819310958250f, -0.961280485811320640f, 0.274834445428843940f, + -0.961491563980579000f, + 0.274096909868706330f, -0.961702076529122540f, 0.273359213064418790f, + -0.961912023333112100f, + 0.272621355449948980f, -0.962121404269041580f, 0.271883337459359890f, + -0.962330219213737400f, + 0.271145159526808070f, -0.962538468044359160f, 0.270406822086544820f, + -0.962746150638399410f, + 0.269668325572915200f, -0.962953266873683880f, 0.268929670420357310f, + -0.963159816628371360f, + 0.268190857063403180f, -0.963365799780954050f, 0.267451885936677740f, + -0.963571216210257210f, + 0.266712757474898420f, -0.963776065795439840f, 0.265973472112875530f, + -0.963980348415994110f, + 0.265234030285511900f, -0.964184063951745720f, 0.264494432427801630f, + -0.964387212282854290f, + 0.263754678974831510f, -0.964589793289812650f, 0.263014770361779060f, + -0.964791806853447900f, + 0.262274707023913590f, -0.964993252854920320f, 0.261534489396595630f, + -0.965194131175724720f, + 0.260794117915275570f, -0.965394441697689400f, 0.260053593015495130f, + -0.965594184302976830f, + 0.259312915132886350f, -0.965793358874083570f, 0.258572084703170390f, + -0.965991965293840570f, + 0.257831102162158930f, -0.966190003445412620f, 0.257089967945753230f, + -0.966387473212298790f, + 0.256348682489942910f, -0.966584374478333120f, 0.255607246230807550f, + -0.966780707127683270f, + 0.254865659604514630f, -0.966976471044852070f, 0.254123923047320620f, + -0.967171666114676640f, + 0.253382036995570270f, -0.967366292222328510f, 0.252640001885695580f, + -0.967560349253314360f, + 0.251897818154216910f, -0.967753837093475510f, 0.251155486237742030f, + -0.967946755628987800f, + 0.250413006572965280f, -0.968139104746362330f, 0.249670379596668520f, + -0.968330884332445300f, + 0.248927605745720260f, -0.968522094274417270f, 0.248184685457074780f, + -0.968712734459794780f, + 0.247441619167773440f, -0.968902804776428870f, 0.246698407314942500f, + -0.969092305112506100f, + 0.245955050335794590f, -0.969281235356548530f, 0.245211548667627680f, + -0.969469595397412950f, + 0.244467902747824210f, -0.969657385124292450f, 0.243724113013852130f, + -0.969844604426714830f, + 0.242980179903263980f, -0.970031253194543970f, 0.242236103853696070f, + -0.970217331317979160f, + 0.241491885302869300f, -0.970402838687555500f, 0.240747524688588540f, + -0.970587775194143630f, + 0.240003022448741500f, -0.970772140728950350f, 0.239258379021300120f, + -0.970955935183517970f, + 0.238513594844318500f, -0.971139158449725090f, 0.237768670355934210f, + -0.971321810419786160f, + 0.237023605994367340f, -0.971503890986251780f, 0.236278402197919620f, + -0.971685400042008540f, + 0.235533059404975460f, -0.971866337480279400f, 0.234787578054001080f, + -0.972046703194623500f, + 0.234041958583543460f, -0.972226497078936270f, 0.233296201432231560f, + -0.972405719027449770f, + 0.232550307038775330f, -0.972584368934732210f, 0.231804275841964780f, + -0.972762446695688570f, + 0.231058108280671280f, -0.972939952205560070f, 0.230311804793845530f, + -0.973116885359925130f, + 0.229565365820518870f, -0.973293246054698250f, 0.228818791799802360f, + -0.973469034186130950f, + 0.228072083170885790f, -0.973644249650811870f, 0.227325240373038830f, + -0.973818892345666100f, + 0.226578263845610110f, -0.973992962167955830f, 0.225831154028026200f, + -0.974166459015280320f, + 0.225083911359792780f, -0.974339382785575860f, 0.224336536280493690f, + -0.974511733377115720f, + 0.223589029229790020f, -0.974683510688510670f, 0.222841390647421280f, + -0.974854714618708430f, + 0.222093620973203590f, -0.975025345066994120f, 0.221345720647030810f, + -0.975195401932990370f, + 0.220597690108873650f, -0.975364885116656870f, 0.219849529798778750f, + -0.975533794518291360f, + 0.219101240156869770f, -0.975702130038528570f, 0.218352821623346430f, + -0.975869891578341030f, + 0.217604274638483670f, -0.976037079039039020f, 0.216855599642632570f, + -0.976203692322270560f, + 0.216106797076219600f, -0.976369731330021140f, 0.215357867379745550f, + -0.976535195964614470f, + 0.214608810993786920f, -0.976700086128711840f, 0.213859628358993830f, + -0.976864401725312640f, + 0.213110319916091360f, -0.977028142657754390f, 0.212360886105878580f, + -0.977191308829712280f, + 0.211611327369227610f, -0.977353900145199960f, 0.210861644147084830f, + -0.977515916508569280f, + 0.210111836880469720f, -0.977677357824509930f, 0.209361906010474190f, + -0.977838223998050430f, + 0.208611851978263460f, -0.977998514934557140f, 0.207861675225075150f, + -0.978158230539735050f, + 0.207111376192218560f, -0.978317370719627650f, 0.206360955321075680f, + -0.978475935380616830f, + 0.205610413053099320f, -0.978633924429423100f, 0.204859749829814420f, + -0.978791337773105670f, + 0.204108966092817010f, -0.978948175319062200f, 0.203358062283773370f, + -0.979104436975029250f, + 0.202607038844421110f, -0.979260122649082020f, 0.201855896216568160f, + -0.979415232249634780f, + 0.201104634842091960f, -0.979569765685440520f, 0.200353255162940420f, + -0.979723722865591170f, + 0.199601757621131050f, -0.979877103699517640f, 0.198850142658750120f, + -0.980029908096989980f, + 0.198098410717953730f, -0.980182135968117320f, 0.197346562240966000f, + -0.980333787223347960f, + 0.196594597670080220f, -0.980484861773469380f, 0.195842517447657990f, + -0.980635359529608120f, + 0.195090322016128330f, -0.980785280403230430f, 0.194338011817988600f, + -0.980934624306141640f, + 0.193585587295803750f, -0.981083391150486590f, 0.192833048892205290f, + -0.981231580848749730f, + 0.192080397049892380f, -0.981379193313754560f, 0.191327632211630990f, + -0.981526228458664660f, + 0.190574754820252800f, -0.981672686196983110f, 0.189821765318656580f, + -0.981818566442552500f, + 0.189068664149806280f, -0.981963869109555240f, 0.188315451756732120f, + -0.982108594112513610f, + 0.187562128582529740f, -0.982252741366289370f, 0.186808695070359330f, + -0.982396310786084690f, + 0.186055151663446630f, -0.982539302287441240f, 0.185301498805082040f, + -0.982681715786240860f, + 0.184547736938619640f, -0.982823551198705240f, 0.183793866507478390f, + -0.982964808441396440f, + 0.183039887955141060f, -0.983105487431216290f, 0.182285801725153320f, + -0.983245588085407070f, + 0.181531608261125130f, -0.983385110321551180f, 0.180777308006728670f, + -0.983524054057571260f, + 0.180022901405699510f, -0.983662419211730250f, 0.179268388901835880f, + -0.983800205702631490f, + 0.178513770938997590f, -0.983937413449218920f, 0.177759047961107140f, + -0.984074042370776450f, + 0.177004220412148860f, -0.984210092386929030f, 0.176249288736167940f, + -0.984345563417641900f, + 0.175494253377271400f, -0.984480455383220930f, 0.174739114779627310f, + -0.984614768204312600f, + 0.173983873387463850f, -0.984748501801904210f, 0.173228529645070490f, + -0.984881656097323700f, + 0.172473083996796030f, -0.985014231012239840f, 0.171717536887049970f, + -0.985146226468662230f, + 0.170961888760301360f, -0.985277642388941220f, 0.170206140061078120f, + -0.985408478695768420f, + 0.169450291233967930f, -0.985538735312176060f, 0.168694342723617440f, + -0.985668412161537550f, + 0.167938294974731230f, -0.985797509167567370f, 0.167182148432072880f, + -0.985926026254321130f, + 0.166425903540464220f, -0.986053963346195440f, 0.165669560744784140f, + -0.986181320367928270f, + 0.164913120489970090f, -0.986308097244598670f, 0.164156583221015890f, + -0.986434293901627070f, + 0.163399949382973230f, -0.986559910264775410f, 0.162643219420950450f, + -0.986684946260146690f, + 0.161886393780111910f, -0.986809401814185420f, 0.161129472905678780f, + -0.986933276853677710f, + 0.160372457242928400f, -0.987056571305750970f, 0.159615347237193090f, + -0.987179285097874340f, + 0.158858143333861390f, -0.987301418157858430f, 0.158100845978377090f, + -0.987422970413855410f, + 0.157343455616238280f, -0.987543941794359230f, 0.156585972692998590f, + -0.987664332228205710f, + 0.155828397654265320f, -0.987784141644572180f, 0.155070730945700510f, + -0.987903369972977790f, + 0.154312973013020240f, -0.988022017143283530f, 0.153555124301993500f, + -0.988140083085692570f, + 0.152797185258443410f, -0.988257567730749460f, 0.152039156328246160f, + -0.988374471009341280f, + 0.151281037957330250f, -0.988490792852696590f, 0.150522830591677370f, + -0.988606533192386450f, + 0.149764534677321620f, -0.988721691960323780f, 0.149006150660348470f, + -0.988836269088763540f, + 0.148247678986896200f, -0.988950264510302990f, 0.147489120103153680f, + -0.989063678157881540f, + 0.146730474455361750f, -0.989176509964781010f, 0.145971742489812370f, + -0.989288759864625170f, + 0.145212924652847520f, -0.989400427791380380f, 0.144454021390860440f, + -0.989511513679355190f, + 0.143695033150294580f, -0.989622017463200780f, 0.142935960377642700f, + -0.989731939077910570f, + 0.142176803519448000f, -0.989841278458820530f, 0.141417563022303130f, + -0.989950035541608990f, + 0.140658239332849240f, -0.990058210262297120f, 0.139898832897777380f, + -0.990165802557248400f, + 0.139139344163826280f, -0.990272812363169110f, 0.138379773577783890f, + -0.990379239617108160f, + 0.137620121586486180f, -0.990485084256456980f, 0.136860388636816430f, + -0.990590346218950150f, + 0.136100575175706200f, -0.990695025442664630f, 0.135340681650134330f, + -0.990799121866020370f, + 0.134580708507126220f, -0.990902635427780010f, 0.133820656193754690f, + -0.991005566067049370f, + 0.133060525157139180f, -0.991107913723276780f, 0.132300315844444680f, + -0.991209678336254060f, + 0.131540028702883280f, -0.991310859846115440f, 0.130779664179711790f, + -0.991411458193338540f, + 0.130019222722233350f, -0.991511473318743900f, 0.129258704777796270f, + -0.991610905163495370f, + 0.128498110793793220f, -0.991709753669099530f, 0.127737441217662280f, + -0.991808018777406430f, + 0.126976696496885980f, -0.991905700430609330f, 0.126215877078990400f, + -0.992002798571244520f, + 0.125454983411546210f, -0.992099313142191800f, 0.124694015942167770f, + -0.992195244086673920f, + 0.123932975118512200f, -0.992290591348257370f, 0.123171861388280650f, + -0.992385354870851670f, + 0.122410675199216280f, -0.992479534598709970f, 0.121649416999105540f, + -0.992573130476428810f, + 0.120888087235777220f, -0.992666142448948020f, 0.120126686357101580f, + -0.992758570461551140f, + 0.119365214810991350f, -0.992850414459865100f, 0.118603673045400840f, + -0.992941674389860470f, + 0.117842061508325020f, -0.993032350197851410f, 0.117080380647800550f, + -0.993122441830495580f, + 0.116318630911904880f, -0.993211949234794500f, 0.115556812748755290f, + -0.993300872358093280f, + 0.114794926606510250f, -0.993389211148080650f, 0.114032972933367300f, + -0.993476965552789190f, + 0.113270952177564360f, -0.993564135520595300f, 0.112508864787378830f, + -0.993650721000219120f, + 0.111746711211126660f, -0.993736721940724600f, 0.110984491897163380f, + -0.993822138291519660f, + 0.110222207293883180f, -0.993906970002356060f, 0.109459857849718030f, + -0.993991217023329380f, + 0.108697444013138670f, -0.994074879304879370f, 0.107934966232653760f, + -0.994157956797789730f, + 0.107172424956808870f, -0.994240449453187900f, 0.106409820634187840f, + -0.994322357222545810f, + 0.105647153713410700f, -0.994403680057679100f, 0.104884424643134970f, + -0.994484417910747600f, + 0.104121633872054730f, -0.994564570734255420f, 0.103358781848899700f, + -0.994644138481050710f, + 0.102595869022436280f, -0.994723121104325700f, 0.101832895841466670f, + -0.994801518557617110f, + 0.101069862754827880f, -0.994879330794805620f, 0.100306770211392820f, + -0.994956557770116380f, + 0.099543618660069444f, -0.995033199438118630f, 0.098780408549799664f, + -0.995109255753726110f, + 0.098017140329560770f, -0.995184726672196820f, 0.097253814448363354f, + -0.995259612149133390f, + 0.096490431355252607f, -0.995333912140482280f, 0.095726991499307315f, + -0.995407626602534900f, + 0.094963495329639061f, -0.995480755491926940f, 0.094199943295393190f, + -0.995553298765638470f, + 0.093436335845747912f, -0.995625256380994310f, 0.092672673429913366f, + -0.995696628295663520f, + 0.091908956497132696f, -0.995767414467659820f, 0.091145185496681130f, + -0.995837614855341610f, + 0.090381360877865011f, -0.995907229417411720f, 0.089617483090022917f, + -0.995976258112917790f, + 0.088853552582524684f, -0.996044700901251970f, 0.088089569804770507f, + -0.996112557742151130f, + 0.087325535206192226f, -0.996179828595696870f, 0.086561449236251239f, + -0.996246513422315520f, + 0.085797312344439880f, -0.996312612182778000f, 0.085033124980280414f, + -0.996378124838200210f, + 0.084268887593324127f, -0.996443051350042630f, 0.083504600633152404f, + -0.996507391680110820f, + 0.082740264549375803f, -0.996571145790554840f, 0.081975879791633108f, + -0.996634313643869900f, + 0.081211446809592386f, -0.996696895202896060f, 0.080446966052950097f, + -0.996758890430818000f, + 0.079682437971430126f, -0.996820299291165670f, 0.078917863014785095f, + -0.996881121747813850f, + 0.078153241632794315f, -0.996941357764982160f, 0.077388574275265049f, + -0.997001007307235290f, + 0.076623861392031617f, -0.997060070339482960f, 0.075859103432954503f, + -0.997118546826979980f, + 0.075094300847921291f, -0.997176436735326190f, 0.074329454086845867f, + -0.997233740030466160f, + 0.073564563599667454f, -0.997290456678690210f, 0.072799629836351618f, + -0.997346586646633230f, + 0.072034653246889416f, -0.997402129901275300f, 0.071269634281296415f, + -0.997457086409941910f, + 0.070504573389614009f, -0.997511456140303450f, 0.069739471021907376f, + -0.997565239060375750f, + 0.068974327628266732f, -0.997618435138519550f, 0.068209143658806454f, + -0.997671044343441000f, + 0.067443919563664106f, -0.997723066644191640f, 0.066678655793001543f, + -0.997774502010167820f, + 0.065913352797003930f, -0.997825350411111640f, 0.065148011025878860f, + -0.997875611817110150f, + 0.064382630929857410f, -0.997925286198596000f, 0.063617212959193190f, + -0.997974373526346990f, + 0.062851757564161420f, -0.998022873771486240f, 0.062086265195060247f, + -0.998070786905482340f, + 0.061320736302208648f, -0.998118112900149180f, 0.060555171335947781f, + -0.998164851727646240f, + 0.059789570746640007f, -0.998211003360478190f, 0.059023934984667986f, + -0.998256567771495180f, + 0.058258264500435732f, -0.998301544933892890f, 0.057492559744367684f, + -0.998345934821212370f, + 0.056726821166907783f, -0.998389737407340160f, 0.055961049218520520f, + -0.998432952666508440f, + 0.055195244349690031f, -0.998475580573294770f, 0.054429407010919147f, + -0.998517621102622210f, + 0.053663537652730679f, -0.998559074229759310f, 0.052897636725665401f, + -0.998599939930320370f, + 0.052131704680283317f, -0.998640218180265270f, 0.051365741967162731f, + -0.998679908955899090f, + 0.050599749036899337f, -0.998719012233872940f, 0.049833726340107257f, + -0.998757527991183340f, + 0.049067674327418126f, -0.998795456205172410f, 0.048301593449480172f, + -0.998832796853527990f, + 0.047535484156959261f, -0.998869549914283560f, 0.046769346900537960f, + -0.998905715365818290f, + 0.046003182130914644f, -0.998941293186856870f, 0.045236990298804750f, + -0.998976283356469820f, + 0.044470771854938744f, -0.999010685854073380f, 0.043704527250063421f, + -0.999044500659429290f, + 0.042938256934940959f, -0.999077727752645360f, 0.042171961360348002f, + -0.999110367114174890f, + 0.041405640977076712f, -0.999142418724816910f, 0.040639296235933854f, + -0.999173882565716380f, + 0.039872927587739845f, -0.999204758618363890f, 0.039106535483329839f, + -0.999235046864595850f, + 0.038340120373552791f, -0.999264747286594420f, 0.037573682709270514f, + -0.999293859866887790f, + 0.036807222941358991f, -0.999322384588349540f, 0.036040741520706299f, + -0.999350321434199440f, + 0.035274238898213947f, -0.999377670388002850f, 0.034507715524795889f, + -0.999404431433671300f, + 0.033741171851377642f, -0.999430604555461730f, 0.032974608328897315f, + -0.999456189737977340f, + 0.032208025408304704f, -0.999481186966166950f, 0.031441423540560343f, + -0.999505596225325310f, + 0.030674803176636581f, -0.999529417501093140f, 0.029908164767516655f, + -0.999552650779456990f, + 0.029141508764193740f, -0.999575296046749220f, 0.028374835617672258f, + -0.999597353289648380f, + 0.027608145778965820f, -0.999618822495178640f, 0.026841439699098527f, + -0.999639703650710200f, + 0.026074717829104040f, -0.999659996743959220f, 0.025307980620024630f, + -0.999679701762987930f, + 0.024541228522912264f, -0.999698818696204250f, 0.023774461988827676f, + -0.999717347532362190f, + 0.023007681468839410f, -0.999735288260561680f, 0.022240887414024919f, + -0.999752640870248840f, + 0.021474080275469605f, -0.999769405351215280f, 0.020707260504265912f, + -0.999785581693599210f, + 0.019940428551514598f, -0.999801169887884260f, 0.019173584868322699f, + -0.999816169924900410f, + 0.018406729905804820f, -0.999830581795823400f, 0.017639864115082195f, + -0.999844405492175240f, + 0.016872987947281773f, -0.999857641005823860f, 0.016106101853537263f, + -0.999870288328982950f, + 0.015339206284988220f, -0.999882347454212560f, 0.014572301692779104f, + -0.999893818374418490f, + 0.013805388528060349f, -0.999904701082852900f, 0.013038467241987433f, + -0.999914995573113470f, + 0.012271538285719944f, -0.999924701839144500f, 0.011504602110422875f, + -0.999933819875236000f, + 0.010737659167264572f, -0.999942349676023910f, 0.009970709907418029f, + -0.999950291236490480f, + 0.009203754782059960f, -0.999957644551963900f, 0.008436794242369860f, + -0.999964409618118280f, + 0.007669828739531077f, -0.999970586430974140f, 0.006902858724729877f, + -0.999976174986897610f, + 0.006135884649154515f, -0.999981175282601110f, 0.005368906963996303f, + -0.999985587315143200f, + 0.004601926120448672f, -0.999989411081928400f, 0.003834942569706248f, + -0.999992646580707190f, + 0.003067956762966138f, -0.999995293809576190f, 0.002300969151425887f, + -0.999997352766978210f, + 0.001533980186284766f, -0.999998823451701880f, 0.000766990318742846f, + -0.999999705862882230f +}; + +/** +* \par +* cosFactor tables are generated using the formula :
cos_factors[n] = 2 * cos((2n+1)*pi/(4*N))
+* \par +* C command to generate the table +* \par +*
 for(i = 0; i< N; i++)   
+* {   
+*    cos_factors[i]= 2 * cos((2*i+1)*c/2);   
+* } 
+* \par +* where N is the number of factors to generate and c is pi/(2*N) +*/ +static const float32_t cos_factors_128[128] = { + 0.999981175282601110f, 0.999830581795823400f, 0.999529417501093140f, + 0.999077727752645360f, + 0.998475580573294770f, 0.997723066644191640f, 0.996820299291165670f, + 0.995767414467659820f, + 0.994564570734255420f, 0.993211949234794500f, 0.991709753669099530f, + 0.990058210262297120f, + 0.988257567730749460f, 0.986308097244598670f, 0.984210092386929030f, + 0.981963869109555240f, + 0.979569765685440520f, 0.977028142657754390f, 0.974339382785575860f, + 0.971503890986251780f, + 0.968522094274417380f, 0.965394441697689400f, 0.962121404269041580f, + 0.958703474895871600f, + 0.955141168305770780f, 0.951435020969008340f, 0.947585591017741090f, + 0.943593458161960390f, + 0.939459223602189920f, 0.935183509938947610f, 0.930766961078983710f, + 0.926210242138311380f, + 0.921514039342042010f, 0.916679059921042700f, 0.911706032005429880f, + 0.906595704514915330f, + 0.901348847046022030f, 0.895966249756185220f, 0.890448723244757880f, + 0.884797098430937790f, + 0.879012226428633530f, 0.873094978418290090f, 0.867046245515692650f, + 0.860866938637767310f, + 0.854557988365400530f, 0.848120344803297230f, 0.841554977436898440f, + 0.834862874986380010f, + 0.828045045257755800f, 0.821102514991104650f, 0.814036329705948410f, + 0.806847553543799330f, + 0.799537269107905010f, 0.792106577300212390f, 0.784556597155575240f, + 0.776888465673232440f, + 0.769103337645579700f, 0.761202385484261780f, 0.753186799043612520f, + 0.745057785441466060f, + 0.736816568877369900f, 0.728464390448225200f, 0.720002507961381650f, + 0.711432195745216430f, + 0.702754744457225300f, 0.693971460889654000f, 0.685083667772700360f, + 0.676092703575316030f, + 0.666999922303637470f, 0.657806693297078640f, 0.648514401022112550f, + 0.639124444863775730f, + 0.629638238914927100f, 0.620057211763289210f, 0.610382806276309480f, + 0.600616479383868970f, + 0.590759701858874280f, 0.580813958095764530f, 0.570780745886967370f, + 0.560661576197336030f, + 0.550457972936604810f, 0.540171472729892970f, 0.529803624686294830f, + 0.519355990165589530f, + 0.508830142543106990f, 0.498227666972781870f, 0.487550160148436050f, + 0.476799230063322250f, + 0.465976495767966130f, 0.455083587126343840f, 0.444122144570429260f, + 0.433093818853152010f, + 0.422000270799799790f, 0.410843171057903910f, 0.399624199845646790f, + 0.388345046698826300f, + 0.377007410216418310f, 0.365612997804773960f, 0.354163525420490510f, + 0.342660717311994380f, + 0.331106305759876430f, 0.319502030816015750f, 0.307849640041534980f, + 0.296150888243623960f, + 0.284407537211271820f, 0.272621355449948980f, 0.260794117915275570f, + 0.248927605745720260f, + 0.237023605994367340f, 0.225083911359792780f, 0.213110319916091360f, + 0.201104634842091960f, + 0.189068664149806280f, 0.177004220412148860f, 0.164913120489970090f, + 0.152797185258443410f, + 0.140658239332849240f, 0.128498110793793220f, 0.116318630911904880f, + 0.104121633872054730f, + 0.091908956497132696f, 0.079682437971430126f, 0.067443919563664106f, + 0.055195244349690031f, + 0.042938256934940959f, 0.030674803176636581f, 0.018406729905804820f, + 0.006135884649154515f +}; + +static const float32_t cos_factors_512[512] = { + 0.999998823451701880f, 0.999989411081928400f, 0.999970586430974140f, + 0.999942349676023910f, + 0.999904701082852900f, 0.999857641005823860f, 0.999801169887884260f, + 0.999735288260561680f, + 0.999659996743959220f, 0.999575296046749220f, 0.999481186966166950f, + 0.999377670388002850f, + 0.999264747286594420f, 0.999142418724816910f, 0.999010685854073380f, + 0.998869549914283560f, + 0.998719012233872940f, 0.998559074229759310f, 0.998389737407340160f, + 0.998211003360478190f, + 0.998022873771486240f, 0.997825350411111640f, 0.997618435138519550f, + 0.997402129901275300f, + 0.997176436735326190f, 0.996941357764982160f, 0.996696895202896060f, + 0.996443051350042630f, + 0.996179828595696980f, 0.995907229417411720f, 0.995625256380994310f, + 0.995333912140482280f, + 0.995033199438118630f, 0.994723121104325700f, 0.994403680057679100f, + 0.994074879304879370f, + 0.993736721940724600f, 0.993389211148080650f, 0.993032350197851410f, + 0.992666142448948020f, + 0.992290591348257370f, 0.991905700430609330f, 0.991511473318743900f, + 0.991107913723276890f, + 0.990695025442664630f, 0.990272812363169110f, 0.989841278458820530f, + 0.989400427791380380f, + 0.988950264510302990f, 0.988490792852696590f, 0.988022017143283530f, + 0.987543941794359230f, + 0.987056571305750970f, 0.986559910264775410f, 0.986053963346195440f, + 0.985538735312176060f, + 0.985014231012239840f, 0.984480455383220930f, 0.983937413449218920f, + 0.983385110321551180f, + 0.982823551198705240f, 0.982252741366289370f, 0.981672686196983110f, + 0.981083391150486710f, + 0.980484861773469380f, 0.979877103699517640f, 0.979260122649082020f, + 0.978633924429423210f, + 0.977998514934557140f, 0.977353900145199960f, 0.976700086128711840f, + 0.976037079039039020f, + 0.975364885116656980f, 0.974683510688510670f, 0.973992962167955830f, + 0.973293246054698250f, + 0.972584368934732210f, 0.971866337480279400f, 0.971139158449725090f, + 0.970402838687555500f, + 0.969657385124292450f, 0.968902804776428870f, 0.968139104746362440f, + 0.967366292222328510f, + 0.966584374478333120f, 0.965793358874083680f, 0.964993252854920320f, + 0.964184063951745830f, + 0.963365799780954050f, 0.962538468044359160f, 0.961702076529122540f, + 0.960856633107679660f, + 0.960002145737665960f, 0.959138622461841890f, 0.958266071408017670f, + 0.957384500788975860f, + 0.956493918902395100f, 0.955594334130771110f, 0.954685754941338340f, + 0.953768189885990330f, + 0.952841647601198720f, 0.951906136807932350f, 0.950961666311575080f, + 0.950008245001843000f, + 0.949045881852700560f, 0.948074585922276230f, 0.947094366352777220f, + 0.946105232370403450f, + 0.945107193285260610f, 0.944100258491272660f, 0.943084437466093490f, + 0.942059739771017310f, + 0.941026175050889260f, 0.939983753034014050f, 0.938932483532064600f, + 0.937872376439989890f, + 0.936803441735921560f, 0.935725689481080370f, 0.934639129819680780f, + 0.933543772978836170f, + 0.932439629268462360f, 0.931326709081180430f, 0.930205022892219070f, + 0.929074581259315860f, + 0.927935394822617890f, 0.926787474304581750f, 0.925630830509872720f, + 0.924465474325262600f, + 0.923291416719527640f, 0.922108668743345180f, 0.920917241529189520f, + 0.919717146291227360f, + 0.918508394325212250f, 0.917290997008377910f, 0.916064965799331720f, + 0.914830312237946200f, + 0.913587047945250810f, 0.912335184623322750f, 0.911074734055176360f, + 0.909805708104652220f, + 0.908528118716306120f, 0.907241977915295820f, 0.905947297807268460f, + 0.904644090578246240f, + 0.903332368494511820f, 0.902012143902493180f, 0.900683429228646970f, + 0.899346236979341570f, + 0.898000579740739880f, 0.896646470178680150f, 0.895283921038557580f, + 0.893912945145203250f, + 0.892533555402764580f, 0.891145764794583180f, 0.889749586383072780f, + 0.888345033309596350f, + 0.886932118794342190f, 0.885510856136199950f, 0.884081258712634990f, + 0.882643339979562790f, + 0.881197113471222090f, 0.879742592800047410f, 0.878279791656541580f, + 0.876808723809145650f, + 0.875329403104110890f, 0.873841843465366860f, 0.872346058894391540f, + 0.870842063470078980f, + 0.869329871348606840f, 0.867809496763303320f, 0.866280954024512990f, + 0.864744257519462380f, + 0.863199421712124160f, 0.861646461143081300f, 0.860085390429390140f, + 0.858516224264442740f, + 0.856938977417828760f, 0.855353664735196030f, 0.853760301138111410f, + 0.852158901623919830f, + 0.850549481265603480f, 0.848932055211639610f, 0.847306638685858320f, + 0.845673246987299070f, + 0.844031895490066410f, 0.842382599643185850f, 0.840725374970458070f, + 0.839060237070312740f, + 0.837387201615661940f, 0.835706284353752600f, 0.834017501106018130f, + 0.832320867767929680f, + 0.830616400308846310f, 0.828904114771864870f, 0.827184027273669130f, + 0.825456154004377550f, + 0.823720511227391430f, 0.821977115279241550f, 0.820225982569434690f, + 0.818467129580298660f, + 0.816700572866827850f, 0.814926329056526620f, 0.813144414849253590f, + 0.811354847017063730f, + 0.809557642404051260f, 0.807752817926190360f, 0.805940390571176280f, + 0.804120377398265810f, + 0.802292795538115720f, 0.800457662192622820f, 0.798614994634760820f, + 0.796764810208418830f, + 0.794907126328237010f, 0.793041960479443640f, 0.791169330217690200f, + 0.789289253168885650f, + 0.787401747029031430f, 0.785506829564053930f, 0.783604518609638200f, + 0.781694832071059390f, + 0.779777787923014550f, 0.777853404209453150f, 0.775921699043407690f, + 0.773982690606822900f, + 0.772036397150384520f, 0.770082836993347900f, 0.768122028523365420f, + 0.766153990196312920f, + 0.764178740536116670f, 0.762196298134578900f, 0.760206681651202420f, + 0.758209909813015280f, + 0.756206001414394540f, 0.754194975316889170f, 0.752176850449042810f, + 0.750151645806215070f, + 0.748119380450403600f, 0.746080073510063780f, 0.744033744179929290f, + 0.741980411720831070f, + 0.739920095459516200f, 0.737852814788465980f, 0.735778589165713590f, + 0.733697438114660370f, + 0.731609381223892630f, 0.729514438146997010f, 0.727412628602375770f, + 0.725303972373060770f, + 0.723188489306527460f, 0.721066199314508110f, 0.718937122372804490f, + 0.716801278521099540f, + 0.714658687862769090f, 0.712509370564692320f, 0.710353346857062420f, + 0.708190637033195400f, + 0.706021261449339740f, 0.703845240524484940f, 0.701662594740168570f, + 0.699473344640283770f, + 0.697277510830886630f, 0.695075113980000880f, 0.692866174817424740f, + 0.690650714134534720f, + 0.688428752784090550f, 0.686200311680038700f, 0.683965411797315510f, + 0.681724074171649820f, + 0.679476319899365080f, 0.677222170137180450f, 0.674961646102012040f, + 0.672694769070772970f, + 0.670421560380173090f, 0.668142041426518560f, 0.665856233665509720f, + 0.663564158612039880f, + 0.661265837839992270f, 0.658961292982037320f, 0.656650545729429050f, + 0.654333617831800550f, + 0.652010531096959500f, 0.649681307390683190f, 0.647345968636512060f, + 0.645004536815544040f, + 0.642657033966226860f, 0.640303482184151670f, 0.637943903621844170f, + 0.635578320488556230f, + 0.633206755050057190f, 0.630829229628424470f, 0.628445766601832710f, + 0.626056388404343520f, + 0.623661117525694640f, 0.621259976511087660f, 0.618852987960976320f, + 0.616440174530853650f, + 0.614021558931038490f, 0.611597163926462020f, 0.609167012336453210f, + 0.606731127034524480f, + 0.604289530948156070f, 0.601842247058580030f, 0.599389298400564540f, + 0.596930708062196500f, + 0.594466499184664540f, 0.591996694962040990f, 0.589521318641063940f, + 0.587040393520918080f, + 0.584553942953015330f, 0.582061990340775550f, 0.579564559139405740f, + 0.577061672855679550f, + 0.574553355047715760f, 0.572039629324757050f, 0.569520519346947250f, + 0.566996048825108680f, + 0.564466241520519500f, 0.561931121244689470f, 0.559390711859136140f, + 0.556845037275160100f, + 0.554294121453620110f, 0.551737988404707450f, 0.549176662187719770f, + 0.546610166910834860f, + 0.544038526730883930f, 0.541461765853123560f, 0.538879908531008420f, + 0.536292979065963180f, + 0.533701001807152960f, 0.531104001151255000f, 0.528502001542228480f, + 0.525895027471084740f, + 0.523283103475656430f, 0.520666254140367270f, 0.518044504095999340f, + 0.515417878019463150f, + 0.512786400633563070f, 0.510150096706766700f, 0.507508991052970870f, + 0.504863108531267480f, + 0.502212474045710900f, 0.499557112545081890f, 0.496897049022654640f, + 0.494232308515959730f, + 0.491562916106550060f, 0.488888896919763230f, 0.486210276124486530f, + 0.483527078932918740f, + 0.480839330600333900f, 0.478147056424843120f, 0.475450281747155870f, + 0.472749031950342900f, + 0.470043332459595620f, 0.467333208741988530f, 0.464618686306237820f, + 0.461899790702462840f, + 0.459176547521944150f, 0.456448982396883860f, 0.453717121000163930f, + 0.450980989045103810f, + 0.448240612285220000f, 0.445496016513981740f, 0.442747227564570130f, + 0.439994271309633260f, + 0.437237173661044200f, 0.434475960569655710f, 0.431710658025057370f, + 0.428941292055329550f, + 0.426167888726799620f, 0.423390474143796100f, 0.420609074448402510f, + 0.417823715820212380f, + 0.415034424476081630f, 0.412241226669883000f, 0.409444148692257590f, + 0.406643216870369140f, + 0.403838457567654130f, 0.401029897183575790f, 0.398217562153373620f, + 0.395401478947816300f, + 0.392581674072951530f, 0.389758174069856410f, 0.386931005514388690f, + 0.384100195016935040f, + 0.381265769222162490f, 0.378427754808765620f, 0.375586178489217330f, + 0.372741067009515810f, + 0.369892447148934270f, 0.367040345719767240f, 0.364184789567079840f, + 0.361325805568454340f, + 0.358463420633736540f, 0.355597661704783960f, 0.352728555755210730f, + 0.349856129790135030f, + 0.346980410845923680f, 0.344101425989938980f, 0.341219202320282410f, + 0.338333766965541290f, + 0.335445147084531660f, 0.332553369866044220f, 0.329658462528587550f, + 0.326760452320131790f, + 0.323859366517852960f, 0.320955232427875210f, 0.318048077385015060f, + 0.315137928752522440f, + 0.312224813921825050f, 0.309308760312268780f, 0.306389795370861080f, + 0.303467946572011370f, + 0.300543241417273400f, 0.297615707435086310f, 0.294685372180514330f, + 0.291752263234989370f, + 0.288816408206049480f, 0.285877834727080730f, 0.282936570457055390f, + 0.279992643080273380f, + 0.277046080306099950f, 0.274096909868706330f, 0.271145159526808070f, + 0.268190857063403180f, + 0.265234030285511900f, 0.262274707023913590f, 0.259312915132886350f, + 0.256348682489942910f, + 0.253382036995570270f, 0.250413006572965280f, 0.247441619167773440f, + 0.244467902747824210f, + 0.241491885302869300f, 0.238513594844318500f, 0.235533059404975460f, + 0.232550307038775330f, + 0.229565365820518870f, 0.226578263845610110f, 0.223589029229790020f, + 0.220597690108873650f, + 0.217604274638483670f, 0.214608810993786920f, 0.211611327369227610f, + 0.208611851978263460f, + 0.205610413053099320f, 0.202607038844421110f, 0.199601757621131050f, + 0.196594597670080220f, + 0.193585587295803750f, 0.190574754820252800f, 0.187562128582529740f, + 0.184547736938619640f, + 0.181531608261125130f, 0.178513770938997590f, 0.175494253377271400f, + 0.172473083996796030f, + 0.169450291233967930f, 0.166425903540464220f, 0.163399949382973230f, + 0.160372457242928400f, + 0.157343455616238280f, 0.154312973013020240f, 0.151281037957330250f, + 0.148247678986896200f, + 0.145212924652847520f, 0.142176803519448000f, 0.139139344163826280f, + 0.136100575175706200f, + 0.133060525157139180f, 0.130019222722233350f, 0.126976696496885980f, + 0.123932975118512200f, + 0.120888087235777220f, 0.117842061508325020f, 0.114794926606510250f, + 0.111746711211126660f, + 0.108697444013138670f, 0.105647153713410700f, 0.102595869022436280f, + 0.099543618660069444f, + 0.096490431355252607f, 0.093436335845747912f, 0.090381360877865011f, + 0.087325535206192226f, + 0.084268887593324127f, 0.081211446809592386f, 0.078153241632794315f, + 0.075094300847921291f, + 0.072034653246889416f, 0.068974327628266732f, 0.065913352797003930f, + 0.062851757564161420f, + 0.059789570746640007f, 0.056726821166907783f, 0.053663537652730679f, + 0.050599749036899337f, + 0.047535484156959261f, 0.044470771854938744f, 0.041405640977076712f, + 0.038340120373552791f, + 0.035274238898213947f, 0.032208025408304704f, 0.029141508764193740f, + 0.026074717829104040f, + 0.023007681468839410f, 0.019940428551514598f, 0.016872987947281773f, + 0.013805388528060349f, + 0.010737659167264572f, 0.007669828739531077f, 0.004601926120448672f, + 0.001533980186284766f +}; + +static const float32_t cos_factors_2048[2048] = { + 0.999999926465717890f, 0.999999338191525530f, 0.999998161643486980f, + 0.999996396822294350f, + 0.999994043728985820f, 0.999991102364945590f, 0.999987572731904080f, + 0.999983454831937730f, + 0.999978748667468830f, 0.999973454241265940f, 0.999967571556443780f, + 0.999961100616462820f, + 0.999954041425129780f, 0.999946393986597460f, 0.999938158305364590f, + 0.999929334386276070f, + 0.999919922234522750f, 0.999909921855641540f, 0.999899333255515390f, + 0.999888156440373320f, + 0.999876391416790410f, 0.999864038191687680f, 0.999851096772332190f, + 0.999837567166337090f, + 0.999823449381661570f, 0.999808743426610520f, 0.999793449309835270f, + 0.999777567040332940f, + 0.999761096627446610f, 0.999744038080865430f, 0.999726391410624470f, + 0.999708156627104880f, + 0.999689333741033640f, 0.999669922763483760f, 0.999649923705874240f, + 0.999629336579970110f, + 0.999608161397882110f, 0.999586398172067070f, 0.999564046915327740f, + 0.999541107640812940f, + 0.999517580362016990f, 0.999493465092780590f, 0.999468761847290050f, + 0.999443470640077770f, + 0.999417591486021720f, 0.999391124400346050f, 0.999364069398620550f, + 0.999336426496761240f, + 0.999308195711029470f, 0.999279377058032710f, 0.999249970554724420f, + 0.999219976218403530f, + 0.999189394066714920f, 0.999158224117649430f, 0.999126466389543390f, + 0.999094120901079070f, + 0.999061187671284600f, 0.999027666719533690f, 0.998993558065545680f, + 0.998958861729386080f, + 0.998923577731465780f, 0.998887706092541290f, 0.998851246833715180f, + 0.998814199976435390f, + 0.998776565542495610f, 0.998738343554035230f, 0.998699534033539280f, + 0.998660137003838490f, + 0.998620152488108870f, 0.998579580509872500f, 0.998538421092996730f, + 0.998496674261694640f, + 0.998454340040524800f, 0.998411418454391300f, 0.998367909528543820f, + 0.998323813288577560f, + 0.998279129760433200f, 0.998233858970396850f, 0.998188000945100300f, + 0.998141555711520520f, + 0.998094523296980010f, 0.998046903729146840f, 0.997998697036034390f, + 0.997949903246001190f, + 0.997900522387751620f, 0.997850554490335110f, 0.997799999583146470f, + 0.997748857695925690f, + 0.997697128858758500f, 0.997644813102075420f, 0.997591910456652630f, + 0.997538420953611340f, + 0.997484344624417930f, 0.997429681500884180f, 0.997374431615167150f, + 0.997318594999768600f, + 0.997262171687536170f, 0.997205161711661850f, 0.997147565105683480f, + 0.997089381903483400f, + 0.997030612139289450f, 0.996971255847674320f, 0.996911313063555740f, + 0.996850783822196610f, + 0.996789668159204560f, 0.996727966110532490f, 0.996665677712478160f, + 0.996602803001684130f, + 0.996539342015137940f, 0.996475294790172160f, 0.996410661364464100f, + 0.996345441776035900f, + 0.996279636063254650f, 0.996213244264832040f, 0.996146266419824620f, + 0.996078702567633980f, + 0.996010552748005870f, 0.995941817001031350f, 0.995872495367145730f, + 0.995802587887129160f, + 0.995732094602106430f, 0.995661015553546910f, 0.995589350783264600f, + 0.995517100333418110f, + 0.995444264246510340f, 0.995370842565388990f, 0.995296835333246090f, + 0.995222242593618360f, + 0.995147064390386470f, 0.995071300767776170f, 0.994994951770357020f, + 0.994918017443043200f, + 0.994840497831093180f, 0.994762392980109930f, 0.994683702936040250f, + 0.994604427745175660f, + 0.994524567454151740f, 0.994444122109948040f, 0.994363091759888570f, + 0.994281476451641550f, + 0.994199276233218910f, 0.994116491152977070f, 0.994033121259616400f, + 0.993949166602181130f, + 0.993864627230059750f, 0.993779503192984580f, 0.993693794541031790f, + 0.993607501324621610f, + 0.993520623594518090f, 0.993433161401829360f, 0.993345114798006910f, + 0.993256483834846440f, + 0.993167268564487230f, 0.993077469039412300f, 0.992987085312448390f, + 0.992896117436765980f, + 0.992804565465879140f, 0.992712429453645460f, 0.992619709454266140f, + 0.992526405522286100f, + 0.992432517712593660f, 0.992338046080420420f, 0.992242990681341700f, + 0.992147351571276090f, + 0.992051128806485720f, 0.991954322443575950f, 0.991856932539495470f, + 0.991758959151536110f, + 0.991660402337333210f, 0.991561262154865290f, 0.991461538662453790f, + 0.991361231918763460f, + 0.991260341982802440f, 0.991158868913921350f, 0.991056812771814340f, + 0.990954173616518500f, + 0.990850951508413620f, 0.990747146508222710f, 0.990642758677011570f, + 0.990537788076188750f, + 0.990432234767505970f, 0.990326098813057330f, 0.990219380275280000f, + 0.990112079216953770f, + 0.990004195701200910f, 0.989895729791486660f, 0.989786681551618640f, + 0.989677051045747210f, + 0.989566838338365120f, 0.989456043494307710f, 0.989344666578752640f, + 0.989232707657220050f, + 0.989120166795572690f, 0.989007044060015270f, 0.988893339517095130f, + 0.988779053233701520f, + 0.988664185277066230f, 0.988548735714763200f, 0.988432704614708340f, + 0.988316092045159690f, + 0.988198898074717610f, 0.988081122772324070f, 0.987962766207263420f, + 0.987843828449161740f, + 0.987724309567986960f, 0.987604209634049160f, 0.987483528717999710f, + 0.987362266890832400f, + 0.987240424223882250f, 0.987118000788826280f, 0.986994996657682980f, + 0.986871411902812470f, + 0.986747246596916590f, 0.986622500813038480f, 0.986497174624562880f, + 0.986371268105216030f, + 0.986244781329065460f, 0.986117714370520090f, 0.985990067304330140f, + 0.985861840205586980f, + 0.985733033149723490f, 0.985603646212513400f, 0.985473679470071810f, + 0.985343132998854790f, + 0.985212006875659350f, 0.985080301177623800f, 0.984948015982227030f, + 0.984815151367289140f, + 0.984681707410970940f, 0.984547684191773960f, 0.984413081788540700f, + 0.984277900280454370f, + 0.984142139747038570f, 0.984005800268157870f, 0.983868881924017220f, + 0.983731384795162090f, + 0.983593308962478650f, 0.983454654507193270f, 0.983315421510872810f, + 0.983175610055424420f, + 0.983035220223095640f, 0.982894252096474070f, 0.982752705758487830f, + 0.982610581292404750f, + 0.982467878781833170f, 0.982324598310721280f, 0.982180739963357090f, + 0.982036303824369020f, + 0.981891289978725100f, 0.981745698511732990f, 0.981599529509040720f, + 0.981452783056635520f, + 0.981305459240844670f, 0.981157558148334830f, 0.981009079866112630f, + 0.980860024481523870f, + 0.980710392082253970f, 0.980560182756327840f, 0.980409396592109910f, + 0.980258033678303550f, + 0.980106094103951770f, 0.979953577958436740f, 0.979800485331479790f, + 0.979646816313141210f, + 0.979492570993820810f, 0.979337749464256780f, 0.979182351815526930f, + 0.979026378139047580f, + 0.978869828526574120f, 0.978712703070200420f, 0.978555001862359550f, + 0.978396724995823090f, + 0.978237872563701090f, 0.978078444659442380f, 0.977918441376834370f, + 0.977757862810002760f, + 0.977596709053411890f, 0.977434980201864260f, 0.977272676350500860f, + 0.977109797594800880f, + 0.976946344030581670f, 0.976782315753998650f, 0.976617712861545640f, + 0.976452535450054060f, + 0.976286783616693630f, 0.976120457458971910f, 0.975953557074734300f, + 0.975786082562163930f, + 0.975618034019781750f, 0.975449411546446380f, 0.975280215241354220f, + 0.975110445204038890f, + 0.974940101534371830f, 0.974769184332561770f, 0.974597693699155050f, + 0.974425629735034990f, + 0.974252992541422500f, 0.974079782219875680f, 0.973905998872289570f, + 0.973731642600896400f, + 0.973556713508265560f, 0.973381211697303290f, 0.973205137271252800f, + 0.973028490333694210f, + 0.972851270988544180f, 0.972673479340056430f, 0.972495115492821190f, + 0.972316179551765300f, + 0.972136671622152230f, 0.971956591809581720f, 0.971775940219990140f, + 0.971594716959650160f, + 0.971412922135170940f, 0.971230555853497380f, 0.971047618221911100f, + 0.970864109348029470f, + 0.970680029339806130f, 0.970495378305530560f, 0.970310156353828110f, + 0.970124363593660280f, + 0.969938000134323960f, 0.969751066085452140f, 0.969563561557013180f, + 0.969375486659311280f, + 0.969186841502985950f, 0.968997626199012420f, 0.968807840858700970f, + 0.968617485593697540f, + 0.968426560515983190f, 0.968235065737874320f, 0.968043001372022260f, + 0.967850367531413620f, + 0.967657164329369880f, 0.967463391879547550f, 0.967269050295937790f, + 0.967074139692867040f, + 0.966878660184995910f, 0.966682611887320080f, 0.966485994915169840f, + 0.966288809384209690f, + 0.966091055410438830f, 0.965892733110190860f, 0.965693842600133690f, + 0.965494383997269500f, + 0.965294357418934660f, 0.965093762982799590f, 0.964892600806868890f, + 0.964690871009481030f, + 0.964488573709308410f, 0.964285709025357480f, 0.964082277076968140f, + 0.963878277983814200f, + 0.963673711865903230f, 0.963468578843575950f, 0.963262879037507070f, + 0.963056612568704340f, + 0.962849779558509030f, 0.962642380128595710f, 0.962434414400972100f, + 0.962225882497979020f, + 0.962016784542290560f, 0.961807120656913540f, 0.961596890965187860f, + 0.961386095590786250f, + 0.961174734657714080f, 0.960962808290309780f, 0.960750316613243950f, + 0.960537259751520050f, + 0.960323637830473920f, 0.960109450975773940f, 0.959894699313420530f, + 0.959679382969746750f, + 0.959463502071417510f, 0.959247056745430090f, 0.959030047119113660f, + 0.958812473320129310f, + 0.958594335476470220f, 0.958375633716461170f, 0.958156368168758820f, + 0.957936538962351420f, + 0.957716146226558870f, 0.957495190091032570f, 0.957273670685755200f, + 0.957051588141040970f, + 0.956828942587535370f, 0.956605734156215080f, 0.956381962978387730f, + 0.956157629185692140f, + 0.955932732910098280f, 0.955707274283906560f, 0.955481253439748770f, + 0.955254670510586990f, + 0.955027525629714160f, 0.954799818930753720f, 0.954571550547659630f, + 0.954342720614716480f, + 0.954113329266538800f, 0.953883376638071770f, 0.953652862864590500f, + 0.953421788081700310f, + 0.953190152425336670f, 0.952957956031764700f, 0.952725199037579570f, + 0.952491881579706320f, + 0.952258003795399600f, 0.952023565822243570f, 0.951788567798152130f, + 0.951553009861368590f, + 0.951316892150465550f, 0.951080214804345010f, 0.950842977962238160f, + 0.950605181763705340f, + 0.950366826348635780f, 0.950127911857248100f, 0.949888438430089300f, + 0.949648406208035480f, + 0.949407815332291570f, 0.949166665944390700f, 0.948924958186195160f, + 0.948682692199895090f, + 0.948439868128009620f, 0.948196486113385580f, 0.947952546299198670f, + 0.947708048828952100f, + 0.947462993846477700f, 0.947217381495934820f, 0.946971211921810880f, + 0.946724485268921170f, + 0.946477201682408680f, 0.946229361307743820f, 0.945980964290724760f, + 0.945732010777477150f, + 0.945482500914453740f, 0.945232434848435000f, 0.944981812726528150f, + 0.944730634696167800f, + 0.944478900905115550f, 0.944226611501459810f, 0.943973766633615980f, + 0.943720366450326200f, + 0.943466411100659320f, 0.943211900734010620f, 0.942956835500102120f, + 0.942701215548981900f, + 0.942445041031024890f, 0.942188312096931770f, 0.941931028897729620f, + 0.941673191584771360f, + 0.941414800309736340f, 0.941155855224629190f, 0.940896356481780830f, + 0.940636304233847590f, + 0.940375698633811540f, 0.940114539834980280f, 0.939852827990986680f, + 0.939590563255789270f, + 0.939327745783671400f, 0.939064375729241950f, 0.938800453247434770f, + 0.938535978493508560f, + 0.938270951623047190f, 0.938005372791958840f, 0.937739242156476970f, + 0.937472559873159250f, + 0.937205326098887960f, 0.936937540990869900f, 0.936669204706636170f, + 0.936400317404042060f, + 0.936130879241267030f, 0.935860890376814640f, 0.935590350969512370f, + 0.935319261178511610f, + 0.935047621163287430f, 0.934775431083638700f, 0.934502691099687870f, + 0.934229401371880820f, + 0.933955562060986730f, 0.933681173328098410f, 0.933406235334631520f, + 0.933130748242325230f, + 0.932854712213241120f, 0.932578127409764420f, 0.932300993994602760f, + 0.932023312130786490f, + 0.931745081981668720f, 0.931466303710925090f, 0.931186977482553750f, + 0.930907103460875130f, + 0.930626681810531760f, 0.930345712696488470f, 0.930064196284032360f, + 0.929782132738772190f, + 0.929499522226638560f, 0.929216364913884040f, 0.928932660967082820f, + 0.928648410553130520f, + 0.928363613839244370f, 0.928078270992963140f, 0.927792382182146320f, + 0.927505947574975180f, + 0.927218967339951790f, 0.926931441645899130f, 0.926643370661961230f, + 0.926354754557602860f, + 0.926065593502609310f, 0.925775887667086740f, 0.925485637221461490f, + 0.925194842336480530f, + 0.924903503183210910f, 0.924611619933039970f, 0.924319192757675160f, + 0.924026221829143850f, + 0.923732707319793290f, 0.923438649402290370f, 0.923144048249621930f, + 0.922848904035094120f, + 0.922553216932332830f, 0.922256987115283030f, 0.921960214758209220f, + 0.921662900035694730f, + 0.921365043122642340f, 0.921066644194273640f, 0.920767703426128790f, + 0.920468220994067110f, + 0.920168197074266340f, 0.919867631843222950f, 0.919566525477751530f, + 0.919264878154985370f, + 0.918962690052375630f, 0.918659961347691900f, 0.918356692219021720f, + 0.918052882844770380f, + 0.917748533403661250f, 0.917443644074735220f, 0.917138215037350710f, + 0.916832246471183890f, + 0.916525738556228210f, 0.916218691472794220f, 0.915911105401509880f, + 0.915602980523320230f, + 0.915294317019487050f, 0.914985115071589310f, 0.914675374861522390f, + 0.914365096571498560f, + 0.914054280384046570f, 0.913742926482011390f, 0.913431035048554720f, + 0.913118606267154240f, + 0.912805640321603500f, 0.912492137396012650f, 0.912178097674807180f, + 0.911863521342728520f, + 0.911548408584833990f, 0.911232759586496190f, 0.910916574533403360f, + 0.910599853611558930f, + 0.910282597007281760f, 0.909964804907205660f, 0.909646477498279540f, + 0.909327614967767260f, + 0.909008217503247450f, 0.908688285292613360f, 0.908367818524072890f, + 0.908046817386148340f, + 0.907725282067676440f, 0.907403212757808110f, 0.907080609646008450f, + 0.906757472922056550f, + 0.906433802776045460f, 0.906109599398381980f, 0.905784862979786550f, + 0.905459593711293250f, + 0.905133791784249690f, 0.904807457390316540f, 0.904480590721468250f, + 0.904153191969991780f, + 0.903825261328487510f, 0.903496798989868450f, 0.903167805147360720f, + 0.902838279994502830f, + 0.902508223725145940f, 0.902177636533453620f, 0.901846518613901750f, + 0.901514870161278740f, + 0.901182691370684520f, 0.900849982437531450f, 0.900516743557543520f, + 0.900182974926756810f, + 0.899848676741518580f, 0.899513849198487980f, 0.899178492494635330f, + 0.898842606827242370f, + 0.898506192393901950f, 0.898169249392518080f, 0.897831778021305650f, + 0.897493778478790310f, + 0.897155250963808550f, 0.896816195675507300f, 0.896476612813344120f, + 0.896136502577086770f, + 0.895795865166813530f, 0.895454700782912450f, 0.895113009626081760f, + 0.894770791897329550f, + 0.894428047797973800f, 0.894084777529641990f, 0.893740981294271040f, + 0.893396659294107720f, + 0.893051811731707450f, 0.892706438809935390f, 0.892360540731965360f, + 0.892014117701280470f, + 0.891667169921672280f, 0.891319697597241390f, 0.890971700932396860f, + 0.890623180131855930f, + 0.890274135400644600f, 0.889924566944096720f, 0.889574474967854580f, + 0.889223859677868210f, + 0.888872721280395630f, 0.888521059982002260f, 0.888168875989561730f, + 0.887816169510254440f, + 0.887462940751568840f, 0.887109189921300170f, 0.886754917227550840f, + 0.886400122878730600f, + 0.886044807083555600f, 0.885688970051048960f, 0.885332611990540590f, + 0.884975733111666660f, + 0.884618333624369920f, 0.884260413738899190f, 0.883901973665809470f, + 0.883543013615961880f, + 0.883183533800523390f, 0.882823534430966620f, 0.882463015719070150f, + 0.882101977876917580f, + 0.881740421116898320f, 0.881378345651706920f, 0.881015751694342870f, + 0.880652639458111010f, + 0.880289009156621010f, 0.879924861003786860f, 0.879560195213827890f, + 0.879195012001267480f, + 0.878829311580933360f, 0.878463094167957870f, 0.878096359977777130f, + 0.877729109226131570f, + 0.877361342129065140f, 0.876993058902925890f, 0.876624259764365310f, + 0.876254944930338510f, + 0.875885114618103810f, 0.875514769045222850f, 0.875143908429560360f, + 0.874772532989284150f, + 0.874400642942864790f, 0.874028238509075740f, 0.873655319906992630f, + 0.873281887355994210f, + 0.872907941075761080f, 0.872533481286276170f, 0.872158508207824480f, + 0.871783022060993120f, + 0.871407023066670950f, 0.871030511446048260f, 0.870653487420617430f, + 0.870275951212171940f, + 0.869897903042806340f, 0.869519343134916860f, 0.869140271711200560f, + 0.868760688994655310f, + 0.868380595208579800f, 0.867999990576573510f, 0.867618875322536230f, + 0.867237249670668400f, + 0.866855113845470430f, 0.866472468071743050f, 0.866089312574586770f, + 0.865705647579402380f, + 0.865321473311889800f, 0.864936789998049020f, 0.864551597864179340f, + 0.864165897136879300f, + 0.863779688043046720f, 0.863392970809878420f, 0.863005745664870320f, + 0.862618012835816740f, + 0.862229772550811240f, 0.861841025038245330f, 0.861451770526809320f, + 0.861062009245491480f, + 0.860671741423578380f, 0.860280967290654510f, 0.859889687076602290f, + 0.859497901011601730f, + 0.859105609326130450f, 0.858712812250963520f, 0.858319510017173440f, + 0.857925702856129790f, + 0.857531390999499150f, 0.857136574679244980f, 0.856741254127627470f, + 0.856345429577203610f, + 0.855949101260826910f, 0.855552269411646860f, 0.855154934263109620f, + 0.854757096048957220f, + 0.854358755003227440f, 0.853959911360254180f, 0.853560565354666840f, + 0.853160717221390420f, + 0.852760367195645300f, 0.852359515512947090f, 0.851958162409106380f, + 0.851556308120228980f, + 0.851153952882715340f, 0.850751096933260790f, 0.850347740508854980f, + 0.849943883846782210f, + 0.849539527184620890f, 0.849134670760243630f, 0.848729314811817130f, + 0.848323459577801640f, + 0.847917105296951410f, 0.847510252208314330f, 0.847102900551231500f, + 0.846695050565337450f, + 0.846286702490559710f, 0.845877856567119000f, 0.845468513035528830f, + 0.845058672136595470f, + 0.844648334111417820f, 0.844237499201387020f, 0.843826167648186740f, + 0.843414339693792760f, + 0.843002015580472940f, 0.842589195550786710f, 0.842175879847585570f, + 0.841762068714012490f, + 0.841347762393501950f, 0.840932961129779780f, 0.840517665166862550f, + 0.840101874749058400f, + 0.839685590120966110f, 0.839268811527475230f, 0.838851539213765760f, + 0.838433773425308340f, + 0.838015514407863820f, 0.837596762407483040f, 0.837177517670507300f, + 0.836757780443567190f, + 0.836337550973583530f, 0.835916829507766360f, 0.835495616293615350f, + 0.835073911578919410f, + 0.834651715611756440f, 0.834229028640493420f, 0.833805850913786340f, + 0.833382182680579730f, + 0.832958024190106670f, 0.832533375691888680f, 0.832108237435735590f, + 0.831682609671745120f, + 0.831256492650303210f, 0.830829886622083570f, 0.830402791838047550f, + 0.829975208549443950f, + 0.829547137007808910f, 0.829118577464965980f, 0.828689530173025820f, + 0.828259995384385660f, + 0.827829973351729920f, 0.827399464328029470f, 0.826968468566541600f, + 0.826536986320809960f, + 0.826105017844664610f, 0.825672563392221390f, 0.825239623217882250f, + 0.824806197576334330f, + 0.824372286722551250f, 0.823937890911791370f, 0.823503010399598500f, + 0.823067645441801670f, + 0.822631796294514990f, 0.822195463214137170f, 0.821758646457351750f, + 0.821321346281126740f, + 0.820883562942714580f, 0.820445296699652050f, 0.820006547809759680f, + 0.819567316531142230f, + 0.819127603122188240f, 0.818687407841569680f, 0.818246730948242070f, + 0.817805572701444270f, + 0.817363933360698460f, 0.816921813185809480f, 0.816479212436865390f, + 0.816036131374236810f, + 0.815592570258576790f, 0.815148529350820830f, 0.814704008912187080f, + 0.814259009204175270f, + 0.813813530488567190f, 0.813367573027426570f, 0.812921137083098770f, + 0.812474222918210480f, + 0.812026830795669730f, 0.811578960978665890f, 0.811130613730669190f, + 0.810681789315430780f, + 0.810232487996982330f, 0.809782710039636530f, 0.809332455707985950f, + 0.808881725266903610f, + 0.808430518981542720f, 0.807978837117336310f, 0.807526679939997160f, + 0.807074047715517610f, + 0.806620940710169650f, 0.806167359190504420f, 0.805713303423352230f, + 0.805258773675822210f, + 0.804803770215302920f, 0.804348293309460780f, 0.803892343226241260f, + 0.803435920233868120f, + 0.802979024600843250f, 0.802521656595946430f, 0.802063816488235440f, + 0.801605504547046150f, + 0.801146721041991360f, 0.800687466242961610f, 0.800227740420124790f, + 0.799767543843925680f, + 0.799306876785086160f, 0.798845739514604580f, 0.798384132303756380f, + 0.797922055424093000f, + 0.797459509147442460f, 0.796996493745908750f, 0.796533009491872000f, + 0.796069056657987990f, + 0.795604635517188070f, 0.795139746342679590f, 0.794674389407944550f, + 0.794208564986740640f, + 0.793742273353100210f, 0.793275514781330630f, 0.792808289546014120f, + 0.792340597922007170f, + 0.791872440184440470f, 0.791403816608719500f, 0.790934727470523290f, + 0.790465173045804880f, + 0.789995153610791090f, 0.789524669441982190f, 0.789053720816151880f, + 0.788582308010347120f, + 0.788110431301888070f, 0.787638090968367450f, 0.787165287287651010f, + 0.786692020537876790f, + 0.786218290997455660f, 0.785744098945070360f, 0.785269444659675850f, + 0.784794328420499230f, + 0.784318750507038920f, 0.783842711199065230f, 0.783366210776619720f, + 0.782889249520015480f, + 0.782411827709836530f, 0.781933945626937630f, 0.781455603552444590f, + 0.780976801767753750f, + 0.780497540554531910f, 0.780017820194715990f, 0.779537640970513260f, + 0.779057003164400630f, + 0.778575907059125050f, 0.778094352937702790f, 0.777612341083420030f, + 0.777129871779831620f, + 0.776646945310762060f, 0.776163561960304340f, 0.775679722012820650f, + 0.775195425752941420f, + 0.774710673465565550f, 0.774225465435860680f, 0.773739801949261840f, + 0.773253683291472590f, + 0.772767109748463850f, 0.772280081606474320f, 0.771792599152010150f, + 0.771304662671844830f, + 0.770816272453018540f, 0.770327428782838890f, 0.769838131948879840f, + 0.769348382238982280f, + 0.768858179941253270f, 0.768367525344066270f, 0.767876418736060610f, + 0.767384860406141730f, + 0.766892850643480670f, 0.766400389737514230f, 0.765907477977944340f, + 0.765414115654738270f, + 0.764920303058128410f, 0.764426040478612070f, 0.763931328206951090f, + 0.763436166534172010f, + 0.762940555751565720f, 0.762444496150687210f, 0.761947988023355390f, + 0.761451031661653620f, + 0.760953627357928150f, 0.760455775404789260f, 0.759957476095110330f, + 0.759458729722028210f, + 0.758959536578942440f, 0.758459896959515430f, 0.757959811157672300f, + 0.757459279467600720f, + 0.756958302183750490f, 0.756456879600833740f, 0.755955012013824420f, + 0.755452699717958250f, + 0.754949943008732640f, 0.754446742181906440f, 0.753943097533499640f, + 0.753439009359793580f, + 0.752934477957330150f, 0.752429503622912390f, 0.751924086653603550f, + 0.751418227346727470f, + 0.750911925999867890f, 0.750405182910869330f, 0.749897998377835330f, + 0.749390372699129560f, + 0.748882306173375150f, 0.748373799099454560f, 0.747864851776509410f, + 0.747355464503940190f, + 0.746845637581406540f, 0.746335371308826320f, 0.745824665986376090f, + 0.745313521914490520f, + 0.744801939393862630f, 0.744289918725443260f, 0.743777460210440890f, + 0.743264564150321600f, + 0.742751230846809050f, 0.742237460601884000f, 0.741723253717784140f, + 0.741208610497004260f, + 0.740693531242295760f, 0.740178016256666240f, 0.739662065843380010f, + 0.739145680305957510f, + 0.738628859948174840f, 0.738111605074064260f, 0.737593915987913570f, + 0.737075792994265730f, + 0.736557236397919150f, 0.736038246503927350f, 0.735518823617598900f, + 0.734998968044496710f, + 0.734478680090438370f, 0.733957960061495940f, 0.733436808263995710f, + 0.732915225004517780f, + 0.732393210589896040f, 0.731870765327218290f, 0.731347889523825570f, + 0.730824583487312160f, + 0.730300847525525490f, 0.729776681946566090f, 0.729252087058786970f, + 0.728727063170793830f, + 0.728201610591444610f, 0.727675729629849610f, 0.727149420595371020f, + 0.726622683797622850f, + 0.726095519546471000f, 0.725567928152032300f, 0.725039909924675370f, + 0.724511465175019630f, + 0.723982594213935520f, 0.723453297352544380f, 0.722923574902217700f, + 0.722393427174577550f, + 0.721862854481496340f, 0.721331857135096290f, 0.720800435447749190f, + 0.720268589732077190f, + 0.719736320300951030f, 0.719203627467491220f, 0.718670511545067230f, + 0.718136972847297490f, + 0.717603011688049080f, 0.717068628381437480f, 0.716533823241826680f, + 0.715998596583828690f, + 0.715462948722303760f, 0.714926879972359490f, 0.714390390649351390f, + 0.713853481068882470f, + 0.713316151546802610f, 0.712778402399208980f, 0.712240233942445510f, + 0.711701646493102970f, + 0.711162640368018350f, 0.710623215884275020f, 0.710083373359202800f, + 0.709543113110376770f, + 0.709002435455618250f, 0.708461340712994160f, 0.707919829200816310f, + 0.707377901237642100f, + 0.706835557142273860f, 0.706292797233758480f, 0.705749621831387790f, + 0.705206031254697830f, + 0.704662025823468930f, 0.704117605857725430f, 0.703572771677735580f, + 0.703027523604011220f, + 0.702481861957308000f, 0.701935787058624360f, 0.701389299229202230f, + 0.700842398790526230f, + 0.700295086064323780f, 0.699747361372564990f, 0.699199225037462120f, + 0.698650677381469580f, + 0.698101718727283880f, 0.697552349397843270f, 0.697002569716327460f, + 0.696452380006157830f, + 0.695901780590996830f, 0.695350771794747800f, 0.694799353941554900f, + 0.694247527355803310f, + 0.693695292362118350f, 0.693142649285365510f, 0.692589598450650380f, + 0.692036140183318830f, + 0.691482274808955850f, 0.690928002653386280f, 0.690373324042674040f, + 0.689818239303122470f, + 0.689262748761273470f, 0.688706852743907750f, 0.688150551578044830f, + 0.687593845590942170f, + 0.687036735110095660f, 0.686479220463238950f, 0.685921301978343670f, + 0.685362979983618730f, + 0.684804254807510620f, 0.684245126778703080f, 0.683685596226116690f, + 0.683125663478908800f, + 0.682565328866473250f, 0.682004592718440830f, 0.681443455364677990f, + 0.680881917135287340f, + 0.680319978360607200f, 0.679757639371212030f, 0.679194900497911200f, + 0.678631762071749470f, + 0.678068224424006600f, 0.677504287886197430f, 0.676939952790071240f, + 0.676375219467611700f, + 0.675810088251037060f, 0.675244559472799270f, 0.674678633465584540f, + 0.674112310562312360f, + 0.673545591096136100f, 0.672978475400442090f, 0.672410963808849900f, + 0.671843056655211930f, + 0.671274754273613490f, 0.670706056998372160f, 0.670136965164037760f, + 0.669567479105392490f, + 0.668997599157450270f, 0.668427325655456820f, 0.667856658934889440f, + 0.667285599331456480f, + 0.666714147181097670f, 0.666142302819983540f, 0.665570066584515560f, + 0.664997438811325340f, + 0.664424419837275180f, 0.663851009999457340f, 0.663277209635194100f, + 0.662703019082037440f, + 0.662128438677768720f, 0.661553468760399000f, 0.660978109668168060f, + 0.660402361739545030f, + 0.659826225313227430f, 0.659249700728141490f, 0.658672788323441890f, + 0.658095488438511290f, + 0.657517801412960120f, 0.656939727586627110f, 0.656361267299578000f, + 0.655782420892106030f, + 0.655203188704731930f, 0.654623571078202680f, 0.654043568353492640f, + 0.653463180871802330f, + 0.652882408974558960f, 0.652301253003415460f, 0.651719713300251020f, + 0.651137790207170330f, + 0.650555484066503990f, 0.649972795220807530f, 0.649389724012861770f, + 0.648806270785672550f, + 0.648222435882470420f, 0.647638219646710420f, 0.647053622422071650f, + 0.646468644552457890f, + 0.645883286381996440f, 0.645297548255038380f, 0.644711430516158420f, + 0.644124933510154540f, + 0.643538057582047850f, 0.642950803077082080f, 0.642363170340724320f, + 0.641775159718663500f, + 0.641186771556811250f, 0.640598006201301030f, 0.640008863998488440f, + 0.639419345294950700f, + 0.638829450437486400f, 0.638239179773115390f, 0.637648533649078810f, + 0.637057512412838590f, + 0.636466116412077180f, 0.635874345994697720f, 0.635282201508823530f, + 0.634689683302797850f, + 0.634096791725183740f, 0.633503527124764320f, 0.632909889850541860f, + 0.632315880251737680f, + 0.631721498677792370f, 0.631126745478365340f, 0.630531621003334600f, + 0.629936125602796550f, + 0.629340259627065750f, 0.628744023426674790f, 0.628147417352374120f, + 0.627550441755131530f, + 0.626953096986132770f, 0.626355383396779990f, 0.625757301338692900f, + 0.625158851163707730f, + 0.624560033223877320f, 0.623960847871470770f, 0.623361295458973340f, + 0.622761376339086460f, + 0.622161090864726930f, 0.621560439389027270f, 0.620959422265335180f, + 0.620358039847213830f, + 0.619756292488440660f, 0.619154180543008410f, 0.618551704365123860f, + 0.617948864309208260f, + 0.617345660729896940f, 0.616742093982038830f, 0.616138164420696910f, + 0.615533872401147430f, + 0.614929218278879590f, 0.614324202409595950f, 0.613718825149211830f, + 0.613113086853854910f, + 0.612506987879865570f, 0.611900528583796070f, 0.611293709322411010f, + 0.610686530452686280f, + 0.610078992331809620f, 0.609471095317180240f, 0.608862839766408200f, + 0.608254226037314490f, + 0.607645254487930830f, 0.607035925476499760f, 0.606426239361473550f, + 0.605816196501515080f, + 0.605205797255496500f, 0.604595041982500360f, 0.603983931041818020f, + 0.603372464792950370f, + 0.602760643595607220f, 0.602148467809707320f, 0.601535937795377730f, + 0.600923053912954090f, + 0.600309816522980430f, 0.599696225986208310f, 0.599082282663597310f, + 0.598467986916314310f, + 0.597853339105733910f, 0.597238339593437530f, 0.596622988741213330f, + 0.596007286911056530f, + 0.595391234465168730f, 0.594774831765957580f, 0.594158079176036800f, + 0.593540977058226390f, + 0.592923525775551410f, 0.592305725691242400f, 0.591687577168735550f, + 0.591069080571671510f, + 0.590450236263895920f, 0.589831044609458900f, 0.589211505972615070f, + 0.588591620717822890f, + 0.587971389209745120f, 0.587350811813247660f, 0.586729888893400500f, + 0.586108620815476430f, + 0.585487007944951450f, 0.584865050647504490f, 0.584242749289016980f, + 0.583620104235572760f, + 0.582997115853457700f, 0.582373784509160220f, 0.581750110569369760f, + 0.581126094400977620f, + 0.580501736371076600f, 0.579877036846960350f, 0.579251996196123550f, + 0.578626614786261430f, + 0.578000892985269910f, 0.577374831161244880f, 0.576748429682482520f, + 0.576121688917478390f, + 0.575494609234928230f, 0.574867191003726740f, 0.574239434592967890f, + 0.573611340371944610f, + 0.572982908710148680f, 0.572354139977270030f, 0.571725034543197120f, + 0.571095592778016690f, + 0.570465815052012990f, 0.569835701735668110f, 0.569205253199661200f, + 0.568574469814869250f, + 0.567943351952365670f, 0.567311899983420800f, 0.566680114279501710f, + 0.566047995212271560f, + 0.565415543153589770f, 0.564782758475511400f, 0.564149641550287680f, + 0.563516192750364910f, + 0.562882412448384550f, 0.562248301017183150f, 0.561613858829792420f, + 0.560979086259438260f, + 0.560343983679540860f, 0.559708551463714790f, 0.559072789985768480f, + 0.558436699619704100f, + 0.557800280739717100f, 0.557163533720196340f, 0.556526458935723720f, + 0.555889056761073920f, + 0.555251327571214090f, 0.554613271741304040f, 0.553974889646695610f, + 0.553336181662932410f, + 0.552697148165749770f, 0.552057789531074980f, 0.551418106135026060f, + 0.550778098353912230f, + 0.550137766564233630f, 0.549497111142680960f, 0.548856132466135290f, + 0.548214830911667780f, + 0.547573206856539870f, 0.546931260678202190f, 0.546288992754295210f, + 0.545646403462648590f, + 0.545003493181281160f, 0.544360262288400400f, 0.543716711162402390f, + 0.543072840181871850f, + 0.542428649725581360f, 0.541784140172491660f, 0.541139311901750910f, + 0.540494165292695230f, + 0.539848700724847700f, 0.539202918577918240f, 0.538556819231804210f, + 0.537910403066588990f, + 0.537263670462542530f, 0.536616621800121150f, 0.535969257459966710f, + 0.535321577822907010f, + 0.534673583269955510f, 0.534025274182310380f, 0.533376650941355560f, + 0.532727713928658810f, + 0.532078463525973540f, 0.531428900115236910f, 0.530779024078570250f, + 0.530128835798278850f, + 0.529478335656852090f, 0.528827524036961980f, 0.528176401321464370f, + 0.527524967893398200f, + 0.526873224135984700f, 0.526221170432628170f, 0.525568807166914680f, + 0.524916134722612890f, + 0.524263153483673470f, 0.523609863834228030f, 0.522956266158590140f, + 0.522302360841254700f, + 0.521648148266897090f, 0.520993628820373810f, 0.520338802886721960f, + 0.519683670851158520f, + 0.519028233099080970f, 0.518372490016066220f, 0.517716441987871150f, + 0.517060089400432130f, + 0.516403432639863990f, 0.515746472092461380f, 0.515089208144697270f, + 0.514431641183222930f, + 0.513773771594868030f, 0.513115599766640560f, 0.512457126085725800f, + 0.511798350939487000f, + 0.511139274715464390f, 0.510479897801375700f, 0.509820220585115560f, + 0.509160243454754750f, + 0.508499966798540810f, 0.507839391004897940f, 0.507178516462425290f, + 0.506517343559898530f, + 0.505855872686268860f, 0.505194104230662240f, 0.504532038582380380f, + 0.503869676130898950f, + 0.503207017265869030f, 0.502544062377115800f, 0.501880811854638400f, + 0.501217266088609950f, + 0.500553425469377640f, 0.499889290387461380f, 0.499224861233555030f, + 0.498560138398525200f, + 0.497895122273410930f, 0.497229813249424340f, 0.496564211717949340f, + 0.495898318070542240f, + 0.495232132698931350f, 0.494565655995016010f, 0.493898888350867430f, + 0.493231830158728070f, + 0.492564481811010650f, 0.491896843700299240f, 0.491228916219348330f, + 0.490560699761082080f, + 0.489892194718595300f, 0.489223401485152030f, 0.488554320454186230f, + 0.487884952019301210f, + 0.487215296574268820f, 0.486545354513030270f, 0.485875126229695420f, + 0.485204612118541880f, + 0.484533812574016120f, 0.483862727990732320f, 0.483191358763471910f, + 0.482519705287184520f, + 0.481847767956986080f, 0.481175547168160360f, 0.480503043316157670f, + 0.479830256796594250f, + 0.479157188005253310f, 0.478483837338084080f, 0.477810205191201040f, + 0.477136291960884750f, + 0.476462098043581310f, 0.475787623835901120f, 0.475112869734620470f, + 0.474437836136679340f, + 0.473762523439182850f, 0.473086932039400220f, 0.472411062334764100f, + 0.471734914722871430f, + 0.471058489601482610f, 0.470381787368520710f, 0.469704808422072460f, + 0.469027553160387240f, + 0.468350021981876530f, 0.467672215285114710f, 0.466994133468838110f, + 0.466315776931944480f, + 0.465637146073493770f, 0.464958241292706740f, 0.464279062988965760f, + 0.463599611561814120f, + 0.462919887410955130f, 0.462239890936253280f, 0.461559622537733190f, + 0.460879082615578690f, + 0.460198271570134270f, 0.459517189801903590f, 0.458835837711549120f, + 0.458154215699893230f, + 0.457472324167916110f, 0.456790163516757220f, 0.456107734147714220f, + 0.455425036462242420f, + 0.454742070861955450f, 0.454058837748624540f, 0.453375337524177750f, + 0.452691570590700860f, + 0.452007537350436530f, 0.451323238205783520f, 0.450638673559297760f, + 0.449953843813690580f, + 0.449268749371829920f, 0.448583390636739300f, 0.447897768011597360f, + 0.447211881899738260f, + 0.446525732704651400f, 0.445839320829980350f, 0.445152646679523590f, + 0.444465710657234110f, + 0.443778513167218280f, 0.443091054613736990f, 0.442403335401204130f, + 0.441715355934187310f, + 0.441027116617407340f, 0.440338617855737300f, 0.439649860054203420f, + 0.438960843617984430f, + 0.438271568952410480f, 0.437582036462964340f, 0.436892246555280470f, + 0.436202199635143950f, + 0.435511896108492170f, 0.434821336381412350f, 0.434130520860143310f, + 0.433439449951074200f, + 0.432748124060743760f, 0.432056543595841450f, 0.431364708963206440f, + 0.430672620569826860f, + 0.429980278822840570f, 0.429287684129534720f, 0.428594836897344400f, + 0.427901737533854240f, + 0.427208386446796370f, 0.426514784044051520f, 0.425820930733648350f, + 0.425126826923762410f, + 0.424432473022717420f, 0.423737869438983950f, 0.423043016581179100f, + 0.422347914858067000f, + 0.421652564678558380f, 0.420956966451709440f, 0.420261120586723050f, + 0.419565027492946940f, + 0.418868687579875110f, 0.418172101257146430f, 0.417475268934544340f, + 0.416778191021997590f, + 0.416080867929579320f, 0.415383300067506290f, 0.414685487846140010f, + 0.413987431675985510f, + 0.413289131967690960f, 0.412590589132048380f, 0.411891803579992220f, + 0.411192775722600160f, + 0.410493505971092520f, 0.409793994736831200f, 0.409094242431320920f, + 0.408394249466208110f, + 0.407694016253280170f, 0.406993543204466460f, 0.406292830731837470f, + 0.405591879247603870f, + 0.404890689164117750f, 0.404189260893870750f, 0.403487594849495310f, + 0.402785691443763640f, + 0.402083551089587040f, 0.401381174200016790f, 0.400678561188243350f, + 0.399975712467595390f, + 0.399272628451540930f, 0.398569309553686360f, 0.397865756187775750f, + 0.397161968767691720f, + 0.396457947707453960f, 0.395753693421220080f, 0.395049206323284880f, + 0.394344486828079650f, + 0.393639535350172880f, 0.392934352304269600f, 0.392228938105210370f, + 0.391523293167972350f, + 0.390817417907668610f, 0.390111312739546910f, 0.389404978078991100f, + 0.388698414341519250f, + 0.387991621942784910f, 0.387284601298575890f, 0.386577352824813980f, + 0.385869876937555310f, + 0.385162174052989970f, 0.384454244587440870f, 0.383746088957365010f, + 0.383037707579352130f, + 0.382329100870124510f, 0.381620269246537520f, 0.380911213125578130f, + 0.380201932924366050f, + 0.379492429060152740f, 0.378782701950320600f, 0.378072752012383990f, + 0.377362579663988450f, + 0.376652185322909620f, 0.375941569407054420f, 0.375230732334460030f, + 0.374519674523293210f, + 0.373808396391851370f, 0.373096898358560690f, 0.372385180841977360f, + 0.371673244260786630f, + 0.370961089033802040f, 0.370248715579966360f, 0.369536124318350760f, + 0.368823315668153960f, + 0.368110290048703050f, 0.367397047879452820f, 0.366683589579984930f, + 0.365969915570008910f, + 0.365256026269360380f, 0.364541922098002180f, 0.363827603476023610f, + 0.363113070823639530f, + 0.362398324561191310f, 0.361683365109145950f, 0.360968192888095290f, + 0.360252808318756830f, + 0.359537211821973180f, 0.358821403818710860f, 0.358105384730061760f, + 0.357389154977241000f, + 0.356672714981588260f, 0.355956065164567010f, 0.355239205947763370f, + 0.354522137752887430f, + 0.353804861001772160f, 0.353087376116372530f, 0.352369683518766630f, + 0.351651783631154680f, + 0.350933676875858360f, 0.350215363675321740f, 0.349496844452109600f, + 0.348778119628908420f, + 0.348059189628525780f, 0.347340054873889190f, 0.346620715788047320f, + 0.345901172794169100f, + 0.345181426315542610f, 0.344461476775576480f, 0.343741324597798600f, + 0.343020970205855540f, + 0.342300414023513690f, 0.341579656474657210f, 0.340858697983289440f, + 0.340137538973531880f, + 0.339416179869623410f, 0.338694621095921190f, 0.337972863076899830f, + 0.337250906237150650f, + 0.336528751001382350f, 0.335806397794420560f, 0.335083847041206580f, + 0.334361099166798900f, + 0.333638154596370920f, 0.332915013755212650f, 0.332191677068729320f, + 0.331468144962440920f, + 0.330744417861982890f, 0.330020496193105530f, 0.329296380381672800f, + 0.328572070853663690f, + 0.327847568035170960f, 0.327122872352400510f, 0.326397984231672660f, + 0.325672904099419900f, + 0.324947632382188430f, 0.324222169506637130f, 0.323496515899536760f, + 0.322770671987770710f, + 0.322044638198334620f, 0.321318414958334910f, 0.320592002694990330f, + 0.319865401835630610f, + 0.319138612807695900f, 0.318411636038737960f, 0.317684471956418020f, + 0.316957120988508150f, + 0.316229583562890490f, 0.315501860107556040f, 0.314773951050606070f, + 0.314045856820250820f, + 0.313317577844809070f, 0.312589114552708660f, 0.311860467372486130f, + 0.311131636732785270f, + 0.310402623062358880f, 0.309673426790066490f, 0.308944048344875710f, + 0.308214488155861220f, + 0.307484746652204160f, 0.306754824263192780f, 0.306024721418221900f, + 0.305294438546791720f, + 0.304563976078509050f, 0.303833334443086470f, 0.303102514070341060f, + 0.302371515390196130f, + 0.301640338832678880f, 0.300908984827921890f, 0.300177453806162120f, + 0.299445746197739950f, + 0.298713862433100390f, 0.297981802942791920f, 0.297249568157465890f, + 0.296517158507877410f, + 0.295784574424884370f, 0.295051816339446720f, 0.294318884682627570f, + 0.293585779885591310f, + 0.292852502379604810f, 0.292119052596036540f, 0.291385430966355720f, + 0.290651637922133220f, + 0.289917673895040860f, 0.289183539316850310f, 0.288449234619434170f, + 0.287714760234765280f, + 0.286980116594915570f, 0.286245304132057120f, 0.285510323278461380f, + 0.284775174466498300f, + 0.284039858128637360f, 0.283304374697445790f, 0.282568724605589740f, + 0.281832908285833460f, + 0.281096926171038320f, 0.280360778694163810f, 0.279624466288266700f, + 0.278887989386500280f, + 0.278151348422115090f, 0.277414543828458200f, 0.276677576038972420f, + 0.275940445487197320f, + 0.275203152606767370f, 0.274465697831413220f, 0.273728081594960650f, + 0.272990304331329980f, + 0.272252366474536660f, 0.271514268458690810f, 0.270776010717996010f, + 0.270037593686750510f, + 0.269299017799346230f, 0.268560283490267890f, 0.267821391194094320f, + 0.267082341345496350f, + 0.266343134379238180f, 0.265603770730176440f, 0.264864250833259320f, + 0.264124575123527490f, + 0.263384744036113390f, 0.262644758006240100f, 0.261904617469222560f, + 0.261164322860466590f, + 0.260423874615468010f, 0.259683273169813930f, 0.258942518959180580f, + 0.258201612419334870f, + 0.257460553986133210f, 0.256719344095520720f, 0.255977983183532380f, + 0.255236471686291820f, + 0.254494810040010790f, 0.253752998680989940f, 0.253011038045617980f, + 0.252268928570370810f, + 0.251526670691812780f, 0.250784264846594550f, 0.250041711471454650f, + 0.249299011003218300f, + 0.248556163878796620f, 0.247813170535187620f, 0.247070031409475370f, + 0.246326746938829060f, + 0.245583317560504000f, 0.244839743711840750f, 0.244096025830264210f, + 0.243352164353284880f, + 0.242608159718496890f, 0.241864012363579210f, 0.241119722726294730f, + 0.240375291244489500f, + 0.239630718356093560f, 0.238886004499120170f, 0.238141150111664870f, + 0.237396155631906550f, + 0.236651021498106460f, 0.235905748148607370f, 0.235160336021834860f, + 0.234414785556295250f, + 0.233669097190576820f, 0.232923271363349120f, 0.232177308513361770f, + 0.231431209079445730f, + 0.230684973500512310f, 0.229938602215552260f, 0.229192095663636740f, + 0.228445454283916550f, + 0.227698678515621170f, 0.226951768798059980f, 0.226204725570620270f, + 0.225457549272768540f, + 0.224710240344049570f, 0.223962799224085520f, 0.223215226352576960f, + 0.222467522169301990f, + 0.221719687114115240f, 0.220971721626949060f, 0.220223626147812460f, + 0.219475401116790340f, + 0.218727046974044600f, 0.217978564159812290f, 0.217229953114406790f, + 0.216481214278216900f, + 0.215732348091705940f, 0.214983354995412820f, 0.214234235429951100f, + 0.213484989836008080f, + 0.212735618654345870f, 0.211986122325800410f, 0.211236501291280710f, + 0.210486755991769890f, + 0.209736886868323370f, 0.208986894362070070f, 0.208236778914211470f, + 0.207486540966020700f, + 0.206736180958843660f, 0.205985699334098050f, 0.205235096533272380f, + 0.204484372997927180f, + 0.203733529169694010f, 0.202982565490274460f, 0.202231482401441620f, + 0.201480280345037820f, + 0.200728959762976140f, 0.199977521097239290f, 0.199225964789878890f, + 0.198474291283016360f, + 0.197722501018842030f, 0.196970594439614370f, 0.196218571987660850f, + 0.195466434105377090f, + 0.194714181235225990f, 0.193961813819739010f, 0.193209332301514080f, + 0.192456737123216840f, + 0.191704028727579940f, 0.190951207557401860f, 0.190198274055548120f, + 0.189445228664950340f, + 0.188692071828605260f, 0.187938803989575850f, 0.187185425590990440f, + 0.186431937076041640f, + 0.185678338887987790f, 0.184924631470150870f, 0.184170815265917720f, + 0.183416890718739230f, + 0.182662858272129360f, 0.181908718369666160f, 0.181154471454990920f, + 0.180400117971807270f, + 0.179645658363882100f, 0.178891093075044830f, 0.178136422549186320f, + 0.177381647230260200f, + 0.176626767562280960f, 0.175871783989325040f, 0.175116696955530060f, + 0.174361506905093830f, + 0.173606214282275410f, 0.172850819531394200f, 0.172095323096829040f, + 0.171339725423019260f, + 0.170584026954463700f, 0.169828228135719880f, 0.169072329411405180f, + 0.168316331226194910f, + 0.167560234024823590f, 0.166804038252083870f, 0.166047744352825850f, + 0.165291352771957970f, + 0.164534863954446110f, 0.163778278345312690f, 0.163021596389637810f, + 0.162264818532558110f, + 0.161507945219266150f, 0.160750976895011390f, 0.159993914005098350f, + 0.159236756994887850f, + 0.158479506309796100f, 0.157722162395293690f, 0.156964725696906750f, + 0.156207196660216040f, + 0.155449575730855880f, 0.154691863354515400f, 0.153934059976937460f, + 0.153176166043917870f, + 0.152418182001306500f, 0.151660108295005400f, 0.150901945370970040f, + 0.150143693675208330f, + 0.149385353653779810f, 0.148626925752796540f, 0.147868410418422360f, + 0.147109808096871850f, + 0.146351119234411440f, 0.145592344277358450f, 0.144833483672080240f, + 0.144074537864995330f, + 0.143315507302571590f, 0.142556392431327340f, 0.141797193697830530f, + 0.141037911548697770f, + 0.140278546430595420f, 0.139519098790238600f, 0.138759569074390380f, + 0.137999957729862760f, + 0.137240265203515700f, 0.136480491942256310f, 0.135720638393040080f, + 0.134960705002868830f, + 0.134200692218792020f, 0.133440600487905820f, 0.132680430257352130f, + 0.131920181974319760f, + 0.131159856086043410f, 0.130399453039802740f, 0.129638973282923540f, + 0.128878417262776660f, + 0.128117785426777150f, 0.127357078222385570f, 0.126596296097105960f, + 0.125835439498487020f, + 0.125074508874121300f, 0.124313504671644300f, 0.123552427338735370f, + 0.122791277323116900f, + 0.122030055072553410f, 0.121268761034852550f, 0.120507395657864240f, + 0.119745959389479630f, + 0.118984452677632520f, 0.118222875970297250f, 0.117461229715489990f, + 0.116699514361267840f, + 0.115937730355727850f, 0.115175878147008180f, 0.114413958183287050f, + 0.113651970912781920f, + 0.112889916783750470f, 0.112127796244489750f, 0.111365609743335190f, + 0.110603357728661910f, + 0.109841040648882680f, 0.109078658952449240f, 0.108316213087851300f, + 0.107553703503615710f, + 0.106791130648307380f, 0.106028494970528530f, 0.105265796918917650f, + 0.104503036942150550f, + 0.103740215488939480f, 0.102977333008032250f, 0.102214389948213370f, + 0.101451386758302160f, + 0.100688323887153970f, 0.099925201783659226f, 0.099162020896742573f, + 0.098398781675363881f, + 0.097635484568517339f, 0.096872130025230527f, 0.096108718494565468f, + 0.095345250425617742f, + 0.094581726267515473f, 0.093818146469420494f, 0.093054511480527333f, + 0.092290821750062355f, + 0.091527077727284981f, 0.090763279861485704f, 0.089999428601987341f, + 0.089235524398144139f, + 0.088471567699340822f, 0.087707558954993645f, 0.086943498614549489f, + 0.086179387127484922f, + 0.085415224943307277f, 0.084651012511553700f, 0.083886750281790226f, + 0.083122438703613077f, + 0.082358078226646619f, 0.081593669300544638f, 0.080829212374989468f, + 0.080064707899690932f, + 0.079300156324387569f, 0.078535558098845590f, 0.077770913672857989f, + 0.077006223496245585f, + 0.076241488018856149f, 0.075476707690563416f, 0.074711882961268378f, + 0.073947014280897269f, + 0.073182102099402888f, 0.072417146866763538f, 0.071652149032982254f, + 0.070887109048087787f, + 0.070122027362133646f, 0.069356904425197236f, 0.068591740687380900f, + 0.067826536598810966f, + 0.067061292609636836f, 0.066296009170032283f, 0.065530686730193397f, + 0.064765325740339871f, + 0.063999926650714078f, 0.063234489911580136f, 0.062469015973224969f, + 0.061703505285957416f, + 0.060937958300107238f, 0.060172375466026218f, 0.059406757234087247f, + 0.058641104054683348f, + 0.057875416378229017f, 0.057109694655158132f, 0.056343939335925283f, + 0.055578150871004817f, + 0.054812329710889909f, 0.054046476306093640f, 0.053280591107148056f, + 0.052514674564603257f, + 0.051748727129028414f, 0.050982749251010900f, 0.050216741381155325f, + 0.049450703970084824f, + 0.048684637468439020f, 0.047918542326875327f, 0.047152418996068000f, + 0.046386267926707213f, + 0.045620089569500123f, 0.044853884375169933f, 0.044087652794454979f, + 0.043321395278109784f, + 0.042555112276904117f, 0.041788804241622082f, 0.041022471623063397f, + 0.040256114872041358f, + 0.039489734439384118f, 0.038723330775933762f, 0.037956904332545366f, + 0.037190455560088091f, + 0.036423984909444228f, 0.035657492831508264f, 0.034890979777187955f, + 0.034124446197403423f, + 0.033357892543086159f, 0.032591319265180385f, 0.031824726814640963f, + 0.031058115642434700f, + 0.030291486199539423f, 0.029524838936943035f, 0.028758174305644590f, + 0.027991492756653365f, + 0.027224794740987910f, 0.026458080709677145f, 0.025691351113759395f, + 0.024924606404281485f, + 0.024157847032300020f, 0.023391073448879338f, 0.022624286105092803f, + 0.021857485452021874f, + 0.021090671940755180f, 0.020323846022389572f, 0.019557008148029204f, + 0.018790158768784596f, + 0.018023298335773701f, 0.017256427300120978f, 0.016489546112956454f, + 0.015722655225417017f, + 0.014955755088644378f, 0.014188846153786343f, 0.013421928871995907f, + 0.012655003694430301f, + 0.011888071072252072f, 0.011121131456628141f, 0.010354185298728884f, + 0.009587233049729183f, + 0.008820275160807512f, 0.008053312083144991f, 0.007286344267926684f, + 0.006519372166339549f, + 0.005752396229573737f, 0.004985416908821652f, 0.004218434655277024f, + 0.003451449920135975f, + 0.002684463154596083f, 0.001917474809855460f, 0.001150485337113809f, + 0.000383495187571497f +}; + +/** + * @brief Initialization function for the floating-point DCT4/IDCT4. + * @param[in,out] *S points to an instance of floating-point DCT4/IDCT4 structure. + * @param[in] *S_RFFT points to an instance of floating-point RFFT/RIFFT structure. + * @param[in] *S_CFFT points to an instance of floating-point CFFT/CIFFT structure. + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported transform length. + * \par Normalizing factor: + * The normalizing factor is sqrt(2/N), which depends on the size of transform N. + * Floating-point normalizing factors are mentioned in the table below for different DCT sizes: + * \image html dct4NormalizingF32Table.gif + */ + +arm_status arm_dct4_init_f32( + arm_dct4_instance_f32 * S, + arm_rfft_instance_f32 * S_RFFT, + arm_cfft_radix4_instance_f32 * S_CFFT, + uint16_t N, + uint16_t Nby2, + float32_t normalize) +{ + /* Initialize the default arm status */ + arm_status status = ARM_MATH_SUCCESS; + + /* Initializing the pointer array with the weight table base addresses of different lengths */ + float32_t *twiddlePtr[3] = + { (float32_t *) Weights_128, (float32_t *) Weights_512, + (float32_t *) Weights_2048 + }; + + /* Initializing the pointer array with the cos factor table base addresses of different lengths */ + float32_t *pCosFactor[3] = + { (float32_t *) cos_factors_128, (float32_t *) cos_factors_512, + (float32_t *) cos_factors_2048 + }; + + /* Initialize the DCT4 length */ + S->N = N; + + /* Initialize the half of DCT4 length */ + S->Nby2 = Nby2; + + /* Initialize the DCT4 Normalizing factor */ + S->normalize = normalize; + + /* Initialize Real FFT Instance */ + S->pRfft = S_RFFT; + + /* Initialize Complex FFT Instance */ + S->pCfft = S_CFFT; + + switch (N) + { + /* Initialize the table modifier values */ + case 2048u: + S->pTwiddle = twiddlePtr[2]; + S->pCosFactor = pCosFactor[2]; + break; + case 512u: + S->pTwiddle = twiddlePtr[1]; + S->pCosFactor = pCosFactor[1]; + break; + case 128u: + S->pTwiddle = twiddlePtr[0]; + S->pCosFactor = pCosFactor[0]; + break; + default: + status = ARM_MATH_ARGUMENT_ERROR; + } + + /* Initialize the RFFT/RIFFT */ + arm_rfft_init_f32(S->pRfft, S->pCfft, S->N, 0u, 1u); + + /* return the status of DCT4 Init function */ + return (status); +} + +/** + * @} end of DCT4_IDCT4 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q15.c index 25ed1e8ed..260f1b77f 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q15.c @@ -1,1190 +1,1190 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_init_q15.c -* -* Description: Initialization function of DCT-4 & IDCT4 Q15 -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/* -* @brief Weights Table -*/ - -/** -* \par -* Weights tables are generated using the formula :
weights[n] = e^(-j*n*pi/(2*N))
-* \par -* C command to generate the table -*
   
-* for(i = 0; i< N; i++)   
-* {   
-*   weights[2*i]= cos(i*c);   
-*   weights[(2*i)+1]= -sin(i * c);   
-* } 
-* \par -* where N is the Number of weights to be calculated and c is pi/(2*N) -* \par -* Converted the output to q15 format by multiplying with 2^31 and saturated if required. -* \par -* In the tables below the real and imaginary values are placed alternatively, hence the -* array length is 2*N. -*/ - -static const q15_t WeightsQ15_128[256] = { - 0x7fff, 0x0, 0x7ffd, 0xfe6e, 0x7ff6, 0xfcdc, 0x7fe9, 0xfb4a, - 0x7fd8, 0xf9b9, 0x7fc2, 0xf827, 0x7fa7, 0xf696, 0x7f87, 0xf505, - 0x7f62, 0xf375, 0x7f38, 0xf1e5, 0x7f09, 0xf055, 0x7ed5, 0xeec7, - 0x7e9d, 0xed38, 0x7e5f, 0xebab, 0x7e1d, 0xea1e, 0x7dd6, 0xe893, - 0x7d8a, 0xe708, 0x7d39, 0xe57e, 0x7ce3, 0xe3f5, 0x7c89, 0xe26d, - 0x7c29, 0xe0e7, 0x7bc5, 0xdf61, 0x7b5d, 0xdddd, 0x7aef, 0xdc5a, - 0x7a7d, 0xdad8, 0x7a05, 0xd958, 0x798a, 0xd7da, 0x7909, 0xd65d, - 0x7884, 0xd4e1, 0x77fa, 0xd368, 0x776c, 0xd1ef, 0x76d9, 0xd079, - 0x7641, 0xcf05, 0x75a5, 0xcd92, 0x7504, 0xcc22, 0x745f, 0xcab3, - 0x73b5, 0xc946, 0x7307, 0xc7dc, 0x7255, 0xc674, 0x719e, 0xc50e, - 0x70e2, 0xc3aa, 0x7023, 0xc248, 0x6f5f, 0xc0e9, 0x6e96, 0xbf8d, - 0x6dca, 0xbe32, 0x6cf9, 0xbcdb, 0x6c24, 0xbb86, 0x6b4a, 0xba33, - 0x6a6d, 0xb8e4, 0x698c, 0xb797, 0x68a6, 0xb64c, 0x67bd, 0xb505, - 0x66cf, 0xb3c1, 0x65dd, 0xb27f, 0x64e8, 0xb141, 0x63ef, 0xb005, - 0x62f2, 0xaecd, 0x61f1, 0xad97, 0x60ec, 0xac65, 0x5fe3, 0xab36, - 0x5ed7, 0xaa0b, 0x5dc7, 0xa8e3, 0x5cb4, 0xa7be, 0x5b9d, 0xa69c, - 0x5a82, 0xa57e, 0x5964, 0xa463, 0x5842, 0xa34c, 0x571d, 0xa239, - 0x55f5, 0xa129, 0x54ca, 0xa01d, 0x539b, 0x9f14, 0x5269, 0x9e0f, - 0x5133, 0x9d0e, 0x4ffb, 0x9c11, 0x4ebf, 0x9b18, 0x4d81, 0x9a23, - 0x4c3f, 0x9931, 0x4afb, 0x9843, 0x49b4, 0x975a, 0x4869, 0x9674, - 0x471c, 0x9593, 0x45cd, 0x94b6, 0x447a, 0x93dc, 0x4325, 0x9307, - 0x41ce, 0x9236, 0x4073, 0x916a, 0x3f17, 0x90a1, 0x3db8, 0x8fdd, - 0x3c56, 0x8f1e, 0x3af2, 0x8e62, 0x398c, 0x8dab, 0x3824, 0x8cf9, - 0x36ba, 0x8c4b, 0x354d, 0x8ba1, 0x33de, 0x8afc, 0x326e, 0x8a5b, - 0x30fb, 0x89bf, 0x2f87, 0x8927, 0x2e11, 0x8894, 0x2c98, 0x8806, - 0x2b1f, 0x877c, 0x29a3, 0x86f7, 0x2826, 0x8676, 0x26a8, 0x85fb, - 0x2528, 0x8583, 0x23a6, 0x8511, 0x2223, 0x84a3, 0x209f, 0x843b, - 0x1f19, 0x83d7, 0x1d93, 0x8377, 0x1c0b, 0x831d, 0x1a82, 0x82c7, - 0x18f8, 0x8276, 0x176d, 0x822a, 0x15e2, 0x81e3, 0x1455, 0x81a1, - 0x12c8, 0x8163, 0x1139, 0x812b, 0xfab, 0x80f7, 0xe1b, 0x80c8, - 0xc8b, 0x809e, 0xafb, 0x8079, 0x96a, 0x8059, 0x7d9, 0x803e, - 0x647, 0x8028, 0x4b6, 0x8017, 0x324, 0x800a, 0x192, 0x8003, -}; - -static const q15_t WeightsQ15_512[1024] = { - 0x7fff, 0x0, 0x7fff, 0xff9c, 0x7fff, 0xff37, 0x7ffe, 0xfed3, - 0x7ffd, 0xfe6e, 0x7ffc, 0xfe0a, 0x7ffa, 0xfda5, 0x7ff8, 0xfd41, - 0x7ff6, 0xfcdc, 0x7ff3, 0xfc78, 0x7ff0, 0xfc13, 0x7fed, 0xfbaf, - 0x7fe9, 0xfb4a, 0x7fe5, 0xfae6, 0x7fe1, 0xfa81, 0x7fdd, 0xfa1d, - 0x7fd8, 0xf9b9, 0x7fd3, 0xf954, 0x7fce, 0xf8f0, 0x7fc8, 0xf88b, - 0x7fc2, 0xf827, 0x7fbc, 0xf7c3, 0x7fb5, 0xf75e, 0x7fae, 0xf6fa, - 0x7fa7, 0xf696, 0x7f9f, 0xf632, 0x7f97, 0xf5cd, 0x7f8f, 0xf569, - 0x7f87, 0xf505, 0x7f7e, 0xf4a1, 0x7f75, 0xf43d, 0x7f6b, 0xf3d9, - 0x7f62, 0xf375, 0x7f58, 0xf311, 0x7f4d, 0xf2ad, 0x7f43, 0xf249, - 0x7f38, 0xf1e5, 0x7f2d, 0xf181, 0x7f21, 0xf11d, 0x7f15, 0xf0b9, - 0x7f09, 0xf055, 0x7efd, 0xeff2, 0x7ef0, 0xef8e, 0x7ee3, 0xef2a, - 0x7ed5, 0xeec7, 0x7ec8, 0xee63, 0x7eba, 0xedff, 0x7eab, 0xed9c, - 0x7e9d, 0xed38, 0x7e8e, 0xecd5, 0x7e7f, 0xec72, 0x7e6f, 0xec0e, - 0x7e5f, 0xebab, 0x7e4f, 0xeb48, 0x7e3f, 0xeae5, 0x7e2e, 0xea81, - 0x7e1d, 0xea1e, 0x7e0c, 0xe9bb, 0x7dfa, 0xe958, 0x7de8, 0xe8f6, - 0x7dd6, 0xe893, 0x7dc3, 0xe830, 0x7db0, 0xe7cd, 0x7d9d, 0xe76a, - 0x7d8a, 0xe708, 0x7d76, 0xe6a5, 0x7d62, 0xe643, 0x7d4e, 0xe5e0, - 0x7d39, 0xe57e, 0x7d24, 0xe51c, 0x7d0f, 0xe4b9, 0x7cf9, 0xe457, - 0x7ce3, 0xe3f5, 0x7ccd, 0xe393, 0x7cb7, 0xe331, 0x7ca0, 0xe2cf, - 0x7c89, 0xe26d, 0x7c71, 0xe20b, 0x7c5a, 0xe1aa, 0x7c42, 0xe148, - 0x7c29, 0xe0e7, 0x7c11, 0xe085, 0x7bf8, 0xe024, 0x7bdf, 0xdfc2, - 0x7bc5, 0xdf61, 0x7bac, 0xdf00, 0x7b92, 0xde9f, 0x7b77, 0xde3e, - 0x7b5d, 0xdddd, 0x7b42, 0xdd7c, 0x7b26, 0xdd1b, 0x7b0b, 0xdcbb, - 0x7aef, 0xdc5a, 0x7ad3, 0xdbf9, 0x7ab6, 0xdb99, 0x7a9a, 0xdb39, - 0x7a7d, 0xdad8, 0x7a5f, 0xda78, 0x7a42, 0xda18, 0x7a24, 0xd9b8, - 0x7a05, 0xd958, 0x79e7, 0xd8f9, 0x79c8, 0xd899, 0x79a9, 0xd839, - 0x798a, 0xd7da, 0x796a, 0xd77a, 0x794a, 0xd71b, 0x792a, 0xd6bc, - 0x7909, 0xd65d, 0x78e8, 0xd5fe, 0x78c7, 0xd59f, 0x78a6, 0xd540, - 0x7884, 0xd4e1, 0x7862, 0xd483, 0x7840, 0xd424, 0x781d, 0xd3c6, - 0x77fa, 0xd368, 0x77d7, 0xd309, 0x77b4, 0xd2ab, 0x7790, 0xd24d, - 0x776c, 0xd1ef, 0x7747, 0xd192, 0x7723, 0xd134, 0x76fe, 0xd0d7, - 0x76d9, 0xd079, 0x76b3, 0xd01c, 0x768e, 0xcfbf, 0x7668, 0xcf62, - 0x7641, 0xcf05, 0x761b, 0xcea8, 0x75f4, 0xce4b, 0x75cc, 0xcdef, - 0x75a5, 0xcd92, 0x757d, 0xcd36, 0x7555, 0xccda, 0x752d, 0xcc7e, - 0x7504, 0xcc22, 0x74db, 0xcbc6, 0x74b2, 0xcb6a, 0x7489, 0xcb0e, - 0x745f, 0xcab3, 0x7435, 0xca58, 0x740b, 0xc9fc, 0x73e0, 0xc9a1, - 0x73b5, 0xc946, 0x738a, 0xc8ec, 0x735f, 0xc891, 0x7333, 0xc836, - 0x7307, 0xc7dc, 0x72db, 0xc782, 0x72af, 0xc728, 0x7282, 0xc6ce, - 0x7255, 0xc674, 0x7227, 0xc61a, 0x71fa, 0xc5c0, 0x71cc, 0xc567, - 0x719e, 0xc50e, 0x716f, 0xc4b4, 0x7141, 0xc45b, 0x7112, 0xc403, - 0x70e2, 0xc3aa, 0x70b3, 0xc351, 0x7083, 0xc2f9, 0x7053, 0xc2a0, - 0x7023, 0xc248, 0x6ff2, 0xc1f0, 0x6fc1, 0xc198, 0x6f90, 0xc141, - 0x6f5f, 0xc0e9, 0x6f2d, 0xc092, 0x6efb, 0xc03b, 0x6ec9, 0xbfe3, - 0x6e96, 0xbf8d, 0x6e63, 0xbf36, 0x6e30, 0xbedf, 0x6dfd, 0xbe89, - 0x6dca, 0xbe32, 0x6d96, 0xbddc, 0x6d62, 0xbd86, 0x6d2d, 0xbd30, - 0x6cf9, 0xbcdb, 0x6cc4, 0xbc85, 0x6c8f, 0xbc30, 0x6c59, 0xbbdb, - 0x6c24, 0xbb86, 0x6bee, 0xbb31, 0x6bb8, 0xbadc, 0x6b81, 0xba88, - 0x6b4a, 0xba33, 0x6b13, 0xb9df, 0x6adc, 0xb98b, 0x6aa5, 0xb937, - 0x6a6d, 0xb8e4, 0x6a35, 0xb890, 0x69fd, 0xb83d, 0x69c4, 0xb7ea, - 0x698c, 0xb797, 0x6953, 0xb744, 0x6919, 0xb6f1, 0x68e0, 0xb69f, - 0x68a6, 0xb64c, 0x686c, 0xb5fa, 0x6832, 0xb5a8, 0x67f7, 0xb557, - 0x67bd, 0xb505, 0x6782, 0xb4b4, 0x6746, 0xb462, 0x670b, 0xb411, - 0x66cf, 0xb3c1, 0x6693, 0xb370, 0x6657, 0xb31f, 0x661a, 0xb2cf, - 0x65dd, 0xb27f, 0x65a0, 0xb22f, 0x6563, 0xb1df, 0x6526, 0xb190, - 0x64e8, 0xb141, 0x64aa, 0xb0f1, 0x646c, 0xb0a2, 0x642d, 0xb054, - 0x63ef, 0xb005, 0x63b0, 0xafb7, 0x6371, 0xaf69, 0x6331, 0xaf1b, - 0x62f2, 0xaecd, 0x62b2, 0xae7f, 0x6271, 0xae32, 0x6231, 0xade4, - 0x61f1, 0xad97, 0x61b0, 0xad4b, 0x616f, 0xacfe, 0x612d, 0xacb2, - 0x60ec, 0xac65, 0x60aa, 0xac19, 0x6068, 0xabcd, 0x6026, 0xab82, - 0x5fe3, 0xab36, 0x5fa0, 0xaaeb, 0x5f5e, 0xaaa0, 0x5f1a, 0xaa55, - 0x5ed7, 0xaa0b, 0x5e93, 0xa9c0, 0x5e50, 0xa976, 0x5e0b, 0xa92c, - 0x5dc7, 0xa8e3, 0x5d83, 0xa899, 0x5d3e, 0xa850, 0x5cf9, 0xa807, - 0x5cb4, 0xa7be, 0x5c6e, 0xa775, 0x5c29, 0xa72c, 0x5be3, 0xa6e4, - 0x5b9d, 0xa69c, 0x5b56, 0xa654, 0x5b10, 0xa60d, 0x5ac9, 0xa5c5, - 0x5a82, 0xa57e, 0x5a3b, 0xa537, 0x59f3, 0xa4f0, 0x59ac, 0xa4aa, - 0x5964, 0xa463, 0x591c, 0xa41d, 0x58d4, 0xa3d7, 0x588b, 0xa392, - 0x5842, 0xa34c, 0x57f9, 0xa307, 0x57b0, 0xa2c2, 0x5767, 0xa27d, - 0x571d, 0xa239, 0x56d4, 0xa1f5, 0x568a, 0xa1b0, 0x5640, 0xa16d, - 0x55f5, 0xa129, 0x55ab, 0xa0e6, 0x5560, 0xa0a2, 0x5515, 0xa060, - 0x54ca, 0xa01d, 0x547e, 0x9fda, 0x5433, 0x9f98, 0x53e7, 0x9f56, - 0x539b, 0x9f14, 0x534e, 0x9ed3, 0x5302, 0x9e91, 0x52b5, 0x9e50, - 0x5269, 0x9e0f, 0x521c, 0x9dcf, 0x51ce, 0x9d8f, 0x5181, 0x9d4e, - 0x5133, 0x9d0e, 0x50e5, 0x9ccf, 0x5097, 0x9c8f, 0x5049, 0x9c50, - 0x4ffb, 0x9c11, 0x4fac, 0x9bd3, 0x4f5e, 0x9b94, 0x4f0f, 0x9b56, - 0x4ebf, 0x9b18, 0x4e70, 0x9ada, 0x4e21, 0x9a9d, 0x4dd1, 0x9a60, - 0x4d81, 0x9a23, 0x4d31, 0x99e6, 0x4ce1, 0x99a9, 0x4c90, 0x996d, - 0x4c3f, 0x9931, 0x4bef, 0x98f5, 0x4b9e, 0x98ba, 0x4b4c, 0x987e, - 0x4afb, 0x9843, 0x4aa9, 0x9809, 0x4a58, 0x97ce, 0x4a06, 0x9794, - 0x49b4, 0x975a, 0x4961, 0x9720, 0x490f, 0x96e7, 0x48bc, 0x96ad, - 0x4869, 0x9674, 0x4816, 0x963c, 0x47c3, 0x9603, 0x4770, 0x95cb, - 0x471c, 0x9593, 0x46c9, 0x955b, 0x4675, 0x9524, 0x4621, 0x94ed, - 0x45cd, 0x94b6, 0x4578, 0x947f, 0x4524, 0x9448, 0x44cf, 0x9412, - 0x447a, 0x93dc, 0x4425, 0x93a7, 0x43d0, 0x9371, 0x437b, 0x933c, - 0x4325, 0x9307, 0x42d0, 0x92d3, 0x427a, 0x929e, 0x4224, 0x926a, - 0x41ce, 0x9236, 0x4177, 0x9203, 0x4121, 0x91d0, 0x40ca, 0x919d, - 0x4073, 0x916a, 0x401d, 0x9137, 0x3fc5, 0x9105, 0x3f6e, 0x90d3, - 0x3f17, 0x90a1, 0x3ebf, 0x9070, 0x3e68, 0x903f, 0x3e10, 0x900e, - 0x3db8, 0x8fdd, 0x3d60, 0x8fad, 0x3d07, 0x8f7d, 0x3caf, 0x8f4d, - 0x3c56, 0x8f1e, 0x3bfd, 0x8eee, 0x3ba5, 0x8ebf, 0x3b4c, 0x8e91, - 0x3af2, 0x8e62, 0x3a99, 0x8e34, 0x3a40, 0x8e06, 0x39e6, 0x8dd9, - 0x398c, 0x8dab, 0x3932, 0x8d7e, 0x38d8, 0x8d51, 0x387e, 0x8d25, - 0x3824, 0x8cf9, 0x37ca, 0x8ccd, 0x376f, 0x8ca1, 0x3714, 0x8c76, - 0x36ba, 0x8c4b, 0x365f, 0x8c20, 0x3604, 0x8bf5, 0x35a8, 0x8bcb, - 0x354d, 0x8ba1, 0x34f2, 0x8b77, 0x3496, 0x8b4e, 0x343a, 0x8b25, - 0x33de, 0x8afc, 0x3382, 0x8ad3, 0x3326, 0x8aab, 0x32ca, 0x8a83, - 0x326e, 0x8a5b, 0x3211, 0x8a34, 0x31b5, 0x8a0c, 0x3158, 0x89e5, - 0x30fb, 0x89bf, 0x309e, 0x8998, 0x3041, 0x8972, 0x2fe4, 0x894d, - 0x2f87, 0x8927, 0x2f29, 0x8902, 0x2ecc, 0x88dd, 0x2e6e, 0x88b9, - 0x2e11, 0x8894, 0x2db3, 0x8870, 0x2d55, 0x884c, 0x2cf7, 0x8829, - 0x2c98, 0x8806, 0x2c3a, 0x87e3, 0x2bdc, 0x87c0, 0x2b7d, 0x879e, - 0x2b1f, 0x877c, 0x2ac0, 0x875a, 0x2a61, 0x8739, 0x2a02, 0x8718, - 0x29a3, 0x86f7, 0x2944, 0x86d6, 0x28e5, 0x86b6, 0x2886, 0x8696, - 0x2826, 0x8676, 0x27c7, 0x8657, 0x2767, 0x8638, 0x2707, 0x8619, - 0x26a8, 0x85fb, 0x2648, 0x85dc, 0x25e8, 0x85be, 0x2588, 0x85a1, - 0x2528, 0x8583, 0x24c7, 0x8566, 0x2467, 0x854a, 0x2407, 0x852d, - 0x23a6, 0x8511, 0x2345, 0x84f5, 0x22e5, 0x84da, 0x2284, 0x84be, - 0x2223, 0x84a3, 0x21c2, 0x8489, 0x2161, 0x846e, 0x2100, 0x8454, - 0x209f, 0x843b, 0x203e, 0x8421, 0x1fdc, 0x8408, 0x1f7b, 0x83ef, - 0x1f19, 0x83d7, 0x1eb8, 0x83be, 0x1e56, 0x83a6, 0x1df5, 0x838f, - 0x1d93, 0x8377, 0x1d31, 0x8360, 0x1ccf, 0x8349, 0x1c6d, 0x8333, - 0x1c0b, 0x831d, 0x1ba9, 0x8307, 0x1b47, 0x82f1, 0x1ae4, 0x82dc, - 0x1a82, 0x82c7, 0x1a20, 0x82b2, 0x19bd, 0x829e, 0x195b, 0x828a, - 0x18f8, 0x8276, 0x1896, 0x8263, 0x1833, 0x8250, 0x17d0, 0x823d, - 0x176d, 0x822a, 0x170a, 0x8218, 0x16a8, 0x8206, 0x1645, 0x81f4, - 0x15e2, 0x81e3, 0x157f, 0x81d2, 0x151b, 0x81c1, 0x14b8, 0x81b1, - 0x1455, 0x81a1, 0x13f2, 0x8191, 0x138e, 0x8181, 0x132b, 0x8172, - 0x12c8, 0x8163, 0x1264, 0x8155, 0x1201, 0x8146, 0x119d, 0x8138, - 0x1139, 0x812b, 0x10d6, 0x811d, 0x1072, 0x8110, 0x100e, 0x8103, - 0xfab, 0x80f7, 0xf47, 0x80eb, 0xee3, 0x80df, 0xe7f, 0x80d3, - 0xe1b, 0x80c8, 0xdb7, 0x80bd, 0xd53, 0x80b3, 0xcef, 0x80a8, - 0xc8b, 0x809e, 0xc27, 0x8095, 0xbc3, 0x808b, 0xb5f, 0x8082, - 0xafb, 0x8079, 0xa97, 0x8071, 0xa33, 0x8069, 0x9ce, 0x8061, - 0x96a, 0x8059, 0x906, 0x8052, 0x8a2, 0x804b, 0x83d, 0x8044, - 0x7d9, 0x803e, 0x775, 0x8038, 0x710, 0x8032, 0x6ac, 0x802d, - 0x647, 0x8028, 0x5e3, 0x8023, 0x57f, 0x801f, 0x51a, 0x801b, - 0x4b6, 0x8017, 0x451, 0x8013, 0x3ed, 0x8010, 0x388, 0x800d, - 0x324, 0x800a, 0x2bf, 0x8008, 0x25b, 0x8006, 0x1f6, 0x8004, - 0x192, 0x8003, 0x12d, 0x8002, 0xc9, 0x8001, 0x64, 0x8001, -}; - -static const q15_t WeightsQ15_2048[4096] = { - 0x7fff, 0x0, 0x7fff, 0xffe7, 0x7fff, 0xffce, 0x7fff, 0xffb5, - 0x7fff, 0xff9c, 0x7fff, 0xff83, 0x7fff, 0xff6a, 0x7fff, 0xff51, - 0x7fff, 0xff37, 0x7fff, 0xff1e, 0x7fff, 0xff05, 0x7ffe, 0xfeec, - 0x7ffe, 0xfed3, 0x7ffe, 0xfeba, 0x7ffe, 0xfea1, 0x7ffd, 0xfe88, - 0x7ffd, 0xfe6e, 0x7ffd, 0xfe55, 0x7ffc, 0xfe3c, 0x7ffc, 0xfe23, - 0x7ffc, 0xfe0a, 0x7ffb, 0xfdf1, 0x7ffb, 0xfdd8, 0x7ffa, 0xfdbe, - 0x7ffa, 0xfda5, 0x7ff9, 0xfd8c, 0x7ff9, 0xfd73, 0x7ff8, 0xfd5a, - 0x7ff8, 0xfd41, 0x7ff7, 0xfd28, 0x7ff7, 0xfd0f, 0x7ff6, 0xfcf5, - 0x7ff6, 0xfcdc, 0x7ff5, 0xfcc3, 0x7ff4, 0xfcaa, 0x7ff4, 0xfc91, - 0x7ff3, 0xfc78, 0x7ff2, 0xfc5f, 0x7ff2, 0xfc46, 0x7ff1, 0xfc2c, - 0x7ff0, 0xfc13, 0x7fef, 0xfbfa, 0x7fee, 0xfbe1, 0x7fee, 0xfbc8, - 0x7fed, 0xfbaf, 0x7fec, 0xfb96, 0x7feb, 0xfb7d, 0x7fea, 0xfb64, - 0x7fe9, 0xfb4a, 0x7fe8, 0xfb31, 0x7fe7, 0xfb18, 0x7fe6, 0xfaff, - 0x7fe5, 0xfae6, 0x7fe4, 0xfacd, 0x7fe3, 0xfab4, 0x7fe2, 0xfa9b, - 0x7fe1, 0xfa81, 0x7fe0, 0xfa68, 0x7fdf, 0xfa4f, 0x7fde, 0xfa36, - 0x7fdd, 0xfa1d, 0x7fdc, 0xfa04, 0x7fda, 0xf9eb, 0x7fd9, 0xf9d2, - 0x7fd8, 0xf9b9, 0x7fd7, 0xf9a0, 0x7fd6, 0xf986, 0x7fd4, 0xf96d, - 0x7fd3, 0xf954, 0x7fd2, 0xf93b, 0x7fd0, 0xf922, 0x7fcf, 0xf909, - 0x7fce, 0xf8f0, 0x7fcc, 0xf8d7, 0x7fcb, 0xf8be, 0x7fc9, 0xf8a5, - 0x7fc8, 0xf88b, 0x7fc6, 0xf872, 0x7fc5, 0xf859, 0x7fc3, 0xf840, - 0x7fc2, 0xf827, 0x7fc0, 0xf80e, 0x7fbf, 0xf7f5, 0x7fbd, 0xf7dc, - 0x7fbc, 0xf7c3, 0x7fba, 0xf7aa, 0x7fb8, 0xf791, 0x7fb7, 0xf778, - 0x7fb5, 0xf75e, 0x7fb3, 0xf745, 0x7fb1, 0xf72c, 0x7fb0, 0xf713, - 0x7fae, 0xf6fa, 0x7fac, 0xf6e1, 0x7faa, 0xf6c8, 0x7fa9, 0xf6af, - 0x7fa7, 0xf696, 0x7fa5, 0xf67d, 0x7fa3, 0xf664, 0x7fa1, 0xf64b, - 0x7f9f, 0xf632, 0x7f9d, 0xf619, 0x7f9b, 0xf600, 0x7f99, 0xf5e7, - 0x7f97, 0xf5cd, 0x7f95, 0xf5b4, 0x7f93, 0xf59b, 0x7f91, 0xf582, - 0x7f8f, 0xf569, 0x7f8d, 0xf550, 0x7f8b, 0xf537, 0x7f89, 0xf51e, - 0x7f87, 0xf505, 0x7f85, 0xf4ec, 0x7f82, 0xf4d3, 0x7f80, 0xf4ba, - 0x7f7e, 0xf4a1, 0x7f7c, 0xf488, 0x7f79, 0xf46f, 0x7f77, 0xf456, - 0x7f75, 0xf43d, 0x7f72, 0xf424, 0x7f70, 0xf40b, 0x7f6e, 0xf3f2, - 0x7f6b, 0xf3d9, 0x7f69, 0xf3c0, 0x7f67, 0xf3a7, 0x7f64, 0xf38e, - 0x7f62, 0xf375, 0x7f5f, 0xf35c, 0x7f5d, 0xf343, 0x7f5a, 0xf32a, - 0x7f58, 0xf311, 0x7f55, 0xf2f8, 0x7f53, 0xf2df, 0x7f50, 0xf2c6, - 0x7f4d, 0xf2ad, 0x7f4b, 0xf294, 0x7f48, 0xf27b, 0x7f45, 0xf262, - 0x7f43, 0xf249, 0x7f40, 0xf230, 0x7f3d, 0xf217, 0x7f3b, 0xf1fe, - 0x7f38, 0xf1e5, 0x7f35, 0xf1cc, 0x7f32, 0xf1b3, 0x7f2f, 0xf19a, - 0x7f2d, 0xf181, 0x7f2a, 0xf168, 0x7f27, 0xf14f, 0x7f24, 0xf136, - 0x7f21, 0xf11d, 0x7f1e, 0xf104, 0x7f1b, 0xf0eb, 0x7f18, 0xf0d2, - 0x7f15, 0xf0b9, 0x7f12, 0xf0a0, 0x7f0f, 0xf087, 0x7f0c, 0xf06e, - 0x7f09, 0xf055, 0x7f06, 0xf03c, 0x7f03, 0xf023, 0x7f00, 0xf00b, - 0x7efd, 0xeff2, 0x7ef9, 0xefd9, 0x7ef6, 0xefc0, 0x7ef3, 0xefa7, - 0x7ef0, 0xef8e, 0x7eed, 0xef75, 0x7ee9, 0xef5c, 0x7ee6, 0xef43, - 0x7ee3, 0xef2a, 0x7edf, 0xef11, 0x7edc, 0xeef8, 0x7ed9, 0xeedf, - 0x7ed5, 0xeec7, 0x7ed2, 0xeeae, 0x7ecf, 0xee95, 0x7ecb, 0xee7c, - 0x7ec8, 0xee63, 0x7ec4, 0xee4a, 0x7ec1, 0xee31, 0x7ebd, 0xee18, - 0x7eba, 0xedff, 0x7eb6, 0xede7, 0x7eb3, 0xedce, 0x7eaf, 0xedb5, - 0x7eab, 0xed9c, 0x7ea8, 0xed83, 0x7ea4, 0xed6a, 0x7ea1, 0xed51, - 0x7e9d, 0xed38, 0x7e99, 0xed20, 0x7e95, 0xed07, 0x7e92, 0xecee, - 0x7e8e, 0xecd5, 0x7e8a, 0xecbc, 0x7e86, 0xeca3, 0x7e83, 0xec8a, - 0x7e7f, 0xec72, 0x7e7b, 0xec59, 0x7e77, 0xec40, 0x7e73, 0xec27, - 0x7e6f, 0xec0e, 0x7e6b, 0xebf5, 0x7e67, 0xebdd, 0x7e63, 0xebc4, - 0x7e5f, 0xebab, 0x7e5b, 0xeb92, 0x7e57, 0xeb79, 0x7e53, 0xeb61, - 0x7e4f, 0xeb48, 0x7e4b, 0xeb2f, 0x7e47, 0xeb16, 0x7e43, 0xeafd, - 0x7e3f, 0xeae5, 0x7e3b, 0xeacc, 0x7e37, 0xeab3, 0x7e32, 0xea9a, - 0x7e2e, 0xea81, 0x7e2a, 0xea69, 0x7e26, 0xea50, 0x7e21, 0xea37, - 0x7e1d, 0xea1e, 0x7e19, 0xea06, 0x7e14, 0xe9ed, 0x7e10, 0xe9d4, - 0x7e0c, 0xe9bb, 0x7e07, 0xe9a3, 0x7e03, 0xe98a, 0x7dff, 0xe971, - 0x7dfa, 0xe958, 0x7df6, 0xe940, 0x7df1, 0xe927, 0x7ded, 0xe90e, - 0x7de8, 0xe8f6, 0x7de4, 0xe8dd, 0x7ddf, 0xe8c4, 0x7dda, 0xe8ab, - 0x7dd6, 0xe893, 0x7dd1, 0xe87a, 0x7dcd, 0xe861, 0x7dc8, 0xe849, - 0x7dc3, 0xe830, 0x7dbf, 0xe817, 0x7dba, 0xe7fe, 0x7db5, 0xe7e6, - 0x7db0, 0xe7cd, 0x7dac, 0xe7b4, 0x7da7, 0xe79c, 0x7da2, 0xe783, - 0x7d9d, 0xe76a, 0x7d98, 0xe752, 0x7d94, 0xe739, 0x7d8f, 0xe720, - 0x7d8a, 0xe708, 0x7d85, 0xe6ef, 0x7d80, 0xe6d6, 0x7d7b, 0xe6be, - 0x7d76, 0xe6a5, 0x7d71, 0xe68d, 0x7d6c, 0xe674, 0x7d67, 0xe65b, - 0x7d62, 0xe643, 0x7d5d, 0xe62a, 0x7d58, 0xe611, 0x7d53, 0xe5f9, - 0x7d4e, 0xe5e0, 0x7d49, 0xe5c8, 0x7d43, 0xe5af, 0x7d3e, 0xe596, - 0x7d39, 0xe57e, 0x7d34, 0xe565, 0x7d2f, 0xe54d, 0x7d29, 0xe534, - 0x7d24, 0xe51c, 0x7d1f, 0xe503, 0x7d19, 0xe4ea, 0x7d14, 0xe4d2, - 0x7d0f, 0xe4b9, 0x7d09, 0xe4a1, 0x7d04, 0xe488, 0x7cff, 0xe470, - 0x7cf9, 0xe457, 0x7cf4, 0xe43f, 0x7cee, 0xe426, 0x7ce9, 0xe40e, - 0x7ce3, 0xe3f5, 0x7cde, 0xe3dc, 0x7cd8, 0xe3c4, 0x7cd3, 0xe3ab, - 0x7ccd, 0xe393, 0x7cc8, 0xe37a, 0x7cc2, 0xe362, 0x7cbc, 0xe349, - 0x7cb7, 0xe331, 0x7cb1, 0xe318, 0x7cab, 0xe300, 0x7ca6, 0xe2e8, - 0x7ca0, 0xe2cf, 0x7c9a, 0xe2b7, 0x7c94, 0xe29e, 0x7c8f, 0xe286, - 0x7c89, 0xe26d, 0x7c83, 0xe255, 0x7c7d, 0xe23c, 0x7c77, 0xe224, - 0x7c71, 0xe20b, 0x7c6c, 0xe1f3, 0x7c66, 0xe1db, 0x7c60, 0xe1c2, - 0x7c5a, 0xe1aa, 0x7c54, 0xe191, 0x7c4e, 0xe179, 0x7c48, 0xe160, - 0x7c42, 0xe148, 0x7c3c, 0xe130, 0x7c36, 0xe117, 0x7c30, 0xe0ff, - 0x7c29, 0xe0e7, 0x7c23, 0xe0ce, 0x7c1d, 0xe0b6, 0x7c17, 0xe09d, - 0x7c11, 0xe085, 0x7c0b, 0xe06d, 0x7c05, 0xe054, 0x7bfe, 0xe03c, - 0x7bf8, 0xe024, 0x7bf2, 0xe00b, 0x7beb, 0xdff3, 0x7be5, 0xdfdb, - 0x7bdf, 0xdfc2, 0x7bd9, 0xdfaa, 0x7bd2, 0xdf92, 0x7bcc, 0xdf79, - 0x7bc5, 0xdf61, 0x7bbf, 0xdf49, 0x7bb9, 0xdf30, 0x7bb2, 0xdf18, - 0x7bac, 0xdf00, 0x7ba5, 0xdee8, 0x7b9f, 0xdecf, 0x7b98, 0xdeb7, - 0x7b92, 0xde9f, 0x7b8b, 0xde87, 0x7b84, 0xde6e, 0x7b7e, 0xde56, - 0x7b77, 0xde3e, 0x7b71, 0xde26, 0x7b6a, 0xde0d, 0x7b63, 0xddf5, - 0x7b5d, 0xdddd, 0x7b56, 0xddc5, 0x7b4f, 0xddac, 0x7b48, 0xdd94, - 0x7b42, 0xdd7c, 0x7b3b, 0xdd64, 0x7b34, 0xdd4c, 0x7b2d, 0xdd33, - 0x7b26, 0xdd1b, 0x7b1f, 0xdd03, 0x7b19, 0xdceb, 0x7b12, 0xdcd3, - 0x7b0b, 0xdcbb, 0x7b04, 0xdca2, 0x7afd, 0xdc8a, 0x7af6, 0xdc72, - 0x7aef, 0xdc5a, 0x7ae8, 0xdc42, 0x7ae1, 0xdc2a, 0x7ada, 0xdc12, - 0x7ad3, 0xdbf9, 0x7acc, 0xdbe1, 0x7ac5, 0xdbc9, 0x7abd, 0xdbb1, - 0x7ab6, 0xdb99, 0x7aaf, 0xdb81, 0x7aa8, 0xdb69, 0x7aa1, 0xdb51, - 0x7a9a, 0xdb39, 0x7a92, 0xdb21, 0x7a8b, 0xdb09, 0x7a84, 0xdaf1, - 0x7a7d, 0xdad8, 0x7a75, 0xdac0, 0x7a6e, 0xdaa8, 0x7a67, 0xda90, - 0x7a5f, 0xda78, 0x7a58, 0xda60, 0x7a50, 0xda48, 0x7a49, 0xda30, - 0x7a42, 0xda18, 0x7a3a, 0xda00, 0x7a33, 0xd9e8, 0x7a2b, 0xd9d0, - 0x7a24, 0xd9b8, 0x7a1c, 0xd9a0, 0x7a15, 0xd988, 0x7a0d, 0xd970, - 0x7a05, 0xd958, 0x79fe, 0xd940, 0x79f6, 0xd928, 0x79ef, 0xd911, - 0x79e7, 0xd8f9, 0x79df, 0xd8e1, 0x79d8, 0xd8c9, 0x79d0, 0xd8b1, - 0x79c8, 0xd899, 0x79c0, 0xd881, 0x79b9, 0xd869, 0x79b1, 0xd851, - 0x79a9, 0xd839, 0x79a1, 0xd821, 0x7999, 0xd80a, 0x7992, 0xd7f2, - 0x798a, 0xd7da, 0x7982, 0xd7c2, 0x797a, 0xd7aa, 0x7972, 0xd792, - 0x796a, 0xd77a, 0x7962, 0xd763, 0x795a, 0xd74b, 0x7952, 0xd733, - 0x794a, 0xd71b, 0x7942, 0xd703, 0x793a, 0xd6eb, 0x7932, 0xd6d4, - 0x792a, 0xd6bc, 0x7922, 0xd6a4, 0x7919, 0xd68c, 0x7911, 0xd675, - 0x7909, 0xd65d, 0x7901, 0xd645, 0x78f9, 0xd62d, 0x78f1, 0xd615, - 0x78e8, 0xd5fe, 0x78e0, 0xd5e6, 0x78d8, 0xd5ce, 0x78cf, 0xd5b7, - 0x78c7, 0xd59f, 0x78bf, 0xd587, 0x78b6, 0xd56f, 0x78ae, 0xd558, - 0x78a6, 0xd540, 0x789d, 0xd528, 0x7895, 0xd511, 0x788c, 0xd4f9, - 0x7884, 0xd4e1, 0x787c, 0xd4ca, 0x7873, 0xd4b2, 0x786b, 0xd49a, - 0x7862, 0xd483, 0x7859, 0xd46b, 0x7851, 0xd453, 0x7848, 0xd43c, - 0x7840, 0xd424, 0x7837, 0xd40d, 0x782e, 0xd3f5, 0x7826, 0xd3dd, - 0x781d, 0xd3c6, 0x7814, 0xd3ae, 0x780c, 0xd397, 0x7803, 0xd37f, - 0x77fa, 0xd368, 0x77f1, 0xd350, 0x77e9, 0xd338, 0x77e0, 0xd321, - 0x77d7, 0xd309, 0x77ce, 0xd2f2, 0x77c5, 0xd2da, 0x77bc, 0xd2c3, - 0x77b4, 0xd2ab, 0x77ab, 0xd294, 0x77a2, 0xd27c, 0x7799, 0xd265, - 0x7790, 0xd24d, 0x7787, 0xd236, 0x777e, 0xd21e, 0x7775, 0xd207, - 0x776c, 0xd1ef, 0x7763, 0xd1d8, 0x775a, 0xd1c1, 0x7751, 0xd1a9, - 0x7747, 0xd192, 0x773e, 0xd17a, 0x7735, 0xd163, 0x772c, 0xd14b, - 0x7723, 0xd134, 0x771a, 0xd11d, 0x7710, 0xd105, 0x7707, 0xd0ee, - 0x76fe, 0xd0d7, 0x76f5, 0xd0bf, 0x76eb, 0xd0a8, 0x76e2, 0xd091, - 0x76d9, 0xd079, 0x76cf, 0xd062, 0x76c6, 0xd04b, 0x76bd, 0xd033, - 0x76b3, 0xd01c, 0x76aa, 0xd005, 0x76a0, 0xcfed, 0x7697, 0xcfd6, - 0x768e, 0xcfbf, 0x7684, 0xcfa7, 0x767b, 0xcf90, 0x7671, 0xcf79, - 0x7668, 0xcf62, 0x765e, 0xcf4a, 0x7654, 0xcf33, 0x764b, 0xcf1c, - 0x7641, 0xcf05, 0x7638, 0xceee, 0x762e, 0xced6, 0x7624, 0xcebf, - 0x761b, 0xcea8, 0x7611, 0xce91, 0x7607, 0xce7a, 0x75fd, 0xce62, - 0x75f4, 0xce4b, 0x75ea, 0xce34, 0x75e0, 0xce1d, 0x75d6, 0xce06, - 0x75cc, 0xcdef, 0x75c3, 0xcdd8, 0x75b9, 0xcdc0, 0x75af, 0xcda9, - 0x75a5, 0xcd92, 0x759b, 0xcd7b, 0x7591, 0xcd64, 0x7587, 0xcd4d, - 0x757d, 0xcd36, 0x7573, 0xcd1f, 0x7569, 0xcd08, 0x755f, 0xccf1, - 0x7555, 0xccda, 0x754b, 0xccc3, 0x7541, 0xccac, 0x7537, 0xcc95, - 0x752d, 0xcc7e, 0x7523, 0xcc67, 0x7519, 0xcc50, 0x750f, 0xcc39, - 0x7504, 0xcc22, 0x74fa, 0xcc0b, 0x74f0, 0xcbf4, 0x74e6, 0xcbdd, - 0x74db, 0xcbc6, 0x74d1, 0xcbaf, 0x74c7, 0xcb98, 0x74bd, 0xcb81, - 0x74b2, 0xcb6a, 0x74a8, 0xcb53, 0x749e, 0xcb3c, 0x7493, 0xcb25, - 0x7489, 0xcb0e, 0x747e, 0xcaf8, 0x7474, 0xcae1, 0x746a, 0xcaca, - 0x745f, 0xcab3, 0x7455, 0xca9c, 0x744a, 0xca85, 0x7440, 0xca6e, - 0x7435, 0xca58, 0x742b, 0xca41, 0x7420, 0xca2a, 0x7415, 0xca13, - 0x740b, 0xc9fc, 0x7400, 0xc9e6, 0x73f6, 0xc9cf, 0x73eb, 0xc9b8, - 0x73e0, 0xc9a1, 0x73d6, 0xc98b, 0x73cb, 0xc974, 0x73c0, 0xc95d, - 0x73b5, 0xc946, 0x73ab, 0xc930, 0x73a0, 0xc919, 0x7395, 0xc902, - 0x738a, 0xc8ec, 0x737f, 0xc8d5, 0x7375, 0xc8be, 0x736a, 0xc8a8, - 0x735f, 0xc891, 0x7354, 0xc87a, 0x7349, 0xc864, 0x733e, 0xc84d, - 0x7333, 0xc836, 0x7328, 0xc820, 0x731d, 0xc809, 0x7312, 0xc7f3, - 0x7307, 0xc7dc, 0x72fc, 0xc7c5, 0x72f1, 0xc7af, 0x72e6, 0xc798, - 0x72db, 0xc782, 0x72d0, 0xc76b, 0x72c5, 0xc755, 0x72ba, 0xc73e, - 0x72af, 0xc728, 0x72a3, 0xc711, 0x7298, 0xc6fa, 0x728d, 0xc6e4, - 0x7282, 0xc6ce, 0x7276, 0xc6b7, 0x726b, 0xc6a1, 0x7260, 0xc68a, - 0x7255, 0xc674, 0x7249, 0xc65d, 0x723e, 0xc647, 0x7233, 0xc630, - 0x7227, 0xc61a, 0x721c, 0xc603, 0x7211, 0xc5ed, 0x7205, 0xc5d7, - 0x71fa, 0xc5c0, 0x71ee, 0xc5aa, 0x71e3, 0xc594, 0x71d7, 0xc57d, - 0x71cc, 0xc567, 0x71c0, 0xc551, 0x71b5, 0xc53a, 0x71a9, 0xc524, - 0x719e, 0xc50e, 0x7192, 0xc4f7, 0x7186, 0xc4e1, 0x717b, 0xc4cb, - 0x716f, 0xc4b4, 0x7164, 0xc49e, 0x7158, 0xc488, 0x714c, 0xc472, - 0x7141, 0xc45b, 0x7135, 0xc445, 0x7129, 0xc42f, 0x711d, 0xc419, - 0x7112, 0xc403, 0x7106, 0xc3ec, 0x70fa, 0xc3d6, 0x70ee, 0xc3c0, - 0x70e2, 0xc3aa, 0x70d6, 0xc394, 0x70cb, 0xc37d, 0x70bf, 0xc367, - 0x70b3, 0xc351, 0x70a7, 0xc33b, 0x709b, 0xc325, 0x708f, 0xc30f, - 0x7083, 0xc2f9, 0x7077, 0xc2e3, 0x706b, 0xc2cd, 0x705f, 0xc2b7, - 0x7053, 0xc2a0, 0x7047, 0xc28a, 0x703b, 0xc274, 0x702f, 0xc25e, - 0x7023, 0xc248, 0x7016, 0xc232, 0x700a, 0xc21c, 0x6ffe, 0xc206, - 0x6ff2, 0xc1f0, 0x6fe6, 0xc1da, 0x6fda, 0xc1c4, 0x6fcd, 0xc1ae, - 0x6fc1, 0xc198, 0x6fb5, 0xc183, 0x6fa9, 0xc16d, 0x6f9c, 0xc157, - 0x6f90, 0xc141, 0x6f84, 0xc12b, 0x6f77, 0xc115, 0x6f6b, 0xc0ff, - 0x6f5f, 0xc0e9, 0x6f52, 0xc0d3, 0x6f46, 0xc0bd, 0x6f39, 0xc0a8, - 0x6f2d, 0xc092, 0x6f20, 0xc07c, 0x6f14, 0xc066, 0x6f07, 0xc050, - 0x6efb, 0xc03b, 0x6eee, 0xc025, 0x6ee2, 0xc00f, 0x6ed5, 0xbff9, - 0x6ec9, 0xbfe3, 0x6ebc, 0xbfce, 0x6eaf, 0xbfb8, 0x6ea3, 0xbfa2, - 0x6e96, 0xbf8d, 0x6e89, 0xbf77, 0x6e7d, 0xbf61, 0x6e70, 0xbf4b, - 0x6e63, 0xbf36, 0x6e57, 0xbf20, 0x6e4a, 0xbf0a, 0x6e3d, 0xbef5, - 0x6e30, 0xbedf, 0x6e24, 0xbeca, 0x6e17, 0xbeb4, 0x6e0a, 0xbe9e, - 0x6dfd, 0xbe89, 0x6df0, 0xbe73, 0x6de3, 0xbe5e, 0x6dd6, 0xbe48, - 0x6dca, 0xbe32, 0x6dbd, 0xbe1d, 0x6db0, 0xbe07, 0x6da3, 0xbdf2, - 0x6d96, 0xbddc, 0x6d89, 0xbdc7, 0x6d7c, 0xbdb1, 0x6d6f, 0xbd9c, - 0x6d62, 0xbd86, 0x6d55, 0xbd71, 0x6d48, 0xbd5b, 0x6d3a, 0xbd46, - 0x6d2d, 0xbd30, 0x6d20, 0xbd1b, 0x6d13, 0xbd06, 0x6d06, 0xbcf0, - 0x6cf9, 0xbcdb, 0x6cec, 0xbcc5, 0x6cde, 0xbcb0, 0x6cd1, 0xbc9b, - 0x6cc4, 0xbc85, 0x6cb7, 0xbc70, 0x6ca9, 0xbc5b, 0x6c9c, 0xbc45, - 0x6c8f, 0xbc30, 0x6c81, 0xbc1b, 0x6c74, 0xbc05, 0x6c67, 0xbbf0, - 0x6c59, 0xbbdb, 0x6c4c, 0xbbc5, 0x6c3f, 0xbbb0, 0x6c31, 0xbb9b, - 0x6c24, 0xbb86, 0x6c16, 0xbb70, 0x6c09, 0xbb5b, 0x6bfb, 0xbb46, - 0x6bee, 0xbb31, 0x6be0, 0xbb1c, 0x6bd3, 0xbb06, 0x6bc5, 0xbaf1, - 0x6bb8, 0xbadc, 0x6baa, 0xbac7, 0x6b9c, 0xbab2, 0x6b8f, 0xba9d, - 0x6b81, 0xba88, 0x6b73, 0xba73, 0x6b66, 0xba5d, 0x6b58, 0xba48, - 0x6b4a, 0xba33, 0x6b3d, 0xba1e, 0x6b2f, 0xba09, 0x6b21, 0xb9f4, - 0x6b13, 0xb9df, 0x6b06, 0xb9ca, 0x6af8, 0xb9b5, 0x6aea, 0xb9a0, - 0x6adc, 0xb98b, 0x6ace, 0xb976, 0x6ac1, 0xb961, 0x6ab3, 0xb94c, - 0x6aa5, 0xb937, 0x6a97, 0xb922, 0x6a89, 0xb90d, 0x6a7b, 0xb8f8, - 0x6a6d, 0xb8e4, 0x6a5f, 0xb8cf, 0x6a51, 0xb8ba, 0x6a43, 0xb8a5, - 0x6a35, 0xb890, 0x6a27, 0xb87b, 0x6a19, 0xb866, 0x6a0b, 0xb852, - 0x69fd, 0xb83d, 0x69ef, 0xb828, 0x69e1, 0xb813, 0x69d3, 0xb7fe, - 0x69c4, 0xb7ea, 0x69b6, 0xb7d5, 0x69a8, 0xb7c0, 0x699a, 0xb7ab, - 0x698c, 0xb797, 0x697d, 0xb782, 0x696f, 0xb76d, 0x6961, 0xb758, - 0x6953, 0xb744, 0x6944, 0xb72f, 0x6936, 0xb71a, 0x6928, 0xb706, - 0x6919, 0xb6f1, 0x690b, 0xb6dd, 0x68fd, 0xb6c8, 0x68ee, 0xb6b3, - 0x68e0, 0xb69f, 0x68d1, 0xb68a, 0x68c3, 0xb676, 0x68b5, 0xb661, - 0x68a6, 0xb64c, 0x6898, 0xb638, 0x6889, 0xb623, 0x687b, 0xb60f, - 0x686c, 0xb5fa, 0x685e, 0xb5e6, 0x684f, 0xb5d1, 0x6840, 0xb5bd, - 0x6832, 0xb5a8, 0x6823, 0xb594, 0x6815, 0xb57f, 0x6806, 0xb56b, - 0x67f7, 0xb557, 0x67e9, 0xb542, 0x67da, 0xb52e, 0x67cb, 0xb519, - 0x67bd, 0xb505, 0x67ae, 0xb4f1, 0x679f, 0xb4dc, 0x6790, 0xb4c8, - 0x6782, 0xb4b4, 0x6773, 0xb49f, 0x6764, 0xb48b, 0x6755, 0xb477, - 0x6746, 0xb462, 0x6737, 0xb44e, 0x6729, 0xb43a, 0x671a, 0xb426, - 0x670b, 0xb411, 0x66fc, 0xb3fd, 0x66ed, 0xb3e9, 0x66de, 0xb3d5, - 0x66cf, 0xb3c1, 0x66c0, 0xb3ac, 0x66b1, 0xb398, 0x66a2, 0xb384, - 0x6693, 0xb370, 0x6684, 0xb35c, 0x6675, 0xb348, 0x6666, 0xb334, - 0x6657, 0xb31f, 0x6648, 0xb30b, 0x6639, 0xb2f7, 0x6629, 0xb2e3, - 0x661a, 0xb2cf, 0x660b, 0xb2bb, 0x65fc, 0xb2a7, 0x65ed, 0xb293, - 0x65dd, 0xb27f, 0x65ce, 0xb26b, 0x65bf, 0xb257, 0x65b0, 0xb243, - 0x65a0, 0xb22f, 0x6591, 0xb21b, 0x6582, 0xb207, 0x6573, 0xb1f3, - 0x6563, 0xb1df, 0x6554, 0xb1cc, 0x6545, 0xb1b8, 0x6535, 0xb1a4, - 0x6526, 0xb190, 0x6516, 0xb17c, 0x6507, 0xb168, 0x64f7, 0xb154, - 0x64e8, 0xb141, 0x64d9, 0xb12d, 0x64c9, 0xb119, 0x64ba, 0xb105, - 0x64aa, 0xb0f1, 0x649b, 0xb0de, 0x648b, 0xb0ca, 0x647b, 0xb0b6, - 0x646c, 0xb0a2, 0x645c, 0xb08f, 0x644d, 0xb07b, 0x643d, 0xb067, - 0x642d, 0xb054, 0x641e, 0xb040, 0x640e, 0xb02c, 0x63fe, 0xb019, - 0x63ef, 0xb005, 0x63df, 0xaff1, 0x63cf, 0xafde, 0x63c0, 0xafca, - 0x63b0, 0xafb7, 0x63a0, 0xafa3, 0x6390, 0xaf90, 0x6380, 0xaf7c, - 0x6371, 0xaf69, 0x6361, 0xaf55, 0x6351, 0xaf41, 0x6341, 0xaf2e, - 0x6331, 0xaf1b, 0x6321, 0xaf07, 0x6311, 0xaef4, 0x6301, 0xaee0, - 0x62f2, 0xaecd, 0x62e2, 0xaeb9, 0x62d2, 0xaea6, 0x62c2, 0xae92, - 0x62b2, 0xae7f, 0x62a2, 0xae6c, 0x6292, 0xae58, 0x6282, 0xae45, - 0x6271, 0xae32, 0x6261, 0xae1e, 0x6251, 0xae0b, 0x6241, 0xadf8, - 0x6231, 0xade4, 0x6221, 0xadd1, 0x6211, 0xadbe, 0x6201, 0xadab, - 0x61f1, 0xad97, 0x61e0, 0xad84, 0x61d0, 0xad71, 0x61c0, 0xad5e, - 0x61b0, 0xad4b, 0x619f, 0xad37, 0x618f, 0xad24, 0x617f, 0xad11, - 0x616f, 0xacfe, 0x615e, 0xaceb, 0x614e, 0xacd8, 0x613e, 0xacc5, - 0x612d, 0xacb2, 0x611d, 0xac9e, 0x610d, 0xac8b, 0x60fc, 0xac78, - 0x60ec, 0xac65, 0x60db, 0xac52, 0x60cb, 0xac3f, 0x60ba, 0xac2c, - 0x60aa, 0xac19, 0x6099, 0xac06, 0x6089, 0xabf3, 0x6078, 0xabe0, - 0x6068, 0xabcd, 0x6057, 0xabbb, 0x6047, 0xaba8, 0x6036, 0xab95, - 0x6026, 0xab82, 0x6015, 0xab6f, 0x6004, 0xab5c, 0x5ff4, 0xab49, - 0x5fe3, 0xab36, 0x5fd3, 0xab24, 0x5fc2, 0xab11, 0x5fb1, 0xaafe, - 0x5fa0, 0xaaeb, 0x5f90, 0xaad8, 0x5f7f, 0xaac6, 0x5f6e, 0xaab3, - 0x5f5e, 0xaaa0, 0x5f4d, 0xaa8e, 0x5f3c, 0xaa7b, 0x5f2b, 0xaa68, - 0x5f1a, 0xaa55, 0x5f0a, 0xaa43, 0x5ef9, 0xaa30, 0x5ee8, 0xaa1d, - 0x5ed7, 0xaa0b, 0x5ec6, 0xa9f8, 0x5eb5, 0xa9e6, 0x5ea4, 0xa9d3, - 0x5e93, 0xa9c0, 0x5e82, 0xa9ae, 0x5e71, 0xa99b, 0x5e60, 0xa989, - 0x5e50, 0xa976, 0x5e3f, 0xa964, 0x5e2d, 0xa951, 0x5e1c, 0xa93f, - 0x5e0b, 0xa92c, 0x5dfa, 0xa91a, 0x5de9, 0xa907, 0x5dd8, 0xa8f5, - 0x5dc7, 0xa8e3, 0x5db6, 0xa8d0, 0x5da5, 0xa8be, 0x5d94, 0xa8ab, - 0x5d83, 0xa899, 0x5d71, 0xa887, 0x5d60, 0xa874, 0x5d4f, 0xa862, - 0x5d3e, 0xa850, 0x5d2d, 0xa83d, 0x5d1b, 0xa82b, 0x5d0a, 0xa819, - 0x5cf9, 0xa807, 0x5ce8, 0xa7f4, 0x5cd6, 0xa7e2, 0x5cc5, 0xa7d0, - 0x5cb4, 0xa7be, 0x5ca2, 0xa7ab, 0x5c91, 0xa799, 0x5c80, 0xa787, - 0x5c6e, 0xa775, 0x5c5d, 0xa763, 0x5c4b, 0xa751, 0x5c3a, 0xa73f, - 0x5c29, 0xa72c, 0x5c17, 0xa71a, 0x5c06, 0xa708, 0x5bf4, 0xa6f6, - 0x5be3, 0xa6e4, 0x5bd1, 0xa6d2, 0x5bc0, 0xa6c0, 0x5bae, 0xa6ae, - 0x5b9d, 0xa69c, 0x5b8b, 0xa68a, 0x5b79, 0xa678, 0x5b68, 0xa666, - 0x5b56, 0xa654, 0x5b45, 0xa642, 0x5b33, 0xa630, 0x5b21, 0xa61f, - 0x5b10, 0xa60d, 0x5afe, 0xa5fb, 0x5aec, 0xa5e9, 0x5adb, 0xa5d7, - 0x5ac9, 0xa5c5, 0x5ab7, 0xa5b3, 0x5aa5, 0xa5a2, 0x5a94, 0xa590, - 0x5a82, 0xa57e, 0x5a70, 0xa56c, 0x5a5e, 0xa55b, 0x5a4d, 0xa549, - 0x5a3b, 0xa537, 0x5a29, 0xa525, 0x5a17, 0xa514, 0x5a05, 0xa502, - 0x59f3, 0xa4f0, 0x59e1, 0xa4df, 0x59d0, 0xa4cd, 0x59be, 0xa4bb, - 0x59ac, 0xa4aa, 0x599a, 0xa498, 0x5988, 0xa487, 0x5976, 0xa475, - 0x5964, 0xa463, 0x5952, 0xa452, 0x5940, 0xa440, 0x592e, 0xa42f, - 0x591c, 0xa41d, 0x590a, 0xa40c, 0x58f8, 0xa3fa, 0x58e6, 0xa3e9, - 0x58d4, 0xa3d7, 0x58c1, 0xa3c6, 0x58af, 0xa3b5, 0x589d, 0xa3a3, - 0x588b, 0xa392, 0x5879, 0xa380, 0x5867, 0xa36f, 0x5855, 0xa35e, - 0x5842, 0xa34c, 0x5830, 0xa33b, 0x581e, 0xa32a, 0x580c, 0xa318, - 0x57f9, 0xa307, 0x57e7, 0xa2f6, 0x57d5, 0xa2e5, 0x57c3, 0xa2d3, - 0x57b0, 0xa2c2, 0x579e, 0xa2b1, 0x578c, 0xa2a0, 0x5779, 0xa28f, - 0x5767, 0xa27d, 0x5755, 0xa26c, 0x5742, 0xa25b, 0x5730, 0xa24a, - 0x571d, 0xa239, 0x570b, 0xa228, 0x56f9, 0xa217, 0x56e6, 0xa206, - 0x56d4, 0xa1f5, 0x56c1, 0xa1e4, 0x56af, 0xa1d3, 0x569c, 0xa1c1, - 0x568a, 0xa1b0, 0x5677, 0xa1a0, 0x5665, 0xa18f, 0x5652, 0xa17e, - 0x5640, 0xa16d, 0x562d, 0xa15c, 0x561a, 0xa14b, 0x5608, 0xa13a, - 0x55f5, 0xa129, 0x55e3, 0xa118, 0x55d0, 0xa107, 0x55bd, 0xa0f6, - 0x55ab, 0xa0e6, 0x5598, 0xa0d5, 0x5585, 0xa0c4, 0x5572, 0xa0b3, - 0x5560, 0xa0a2, 0x554d, 0xa092, 0x553a, 0xa081, 0x5528, 0xa070, - 0x5515, 0xa060, 0x5502, 0xa04f, 0x54ef, 0xa03e, 0x54dc, 0xa02d, - 0x54ca, 0xa01d, 0x54b7, 0xa00c, 0x54a4, 0x9ffc, 0x5491, 0x9feb, - 0x547e, 0x9fda, 0x546b, 0x9fca, 0x5458, 0x9fb9, 0x5445, 0x9fa9, - 0x5433, 0x9f98, 0x5420, 0x9f88, 0x540d, 0x9f77, 0x53fa, 0x9f67, - 0x53e7, 0x9f56, 0x53d4, 0x9f46, 0x53c1, 0x9f35, 0x53ae, 0x9f25, - 0x539b, 0x9f14, 0x5388, 0x9f04, 0x5375, 0x9ef3, 0x5362, 0x9ee3, - 0x534e, 0x9ed3, 0x533b, 0x9ec2, 0x5328, 0x9eb2, 0x5315, 0x9ea2, - 0x5302, 0x9e91, 0x52ef, 0x9e81, 0x52dc, 0x9e71, 0x52c9, 0x9e61, - 0x52b5, 0x9e50, 0x52a2, 0x9e40, 0x528f, 0x9e30, 0x527c, 0x9e20, - 0x5269, 0x9e0f, 0x5255, 0x9dff, 0x5242, 0x9def, 0x522f, 0x9ddf, - 0x521c, 0x9dcf, 0x5208, 0x9dbf, 0x51f5, 0x9daf, 0x51e2, 0x9d9f, - 0x51ce, 0x9d8f, 0x51bb, 0x9d7e, 0x51a8, 0x9d6e, 0x5194, 0x9d5e, - 0x5181, 0x9d4e, 0x516e, 0x9d3e, 0x515a, 0x9d2e, 0x5147, 0x9d1e, - 0x5133, 0x9d0e, 0x5120, 0x9cff, 0x510c, 0x9cef, 0x50f9, 0x9cdf, - 0x50e5, 0x9ccf, 0x50d2, 0x9cbf, 0x50bf, 0x9caf, 0x50ab, 0x9c9f, - 0x5097, 0x9c8f, 0x5084, 0x9c80, 0x5070, 0x9c70, 0x505d, 0x9c60, - 0x5049, 0x9c50, 0x5036, 0x9c40, 0x5022, 0x9c31, 0x500f, 0x9c21, - 0x4ffb, 0x9c11, 0x4fe7, 0x9c02, 0x4fd4, 0x9bf2, 0x4fc0, 0x9be2, - 0x4fac, 0x9bd3, 0x4f99, 0x9bc3, 0x4f85, 0x9bb3, 0x4f71, 0x9ba4, - 0x4f5e, 0x9b94, 0x4f4a, 0x9b85, 0x4f36, 0x9b75, 0x4f22, 0x9b65, - 0x4f0f, 0x9b56, 0x4efb, 0x9b46, 0x4ee7, 0x9b37, 0x4ed3, 0x9b27, - 0x4ebf, 0x9b18, 0x4eac, 0x9b09, 0x4e98, 0x9af9, 0x4e84, 0x9aea, - 0x4e70, 0x9ada, 0x4e5c, 0x9acb, 0x4e48, 0x9abb, 0x4e34, 0x9aac, - 0x4e21, 0x9a9d, 0x4e0d, 0x9a8d, 0x4df9, 0x9a7e, 0x4de5, 0x9a6f, - 0x4dd1, 0x9a60, 0x4dbd, 0x9a50, 0x4da9, 0x9a41, 0x4d95, 0x9a32, - 0x4d81, 0x9a23, 0x4d6d, 0x9a13, 0x4d59, 0x9a04, 0x4d45, 0x99f5, - 0x4d31, 0x99e6, 0x4d1d, 0x99d7, 0x4d09, 0x99c7, 0x4cf5, 0x99b8, - 0x4ce1, 0x99a9, 0x4ccc, 0x999a, 0x4cb8, 0x998b, 0x4ca4, 0x997c, - 0x4c90, 0x996d, 0x4c7c, 0x995e, 0x4c68, 0x994f, 0x4c54, 0x9940, - 0x4c3f, 0x9931, 0x4c2b, 0x9922, 0x4c17, 0x9913, 0x4c03, 0x9904, - 0x4bef, 0x98f5, 0x4bda, 0x98e6, 0x4bc6, 0x98d7, 0x4bb2, 0x98c9, - 0x4b9e, 0x98ba, 0x4b89, 0x98ab, 0x4b75, 0x989c, 0x4b61, 0x988d, - 0x4b4c, 0x987e, 0x4b38, 0x9870, 0x4b24, 0x9861, 0x4b0f, 0x9852, - 0x4afb, 0x9843, 0x4ae7, 0x9835, 0x4ad2, 0x9826, 0x4abe, 0x9817, - 0x4aa9, 0x9809, 0x4a95, 0x97fa, 0x4a81, 0x97eb, 0x4a6c, 0x97dd, - 0x4a58, 0x97ce, 0x4a43, 0x97c0, 0x4a2f, 0x97b1, 0x4a1a, 0x97a2, - 0x4a06, 0x9794, 0x49f1, 0x9785, 0x49dd, 0x9777, 0x49c8, 0x9768, - 0x49b4, 0x975a, 0x499f, 0x974b, 0x498a, 0x973d, 0x4976, 0x972f, - 0x4961, 0x9720, 0x494d, 0x9712, 0x4938, 0x9703, 0x4923, 0x96f5, - 0x490f, 0x96e7, 0x48fa, 0x96d8, 0x48e6, 0x96ca, 0x48d1, 0x96bc, - 0x48bc, 0x96ad, 0x48a8, 0x969f, 0x4893, 0x9691, 0x487e, 0x9683, - 0x4869, 0x9674, 0x4855, 0x9666, 0x4840, 0x9658, 0x482b, 0x964a, - 0x4816, 0x963c, 0x4802, 0x962d, 0x47ed, 0x961f, 0x47d8, 0x9611, - 0x47c3, 0x9603, 0x47ae, 0x95f5, 0x479a, 0x95e7, 0x4785, 0x95d9, - 0x4770, 0x95cb, 0x475b, 0x95bd, 0x4746, 0x95af, 0x4731, 0x95a1, - 0x471c, 0x9593, 0x4708, 0x9585, 0x46f3, 0x9577, 0x46de, 0x9569, - 0x46c9, 0x955b, 0x46b4, 0x954d, 0x469f, 0x953f, 0x468a, 0x9532, - 0x4675, 0x9524, 0x4660, 0x9516, 0x464b, 0x9508, 0x4636, 0x94fa, - 0x4621, 0x94ed, 0x460c, 0x94df, 0x45f7, 0x94d1, 0x45e2, 0x94c3, - 0x45cd, 0x94b6, 0x45b8, 0x94a8, 0x45a3, 0x949a, 0x458d, 0x948d, - 0x4578, 0x947f, 0x4563, 0x9471, 0x454e, 0x9464, 0x4539, 0x9456, - 0x4524, 0x9448, 0x450f, 0x943b, 0x44fa, 0x942d, 0x44e4, 0x9420, - 0x44cf, 0x9412, 0x44ba, 0x9405, 0x44a5, 0x93f7, 0x4490, 0x93ea, - 0x447a, 0x93dc, 0x4465, 0x93cf, 0x4450, 0x93c1, 0x443b, 0x93b4, - 0x4425, 0x93a7, 0x4410, 0x9399, 0x43fb, 0x938c, 0x43e5, 0x937f, - 0x43d0, 0x9371, 0x43bb, 0x9364, 0x43a5, 0x9357, 0x4390, 0x9349, - 0x437b, 0x933c, 0x4365, 0x932f, 0x4350, 0x9322, 0x433b, 0x9314, - 0x4325, 0x9307, 0x4310, 0x92fa, 0x42fa, 0x92ed, 0x42e5, 0x92e0, - 0x42d0, 0x92d3, 0x42ba, 0x92c6, 0x42a5, 0x92b8, 0x428f, 0x92ab, - 0x427a, 0x929e, 0x4264, 0x9291, 0x424f, 0x9284, 0x4239, 0x9277, - 0x4224, 0x926a, 0x420e, 0x925d, 0x41f9, 0x9250, 0x41e3, 0x9243, - 0x41ce, 0x9236, 0x41b8, 0x922a, 0x41a2, 0x921d, 0x418d, 0x9210, - 0x4177, 0x9203, 0x4162, 0x91f6, 0x414c, 0x91e9, 0x4136, 0x91dc, - 0x4121, 0x91d0, 0x410b, 0x91c3, 0x40f6, 0x91b6, 0x40e0, 0x91a9, - 0x40ca, 0x919d, 0x40b5, 0x9190, 0x409f, 0x9183, 0x4089, 0x9177, - 0x4073, 0x916a, 0x405e, 0x915d, 0x4048, 0x9151, 0x4032, 0x9144, - 0x401d, 0x9137, 0x4007, 0x912b, 0x3ff1, 0x911e, 0x3fdb, 0x9112, - 0x3fc5, 0x9105, 0x3fb0, 0x90f9, 0x3f9a, 0x90ec, 0x3f84, 0x90e0, - 0x3f6e, 0x90d3, 0x3f58, 0x90c7, 0x3f43, 0x90ba, 0x3f2d, 0x90ae, - 0x3f17, 0x90a1, 0x3f01, 0x9095, 0x3eeb, 0x9089, 0x3ed5, 0x907c, - 0x3ebf, 0x9070, 0x3ea9, 0x9064, 0x3e93, 0x9057, 0x3e7d, 0x904b, - 0x3e68, 0x903f, 0x3e52, 0x9033, 0x3e3c, 0x9026, 0x3e26, 0x901a, - 0x3e10, 0x900e, 0x3dfa, 0x9002, 0x3de4, 0x8ff6, 0x3dce, 0x8fea, - 0x3db8, 0x8fdd, 0x3da2, 0x8fd1, 0x3d8c, 0x8fc5, 0x3d76, 0x8fb9, - 0x3d60, 0x8fad, 0x3d49, 0x8fa1, 0x3d33, 0x8f95, 0x3d1d, 0x8f89, - 0x3d07, 0x8f7d, 0x3cf1, 0x8f71, 0x3cdb, 0x8f65, 0x3cc5, 0x8f59, - 0x3caf, 0x8f4d, 0x3c99, 0x8f41, 0x3c83, 0x8f35, 0x3c6c, 0x8f2a, - 0x3c56, 0x8f1e, 0x3c40, 0x8f12, 0x3c2a, 0x8f06, 0x3c14, 0x8efa, - 0x3bfd, 0x8eee, 0x3be7, 0x8ee3, 0x3bd1, 0x8ed7, 0x3bbb, 0x8ecb, - 0x3ba5, 0x8ebf, 0x3b8e, 0x8eb4, 0x3b78, 0x8ea8, 0x3b62, 0x8e9c, - 0x3b4c, 0x8e91, 0x3b35, 0x8e85, 0x3b1f, 0x8e7a, 0x3b09, 0x8e6e, - 0x3af2, 0x8e62, 0x3adc, 0x8e57, 0x3ac6, 0x8e4b, 0x3aaf, 0x8e40, - 0x3a99, 0x8e34, 0x3a83, 0x8e29, 0x3a6c, 0x8e1d, 0x3a56, 0x8e12, - 0x3a40, 0x8e06, 0x3a29, 0x8dfb, 0x3a13, 0x8def, 0x39fd, 0x8de4, - 0x39e6, 0x8dd9, 0x39d0, 0x8dcd, 0x39b9, 0x8dc2, 0x39a3, 0x8db7, - 0x398c, 0x8dab, 0x3976, 0x8da0, 0x395f, 0x8d95, 0x3949, 0x8d8a, - 0x3932, 0x8d7e, 0x391c, 0x8d73, 0x3906, 0x8d68, 0x38ef, 0x8d5d, - 0x38d8, 0x8d51, 0x38c2, 0x8d46, 0x38ab, 0x8d3b, 0x3895, 0x8d30, - 0x387e, 0x8d25, 0x3868, 0x8d1a, 0x3851, 0x8d0f, 0x383b, 0x8d04, - 0x3824, 0x8cf9, 0x380d, 0x8cee, 0x37f7, 0x8ce3, 0x37e0, 0x8cd8, - 0x37ca, 0x8ccd, 0x37b3, 0x8cc2, 0x379c, 0x8cb7, 0x3786, 0x8cac, - 0x376f, 0x8ca1, 0x3758, 0x8c96, 0x3742, 0x8c8b, 0x372b, 0x8c81, - 0x3714, 0x8c76, 0x36fe, 0x8c6b, 0x36e7, 0x8c60, 0x36d0, 0x8c55, - 0x36ba, 0x8c4b, 0x36a3, 0x8c40, 0x368c, 0x8c35, 0x3675, 0x8c2a, - 0x365f, 0x8c20, 0x3648, 0x8c15, 0x3631, 0x8c0a, 0x361a, 0x8c00, - 0x3604, 0x8bf5, 0x35ed, 0x8beb, 0x35d6, 0x8be0, 0x35bf, 0x8bd5, - 0x35a8, 0x8bcb, 0x3592, 0x8bc0, 0x357b, 0x8bb6, 0x3564, 0x8bab, - 0x354d, 0x8ba1, 0x3536, 0x8b96, 0x351f, 0x8b8c, 0x3508, 0x8b82, - 0x34f2, 0x8b77, 0x34db, 0x8b6d, 0x34c4, 0x8b62, 0x34ad, 0x8b58, - 0x3496, 0x8b4e, 0x347f, 0x8b43, 0x3468, 0x8b39, 0x3451, 0x8b2f, - 0x343a, 0x8b25, 0x3423, 0x8b1a, 0x340c, 0x8b10, 0x33f5, 0x8b06, - 0x33de, 0x8afc, 0x33c7, 0x8af1, 0x33b0, 0x8ae7, 0x3399, 0x8add, - 0x3382, 0x8ad3, 0x336b, 0x8ac9, 0x3354, 0x8abf, 0x333d, 0x8ab5, - 0x3326, 0x8aab, 0x330f, 0x8aa1, 0x32f8, 0x8a97, 0x32e1, 0x8a8d, - 0x32ca, 0x8a83, 0x32b3, 0x8a79, 0x329c, 0x8a6f, 0x3285, 0x8a65, - 0x326e, 0x8a5b, 0x3257, 0x8a51, 0x3240, 0x8a47, 0x3228, 0x8a3d, - 0x3211, 0x8a34, 0x31fa, 0x8a2a, 0x31e3, 0x8a20, 0x31cc, 0x8a16, - 0x31b5, 0x8a0c, 0x319e, 0x8a03, 0x3186, 0x89f9, 0x316f, 0x89ef, - 0x3158, 0x89e5, 0x3141, 0x89dc, 0x312a, 0x89d2, 0x3112, 0x89c8, - 0x30fb, 0x89bf, 0x30e4, 0x89b5, 0x30cd, 0x89ac, 0x30b6, 0x89a2, - 0x309e, 0x8998, 0x3087, 0x898f, 0x3070, 0x8985, 0x3059, 0x897c, - 0x3041, 0x8972, 0x302a, 0x8969, 0x3013, 0x8960, 0x2ffb, 0x8956, - 0x2fe4, 0x894d, 0x2fcd, 0x8943, 0x2fb5, 0x893a, 0x2f9e, 0x8931, - 0x2f87, 0x8927, 0x2f6f, 0x891e, 0x2f58, 0x8915, 0x2f41, 0x890b, - 0x2f29, 0x8902, 0x2f12, 0x88f9, 0x2efb, 0x88f0, 0x2ee3, 0x88e6, - 0x2ecc, 0x88dd, 0x2eb5, 0x88d4, 0x2e9d, 0x88cb, 0x2e86, 0x88c2, - 0x2e6e, 0x88b9, 0x2e57, 0x88af, 0x2e3f, 0x88a6, 0x2e28, 0x889d, - 0x2e11, 0x8894, 0x2df9, 0x888b, 0x2de2, 0x8882, 0x2dca, 0x8879, - 0x2db3, 0x8870, 0x2d9b, 0x8867, 0x2d84, 0x885e, 0x2d6c, 0x8855, - 0x2d55, 0x884c, 0x2d3d, 0x8844, 0x2d26, 0x883b, 0x2d0e, 0x8832, - 0x2cf7, 0x8829, 0x2cdf, 0x8820, 0x2cc8, 0x8817, 0x2cb0, 0x880f, - 0x2c98, 0x8806, 0x2c81, 0x87fd, 0x2c69, 0x87f4, 0x2c52, 0x87ec, - 0x2c3a, 0x87e3, 0x2c23, 0x87da, 0x2c0b, 0x87d2, 0x2bf3, 0x87c9, - 0x2bdc, 0x87c0, 0x2bc4, 0x87b8, 0x2bad, 0x87af, 0x2b95, 0x87a7, - 0x2b7d, 0x879e, 0x2b66, 0x8795, 0x2b4e, 0x878d, 0x2b36, 0x8784, - 0x2b1f, 0x877c, 0x2b07, 0x8774, 0x2aef, 0x876b, 0x2ad8, 0x8763, - 0x2ac0, 0x875a, 0x2aa8, 0x8752, 0x2a91, 0x874a, 0x2a79, 0x8741, - 0x2a61, 0x8739, 0x2a49, 0x8731, 0x2a32, 0x8728, 0x2a1a, 0x8720, - 0x2a02, 0x8718, 0x29eb, 0x870f, 0x29d3, 0x8707, 0x29bb, 0x86ff, - 0x29a3, 0x86f7, 0x298b, 0x86ef, 0x2974, 0x86e7, 0x295c, 0x86de, - 0x2944, 0x86d6, 0x292c, 0x86ce, 0x2915, 0x86c6, 0x28fd, 0x86be, - 0x28e5, 0x86b6, 0x28cd, 0x86ae, 0x28b5, 0x86a6, 0x289d, 0x869e, - 0x2886, 0x8696, 0x286e, 0x868e, 0x2856, 0x8686, 0x283e, 0x867e, - 0x2826, 0x8676, 0x280e, 0x866e, 0x27f6, 0x8667, 0x27df, 0x865f, - 0x27c7, 0x8657, 0x27af, 0x864f, 0x2797, 0x8647, 0x277f, 0x8640, - 0x2767, 0x8638, 0x274f, 0x8630, 0x2737, 0x8628, 0x271f, 0x8621, - 0x2707, 0x8619, 0x26ef, 0x8611, 0x26d8, 0x860a, 0x26c0, 0x8602, - 0x26a8, 0x85fb, 0x2690, 0x85f3, 0x2678, 0x85eb, 0x2660, 0x85e4, - 0x2648, 0x85dc, 0x2630, 0x85d5, 0x2618, 0x85cd, 0x2600, 0x85c6, - 0x25e8, 0x85be, 0x25d0, 0x85b7, 0x25b8, 0x85b0, 0x25a0, 0x85a8, - 0x2588, 0x85a1, 0x2570, 0x8599, 0x2558, 0x8592, 0x2540, 0x858b, - 0x2528, 0x8583, 0x250f, 0x857c, 0x24f7, 0x8575, 0x24df, 0x856e, - 0x24c7, 0x8566, 0x24af, 0x855f, 0x2497, 0x8558, 0x247f, 0x8551, - 0x2467, 0x854a, 0x244f, 0x8543, 0x2437, 0x853b, 0x241f, 0x8534, - 0x2407, 0x852d, 0x23ee, 0x8526, 0x23d6, 0x851f, 0x23be, 0x8518, - 0x23a6, 0x8511, 0x238e, 0x850a, 0x2376, 0x8503, 0x235e, 0x84fc, - 0x2345, 0x84f5, 0x232d, 0x84ee, 0x2315, 0x84e7, 0x22fd, 0x84e1, - 0x22e5, 0x84da, 0x22cd, 0x84d3, 0x22b4, 0x84cc, 0x229c, 0x84c5, - 0x2284, 0x84be, 0x226c, 0x84b8, 0x2254, 0x84b1, 0x223b, 0x84aa, - 0x2223, 0x84a3, 0x220b, 0x849d, 0x21f3, 0x8496, 0x21da, 0x848f, - 0x21c2, 0x8489, 0x21aa, 0x8482, 0x2192, 0x847c, 0x2179, 0x8475, - 0x2161, 0x846e, 0x2149, 0x8468, 0x2131, 0x8461, 0x2118, 0x845b, - 0x2100, 0x8454, 0x20e8, 0x844e, 0x20d0, 0x8447, 0x20b7, 0x8441, - 0x209f, 0x843b, 0x2087, 0x8434, 0x206e, 0x842e, 0x2056, 0x8427, - 0x203e, 0x8421, 0x2025, 0x841b, 0x200d, 0x8415, 0x1ff5, 0x840e, - 0x1fdc, 0x8408, 0x1fc4, 0x8402, 0x1fac, 0x83fb, 0x1f93, 0x83f5, - 0x1f7b, 0x83ef, 0x1f63, 0x83e9, 0x1f4a, 0x83e3, 0x1f32, 0x83dd, - 0x1f19, 0x83d7, 0x1f01, 0x83d0, 0x1ee9, 0x83ca, 0x1ed0, 0x83c4, - 0x1eb8, 0x83be, 0x1ea0, 0x83b8, 0x1e87, 0x83b2, 0x1e6f, 0x83ac, - 0x1e56, 0x83a6, 0x1e3e, 0x83a0, 0x1e25, 0x839a, 0x1e0d, 0x8394, - 0x1df5, 0x838f, 0x1ddc, 0x8389, 0x1dc4, 0x8383, 0x1dab, 0x837d, - 0x1d93, 0x8377, 0x1d7a, 0x8371, 0x1d62, 0x836c, 0x1d49, 0x8366, - 0x1d31, 0x8360, 0x1d18, 0x835a, 0x1d00, 0x8355, 0x1ce8, 0x834f, - 0x1ccf, 0x8349, 0x1cb7, 0x8344, 0x1c9e, 0x833e, 0x1c86, 0x8338, - 0x1c6d, 0x8333, 0x1c55, 0x832d, 0x1c3c, 0x8328, 0x1c24, 0x8322, - 0x1c0b, 0x831d, 0x1bf2, 0x8317, 0x1bda, 0x8312, 0x1bc1, 0x830c, - 0x1ba9, 0x8307, 0x1b90, 0x8301, 0x1b78, 0x82fc, 0x1b5f, 0x82f7, - 0x1b47, 0x82f1, 0x1b2e, 0x82ec, 0x1b16, 0x82e7, 0x1afd, 0x82e1, - 0x1ae4, 0x82dc, 0x1acc, 0x82d7, 0x1ab3, 0x82d1, 0x1a9b, 0x82cc, - 0x1a82, 0x82c7, 0x1a6a, 0x82c2, 0x1a51, 0x82bd, 0x1a38, 0x82b7, - 0x1a20, 0x82b2, 0x1a07, 0x82ad, 0x19ef, 0x82a8, 0x19d6, 0x82a3, - 0x19bd, 0x829e, 0x19a5, 0x8299, 0x198c, 0x8294, 0x1973, 0x828f, - 0x195b, 0x828a, 0x1942, 0x8285, 0x192a, 0x8280, 0x1911, 0x827b, - 0x18f8, 0x8276, 0x18e0, 0x8271, 0x18c7, 0x826c, 0x18ae, 0x8268, - 0x1896, 0x8263, 0x187d, 0x825e, 0x1864, 0x8259, 0x184c, 0x8254, - 0x1833, 0x8250, 0x181a, 0x824b, 0x1802, 0x8246, 0x17e9, 0x8241, - 0x17d0, 0x823d, 0x17b7, 0x8238, 0x179f, 0x8233, 0x1786, 0x822f, - 0x176d, 0x822a, 0x1755, 0x8226, 0x173c, 0x8221, 0x1723, 0x821c, - 0x170a, 0x8218, 0x16f2, 0x8213, 0x16d9, 0x820f, 0x16c0, 0x820a, - 0x16a8, 0x8206, 0x168f, 0x8201, 0x1676, 0x81fd, 0x165d, 0x81f9, - 0x1645, 0x81f4, 0x162c, 0x81f0, 0x1613, 0x81ec, 0x15fa, 0x81e7, - 0x15e2, 0x81e3, 0x15c9, 0x81df, 0x15b0, 0x81da, 0x1597, 0x81d6, - 0x157f, 0x81d2, 0x1566, 0x81ce, 0x154d, 0x81c9, 0x1534, 0x81c5, - 0x151b, 0x81c1, 0x1503, 0x81bd, 0x14ea, 0x81b9, 0x14d1, 0x81b5, - 0x14b8, 0x81b1, 0x149f, 0x81ad, 0x1487, 0x81a9, 0x146e, 0x81a5, - 0x1455, 0x81a1, 0x143c, 0x819d, 0x1423, 0x8199, 0x140b, 0x8195, - 0x13f2, 0x8191, 0x13d9, 0x818d, 0x13c0, 0x8189, 0x13a7, 0x8185, - 0x138e, 0x8181, 0x1376, 0x817d, 0x135d, 0x817a, 0x1344, 0x8176, - 0x132b, 0x8172, 0x1312, 0x816e, 0x12f9, 0x816b, 0x12e0, 0x8167, - 0x12c8, 0x8163, 0x12af, 0x815f, 0x1296, 0x815c, 0x127d, 0x8158, - 0x1264, 0x8155, 0x124b, 0x8151, 0x1232, 0x814d, 0x1219, 0x814a, - 0x1201, 0x8146, 0x11e8, 0x8143, 0x11cf, 0x813f, 0x11b6, 0x813c, - 0x119d, 0x8138, 0x1184, 0x8135, 0x116b, 0x8131, 0x1152, 0x812e, - 0x1139, 0x812b, 0x1121, 0x8127, 0x1108, 0x8124, 0x10ef, 0x8121, - 0x10d6, 0x811d, 0x10bd, 0x811a, 0x10a4, 0x8117, 0x108b, 0x8113, - 0x1072, 0x8110, 0x1059, 0x810d, 0x1040, 0x810a, 0x1027, 0x8107, - 0x100e, 0x8103, 0xff5, 0x8100, 0xfdd, 0x80fd, 0xfc4, 0x80fa, - 0xfab, 0x80f7, 0xf92, 0x80f4, 0xf79, 0x80f1, 0xf60, 0x80ee, - 0xf47, 0x80eb, 0xf2e, 0x80e8, 0xf15, 0x80e5, 0xefc, 0x80e2, - 0xee3, 0x80df, 0xeca, 0x80dc, 0xeb1, 0x80d9, 0xe98, 0x80d6, - 0xe7f, 0x80d3, 0xe66, 0x80d1, 0xe4d, 0x80ce, 0xe34, 0x80cb, - 0xe1b, 0x80c8, 0xe02, 0x80c5, 0xde9, 0x80c3, 0xdd0, 0x80c0, - 0xdb7, 0x80bd, 0xd9e, 0x80bb, 0xd85, 0x80b8, 0xd6c, 0x80b5, - 0xd53, 0x80b3, 0xd3a, 0x80b0, 0xd21, 0x80ad, 0xd08, 0x80ab, - 0xcef, 0x80a8, 0xcd6, 0x80a6, 0xcbd, 0x80a3, 0xca4, 0x80a1, - 0xc8b, 0x809e, 0xc72, 0x809c, 0xc59, 0x8099, 0xc40, 0x8097, - 0xc27, 0x8095, 0xc0e, 0x8092, 0xbf5, 0x8090, 0xbdc, 0x808e, - 0xbc3, 0x808b, 0xbaa, 0x8089, 0xb91, 0x8087, 0xb78, 0x8084, - 0xb5f, 0x8082, 0xb46, 0x8080, 0xb2d, 0x807e, 0xb14, 0x807b, - 0xafb, 0x8079, 0xae2, 0x8077, 0xac9, 0x8075, 0xab0, 0x8073, - 0xa97, 0x8071, 0xa7e, 0x806f, 0xa65, 0x806d, 0xa4c, 0x806b, - 0xa33, 0x8069, 0xa19, 0x8067, 0xa00, 0x8065, 0x9e7, 0x8063, - 0x9ce, 0x8061, 0x9b5, 0x805f, 0x99c, 0x805d, 0x983, 0x805b, - 0x96a, 0x8059, 0x951, 0x8057, 0x938, 0x8056, 0x91f, 0x8054, - 0x906, 0x8052, 0x8ed, 0x8050, 0x8d4, 0x804f, 0x8bb, 0x804d, - 0x8a2, 0x804b, 0x888, 0x8049, 0x86f, 0x8048, 0x856, 0x8046, - 0x83d, 0x8044, 0x824, 0x8043, 0x80b, 0x8041, 0x7f2, 0x8040, - 0x7d9, 0x803e, 0x7c0, 0x803d, 0x7a7, 0x803b, 0x78e, 0x803a, - 0x775, 0x8038, 0x75b, 0x8037, 0x742, 0x8035, 0x729, 0x8034, - 0x710, 0x8032, 0x6f7, 0x8031, 0x6de, 0x8030, 0x6c5, 0x802e, - 0x6ac, 0x802d, 0x693, 0x802c, 0x67a, 0x802a, 0x660, 0x8029, - 0x647, 0x8028, 0x62e, 0x8027, 0x615, 0x8026, 0x5fc, 0x8024, - 0x5e3, 0x8023, 0x5ca, 0x8022, 0x5b1, 0x8021, 0x598, 0x8020, - 0x57f, 0x801f, 0x565, 0x801e, 0x54c, 0x801d, 0x533, 0x801c, - 0x51a, 0x801b, 0x501, 0x801a, 0x4e8, 0x8019, 0x4cf, 0x8018, - 0x4b6, 0x8017, 0x49c, 0x8016, 0x483, 0x8015, 0x46a, 0x8014, - 0x451, 0x8013, 0x438, 0x8012, 0x41f, 0x8012, 0x406, 0x8011, - 0x3ed, 0x8010, 0x3d4, 0x800f, 0x3ba, 0x800e, 0x3a1, 0x800e, - 0x388, 0x800d, 0x36f, 0x800c, 0x356, 0x800c, 0x33d, 0x800b, - 0x324, 0x800a, 0x30b, 0x800a, 0x2f1, 0x8009, 0x2d8, 0x8009, - 0x2bf, 0x8008, 0x2a6, 0x8008, 0x28d, 0x8007, 0x274, 0x8007, - 0x25b, 0x8006, 0x242, 0x8006, 0x228, 0x8005, 0x20f, 0x8005, - 0x1f6, 0x8004, 0x1dd, 0x8004, 0x1c4, 0x8004, 0x1ab, 0x8003, - 0x192, 0x8003, 0x178, 0x8003, 0x15f, 0x8002, 0x146, 0x8002, - 0x12d, 0x8002, 0x114, 0x8002, 0xfb, 0x8001, 0xe2, 0x8001, - 0xc9, 0x8001, 0xaf, 0x8001, 0x96, 0x8001, 0x7d, 0x8001, - 0x64, 0x8001, 0x4b, 0x8001, 0x32, 0x8001, 0x19, 0x8001, -}; - -/** -* \par -* cosFactor tables are generated using the formula :
 cos_factors[n] = 2 * cos((2n+1)*pi/(4*N)) 
-* \par -* C command to generate the table -*
   
-* for(i = 0; i< N; i++)   
-* {   
-*   cos_factors[i]= 2 * cos((2*i+1)*c/2);   
-* } 
-* \par -* where N is the number of factors to generate and c is pi/(2*N) -* \par -* Then converted to q15 format by multiplying with 2^31 and saturated if required. - -*/ - -static const q15_t cos_factorsQ15_128[128] = { - 0x7fff, 0x7ffa, 0x7ff0, 0x7fe1, 0x7fce, 0x7fb5, 0x7f97, 0x7f75, - 0x7f4d, 0x7f21, 0x7ef0, 0x7eba, 0x7e7f, 0x7e3f, 0x7dfa, 0x7db0, - 0x7d62, 0x7d0f, 0x7cb7, 0x7c5a, 0x7bf8, 0x7b92, 0x7b26, 0x7ab6, - 0x7a42, 0x79c8, 0x794a, 0x78c7, 0x7840, 0x77b4, 0x7723, 0x768e, - 0x75f4, 0x7555, 0x74b2, 0x740b, 0x735f, 0x72af, 0x71fa, 0x7141, - 0x7083, 0x6fc1, 0x6efb, 0x6e30, 0x6d62, 0x6c8f, 0x6bb8, 0x6adc, - 0x69fd, 0x6919, 0x6832, 0x6746, 0x6657, 0x6563, 0x646c, 0x6371, - 0x6271, 0x616f, 0x6068, 0x5f5e, 0x5e50, 0x5d3e, 0x5c29, 0x5b10, - 0x59f3, 0x58d4, 0x57b0, 0x568a, 0x5560, 0x5433, 0x5302, 0x51ce, - 0x5097, 0x4f5e, 0x4e21, 0x4ce1, 0x4b9e, 0x4a58, 0x490f, 0x47c3, - 0x4675, 0x4524, 0x43d0, 0x427a, 0x4121, 0x3fc5, 0x3e68, 0x3d07, - 0x3ba5, 0x3a40, 0x38d8, 0x376f, 0x3604, 0x3496, 0x3326, 0x31b5, - 0x3041, 0x2ecc, 0x2d55, 0x2bdc, 0x2a61, 0x28e5, 0x2767, 0x25e8, - 0x2467, 0x22e5, 0x2161, 0x1fdc, 0x1e56, 0x1ccf, 0x1b47, 0x19bd, - 0x1833, 0x16a8, 0x151b, 0x138e, 0x1201, 0x1072, 0xee3, 0xd53, - 0xbc3, 0xa33, 0x8a2, 0x710, 0x57f, 0x3ed, 0x25b, 0xc9 -}; - -static const q15_t cos_factorsQ15_512[512] = { - 0x7fff, 0x7fff, 0x7fff, 0x7ffe, 0x7ffc, 0x7ffb, 0x7ff9, 0x7ff7, - 0x7ff4, 0x7ff2, 0x7fee, 0x7feb, 0x7fe7, 0x7fe3, 0x7fdf, 0x7fda, - 0x7fd6, 0x7fd0, 0x7fcb, 0x7fc5, 0x7fbf, 0x7fb8, 0x7fb1, 0x7faa, - 0x7fa3, 0x7f9b, 0x7f93, 0x7f8b, 0x7f82, 0x7f79, 0x7f70, 0x7f67, - 0x7f5d, 0x7f53, 0x7f48, 0x7f3d, 0x7f32, 0x7f27, 0x7f1b, 0x7f0f, - 0x7f03, 0x7ef6, 0x7ee9, 0x7edc, 0x7ecf, 0x7ec1, 0x7eb3, 0x7ea4, - 0x7e95, 0x7e86, 0x7e77, 0x7e67, 0x7e57, 0x7e47, 0x7e37, 0x7e26, - 0x7e14, 0x7e03, 0x7df1, 0x7ddf, 0x7dcd, 0x7dba, 0x7da7, 0x7d94, - 0x7d80, 0x7d6c, 0x7d58, 0x7d43, 0x7d2f, 0x7d19, 0x7d04, 0x7cee, - 0x7cd8, 0x7cc2, 0x7cab, 0x7c94, 0x7c7d, 0x7c66, 0x7c4e, 0x7c36, - 0x7c1d, 0x7c05, 0x7beb, 0x7bd2, 0x7bb9, 0x7b9f, 0x7b84, 0x7b6a, - 0x7b4f, 0x7b34, 0x7b19, 0x7afd, 0x7ae1, 0x7ac5, 0x7aa8, 0x7a8b, - 0x7a6e, 0x7a50, 0x7a33, 0x7a15, 0x79f6, 0x79d8, 0x79b9, 0x7999, - 0x797a, 0x795a, 0x793a, 0x7919, 0x78f9, 0x78d8, 0x78b6, 0x7895, - 0x7873, 0x7851, 0x782e, 0x780c, 0x77e9, 0x77c5, 0x77a2, 0x777e, - 0x775a, 0x7735, 0x7710, 0x76eb, 0x76c6, 0x76a0, 0x767b, 0x7654, - 0x762e, 0x7607, 0x75e0, 0x75b9, 0x7591, 0x7569, 0x7541, 0x7519, - 0x74f0, 0x74c7, 0x749e, 0x7474, 0x744a, 0x7420, 0x73f6, 0x73cb, - 0x73a0, 0x7375, 0x7349, 0x731d, 0x72f1, 0x72c5, 0x7298, 0x726b, - 0x723e, 0x7211, 0x71e3, 0x71b5, 0x7186, 0x7158, 0x7129, 0x70fa, - 0x70cb, 0x709b, 0x706b, 0x703b, 0x700a, 0x6fda, 0x6fa9, 0x6f77, - 0x6f46, 0x6f14, 0x6ee2, 0x6eaf, 0x6e7d, 0x6e4a, 0x6e17, 0x6de3, - 0x6db0, 0x6d7c, 0x6d48, 0x6d13, 0x6cde, 0x6ca9, 0x6c74, 0x6c3f, - 0x6c09, 0x6bd3, 0x6b9c, 0x6b66, 0x6b2f, 0x6af8, 0x6ac1, 0x6a89, - 0x6a51, 0x6a19, 0x69e1, 0x69a8, 0x696f, 0x6936, 0x68fd, 0x68c3, - 0x6889, 0x684f, 0x6815, 0x67da, 0x679f, 0x6764, 0x6729, 0x66ed, - 0x66b1, 0x6675, 0x6639, 0x65fc, 0x65bf, 0x6582, 0x6545, 0x6507, - 0x64c9, 0x648b, 0x644d, 0x640e, 0x63cf, 0x6390, 0x6351, 0x6311, - 0x62d2, 0x6292, 0x6251, 0x6211, 0x61d0, 0x618f, 0x614e, 0x610d, - 0x60cb, 0x6089, 0x6047, 0x6004, 0x5fc2, 0x5f7f, 0x5f3c, 0x5ef9, - 0x5eb5, 0x5e71, 0x5e2d, 0x5de9, 0x5da5, 0x5d60, 0x5d1b, 0x5cd6, - 0x5c91, 0x5c4b, 0x5c06, 0x5bc0, 0x5b79, 0x5b33, 0x5aec, 0x5aa5, - 0x5a5e, 0x5a17, 0x59d0, 0x5988, 0x5940, 0x58f8, 0x58af, 0x5867, - 0x581e, 0x57d5, 0x578c, 0x5742, 0x56f9, 0x56af, 0x5665, 0x561a, - 0x55d0, 0x5585, 0x553a, 0x54ef, 0x54a4, 0x5458, 0x540d, 0x53c1, - 0x5375, 0x5328, 0x52dc, 0x528f, 0x5242, 0x51f5, 0x51a8, 0x515a, - 0x510c, 0x50bf, 0x5070, 0x5022, 0x4fd4, 0x4f85, 0x4f36, 0x4ee7, - 0x4e98, 0x4e48, 0x4df9, 0x4da9, 0x4d59, 0x4d09, 0x4cb8, 0x4c68, - 0x4c17, 0x4bc6, 0x4b75, 0x4b24, 0x4ad2, 0x4a81, 0x4a2f, 0x49dd, - 0x498a, 0x4938, 0x48e6, 0x4893, 0x4840, 0x47ed, 0x479a, 0x4746, - 0x46f3, 0x469f, 0x464b, 0x45f7, 0x45a3, 0x454e, 0x44fa, 0x44a5, - 0x4450, 0x43fb, 0x43a5, 0x4350, 0x42fa, 0x42a5, 0x424f, 0x41f9, - 0x41a2, 0x414c, 0x40f6, 0x409f, 0x4048, 0x3ff1, 0x3f9a, 0x3f43, - 0x3eeb, 0x3e93, 0x3e3c, 0x3de4, 0x3d8c, 0x3d33, 0x3cdb, 0x3c83, - 0x3c2a, 0x3bd1, 0x3b78, 0x3b1f, 0x3ac6, 0x3a6c, 0x3a13, 0x39b9, - 0x395f, 0x3906, 0x38ab, 0x3851, 0x37f7, 0x379c, 0x3742, 0x36e7, - 0x368c, 0x3631, 0x35d6, 0x357b, 0x351f, 0x34c4, 0x3468, 0x340c, - 0x33b0, 0x3354, 0x32f8, 0x329c, 0x3240, 0x31e3, 0x3186, 0x312a, - 0x30cd, 0x3070, 0x3013, 0x2fb5, 0x2f58, 0x2efb, 0x2e9d, 0x2e3f, - 0x2de2, 0x2d84, 0x2d26, 0x2cc8, 0x2c69, 0x2c0b, 0x2bad, 0x2b4e, - 0x2aef, 0x2a91, 0x2a32, 0x29d3, 0x2974, 0x2915, 0x28b5, 0x2856, - 0x27f6, 0x2797, 0x2737, 0x26d8, 0x2678, 0x2618, 0x25b8, 0x2558, - 0x24f7, 0x2497, 0x2437, 0x23d6, 0x2376, 0x2315, 0x22b4, 0x2254, - 0x21f3, 0x2192, 0x2131, 0x20d0, 0x206e, 0x200d, 0x1fac, 0x1f4a, - 0x1ee9, 0x1e87, 0x1e25, 0x1dc4, 0x1d62, 0x1d00, 0x1c9e, 0x1c3c, - 0x1bda, 0x1b78, 0x1b16, 0x1ab3, 0x1a51, 0x19ef, 0x198c, 0x192a, - 0x18c7, 0x1864, 0x1802, 0x179f, 0x173c, 0x16d9, 0x1676, 0x1613, - 0x15b0, 0x154d, 0x14ea, 0x1487, 0x1423, 0x13c0, 0x135d, 0x12f9, - 0x1296, 0x1232, 0x11cf, 0x116b, 0x1108, 0x10a4, 0x1040, 0xfdd, - 0xf79, 0xf15, 0xeb1, 0xe4d, 0xde9, 0xd85, 0xd21, 0xcbd, - 0xc59, 0xbf5, 0xb91, 0xb2d, 0xac9, 0xa65, 0xa00, 0x99c, - 0x938, 0x8d4, 0x86f, 0x80b, 0x7a7, 0x742, 0x6de, 0x67a, - 0x615, 0x5b1, 0x54c, 0x4e8, 0x483, 0x41f, 0x3ba, 0x356, - 0x2f1, 0x28d, 0x228, 0x1c4, 0x15f, 0xfb, 0x96, 0x32, -}; - -static const q15_t cos_factorsQ15_2048[2048] = { - 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, - 0x7fff, 0x7fff, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffd, 0x7ffd, - 0x7ffd, 0x7ffd, 0x7ffc, 0x7ffc, 0x7ffb, 0x7ffb, 0x7ffb, 0x7ffa, - 0x7ffa, 0x7ff9, 0x7ff9, 0x7ff8, 0x7ff8, 0x7ff7, 0x7ff7, 0x7ff6, - 0x7ff5, 0x7ff5, 0x7ff4, 0x7ff3, 0x7ff3, 0x7ff2, 0x7ff1, 0x7ff0, - 0x7ff0, 0x7fef, 0x7fee, 0x7fed, 0x7fec, 0x7fec, 0x7feb, 0x7fea, - 0x7fe9, 0x7fe8, 0x7fe7, 0x7fe6, 0x7fe5, 0x7fe4, 0x7fe3, 0x7fe2, - 0x7fe1, 0x7fe0, 0x7fdf, 0x7fdd, 0x7fdc, 0x7fdb, 0x7fda, 0x7fd9, - 0x7fd7, 0x7fd6, 0x7fd5, 0x7fd4, 0x7fd2, 0x7fd1, 0x7fd0, 0x7fce, - 0x7fcd, 0x7fcb, 0x7fca, 0x7fc9, 0x7fc7, 0x7fc6, 0x7fc4, 0x7fc3, - 0x7fc1, 0x7fc0, 0x7fbe, 0x7fbc, 0x7fbb, 0x7fb9, 0x7fb7, 0x7fb6, - 0x7fb4, 0x7fb2, 0x7fb1, 0x7faf, 0x7fad, 0x7fab, 0x7fa9, 0x7fa8, - 0x7fa6, 0x7fa4, 0x7fa2, 0x7fa0, 0x7f9e, 0x7f9c, 0x7f9a, 0x7f98, - 0x7f96, 0x7f94, 0x7f92, 0x7f90, 0x7f8e, 0x7f8c, 0x7f8a, 0x7f88, - 0x7f86, 0x7f83, 0x7f81, 0x7f7f, 0x7f7d, 0x7f7b, 0x7f78, 0x7f76, - 0x7f74, 0x7f71, 0x7f6f, 0x7f6d, 0x7f6a, 0x7f68, 0x7f65, 0x7f63, - 0x7f60, 0x7f5e, 0x7f5b, 0x7f59, 0x7f56, 0x7f54, 0x7f51, 0x7f4f, - 0x7f4c, 0x7f49, 0x7f47, 0x7f44, 0x7f41, 0x7f3f, 0x7f3c, 0x7f39, - 0x7f36, 0x7f34, 0x7f31, 0x7f2e, 0x7f2b, 0x7f28, 0x7f25, 0x7f23, - 0x7f20, 0x7f1d, 0x7f1a, 0x7f17, 0x7f14, 0x7f11, 0x7f0e, 0x7f0b, - 0x7f08, 0x7f04, 0x7f01, 0x7efe, 0x7efb, 0x7ef8, 0x7ef5, 0x7ef1, - 0x7eee, 0x7eeb, 0x7ee8, 0x7ee4, 0x7ee1, 0x7ede, 0x7eda, 0x7ed7, - 0x7ed4, 0x7ed0, 0x7ecd, 0x7ec9, 0x7ec6, 0x7ec3, 0x7ebf, 0x7ebb, - 0x7eb8, 0x7eb4, 0x7eb1, 0x7ead, 0x7eaa, 0x7ea6, 0x7ea2, 0x7e9f, - 0x7e9b, 0x7e97, 0x7e94, 0x7e90, 0x7e8c, 0x7e88, 0x7e84, 0x7e81, - 0x7e7d, 0x7e79, 0x7e75, 0x7e71, 0x7e6d, 0x7e69, 0x7e65, 0x7e61, - 0x7e5d, 0x7e59, 0x7e55, 0x7e51, 0x7e4d, 0x7e49, 0x7e45, 0x7e41, - 0x7e3d, 0x7e39, 0x7e34, 0x7e30, 0x7e2c, 0x7e28, 0x7e24, 0x7e1f, - 0x7e1b, 0x7e17, 0x7e12, 0x7e0e, 0x7e0a, 0x7e05, 0x7e01, 0x7dfc, - 0x7df8, 0x7df3, 0x7def, 0x7dea, 0x7de6, 0x7de1, 0x7ddd, 0x7dd8, - 0x7dd4, 0x7dcf, 0x7dca, 0x7dc6, 0x7dc1, 0x7dbc, 0x7db8, 0x7db3, - 0x7dae, 0x7da9, 0x7da5, 0x7da0, 0x7d9b, 0x7d96, 0x7d91, 0x7d8c, - 0x7d87, 0x7d82, 0x7d7e, 0x7d79, 0x7d74, 0x7d6f, 0x7d6a, 0x7d65, - 0x7d60, 0x7d5a, 0x7d55, 0x7d50, 0x7d4b, 0x7d46, 0x7d41, 0x7d3c, - 0x7d36, 0x7d31, 0x7d2c, 0x7d27, 0x7d21, 0x7d1c, 0x7d17, 0x7d11, - 0x7d0c, 0x7d07, 0x7d01, 0x7cfc, 0x7cf6, 0x7cf1, 0x7cec, 0x7ce6, - 0x7ce1, 0x7cdb, 0x7cd5, 0x7cd0, 0x7cca, 0x7cc5, 0x7cbf, 0x7cb9, - 0x7cb4, 0x7cae, 0x7ca8, 0x7ca3, 0x7c9d, 0x7c97, 0x7c91, 0x7c8c, - 0x7c86, 0x7c80, 0x7c7a, 0x7c74, 0x7c6e, 0x7c69, 0x7c63, 0x7c5d, - 0x7c57, 0x7c51, 0x7c4b, 0x7c45, 0x7c3f, 0x7c39, 0x7c33, 0x7c2d, - 0x7c26, 0x7c20, 0x7c1a, 0x7c14, 0x7c0e, 0x7c08, 0x7c01, 0x7bfb, - 0x7bf5, 0x7bef, 0x7be8, 0x7be2, 0x7bdc, 0x7bd5, 0x7bcf, 0x7bc9, - 0x7bc2, 0x7bbc, 0x7bb5, 0x7baf, 0x7ba8, 0x7ba2, 0x7b9b, 0x7b95, - 0x7b8e, 0x7b88, 0x7b81, 0x7b7a, 0x7b74, 0x7b6d, 0x7b67, 0x7b60, - 0x7b59, 0x7b52, 0x7b4c, 0x7b45, 0x7b3e, 0x7b37, 0x7b31, 0x7b2a, - 0x7b23, 0x7b1c, 0x7b15, 0x7b0e, 0x7b07, 0x7b00, 0x7af9, 0x7af2, - 0x7aeb, 0x7ae4, 0x7add, 0x7ad6, 0x7acf, 0x7ac8, 0x7ac1, 0x7aba, - 0x7ab3, 0x7aac, 0x7aa4, 0x7a9d, 0x7a96, 0x7a8f, 0x7a87, 0x7a80, - 0x7a79, 0x7a72, 0x7a6a, 0x7a63, 0x7a5c, 0x7a54, 0x7a4d, 0x7a45, - 0x7a3e, 0x7a36, 0x7a2f, 0x7a27, 0x7a20, 0x7a18, 0x7a11, 0x7a09, - 0x7a02, 0x79fa, 0x79f2, 0x79eb, 0x79e3, 0x79db, 0x79d4, 0x79cc, - 0x79c4, 0x79bc, 0x79b5, 0x79ad, 0x79a5, 0x799d, 0x7995, 0x798e, - 0x7986, 0x797e, 0x7976, 0x796e, 0x7966, 0x795e, 0x7956, 0x794e, - 0x7946, 0x793e, 0x7936, 0x792e, 0x7926, 0x791e, 0x7915, 0x790d, - 0x7905, 0x78fd, 0x78f5, 0x78ec, 0x78e4, 0x78dc, 0x78d4, 0x78cb, - 0x78c3, 0x78bb, 0x78b2, 0x78aa, 0x78a2, 0x7899, 0x7891, 0x7888, - 0x7880, 0x7877, 0x786f, 0x7866, 0x785e, 0x7855, 0x784d, 0x7844, - 0x783b, 0x7833, 0x782a, 0x7821, 0x7819, 0x7810, 0x7807, 0x77ff, - 0x77f6, 0x77ed, 0x77e4, 0x77db, 0x77d3, 0x77ca, 0x77c1, 0x77b8, - 0x77af, 0x77a6, 0x779d, 0x7794, 0x778b, 0x7782, 0x7779, 0x7770, - 0x7767, 0x775e, 0x7755, 0x774c, 0x7743, 0x773a, 0x7731, 0x7727, - 0x771e, 0x7715, 0x770c, 0x7703, 0x76f9, 0x76f0, 0x76e7, 0x76dd, - 0x76d4, 0x76cb, 0x76c1, 0x76b8, 0x76af, 0x76a5, 0x769c, 0x7692, - 0x7689, 0x767f, 0x7676, 0x766c, 0x7663, 0x7659, 0x7650, 0x7646, - 0x763c, 0x7633, 0x7629, 0x761f, 0x7616, 0x760c, 0x7602, 0x75f9, - 0x75ef, 0x75e5, 0x75db, 0x75d1, 0x75c8, 0x75be, 0x75b4, 0x75aa, - 0x75a0, 0x7596, 0x758c, 0x7582, 0x7578, 0x756e, 0x7564, 0x755a, - 0x7550, 0x7546, 0x753c, 0x7532, 0x7528, 0x751e, 0x7514, 0x7509, - 0x74ff, 0x74f5, 0x74eb, 0x74e1, 0x74d6, 0x74cc, 0x74c2, 0x74b7, - 0x74ad, 0x74a3, 0x7498, 0x748e, 0x7484, 0x7479, 0x746f, 0x7464, - 0x745a, 0x744f, 0x7445, 0x743a, 0x7430, 0x7425, 0x741b, 0x7410, - 0x7406, 0x73fb, 0x73f0, 0x73e6, 0x73db, 0x73d0, 0x73c6, 0x73bb, - 0x73b0, 0x73a5, 0x739b, 0x7390, 0x7385, 0x737a, 0x736f, 0x7364, - 0x7359, 0x734f, 0x7344, 0x7339, 0x732e, 0x7323, 0x7318, 0x730d, - 0x7302, 0x72f7, 0x72ec, 0x72e1, 0x72d5, 0x72ca, 0x72bf, 0x72b4, - 0x72a9, 0x729e, 0x7293, 0x7287, 0x727c, 0x7271, 0x7266, 0x725a, - 0x724f, 0x7244, 0x7238, 0x722d, 0x7222, 0x7216, 0x720b, 0x71ff, - 0x71f4, 0x71e9, 0x71dd, 0x71d2, 0x71c6, 0x71bb, 0x71af, 0x71a3, - 0x7198, 0x718c, 0x7181, 0x7175, 0x7169, 0x715e, 0x7152, 0x7146, - 0x713b, 0x712f, 0x7123, 0x7117, 0x710c, 0x7100, 0x70f4, 0x70e8, - 0x70dc, 0x70d1, 0x70c5, 0x70b9, 0x70ad, 0x70a1, 0x7095, 0x7089, - 0x707d, 0x7071, 0x7065, 0x7059, 0x704d, 0x7041, 0x7035, 0x7029, - 0x701d, 0x7010, 0x7004, 0x6ff8, 0x6fec, 0x6fe0, 0x6fd3, 0x6fc7, - 0x6fbb, 0x6faf, 0x6fa2, 0x6f96, 0x6f8a, 0x6f7d, 0x6f71, 0x6f65, - 0x6f58, 0x6f4c, 0x6f3f, 0x6f33, 0x6f27, 0x6f1a, 0x6f0e, 0x6f01, - 0x6ef5, 0x6ee8, 0x6edc, 0x6ecf, 0x6ec2, 0x6eb6, 0x6ea9, 0x6e9c, - 0x6e90, 0x6e83, 0x6e76, 0x6e6a, 0x6e5d, 0x6e50, 0x6e44, 0x6e37, - 0x6e2a, 0x6e1d, 0x6e10, 0x6e04, 0x6df7, 0x6dea, 0x6ddd, 0x6dd0, - 0x6dc3, 0x6db6, 0x6da9, 0x6d9c, 0x6d8f, 0x6d82, 0x6d75, 0x6d68, - 0x6d5b, 0x6d4e, 0x6d41, 0x6d34, 0x6d27, 0x6d1a, 0x6d0c, 0x6cff, - 0x6cf2, 0x6ce5, 0x6cd8, 0x6cca, 0x6cbd, 0x6cb0, 0x6ca3, 0x6c95, - 0x6c88, 0x6c7b, 0x6c6d, 0x6c60, 0x6c53, 0x6c45, 0x6c38, 0x6c2a, - 0x6c1d, 0x6c0f, 0x6c02, 0x6bf5, 0x6be7, 0x6bd9, 0x6bcc, 0x6bbe, - 0x6bb1, 0x6ba3, 0x6b96, 0x6b88, 0x6b7a, 0x6b6d, 0x6b5f, 0x6b51, - 0x6b44, 0x6b36, 0x6b28, 0x6b1a, 0x6b0d, 0x6aff, 0x6af1, 0x6ae3, - 0x6ad5, 0x6ac8, 0x6aba, 0x6aac, 0x6a9e, 0x6a90, 0x6a82, 0x6a74, - 0x6a66, 0x6a58, 0x6a4a, 0x6a3c, 0x6a2e, 0x6a20, 0x6a12, 0x6a04, - 0x69f6, 0x69e8, 0x69da, 0x69cb, 0x69bd, 0x69af, 0x69a1, 0x6993, - 0x6985, 0x6976, 0x6968, 0x695a, 0x694b, 0x693d, 0x692f, 0x6921, - 0x6912, 0x6904, 0x68f5, 0x68e7, 0x68d9, 0x68ca, 0x68bc, 0x68ad, - 0x689f, 0x6890, 0x6882, 0x6873, 0x6865, 0x6856, 0x6848, 0x6839, - 0x682b, 0x681c, 0x680d, 0x67ff, 0x67f0, 0x67e1, 0x67d3, 0x67c4, - 0x67b5, 0x67a6, 0x6798, 0x6789, 0x677a, 0x676b, 0x675d, 0x674e, - 0x673f, 0x6730, 0x6721, 0x6712, 0x6703, 0x66f4, 0x66e5, 0x66d6, - 0x66c8, 0x66b9, 0x66aa, 0x669b, 0x668b, 0x667c, 0x666d, 0x665e, - 0x664f, 0x6640, 0x6631, 0x6622, 0x6613, 0x6603, 0x65f4, 0x65e5, - 0x65d6, 0x65c7, 0x65b7, 0x65a8, 0x6599, 0x658a, 0x657a, 0x656b, - 0x655c, 0x654c, 0x653d, 0x652d, 0x651e, 0x650f, 0x64ff, 0x64f0, - 0x64e0, 0x64d1, 0x64c1, 0x64b2, 0x64a2, 0x6493, 0x6483, 0x6474, - 0x6464, 0x6454, 0x6445, 0x6435, 0x6426, 0x6416, 0x6406, 0x63f7, - 0x63e7, 0x63d7, 0x63c7, 0x63b8, 0x63a8, 0x6398, 0x6388, 0x6378, - 0x6369, 0x6359, 0x6349, 0x6339, 0x6329, 0x6319, 0x6309, 0x62f9, - 0x62ea, 0x62da, 0x62ca, 0x62ba, 0x62aa, 0x629a, 0x628a, 0x627a, - 0x6269, 0x6259, 0x6249, 0x6239, 0x6229, 0x6219, 0x6209, 0x61f9, - 0x61e8, 0x61d8, 0x61c8, 0x61b8, 0x61a8, 0x6197, 0x6187, 0x6177, - 0x6166, 0x6156, 0x6146, 0x6135, 0x6125, 0x6115, 0x6104, 0x60f4, - 0x60e4, 0x60d3, 0x60c3, 0x60b2, 0x60a2, 0x6091, 0x6081, 0x6070, - 0x6060, 0x604f, 0x603f, 0x602e, 0x601d, 0x600d, 0x5ffc, 0x5fec, - 0x5fdb, 0x5fca, 0x5fba, 0x5fa9, 0x5f98, 0x5f87, 0x5f77, 0x5f66, - 0x5f55, 0x5f44, 0x5f34, 0x5f23, 0x5f12, 0x5f01, 0x5ef0, 0x5edf, - 0x5ecf, 0x5ebe, 0x5ead, 0x5e9c, 0x5e8b, 0x5e7a, 0x5e69, 0x5e58, - 0x5e47, 0x5e36, 0x5e25, 0x5e14, 0x5e03, 0x5df2, 0x5de1, 0x5dd0, - 0x5dbf, 0x5dad, 0x5d9c, 0x5d8b, 0x5d7a, 0x5d69, 0x5d58, 0x5d46, - 0x5d35, 0x5d24, 0x5d13, 0x5d01, 0x5cf0, 0x5cdf, 0x5cce, 0x5cbc, - 0x5cab, 0x5c9a, 0x5c88, 0x5c77, 0x5c66, 0x5c54, 0x5c43, 0x5c31, - 0x5c20, 0x5c0e, 0x5bfd, 0x5beb, 0x5bda, 0x5bc8, 0x5bb7, 0x5ba5, - 0x5b94, 0x5b82, 0x5b71, 0x5b5f, 0x5b4d, 0x5b3c, 0x5b2a, 0x5b19, - 0x5b07, 0x5af5, 0x5ae4, 0x5ad2, 0x5ac0, 0x5aae, 0x5a9d, 0x5a8b, - 0x5a79, 0x5a67, 0x5a56, 0x5a44, 0x5a32, 0x5a20, 0x5a0e, 0x59fc, - 0x59ea, 0x59d9, 0x59c7, 0x59b5, 0x59a3, 0x5991, 0x597f, 0x596d, - 0x595b, 0x5949, 0x5937, 0x5925, 0x5913, 0x5901, 0x58ef, 0x58dd, - 0x58cb, 0x58b8, 0x58a6, 0x5894, 0x5882, 0x5870, 0x585e, 0x584b, - 0x5839, 0x5827, 0x5815, 0x5803, 0x57f0, 0x57de, 0x57cc, 0x57b9, - 0x57a7, 0x5795, 0x5783, 0x5770, 0x575e, 0x574b, 0x5739, 0x5727, - 0x5714, 0x5702, 0x56ef, 0x56dd, 0x56ca, 0x56b8, 0x56a5, 0x5693, - 0x5680, 0x566e, 0x565b, 0x5649, 0x5636, 0x5624, 0x5611, 0x55fe, - 0x55ec, 0x55d9, 0x55c7, 0x55b4, 0x55a1, 0x558f, 0x557c, 0x5569, - 0x5556, 0x5544, 0x5531, 0x551e, 0x550b, 0x54f9, 0x54e6, 0x54d3, - 0x54c0, 0x54ad, 0x549a, 0x5488, 0x5475, 0x5462, 0x544f, 0x543c, - 0x5429, 0x5416, 0x5403, 0x53f0, 0x53dd, 0x53ca, 0x53b7, 0x53a4, - 0x5391, 0x537e, 0x536b, 0x5358, 0x5345, 0x5332, 0x531f, 0x530c, - 0x52f8, 0x52e5, 0x52d2, 0x52bf, 0x52ac, 0x5299, 0x5285, 0x5272, - 0x525f, 0x524c, 0x5238, 0x5225, 0x5212, 0x51ff, 0x51eb, 0x51d8, - 0x51c5, 0x51b1, 0x519e, 0x518b, 0x5177, 0x5164, 0x5150, 0x513d, - 0x512a, 0x5116, 0x5103, 0x50ef, 0x50dc, 0x50c8, 0x50b5, 0x50a1, - 0x508e, 0x507a, 0x5067, 0x5053, 0x503f, 0x502c, 0x5018, 0x5005, - 0x4ff1, 0x4fdd, 0x4fca, 0x4fb6, 0x4fa2, 0x4f8f, 0x4f7b, 0x4f67, - 0x4f54, 0x4f40, 0x4f2c, 0x4f18, 0x4f05, 0x4ef1, 0x4edd, 0x4ec9, - 0x4eb6, 0x4ea2, 0x4e8e, 0x4e7a, 0x4e66, 0x4e52, 0x4e3e, 0x4e2a, - 0x4e17, 0x4e03, 0x4def, 0x4ddb, 0x4dc7, 0x4db3, 0x4d9f, 0x4d8b, - 0x4d77, 0x4d63, 0x4d4f, 0x4d3b, 0x4d27, 0x4d13, 0x4cff, 0x4ceb, - 0x4cd6, 0x4cc2, 0x4cae, 0x4c9a, 0x4c86, 0x4c72, 0x4c5e, 0x4c49, - 0x4c35, 0x4c21, 0x4c0d, 0x4bf9, 0x4be4, 0x4bd0, 0x4bbc, 0x4ba8, - 0x4b93, 0x4b7f, 0x4b6b, 0x4b56, 0x4b42, 0x4b2e, 0x4b19, 0x4b05, - 0x4af1, 0x4adc, 0x4ac8, 0x4ab4, 0x4a9f, 0x4a8b, 0x4a76, 0x4a62, - 0x4a4d, 0x4a39, 0x4a24, 0x4a10, 0x49fb, 0x49e7, 0x49d2, 0x49be, - 0x49a9, 0x4995, 0x4980, 0x496c, 0x4957, 0x4942, 0x492e, 0x4919, - 0x4905, 0x48f0, 0x48db, 0x48c7, 0x48b2, 0x489d, 0x4888, 0x4874, - 0x485f, 0x484a, 0x4836, 0x4821, 0x480c, 0x47f7, 0x47e2, 0x47ce, - 0x47b9, 0x47a4, 0x478f, 0x477a, 0x4765, 0x4751, 0x473c, 0x4727, - 0x4712, 0x46fd, 0x46e8, 0x46d3, 0x46be, 0x46a9, 0x4694, 0x467f, - 0x466a, 0x4655, 0x4640, 0x462b, 0x4616, 0x4601, 0x45ec, 0x45d7, - 0x45c2, 0x45ad, 0x4598, 0x4583, 0x456e, 0x4559, 0x4544, 0x452e, - 0x4519, 0x4504, 0x44ef, 0x44da, 0x44c5, 0x44af, 0x449a, 0x4485, - 0x4470, 0x445a, 0x4445, 0x4430, 0x441b, 0x4405, 0x43f0, 0x43db, - 0x43c5, 0x43b0, 0x439b, 0x4385, 0x4370, 0x435b, 0x4345, 0x4330, - 0x431b, 0x4305, 0x42f0, 0x42da, 0x42c5, 0x42af, 0x429a, 0x4284, - 0x426f, 0x425a, 0x4244, 0x422f, 0x4219, 0x4203, 0x41ee, 0x41d8, - 0x41c3, 0x41ad, 0x4198, 0x4182, 0x416d, 0x4157, 0x4141, 0x412c, - 0x4116, 0x4100, 0x40eb, 0x40d5, 0x40bf, 0x40aa, 0x4094, 0x407e, - 0x4069, 0x4053, 0x403d, 0x4027, 0x4012, 0x3ffc, 0x3fe6, 0x3fd0, - 0x3fbb, 0x3fa5, 0x3f8f, 0x3f79, 0x3f63, 0x3f4d, 0x3f38, 0x3f22, - 0x3f0c, 0x3ef6, 0x3ee0, 0x3eca, 0x3eb4, 0x3e9e, 0x3e88, 0x3e73, - 0x3e5d, 0x3e47, 0x3e31, 0x3e1b, 0x3e05, 0x3def, 0x3dd9, 0x3dc3, - 0x3dad, 0x3d97, 0x3d81, 0x3d6b, 0x3d55, 0x3d3e, 0x3d28, 0x3d12, - 0x3cfc, 0x3ce6, 0x3cd0, 0x3cba, 0x3ca4, 0x3c8e, 0x3c77, 0x3c61, - 0x3c4b, 0x3c35, 0x3c1f, 0x3c09, 0x3bf2, 0x3bdc, 0x3bc6, 0x3bb0, - 0x3b99, 0x3b83, 0x3b6d, 0x3b57, 0x3b40, 0x3b2a, 0x3b14, 0x3afe, - 0x3ae7, 0x3ad1, 0x3abb, 0x3aa4, 0x3a8e, 0x3a78, 0x3a61, 0x3a4b, - 0x3a34, 0x3a1e, 0x3a08, 0x39f1, 0x39db, 0x39c4, 0x39ae, 0x3998, - 0x3981, 0x396b, 0x3954, 0x393e, 0x3927, 0x3911, 0x38fa, 0x38e4, - 0x38cd, 0x38b7, 0x38a0, 0x388a, 0x3873, 0x385d, 0x3846, 0x382f, - 0x3819, 0x3802, 0x37ec, 0x37d5, 0x37be, 0x37a8, 0x3791, 0x377a, - 0x3764, 0x374d, 0x3736, 0x3720, 0x3709, 0x36f2, 0x36dc, 0x36c5, - 0x36ae, 0x3698, 0x3681, 0x366a, 0x3653, 0x363d, 0x3626, 0x360f, - 0x35f8, 0x35e1, 0x35cb, 0x35b4, 0x359d, 0x3586, 0x356f, 0x3558, - 0x3542, 0x352b, 0x3514, 0x34fd, 0x34e6, 0x34cf, 0x34b8, 0x34a1, - 0x348b, 0x3474, 0x345d, 0x3446, 0x342f, 0x3418, 0x3401, 0x33ea, - 0x33d3, 0x33bc, 0x33a5, 0x338e, 0x3377, 0x3360, 0x3349, 0x3332, - 0x331b, 0x3304, 0x32ed, 0x32d6, 0x32bf, 0x32a8, 0x3290, 0x3279, - 0x3262, 0x324b, 0x3234, 0x321d, 0x3206, 0x31ef, 0x31d8, 0x31c0, - 0x31a9, 0x3192, 0x317b, 0x3164, 0x314c, 0x3135, 0x311e, 0x3107, - 0x30f0, 0x30d8, 0x30c1, 0x30aa, 0x3093, 0x307b, 0x3064, 0x304d, - 0x3036, 0x301e, 0x3007, 0x2ff0, 0x2fd8, 0x2fc1, 0x2faa, 0x2f92, - 0x2f7b, 0x2f64, 0x2f4c, 0x2f35, 0x2f1e, 0x2f06, 0x2eef, 0x2ed8, - 0x2ec0, 0x2ea9, 0x2e91, 0x2e7a, 0x2e63, 0x2e4b, 0x2e34, 0x2e1c, - 0x2e05, 0x2ded, 0x2dd6, 0x2dbe, 0x2da7, 0x2d8f, 0x2d78, 0x2d60, - 0x2d49, 0x2d31, 0x2d1a, 0x2d02, 0x2ceb, 0x2cd3, 0x2cbc, 0x2ca4, - 0x2c8d, 0x2c75, 0x2c5e, 0x2c46, 0x2c2e, 0x2c17, 0x2bff, 0x2be8, - 0x2bd0, 0x2bb8, 0x2ba1, 0x2b89, 0x2b71, 0x2b5a, 0x2b42, 0x2b2b, - 0x2b13, 0x2afb, 0x2ae4, 0x2acc, 0x2ab4, 0x2a9c, 0x2a85, 0x2a6d, - 0x2a55, 0x2a3e, 0x2a26, 0x2a0e, 0x29f6, 0x29df, 0x29c7, 0x29af, - 0x2997, 0x2980, 0x2968, 0x2950, 0x2938, 0x2920, 0x2909, 0x28f1, - 0x28d9, 0x28c1, 0x28a9, 0x2892, 0x287a, 0x2862, 0x284a, 0x2832, - 0x281a, 0x2802, 0x27eb, 0x27d3, 0x27bb, 0x27a3, 0x278b, 0x2773, - 0x275b, 0x2743, 0x272b, 0x2713, 0x26fb, 0x26e4, 0x26cc, 0x26b4, - 0x269c, 0x2684, 0x266c, 0x2654, 0x263c, 0x2624, 0x260c, 0x25f4, - 0x25dc, 0x25c4, 0x25ac, 0x2594, 0x257c, 0x2564, 0x254c, 0x2534, - 0x251c, 0x2503, 0x24eb, 0x24d3, 0x24bb, 0x24a3, 0x248b, 0x2473, - 0x245b, 0x2443, 0x242b, 0x2413, 0x23fa, 0x23e2, 0x23ca, 0x23b2, - 0x239a, 0x2382, 0x236a, 0x2352, 0x2339, 0x2321, 0x2309, 0x22f1, - 0x22d9, 0x22c0, 0x22a8, 0x2290, 0x2278, 0x2260, 0x2247, 0x222f, - 0x2217, 0x21ff, 0x21e7, 0x21ce, 0x21b6, 0x219e, 0x2186, 0x216d, - 0x2155, 0x213d, 0x2125, 0x210c, 0x20f4, 0x20dc, 0x20c3, 0x20ab, - 0x2093, 0x207a, 0x2062, 0x204a, 0x2032, 0x2019, 0x2001, 0x1fe9, - 0x1fd0, 0x1fb8, 0x1f9f, 0x1f87, 0x1f6f, 0x1f56, 0x1f3e, 0x1f26, - 0x1f0d, 0x1ef5, 0x1edd, 0x1ec4, 0x1eac, 0x1e93, 0x1e7b, 0x1e62, - 0x1e4a, 0x1e32, 0x1e19, 0x1e01, 0x1de8, 0x1dd0, 0x1db7, 0x1d9f, - 0x1d87, 0x1d6e, 0x1d56, 0x1d3d, 0x1d25, 0x1d0c, 0x1cf4, 0x1cdb, - 0x1cc3, 0x1caa, 0x1c92, 0x1c79, 0x1c61, 0x1c48, 0x1c30, 0x1c17, - 0x1bff, 0x1be6, 0x1bce, 0x1bb5, 0x1b9d, 0x1b84, 0x1b6c, 0x1b53, - 0x1b3a, 0x1b22, 0x1b09, 0x1af1, 0x1ad8, 0x1ac0, 0x1aa7, 0x1a8e, - 0x1a76, 0x1a5d, 0x1a45, 0x1a2c, 0x1a13, 0x19fb, 0x19e2, 0x19ca, - 0x19b1, 0x1998, 0x1980, 0x1967, 0x194e, 0x1936, 0x191d, 0x1905, - 0x18ec, 0x18d3, 0x18bb, 0x18a2, 0x1889, 0x1871, 0x1858, 0x183f, - 0x1827, 0x180e, 0x17f5, 0x17dd, 0x17c4, 0x17ab, 0x1792, 0x177a, - 0x1761, 0x1748, 0x1730, 0x1717, 0x16fe, 0x16e5, 0x16cd, 0x16b4, - 0x169b, 0x1682, 0x166a, 0x1651, 0x1638, 0x161f, 0x1607, 0x15ee, - 0x15d5, 0x15bc, 0x15a4, 0x158b, 0x1572, 0x1559, 0x1541, 0x1528, - 0x150f, 0x14f6, 0x14dd, 0x14c5, 0x14ac, 0x1493, 0x147a, 0x1461, - 0x1449, 0x1430, 0x1417, 0x13fe, 0x13e5, 0x13cc, 0x13b4, 0x139b, - 0x1382, 0x1369, 0x1350, 0x1337, 0x131f, 0x1306, 0x12ed, 0x12d4, - 0x12bb, 0x12a2, 0x1289, 0x1271, 0x1258, 0x123f, 0x1226, 0x120d, - 0x11f4, 0x11db, 0x11c2, 0x11a9, 0x1191, 0x1178, 0x115f, 0x1146, - 0x112d, 0x1114, 0x10fb, 0x10e2, 0x10c9, 0x10b0, 0x1098, 0x107f, - 0x1066, 0x104d, 0x1034, 0x101b, 0x1002, 0xfe9, 0xfd0, 0xfb7, - 0xf9e, 0xf85, 0xf6c, 0xf53, 0xf3a, 0xf21, 0xf08, 0xef0, - 0xed7, 0xebe, 0xea5, 0xe8c, 0xe73, 0xe5a, 0xe41, 0xe28, - 0xe0f, 0xdf6, 0xddd, 0xdc4, 0xdab, 0xd92, 0xd79, 0xd60, - 0xd47, 0xd2e, 0xd15, 0xcfc, 0xce3, 0xcca, 0xcb1, 0xc98, - 0xc7f, 0xc66, 0xc4d, 0xc34, 0xc1b, 0xc02, 0xbe9, 0xbd0, - 0xbb7, 0xb9e, 0xb85, 0xb6c, 0xb53, 0xb3a, 0xb20, 0xb07, - 0xaee, 0xad5, 0xabc, 0xaa3, 0xa8a, 0xa71, 0xa58, 0xa3f, - 0xa26, 0xa0d, 0x9f4, 0x9db, 0x9c2, 0x9a9, 0x990, 0x977, - 0x95e, 0x944, 0x92b, 0x912, 0x8f9, 0x8e0, 0x8c7, 0x8ae, - 0x895, 0x87c, 0x863, 0x84a, 0x831, 0x818, 0x7fe, 0x7e5, - 0x7cc, 0x7b3, 0x79a, 0x781, 0x768, 0x74f, 0x736, 0x71d, - 0x704, 0x6ea, 0x6d1, 0x6b8, 0x69f, 0x686, 0x66d, 0x654, - 0x63b, 0x622, 0x609, 0x5ef, 0x5d6, 0x5bd, 0x5a4, 0x58b, - 0x572, 0x559, 0x540, 0x527, 0x50d, 0x4f4, 0x4db, 0x4c2, - 0x4a9, 0x490, 0x477, 0x45e, 0x445, 0x42b, 0x412, 0x3f9, - 0x3e0, 0x3c7, 0x3ae, 0x395, 0x37c, 0x362, 0x349, 0x330, - 0x317, 0x2fe, 0x2e5, 0x2cc, 0x2b3, 0x299, 0x280, 0x267, - 0x24e, 0x235, 0x21c, 0x203, 0x1ea, 0x1d0, 0x1b7, 0x19e, - 0x185, 0x16c, 0x153, 0x13a, 0x121, 0x107, 0xee, 0xd5, - 0xbc, 0xa3, 0x8a, 0x71, 0x57, 0x3e, 0x25, 0xc, - -}; - -/** - * @brief Initialization function for the Q15 DCT4/IDCT4. - * @param[in,out] *S points to an instance of Q15 DCT4/IDCT4 structure. - * @param[in] *S_RFFT points to an instance of Q15 RFFT/RIFFT structure. - * @param[in] *S_CFFT points to an instance of Q15 CFFT/CIFFT structure. - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. - * \par Normalizing factor: - * The normalizing factor is sqrt(2/N), which depends on the size of transform N. - * Normalizing factors in 1.15 format are mentioned in the table below for different DCT sizes: - * \image html dct4NormalizingQ15Table.gif - */ - -arm_status arm_dct4_init_q15( - arm_dct4_instance_q15 * S, - arm_rfft_instance_q15 * S_RFFT, - arm_cfft_radix4_instance_q15 * S_CFFT, - uint16_t N, - uint16_t Nby2, - q15_t normalize) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initializing the pointer array with the weight table base addresses of different lengths */ - q15_t *twiddlePtr[3] = { (q15_t *) WeightsQ15_128, (q15_t *) WeightsQ15_512, - (q15_t *) WeightsQ15_2048 - }; - - /* Initializing the pointer array with the cos factor table base addresses of different lengths */ - q15_t *pCosFactor[3] = - { (q15_t *) cos_factorsQ15_128, (q15_t *) cos_factorsQ15_512, - (q15_t *) cos_factorsQ15_2048 - }; - - /* Initialize the DCT4 length */ - S->N = N; - - /* Initialize the half of DCT4 length */ - S->Nby2 = Nby2; - - /* Initialize the DCT4 Normalizing factor */ - S->normalize = normalize; - - /* Initialize Real FFT Instance */ - S->pRfft = S_RFFT; - - /* Initialize Complex FFT Instance */ - S->pCfft = S_CFFT; - - switch (N) - { - /* Initialize the table modifier values */ - case 2048u: - S->pTwiddle = twiddlePtr[2]; - S->pCosFactor = pCosFactor[2]; - break; - case 512u: - S->pTwiddle = twiddlePtr[1]; - S->pCosFactor = pCosFactor[1]; - break; - case 128u: - S->pTwiddle = twiddlePtr[0]; - S->pCosFactor = pCosFactor[0]; - break; - default: - status = ARM_MATH_ARGUMENT_ERROR; - } - - /* Initialize the RFFT/RIFFT */ - arm_rfft_init_q15(S->pRfft, S->pCfft, S->N, 0u, 1u); - - /* return the status of DCT4 Init function */ - return (status); -} - -/** - * @} end of DCT4_IDCT4 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_dct4_init_q15.c +* +* Description: Initialization function of DCT-4 & IDCT4 Q15 +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup DCT4_IDCT4 + * @{ + */ + +/* +* @brief Weights Table +*/ + +/** +* \par +* Weights tables are generated using the formula :
weights[n] = e^(-j*n*pi/(2*N))
+* \par +* C command to generate the table +*
   
+* for(i = 0; i< N; i++)   
+* {   
+*   weights[2*i]= cos(i*c);   
+*   weights[(2*i)+1]= -sin(i * c);   
+* } 
+* \par +* where N is the Number of weights to be calculated and c is pi/(2*N) +* \par +* Converted the output to q15 format by multiplying with 2^31 and saturated if required. +* \par +* In the tables below the real and imaginary values are placed alternatively, hence the +* array length is 2*N. +*/ + +static const q15_t WeightsQ15_128[256] = { + 0x7fff, 0x0, 0x7ffd, 0xfe6e, 0x7ff6, 0xfcdc, 0x7fe9, 0xfb4a, + 0x7fd8, 0xf9b9, 0x7fc2, 0xf827, 0x7fa7, 0xf696, 0x7f87, 0xf505, + 0x7f62, 0xf375, 0x7f38, 0xf1e5, 0x7f09, 0xf055, 0x7ed5, 0xeec7, + 0x7e9d, 0xed38, 0x7e5f, 0xebab, 0x7e1d, 0xea1e, 0x7dd6, 0xe893, + 0x7d8a, 0xe708, 0x7d39, 0xe57e, 0x7ce3, 0xe3f5, 0x7c89, 0xe26d, + 0x7c29, 0xe0e7, 0x7bc5, 0xdf61, 0x7b5d, 0xdddd, 0x7aef, 0xdc5a, + 0x7a7d, 0xdad8, 0x7a05, 0xd958, 0x798a, 0xd7da, 0x7909, 0xd65d, + 0x7884, 0xd4e1, 0x77fa, 0xd368, 0x776c, 0xd1ef, 0x76d9, 0xd079, + 0x7641, 0xcf05, 0x75a5, 0xcd92, 0x7504, 0xcc22, 0x745f, 0xcab3, + 0x73b5, 0xc946, 0x7307, 0xc7dc, 0x7255, 0xc674, 0x719e, 0xc50e, + 0x70e2, 0xc3aa, 0x7023, 0xc248, 0x6f5f, 0xc0e9, 0x6e96, 0xbf8d, + 0x6dca, 0xbe32, 0x6cf9, 0xbcdb, 0x6c24, 0xbb86, 0x6b4a, 0xba33, + 0x6a6d, 0xb8e4, 0x698c, 0xb797, 0x68a6, 0xb64c, 0x67bd, 0xb505, + 0x66cf, 0xb3c1, 0x65dd, 0xb27f, 0x64e8, 0xb141, 0x63ef, 0xb005, + 0x62f2, 0xaecd, 0x61f1, 0xad97, 0x60ec, 0xac65, 0x5fe3, 0xab36, + 0x5ed7, 0xaa0b, 0x5dc7, 0xa8e3, 0x5cb4, 0xa7be, 0x5b9d, 0xa69c, + 0x5a82, 0xa57e, 0x5964, 0xa463, 0x5842, 0xa34c, 0x571d, 0xa239, + 0x55f5, 0xa129, 0x54ca, 0xa01d, 0x539b, 0x9f14, 0x5269, 0x9e0f, + 0x5133, 0x9d0e, 0x4ffb, 0x9c11, 0x4ebf, 0x9b18, 0x4d81, 0x9a23, + 0x4c3f, 0x9931, 0x4afb, 0x9843, 0x49b4, 0x975a, 0x4869, 0x9674, + 0x471c, 0x9593, 0x45cd, 0x94b6, 0x447a, 0x93dc, 0x4325, 0x9307, + 0x41ce, 0x9236, 0x4073, 0x916a, 0x3f17, 0x90a1, 0x3db8, 0x8fdd, + 0x3c56, 0x8f1e, 0x3af2, 0x8e62, 0x398c, 0x8dab, 0x3824, 0x8cf9, + 0x36ba, 0x8c4b, 0x354d, 0x8ba1, 0x33de, 0x8afc, 0x326e, 0x8a5b, + 0x30fb, 0x89bf, 0x2f87, 0x8927, 0x2e11, 0x8894, 0x2c98, 0x8806, + 0x2b1f, 0x877c, 0x29a3, 0x86f7, 0x2826, 0x8676, 0x26a8, 0x85fb, + 0x2528, 0x8583, 0x23a6, 0x8511, 0x2223, 0x84a3, 0x209f, 0x843b, + 0x1f19, 0x83d7, 0x1d93, 0x8377, 0x1c0b, 0x831d, 0x1a82, 0x82c7, + 0x18f8, 0x8276, 0x176d, 0x822a, 0x15e2, 0x81e3, 0x1455, 0x81a1, + 0x12c8, 0x8163, 0x1139, 0x812b, 0xfab, 0x80f7, 0xe1b, 0x80c8, + 0xc8b, 0x809e, 0xafb, 0x8079, 0x96a, 0x8059, 0x7d9, 0x803e, + 0x647, 0x8028, 0x4b6, 0x8017, 0x324, 0x800a, 0x192, 0x8003, +}; + +static const q15_t WeightsQ15_512[1024] = { + 0x7fff, 0x0, 0x7fff, 0xff9c, 0x7fff, 0xff37, 0x7ffe, 0xfed3, + 0x7ffd, 0xfe6e, 0x7ffc, 0xfe0a, 0x7ffa, 0xfda5, 0x7ff8, 0xfd41, + 0x7ff6, 0xfcdc, 0x7ff3, 0xfc78, 0x7ff0, 0xfc13, 0x7fed, 0xfbaf, + 0x7fe9, 0xfb4a, 0x7fe5, 0xfae6, 0x7fe1, 0xfa81, 0x7fdd, 0xfa1d, + 0x7fd8, 0xf9b9, 0x7fd3, 0xf954, 0x7fce, 0xf8f0, 0x7fc8, 0xf88b, + 0x7fc2, 0xf827, 0x7fbc, 0xf7c3, 0x7fb5, 0xf75e, 0x7fae, 0xf6fa, + 0x7fa7, 0xf696, 0x7f9f, 0xf632, 0x7f97, 0xf5cd, 0x7f8f, 0xf569, + 0x7f87, 0xf505, 0x7f7e, 0xf4a1, 0x7f75, 0xf43d, 0x7f6b, 0xf3d9, + 0x7f62, 0xf375, 0x7f58, 0xf311, 0x7f4d, 0xf2ad, 0x7f43, 0xf249, + 0x7f38, 0xf1e5, 0x7f2d, 0xf181, 0x7f21, 0xf11d, 0x7f15, 0xf0b9, + 0x7f09, 0xf055, 0x7efd, 0xeff2, 0x7ef0, 0xef8e, 0x7ee3, 0xef2a, + 0x7ed5, 0xeec7, 0x7ec8, 0xee63, 0x7eba, 0xedff, 0x7eab, 0xed9c, + 0x7e9d, 0xed38, 0x7e8e, 0xecd5, 0x7e7f, 0xec72, 0x7e6f, 0xec0e, + 0x7e5f, 0xebab, 0x7e4f, 0xeb48, 0x7e3f, 0xeae5, 0x7e2e, 0xea81, + 0x7e1d, 0xea1e, 0x7e0c, 0xe9bb, 0x7dfa, 0xe958, 0x7de8, 0xe8f6, + 0x7dd6, 0xe893, 0x7dc3, 0xe830, 0x7db0, 0xe7cd, 0x7d9d, 0xe76a, + 0x7d8a, 0xe708, 0x7d76, 0xe6a5, 0x7d62, 0xe643, 0x7d4e, 0xe5e0, + 0x7d39, 0xe57e, 0x7d24, 0xe51c, 0x7d0f, 0xe4b9, 0x7cf9, 0xe457, + 0x7ce3, 0xe3f5, 0x7ccd, 0xe393, 0x7cb7, 0xe331, 0x7ca0, 0xe2cf, + 0x7c89, 0xe26d, 0x7c71, 0xe20b, 0x7c5a, 0xe1aa, 0x7c42, 0xe148, + 0x7c29, 0xe0e7, 0x7c11, 0xe085, 0x7bf8, 0xe024, 0x7bdf, 0xdfc2, + 0x7bc5, 0xdf61, 0x7bac, 0xdf00, 0x7b92, 0xde9f, 0x7b77, 0xde3e, + 0x7b5d, 0xdddd, 0x7b42, 0xdd7c, 0x7b26, 0xdd1b, 0x7b0b, 0xdcbb, + 0x7aef, 0xdc5a, 0x7ad3, 0xdbf9, 0x7ab6, 0xdb99, 0x7a9a, 0xdb39, + 0x7a7d, 0xdad8, 0x7a5f, 0xda78, 0x7a42, 0xda18, 0x7a24, 0xd9b8, + 0x7a05, 0xd958, 0x79e7, 0xd8f9, 0x79c8, 0xd899, 0x79a9, 0xd839, + 0x798a, 0xd7da, 0x796a, 0xd77a, 0x794a, 0xd71b, 0x792a, 0xd6bc, + 0x7909, 0xd65d, 0x78e8, 0xd5fe, 0x78c7, 0xd59f, 0x78a6, 0xd540, + 0x7884, 0xd4e1, 0x7862, 0xd483, 0x7840, 0xd424, 0x781d, 0xd3c6, + 0x77fa, 0xd368, 0x77d7, 0xd309, 0x77b4, 0xd2ab, 0x7790, 0xd24d, + 0x776c, 0xd1ef, 0x7747, 0xd192, 0x7723, 0xd134, 0x76fe, 0xd0d7, + 0x76d9, 0xd079, 0x76b3, 0xd01c, 0x768e, 0xcfbf, 0x7668, 0xcf62, + 0x7641, 0xcf05, 0x761b, 0xcea8, 0x75f4, 0xce4b, 0x75cc, 0xcdef, + 0x75a5, 0xcd92, 0x757d, 0xcd36, 0x7555, 0xccda, 0x752d, 0xcc7e, + 0x7504, 0xcc22, 0x74db, 0xcbc6, 0x74b2, 0xcb6a, 0x7489, 0xcb0e, + 0x745f, 0xcab3, 0x7435, 0xca58, 0x740b, 0xc9fc, 0x73e0, 0xc9a1, + 0x73b5, 0xc946, 0x738a, 0xc8ec, 0x735f, 0xc891, 0x7333, 0xc836, + 0x7307, 0xc7dc, 0x72db, 0xc782, 0x72af, 0xc728, 0x7282, 0xc6ce, + 0x7255, 0xc674, 0x7227, 0xc61a, 0x71fa, 0xc5c0, 0x71cc, 0xc567, + 0x719e, 0xc50e, 0x716f, 0xc4b4, 0x7141, 0xc45b, 0x7112, 0xc403, + 0x70e2, 0xc3aa, 0x70b3, 0xc351, 0x7083, 0xc2f9, 0x7053, 0xc2a0, + 0x7023, 0xc248, 0x6ff2, 0xc1f0, 0x6fc1, 0xc198, 0x6f90, 0xc141, + 0x6f5f, 0xc0e9, 0x6f2d, 0xc092, 0x6efb, 0xc03b, 0x6ec9, 0xbfe3, + 0x6e96, 0xbf8d, 0x6e63, 0xbf36, 0x6e30, 0xbedf, 0x6dfd, 0xbe89, + 0x6dca, 0xbe32, 0x6d96, 0xbddc, 0x6d62, 0xbd86, 0x6d2d, 0xbd30, + 0x6cf9, 0xbcdb, 0x6cc4, 0xbc85, 0x6c8f, 0xbc30, 0x6c59, 0xbbdb, + 0x6c24, 0xbb86, 0x6bee, 0xbb31, 0x6bb8, 0xbadc, 0x6b81, 0xba88, + 0x6b4a, 0xba33, 0x6b13, 0xb9df, 0x6adc, 0xb98b, 0x6aa5, 0xb937, + 0x6a6d, 0xb8e4, 0x6a35, 0xb890, 0x69fd, 0xb83d, 0x69c4, 0xb7ea, + 0x698c, 0xb797, 0x6953, 0xb744, 0x6919, 0xb6f1, 0x68e0, 0xb69f, + 0x68a6, 0xb64c, 0x686c, 0xb5fa, 0x6832, 0xb5a8, 0x67f7, 0xb557, + 0x67bd, 0xb505, 0x6782, 0xb4b4, 0x6746, 0xb462, 0x670b, 0xb411, + 0x66cf, 0xb3c1, 0x6693, 0xb370, 0x6657, 0xb31f, 0x661a, 0xb2cf, + 0x65dd, 0xb27f, 0x65a0, 0xb22f, 0x6563, 0xb1df, 0x6526, 0xb190, + 0x64e8, 0xb141, 0x64aa, 0xb0f1, 0x646c, 0xb0a2, 0x642d, 0xb054, + 0x63ef, 0xb005, 0x63b0, 0xafb7, 0x6371, 0xaf69, 0x6331, 0xaf1b, + 0x62f2, 0xaecd, 0x62b2, 0xae7f, 0x6271, 0xae32, 0x6231, 0xade4, + 0x61f1, 0xad97, 0x61b0, 0xad4b, 0x616f, 0xacfe, 0x612d, 0xacb2, + 0x60ec, 0xac65, 0x60aa, 0xac19, 0x6068, 0xabcd, 0x6026, 0xab82, + 0x5fe3, 0xab36, 0x5fa0, 0xaaeb, 0x5f5e, 0xaaa0, 0x5f1a, 0xaa55, + 0x5ed7, 0xaa0b, 0x5e93, 0xa9c0, 0x5e50, 0xa976, 0x5e0b, 0xa92c, + 0x5dc7, 0xa8e3, 0x5d83, 0xa899, 0x5d3e, 0xa850, 0x5cf9, 0xa807, + 0x5cb4, 0xa7be, 0x5c6e, 0xa775, 0x5c29, 0xa72c, 0x5be3, 0xa6e4, + 0x5b9d, 0xa69c, 0x5b56, 0xa654, 0x5b10, 0xa60d, 0x5ac9, 0xa5c5, + 0x5a82, 0xa57e, 0x5a3b, 0xa537, 0x59f3, 0xa4f0, 0x59ac, 0xa4aa, + 0x5964, 0xa463, 0x591c, 0xa41d, 0x58d4, 0xa3d7, 0x588b, 0xa392, + 0x5842, 0xa34c, 0x57f9, 0xa307, 0x57b0, 0xa2c2, 0x5767, 0xa27d, + 0x571d, 0xa239, 0x56d4, 0xa1f5, 0x568a, 0xa1b0, 0x5640, 0xa16d, + 0x55f5, 0xa129, 0x55ab, 0xa0e6, 0x5560, 0xa0a2, 0x5515, 0xa060, + 0x54ca, 0xa01d, 0x547e, 0x9fda, 0x5433, 0x9f98, 0x53e7, 0x9f56, + 0x539b, 0x9f14, 0x534e, 0x9ed3, 0x5302, 0x9e91, 0x52b5, 0x9e50, + 0x5269, 0x9e0f, 0x521c, 0x9dcf, 0x51ce, 0x9d8f, 0x5181, 0x9d4e, + 0x5133, 0x9d0e, 0x50e5, 0x9ccf, 0x5097, 0x9c8f, 0x5049, 0x9c50, + 0x4ffb, 0x9c11, 0x4fac, 0x9bd3, 0x4f5e, 0x9b94, 0x4f0f, 0x9b56, + 0x4ebf, 0x9b18, 0x4e70, 0x9ada, 0x4e21, 0x9a9d, 0x4dd1, 0x9a60, + 0x4d81, 0x9a23, 0x4d31, 0x99e6, 0x4ce1, 0x99a9, 0x4c90, 0x996d, + 0x4c3f, 0x9931, 0x4bef, 0x98f5, 0x4b9e, 0x98ba, 0x4b4c, 0x987e, + 0x4afb, 0x9843, 0x4aa9, 0x9809, 0x4a58, 0x97ce, 0x4a06, 0x9794, + 0x49b4, 0x975a, 0x4961, 0x9720, 0x490f, 0x96e7, 0x48bc, 0x96ad, + 0x4869, 0x9674, 0x4816, 0x963c, 0x47c3, 0x9603, 0x4770, 0x95cb, + 0x471c, 0x9593, 0x46c9, 0x955b, 0x4675, 0x9524, 0x4621, 0x94ed, + 0x45cd, 0x94b6, 0x4578, 0x947f, 0x4524, 0x9448, 0x44cf, 0x9412, + 0x447a, 0x93dc, 0x4425, 0x93a7, 0x43d0, 0x9371, 0x437b, 0x933c, + 0x4325, 0x9307, 0x42d0, 0x92d3, 0x427a, 0x929e, 0x4224, 0x926a, + 0x41ce, 0x9236, 0x4177, 0x9203, 0x4121, 0x91d0, 0x40ca, 0x919d, + 0x4073, 0x916a, 0x401d, 0x9137, 0x3fc5, 0x9105, 0x3f6e, 0x90d3, + 0x3f17, 0x90a1, 0x3ebf, 0x9070, 0x3e68, 0x903f, 0x3e10, 0x900e, + 0x3db8, 0x8fdd, 0x3d60, 0x8fad, 0x3d07, 0x8f7d, 0x3caf, 0x8f4d, + 0x3c56, 0x8f1e, 0x3bfd, 0x8eee, 0x3ba5, 0x8ebf, 0x3b4c, 0x8e91, + 0x3af2, 0x8e62, 0x3a99, 0x8e34, 0x3a40, 0x8e06, 0x39e6, 0x8dd9, + 0x398c, 0x8dab, 0x3932, 0x8d7e, 0x38d8, 0x8d51, 0x387e, 0x8d25, + 0x3824, 0x8cf9, 0x37ca, 0x8ccd, 0x376f, 0x8ca1, 0x3714, 0x8c76, + 0x36ba, 0x8c4b, 0x365f, 0x8c20, 0x3604, 0x8bf5, 0x35a8, 0x8bcb, + 0x354d, 0x8ba1, 0x34f2, 0x8b77, 0x3496, 0x8b4e, 0x343a, 0x8b25, + 0x33de, 0x8afc, 0x3382, 0x8ad3, 0x3326, 0x8aab, 0x32ca, 0x8a83, + 0x326e, 0x8a5b, 0x3211, 0x8a34, 0x31b5, 0x8a0c, 0x3158, 0x89e5, + 0x30fb, 0x89bf, 0x309e, 0x8998, 0x3041, 0x8972, 0x2fe4, 0x894d, + 0x2f87, 0x8927, 0x2f29, 0x8902, 0x2ecc, 0x88dd, 0x2e6e, 0x88b9, + 0x2e11, 0x8894, 0x2db3, 0x8870, 0x2d55, 0x884c, 0x2cf7, 0x8829, + 0x2c98, 0x8806, 0x2c3a, 0x87e3, 0x2bdc, 0x87c0, 0x2b7d, 0x879e, + 0x2b1f, 0x877c, 0x2ac0, 0x875a, 0x2a61, 0x8739, 0x2a02, 0x8718, + 0x29a3, 0x86f7, 0x2944, 0x86d6, 0x28e5, 0x86b6, 0x2886, 0x8696, + 0x2826, 0x8676, 0x27c7, 0x8657, 0x2767, 0x8638, 0x2707, 0x8619, + 0x26a8, 0x85fb, 0x2648, 0x85dc, 0x25e8, 0x85be, 0x2588, 0x85a1, + 0x2528, 0x8583, 0x24c7, 0x8566, 0x2467, 0x854a, 0x2407, 0x852d, + 0x23a6, 0x8511, 0x2345, 0x84f5, 0x22e5, 0x84da, 0x2284, 0x84be, + 0x2223, 0x84a3, 0x21c2, 0x8489, 0x2161, 0x846e, 0x2100, 0x8454, + 0x209f, 0x843b, 0x203e, 0x8421, 0x1fdc, 0x8408, 0x1f7b, 0x83ef, + 0x1f19, 0x83d7, 0x1eb8, 0x83be, 0x1e56, 0x83a6, 0x1df5, 0x838f, + 0x1d93, 0x8377, 0x1d31, 0x8360, 0x1ccf, 0x8349, 0x1c6d, 0x8333, + 0x1c0b, 0x831d, 0x1ba9, 0x8307, 0x1b47, 0x82f1, 0x1ae4, 0x82dc, + 0x1a82, 0x82c7, 0x1a20, 0x82b2, 0x19bd, 0x829e, 0x195b, 0x828a, + 0x18f8, 0x8276, 0x1896, 0x8263, 0x1833, 0x8250, 0x17d0, 0x823d, + 0x176d, 0x822a, 0x170a, 0x8218, 0x16a8, 0x8206, 0x1645, 0x81f4, + 0x15e2, 0x81e3, 0x157f, 0x81d2, 0x151b, 0x81c1, 0x14b8, 0x81b1, + 0x1455, 0x81a1, 0x13f2, 0x8191, 0x138e, 0x8181, 0x132b, 0x8172, + 0x12c8, 0x8163, 0x1264, 0x8155, 0x1201, 0x8146, 0x119d, 0x8138, + 0x1139, 0x812b, 0x10d6, 0x811d, 0x1072, 0x8110, 0x100e, 0x8103, + 0xfab, 0x80f7, 0xf47, 0x80eb, 0xee3, 0x80df, 0xe7f, 0x80d3, + 0xe1b, 0x80c8, 0xdb7, 0x80bd, 0xd53, 0x80b3, 0xcef, 0x80a8, + 0xc8b, 0x809e, 0xc27, 0x8095, 0xbc3, 0x808b, 0xb5f, 0x8082, + 0xafb, 0x8079, 0xa97, 0x8071, 0xa33, 0x8069, 0x9ce, 0x8061, + 0x96a, 0x8059, 0x906, 0x8052, 0x8a2, 0x804b, 0x83d, 0x8044, + 0x7d9, 0x803e, 0x775, 0x8038, 0x710, 0x8032, 0x6ac, 0x802d, + 0x647, 0x8028, 0x5e3, 0x8023, 0x57f, 0x801f, 0x51a, 0x801b, + 0x4b6, 0x8017, 0x451, 0x8013, 0x3ed, 0x8010, 0x388, 0x800d, + 0x324, 0x800a, 0x2bf, 0x8008, 0x25b, 0x8006, 0x1f6, 0x8004, + 0x192, 0x8003, 0x12d, 0x8002, 0xc9, 0x8001, 0x64, 0x8001, +}; + +static const q15_t WeightsQ15_2048[4096] = { + 0x7fff, 0x0, 0x7fff, 0xffe7, 0x7fff, 0xffce, 0x7fff, 0xffb5, + 0x7fff, 0xff9c, 0x7fff, 0xff83, 0x7fff, 0xff6a, 0x7fff, 0xff51, + 0x7fff, 0xff37, 0x7fff, 0xff1e, 0x7fff, 0xff05, 0x7ffe, 0xfeec, + 0x7ffe, 0xfed3, 0x7ffe, 0xfeba, 0x7ffe, 0xfea1, 0x7ffd, 0xfe88, + 0x7ffd, 0xfe6e, 0x7ffd, 0xfe55, 0x7ffc, 0xfe3c, 0x7ffc, 0xfe23, + 0x7ffc, 0xfe0a, 0x7ffb, 0xfdf1, 0x7ffb, 0xfdd8, 0x7ffa, 0xfdbe, + 0x7ffa, 0xfda5, 0x7ff9, 0xfd8c, 0x7ff9, 0xfd73, 0x7ff8, 0xfd5a, + 0x7ff8, 0xfd41, 0x7ff7, 0xfd28, 0x7ff7, 0xfd0f, 0x7ff6, 0xfcf5, + 0x7ff6, 0xfcdc, 0x7ff5, 0xfcc3, 0x7ff4, 0xfcaa, 0x7ff4, 0xfc91, + 0x7ff3, 0xfc78, 0x7ff2, 0xfc5f, 0x7ff2, 0xfc46, 0x7ff1, 0xfc2c, + 0x7ff0, 0xfc13, 0x7fef, 0xfbfa, 0x7fee, 0xfbe1, 0x7fee, 0xfbc8, + 0x7fed, 0xfbaf, 0x7fec, 0xfb96, 0x7feb, 0xfb7d, 0x7fea, 0xfb64, + 0x7fe9, 0xfb4a, 0x7fe8, 0xfb31, 0x7fe7, 0xfb18, 0x7fe6, 0xfaff, + 0x7fe5, 0xfae6, 0x7fe4, 0xfacd, 0x7fe3, 0xfab4, 0x7fe2, 0xfa9b, + 0x7fe1, 0xfa81, 0x7fe0, 0xfa68, 0x7fdf, 0xfa4f, 0x7fde, 0xfa36, + 0x7fdd, 0xfa1d, 0x7fdc, 0xfa04, 0x7fda, 0xf9eb, 0x7fd9, 0xf9d2, + 0x7fd8, 0xf9b9, 0x7fd7, 0xf9a0, 0x7fd6, 0xf986, 0x7fd4, 0xf96d, + 0x7fd3, 0xf954, 0x7fd2, 0xf93b, 0x7fd0, 0xf922, 0x7fcf, 0xf909, + 0x7fce, 0xf8f0, 0x7fcc, 0xf8d7, 0x7fcb, 0xf8be, 0x7fc9, 0xf8a5, + 0x7fc8, 0xf88b, 0x7fc6, 0xf872, 0x7fc5, 0xf859, 0x7fc3, 0xf840, + 0x7fc2, 0xf827, 0x7fc0, 0xf80e, 0x7fbf, 0xf7f5, 0x7fbd, 0xf7dc, + 0x7fbc, 0xf7c3, 0x7fba, 0xf7aa, 0x7fb8, 0xf791, 0x7fb7, 0xf778, + 0x7fb5, 0xf75e, 0x7fb3, 0xf745, 0x7fb1, 0xf72c, 0x7fb0, 0xf713, + 0x7fae, 0xf6fa, 0x7fac, 0xf6e1, 0x7faa, 0xf6c8, 0x7fa9, 0xf6af, + 0x7fa7, 0xf696, 0x7fa5, 0xf67d, 0x7fa3, 0xf664, 0x7fa1, 0xf64b, + 0x7f9f, 0xf632, 0x7f9d, 0xf619, 0x7f9b, 0xf600, 0x7f99, 0xf5e7, + 0x7f97, 0xf5cd, 0x7f95, 0xf5b4, 0x7f93, 0xf59b, 0x7f91, 0xf582, + 0x7f8f, 0xf569, 0x7f8d, 0xf550, 0x7f8b, 0xf537, 0x7f89, 0xf51e, + 0x7f87, 0xf505, 0x7f85, 0xf4ec, 0x7f82, 0xf4d3, 0x7f80, 0xf4ba, + 0x7f7e, 0xf4a1, 0x7f7c, 0xf488, 0x7f79, 0xf46f, 0x7f77, 0xf456, + 0x7f75, 0xf43d, 0x7f72, 0xf424, 0x7f70, 0xf40b, 0x7f6e, 0xf3f2, + 0x7f6b, 0xf3d9, 0x7f69, 0xf3c0, 0x7f67, 0xf3a7, 0x7f64, 0xf38e, + 0x7f62, 0xf375, 0x7f5f, 0xf35c, 0x7f5d, 0xf343, 0x7f5a, 0xf32a, + 0x7f58, 0xf311, 0x7f55, 0xf2f8, 0x7f53, 0xf2df, 0x7f50, 0xf2c6, + 0x7f4d, 0xf2ad, 0x7f4b, 0xf294, 0x7f48, 0xf27b, 0x7f45, 0xf262, + 0x7f43, 0xf249, 0x7f40, 0xf230, 0x7f3d, 0xf217, 0x7f3b, 0xf1fe, + 0x7f38, 0xf1e5, 0x7f35, 0xf1cc, 0x7f32, 0xf1b3, 0x7f2f, 0xf19a, + 0x7f2d, 0xf181, 0x7f2a, 0xf168, 0x7f27, 0xf14f, 0x7f24, 0xf136, + 0x7f21, 0xf11d, 0x7f1e, 0xf104, 0x7f1b, 0xf0eb, 0x7f18, 0xf0d2, + 0x7f15, 0xf0b9, 0x7f12, 0xf0a0, 0x7f0f, 0xf087, 0x7f0c, 0xf06e, + 0x7f09, 0xf055, 0x7f06, 0xf03c, 0x7f03, 0xf023, 0x7f00, 0xf00b, + 0x7efd, 0xeff2, 0x7ef9, 0xefd9, 0x7ef6, 0xefc0, 0x7ef3, 0xefa7, + 0x7ef0, 0xef8e, 0x7eed, 0xef75, 0x7ee9, 0xef5c, 0x7ee6, 0xef43, + 0x7ee3, 0xef2a, 0x7edf, 0xef11, 0x7edc, 0xeef8, 0x7ed9, 0xeedf, + 0x7ed5, 0xeec7, 0x7ed2, 0xeeae, 0x7ecf, 0xee95, 0x7ecb, 0xee7c, + 0x7ec8, 0xee63, 0x7ec4, 0xee4a, 0x7ec1, 0xee31, 0x7ebd, 0xee18, + 0x7eba, 0xedff, 0x7eb6, 0xede7, 0x7eb3, 0xedce, 0x7eaf, 0xedb5, + 0x7eab, 0xed9c, 0x7ea8, 0xed83, 0x7ea4, 0xed6a, 0x7ea1, 0xed51, + 0x7e9d, 0xed38, 0x7e99, 0xed20, 0x7e95, 0xed07, 0x7e92, 0xecee, + 0x7e8e, 0xecd5, 0x7e8a, 0xecbc, 0x7e86, 0xeca3, 0x7e83, 0xec8a, + 0x7e7f, 0xec72, 0x7e7b, 0xec59, 0x7e77, 0xec40, 0x7e73, 0xec27, + 0x7e6f, 0xec0e, 0x7e6b, 0xebf5, 0x7e67, 0xebdd, 0x7e63, 0xebc4, + 0x7e5f, 0xebab, 0x7e5b, 0xeb92, 0x7e57, 0xeb79, 0x7e53, 0xeb61, + 0x7e4f, 0xeb48, 0x7e4b, 0xeb2f, 0x7e47, 0xeb16, 0x7e43, 0xeafd, + 0x7e3f, 0xeae5, 0x7e3b, 0xeacc, 0x7e37, 0xeab3, 0x7e32, 0xea9a, + 0x7e2e, 0xea81, 0x7e2a, 0xea69, 0x7e26, 0xea50, 0x7e21, 0xea37, + 0x7e1d, 0xea1e, 0x7e19, 0xea06, 0x7e14, 0xe9ed, 0x7e10, 0xe9d4, + 0x7e0c, 0xe9bb, 0x7e07, 0xe9a3, 0x7e03, 0xe98a, 0x7dff, 0xe971, + 0x7dfa, 0xe958, 0x7df6, 0xe940, 0x7df1, 0xe927, 0x7ded, 0xe90e, + 0x7de8, 0xe8f6, 0x7de4, 0xe8dd, 0x7ddf, 0xe8c4, 0x7dda, 0xe8ab, + 0x7dd6, 0xe893, 0x7dd1, 0xe87a, 0x7dcd, 0xe861, 0x7dc8, 0xe849, + 0x7dc3, 0xe830, 0x7dbf, 0xe817, 0x7dba, 0xe7fe, 0x7db5, 0xe7e6, + 0x7db0, 0xe7cd, 0x7dac, 0xe7b4, 0x7da7, 0xe79c, 0x7da2, 0xe783, + 0x7d9d, 0xe76a, 0x7d98, 0xe752, 0x7d94, 0xe739, 0x7d8f, 0xe720, + 0x7d8a, 0xe708, 0x7d85, 0xe6ef, 0x7d80, 0xe6d6, 0x7d7b, 0xe6be, + 0x7d76, 0xe6a5, 0x7d71, 0xe68d, 0x7d6c, 0xe674, 0x7d67, 0xe65b, + 0x7d62, 0xe643, 0x7d5d, 0xe62a, 0x7d58, 0xe611, 0x7d53, 0xe5f9, + 0x7d4e, 0xe5e0, 0x7d49, 0xe5c8, 0x7d43, 0xe5af, 0x7d3e, 0xe596, + 0x7d39, 0xe57e, 0x7d34, 0xe565, 0x7d2f, 0xe54d, 0x7d29, 0xe534, + 0x7d24, 0xe51c, 0x7d1f, 0xe503, 0x7d19, 0xe4ea, 0x7d14, 0xe4d2, + 0x7d0f, 0xe4b9, 0x7d09, 0xe4a1, 0x7d04, 0xe488, 0x7cff, 0xe470, + 0x7cf9, 0xe457, 0x7cf4, 0xe43f, 0x7cee, 0xe426, 0x7ce9, 0xe40e, + 0x7ce3, 0xe3f5, 0x7cde, 0xe3dc, 0x7cd8, 0xe3c4, 0x7cd3, 0xe3ab, + 0x7ccd, 0xe393, 0x7cc8, 0xe37a, 0x7cc2, 0xe362, 0x7cbc, 0xe349, + 0x7cb7, 0xe331, 0x7cb1, 0xe318, 0x7cab, 0xe300, 0x7ca6, 0xe2e8, + 0x7ca0, 0xe2cf, 0x7c9a, 0xe2b7, 0x7c94, 0xe29e, 0x7c8f, 0xe286, + 0x7c89, 0xe26d, 0x7c83, 0xe255, 0x7c7d, 0xe23c, 0x7c77, 0xe224, + 0x7c71, 0xe20b, 0x7c6c, 0xe1f3, 0x7c66, 0xe1db, 0x7c60, 0xe1c2, + 0x7c5a, 0xe1aa, 0x7c54, 0xe191, 0x7c4e, 0xe179, 0x7c48, 0xe160, + 0x7c42, 0xe148, 0x7c3c, 0xe130, 0x7c36, 0xe117, 0x7c30, 0xe0ff, + 0x7c29, 0xe0e7, 0x7c23, 0xe0ce, 0x7c1d, 0xe0b6, 0x7c17, 0xe09d, + 0x7c11, 0xe085, 0x7c0b, 0xe06d, 0x7c05, 0xe054, 0x7bfe, 0xe03c, + 0x7bf8, 0xe024, 0x7bf2, 0xe00b, 0x7beb, 0xdff3, 0x7be5, 0xdfdb, + 0x7bdf, 0xdfc2, 0x7bd9, 0xdfaa, 0x7bd2, 0xdf92, 0x7bcc, 0xdf79, + 0x7bc5, 0xdf61, 0x7bbf, 0xdf49, 0x7bb9, 0xdf30, 0x7bb2, 0xdf18, + 0x7bac, 0xdf00, 0x7ba5, 0xdee8, 0x7b9f, 0xdecf, 0x7b98, 0xdeb7, + 0x7b92, 0xde9f, 0x7b8b, 0xde87, 0x7b84, 0xde6e, 0x7b7e, 0xde56, + 0x7b77, 0xde3e, 0x7b71, 0xde26, 0x7b6a, 0xde0d, 0x7b63, 0xddf5, + 0x7b5d, 0xdddd, 0x7b56, 0xddc5, 0x7b4f, 0xddac, 0x7b48, 0xdd94, + 0x7b42, 0xdd7c, 0x7b3b, 0xdd64, 0x7b34, 0xdd4c, 0x7b2d, 0xdd33, + 0x7b26, 0xdd1b, 0x7b1f, 0xdd03, 0x7b19, 0xdceb, 0x7b12, 0xdcd3, + 0x7b0b, 0xdcbb, 0x7b04, 0xdca2, 0x7afd, 0xdc8a, 0x7af6, 0xdc72, + 0x7aef, 0xdc5a, 0x7ae8, 0xdc42, 0x7ae1, 0xdc2a, 0x7ada, 0xdc12, + 0x7ad3, 0xdbf9, 0x7acc, 0xdbe1, 0x7ac5, 0xdbc9, 0x7abd, 0xdbb1, + 0x7ab6, 0xdb99, 0x7aaf, 0xdb81, 0x7aa8, 0xdb69, 0x7aa1, 0xdb51, + 0x7a9a, 0xdb39, 0x7a92, 0xdb21, 0x7a8b, 0xdb09, 0x7a84, 0xdaf1, + 0x7a7d, 0xdad8, 0x7a75, 0xdac0, 0x7a6e, 0xdaa8, 0x7a67, 0xda90, + 0x7a5f, 0xda78, 0x7a58, 0xda60, 0x7a50, 0xda48, 0x7a49, 0xda30, + 0x7a42, 0xda18, 0x7a3a, 0xda00, 0x7a33, 0xd9e8, 0x7a2b, 0xd9d0, + 0x7a24, 0xd9b8, 0x7a1c, 0xd9a0, 0x7a15, 0xd988, 0x7a0d, 0xd970, + 0x7a05, 0xd958, 0x79fe, 0xd940, 0x79f6, 0xd928, 0x79ef, 0xd911, + 0x79e7, 0xd8f9, 0x79df, 0xd8e1, 0x79d8, 0xd8c9, 0x79d0, 0xd8b1, + 0x79c8, 0xd899, 0x79c0, 0xd881, 0x79b9, 0xd869, 0x79b1, 0xd851, + 0x79a9, 0xd839, 0x79a1, 0xd821, 0x7999, 0xd80a, 0x7992, 0xd7f2, + 0x798a, 0xd7da, 0x7982, 0xd7c2, 0x797a, 0xd7aa, 0x7972, 0xd792, + 0x796a, 0xd77a, 0x7962, 0xd763, 0x795a, 0xd74b, 0x7952, 0xd733, + 0x794a, 0xd71b, 0x7942, 0xd703, 0x793a, 0xd6eb, 0x7932, 0xd6d4, + 0x792a, 0xd6bc, 0x7922, 0xd6a4, 0x7919, 0xd68c, 0x7911, 0xd675, + 0x7909, 0xd65d, 0x7901, 0xd645, 0x78f9, 0xd62d, 0x78f1, 0xd615, + 0x78e8, 0xd5fe, 0x78e0, 0xd5e6, 0x78d8, 0xd5ce, 0x78cf, 0xd5b7, + 0x78c7, 0xd59f, 0x78bf, 0xd587, 0x78b6, 0xd56f, 0x78ae, 0xd558, + 0x78a6, 0xd540, 0x789d, 0xd528, 0x7895, 0xd511, 0x788c, 0xd4f9, + 0x7884, 0xd4e1, 0x787c, 0xd4ca, 0x7873, 0xd4b2, 0x786b, 0xd49a, + 0x7862, 0xd483, 0x7859, 0xd46b, 0x7851, 0xd453, 0x7848, 0xd43c, + 0x7840, 0xd424, 0x7837, 0xd40d, 0x782e, 0xd3f5, 0x7826, 0xd3dd, + 0x781d, 0xd3c6, 0x7814, 0xd3ae, 0x780c, 0xd397, 0x7803, 0xd37f, + 0x77fa, 0xd368, 0x77f1, 0xd350, 0x77e9, 0xd338, 0x77e0, 0xd321, + 0x77d7, 0xd309, 0x77ce, 0xd2f2, 0x77c5, 0xd2da, 0x77bc, 0xd2c3, + 0x77b4, 0xd2ab, 0x77ab, 0xd294, 0x77a2, 0xd27c, 0x7799, 0xd265, + 0x7790, 0xd24d, 0x7787, 0xd236, 0x777e, 0xd21e, 0x7775, 0xd207, + 0x776c, 0xd1ef, 0x7763, 0xd1d8, 0x775a, 0xd1c1, 0x7751, 0xd1a9, + 0x7747, 0xd192, 0x773e, 0xd17a, 0x7735, 0xd163, 0x772c, 0xd14b, + 0x7723, 0xd134, 0x771a, 0xd11d, 0x7710, 0xd105, 0x7707, 0xd0ee, + 0x76fe, 0xd0d7, 0x76f5, 0xd0bf, 0x76eb, 0xd0a8, 0x76e2, 0xd091, + 0x76d9, 0xd079, 0x76cf, 0xd062, 0x76c6, 0xd04b, 0x76bd, 0xd033, + 0x76b3, 0xd01c, 0x76aa, 0xd005, 0x76a0, 0xcfed, 0x7697, 0xcfd6, + 0x768e, 0xcfbf, 0x7684, 0xcfa7, 0x767b, 0xcf90, 0x7671, 0xcf79, + 0x7668, 0xcf62, 0x765e, 0xcf4a, 0x7654, 0xcf33, 0x764b, 0xcf1c, + 0x7641, 0xcf05, 0x7638, 0xceee, 0x762e, 0xced6, 0x7624, 0xcebf, + 0x761b, 0xcea8, 0x7611, 0xce91, 0x7607, 0xce7a, 0x75fd, 0xce62, + 0x75f4, 0xce4b, 0x75ea, 0xce34, 0x75e0, 0xce1d, 0x75d6, 0xce06, + 0x75cc, 0xcdef, 0x75c3, 0xcdd8, 0x75b9, 0xcdc0, 0x75af, 0xcda9, + 0x75a5, 0xcd92, 0x759b, 0xcd7b, 0x7591, 0xcd64, 0x7587, 0xcd4d, + 0x757d, 0xcd36, 0x7573, 0xcd1f, 0x7569, 0xcd08, 0x755f, 0xccf1, + 0x7555, 0xccda, 0x754b, 0xccc3, 0x7541, 0xccac, 0x7537, 0xcc95, + 0x752d, 0xcc7e, 0x7523, 0xcc67, 0x7519, 0xcc50, 0x750f, 0xcc39, + 0x7504, 0xcc22, 0x74fa, 0xcc0b, 0x74f0, 0xcbf4, 0x74e6, 0xcbdd, + 0x74db, 0xcbc6, 0x74d1, 0xcbaf, 0x74c7, 0xcb98, 0x74bd, 0xcb81, + 0x74b2, 0xcb6a, 0x74a8, 0xcb53, 0x749e, 0xcb3c, 0x7493, 0xcb25, + 0x7489, 0xcb0e, 0x747e, 0xcaf8, 0x7474, 0xcae1, 0x746a, 0xcaca, + 0x745f, 0xcab3, 0x7455, 0xca9c, 0x744a, 0xca85, 0x7440, 0xca6e, + 0x7435, 0xca58, 0x742b, 0xca41, 0x7420, 0xca2a, 0x7415, 0xca13, + 0x740b, 0xc9fc, 0x7400, 0xc9e6, 0x73f6, 0xc9cf, 0x73eb, 0xc9b8, + 0x73e0, 0xc9a1, 0x73d6, 0xc98b, 0x73cb, 0xc974, 0x73c0, 0xc95d, + 0x73b5, 0xc946, 0x73ab, 0xc930, 0x73a0, 0xc919, 0x7395, 0xc902, + 0x738a, 0xc8ec, 0x737f, 0xc8d5, 0x7375, 0xc8be, 0x736a, 0xc8a8, + 0x735f, 0xc891, 0x7354, 0xc87a, 0x7349, 0xc864, 0x733e, 0xc84d, + 0x7333, 0xc836, 0x7328, 0xc820, 0x731d, 0xc809, 0x7312, 0xc7f3, + 0x7307, 0xc7dc, 0x72fc, 0xc7c5, 0x72f1, 0xc7af, 0x72e6, 0xc798, + 0x72db, 0xc782, 0x72d0, 0xc76b, 0x72c5, 0xc755, 0x72ba, 0xc73e, + 0x72af, 0xc728, 0x72a3, 0xc711, 0x7298, 0xc6fa, 0x728d, 0xc6e4, + 0x7282, 0xc6ce, 0x7276, 0xc6b7, 0x726b, 0xc6a1, 0x7260, 0xc68a, + 0x7255, 0xc674, 0x7249, 0xc65d, 0x723e, 0xc647, 0x7233, 0xc630, + 0x7227, 0xc61a, 0x721c, 0xc603, 0x7211, 0xc5ed, 0x7205, 0xc5d7, + 0x71fa, 0xc5c0, 0x71ee, 0xc5aa, 0x71e3, 0xc594, 0x71d7, 0xc57d, + 0x71cc, 0xc567, 0x71c0, 0xc551, 0x71b5, 0xc53a, 0x71a9, 0xc524, + 0x719e, 0xc50e, 0x7192, 0xc4f7, 0x7186, 0xc4e1, 0x717b, 0xc4cb, + 0x716f, 0xc4b4, 0x7164, 0xc49e, 0x7158, 0xc488, 0x714c, 0xc472, + 0x7141, 0xc45b, 0x7135, 0xc445, 0x7129, 0xc42f, 0x711d, 0xc419, + 0x7112, 0xc403, 0x7106, 0xc3ec, 0x70fa, 0xc3d6, 0x70ee, 0xc3c0, + 0x70e2, 0xc3aa, 0x70d6, 0xc394, 0x70cb, 0xc37d, 0x70bf, 0xc367, + 0x70b3, 0xc351, 0x70a7, 0xc33b, 0x709b, 0xc325, 0x708f, 0xc30f, + 0x7083, 0xc2f9, 0x7077, 0xc2e3, 0x706b, 0xc2cd, 0x705f, 0xc2b7, + 0x7053, 0xc2a0, 0x7047, 0xc28a, 0x703b, 0xc274, 0x702f, 0xc25e, + 0x7023, 0xc248, 0x7016, 0xc232, 0x700a, 0xc21c, 0x6ffe, 0xc206, + 0x6ff2, 0xc1f0, 0x6fe6, 0xc1da, 0x6fda, 0xc1c4, 0x6fcd, 0xc1ae, + 0x6fc1, 0xc198, 0x6fb5, 0xc183, 0x6fa9, 0xc16d, 0x6f9c, 0xc157, + 0x6f90, 0xc141, 0x6f84, 0xc12b, 0x6f77, 0xc115, 0x6f6b, 0xc0ff, + 0x6f5f, 0xc0e9, 0x6f52, 0xc0d3, 0x6f46, 0xc0bd, 0x6f39, 0xc0a8, + 0x6f2d, 0xc092, 0x6f20, 0xc07c, 0x6f14, 0xc066, 0x6f07, 0xc050, + 0x6efb, 0xc03b, 0x6eee, 0xc025, 0x6ee2, 0xc00f, 0x6ed5, 0xbff9, + 0x6ec9, 0xbfe3, 0x6ebc, 0xbfce, 0x6eaf, 0xbfb8, 0x6ea3, 0xbfa2, + 0x6e96, 0xbf8d, 0x6e89, 0xbf77, 0x6e7d, 0xbf61, 0x6e70, 0xbf4b, + 0x6e63, 0xbf36, 0x6e57, 0xbf20, 0x6e4a, 0xbf0a, 0x6e3d, 0xbef5, + 0x6e30, 0xbedf, 0x6e24, 0xbeca, 0x6e17, 0xbeb4, 0x6e0a, 0xbe9e, + 0x6dfd, 0xbe89, 0x6df0, 0xbe73, 0x6de3, 0xbe5e, 0x6dd6, 0xbe48, + 0x6dca, 0xbe32, 0x6dbd, 0xbe1d, 0x6db0, 0xbe07, 0x6da3, 0xbdf2, + 0x6d96, 0xbddc, 0x6d89, 0xbdc7, 0x6d7c, 0xbdb1, 0x6d6f, 0xbd9c, + 0x6d62, 0xbd86, 0x6d55, 0xbd71, 0x6d48, 0xbd5b, 0x6d3a, 0xbd46, + 0x6d2d, 0xbd30, 0x6d20, 0xbd1b, 0x6d13, 0xbd06, 0x6d06, 0xbcf0, + 0x6cf9, 0xbcdb, 0x6cec, 0xbcc5, 0x6cde, 0xbcb0, 0x6cd1, 0xbc9b, + 0x6cc4, 0xbc85, 0x6cb7, 0xbc70, 0x6ca9, 0xbc5b, 0x6c9c, 0xbc45, + 0x6c8f, 0xbc30, 0x6c81, 0xbc1b, 0x6c74, 0xbc05, 0x6c67, 0xbbf0, + 0x6c59, 0xbbdb, 0x6c4c, 0xbbc5, 0x6c3f, 0xbbb0, 0x6c31, 0xbb9b, + 0x6c24, 0xbb86, 0x6c16, 0xbb70, 0x6c09, 0xbb5b, 0x6bfb, 0xbb46, + 0x6bee, 0xbb31, 0x6be0, 0xbb1c, 0x6bd3, 0xbb06, 0x6bc5, 0xbaf1, + 0x6bb8, 0xbadc, 0x6baa, 0xbac7, 0x6b9c, 0xbab2, 0x6b8f, 0xba9d, + 0x6b81, 0xba88, 0x6b73, 0xba73, 0x6b66, 0xba5d, 0x6b58, 0xba48, + 0x6b4a, 0xba33, 0x6b3d, 0xba1e, 0x6b2f, 0xba09, 0x6b21, 0xb9f4, + 0x6b13, 0xb9df, 0x6b06, 0xb9ca, 0x6af8, 0xb9b5, 0x6aea, 0xb9a0, + 0x6adc, 0xb98b, 0x6ace, 0xb976, 0x6ac1, 0xb961, 0x6ab3, 0xb94c, + 0x6aa5, 0xb937, 0x6a97, 0xb922, 0x6a89, 0xb90d, 0x6a7b, 0xb8f8, + 0x6a6d, 0xb8e4, 0x6a5f, 0xb8cf, 0x6a51, 0xb8ba, 0x6a43, 0xb8a5, + 0x6a35, 0xb890, 0x6a27, 0xb87b, 0x6a19, 0xb866, 0x6a0b, 0xb852, + 0x69fd, 0xb83d, 0x69ef, 0xb828, 0x69e1, 0xb813, 0x69d3, 0xb7fe, + 0x69c4, 0xb7ea, 0x69b6, 0xb7d5, 0x69a8, 0xb7c0, 0x699a, 0xb7ab, + 0x698c, 0xb797, 0x697d, 0xb782, 0x696f, 0xb76d, 0x6961, 0xb758, + 0x6953, 0xb744, 0x6944, 0xb72f, 0x6936, 0xb71a, 0x6928, 0xb706, + 0x6919, 0xb6f1, 0x690b, 0xb6dd, 0x68fd, 0xb6c8, 0x68ee, 0xb6b3, + 0x68e0, 0xb69f, 0x68d1, 0xb68a, 0x68c3, 0xb676, 0x68b5, 0xb661, + 0x68a6, 0xb64c, 0x6898, 0xb638, 0x6889, 0xb623, 0x687b, 0xb60f, + 0x686c, 0xb5fa, 0x685e, 0xb5e6, 0x684f, 0xb5d1, 0x6840, 0xb5bd, + 0x6832, 0xb5a8, 0x6823, 0xb594, 0x6815, 0xb57f, 0x6806, 0xb56b, + 0x67f7, 0xb557, 0x67e9, 0xb542, 0x67da, 0xb52e, 0x67cb, 0xb519, + 0x67bd, 0xb505, 0x67ae, 0xb4f1, 0x679f, 0xb4dc, 0x6790, 0xb4c8, + 0x6782, 0xb4b4, 0x6773, 0xb49f, 0x6764, 0xb48b, 0x6755, 0xb477, + 0x6746, 0xb462, 0x6737, 0xb44e, 0x6729, 0xb43a, 0x671a, 0xb426, + 0x670b, 0xb411, 0x66fc, 0xb3fd, 0x66ed, 0xb3e9, 0x66de, 0xb3d5, + 0x66cf, 0xb3c1, 0x66c0, 0xb3ac, 0x66b1, 0xb398, 0x66a2, 0xb384, + 0x6693, 0xb370, 0x6684, 0xb35c, 0x6675, 0xb348, 0x6666, 0xb334, + 0x6657, 0xb31f, 0x6648, 0xb30b, 0x6639, 0xb2f7, 0x6629, 0xb2e3, + 0x661a, 0xb2cf, 0x660b, 0xb2bb, 0x65fc, 0xb2a7, 0x65ed, 0xb293, + 0x65dd, 0xb27f, 0x65ce, 0xb26b, 0x65bf, 0xb257, 0x65b0, 0xb243, + 0x65a0, 0xb22f, 0x6591, 0xb21b, 0x6582, 0xb207, 0x6573, 0xb1f3, + 0x6563, 0xb1df, 0x6554, 0xb1cc, 0x6545, 0xb1b8, 0x6535, 0xb1a4, + 0x6526, 0xb190, 0x6516, 0xb17c, 0x6507, 0xb168, 0x64f7, 0xb154, + 0x64e8, 0xb141, 0x64d9, 0xb12d, 0x64c9, 0xb119, 0x64ba, 0xb105, + 0x64aa, 0xb0f1, 0x649b, 0xb0de, 0x648b, 0xb0ca, 0x647b, 0xb0b6, + 0x646c, 0xb0a2, 0x645c, 0xb08f, 0x644d, 0xb07b, 0x643d, 0xb067, + 0x642d, 0xb054, 0x641e, 0xb040, 0x640e, 0xb02c, 0x63fe, 0xb019, + 0x63ef, 0xb005, 0x63df, 0xaff1, 0x63cf, 0xafde, 0x63c0, 0xafca, + 0x63b0, 0xafb7, 0x63a0, 0xafa3, 0x6390, 0xaf90, 0x6380, 0xaf7c, + 0x6371, 0xaf69, 0x6361, 0xaf55, 0x6351, 0xaf41, 0x6341, 0xaf2e, + 0x6331, 0xaf1b, 0x6321, 0xaf07, 0x6311, 0xaef4, 0x6301, 0xaee0, + 0x62f2, 0xaecd, 0x62e2, 0xaeb9, 0x62d2, 0xaea6, 0x62c2, 0xae92, + 0x62b2, 0xae7f, 0x62a2, 0xae6c, 0x6292, 0xae58, 0x6282, 0xae45, + 0x6271, 0xae32, 0x6261, 0xae1e, 0x6251, 0xae0b, 0x6241, 0xadf8, + 0x6231, 0xade4, 0x6221, 0xadd1, 0x6211, 0xadbe, 0x6201, 0xadab, + 0x61f1, 0xad97, 0x61e0, 0xad84, 0x61d0, 0xad71, 0x61c0, 0xad5e, + 0x61b0, 0xad4b, 0x619f, 0xad37, 0x618f, 0xad24, 0x617f, 0xad11, + 0x616f, 0xacfe, 0x615e, 0xaceb, 0x614e, 0xacd8, 0x613e, 0xacc5, + 0x612d, 0xacb2, 0x611d, 0xac9e, 0x610d, 0xac8b, 0x60fc, 0xac78, + 0x60ec, 0xac65, 0x60db, 0xac52, 0x60cb, 0xac3f, 0x60ba, 0xac2c, + 0x60aa, 0xac19, 0x6099, 0xac06, 0x6089, 0xabf3, 0x6078, 0xabe0, + 0x6068, 0xabcd, 0x6057, 0xabbb, 0x6047, 0xaba8, 0x6036, 0xab95, + 0x6026, 0xab82, 0x6015, 0xab6f, 0x6004, 0xab5c, 0x5ff4, 0xab49, + 0x5fe3, 0xab36, 0x5fd3, 0xab24, 0x5fc2, 0xab11, 0x5fb1, 0xaafe, + 0x5fa0, 0xaaeb, 0x5f90, 0xaad8, 0x5f7f, 0xaac6, 0x5f6e, 0xaab3, + 0x5f5e, 0xaaa0, 0x5f4d, 0xaa8e, 0x5f3c, 0xaa7b, 0x5f2b, 0xaa68, + 0x5f1a, 0xaa55, 0x5f0a, 0xaa43, 0x5ef9, 0xaa30, 0x5ee8, 0xaa1d, + 0x5ed7, 0xaa0b, 0x5ec6, 0xa9f8, 0x5eb5, 0xa9e6, 0x5ea4, 0xa9d3, + 0x5e93, 0xa9c0, 0x5e82, 0xa9ae, 0x5e71, 0xa99b, 0x5e60, 0xa989, + 0x5e50, 0xa976, 0x5e3f, 0xa964, 0x5e2d, 0xa951, 0x5e1c, 0xa93f, + 0x5e0b, 0xa92c, 0x5dfa, 0xa91a, 0x5de9, 0xa907, 0x5dd8, 0xa8f5, + 0x5dc7, 0xa8e3, 0x5db6, 0xa8d0, 0x5da5, 0xa8be, 0x5d94, 0xa8ab, + 0x5d83, 0xa899, 0x5d71, 0xa887, 0x5d60, 0xa874, 0x5d4f, 0xa862, + 0x5d3e, 0xa850, 0x5d2d, 0xa83d, 0x5d1b, 0xa82b, 0x5d0a, 0xa819, + 0x5cf9, 0xa807, 0x5ce8, 0xa7f4, 0x5cd6, 0xa7e2, 0x5cc5, 0xa7d0, + 0x5cb4, 0xa7be, 0x5ca2, 0xa7ab, 0x5c91, 0xa799, 0x5c80, 0xa787, + 0x5c6e, 0xa775, 0x5c5d, 0xa763, 0x5c4b, 0xa751, 0x5c3a, 0xa73f, + 0x5c29, 0xa72c, 0x5c17, 0xa71a, 0x5c06, 0xa708, 0x5bf4, 0xa6f6, + 0x5be3, 0xa6e4, 0x5bd1, 0xa6d2, 0x5bc0, 0xa6c0, 0x5bae, 0xa6ae, + 0x5b9d, 0xa69c, 0x5b8b, 0xa68a, 0x5b79, 0xa678, 0x5b68, 0xa666, + 0x5b56, 0xa654, 0x5b45, 0xa642, 0x5b33, 0xa630, 0x5b21, 0xa61f, + 0x5b10, 0xa60d, 0x5afe, 0xa5fb, 0x5aec, 0xa5e9, 0x5adb, 0xa5d7, + 0x5ac9, 0xa5c5, 0x5ab7, 0xa5b3, 0x5aa5, 0xa5a2, 0x5a94, 0xa590, + 0x5a82, 0xa57e, 0x5a70, 0xa56c, 0x5a5e, 0xa55b, 0x5a4d, 0xa549, + 0x5a3b, 0xa537, 0x5a29, 0xa525, 0x5a17, 0xa514, 0x5a05, 0xa502, + 0x59f3, 0xa4f0, 0x59e1, 0xa4df, 0x59d0, 0xa4cd, 0x59be, 0xa4bb, + 0x59ac, 0xa4aa, 0x599a, 0xa498, 0x5988, 0xa487, 0x5976, 0xa475, + 0x5964, 0xa463, 0x5952, 0xa452, 0x5940, 0xa440, 0x592e, 0xa42f, + 0x591c, 0xa41d, 0x590a, 0xa40c, 0x58f8, 0xa3fa, 0x58e6, 0xa3e9, + 0x58d4, 0xa3d7, 0x58c1, 0xa3c6, 0x58af, 0xa3b5, 0x589d, 0xa3a3, + 0x588b, 0xa392, 0x5879, 0xa380, 0x5867, 0xa36f, 0x5855, 0xa35e, + 0x5842, 0xa34c, 0x5830, 0xa33b, 0x581e, 0xa32a, 0x580c, 0xa318, + 0x57f9, 0xa307, 0x57e7, 0xa2f6, 0x57d5, 0xa2e5, 0x57c3, 0xa2d3, + 0x57b0, 0xa2c2, 0x579e, 0xa2b1, 0x578c, 0xa2a0, 0x5779, 0xa28f, + 0x5767, 0xa27d, 0x5755, 0xa26c, 0x5742, 0xa25b, 0x5730, 0xa24a, + 0x571d, 0xa239, 0x570b, 0xa228, 0x56f9, 0xa217, 0x56e6, 0xa206, + 0x56d4, 0xa1f5, 0x56c1, 0xa1e4, 0x56af, 0xa1d3, 0x569c, 0xa1c1, + 0x568a, 0xa1b0, 0x5677, 0xa1a0, 0x5665, 0xa18f, 0x5652, 0xa17e, + 0x5640, 0xa16d, 0x562d, 0xa15c, 0x561a, 0xa14b, 0x5608, 0xa13a, + 0x55f5, 0xa129, 0x55e3, 0xa118, 0x55d0, 0xa107, 0x55bd, 0xa0f6, + 0x55ab, 0xa0e6, 0x5598, 0xa0d5, 0x5585, 0xa0c4, 0x5572, 0xa0b3, + 0x5560, 0xa0a2, 0x554d, 0xa092, 0x553a, 0xa081, 0x5528, 0xa070, + 0x5515, 0xa060, 0x5502, 0xa04f, 0x54ef, 0xa03e, 0x54dc, 0xa02d, + 0x54ca, 0xa01d, 0x54b7, 0xa00c, 0x54a4, 0x9ffc, 0x5491, 0x9feb, + 0x547e, 0x9fda, 0x546b, 0x9fca, 0x5458, 0x9fb9, 0x5445, 0x9fa9, + 0x5433, 0x9f98, 0x5420, 0x9f88, 0x540d, 0x9f77, 0x53fa, 0x9f67, + 0x53e7, 0x9f56, 0x53d4, 0x9f46, 0x53c1, 0x9f35, 0x53ae, 0x9f25, + 0x539b, 0x9f14, 0x5388, 0x9f04, 0x5375, 0x9ef3, 0x5362, 0x9ee3, + 0x534e, 0x9ed3, 0x533b, 0x9ec2, 0x5328, 0x9eb2, 0x5315, 0x9ea2, + 0x5302, 0x9e91, 0x52ef, 0x9e81, 0x52dc, 0x9e71, 0x52c9, 0x9e61, + 0x52b5, 0x9e50, 0x52a2, 0x9e40, 0x528f, 0x9e30, 0x527c, 0x9e20, + 0x5269, 0x9e0f, 0x5255, 0x9dff, 0x5242, 0x9def, 0x522f, 0x9ddf, + 0x521c, 0x9dcf, 0x5208, 0x9dbf, 0x51f5, 0x9daf, 0x51e2, 0x9d9f, + 0x51ce, 0x9d8f, 0x51bb, 0x9d7e, 0x51a8, 0x9d6e, 0x5194, 0x9d5e, + 0x5181, 0x9d4e, 0x516e, 0x9d3e, 0x515a, 0x9d2e, 0x5147, 0x9d1e, + 0x5133, 0x9d0e, 0x5120, 0x9cff, 0x510c, 0x9cef, 0x50f9, 0x9cdf, + 0x50e5, 0x9ccf, 0x50d2, 0x9cbf, 0x50bf, 0x9caf, 0x50ab, 0x9c9f, + 0x5097, 0x9c8f, 0x5084, 0x9c80, 0x5070, 0x9c70, 0x505d, 0x9c60, + 0x5049, 0x9c50, 0x5036, 0x9c40, 0x5022, 0x9c31, 0x500f, 0x9c21, + 0x4ffb, 0x9c11, 0x4fe7, 0x9c02, 0x4fd4, 0x9bf2, 0x4fc0, 0x9be2, + 0x4fac, 0x9bd3, 0x4f99, 0x9bc3, 0x4f85, 0x9bb3, 0x4f71, 0x9ba4, + 0x4f5e, 0x9b94, 0x4f4a, 0x9b85, 0x4f36, 0x9b75, 0x4f22, 0x9b65, + 0x4f0f, 0x9b56, 0x4efb, 0x9b46, 0x4ee7, 0x9b37, 0x4ed3, 0x9b27, + 0x4ebf, 0x9b18, 0x4eac, 0x9b09, 0x4e98, 0x9af9, 0x4e84, 0x9aea, + 0x4e70, 0x9ada, 0x4e5c, 0x9acb, 0x4e48, 0x9abb, 0x4e34, 0x9aac, + 0x4e21, 0x9a9d, 0x4e0d, 0x9a8d, 0x4df9, 0x9a7e, 0x4de5, 0x9a6f, + 0x4dd1, 0x9a60, 0x4dbd, 0x9a50, 0x4da9, 0x9a41, 0x4d95, 0x9a32, + 0x4d81, 0x9a23, 0x4d6d, 0x9a13, 0x4d59, 0x9a04, 0x4d45, 0x99f5, + 0x4d31, 0x99e6, 0x4d1d, 0x99d7, 0x4d09, 0x99c7, 0x4cf5, 0x99b8, + 0x4ce1, 0x99a9, 0x4ccc, 0x999a, 0x4cb8, 0x998b, 0x4ca4, 0x997c, + 0x4c90, 0x996d, 0x4c7c, 0x995e, 0x4c68, 0x994f, 0x4c54, 0x9940, + 0x4c3f, 0x9931, 0x4c2b, 0x9922, 0x4c17, 0x9913, 0x4c03, 0x9904, + 0x4bef, 0x98f5, 0x4bda, 0x98e6, 0x4bc6, 0x98d7, 0x4bb2, 0x98c9, + 0x4b9e, 0x98ba, 0x4b89, 0x98ab, 0x4b75, 0x989c, 0x4b61, 0x988d, + 0x4b4c, 0x987e, 0x4b38, 0x9870, 0x4b24, 0x9861, 0x4b0f, 0x9852, + 0x4afb, 0x9843, 0x4ae7, 0x9835, 0x4ad2, 0x9826, 0x4abe, 0x9817, + 0x4aa9, 0x9809, 0x4a95, 0x97fa, 0x4a81, 0x97eb, 0x4a6c, 0x97dd, + 0x4a58, 0x97ce, 0x4a43, 0x97c0, 0x4a2f, 0x97b1, 0x4a1a, 0x97a2, + 0x4a06, 0x9794, 0x49f1, 0x9785, 0x49dd, 0x9777, 0x49c8, 0x9768, + 0x49b4, 0x975a, 0x499f, 0x974b, 0x498a, 0x973d, 0x4976, 0x972f, + 0x4961, 0x9720, 0x494d, 0x9712, 0x4938, 0x9703, 0x4923, 0x96f5, + 0x490f, 0x96e7, 0x48fa, 0x96d8, 0x48e6, 0x96ca, 0x48d1, 0x96bc, + 0x48bc, 0x96ad, 0x48a8, 0x969f, 0x4893, 0x9691, 0x487e, 0x9683, + 0x4869, 0x9674, 0x4855, 0x9666, 0x4840, 0x9658, 0x482b, 0x964a, + 0x4816, 0x963c, 0x4802, 0x962d, 0x47ed, 0x961f, 0x47d8, 0x9611, + 0x47c3, 0x9603, 0x47ae, 0x95f5, 0x479a, 0x95e7, 0x4785, 0x95d9, + 0x4770, 0x95cb, 0x475b, 0x95bd, 0x4746, 0x95af, 0x4731, 0x95a1, + 0x471c, 0x9593, 0x4708, 0x9585, 0x46f3, 0x9577, 0x46de, 0x9569, + 0x46c9, 0x955b, 0x46b4, 0x954d, 0x469f, 0x953f, 0x468a, 0x9532, + 0x4675, 0x9524, 0x4660, 0x9516, 0x464b, 0x9508, 0x4636, 0x94fa, + 0x4621, 0x94ed, 0x460c, 0x94df, 0x45f7, 0x94d1, 0x45e2, 0x94c3, + 0x45cd, 0x94b6, 0x45b8, 0x94a8, 0x45a3, 0x949a, 0x458d, 0x948d, + 0x4578, 0x947f, 0x4563, 0x9471, 0x454e, 0x9464, 0x4539, 0x9456, + 0x4524, 0x9448, 0x450f, 0x943b, 0x44fa, 0x942d, 0x44e4, 0x9420, + 0x44cf, 0x9412, 0x44ba, 0x9405, 0x44a5, 0x93f7, 0x4490, 0x93ea, + 0x447a, 0x93dc, 0x4465, 0x93cf, 0x4450, 0x93c1, 0x443b, 0x93b4, + 0x4425, 0x93a7, 0x4410, 0x9399, 0x43fb, 0x938c, 0x43e5, 0x937f, + 0x43d0, 0x9371, 0x43bb, 0x9364, 0x43a5, 0x9357, 0x4390, 0x9349, + 0x437b, 0x933c, 0x4365, 0x932f, 0x4350, 0x9322, 0x433b, 0x9314, + 0x4325, 0x9307, 0x4310, 0x92fa, 0x42fa, 0x92ed, 0x42e5, 0x92e0, + 0x42d0, 0x92d3, 0x42ba, 0x92c6, 0x42a5, 0x92b8, 0x428f, 0x92ab, + 0x427a, 0x929e, 0x4264, 0x9291, 0x424f, 0x9284, 0x4239, 0x9277, + 0x4224, 0x926a, 0x420e, 0x925d, 0x41f9, 0x9250, 0x41e3, 0x9243, + 0x41ce, 0x9236, 0x41b8, 0x922a, 0x41a2, 0x921d, 0x418d, 0x9210, + 0x4177, 0x9203, 0x4162, 0x91f6, 0x414c, 0x91e9, 0x4136, 0x91dc, + 0x4121, 0x91d0, 0x410b, 0x91c3, 0x40f6, 0x91b6, 0x40e0, 0x91a9, + 0x40ca, 0x919d, 0x40b5, 0x9190, 0x409f, 0x9183, 0x4089, 0x9177, + 0x4073, 0x916a, 0x405e, 0x915d, 0x4048, 0x9151, 0x4032, 0x9144, + 0x401d, 0x9137, 0x4007, 0x912b, 0x3ff1, 0x911e, 0x3fdb, 0x9112, + 0x3fc5, 0x9105, 0x3fb0, 0x90f9, 0x3f9a, 0x90ec, 0x3f84, 0x90e0, + 0x3f6e, 0x90d3, 0x3f58, 0x90c7, 0x3f43, 0x90ba, 0x3f2d, 0x90ae, + 0x3f17, 0x90a1, 0x3f01, 0x9095, 0x3eeb, 0x9089, 0x3ed5, 0x907c, + 0x3ebf, 0x9070, 0x3ea9, 0x9064, 0x3e93, 0x9057, 0x3e7d, 0x904b, + 0x3e68, 0x903f, 0x3e52, 0x9033, 0x3e3c, 0x9026, 0x3e26, 0x901a, + 0x3e10, 0x900e, 0x3dfa, 0x9002, 0x3de4, 0x8ff6, 0x3dce, 0x8fea, + 0x3db8, 0x8fdd, 0x3da2, 0x8fd1, 0x3d8c, 0x8fc5, 0x3d76, 0x8fb9, + 0x3d60, 0x8fad, 0x3d49, 0x8fa1, 0x3d33, 0x8f95, 0x3d1d, 0x8f89, + 0x3d07, 0x8f7d, 0x3cf1, 0x8f71, 0x3cdb, 0x8f65, 0x3cc5, 0x8f59, + 0x3caf, 0x8f4d, 0x3c99, 0x8f41, 0x3c83, 0x8f35, 0x3c6c, 0x8f2a, + 0x3c56, 0x8f1e, 0x3c40, 0x8f12, 0x3c2a, 0x8f06, 0x3c14, 0x8efa, + 0x3bfd, 0x8eee, 0x3be7, 0x8ee3, 0x3bd1, 0x8ed7, 0x3bbb, 0x8ecb, + 0x3ba5, 0x8ebf, 0x3b8e, 0x8eb4, 0x3b78, 0x8ea8, 0x3b62, 0x8e9c, + 0x3b4c, 0x8e91, 0x3b35, 0x8e85, 0x3b1f, 0x8e7a, 0x3b09, 0x8e6e, + 0x3af2, 0x8e62, 0x3adc, 0x8e57, 0x3ac6, 0x8e4b, 0x3aaf, 0x8e40, + 0x3a99, 0x8e34, 0x3a83, 0x8e29, 0x3a6c, 0x8e1d, 0x3a56, 0x8e12, + 0x3a40, 0x8e06, 0x3a29, 0x8dfb, 0x3a13, 0x8def, 0x39fd, 0x8de4, + 0x39e6, 0x8dd9, 0x39d0, 0x8dcd, 0x39b9, 0x8dc2, 0x39a3, 0x8db7, + 0x398c, 0x8dab, 0x3976, 0x8da0, 0x395f, 0x8d95, 0x3949, 0x8d8a, + 0x3932, 0x8d7e, 0x391c, 0x8d73, 0x3906, 0x8d68, 0x38ef, 0x8d5d, + 0x38d8, 0x8d51, 0x38c2, 0x8d46, 0x38ab, 0x8d3b, 0x3895, 0x8d30, + 0x387e, 0x8d25, 0x3868, 0x8d1a, 0x3851, 0x8d0f, 0x383b, 0x8d04, + 0x3824, 0x8cf9, 0x380d, 0x8cee, 0x37f7, 0x8ce3, 0x37e0, 0x8cd8, + 0x37ca, 0x8ccd, 0x37b3, 0x8cc2, 0x379c, 0x8cb7, 0x3786, 0x8cac, + 0x376f, 0x8ca1, 0x3758, 0x8c96, 0x3742, 0x8c8b, 0x372b, 0x8c81, + 0x3714, 0x8c76, 0x36fe, 0x8c6b, 0x36e7, 0x8c60, 0x36d0, 0x8c55, + 0x36ba, 0x8c4b, 0x36a3, 0x8c40, 0x368c, 0x8c35, 0x3675, 0x8c2a, + 0x365f, 0x8c20, 0x3648, 0x8c15, 0x3631, 0x8c0a, 0x361a, 0x8c00, + 0x3604, 0x8bf5, 0x35ed, 0x8beb, 0x35d6, 0x8be0, 0x35bf, 0x8bd5, + 0x35a8, 0x8bcb, 0x3592, 0x8bc0, 0x357b, 0x8bb6, 0x3564, 0x8bab, + 0x354d, 0x8ba1, 0x3536, 0x8b96, 0x351f, 0x8b8c, 0x3508, 0x8b82, + 0x34f2, 0x8b77, 0x34db, 0x8b6d, 0x34c4, 0x8b62, 0x34ad, 0x8b58, + 0x3496, 0x8b4e, 0x347f, 0x8b43, 0x3468, 0x8b39, 0x3451, 0x8b2f, + 0x343a, 0x8b25, 0x3423, 0x8b1a, 0x340c, 0x8b10, 0x33f5, 0x8b06, + 0x33de, 0x8afc, 0x33c7, 0x8af1, 0x33b0, 0x8ae7, 0x3399, 0x8add, + 0x3382, 0x8ad3, 0x336b, 0x8ac9, 0x3354, 0x8abf, 0x333d, 0x8ab5, + 0x3326, 0x8aab, 0x330f, 0x8aa1, 0x32f8, 0x8a97, 0x32e1, 0x8a8d, + 0x32ca, 0x8a83, 0x32b3, 0x8a79, 0x329c, 0x8a6f, 0x3285, 0x8a65, + 0x326e, 0x8a5b, 0x3257, 0x8a51, 0x3240, 0x8a47, 0x3228, 0x8a3d, + 0x3211, 0x8a34, 0x31fa, 0x8a2a, 0x31e3, 0x8a20, 0x31cc, 0x8a16, + 0x31b5, 0x8a0c, 0x319e, 0x8a03, 0x3186, 0x89f9, 0x316f, 0x89ef, + 0x3158, 0x89e5, 0x3141, 0x89dc, 0x312a, 0x89d2, 0x3112, 0x89c8, + 0x30fb, 0x89bf, 0x30e4, 0x89b5, 0x30cd, 0x89ac, 0x30b6, 0x89a2, + 0x309e, 0x8998, 0x3087, 0x898f, 0x3070, 0x8985, 0x3059, 0x897c, + 0x3041, 0x8972, 0x302a, 0x8969, 0x3013, 0x8960, 0x2ffb, 0x8956, + 0x2fe4, 0x894d, 0x2fcd, 0x8943, 0x2fb5, 0x893a, 0x2f9e, 0x8931, + 0x2f87, 0x8927, 0x2f6f, 0x891e, 0x2f58, 0x8915, 0x2f41, 0x890b, + 0x2f29, 0x8902, 0x2f12, 0x88f9, 0x2efb, 0x88f0, 0x2ee3, 0x88e6, + 0x2ecc, 0x88dd, 0x2eb5, 0x88d4, 0x2e9d, 0x88cb, 0x2e86, 0x88c2, + 0x2e6e, 0x88b9, 0x2e57, 0x88af, 0x2e3f, 0x88a6, 0x2e28, 0x889d, + 0x2e11, 0x8894, 0x2df9, 0x888b, 0x2de2, 0x8882, 0x2dca, 0x8879, + 0x2db3, 0x8870, 0x2d9b, 0x8867, 0x2d84, 0x885e, 0x2d6c, 0x8855, + 0x2d55, 0x884c, 0x2d3d, 0x8844, 0x2d26, 0x883b, 0x2d0e, 0x8832, + 0x2cf7, 0x8829, 0x2cdf, 0x8820, 0x2cc8, 0x8817, 0x2cb0, 0x880f, + 0x2c98, 0x8806, 0x2c81, 0x87fd, 0x2c69, 0x87f4, 0x2c52, 0x87ec, + 0x2c3a, 0x87e3, 0x2c23, 0x87da, 0x2c0b, 0x87d2, 0x2bf3, 0x87c9, + 0x2bdc, 0x87c0, 0x2bc4, 0x87b8, 0x2bad, 0x87af, 0x2b95, 0x87a7, + 0x2b7d, 0x879e, 0x2b66, 0x8795, 0x2b4e, 0x878d, 0x2b36, 0x8784, + 0x2b1f, 0x877c, 0x2b07, 0x8774, 0x2aef, 0x876b, 0x2ad8, 0x8763, + 0x2ac0, 0x875a, 0x2aa8, 0x8752, 0x2a91, 0x874a, 0x2a79, 0x8741, + 0x2a61, 0x8739, 0x2a49, 0x8731, 0x2a32, 0x8728, 0x2a1a, 0x8720, + 0x2a02, 0x8718, 0x29eb, 0x870f, 0x29d3, 0x8707, 0x29bb, 0x86ff, + 0x29a3, 0x86f7, 0x298b, 0x86ef, 0x2974, 0x86e7, 0x295c, 0x86de, + 0x2944, 0x86d6, 0x292c, 0x86ce, 0x2915, 0x86c6, 0x28fd, 0x86be, + 0x28e5, 0x86b6, 0x28cd, 0x86ae, 0x28b5, 0x86a6, 0x289d, 0x869e, + 0x2886, 0x8696, 0x286e, 0x868e, 0x2856, 0x8686, 0x283e, 0x867e, + 0x2826, 0x8676, 0x280e, 0x866e, 0x27f6, 0x8667, 0x27df, 0x865f, + 0x27c7, 0x8657, 0x27af, 0x864f, 0x2797, 0x8647, 0x277f, 0x8640, + 0x2767, 0x8638, 0x274f, 0x8630, 0x2737, 0x8628, 0x271f, 0x8621, + 0x2707, 0x8619, 0x26ef, 0x8611, 0x26d8, 0x860a, 0x26c0, 0x8602, + 0x26a8, 0x85fb, 0x2690, 0x85f3, 0x2678, 0x85eb, 0x2660, 0x85e4, + 0x2648, 0x85dc, 0x2630, 0x85d5, 0x2618, 0x85cd, 0x2600, 0x85c6, + 0x25e8, 0x85be, 0x25d0, 0x85b7, 0x25b8, 0x85b0, 0x25a0, 0x85a8, + 0x2588, 0x85a1, 0x2570, 0x8599, 0x2558, 0x8592, 0x2540, 0x858b, + 0x2528, 0x8583, 0x250f, 0x857c, 0x24f7, 0x8575, 0x24df, 0x856e, + 0x24c7, 0x8566, 0x24af, 0x855f, 0x2497, 0x8558, 0x247f, 0x8551, + 0x2467, 0x854a, 0x244f, 0x8543, 0x2437, 0x853b, 0x241f, 0x8534, + 0x2407, 0x852d, 0x23ee, 0x8526, 0x23d6, 0x851f, 0x23be, 0x8518, + 0x23a6, 0x8511, 0x238e, 0x850a, 0x2376, 0x8503, 0x235e, 0x84fc, + 0x2345, 0x84f5, 0x232d, 0x84ee, 0x2315, 0x84e7, 0x22fd, 0x84e1, + 0x22e5, 0x84da, 0x22cd, 0x84d3, 0x22b4, 0x84cc, 0x229c, 0x84c5, + 0x2284, 0x84be, 0x226c, 0x84b8, 0x2254, 0x84b1, 0x223b, 0x84aa, + 0x2223, 0x84a3, 0x220b, 0x849d, 0x21f3, 0x8496, 0x21da, 0x848f, + 0x21c2, 0x8489, 0x21aa, 0x8482, 0x2192, 0x847c, 0x2179, 0x8475, + 0x2161, 0x846e, 0x2149, 0x8468, 0x2131, 0x8461, 0x2118, 0x845b, + 0x2100, 0x8454, 0x20e8, 0x844e, 0x20d0, 0x8447, 0x20b7, 0x8441, + 0x209f, 0x843b, 0x2087, 0x8434, 0x206e, 0x842e, 0x2056, 0x8427, + 0x203e, 0x8421, 0x2025, 0x841b, 0x200d, 0x8415, 0x1ff5, 0x840e, + 0x1fdc, 0x8408, 0x1fc4, 0x8402, 0x1fac, 0x83fb, 0x1f93, 0x83f5, + 0x1f7b, 0x83ef, 0x1f63, 0x83e9, 0x1f4a, 0x83e3, 0x1f32, 0x83dd, + 0x1f19, 0x83d7, 0x1f01, 0x83d0, 0x1ee9, 0x83ca, 0x1ed0, 0x83c4, + 0x1eb8, 0x83be, 0x1ea0, 0x83b8, 0x1e87, 0x83b2, 0x1e6f, 0x83ac, + 0x1e56, 0x83a6, 0x1e3e, 0x83a0, 0x1e25, 0x839a, 0x1e0d, 0x8394, + 0x1df5, 0x838f, 0x1ddc, 0x8389, 0x1dc4, 0x8383, 0x1dab, 0x837d, + 0x1d93, 0x8377, 0x1d7a, 0x8371, 0x1d62, 0x836c, 0x1d49, 0x8366, + 0x1d31, 0x8360, 0x1d18, 0x835a, 0x1d00, 0x8355, 0x1ce8, 0x834f, + 0x1ccf, 0x8349, 0x1cb7, 0x8344, 0x1c9e, 0x833e, 0x1c86, 0x8338, + 0x1c6d, 0x8333, 0x1c55, 0x832d, 0x1c3c, 0x8328, 0x1c24, 0x8322, + 0x1c0b, 0x831d, 0x1bf2, 0x8317, 0x1bda, 0x8312, 0x1bc1, 0x830c, + 0x1ba9, 0x8307, 0x1b90, 0x8301, 0x1b78, 0x82fc, 0x1b5f, 0x82f7, + 0x1b47, 0x82f1, 0x1b2e, 0x82ec, 0x1b16, 0x82e7, 0x1afd, 0x82e1, + 0x1ae4, 0x82dc, 0x1acc, 0x82d7, 0x1ab3, 0x82d1, 0x1a9b, 0x82cc, + 0x1a82, 0x82c7, 0x1a6a, 0x82c2, 0x1a51, 0x82bd, 0x1a38, 0x82b7, + 0x1a20, 0x82b2, 0x1a07, 0x82ad, 0x19ef, 0x82a8, 0x19d6, 0x82a3, + 0x19bd, 0x829e, 0x19a5, 0x8299, 0x198c, 0x8294, 0x1973, 0x828f, + 0x195b, 0x828a, 0x1942, 0x8285, 0x192a, 0x8280, 0x1911, 0x827b, + 0x18f8, 0x8276, 0x18e0, 0x8271, 0x18c7, 0x826c, 0x18ae, 0x8268, + 0x1896, 0x8263, 0x187d, 0x825e, 0x1864, 0x8259, 0x184c, 0x8254, + 0x1833, 0x8250, 0x181a, 0x824b, 0x1802, 0x8246, 0x17e9, 0x8241, + 0x17d0, 0x823d, 0x17b7, 0x8238, 0x179f, 0x8233, 0x1786, 0x822f, + 0x176d, 0x822a, 0x1755, 0x8226, 0x173c, 0x8221, 0x1723, 0x821c, + 0x170a, 0x8218, 0x16f2, 0x8213, 0x16d9, 0x820f, 0x16c0, 0x820a, + 0x16a8, 0x8206, 0x168f, 0x8201, 0x1676, 0x81fd, 0x165d, 0x81f9, + 0x1645, 0x81f4, 0x162c, 0x81f0, 0x1613, 0x81ec, 0x15fa, 0x81e7, + 0x15e2, 0x81e3, 0x15c9, 0x81df, 0x15b0, 0x81da, 0x1597, 0x81d6, + 0x157f, 0x81d2, 0x1566, 0x81ce, 0x154d, 0x81c9, 0x1534, 0x81c5, + 0x151b, 0x81c1, 0x1503, 0x81bd, 0x14ea, 0x81b9, 0x14d1, 0x81b5, + 0x14b8, 0x81b1, 0x149f, 0x81ad, 0x1487, 0x81a9, 0x146e, 0x81a5, + 0x1455, 0x81a1, 0x143c, 0x819d, 0x1423, 0x8199, 0x140b, 0x8195, + 0x13f2, 0x8191, 0x13d9, 0x818d, 0x13c0, 0x8189, 0x13a7, 0x8185, + 0x138e, 0x8181, 0x1376, 0x817d, 0x135d, 0x817a, 0x1344, 0x8176, + 0x132b, 0x8172, 0x1312, 0x816e, 0x12f9, 0x816b, 0x12e0, 0x8167, + 0x12c8, 0x8163, 0x12af, 0x815f, 0x1296, 0x815c, 0x127d, 0x8158, + 0x1264, 0x8155, 0x124b, 0x8151, 0x1232, 0x814d, 0x1219, 0x814a, + 0x1201, 0x8146, 0x11e8, 0x8143, 0x11cf, 0x813f, 0x11b6, 0x813c, + 0x119d, 0x8138, 0x1184, 0x8135, 0x116b, 0x8131, 0x1152, 0x812e, + 0x1139, 0x812b, 0x1121, 0x8127, 0x1108, 0x8124, 0x10ef, 0x8121, + 0x10d6, 0x811d, 0x10bd, 0x811a, 0x10a4, 0x8117, 0x108b, 0x8113, + 0x1072, 0x8110, 0x1059, 0x810d, 0x1040, 0x810a, 0x1027, 0x8107, + 0x100e, 0x8103, 0xff5, 0x8100, 0xfdd, 0x80fd, 0xfc4, 0x80fa, + 0xfab, 0x80f7, 0xf92, 0x80f4, 0xf79, 0x80f1, 0xf60, 0x80ee, + 0xf47, 0x80eb, 0xf2e, 0x80e8, 0xf15, 0x80e5, 0xefc, 0x80e2, + 0xee3, 0x80df, 0xeca, 0x80dc, 0xeb1, 0x80d9, 0xe98, 0x80d6, + 0xe7f, 0x80d3, 0xe66, 0x80d1, 0xe4d, 0x80ce, 0xe34, 0x80cb, + 0xe1b, 0x80c8, 0xe02, 0x80c5, 0xde9, 0x80c3, 0xdd0, 0x80c0, + 0xdb7, 0x80bd, 0xd9e, 0x80bb, 0xd85, 0x80b8, 0xd6c, 0x80b5, + 0xd53, 0x80b3, 0xd3a, 0x80b0, 0xd21, 0x80ad, 0xd08, 0x80ab, + 0xcef, 0x80a8, 0xcd6, 0x80a6, 0xcbd, 0x80a3, 0xca4, 0x80a1, + 0xc8b, 0x809e, 0xc72, 0x809c, 0xc59, 0x8099, 0xc40, 0x8097, + 0xc27, 0x8095, 0xc0e, 0x8092, 0xbf5, 0x8090, 0xbdc, 0x808e, + 0xbc3, 0x808b, 0xbaa, 0x8089, 0xb91, 0x8087, 0xb78, 0x8084, + 0xb5f, 0x8082, 0xb46, 0x8080, 0xb2d, 0x807e, 0xb14, 0x807b, + 0xafb, 0x8079, 0xae2, 0x8077, 0xac9, 0x8075, 0xab0, 0x8073, + 0xa97, 0x8071, 0xa7e, 0x806f, 0xa65, 0x806d, 0xa4c, 0x806b, + 0xa33, 0x8069, 0xa19, 0x8067, 0xa00, 0x8065, 0x9e7, 0x8063, + 0x9ce, 0x8061, 0x9b5, 0x805f, 0x99c, 0x805d, 0x983, 0x805b, + 0x96a, 0x8059, 0x951, 0x8057, 0x938, 0x8056, 0x91f, 0x8054, + 0x906, 0x8052, 0x8ed, 0x8050, 0x8d4, 0x804f, 0x8bb, 0x804d, + 0x8a2, 0x804b, 0x888, 0x8049, 0x86f, 0x8048, 0x856, 0x8046, + 0x83d, 0x8044, 0x824, 0x8043, 0x80b, 0x8041, 0x7f2, 0x8040, + 0x7d9, 0x803e, 0x7c0, 0x803d, 0x7a7, 0x803b, 0x78e, 0x803a, + 0x775, 0x8038, 0x75b, 0x8037, 0x742, 0x8035, 0x729, 0x8034, + 0x710, 0x8032, 0x6f7, 0x8031, 0x6de, 0x8030, 0x6c5, 0x802e, + 0x6ac, 0x802d, 0x693, 0x802c, 0x67a, 0x802a, 0x660, 0x8029, + 0x647, 0x8028, 0x62e, 0x8027, 0x615, 0x8026, 0x5fc, 0x8024, + 0x5e3, 0x8023, 0x5ca, 0x8022, 0x5b1, 0x8021, 0x598, 0x8020, + 0x57f, 0x801f, 0x565, 0x801e, 0x54c, 0x801d, 0x533, 0x801c, + 0x51a, 0x801b, 0x501, 0x801a, 0x4e8, 0x8019, 0x4cf, 0x8018, + 0x4b6, 0x8017, 0x49c, 0x8016, 0x483, 0x8015, 0x46a, 0x8014, + 0x451, 0x8013, 0x438, 0x8012, 0x41f, 0x8012, 0x406, 0x8011, + 0x3ed, 0x8010, 0x3d4, 0x800f, 0x3ba, 0x800e, 0x3a1, 0x800e, + 0x388, 0x800d, 0x36f, 0x800c, 0x356, 0x800c, 0x33d, 0x800b, + 0x324, 0x800a, 0x30b, 0x800a, 0x2f1, 0x8009, 0x2d8, 0x8009, + 0x2bf, 0x8008, 0x2a6, 0x8008, 0x28d, 0x8007, 0x274, 0x8007, + 0x25b, 0x8006, 0x242, 0x8006, 0x228, 0x8005, 0x20f, 0x8005, + 0x1f6, 0x8004, 0x1dd, 0x8004, 0x1c4, 0x8004, 0x1ab, 0x8003, + 0x192, 0x8003, 0x178, 0x8003, 0x15f, 0x8002, 0x146, 0x8002, + 0x12d, 0x8002, 0x114, 0x8002, 0xfb, 0x8001, 0xe2, 0x8001, + 0xc9, 0x8001, 0xaf, 0x8001, 0x96, 0x8001, 0x7d, 0x8001, + 0x64, 0x8001, 0x4b, 0x8001, 0x32, 0x8001, 0x19, 0x8001, +}; + +/** +* \par +* cosFactor tables are generated using the formula :
 cos_factors[n] = 2 * cos((2n+1)*pi/(4*N)) 
+* \par +* C command to generate the table +*
   
+* for(i = 0; i< N; i++)   
+* {   
+*   cos_factors[i]= 2 * cos((2*i+1)*c/2);   
+* } 
+* \par +* where N is the number of factors to generate and c is pi/(2*N) +* \par +* Then converted to q15 format by multiplying with 2^31 and saturated if required. + +*/ + +static const q15_t cos_factorsQ15_128[128] = { + 0x7fff, 0x7ffa, 0x7ff0, 0x7fe1, 0x7fce, 0x7fb5, 0x7f97, 0x7f75, + 0x7f4d, 0x7f21, 0x7ef0, 0x7eba, 0x7e7f, 0x7e3f, 0x7dfa, 0x7db0, + 0x7d62, 0x7d0f, 0x7cb7, 0x7c5a, 0x7bf8, 0x7b92, 0x7b26, 0x7ab6, + 0x7a42, 0x79c8, 0x794a, 0x78c7, 0x7840, 0x77b4, 0x7723, 0x768e, + 0x75f4, 0x7555, 0x74b2, 0x740b, 0x735f, 0x72af, 0x71fa, 0x7141, + 0x7083, 0x6fc1, 0x6efb, 0x6e30, 0x6d62, 0x6c8f, 0x6bb8, 0x6adc, + 0x69fd, 0x6919, 0x6832, 0x6746, 0x6657, 0x6563, 0x646c, 0x6371, + 0x6271, 0x616f, 0x6068, 0x5f5e, 0x5e50, 0x5d3e, 0x5c29, 0x5b10, + 0x59f3, 0x58d4, 0x57b0, 0x568a, 0x5560, 0x5433, 0x5302, 0x51ce, + 0x5097, 0x4f5e, 0x4e21, 0x4ce1, 0x4b9e, 0x4a58, 0x490f, 0x47c3, + 0x4675, 0x4524, 0x43d0, 0x427a, 0x4121, 0x3fc5, 0x3e68, 0x3d07, + 0x3ba5, 0x3a40, 0x38d8, 0x376f, 0x3604, 0x3496, 0x3326, 0x31b5, + 0x3041, 0x2ecc, 0x2d55, 0x2bdc, 0x2a61, 0x28e5, 0x2767, 0x25e8, + 0x2467, 0x22e5, 0x2161, 0x1fdc, 0x1e56, 0x1ccf, 0x1b47, 0x19bd, + 0x1833, 0x16a8, 0x151b, 0x138e, 0x1201, 0x1072, 0xee3, 0xd53, + 0xbc3, 0xa33, 0x8a2, 0x710, 0x57f, 0x3ed, 0x25b, 0xc9 +}; + +static const q15_t cos_factorsQ15_512[512] = { + 0x7fff, 0x7fff, 0x7fff, 0x7ffe, 0x7ffc, 0x7ffb, 0x7ff9, 0x7ff7, + 0x7ff4, 0x7ff2, 0x7fee, 0x7feb, 0x7fe7, 0x7fe3, 0x7fdf, 0x7fda, + 0x7fd6, 0x7fd0, 0x7fcb, 0x7fc5, 0x7fbf, 0x7fb8, 0x7fb1, 0x7faa, + 0x7fa3, 0x7f9b, 0x7f93, 0x7f8b, 0x7f82, 0x7f79, 0x7f70, 0x7f67, + 0x7f5d, 0x7f53, 0x7f48, 0x7f3d, 0x7f32, 0x7f27, 0x7f1b, 0x7f0f, + 0x7f03, 0x7ef6, 0x7ee9, 0x7edc, 0x7ecf, 0x7ec1, 0x7eb3, 0x7ea4, + 0x7e95, 0x7e86, 0x7e77, 0x7e67, 0x7e57, 0x7e47, 0x7e37, 0x7e26, + 0x7e14, 0x7e03, 0x7df1, 0x7ddf, 0x7dcd, 0x7dba, 0x7da7, 0x7d94, + 0x7d80, 0x7d6c, 0x7d58, 0x7d43, 0x7d2f, 0x7d19, 0x7d04, 0x7cee, + 0x7cd8, 0x7cc2, 0x7cab, 0x7c94, 0x7c7d, 0x7c66, 0x7c4e, 0x7c36, + 0x7c1d, 0x7c05, 0x7beb, 0x7bd2, 0x7bb9, 0x7b9f, 0x7b84, 0x7b6a, + 0x7b4f, 0x7b34, 0x7b19, 0x7afd, 0x7ae1, 0x7ac5, 0x7aa8, 0x7a8b, + 0x7a6e, 0x7a50, 0x7a33, 0x7a15, 0x79f6, 0x79d8, 0x79b9, 0x7999, + 0x797a, 0x795a, 0x793a, 0x7919, 0x78f9, 0x78d8, 0x78b6, 0x7895, + 0x7873, 0x7851, 0x782e, 0x780c, 0x77e9, 0x77c5, 0x77a2, 0x777e, + 0x775a, 0x7735, 0x7710, 0x76eb, 0x76c6, 0x76a0, 0x767b, 0x7654, + 0x762e, 0x7607, 0x75e0, 0x75b9, 0x7591, 0x7569, 0x7541, 0x7519, + 0x74f0, 0x74c7, 0x749e, 0x7474, 0x744a, 0x7420, 0x73f6, 0x73cb, + 0x73a0, 0x7375, 0x7349, 0x731d, 0x72f1, 0x72c5, 0x7298, 0x726b, + 0x723e, 0x7211, 0x71e3, 0x71b5, 0x7186, 0x7158, 0x7129, 0x70fa, + 0x70cb, 0x709b, 0x706b, 0x703b, 0x700a, 0x6fda, 0x6fa9, 0x6f77, + 0x6f46, 0x6f14, 0x6ee2, 0x6eaf, 0x6e7d, 0x6e4a, 0x6e17, 0x6de3, + 0x6db0, 0x6d7c, 0x6d48, 0x6d13, 0x6cde, 0x6ca9, 0x6c74, 0x6c3f, + 0x6c09, 0x6bd3, 0x6b9c, 0x6b66, 0x6b2f, 0x6af8, 0x6ac1, 0x6a89, + 0x6a51, 0x6a19, 0x69e1, 0x69a8, 0x696f, 0x6936, 0x68fd, 0x68c3, + 0x6889, 0x684f, 0x6815, 0x67da, 0x679f, 0x6764, 0x6729, 0x66ed, + 0x66b1, 0x6675, 0x6639, 0x65fc, 0x65bf, 0x6582, 0x6545, 0x6507, + 0x64c9, 0x648b, 0x644d, 0x640e, 0x63cf, 0x6390, 0x6351, 0x6311, + 0x62d2, 0x6292, 0x6251, 0x6211, 0x61d0, 0x618f, 0x614e, 0x610d, + 0x60cb, 0x6089, 0x6047, 0x6004, 0x5fc2, 0x5f7f, 0x5f3c, 0x5ef9, + 0x5eb5, 0x5e71, 0x5e2d, 0x5de9, 0x5da5, 0x5d60, 0x5d1b, 0x5cd6, + 0x5c91, 0x5c4b, 0x5c06, 0x5bc0, 0x5b79, 0x5b33, 0x5aec, 0x5aa5, + 0x5a5e, 0x5a17, 0x59d0, 0x5988, 0x5940, 0x58f8, 0x58af, 0x5867, + 0x581e, 0x57d5, 0x578c, 0x5742, 0x56f9, 0x56af, 0x5665, 0x561a, + 0x55d0, 0x5585, 0x553a, 0x54ef, 0x54a4, 0x5458, 0x540d, 0x53c1, + 0x5375, 0x5328, 0x52dc, 0x528f, 0x5242, 0x51f5, 0x51a8, 0x515a, + 0x510c, 0x50bf, 0x5070, 0x5022, 0x4fd4, 0x4f85, 0x4f36, 0x4ee7, + 0x4e98, 0x4e48, 0x4df9, 0x4da9, 0x4d59, 0x4d09, 0x4cb8, 0x4c68, + 0x4c17, 0x4bc6, 0x4b75, 0x4b24, 0x4ad2, 0x4a81, 0x4a2f, 0x49dd, + 0x498a, 0x4938, 0x48e6, 0x4893, 0x4840, 0x47ed, 0x479a, 0x4746, + 0x46f3, 0x469f, 0x464b, 0x45f7, 0x45a3, 0x454e, 0x44fa, 0x44a5, + 0x4450, 0x43fb, 0x43a5, 0x4350, 0x42fa, 0x42a5, 0x424f, 0x41f9, + 0x41a2, 0x414c, 0x40f6, 0x409f, 0x4048, 0x3ff1, 0x3f9a, 0x3f43, + 0x3eeb, 0x3e93, 0x3e3c, 0x3de4, 0x3d8c, 0x3d33, 0x3cdb, 0x3c83, + 0x3c2a, 0x3bd1, 0x3b78, 0x3b1f, 0x3ac6, 0x3a6c, 0x3a13, 0x39b9, + 0x395f, 0x3906, 0x38ab, 0x3851, 0x37f7, 0x379c, 0x3742, 0x36e7, + 0x368c, 0x3631, 0x35d6, 0x357b, 0x351f, 0x34c4, 0x3468, 0x340c, + 0x33b0, 0x3354, 0x32f8, 0x329c, 0x3240, 0x31e3, 0x3186, 0x312a, + 0x30cd, 0x3070, 0x3013, 0x2fb5, 0x2f58, 0x2efb, 0x2e9d, 0x2e3f, + 0x2de2, 0x2d84, 0x2d26, 0x2cc8, 0x2c69, 0x2c0b, 0x2bad, 0x2b4e, + 0x2aef, 0x2a91, 0x2a32, 0x29d3, 0x2974, 0x2915, 0x28b5, 0x2856, + 0x27f6, 0x2797, 0x2737, 0x26d8, 0x2678, 0x2618, 0x25b8, 0x2558, + 0x24f7, 0x2497, 0x2437, 0x23d6, 0x2376, 0x2315, 0x22b4, 0x2254, + 0x21f3, 0x2192, 0x2131, 0x20d0, 0x206e, 0x200d, 0x1fac, 0x1f4a, + 0x1ee9, 0x1e87, 0x1e25, 0x1dc4, 0x1d62, 0x1d00, 0x1c9e, 0x1c3c, + 0x1bda, 0x1b78, 0x1b16, 0x1ab3, 0x1a51, 0x19ef, 0x198c, 0x192a, + 0x18c7, 0x1864, 0x1802, 0x179f, 0x173c, 0x16d9, 0x1676, 0x1613, + 0x15b0, 0x154d, 0x14ea, 0x1487, 0x1423, 0x13c0, 0x135d, 0x12f9, + 0x1296, 0x1232, 0x11cf, 0x116b, 0x1108, 0x10a4, 0x1040, 0xfdd, + 0xf79, 0xf15, 0xeb1, 0xe4d, 0xde9, 0xd85, 0xd21, 0xcbd, + 0xc59, 0xbf5, 0xb91, 0xb2d, 0xac9, 0xa65, 0xa00, 0x99c, + 0x938, 0x8d4, 0x86f, 0x80b, 0x7a7, 0x742, 0x6de, 0x67a, + 0x615, 0x5b1, 0x54c, 0x4e8, 0x483, 0x41f, 0x3ba, 0x356, + 0x2f1, 0x28d, 0x228, 0x1c4, 0x15f, 0xfb, 0x96, 0x32, +}; + +static const q15_t cos_factorsQ15_2048[2048] = { + 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, + 0x7fff, 0x7fff, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffd, 0x7ffd, + 0x7ffd, 0x7ffd, 0x7ffc, 0x7ffc, 0x7ffb, 0x7ffb, 0x7ffb, 0x7ffa, + 0x7ffa, 0x7ff9, 0x7ff9, 0x7ff8, 0x7ff8, 0x7ff7, 0x7ff7, 0x7ff6, + 0x7ff5, 0x7ff5, 0x7ff4, 0x7ff3, 0x7ff3, 0x7ff2, 0x7ff1, 0x7ff0, + 0x7ff0, 0x7fef, 0x7fee, 0x7fed, 0x7fec, 0x7fec, 0x7feb, 0x7fea, + 0x7fe9, 0x7fe8, 0x7fe7, 0x7fe6, 0x7fe5, 0x7fe4, 0x7fe3, 0x7fe2, + 0x7fe1, 0x7fe0, 0x7fdf, 0x7fdd, 0x7fdc, 0x7fdb, 0x7fda, 0x7fd9, + 0x7fd7, 0x7fd6, 0x7fd5, 0x7fd4, 0x7fd2, 0x7fd1, 0x7fd0, 0x7fce, + 0x7fcd, 0x7fcb, 0x7fca, 0x7fc9, 0x7fc7, 0x7fc6, 0x7fc4, 0x7fc3, + 0x7fc1, 0x7fc0, 0x7fbe, 0x7fbc, 0x7fbb, 0x7fb9, 0x7fb7, 0x7fb6, + 0x7fb4, 0x7fb2, 0x7fb1, 0x7faf, 0x7fad, 0x7fab, 0x7fa9, 0x7fa8, + 0x7fa6, 0x7fa4, 0x7fa2, 0x7fa0, 0x7f9e, 0x7f9c, 0x7f9a, 0x7f98, + 0x7f96, 0x7f94, 0x7f92, 0x7f90, 0x7f8e, 0x7f8c, 0x7f8a, 0x7f88, + 0x7f86, 0x7f83, 0x7f81, 0x7f7f, 0x7f7d, 0x7f7b, 0x7f78, 0x7f76, + 0x7f74, 0x7f71, 0x7f6f, 0x7f6d, 0x7f6a, 0x7f68, 0x7f65, 0x7f63, + 0x7f60, 0x7f5e, 0x7f5b, 0x7f59, 0x7f56, 0x7f54, 0x7f51, 0x7f4f, + 0x7f4c, 0x7f49, 0x7f47, 0x7f44, 0x7f41, 0x7f3f, 0x7f3c, 0x7f39, + 0x7f36, 0x7f34, 0x7f31, 0x7f2e, 0x7f2b, 0x7f28, 0x7f25, 0x7f23, + 0x7f20, 0x7f1d, 0x7f1a, 0x7f17, 0x7f14, 0x7f11, 0x7f0e, 0x7f0b, + 0x7f08, 0x7f04, 0x7f01, 0x7efe, 0x7efb, 0x7ef8, 0x7ef5, 0x7ef1, + 0x7eee, 0x7eeb, 0x7ee8, 0x7ee4, 0x7ee1, 0x7ede, 0x7eda, 0x7ed7, + 0x7ed4, 0x7ed0, 0x7ecd, 0x7ec9, 0x7ec6, 0x7ec3, 0x7ebf, 0x7ebb, + 0x7eb8, 0x7eb4, 0x7eb1, 0x7ead, 0x7eaa, 0x7ea6, 0x7ea2, 0x7e9f, + 0x7e9b, 0x7e97, 0x7e94, 0x7e90, 0x7e8c, 0x7e88, 0x7e84, 0x7e81, + 0x7e7d, 0x7e79, 0x7e75, 0x7e71, 0x7e6d, 0x7e69, 0x7e65, 0x7e61, + 0x7e5d, 0x7e59, 0x7e55, 0x7e51, 0x7e4d, 0x7e49, 0x7e45, 0x7e41, + 0x7e3d, 0x7e39, 0x7e34, 0x7e30, 0x7e2c, 0x7e28, 0x7e24, 0x7e1f, + 0x7e1b, 0x7e17, 0x7e12, 0x7e0e, 0x7e0a, 0x7e05, 0x7e01, 0x7dfc, + 0x7df8, 0x7df3, 0x7def, 0x7dea, 0x7de6, 0x7de1, 0x7ddd, 0x7dd8, + 0x7dd4, 0x7dcf, 0x7dca, 0x7dc6, 0x7dc1, 0x7dbc, 0x7db8, 0x7db3, + 0x7dae, 0x7da9, 0x7da5, 0x7da0, 0x7d9b, 0x7d96, 0x7d91, 0x7d8c, + 0x7d87, 0x7d82, 0x7d7e, 0x7d79, 0x7d74, 0x7d6f, 0x7d6a, 0x7d65, + 0x7d60, 0x7d5a, 0x7d55, 0x7d50, 0x7d4b, 0x7d46, 0x7d41, 0x7d3c, + 0x7d36, 0x7d31, 0x7d2c, 0x7d27, 0x7d21, 0x7d1c, 0x7d17, 0x7d11, + 0x7d0c, 0x7d07, 0x7d01, 0x7cfc, 0x7cf6, 0x7cf1, 0x7cec, 0x7ce6, + 0x7ce1, 0x7cdb, 0x7cd5, 0x7cd0, 0x7cca, 0x7cc5, 0x7cbf, 0x7cb9, + 0x7cb4, 0x7cae, 0x7ca8, 0x7ca3, 0x7c9d, 0x7c97, 0x7c91, 0x7c8c, + 0x7c86, 0x7c80, 0x7c7a, 0x7c74, 0x7c6e, 0x7c69, 0x7c63, 0x7c5d, + 0x7c57, 0x7c51, 0x7c4b, 0x7c45, 0x7c3f, 0x7c39, 0x7c33, 0x7c2d, + 0x7c26, 0x7c20, 0x7c1a, 0x7c14, 0x7c0e, 0x7c08, 0x7c01, 0x7bfb, + 0x7bf5, 0x7bef, 0x7be8, 0x7be2, 0x7bdc, 0x7bd5, 0x7bcf, 0x7bc9, + 0x7bc2, 0x7bbc, 0x7bb5, 0x7baf, 0x7ba8, 0x7ba2, 0x7b9b, 0x7b95, + 0x7b8e, 0x7b88, 0x7b81, 0x7b7a, 0x7b74, 0x7b6d, 0x7b67, 0x7b60, + 0x7b59, 0x7b52, 0x7b4c, 0x7b45, 0x7b3e, 0x7b37, 0x7b31, 0x7b2a, + 0x7b23, 0x7b1c, 0x7b15, 0x7b0e, 0x7b07, 0x7b00, 0x7af9, 0x7af2, + 0x7aeb, 0x7ae4, 0x7add, 0x7ad6, 0x7acf, 0x7ac8, 0x7ac1, 0x7aba, + 0x7ab3, 0x7aac, 0x7aa4, 0x7a9d, 0x7a96, 0x7a8f, 0x7a87, 0x7a80, + 0x7a79, 0x7a72, 0x7a6a, 0x7a63, 0x7a5c, 0x7a54, 0x7a4d, 0x7a45, + 0x7a3e, 0x7a36, 0x7a2f, 0x7a27, 0x7a20, 0x7a18, 0x7a11, 0x7a09, + 0x7a02, 0x79fa, 0x79f2, 0x79eb, 0x79e3, 0x79db, 0x79d4, 0x79cc, + 0x79c4, 0x79bc, 0x79b5, 0x79ad, 0x79a5, 0x799d, 0x7995, 0x798e, + 0x7986, 0x797e, 0x7976, 0x796e, 0x7966, 0x795e, 0x7956, 0x794e, + 0x7946, 0x793e, 0x7936, 0x792e, 0x7926, 0x791e, 0x7915, 0x790d, + 0x7905, 0x78fd, 0x78f5, 0x78ec, 0x78e4, 0x78dc, 0x78d4, 0x78cb, + 0x78c3, 0x78bb, 0x78b2, 0x78aa, 0x78a2, 0x7899, 0x7891, 0x7888, + 0x7880, 0x7877, 0x786f, 0x7866, 0x785e, 0x7855, 0x784d, 0x7844, + 0x783b, 0x7833, 0x782a, 0x7821, 0x7819, 0x7810, 0x7807, 0x77ff, + 0x77f6, 0x77ed, 0x77e4, 0x77db, 0x77d3, 0x77ca, 0x77c1, 0x77b8, + 0x77af, 0x77a6, 0x779d, 0x7794, 0x778b, 0x7782, 0x7779, 0x7770, + 0x7767, 0x775e, 0x7755, 0x774c, 0x7743, 0x773a, 0x7731, 0x7727, + 0x771e, 0x7715, 0x770c, 0x7703, 0x76f9, 0x76f0, 0x76e7, 0x76dd, + 0x76d4, 0x76cb, 0x76c1, 0x76b8, 0x76af, 0x76a5, 0x769c, 0x7692, + 0x7689, 0x767f, 0x7676, 0x766c, 0x7663, 0x7659, 0x7650, 0x7646, + 0x763c, 0x7633, 0x7629, 0x761f, 0x7616, 0x760c, 0x7602, 0x75f9, + 0x75ef, 0x75e5, 0x75db, 0x75d1, 0x75c8, 0x75be, 0x75b4, 0x75aa, + 0x75a0, 0x7596, 0x758c, 0x7582, 0x7578, 0x756e, 0x7564, 0x755a, + 0x7550, 0x7546, 0x753c, 0x7532, 0x7528, 0x751e, 0x7514, 0x7509, + 0x74ff, 0x74f5, 0x74eb, 0x74e1, 0x74d6, 0x74cc, 0x74c2, 0x74b7, + 0x74ad, 0x74a3, 0x7498, 0x748e, 0x7484, 0x7479, 0x746f, 0x7464, + 0x745a, 0x744f, 0x7445, 0x743a, 0x7430, 0x7425, 0x741b, 0x7410, + 0x7406, 0x73fb, 0x73f0, 0x73e6, 0x73db, 0x73d0, 0x73c6, 0x73bb, + 0x73b0, 0x73a5, 0x739b, 0x7390, 0x7385, 0x737a, 0x736f, 0x7364, + 0x7359, 0x734f, 0x7344, 0x7339, 0x732e, 0x7323, 0x7318, 0x730d, + 0x7302, 0x72f7, 0x72ec, 0x72e1, 0x72d5, 0x72ca, 0x72bf, 0x72b4, + 0x72a9, 0x729e, 0x7293, 0x7287, 0x727c, 0x7271, 0x7266, 0x725a, + 0x724f, 0x7244, 0x7238, 0x722d, 0x7222, 0x7216, 0x720b, 0x71ff, + 0x71f4, 0x71e9, 0x71dd, 0x71d2, 0x71c6, 0x71bb, 0x71af, 0x71a3, + 0x7198, 0x718c, 0x7181, 0x7175, 0x7169, 0x715e, 0x7152, 0x7146, + 0x713b, 0x712f, 0x7123, 0x7117, 0x710c, 0x7100, 0x70f4, 0x70e8, + 0x70dc, 0x70d1, 0x70c5, 0x70b9, 0x70ad, 0x70a1, 0x7095, 0x7089, + 0x707d, 0x7071, 0x7065, 0x7059, 0x704d, 0x7041, 0x7035, 0x7029, + 0x701d, 0x7010, 0x7004, 0x6ff8, 0x6fec, 0x6fe0, 0x6fd3, 0x6fc7, + 0x6fbb, 0x6faf, 0x6fa2, 0x6f96, 0x6f8a, 0x6f7d, 0x6f71, 0x6f65, + 0x6f58, 0x6f4c, 0x6f3f, 0x6f33, 0x6f27, 0x6f1a, 0x6f0e, 0x6f01, + 0x6ef5, 0x6ee8, 0x6edc, 0x6ecf, 0x6ec2, 0x6eb6, 0x6ea9, 0x6e9c, + 0x6e90, 0x6e83, 0x6e76, 0x6e6a, 0x6e5d, 0x6e50, 0x6e44, 0x6e37, + 0x6e2a, 0x6e1d, 0x6e10, 0x6e04, 0x6df7, 0x6dea, 0x6ddd, 0x6dd0, + 0x6dc3, 0x6db6, 0x6da9, 0x6d9c, 0x6d8f, 0x6d82, 0x6d75, 0x6d68, + 0x6d5b, 0x6d4e, 0x6d41, 0x6d34, 0x6d27, 0x6d1a, 0x6d0c, 0x6cff, + 0x6cf2, 0x6ce5, 0x6cd8, 0x6cca, 0x6cbd, 0x6cb0, 0x6ca3, 0x6c95, + 0x6c88, 0x6c7b, 0x6c6d, 0x6c60, 0x6c53, 0x6c45, 0x6c38, 0x6c2a, + 0x6c1d, 0x6c0f, 0x6c02, 0x6bf5, 0x6be7, 0x6bd9, 0x6bcc, 0x6bbe, + 0x6bb1, 0x6ba3, 0x6b96, 0x6b88, 0x6b7a, 0x6b6d, 0x6b5f, 0x6b51, + 0x6b44, 0x6b36, 0x6b28, 0x6b1a, 0x6b0d, 0x6aff, 0x6af1, 0x6ae3, + 0x6ad5, 0x6ac8, 0x6aba, 0x6aac, 0x6a9e, 0x6a90, 0x6a82, 0x6a74, + 0x6a66, 0x6a58, 0x6a4a, 0x6a3c, 0x6a2e, 0x6a20, 0x6a12, 0x6a04, + 0x69f6, 0x69e8, 0x69da, 0x69cb, 0x69bd, 0x69af, 0x69a1, 0x6993, + 0x6985, 0x6976, 0x6968, 0x695a, 0x694b, 0x693d, 0x692f, 0x6921, + 0x6912, 0x6904, 0x68f5, 0x68e7, 0x68d9, 0x68ca, 0x68bc, 0x68ad, + 0x689f, 0x6890, 0x6882, 0x6873, 0x6865, 0x6856, 0x6848, 0x6839, + 0x682b, 0x681c, 0x680d, 0x67ff, 0x67f0, 0x67e1, 0x67d3, 0x67c4, + 0x67b5, 0x67a6, 0x6798, 0x6789, 0x677a, 0x676b, 0x675d, 0x674e, + 0x673f, 0x6730, 0x6721, 0x6712, 0x6703, 0x66f4, 0x66e5, 0x66d6, + 0x66c8, 0x66b9, 0x66aa, 0x669b, 0x668b, 0x667c, 0x666d, 0x665e, + 0x664f, 0x6640, 0x6631, 0x6622, 0x6613, 0x6603, 0x65f4, 0x65e5, + 0x65d6, 0x65c7, 0x65b7, 0x65a8, 0x6599, 0x658a, 0x657a, 0x656b, + 0x655c, 0x654c, 0x653d, 0x652d, 0x651e, 0x650f, 0x64ff, 0x64f0, + 0x64e0, 0x64d1, 0x64c1, 0x64b2, 0x64a2, 0x6493, 0x6483, 0x6474, + 0x6464, 0x6454, 0x6445, 0x6435, 0x6426, 0x6416, 0x6406, 0x63f7, + 0x63e7, 0x63d7, 0x63c7, 0x63b8, 0x63a8, 0x6398, 0x6388, 0x6378, + 0x6369, 0x6359, 0x6349, 0x6339, 0x6329, 0x6319, 0x6309, 0x62f9, + 0x62ea, 0x62da, 0x62ca, 0x62ba, 0x62aa, 0x629a, 0x628a, 0x627a, + 0x6269, 0x6259, 0x6249, 0x6239, 0x6229, 0x6219, 0x6209, 0x61f9, + 0x61e8, 0x61d8, 0x61c8, 0x61b8, 0x61a8, 0x6197, 0x6187, 0x6177, + 0x6166, 0x6156, 0x6146, 0x6135, 0x6125, 0x6115, 0x6104, 0x60f4, + 0x60e4, 0x60d3, 0x60c3, 0x60b2, 0x60a2, 0x6091, 0x6081, 0x6070, + 0x6060, 0x604f, 0x603f, 0x602e, 0x601d, 0x600d, 0x5ffc, 0x5fec, + 0x5fdb, 0x5fca, 0x5fba, 0x5fa9, 0x5f98, 0x5f87, 0x5f77, 0x5f66, + 0x5f55, 0x5f44, 0x5f34, 0x5f23, 0x5f12, 0x5f01, 0x5ef0, 0x5edf, + 0x5ecf, 0x5ebe, 0x5ead, 0x5e9c, 0x5e8b, 0x5e7a, 0x5e69, 0x5e58, + 0x5e47, 0x5e36, 0x5e25, 0x5e14, 0x5e03, 0x5df2, 0x5de1, 0x5dd0, + 0x5dbf, 0x5dad, 0x5d9c, 0x5d8b, 0x5d7a, 0x5d69, 0x5d58, 0x5d46, + 0x5d35, 0x5d24, 0x5d13, 0x5d01, 0x5cf0, 0x5cdf, 0x5cce, 0x5cbc, + 0x5cab, 0x5c9a, 0x5c88, 0x5c77, 0x5c66, 0x5c54, 0x5c43, 0x5c31, + 0x5c20, 0x5c0e, 0x5bfd, 0x5beb, 0x5bda, 0x5bc8, 0x5bb7, 0x5ba5, + 0x5b94, 0x5b82, 0x5b71, 0x5b5f, 0x5b4d, 0x5b3c, 0x5b2a, 0x5b19, + 0x5b07, 0x5af5, 0x5ae4, 0x5ad2, 0x5ac0, 0x5aae, 0x5a9d, 0x5a8b, + 0x5a79, 0x5a67, 0x5a56, 0x5a44, 0x5a32, 0x5a20, 0x5a0e, 0x59fc, + 0x59ea, 0x59d9, 0x59c7, 0x59b5, 0x59a3, 0x5991, 0x597f, 0x596d, + 0x595b, 0x5949, 0x5937, 0x5925, 0x5913, 0x5901, 0x58ef, 0x58dd, + 0x58cb, 0x58b8, 0x58a6, 0x5894, 0x5882, 0x5870, 0x585e, 0x584b, + 0x5839, 0x5827, 0x5815, 0x5803, 0x57f0, 0x57de, 0x57cc, 0x57b9, + 0x57a7, 0x5795, 0x5783, 0x5770, 0x575e, 0x574b, 0x5739, 0x5727, + 0x5714, 0x5702, 0x56ef, 0x56dd, 0x56ca, 0x56b8, 0x56a5, 0x5693, + 0x5680, 0x566e, 0x565b, 0x5649, 0x5636, 0x5624, 0x5611, 0x55fe, + 0x55ec, 0x55d9, 0x55c7, 0x55b4, 0x55a1, 0x558f, 0x557c, 0x5569, + 0x5556, 0x5544, 0x5531, 0x551e, 0x550b, 0x54f9, 0x54e6, 0x54d3, + 0x54c0, 0x54ad, 0x549a, 0x5488, 0x5475, 0x5462, 0x544f, 0x543c, + 0x5429, 0x5416, 0x5403, 0x53f0, 0x53dd, 0x53ca, 0x53b7, 0x53a4, + 0x5391, 0x537e, 0x536b, 0x5358, 0x5345, 0x5332, 0x531f, 0x530c, + 0x52f8, 0x52e5, 0x52d2, 0x52bf, 0x52ac, 0x5299, 0x5285, 0x5272, + 0x525f, 0x524c, 0x5238, 0x5225, 0x5212, 0x51ff, 0x51eb, 0x51d8, + 0x51c5, 0x51b1, 0x519e, 0x518b, 0x5177, 0x5164, 0x5150, 0x513d, + 0x512a, 0x5116, 0x5103, 0x50ef, 0x50dc, 0x50c8, 0x50b5, 0x50a1, + 0x508e, 0x507a, 0x5067, 0x5053, 0x503f, 0x502c, 0x5018, 0x5005, + 0x4ff1, 0x4fdd, 0x4fca, 0x4fb6, 0x4fa2, 0x4f8f, 0x4f7b, 0x4f67, + 0x4f54, 0x4f40, 0x4f2c, 0x4f18, 0x4f05, 0x4ef1, 0x4edd, 0x4ec9, + 0x4eb6, 0x4ea2, 0x4e8e, 0x4e7a, 0x4e66, 0x4e52, 0x4e3e, 0x4e2a, + 0x4e17, 0x4e03, 0x4def, 0x4ddb, 0x4dc7, 0x4db3, 0x4d9f, 0x4d8b, + 0x4d77, 0x4d63, 0x4d4f, 0x4d3b, 0x4d27, 0x4d13, 0x4cff, 0x4ceb, + 0x4cd6, 0x4cc2, 0x4cae, 0x4c9a, 0x4c86, 0x4c72, 0x4c5e, 0x4c49, + 0x4c35, 0x4c21, 0x4c0d, 0x4bf9, 0x4be4, 0x4bd0, 0x4bbc, 0x4ba8, + 0x4b93, 0x4b7f, 0x4b6b, 0x4b56, 0x4b42, 0x4b2e, 0x4b19, 0x4b05, + 0x4af1, 0x4adc, 0x4ac8, 0x4ab4, 0x4a9f, 0x4a8b, 0x4a76, 0x4a62, + 0x4a4d, 0x4a39, 0x4a24, 0x4a10, 0x49fb, 0x49e7, 0x49d2, 0x49be, + 0x49a9, 0x4995, 0x4980, 0x496c, 0x4957, 0x4942, 0x492e, 0x4919, + 0x4905, 0x48f0, 0x48db, 0x48c7, 0x48b2, 0x489d, 0x4888, 0x4874, + 0x485f, 0x484a, 0x4836, 0x4821, 0x480c, 0x47f7, 0x47e2, 0x47ce, + 0x47b9, 0x47a4, 0x478f, 0x477a, 0x4765, 0x4751, 0x473c, 0x4727, + 0x4712, 0x46fd, 0x46e8, 0x46d3, 0x46be, 0x46a9, 0x4694, 0x467f, + 0x466a, 0x4655, 0x4640, 0x462b, 0x4616, 0x4601, 0x45ec, 0x45d7, + 0x45c2, 0x45ad, 0x4598, 0x4583, 0x456e, 0x4559, 0x4544, 0x452e, + 0x4519, 0x4504, 0x44ef, 0x44da, 0x44c5, 0x44af, 0x449a, 0x4485, + 0x4470, 0x445a, 0x4445, 0x4430, 0x441b, 0x4405, 0x43f0, 0x43db, + 0x43c5, 0x43b0, 0x439b, 0x4385, 0x4370, 0x435b, 0x4345, 0x4330, + 0x431b, 0x4305, 0x42f0, 0x42da, 0x42c5, 0x42af, 0x429a, 0x4284, + 0x426f, 0x425a, 0x4244, 0x422f, 0x4219, 0x4203, 0x41ee, 0x41d8, + 0x41c3, 0x41ad, 0x4198, 0x4182, 0x416d, 0x4157, 0x4141, 0x412c, + 0x4116, 0x4100, 0x40eb, 0x40d5, 0x40bf, 0x40aa, 0x4094, 0x407e, + 0x4069, 0x4053, 0x403d, 0x4027, 0x4012, 0x3ffc, 0x3fe6, 0x3fd0, + 0x3fbb, 0x3fa5, 0x3f8f, 0x3f79, 0x3f63, 0x3f4d, 0x3f38, 0x3f22, + 0x3f0c, 0x3ef6, 0x3ee0, 0x3eca, 0x3eb4, 0x3e9e, 0x3e88, 0x3e73, + 0x3e5d, 0x3e47, 0x3e31, 0x3e1b, 0x3e05, 0x3def, 0x3dd9, 0x3dc3, + 0x3dad, 0x3d97, 0x3d81, 0x3d6b, 0x3d55, 0x3d3e, 0x3d28, 0x3d12, + 0x3cfc, 0x3ce6, 0x3cd0, 0x3cba, 0x3ca4, 0x3c8e, 0x3c77, 0x3c61, + 0x3c4b, 0x3c35, 0x3c1f, 0x3c09, 0x3bf2, 0x3bdc, 0x3bc6, 0x3bb0, + 0x3b99, 0x3b83, 0x3b6d, 0x3b57, 0x3b40, 0x3b2a, 0x3b14, 0x3afe, + 0x3ae7, 0x3ad1, 0x3abb, 0x3aa4, 0x3a8e, 0x3a78, 0x3a61, 0x3a4b, + 0x3a34, 0x3a1e, 0x3a08, 0x39f1, 0x39db, 0x39c4, 0x39ae, 0x3998, + 0x3981, 0x396b, 0x3954, 0x393e, 0x3927, 0x3911, 0x38fa, 0x38e4, + 0x38cd, 0x38b7, 0x38a0, 0x388a, 0x3873, 0x385d, 0x3846, 0x382f, + 0x3819, 0x3802, 0x37ec, 0x37d5, 0x37be, 0x37a8, 0x3791, 0x377a, + 0x3764, 0x374d, 0x3736, 0x3720, 0x3709, 0x36f2, 0x36dc, 0x36c5, + 0x36ae, 0x3698, 0x3681, 0x366a, 0x3653, 0x363d, 0x3626, 0x360f, + 0x35f8, 0x35e1, 0x35cb, 0x35b4, 0x359d, 0x3586, 0x356f, 0x3558, + 0x3542, 0x352b, 0x3514, 0x34fd, 0x34e6, 0x34cf, 0x34b8, 0x34a1, + 0x348b, 0x3474, 0x345d, 0x3446, 0x342f, 0x3418, 0x3401, 0x33ea, + 0x33d3, 0x33bc, 0x33a5, 0x338e, 0x3377, 0x3360, 0x3349, 0x3332, + 0x331b, 0x3304, 0x32ed, 0x32d6, 0x32bf, 0x32a8, 0x3290, 0x3279, + 0x3262, 0x324b, 0x3234, 0x321d, 0x3206, 0x31ef, 0x31d8, 0x31c0, + 0x31a9, 0x3192, 0x317b, 0x3164, 0x314c, 0x3135, 0x311e, 0x3107, + 0x30f0, 0x30d8, 0x30c1, 0x30aa, 0x3093, 0x307b, 0x3064, 0x304d, + 0x3036, 0x301e, 0x3007, 0x2ff0, 0x2fd8, 0x2fc1, 0x2faa, 0x2f92, + 0x2f7b, 0x2f64, 0x2f4c, 0x2f35, 0x2f1e, 0x2f06, 0x2eef, 0x2ed8, + 0x2ec0, 0x2ea9, 0x2e91, 0x2e7a, 0x2e63, 0x2e4b, 0x2e34, 0x2e1c, + 0x2e05, 0x2ded, 0x2dd6, 0x2dbe, 0x2da7, 0x2d8f, 0x2d78, 0x2d60, + 0x2d49, 0x2d31, 0x2d1a, 0x2d02, 0x2ceb, 0x2cd3, 0x2cbc, 0x2ca4, + 0x2c8d, 0x2c75, 0x2c5e, 0x2c46, 0x2c2e, 0x2c17, 0x2bff, 0x2be8, + 0x2bd0, 0x2bb8, 0x2ba1, 0x2b89, 0x2b71, 0x2b5a, 0x2b42, 0x2b2b, + 0x2b13, 0x2afb, 0x2ae4, 0x2acc, 0x2ab4, 0x2a9c, 0x2a85, 0x2a6d, + 0x2a55, 0x2a3e, 0x2a26, 0x2a0e, 0x29f6, 0x29df, 0x29c7, 0x29af, + 0x2997, 0x2980, 0x2968, 0x2950, 0x2938, 0x2920, 0x2909, 0x28f1, + 0x28d9, 0x28c1, 0x28a9, 0x2892, 0x287a, 0x2862, 0x284a, 0x2832, + 0x281a, 0x2802, 0x27eb, 0x27d3, 0x27bb, 0x27a3, 0x278b, 0x2773, + 0x275b, 0x2743, 0x272b, 0x2713, 0x26fb, 0x26e4, 0x26cc, 0x26b4, + 0x269c, 0x2684, 0x266c, 0x2654, 0x263c, 0x2624, 0x260c, 0x25f4, + 0x25dc, 0x25c4, 0x25ac, 0x2594, 0x257c, 0x2564, 0x254c, 0x2534, + 0x251c, 0x2503, 0x24eb, 0x24d3, 0x24bb, 0x24a3, 0x248b, 0x2473, + 0x245b, 0x2443, 0x242b, 0x2413, 0x23fa, 0x23e2, 0x23ca, 0x23b2, + 0x239a, 0x2382, 0x236a, 0x2352, 0x2339, 0x2321, 0x2309, 0x22f1, + 0x22d9, 0x22c0, 0x22a8, 0x2290, 0x2278, 0x2260, 0x2247, 0x222f, + 0x2217, 0x21ff, 0x21e7, 0x21ce, 0x21b6, 0x219e, 0x2186, 0x216d, + 0x2155, 0x213d, 0x2125, 0x210c, 0x20f4, 0x20dc, 0x20c3, 0x20ab, + 0x2093, 0x207a, 0x2062, 0x204a, 0x2032, 0x2019, 0x2001, 0x1fe9, + 0x1fd0, 0x1fb8, 0x1f9f, 0x1f87, 0x1f6f, 0x1f56, 0x1f3e, 0x1f26, + 0x1f0d, 0x1ef5, 0x1edd, 0x1ec4, 0x1eac, 0x1e93, 0x1e7b, 0x1e62, + 0x1e4a, 0x1e32, 0x1e19, 0x1e01, 0x1de8, 0x1dd0, 0x1db7, 0x1d9f, + 0x1d87, 0x1d6e, 0x1d56, 0x1d3d, 0x1d25, 0x1d0c, 0x1cf4, 0x1cdb, + 0x1cc3, 0x1caa, 0x1c92, 0x1c79, 0x1c61, 0x1c48, 0x1c30, 0x1c17, + 0x1bff, 0x1be6, 0x1bce, 0x1bb5, 0x1b9d, 0x1b84, 0x1b6c, 0x1b53, + 0x1b3a, 0x1b22, 0x1b09, 0x1af1, 0x1ad8, 0x1ac0, 0x1aa7, 0x1a8e, + 0x1a76, 0x1a5d, 0x1a45, 0x1a2c, 0x1a13, 0x19fb, 0x19e2, 0x19ca, + 0x19b1, 0x1998, 0x1980, 0x1967, 0x194e, 0x1936, 0x191d, 0x1905, + 0x18ec, 0x18d3, 0x18bb, 0x18a2, 0x1889, 0x1871, 0x1858, 0x183f, + 0x1827, 0x180e, 0x17f5, 0x17dd, 0x17c4, 0x17ab, 0x1792, 0x177a, + 0x1761, 0x1748, 0x1730, 0x1717, 0x16fe, 0x16e5, 0x16cd, 0x16b4, + 0x169b, 0x1682, 0x166a, 0x1651, 0x1638, 0x161f, 0x1607, 0x15ee, + 0x15d5, 0x15bc, 0x15a4, 0x158b, 0x1572, 0x1559, 0x1541, 0x1528, + 0x150f, 0x14f6, 0x14dd, 0x14c5, 0x14ac, 0x1493, 0x147a, 0x1461, + 0x1449, 0x1430, 0x1417, 0x13fe, 0x13e5, 0x13cc, 0x13b4, 0x139b, + 0x1382, 0x1369, 0x1350, 0x1337, 0x131f, 0x1306, 0x12ed, 0x12d4, + 0x12bb, 0x12a2, 0x1289, 0x1271, 0x1258, 0x123f, 0x1226, 0x120d, + 0x11f4, 0x11db, 0x11c2, 0x11a9, 0x1191, 0x1178, 0x115f, 0x1146, + 0x112d, 0x1114, 0x10fb, 0x10e2, 0x10c9, 0x10b0, 0x1098, 0x107f, + 0x1066, 0x104d, 0x1034, 0x101b, 0x1002, 0xfe9, 0xfd0, 0xfb7, + 0xf9e, 0xf85, 0xf6c, 0xf53, 0xf3a, 0xf21, 0xf08, 0xef0, + 0xed7, 0xebe, 0xea5, 0xe8c, 0xe73, 0xe5a, 0xe41, 0xe28, + 0xe0f, 0xdf6, 0xddd, 0xdc4, 0xdab, 0xd92, 0xd79, 0xd60, + 0xd47, 0xd2e, 0xd15, 0xcfc, 0xce3, 0xcca, 0xcb1, 0xc98, + 0xc7f, 0xc66, 0xc4d, 0xc34, 0xc1b, 0xc02, 0xbe9, 0xbd0, + 0xbb7, 0xb9e, 0xb85, 0xb6c, 0xb53, 0xb3a, 0xb20, 0xb07, + 0xaee, 0xad5, 0xabc, 0xaa3, 0xa8a, 0xa71, 0xa58, 0xa3f, + 0xa26, 0xa0d, 0x9f4, 0x9db, 0x9c2, 0x9a9, 0x990, 0x977, + 0x95e, 0x944, 0x92b, 0x912, 0x8f9, 0x8e0, 0x8c7, 0x8ae, + 0x895, 0x87c, 0x863, 0x84a, 0x831, 0x818, 0x7fe, 0x7e5, + 0x7cc, 0x7b3, 0x79a, 0x781, 0x768, 0x74f, 0x736, 0x71d, + 0x704, 0x6ea, 0x6d1, 0x6b8, 0x69f, 0x686, 0x66d, 0x654, + 0x63b, 0x622, 0x609, 0x5ef, 0x5d6, 0x5bd, 0x5a4, 0x58b, + 0x572, 0x559, 0x540, 0x527, 0x50d, 0x4f4, 0x4db, 0x4c2, + 0x4a9, 0x490, 0x477, 0x45e, 0x445, 0x42b, 0x412, 0x3f9, + 0x3e0, 0x3c7, 0x3ae, 0x395, 0x37c, 0x362, 0x349, 0x330, + 0x317, 0x2fe, 0x2e5, 0x2cc, 0x2b3, 0x299, 0x280, 0x267, + 0x24e, 0x235, 0x21c, 0x203, 0x1ea, 0x1d0, 0x1b7, 0x19e, + 0x185, 0x16c, 0x153, 0x13a, 0x121, 0x107, 0xee, 0xd5, + 0xbc, 0xa3, 0x8a, 0x71, 0x57, 0x3e, 0x25, 0xc, + +}; + +/** + * @brief Initialization function for the Q15 DCT4/IDCT4. + * @param[in,out] *S points to an instance of Q15 DCT4/IDCT4 structure. + * @param[in] *S_RFFT points to an instance of Q15 RFFT/RIFFT structure. + * @param[in] *S_CFFT points to an instance of Q15 CFFT/CIFFT structure. + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. + * \par Normalizing factor: + * The normalizing factor is sqrt(2/N), which depends on the size of transform N. + * Normalizing factors in 1.15 format are mentioned in the table below for different DCT sizes: + * \image html dct4NormalizingQ15Table.gif + */ + +arm_status arm_dct4_init_q15( + arm_dct4_instance_q15 * S, + arm_rfft_instance_q15 * S_RFFT, + arm_cfft_radix4_instance_q15 * S_CFFT, + uint16_t N, + uint16_t Nby2, + q15_t normalize) +{ + /* Initialise the default arm status */ + arm_status status = ARM_MATH_SUCCESS; + + /* Initializing the pointer array with the weight table base addresses of different lengths */ + q15_t *twiddlePtr[3] = { (q15_t *) WeightsQ15_128, (q15_t *) WeightsQ15_512, + (q15_t *) WeightsQ15_2048 + }; + + /* Initializing the pointer array with the cos factor table base addresses of different lengths */ + q15_t *pCosFactor[3] = + { (q15_t *) cos_factorsQ15_128, (q15_t *) cos_factorsQ15_512, + (q15_t *) cos_factorsQ15_2048 + }; + + /* Initialize the DCT4 length */ + S->N = N; + + /* Initialize the half of DCT4 length */ + S->Nby2 = Nby2; + + /* Initialize the DCT4 Normalizing factor */ + S->normalize = normalize; + + /* Initialize Real FFT Instance */ + S->pRfft = S_RFFT; + + /* Initialize Complex FFT Instance */ + S->pCfft = S_CFFT; + + switch (N) + { + /* Initialize the table modifier values */ + case 2048u: + S->pTwiddle = twiddlePtr[2]; + S->pCosFactor = pCosFactor[2]; + break; + case 512u: + S->pTwiddle = twiddlePtr[1]; + S->pCosFactor = pCosFactor[1]; + break; + case 128u: + S->pTwiddle = twiddlePtr[0]; + S->pCosFactor = pCosFactor[0]; + break; + default: + status = ARM_MATH_ARGUMENT_ERROR; + } + + /* Initialize the RFFT/RIFFT */ + arm_rfft_init_q15(S->pRfft, S->pCfft, S->N, 0u, 1u); + + /* return the status of DCT4 Init function */ + return (status); +} + +/** + * @} end of DCT4_IDCT4 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q31.c index 78bce4ac6..62ac374ab 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q31.c @@ -1,2198 +1,2198 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_init_q31.c -* -* Description: Initialization function of DCT-4 & IDCT4 Q31 -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/* -* @brief Weights Table -*/ - -/** -* \par -* Weights tables are generated using the formula :
weights[n] = e^(-j*n*pi/(2*N))
-* \par -* C command to generate the table -*
   
-* for(i = 0; i< N; i++)   
-* {   
-*   weights[2*i]= cos(i*c);   
-*   weights[(2*i)+1]= -sin(i * c);   
-* } 
-* \par -* where N is the Number of weights to be calculated and c is pi/(2*N) -* \par -* Convert the output to q31 format by multiplying with 2^31 and saturated if required. -* \par -* In the tables below the real and imaginary values are placed alternatively, hence the -* array length is 2*N. -*/ - -static const q31_t WeightsQ31_128[256] = { - 0x7fffffff, 0x0, 0x7ffd885a, 0xfe6de2e0, 0x7ff62182, 0xfcdbd541, 0x7fe9cbc0, - 0xfb49e6a3, - 0x7fd8878e, 0xf9b82684, 0x7fc25596, 0xf826a462, 0x7fa736b4, 0xf6956fb7, - 0x7f872bf3, 0xf50497fb, - 0x7f62368f, 0xf3742ca2, 0x7f3857f6, 0xf1e43d1c, 0x7f0991c4, 0xf054d8d5, - 0x7ed5e5c6, 0xeec60f31, - 0x7e9d55fc, 0xed37ef91, 0x7e5fe493, 0xebaa894f, 0x7e1d93ea, 0xea1debbb, - 0x7dd6668f, 0xe8922622, - 0x7d8a5f40, 0xe70747c4, 0x7d3980ec, 0xe57d5fda, 0x7ce3ceb2, 0xe3f47d96, - 0x7c894bde, 0xe26cb01b, - 0x7c29fbee, 0xe0e60685, 0x7bc5e290, 0xdf608fe4, 0x7b5d039e, 0xdddc5b3b, - 0x7aef6323, 0xdc597781, - 0x7a7d055b, 0xdad7f3a2, 0x7a05eead, 0xd957de7a, 0x798a23b1, 0xd7d946d8, - 0x7909a92d, 0xd65c3b7b, - 0x78848414, 0xd4e0cb15, 0x77fab989, 0xd3670446, 0x776c4edb, 0xd1eef59e, - 0x76d94989, 0xd078ad9e, - 0x7641af3d, 0xcf043ab3, 0x75a585cf, 0xcd91ab39, 0x7504d345, 0xcc210d79, - 0x745f9dd1, 0xcab26fa9, - 0x73b5ebd1, 0xc945dfec, 0x7307c3d0, 0xc7db6c50, 0x72552c85, 0xc67322ce, - 0x719e2cd2, 0xc50d1149, - 0x70e2cbc6, 0xc3a94590, 0x7023109a, 0xc247cd5a, 0x6f5f02b2, 0xc0e8b648, - 0x6e96a99d, 0xbf8c0de3, - 0x6dca0d14, 0xbe31e19b, 0x6cf934fc, 0xbcda3ecb, 0x6c242960, 0xbb8532b0, - 0x6b4af279, 0xba32ca71, - 0x6a6d98a4, 0xb8e31319, 0x698c246c, 0xb796199b, 0x68a69e81, 0xb64beacd, - 0x67bd0fbd, 0xb5049368, - 0x66cf8120, 0xb3c0200c, 0x65ddfbd3, 0xb27e9d3c, 0x64e88926, 0xb140175b, - 0x63ef3290, 0xb0049ab3, - 0x62f201ac, 0xaecc336c, 0x61f1003f, 0xad96ed92, 0x60ec3830, 0xac64d510, - 0x5fe3b38d, 0xab35f5b5, - 0x5ed77c8a, 0xaa0a5b2e, 0x5dc79d7c, 0xa8e21106, 0x5cb420e0, 0xa7bd22ac, - 0x5b9d1154, 0xa69b9b68, - 0x5a82799a, 0xa57d8666, 0x59646498, 0xa462eeac, 0x5842dd54, 0xa34bdf20, - 0x571deefa, 0xa2386284, - 0x55f5a4d2, 0xa1288376, 0x54ca0a4b, 0xa01c4c73, 0x539b2af0, 0x9f13c7d0, - 0x5269126e, 0x9e0effc1, - 0x5133cc94, 0x9d0dfe54, 0x4ffb654d, 0x9c10cd70, 0x4ebfe8a5, 0x9b1776da, - 0x4d8162c4, 0x9a22042d, - 0x4c3fdff4, 0x99307ee0, 0x4afb6c98, 0x9842f043, 0x49b41533, 0x9759617f, - 0x4869e665, 0x9673db94, - 0x471cece7, 0x9592675c, 0x45cd358f, 0x94b50d87, 0x447acd50, 0x93dbd6a0, - 0x4325c135, 0x9306cb04, - 0x41ce1e65, 0x9235f2ec, 0x4073f21d, 0x91695663, 0x3f1749b8, 0x90a0fd4e, - 0x3db832a6, 0x8fdcef66, - 0x3c56ba70, 0x8f1d343a, 0x3af2eeb7, 0x8e61d32e, 0x398cdd32, 0x8daad37b, - 0x382493b0, 0x8cf83c30, - 0x36ba2014, 0x8c4a142f, 0x354d9057, 0x8ba0622f, 0x33def287, 0x8afb2cbb, - 0x326e54c7, 0x8a5a7a31, - 0x30fbc54d, 0x89be50c3, 0x2f875262, 0x8926b677, 0x2e110a62, 0x8893b125, - 0x2c98fbba, 0x88054677, - 0x2b1f34eb, 0x877b7bec, 0x29a3c485, 0x86f656d3, 0x2826b928, 0x8675dc4f, - 0x26a82186, 0x85fa1153, - 0x25280c5e, 0x8582faa5, 0x23a6887f, 0x85109cdd, 0x2223a4c5, 0x84a2fc62, - 0x209f701c, 0x843a1d70, - 0x1f19f97b, 0x83d60412, 0x1d934fe5, 0x8376b422, 0x1c0b826a, 0x831c314e, - 0x1a82a026, 0x82c67f14, - 0x18f8b83c, 0x8275a0c0, 0x176dd9de, 0x82299971, 0x15e21445, 0x81e26c16, - 0x145576b1, 0x81a01b6d, - 0x12c8106f, 0x8162aa04, 0x1139f0cf, 0x812a1a3a, 0xfab272b, 0x80f66e3c, - 0xe1bc2e4, 0x80c7a80a, - 0xc8bd35e, 0x809dc971, 0xafb6805, 0x8078d40d, 0x96a9049, 0x8058c94c, - 0x7d95b9e, 0x803daa6a, - 0x647d97c, 0x80277872, 0x4b6195d, 0x80163440, 0x3242abf, 0x8009de7e, - 0x1921d20, 0x800277a6, -}; - -static const q31_t WeightsQ31_512[1024] = { - 0x7fffffff, 0x0, 0x7fffd886, 0xff9b781d, 0x7fff6216, 0xff36f078, 0x7ffe9cb2, - 0xfed2694f, - 0x7ffd885a, 0xfe6de2e0, 0x7ffc250f, 0xfe095d69, 0x7ffa72d1, 0xfda4d929, - 0x7ff871a2, 0xfd40565c, - 0x7ff62182, 0xfcdbd541, 0x7ff38274, 0xfc775616, 0x7ff09478, 0xfc12d91a, - 0x7fed5791, 0xfbae5e89, - 0x7fe9cbc0, 0xfb49e6a3, 0x7fe5f108, 0xfae571a4, 0x7fe1c76b, 0xfa80ffcb, - 0x7fdd4eec, 0xfa1c9157, - 0x7fd8878e, 0xf9b82684, 0x7fd37153, 0xf953bf91, 0x7fce0c3e, 0xf8ef5cbb, - 0x7fc85854, 0xf88afe42, - 0x7fc25596, 0xf826a462, 0x7fbc040a, 0xf7c24f59, 0x7fb563b3, 0xf75dff66, - 0x7fae7495, 0xf6f9b4c6, - 0x7fa736b4, 0xf6956fb7, 0x7f9faa15, 0xf6313077, 0x7f97cebd, 0xf5ccf743, - 0x7f8fa4b0, 0xf568c45b, - 0x7f872bf3, 0xf50497fb, 0x7f7e648c, 0xf4a07261, 0x7f754e80, 0xf43c53cb, - 0x7f6be9d4, 0xf3d83c77, - 0x7f62368f, 0xf3742ca2, 0x7f5834b7, 0xf310248a, 0x7f4de451, 0xf2ac246e, - 0x7f434563, 0xf2482c8a, - 0x7f3857f6, 0xf1e43d1c, 0x7f2d1c0e, 0xf1805662, 0x7f2191b4, 0xf11c789a, - 0x7f15b8ee, 0xf0b8a401, - 0x7f0991c4, 0xf054d8d5, 0x7efd1c3c, 0xeff11753, 0x7ef05860, 0xef8d5fb8, - 0x7ee34636, 0xef29b243, - 0x7ed5e5c6, 0xeec60f31, 0x7ec8371a, 0xee6276bf, 0x7eba3a39, 0xedfee92b, - 0x7eabef2c, 0xed9b66b2, - 0x7e9d55fc, 0xed37ef91, 0x7e8e6eb2, 0xecd48407, 0x7e7f3957, 0xec71244f, - 0x7e6fb5f4, 0xec0dd0a8, - 0x7e5fe493, 0xebaa894f, 0x7e4fc53e, 0xeb474e81, 0x7e3f57ff, 0xeae4207a, - 0x7e2e9cdf, 0xea80ff7a, - 0x7e1d93ea, 0xea1debbb, 0x7e0c3d29, 0xe9bae57d, 0x7dfa98a8, 0xe957ecfb, - 0x7de8a670, 0xe8f50273, - 0x7dd6668f, 0xe8922622, 0x7dc3d90d, 0xe82f5844, 0x7db0fdf8, 0xe7cc9917, - 0x7d9dd55a, 0xe769e8d8, - 0x7d8a5f40, 0xe70747c4, 0x7d769bb5, 0xe6a4b616, 0x7d628ac6, 0xe642340d, - 0x7d4e2c7f, 0xe5dfc1e5, - 0x7d3980ec, 0xe57d5fda, 0x7d24881b, 0xe51b0e2a, 0x7d0f4218, 0xe4b8cd11, - 0x7cf9aef0, 0xe4569ccb, - 0x7ce3ceb2, 0xe3f47d96, 0x7ccda169, 0xe3926fad, 0x7cb72724, 0xe330734d, - 0x7ca05ff1, 0xe2ce88b3, - 0x7c894bde, 0xe26cb01b, 0x7c71eaf9, 0xe20ae9c1, 0x7c5a3d50, 0xe1a935e2, - 0x7c4242f2, 0xe14794ba, - 0x7c29fbee, 0xe0e60685, 0x7c116853, 0xe0848b7f, 0x7bf88830, 0xe02323e5, - 0x7bdf5b94, 0xdfc1cff3, - 0x7bc5e290, 0xdf608fe4, 0x7bac1d31, 0xdeff63f4, 0x7b920b89, 0xde9e4c60, - 0x7b77ada8, 0xde3d4964, - 0x7b5d039e, 0xdddc5b3b, 0x7b420d7a, 0xdd7b8220, 0x7b26cb4f, 0xdd1abe51, - 0x7b0b3d2c, 0xdcba1008, - 0x7aef6323, 0xdc597781, 0x7ad33d45, 0xdbf8f4f8, 0x7ab6cba4, 0xdb9888a8, - 0x7a9a0e50, 0xdb3832cd, - 0x7a7d055b, 0xdad7f3a2, 0x7a5fb0d8, 0xda77cb63, 0x7a4210d8, 0xda17ba4a, - 0x7a24256f, 0xd9b7c094, - 0x7a05eead, 0xd957de7a, 0x79e76ca7, 0xd8f81439, 0x79c89f6e, 0xd898620c, - 0x79a98715, 0xd838c82d, - 0x798a23b1, 0xd7d946d8, 0x796a7554, 0xd779de47, 0x794a7c12, 0xd71a8eb5, - 0x792a37fe, 0xd6bb585e, - 0x7909a92d, 0xd65c3b7b, 0x78e8cfb2, 0xd5fd3848, 0x78c7aba2, 0xd59e4eff, - 0x78a63d11, 0xd53f7fda, - 0x78848414, 0xd4e0cb15, 0x786280bf, 0xd48230e9, 0x78403329, 0xd423b191, - 0x781d9b65, 0xd3c54d47, - 0x77fab989, 0xd3670446, 0x77d78daa, 0xd308d6c7, 0x77b417df, 0xd2aac504, - 0x7790583e, 0xd24ccf39, - 0x776c4edb, 0xd1eef59e, 0x7747fbce, 0xd191386e, 0x77235f2d, 0xd13397e2, - 0x76fe790e, 0xd0d61434, - 0x76d94989, 0xd078ad9e, 0x76b3d0b4, 0xd01b6459, 0x768e0ea6, 0xcfbe389f, - 0x76680376, 0xcf612aaa, - 0x7641af3d, 0xcf043ab3, 0x761b1211, 0xcea768f2, 0x75f42c0b, 0xce4ab5a2, - 0x75ccfd42, 0xcdee20fc, - 0x75a585cf, 0xcd91ab39, 0x757dc5ca, 0xcd355491, 0x7555bd4c, 0xccd91d3d, - 0x752d6c6c, 0xcc7d0578, - 0x7504d345, 0xcc210d79, 0x74dbf1ef, 0xcbc53579, 0x74b2c884, 0xcb697db0, - 0x7489571c, 0xcb0de658, - 0x745f9dd1, 0xcab26fa9, 0x74359cbd, 0xca5719db, 0x740b53fb, 0xc9fbe527, - 0x73e0c3a3, 0xc9a0d1c5, - 0x73b5ebd1, 0xc945dfec, 0x738acc9e, 0xc8eb0fd6, 0x735f6626, 0xc89061ba, - 0x7333b883, 0xc835d5d0, - 0x7307c3d0, 0xc7db6c50, 0x72db8828, 0xc7812572, 0x72af05a7, 0xc727016d, - 0x72823c67, 0xc6cd0079, - 0x72552c85, 0xc67322ce, 0x7227d61c, 0xc61968a2, 0x71fa3949, 0xc5bfd22e, - 0x71cc5626, 0xc5665fa9, - 0x719e2cd2, 0xc50d1149, 0x716fbd68, 0xc4b3e746, 0x71410805, 0xc45ae1d7, - 0x71120cc5, 0xc4020133, - 0x70e2cbc6, 0xc3a94590, 0x70b34525, 0xc350af26, 0x708378ff, 0xc2f83e2a, - 0x70536771, 0xc29ff2d4, - 0x7023109a, 0xc247cd5a, 0x6ff27497, 0xc1efcdf3, 0x6fc19385, 0xc197f4d4, - 0x6f906d84, 0xc1404233, - 0x6f5f02b2, 0xc0e8b648, 0x6f2d532c, 0xc0915148, 0x6efb5f12, 0xc03a1368, - 0x6ec92683, 0xbfe2fcdf, - 0x6e96a99d, 0xbf8c0de3, 0x6e63e87f, 0xbf3546a8, 0x6e30e34a, 0xbedea765, - 0x6dfd9a1c, 0xbe88304f, - 0x6dca0d14, 0xbe31e19b, 0x6d963c54, 0xbddbbb7f, 0x6d6227fa, 0xbd85be30, - 0x6d2dd027, 0xbd2fe9e2, - 0x6cf934fc, 0xbcda3ecb, 0x6cc45698, 0xbc84bd1f, 0x6c8f351c, 0xbc2f6513, - 0x6c59d0a9, 0xbbda36dd, - 0x6c242960, 0xbb8532b0, 0x6bee3f62, 0xbb3058c0, 0x6bb812d1, 0xbadba943, - 0x6b81a3cd, 0xba87246d, - 0x6b4af279, 0xba32ca71, 0x6b13fef5, 0xb9de9b83, 0x6adcc964, 0xb98a97d8, - 0x6aa551e9, 0xb936bfa4, - 0x6a6d98a4, 0xb8e31319, 0x6a359db9, 0xb88f926d, 0x69fd614a, 0xb83c3dd1, - 0x69c4e37a, 0xb7e9157a, - 0x698c246c, 0xb796199b, 0x69532442, 0xb7434a67, 0x6919e320, 0xb6f0a812, - 0x68e06129, 0xb69e32cd, - 0x68a69e81, 0xb64beacd, 0x686c9b4b, 0xb5f9d043, 0x683257ab, 0xb5a7e362, - 0x67f7d3c5, 0xb556245e, - 0x67bd0fbd, 0xb5049368, 0x67820bb7, 0xb4b330b3, 0x6746c7d8, 0xb461fc70, - 0x670b4444, 0xb410f6d3, - 0x66cf8120, 0xb3c0200c, 0x66937e91, 0xb36f784f, 0x66573cbb, 0xb31effcc, - 0x661abbc5, 0xb2ceb6b5, - 0x65ddfbd3, 0xb27e9d3c, 0x65a0fd0b, 0xb22eb392, 0x6563bf92, 0xb1def9e9, - 0x6526438f, 0xb18f7071, - 0x64e88926, 0xb140175b, 0x64aa907f, 0xb0f0eeda, 0x646c59bf, 0xb0a1f71d, - 0x642de50d, 0xb0533055, - 0x63ef3290, 0xb0049ab3, 0x63b0426d, 0xafb63667, 0x637114cc, 0xaf6803a2, - 0x6331a9d4, 0xaf1a0293, - 0x62f201ac, 0xaecc336c, 0x62b21c7b, 0xae7e965b, 0x6271fa69, 0xae312b92, - 0x62319b9d, 0xade3f33e, - 0x61f1003f, 0xad96ed92, 0x61b02876, 0xad4a1aba, 0x616f146c, 0xacfd7ae8, - 0x612dc447, 0xacb10e4b, - 0x60ec3830, 0xac64d510, 0x60aa7050, 0xac18cf69, 0x60686ccf, 0xabccfd83, - 0x60262dd6, 0xab815f8d, - 0x5fe3b38d, 0xab35f5b5, 0x5fa0fe1f, 0xaaeac02c, 0x5f5e0db3, 0xaa9fbf1e, - 0x5f1ae274, 0xaa54f2ba, - 0x5ed77c8a, 0xaa0a5b2e, 0x5e93dc1f, 0xa9bff8a8, 0x5e50015d, 0xa975cb57, - 0x5e0bec6e, 0xa92bd367, - 0x5dc79d7c, 0xa8e21106, 0x5d8314b1, 0xa8988463, 0x5d3e5237, 0xa84f2daa, - 0x5cf95638, 0xa8060d08, - 0x5cb420e0, 0xa7bd22ac, 0x5c6eb258, 0xa7746ec0, 0x5c290acc, 0xa72bf174, - 0x5be32a67, 0xa6e3aaf2, - 0x5b9d1154, 0xa69b9b68, 0x5b56bfbd, 0xa653c303, 0x5b1035cf, 0xa60c21ee, - 0x5ac973b5, 0xa5c4b855, - 0x5a82799a, 0xa57d8666, 0x5a3b47ab, 0xa5368c4b, 0x59f3de12, 0xa4efca31, - 0x59ac3cfd, 0xa4a94043, - 0x59646498, 0xa462eeac, 0x591c550e, 0xa41cd599, 0x58d40e8c, 0xa3d6f534, - 0x588b9140, 0xa3914da8, - 0x5842dd54, 0xa34bdf20, 0x57f9f2f8, 0xa306a9c8, 0x57b0d256, 0xa2c1adc9, - 0x57677b9d, 0xa27ceb4f, - 0x571deefa, 0xa2386284, 0x56d42c99, 0xa1f41392, 0x568a34a9, 0xa1affea3, - 0x56400758, 0xa16c23e1, - 0x55f5a4d2, 0xa1288376, 0x55ab0d46, 0xa0e51d8c, 0x556040e2, 0xa0a1f24d, - 0x55153fd4, 0xa05f01e1, - 0x54ca0a4b, 0xa01c4c73, 0x547ea073, 0x9fd9d22a, 0x5433027d, 0x9f979331, - 0x53e73097, 0x9f558fb0, - 0x539b2af0, 0x9f13c7d0, 0x534ef1b5, 0x9ed23bb9, 0x53028518, 0x9e90eb94, - 0x52b5e546, 0x9e4fd78a, - 0x5269126e, 0x9e0effc1, 0x521c0cc2, 0x9dce6463, 0x51ced46e, 0x9d8e0597, - 0x518169a5, 0x9d4de385, - 0x5133cc94, 0x9d0dfe54, 0x50e5fd6d, 0x9cce562c, 0x5097fc5e, 0x9c8eeb34, - 0x5049c999, 0x9c4fbd93, - 0x4ffb654d, 0x9c10cd70, 0x4faccfab, 0x9bd21af3, 0x4f5e08e3, 0x9b93a641, - 0x4f0f1126, 0x9b556f81, - 0x4ebfe8a5, 0x9b1776da, 0x4e708f8f, 0x9ad9bc71, 0x4e210617, 0x9a9c406e, - 0x4dd14c6e, 0x9a5f02f5, - 0x4d8162c4, 0x9a22042d, 0x4d31494b, 0x99e5443b, 0x4ce10034, 0x99a8c345, - 0x4c9087b1, 0x996c816f, - 0x4c3fdff4, 0x99307ee0, 0x4bef092d, 0x98f4bbbc, 0x4b9e0390, 0x98b93828, - 0x4b4ccf4d, 0x987df449, - 0x4afb6c98, 0x9842f043, 0x4aa9dba2, 0x98082c3b, 0x4a581c9e, 0x97cda855, - 0x4a062fbd, 0x979364b5, - 0x49b41533, 0x9759617f, 0x4961cd33, 0x971f9ed7, 0x490f57ee, 0x96e61ce0, - 0x48bcb599, 0x96acdbbe, - 0x4869e665, 0x9673db94, 0x4816ea86, 0x963b1c86, 0x47c3c22f, 0x96029eb6, - 0x47706d93, 0x95ca6247, - 0x471cece7, 0x9592675c, 0x46c9405c, 0x955aae17, 0x46756828, 0x9523369c, - 0x4621647d, 0x94ec010b, - 0x45cd358f, 0x94b50d87, 0x4578db93, 0x947e5c33, 0x452456bd, 0x9447ed2f, - 0x44cfa740, 0x9411c09e, - 0x447acd50, 0x93dbd6a0, 0x4425c923, 0x93a62f57, 0x43d09aed, 0x9370cae4, - 0x437b42e1, 0x933ba968, - 0x4325c135, 0x9306cb04, 0x42d0161e, 0x92d22fd9, 0x427a41d0, 0x929dd806, - 0x42244481, 0x9269c3ac, - 0x41ce1e65, 0x9235f2ec, 0x4177cfb1, 0x920265e4, 0x4121589b, 0x91cf1cb6, - 0x40cab958, 0x919c1781, - 0x4073f21d, 0x91695663, 0x401d0321, 0x9136d97d, 0x3fc5ec98, 0x9104a0ee, - 0x3f6eaeb8, 0x90d2acd4, - 0x3f1749b8, 0x90a0fd4e, 0x3ebfbdcd, 0x906f927c, 0x3e680b2c, 0x903e6c7b, - 0x3e10320d, 0x900d8b69, - 0x3db832a6, 0x8fdcef66, 0x3d600d2c, 0x8fac988f, 0x3d07c1d6, 0x8f7c8701, - 0x3caf50da, 0x8f4cbadb, - 0x3c56ba70, 0x8f1d343a, 0x3bfdfecd, 0x8eedf33b, 0x3ba51e29, 0x8ebef7fb, - 0x3b4c18ba, 0x8e904298, - 0x3af2eeb7, 0x8e61d32e, 0x3a99a057, 0x8e33a9da, 0x3a402dd2, 0x8e05c6b7, - 0x39e6975e, 0x8dd829e4, - 0x398cdd32, 0x8daad37b, 0x3932ff87, 0x8d7dc399, 0x38d8fe93, 0x8d50fa59, - 0x387eda8e, 0x8d2477d8, - 0x382493b0, 0x8cf83c30, 0x37ca2a30, 0x8ccc477d, 0x376f9e46, 0x8ca099da, - 0x3714f02a, 0x8c753362, - 0x36ba2014, 0x8c4a142f, 0x365f2e3b, 0x8c1f3c5d, 0x36041ad9, 0x8bf4ac05, - 0x35a8e625, 0x8bca6343, - 0x354d9057, 0x8ba0622f, 0x34f219a8, 0x8b76a8e4, 0x34968250, 0x8b4d377c, - 0x343aca87, 0x8b240e11, - 0x33def287, 0x8afb2cbb, 0x3382fa88, 0x8ad29394, 0x3326e2c3, 0x8aaa42b4, - 0x32caab6f, 0x8a823a36, - 0x326e54c7, 0x8a5a7a31, 0x3211df04, 0x8a3302be, 0x31b54a5e, 0x8a0bd3f5, - 0x3158970e, 0x89e4edef, - 0x30fbc54d, 0x89be50c3, 0x309ed556, 0x8997fc8a, 0x3041c761, 0x8971f15a, - 0x2fe49ba7, 0x894c2f4c, - 0x2f875262, 0x8926b677, 0x2f29ebcc, 0x890186f2, 0x2ecc681e, 0x88dca0d3, - 0x2e6ec792, 0x88b80432, - 0x2e110a62, 0x8893b125, 0x2db330c7, 0x886fa7c2, 0x2d553afc, 0x884be821, - 0x2cf72939, 0x88287256, - 0x2c98fbba, 0x88054677, 0x2c3ab2b9, 0x87e2649b, 0x2bdc4e6f, 0x87bfccd7, - 0x2b7dcf17, 0x879d7f41, - 0x2b1f34eb, 0x877b7bec, 0x2ac08026, 0x8759c2ef, 0x2a61b101, 0x8738545e, - 0x2a02c7b8, 0x8717304e, - 0x29a3c485, 0x86f656d3, 0x2944a7a2, 0x86d5c802, 0x28e5714b, 0x86b583ee, - 0x288621b9, 0x86958aac, - 0x2826b928, 0x8675dc4f, 0x27c737d3, 0x865678eb, 0x27679df4, 0x86376092, - 0x2707ebc7, 0x86189359, - 0x26a82186, 0x85fa1153, 0x26483f6c, 0x85dbda91, 0x25e845b6, 0x85bdef28, - 0x2588349d, 0x85a04f28, - 0x25280c5e, 0x8582faa5, 0x24c7cd33, 0x8565f1b0, 0x24677758, 0x8549345c, - 0x24070b08, 0x852cc2bb, - 0x23a6887f, 0x85109cdd, 0x2345eff8, 0x84f4c2d4, 0x22e541af, 0x84d934b1, - 0x22847de0, 0x84bdf286, - 0x2223a4c5, 0x84a2fc62, 0x21c2b69c, 0x84885258, 0x2161b3a0, 0x846df477, - 0x21009c0c, 0x8453e2cf, - 0x209f701c, 0x843a1d70, 0x203e300d, 0x8420a46c, 0x1fdcdc1b, 0x840777d0, - 0x1f7b7481, 0x83ee97ad, - 0x1f19f97b, 0x83d60412, 0x1eb86b46, 0x83bdbd0e, 0x1e56ca1e, 0x83a5c2b0, - 0x1df5163f, 0x838e1507, - 0x1d934fe5, 0x8376b422, 0x1d31774d, 0x835fa00f, 0x1ccf8cb3, 0x8348d8dc, - 0x1c6d9053, 0x83325e97, - 0x1c0b826a, 0x831c314e, 0x1ba96335, 0x83065110, 0x1b4732ef, 0x82f0bde8, - 0x1ae4f1d6, 0x82db77e5, - 0x1a82a026, 0x82c67f14, 0x1a203e1b, 0x82b1d381, 0x19bdcbf3, 0x829d753a, - 0x195b49ea, 0x8289644b, - 0x18f8b83c, 0x8275a0c0, 0x18961728, 0x82622aa6, 0x183366e9, 0x824f0208, - 0x17d0a7bc, 0x823c26f3, - 0x176dd9de, 0x82299971, 0x170afd8d, 0x82175990, 0x16a81305, 0x82056758, - 0x16451a83, 0x81f3c2d7, - 0x15e21445, 0x81e26c16, 0x157f0086, 0x81d16321, 0x151bdf86, 0x81c0a801, - 0x14b8b17f, 0x81b03ac2, - 0x145576b1, 0x81a01b6d, 0x13f22f58, 0x81904a0c, 0x138edbb1, 0x8180c6a9, - 0x132b7bf9, 0x8171914e, - 0x12c8106f, 0x8162aa04, 0x1264994e, 0x815410d4, 0x120116d5, 0x8145c5c7, - 0x119d8941, 0x8137c8e6, - 0x1139f0cf, 0x812a1a3a, 0x10d64dbd, 0x811cb9ca, 0x1072a048, 0x810fa7a0, - 0x100ee8ad, 0x8102e3c4, - 0xfab272b, 0x80f66e3c, 0xf475bff, 0x80ea4712, 0xee38766, 0x80de6e4c, - 0xe7fa99e, 0x80d2e3f2, - 0xe1bc2e4, 0x80c7a80a, 0xdb7d376, 0x80bcba9d, 0xd53db92, 0x80b21baf, - 0xcefdb76, 0x80a7cb49, - 0xc8bd35e, 0x809dc971, 0xc27c389, 0x8094162c, 0xbc3ac35, 0x808ab180, - 0xb5f8d9f, 0x80819b74, - 0xafb6805, 0x8078d40d, 0xa973ba5, 0x80705b50, 0xa3308bd, 0x80683143, - 0x9cecf89, 0x806055eb, - 0x96a9049, 0x8058c94c, 0x9064b3a, 0x80518b6b, 0x8a2009a, 0x804a9c4d, - 0x83db0a7, 0x8043fbf6, - 0x7d95b9e, 0x803daa6a, 0x77501be, 0x8037a7ac, 0x710a345, 0x8031f3c2, - 0x6ac406f, 0x802c8ead, - 0x647d97c, 0x80277872, 0x5e36ea9, 0x8022b114, 0x57f0035, 0x801e3895, - 0x51a8e5c, 0x801a0ef8, - 0x4b6195d, 0x80163440, 0x451a177, 0x8012a86f, 0x3ed26e6, 0x800f6b88, - 0x388a9ea, 0x800c7d8c, - 0x3242abf, 0x8009de7e, 0x2bfa9a4, 0x80078e5e, 0x25b26d7, 0x80058d2f, - 0x1f6a297, 0x8003daf1, - 0x1921d20, 0x800277a6, 0x12d96b1, 0x8001634e, 0xc90f88, 0x80009dea, - 0x6487e3, 0x8000277a, -}; - -static const q31_t WeightsQ31_2048[4096] = { - 0x7fffffff, 0x0, 0x7ffffd88, 0xffe6de05, 0x7ffff621, 0xffcdbc0b, 0x7fffe9cb, - 0xffb49a12, - 0x7fffd886, 0xff9b781d, 0x7fffc251, 0xff82562c, 0x7fffa72c, 0xff69343f, - 0x7fff8719, 0xff501258, - 0x7fff6216, 0xff36f078, 0x7fff3824, 0xff1dcea0, 0x7fff0943, 0xff04acd0, - 0x7ffed572, 0xfeeb8b0a, - 0x7ffe9cb2, 0xfed2694f, 0x7ffe5f03, 0xfeb947a0, 0x7ffe1c65, 0xfea025fd, - 0x7ffdd4d7, 0xfe870467, - 0x7ffd885a, 0xfe6de2e0, 0x7ffd36ee, 0xfe54c169, 0x7ffce093, 0xfe3ba002, - 0x7ffc8549, 0xfe227eac, - 0x7ffc250f, 0xfe095d69, 0x7ffbbfe6, 0xfdf03c3a, 0x7ffb55ce, 0xfdd71b1e, - 0x7ffae6c7, 0xfdbdfa18, - 0x7ffa72d1, 0xfda4d929, 0x7ff9f9ec, 0xfd8bb850, 0x7ff97c18, 0xfd729790, - 0x7ff8f954, 0xfd5976e9, - 0x7ff871a2, 0xfd40565c, 0x7ff7e500, 0xfd2735ea, 0x7ff75370, 0xfd0e1594, - 0x7ff6bcf0, 0xfcf4f55c, - 0x7ff62182, 0xfcdbd541, 0x7ff58125, 0xfcc2b545, 0x7ff4dbd9, 0xfca9956a, - 0x7ff4319d, 0xfc9075af, - 0x7ff38274, 0xfc775616, 0x7ff2ce5b, 0xfc5e36a0, 0x7ff21553, 0xfc45174e, - 0x7ff1575d, 0xfc2bf821, - 0x7ff09478, 0xfc12d91a, 0x7fefcca4, 0xfbf9ba39, 0x7feeffe1, 0xfbe09b80, - 0x7fee2e30, 0xfbc77cf0, - 0x7fed5791, 0xfbae5e89, 0x7fec7c02, 0xfb95404d, 0x7feb9b85, 0xfb7c223d, - 0x7feab61a, 0xfb630459, - 0x7fe9cbc0, 0xfb49e6a3, 0x7fe8dc78, 0xfb30c91b, 0x7fe7e841, 0xfb17abc2, - 0x7fe6ef1c, 0xfafe8e9b, - 0x7fe5f108, 0xfae571a4, 0x7fe4ee06, 0xfacc54e0, 0x7fe3e616, 0xfab3384f, - 0x7fe2d938, 0xfa9a1bf3, - 0x7fe1c76b, 0xfa80ffcb, 0x7fe0b0b1, 0xfa67e3da, 0x7fdf9508, 0xfa4ec821, - 0x7fde7471, 0xfa35ac9f, - 0x7fdd4eec, 0xfa1c9157, 0x7fdc247a, 0xfa037648, 0x7fdaf519, 0xf9ea5b75, - 0x7fd9c0ca, 0xf9d140de, - 0x7fd8878e, 0xf9b82684, 0x7fd74964, 0xf99f0c68, 0x7fd6064c, 0xf985f28a, - 0x7fd4be46, 0xf96cd8ed, - 0x7fd37153, 0xf953bf91, 0x7fd21f72, 0xf93aa676, 0x7fd0c8a3, 0xf9218d9e, - 0x7fcf6ce8, 0xf908750a, - 0x7fce0c3e, 0xf8ef5cbb, 0x7fcca6a7, 0xf8d644b2, 0x7fcb3c23, 0xf8bd2cef, - 0x7fc9ccb2, 0xf8a41574, - 0x7fc85854, 0xf88afe42, 0x7fc6df08, 0xf871e759, 0x7fc560cf, 0xf858d0bb, - 0x7fc3dda9, 0xf83fba68, - 0x7fc25596, 0xf826a462, 0x7fc0c896, 0xf80d8ea9, 0x7fbf36aa, 0xf7f4793e, - 0x7fbd9fd0, 0xf7db6423, - 0x7fbc040a, 0xf7c24f59, 0x7fba6357, 0xf7a93ae0, 0x7fb8bdb8, 0xf79026b9, - 0x7fb7132b, 0xf77712e5, - 0x7fb563b3, 0xf75dff66, 0x7fb3af4e, 0xf744ec3b, 0x7fb1f5fc, 0xf72bd967, - 0x7fb037bf, 0xf712c6ea, - 0x7fae7495, 0xf6f9b4c6, 0x7facac7f, 0xf6e0a2fa, 0x7faadf7c, 0xf6c79188, - 0x7fa90d8e, 0xf6ae8071, - 0x7fa736b4, 0xf6956fb7, 0x7fa55aee, 0xf67c5f59, 0x7fa37a3c, 0xf6634f59, - 0x7fa1949e, 0xf64a3fb8, - 0x7f9faa15, 0xf6313077, 0x7f9dbaa0, 0xf6182196, 0x7f9bc640, 0xf5ff1318, - 0x7f99ccf4, 0xf5e604fc, - 0x7f97cebd, 0xf5ccf743, 0x7f95cb9a, 0xf5b3e9f0, 0x7f93c38c, 0xf59add02, - 0x7f91b694, 0xf581d07b, - 0x7f8fa4b0, 0xf568c45b, 0x7f8d8de1, 0xf54fb8a4, 0x7f8b7227, 0xf536ad56, - 0x7f895182, 0xf51da273, - 0x7f872bf3, 0xf50497fb, 0x7f850179, 0xf4eb8def, 0x7f82d214, 0xf4d28451, - 0x7f809dc5, 0xf4b97b21, - 0x7f7e648c, 0xf4a07261, 0x7f7c2668, 0xf4876a10, 0x7f79e35a, 0xf46e6231, - 0x7f779b62, 0xf4555ac5, - 0x7f754e80, 0xf43c53cb, 0x7f72fcb4, 0xf4234d45, 0x7f70a5fe, 0xf40a4735, - 0x7f6e4a5e, 0xf3f1419a, - 0x7f6be9d4, 0xf3d83c77, 0x7f698461, 0xf3bf37cb, 0x7f671a05, 0xf3a63398, - 0x7f64aabf, 0xf38d2fe0, - 0x7f62368f, 0xf3742ca2, 0x7f5fbd77, 0xf35b29e0, 0x7f5d3f75, 0xf342279b, - 0x7f5abc8a, 0xf32925d3, - 0x7f5834b7, 0xf310248a, 0x7f55a7fa, 0xf2f723c1, 0x7f531655, 0xf2de2379, - 0x7f507fc7, 0xf2c523b2, - 0x7f4de451, 0xf2ac246e, 0x7f4b43f2, 0xf29325ad, 0x7f489eaa, 0xf27a2771, - 0x7f45f47b, 0xf26129ba, - 0x7f434563, 0xf2482c8a, 0x7f409164, 0xf22f2fe1, 0x7f3dd87c, 0xf21633c0, - 0x7f3b1aad, 0xf1fd3829, - 0x7f3857f6, 0xf1e43d1c, 0x7f359057, 0xf1cb429a, 0x7f32c3d1, 0xf1b248a5, - 0x7f2ff263, 0xf1994f3d, - 0x7f2d1c0e, 0xf1805662, 0x7f2a40d2, 0xf1675e17, 0x7f2760af, 0xf14e665c, - 0x7f247ba5, 0xf1356f32, - 0x7f2191b4, 0xf11c789a, 0x7f1ea2dc, 0xf1038295, 0x7f1baf1e, 0xf0ea8d24, - 0x7f18b679, 0xf0d19848, - 0x7f15b8ee, 0xf0b8a401, 0x7f12b67c, 0xf09fb051, 0x7f0faf25, 0xf086bd39, - 0x7f0ca2e7, 0xf06dcaba, - 0x7f0991c4, 0xf054d8d5, 0x7f067bba, 0xf03be78a, 0x7f0360cb, 0xf022f6da, - 0x7f0040f6, 0xf00a06c8, - 0x7efd1c3c, 0xeff11753, 0x7ef9f29d, 0xefd8287c, 0x7ef6c418, 0xefbf3a45, - 0x7ef390ae, 0xefa64cae, - 0x7ef05860, 0xef8d5fb8, 0x7eed1b2c, 0xef747365, 0x7ee9d914, 0xef5b87b5, - 0x7ee69217, 0xef429caa, - 0x7ee34636, 0xef29b243, 0x7edff570, 0xef10c883, 0x7edc9fc6, 0xeef7df6a, - 0x7ed94538, 0xeedef6f9, - 0x7ed5e5c6, 0xeec60f31, 0x7ed28171, 0xeead2813, 0x7ecf1837, 0xee9441a0, - 0x7ecbaa1a, 0xee7b5bd9, - 0x7ec8371a, 0xee6276bf, 0x7ec4bf36, 0xee499253, 0x7ec14270, 0xee30ae96, - 0x7ebdc0c6, 0xee17cb88, - 0x7eba3a39, 0xedfee92b, 0x7eb6aeca, 0xede60780, 0x7eb31e78, 0xedcd2687, - 0x7eaf8943, 0xedb44642, - 0x7eabef2c, 0xed9b66b2, 0x7ea85033, 0xed8287d7, 0x7ea4ac58, 0xed69a9b3, - 0x7ea1039b, 0xed50cc46, - 0x7e9d55fc, 0xed37ef91, 0x7e99a37c, 0xed1f1396, 0x7e95ec1a, 0xed063856, - 0x7e922fd6, 0xeced5dd0, - 0x7e8e6eb2, 0xecd48407, 0x7e8aa8ac, 0xecbbaafb, 0x7e86ddc6, 0xeca2d2ad, - 0x7e830dff, 0xec89fb1e, - 0x7e7f3957, 0xec71244f, 0x7e7b5fce, 0xec584e41, 0x7e778166, 0xec3f78f6, - 0x7e739e1d, 0xec26a46d, - 0x7e6fb5f4, 0xec0dd0a8, 0x7e6bc8eb, 0xebf4fda8, 0x7e67d703, 0xebdc2b6e, - 0x7e63e03b, 0xebc359fb, - 0x7e5fe493, 0xebaa894f, 0x7e5be40c, 0xeb91b96c, 0x7e57dea7, 0xeb78ea52, - 0x7e53d462, 0xeb601c04, - 0x7e4fc53e, 0xeb474e81, 0x7e4bb13c, 0xeb2e81ca, 0x7e47985b, 0xeb15b5e1, - 0x7e437a9c, 0xeafceac6, - 0x7e3f57ff, 0xeae4207a, 0x7e3b3083, 0xeacb56ff, 0x7e37042a, 0xeab28e56, - 0x7e32d2f4, 0xea99c67e, - 0x7e2e9cdf, 0xea80ff7a, 0x7e2a61ed, 0xea683949, 0x7e26221f, 0xea4f73ee, - 0x7e21dd73, 0xea36af69, - 0x7e1d93ea, 0xea1debbb, 0x7e194584, 0xea0528e5, 0x7e14f242, 0xe9ec66e8, - 0x7e109a24, 0xe9d3a5c5, - 0x7e0c3d29, 0xe9bae57d, 0x7e07db52, 0xe9a22610, 0x7e0374a0, 0xe9896781, - 0x7dff0911, 0xe970a9ce, - 0x7dfa98a8, 0xe957ecfb, 0x7df62362, 0xe93f3107, 0x7df1a942, 0xe92675f4, - 0x7ded2a47, 0xe90dbbc2, - 0x7de8a670, 0xe8f50273, 0x7de41dc0, 0xe8dc4a07, 0x7ddf9034, 0xe8c39280, - 0x7ddafdce, 0xe8aadbde, - 0x7dd6668f, 0xe8922622, 0x7dd1ca75, 0xe879714d, 0x7dcd2981, 0xe860bd61, - 0x7dc883b4, 0xe8480a5d, - 0x7dc3d90d, 0xe82f5844, 0x7dbf298d, 0xe816a716, 0x7dba7534, 0xe7fdf6d4, - 0x7db5bc02, 0xe7e5477f, - 0x7db0fdf8, 0xe7cc9917, 0x7dac3b15, 0xe7b3eb9f, 0x7da77359, 0xe79b3f16, - 0x7da2a6c6, 0xe782937e, - 0x7d9dd55a, 0xe769e8d8, 0x7d98ff17, 0xe7513f25, 0x7d9423fc, 0xe7389665, - 0x7d8f4409, 0xe71fee99, - 0x7d8a5f40, 0xe70747c4, 0x7d85759f, 0xe6eea1e4, 0x7d808728, 0xe6d5fcfc, - 0x7d7b93da, 0xe6bd590d, - 0x7d769bb5, 0xe6a4b616, 0x7d719eba, 0xe68c141a, 0x7d6c9ce9, 0xe6737319, - 0x7d679642, 0xe65ad315, - 0x7d628ac6, 0xe642340d, 0x7d5d7a74, 0xe6299604, 0x7d58654d, 0xe610f8f9, - 0x7d534b50, 0xe5f85cef, - 0x7d4e2c7f, 0xe5dfc1e5, 0x7d4908d9, 0xe5c727dd, 0x7d43e05e, 0xe5ae8ed8, - 0x7d3eb30f, 0xe595f6d7, - 0x7d3980ec, 0xe57d5fda, 0x7d3449f5, 0xe564c9e3, 0x7d2f0e2b, 0xe54c34f3, - 0x7d29cd8c, 0xe533a10a, - 0x7d24881b, 0xe51b0e2a, 0x7d1f3dd6, 0xe5027c53, 0x7d19eebf, 0xe4e9eb87, - 0x7d149ad5, 0xe4d15bc6, - 0x7d0f4218, 0xe4b8cd11, 0x7d09e489, 0xe4a03f69, 0x7d048228, 0xe487b2d0, - 0x7cff1af5, 0xe46f2745, - 0x7cf9aef0, 0xe4569ccb, 0x7cf43e1a, 0xe43e1362, 0x7ceec873, 0xe4258b0a, - 0x7ce94dfb, 0xe40d03c6, - 0x7ce3ceb2, 0xe3f47d96, 0x7cde4a98, 0xe3dbf87a, 0x7cd8c1ae, 0xe3c37474, - 0x7cd333f3, 0xe3aaf184, - 0x7ccda169, 0xe3926fad, 0x7cc80a0f, 0xe379eeed, 0x7cc26de5, 0xe3616f48, - 0x7cbcccec, 0xe348f0bd, - 0x7cb72724, 0xe330734d, 0x7cb17c8d, 0xe317f6fa, 0x7cabcd28, 0xe2ff7bc3, - 0x7ca618f3, 0xe2e701ac, - 0x7ca05ff1, 0xe2ce88b3, 0x7c9aa221, 0xe2b610da, 0x7c94df83, 0xe29d9a23, - 0x7c8f1817, 0xe285248d, - 0x7c894bde, 0xe26cb01b, 0x7c837ad8, 0xe2543ccc, 0x7c7da505, 0xe23bcaa2, - 0x7c77ca65, 0xe223599e, - 0x7c71eaf9, 0xe20ae9c1, 0x7c6c06c0, 0xe1f27b0b, 0x7c661dbc, 0xe1da0d7e, - 0x7c602fec, 0xe1c1a11b, - 0x7c5a3d50, 0xe1a935e2, 0x7c5445e9, 0xe190cbd4, 0x7c4e49b7, 0xe17862f3, - 0x7c4848ba, 0xe15ffb3f, - 0x7c4242f2, 0xe14794ba, 0x7c3c3860, 0xe12f2f63, 0x7c362904, 0xe116cb3d, - 0x7c3014de, 0xe0fe6848, - 0x7c29fbee, 0xe0e60685, 0x7c23de35, 0xe0cda5f5, 0x7c1dbbb3, 0xe0b54698, - 0x7c179467, 0xe09ce871, - 0x7c116853, 0xe0848b7f, 0x7c0b3777, 0xe06c2fc4, 0x7c0501d2, 0xe053d541, - 0x7bfec765, 0xe03b7bf6, - 0x7bf88830, 0xe02323e5, 0x7bf24434, 0xe00acd0e, 0x7bebfb70, 0xdff27773, - 0x7be5ade6, 0xdfda2314, - 0x7bdf5b94, 0xdfc1cff3, 0x7bd9047c, 0xdfa97e0f, 0x7bd2a89e, 0xdf912d6b, - 0x7bcc47fa, 0xdf78de07, - 0x7bc5e290, 0xdf608fe4, 0x7bbf7860, 0xdf484302, 0x7bb9096b, 0xdf2ff764, - 0x7bb295b0, 0xdf17ad0a, - 0x7bac1d31, 0xdeff63f4, 0x7ba59fee, 0xdee71c24, 0x7b9f1de6, 0xdeced59b, - 0x7b989719, 0xdeb69059, - 0x7b920b89, 0xde9e4c60, 0x7b8b7b36, 0xde8609b1, 0x7b84e61f, 0xde6dc84b, - 0x7b7e4c45, 0xde558831, - 0x7b77ada8, 0xde3d4964, 0x7b710a49, 0xde250be3, 0x7b6a6227, 0xde0ccfb1, - 0x7b63b543, 0xddf494ce, - 0x7b5d039e, 0xdddc5b3b, 0x7b564d36, 0xddc422f8, 0x7b4f920e, 0xddabec08, - 0x7b48d225, 0xdd93b66a, - 0x7b420d7a, 0xdd7b8220, 0x7b3b4410, 0xdd634f2b, 0x7b3475e5, 0xdd4b1d8c, - 0x7b2da2fa, 0xdd32ed43, - 0x7b26cb4f, 0xdd1abe51, 0x7b1feee5, 0xdd0290b8, 0x7b190dbc, 0xdcea6478, - 0x7b1227d3, 0xdcd23993, - 0x7b0b3d2c, 0xdcba1008, 0x7b044dc7, 0xdca1e7da, 0x7afd59a4, 0xdc89c109, - 0x7af660c2, 0xdc719b96, - 0x7aef6323, 0xdc597781, 0x7ae860c7, 0xdc4154cd, 0x7ae159ae, 0xdc293379, - 0x7ada4dd8, 0xdc111388, - 0x7ad33d45, 0xdbf8f4f8, 0x7acc27f7, 0xdbe0d7cd, 0x7ac50dec, 0xdbc8bc06, - 0x7abdef25, 0xdbb0a1a4, - 0x7ab6cba4, 0xdb9888a8, 0x7aafa367, 0xdb807114, 0x7aa8766f, 0xdb685ae9, - 0x7aa144bc, 0xdb504626, - 0x7a9a0e50, 0xdb3832cd, 0x7a92d329, 0xdb2020e0, 0x7a8b9348, 0xdb08105e, - 0x7a844eae, 0xdaf00149, - 0x7a7d055b, 0xdad7f3a2, 0x7a75b74f, 0xdabfe76a, 0x7a6e648a, 0xdaa7dca1, - 0x7a670d0d, 0xda8fd349, - 0x7a5fb0d8, 0xda77cb63, 0x7a584feb, 0xda5fc4ef, 0x7a50ea47, 0xda47bfee, - 0x7a497feb, 0xda2fbc61, - 0x7a4210d8, 0xda17ba4a, 0x7a3a9d0f, 0xd9ffb9a9, 0x7a332490, 0xd9e7ba7f, - 0x7a2ba75a, 0xd9cfbccd, - 0x7a24256f, 0xd9b7c094, 0x7a1c9ece, 0xd99fc5d4, 0x7a151378, 0xd987cc90, - 0x7a0d836d, 0xd96fd4c7, - 0x7a05eead, 0xd957de7a, 0x79fe5539, 0xd93fe9ab, 0x79f6b711, 0xd927f65b, - 0x79ef1436, 0xd910048a, - 0x79e76ca7, 0xd8f81439, 0x79dfc064, 0xd8e0256a, 0x79d80f6f, 0xd8c8381d, - 0x79d059c8, 0xd8b04c52, - 0x79c89f6e, 0xd898620c, 0x79c0e062, 0xd880794b, 0x79b91ca4, 0xd868920f, - 0x79b15435, 0xd850ac5a, - 0x79a98715, 0xd838c82d, 0x79a1b545, 0xd820e589, 0x7999dec4, 0xd809046e, - 0x79920392, 0xd7f124dd, - 0x798a23b1, 0xd7d946d8, 0x79823f20, 0xd7c16a5f, 0x797a55e0, 0xd7a98f73, - 0x797267f2, 0xd791b616, - 0x796a7554, 0xd779de47, 0x79627e08, 0xd7620808, 0x795a820e, 0xd74a335b, - 0x79528167, 0xd732603f, - 0x794a7c12, 0xd71a8eb5, 0x79427210, 0xd702bec0, 0x793a6361, 0xd6eaf05f, - 0x79325006, 0xd6d32393, - 0x792a37fe, 0xd6bb585e, 0x79221b4b, 0xd6a38ec0, 0x7919f9ec, 0xd68bc6ba, - 0x7911d3e2, 0xd674004e, - 0x7909a92d, 0xd65c3b7b, 0x790179cd, 0xd6447844, 0x78f945c3, 0xd62cb6a8, - 0x78f10d0f, 0xd614f6a9, - 0x78e8cfb2, 0xd5fd3848, 0x78e08dab, 0xd5e57b85, 0x78d846fb, 0xd5cdc062, - 0x78cffba3, 0xd5b606e0, - 0x78c7aba2, 0xd59e4eff, 0x78bf56f9, 0xd58698c0, 0x78b6fda8, 0xd56ee424, - 0x78ae9fb0, 0xd557312d, - 0x78a63d11, 0xd53f7fda, 0x789dd5cb, 0xd527d02e, 0x789569df, 0xd5102228, - 0x788cf94c, 0xd4f875ca, - 0x78848414, 0xd4e0cb15, 0x787c0a36, 0xd4c92209, 0x78738bb3, 0xd4b17aa8, - 0x786b088c, 0xd499d4f2, - 0x786280bf, 0xd48230e9, 0x7859f44f, 0xd46a8e8d, 0x7851633b, 0xd452eddf, - 0x7848cd83, 0xd43b4ee0, - 0x78403329, 0xd423b191, 0x7837942b, 0xd40c15f3, 0x782ef08b, 0xd3f47c06, - 0x78264849, 0xd3dce3cd, - 0x781d9b65, 0xd3c54d47, 0x7814e9df, 0xd3adb876, 0x780c33b8, 0xd396255a, - 0x780378f1, 0xd37e93f4, - 0x77fab989, 0xd3670446, 0x77f1f581, 0xd34f764f, 0x77e92cd9, 0xd337ea12, - 0x77e05f91, 0xd3205f8f, - 0x77d78daa, 0xd308d6c7, 0x77ceb725, 0xd2f14fba, 0x77c5dc01, 0xd2d9ca6a, - 0x77bcfc3f, 0xd2c246d8, - 0x77b417df, 0xd2aac504, 0x77ab2ee2, 0xd29344f0, 0x77a24148, 0xd27bc69c, - 0x77994f11, 0xd2644a0a, - 0x7790583e, 0xd24ccf39, 0x77875cce, 0xd235562b, 0x777e5cc3, 0xd21ddee2, - 0x7775581d, 0xd206695d, - 0x776c4edb, 0xd1eef59e, 0x776340ff, 0xd1d783a6, 0x775a2e89, 0xd1c01375, - 0x77511778, 0xd1a8a50d, - 0x7747fbce, 0xd191386e, 0x773edb8b, 0xd179cd99, 0x7735b6af, 0xd1626490, - 0x772c8d3a, 0xd14afd52, - 0x77235f2d, 0xd13397e2, 0x771a2c88, 0xd11c343f, 0x7710f54c, 0xd104d26b, - 0x7707b979, 0xd0ed7267, - 0x76fe790e, 0xd0d61434, 0x76f5340e, 0xd0beb7d2, 0x76ebea77, 0xd0a75d42, - 0x76e29c4b, 0xd0900486, - 0x76d94989, 0xd078ad9e, 0x76cff232, 0xd061588b, 0x76c69647, 0xd04a054e, - 0x76bd35c7, 0xd032b3e7, - 0x76b3d0b4, 0xd01b6459, 0x76aa670d, 0xd00416a3, 0x76a0f8d2, 0xcfeccac7, - 0x76978605, 0xcfd580c6, - 0x768e0ea6, 0xcfbe389f, 0x768492b4, 0xcfa6f255, 0x767b1231, 0xcf8fade9, - 0x76718d1c, 0xcf786b5a, - 0x76680376, 0xcf612aaa, 0x765e7540, 0xcf49ebda, 0x7654e279, 0xcf32aeeb, - 0x764b4b23, 0xcf1b73de, - 0x7641af3d, 0xcf043ab3, 0x76380ec8, 0xceed036b, 0x762e69c4, 0xced5ce08, - 0x7624c031, 0xcebe9a8a, - 0x761b1211, 0xcea768f2, 0x76115f63, 0xce903942, 0x7607a828, 0xce790b79, - 0x75fdec60, 0xce61df99, - 0x75f42c0b, 0xce4ab5a2, 0x75ea672a, 0xce338d97, 0x75e09dbd, 0xce1c6777, - 0x75d6cfc5, 0xce054343, - 0x75ccfd42, 0xcdee20fc, 0x75c32634, 0xcdd700a4, 0x75b94a9c, 0xcdbfe23a, - 0x75af6a7b, 0xcda8c5c1, - 0x75a585cf, 0xcd91ab39, 0x759b9c9b, 0xcd7a92a2, 0x7591aedd, 0xcd637bfe, - 0x7587bc98, 0xcd4c674d, - 0x757dc5ca, 0xcd355491, 0x7573ca75, 0xcd1e43ca, 0x7569ca99, 0xcd0734f9, - 0x755fc635, 0xccf0281f, - 0x7555bd4c, 0xccd91d3d, 0x754bafdc, 0xccc21455, 0x75419de7, 0xccab0d65, - 0x7537876c, 0xcc940871, - 0x752d6c6c, 0xcc7d0578, 0x75234ce8, 0xcc66047b, 0x751928e0, 0xcc4f057c, - 0x750f0054, 0xcc38087b, - 0x7504d345, 0xcc210d79, 0x74faa1b3, 0xcc0a1477, 0x74f06b9e, 0xcbf31d75, - 0x74e63108, 0xcbdc2876, - 0x74dbf1ef, 0xcbc53579, 0x74d1ae55, 0xcbae447f, 0x74c7663a, 0xcb97558a, - 0x74bd199f, 0xcb80689a, - 0x74b2c884, 0xcb697db0, 0x74a872e8, 0xcb5294ce, 0x749e18cd, 0xcb3badf3, - 0x7493ba34, 0xcb24c921, - 0x7489571c, 0xcb0de658, 0x747eef85, 0xcaf7059a, 0x74748371, 0xcae026e8, - 0x746a12df, 0xcac94a42, - 0x745f9dd1, 0xcab26fa9, 0x74552446, 0xca9b971e, 0x744aa63f, 0xca84c0a3, - 0x744023bc, 0xca6dec37, - 0x74359cbd, 0xca5719db, 0x742b1144, 0xca404992, 0x74208150, 0xca297b5a, - 0x7415ece2, 0xca12af37, - 0x740b53fb, 0xc9fbe527, 0x7400b69a, 0xc9e51d2d, 0x73f614c0, 0xc9ce5748, - 0x73eb6e6e, 0xc9b7937a, - 0x73e0c3a3, 0xc9a0d1c5, 0x73d61461, 0xc98a1227, 0x73cb60a8, 0xc97354a4, - 0x73c0a878, 0xc95c993a, - 0x73b5ebd1, 0xc945dfec, 0x73ab2ab4, 0xc92f28ba, 0x73a06522, 0xc91873a5, - 0x73959b1b, 0xc901c0ae, - 0x738acc9e, 0xc8eb0fd6, 0x737ff9ae, 0xc8d4611d, 0x73752249, 0xc8bdb485, - 0x736a4671, 0xc8a70a0e, - 0x735f6626, 0xc89061ba, 0x73548168, 0xc879bb89, 0x73499838, 0xc863177b, - 0x733eaa96, 0xc84c7593, - 0x7333b883, 0xc835d5d0, 0x7328c1ff, 0xc81f3834, 0x731dc70a, 0xc8089cbf, - 0x7312c7a5, 0xc7f20373, - 0x7307c3d0, 0xc7db6c50, 0x72fcbb8c, 0xc7c4d757, 0x72f1aed9, 0xc7ae4489, - 0x72e69db7, 0xc797b3e7, - 0x72db8828, 0xc7812572, 0x72d06e2b, 0xc76a992a, 0x72c54fc1, 0xc7540f11, - 0x72ba2cea, 0xc73d8727, - 0x72af05a7, 0xc727016d, 0x72a3d9f7, 0xc7107de4, 0x7298a9dd, 0xc6f9fc8d, - 0x728d7557, 0xc6e37d69, - 0x72823c67, 0xc6cd0079, 0x7276ff0d, 0xc6b685bd, 0x726bbd48, 0xc6a00d37, - 0x7260771b, 0xc68996e7, - 0x72552c85, 0xc67322ce, 0x7249dd86, 0xc65cb0ed, 0x723e8a20, 0xc6464144, - 0x72333251, 0xc62fd3d6, - 0x7227d61c, 0xc61968a2, 0x721c7580, 0xc602ffaa, 0x7211107e, 0xc5ec98ee, - 0x7205a716, 0xc5d6346f, - 0x71fa3949, 0xc5bfd22e, 0x71eec716, 0xc5a9722c, 0x71e35080, 0xc593146a, - 0x71d7d585, 0xc57cb8e9, - 0x71cc5626, 0xc5665fa9, 0x71c0d265, 0xc55008ab, 0x71b54a41, 0xc539b3f1, - 0x71a9bdba, 0xc523617a, - 0x719e2cd2, 0xc50d1149, 0x71929789, 0xc4f6c35d, 0x7186fdde, 0xc4e077b8, - 0x717b5fd3, 0xc4ca2e5b, - 0x716fbd68, 0xc4b3e746, 0x7164169d, 0xc49da27a, 0x71586b74, 0xc4875ff9, - 0x714cbbeb, 0xc4711fc2, - 0x71410805, 0xc45ae1d7, 0x71354fc0, 0xc444a639, 0x7129931f, 0xc42e6ce8, - 0x711dd220, 0xc41835e6, - 0x71120cc5, 0xc4020133, 0x7106430e, 0xc3ebced0, 0x70fa74fc, 0xc3d59ebe, - 0x70eea28e, 0xc3bf70fd, - 0x70e2cbc6, 0xc3a94590, 0x70d6f0a4, 0xc3931c76, 0x70cb1128, 0xc37cf5b0, - 0x70bf2d53, 0xc366d140, - 0x70b34525, 0xc350af26, 0x70a7589f, 0xc33a8f62, 0x709b67c0, 0xc32471f7, - 0x708f728b, 0xc30e56e4, - 0x708378ff, 0xc2f83e2a, 0x70777b1c, 0xc2e227cb, 0x706b78e3, 0xc2cc13c7, - 0x705f7255, 0xc2b6021f, - 0x70536771, 0xc29ff2d4, 0x70475839, 0xc289e5e7, 0x703b44ad, 0xc273db58, - 0x702f2ccd, 0xc25dd329, - 0x7023109a, 0xc247cd5a, 0x7016f014, 0xc231c9ec, 0x700acb3c, 0xc21bc8e1, - 0x6ffea212, 0xc205ca38, - 0x6ff27497, 0xc1efcdf3, 0x6fe642ca, 0xc1d9d412, 0x6fda0cae, 0xc1c3dc97, - 0x6fcdd241, 0xc1ade781, - 0x6fc19385, 0xc197f4d4, 0x6fb5507a, 0xc182048d, 0x6fa90921, 0xc16c16b0, - 0x6f9cbd79, 0xc1562b3d, - 0x6f906d84, 0xc1404233, 0x6f841942, 0xc12a5b95, 0x6f77c0b3, 0xc1147764, - 0x6f6b63d8, 0xc0fe959f, - 0x6f5f02b2, 0xc0e8b648, 0x6f529d40, 0xc0d2d960, 0x6f463383, 0xc0bcfee7, - 0x6f39c57d, 0xc0a726df, - 0x6f2d532c, 0xc0915148, 0x6f20dc92, 0xc07b7e23, 0x6f1461b0, 0xc065ad70, - 0x6f07e285, 0xc04fdf32, - 0x6efb5f12, 0xc03a1368, 0x6eeed758, 0xc0244a14, 0x6ee24b57, 0xc00e8336, - 0x6ed5bb10, 0xbff8bece, - 0x6ec92683, 0xbfe2fcdf, 0x6ebc8db0, 0xbfcd3d69, 0x6eaff099, 0xbfb7806c, - 0x6ea34f3d, 0xbfa1c5ea, - 0x6e96a99d, 0xbf8c0de3, 0x6e89ffb9, 0xbf765858, 0x6e7d5193, 0xbf60a54a, - 0x6e709f2a, 0xbf4af4ba, - 0x6e63e87f, 0xbf3546a8, 0x6e572d93, 0xbf1f9b16, 0x6e4a6e66, 0xbf09f205, - 0x6e3daaf8, 0xbef44b74, - 0x6e30e34a, 0xbedea765, 0x6e24175c, 0xbec905d9, 0x6e174730, 0xbeb366d1, - 0x6e0a72c5, 0xbe9dca4e, - 0x6dfd9a1c, 0xbe88304f, 0x6df0bd35, 0xbe7298d7, 0x6de3dc11, 0xbe5d03e6, - 0x6dd6f6b1, 0xbe47717c, - 0x6dca0d14, 0xbe31e19b, 0x6dbd1f3c, 0xbe1c5444, 0x6db02d29, 0xbe06c977, - 0x6da336dc, 0xbdf14135, - 0x6d963c54, 0xbddbbb7f, 0x6d893d93, 0xbdc63856, 0x6d7c3a98, 0xbdb0b7bb, - 0x6d6f3365, 0xbd9b39ad, - 0x6d6227fa, 0xbd85be30, 0x6d551858, 0xbd704542, 0x6d48047e, 0xbd5acee5, - 0x6d3aec6e, 0xbd455b1a, - 0x6d2dd027, 0xbd2fe9e2, 0x6d20afac, 0xbd1a7b3d, 0x6d138afb, 0xbd050f2c, - 0x6d066215, 0xbcefa5b0, - 0x6cf934fc, 0xbcda3ecb, 0x6cec03af, 0xbcc4da7b, 0x6cdece2f, 0xbcaf78c4, - 0x6cd1947c, 0xbc9a19a5, - 0x6cc45698, 0xbc84bd1f, 0x6cb71482, 0xbc6f6333, 0x6ca9ce3b, 0xbc5a0be2, - 0x6c9c83c3, 0xbc44b72c, - 0x6c8f351c, 0xbc2f6513, 0x6c81e245, 0xbc1a1598, 0x6c748b3f, 0xbc04c8ba, - 0x6c67300b, 0xbbef7e7c, - 0x6c59d0a9, 0xbbda36dd, 0x6c4c6d1a, 0xbbc4f1df, 0x6c3f055d, 0xbbafaf82, - 0x6c319975, 0xbb9a6fc7, - 0x6c242960, 0xbb8532b0, 0x6c16b521, 0xbb6ff83c, 0x6c093cb6, 0xbb5ac06d, - 0x6bfbc021, 0xbb458b43, - 0x6bee3f62, 0xbb3058c0, 0x6be0ba7b, 0xbb1b28e4, 0x6bd3316a, 0xbb05fbb0, - 0x6bc5a431, 0xbaf0d125, - 0x6bb812d1, 0xbadba943, 0x6baa7d49, 0xbac6840c, 0x6b9ce39b, 0xbab16180, - 0x6b8f45c7, 0xba9c41a0, - 0x6b81a3cd, 0xba87246d, 0x6b73fdae, 0xba7209e7, 0x6b66536b, 0xba5cf210, - 0x6b58a503, 0xba47dce8, - 0x6b4af279, 0xba32ca71, 0x6b3d3bcb, 0xba1dbaaa, 0x6b2f80fb, 0xba08ad95, - 0x6b21c208, 0xb9f3a332, - 0x6b13fef5, 0xb9de9b83, 0x6b0637c1, 0xb9c99688, 0x6af86c6c, 0xb9b49442, - 0x6aea9cf8, 0xb99f94b2, - 0x6adcc964, 0xb98a97d8, 0x6acef1b2, 0xb9759db6, 0x6ac115e2, 0xb960a64c, - 0x6ab335f4, 0xb94bb19b, - 0x6aa551e9, 0xb936bfa4, 0x6a9769c1, 0xb921d067, 0x6a897d7d, 0xb90ce3e6, - 0x6a7b8d1e, 0xb8f7fa21, - 0x6a6d98a4, 0xb8e31319, 0x6a5fa010, 0xb8ce2ecf, 0x6a51a361, 0xb8b94d44, - 0x6a43a29a, 0xb8a46e78, - 0x6a359db9, 0xb88f926d, 0x6a2794c1, 0xb87ab922, 0x6a1987b0, 0xb865e299, - 0x6a0b7689, 0xb8510ed4, - 0x69fd614a, 0xb83c3dd1, 0x69ef47f6, 0xb8276f93, 0x69e12a8c, 0xb812a41a, - 0x69d3090e, 0xb7fddb67, - 0x69c4e37a, 0xb7e9157a, 0x69b6b9d3, 0xb7d45255, 0x69a88c19, 0xb7bf91f8, - 0x699a5a4c, 0xb7aad465, - 0x698c246c, 0xb796199b, 0x697dea7b, 0xb781619c, 0x696fac78, 0xb76cac69, - 0x69616a65, 0xb757fa01, - 0x69532442, 0xb7434a67, 0x6944da10, 0xb72e9d9b, 0x69368bce, 0xb719f39e, - 0x6928397e, 0xb7054c6f, - 0x6919e320, 0xb6f0a812, 0x690b88b5, 0xb6dc0685, 0x68fd2a3d, 0xb6c767ca, - 0x68eec7b9, 0xb6b2cbe2, - 0x68e06129, 0xb69e32cd, 0x68d1f68f, 0xb6899c8d, 0x68c387e9, 0xb6750921, - 0x68b5153a, 0xb660788c, - 0x68a69e81, 0xb64beacd, 0x689823bf, 0xb6375fe5, 0x6889a4f6, 0xb622d7d6, - 0x687b2224, 0xb60e529f, - 0x686c9b4b, 0xb5f9d043, 0x685e106c, 0xb5e550c1, 0x684f8186, 0xb5d0d41a, - 0x6840ee9b, 0xb5bc5a50, - 0x683257ab, 0xb5a7e362, 0x6823bcb7, 0xb5936f53, 0x68151dbe, 0xb57efe22, - 0x68067ac3, 0xb56a8fd0, - 0x67f7d3c5, 0xb556245e, 0x67e928c5, 0xb541bbcd, 0x67da79c3, 0xb52d561e, - 0x67cbc6c0, 0xb518f351, - 0x67bd0fbd, 0xb5049368, 0x67ae54ba, 0xb4f03663, 0x679f95b7, 0xb4dbdc42, - 0x6790d2b6, 0xb4c78507, - 0x67820bb7, 0xb4b330b3, 0x677340ba, 0xb49edf45, 0x676471c0, 0xb48a90c0, - 0x67559eca, 0xb4764523, - 0x6746c7d8, 0xb461fc70, 0x6737ecea, 0xb44db6a8, 0x67290e02, 0xb43973ca, - 0x671a2b20, 0xb42533d8, - 0x670b4444, 0xb410f6d3, 0x66fc596f, 0xb3fcbcbb, 0x66ed6aa1, 0xb3e88592, - 0x66de77dc, 0xb3d45157, - 0x66cf8120, 0xb3c0200c, 0x66c0866d, 0xb3abf1b2, 0x66b187c3, 0xb397c649, - 0x66a28524, 0xb3839dd3, - 0x66937e91, 0xb36f784f, 0x66847408, 0xb35b55bf, 0x6675658c, 0xb3473623, - 0x6666531d, 0xb333197c, - 0x66573cbb, 0xb31effcc, 0x66482267, 0xb30ae912, 0x66390422, 0xb2f6d550, - 0x6629e1ec, 0xb2e2c486, - 0x661abbc5, 0xb2ceb6b5, 0x660b91af, 0xb2baabde, 0x65fc63a9, 0xb2a6a402, - 0x65ed31b5, 0xb2929f21, - 0x65ddfbd3, 0xb27e9d3c, 0x65cec204, 0xb26a9e54, 0x65bf8447, 0xb256a26a, - 0x65b0429f, 0xb242a97e, - 0x65a0fd0b, 0xb22eb392, 0x6591b38c, 0xb21ac0a6, 0x65826622, 0xb206d0ba, - 0x657314cf, 0xb1f2e3d0, - 0x6563bf92, 0xb1def9e9, 0x6554666d, 0xb1cb1304, 0x6545095f, 0xb1b72f23, - 0x6535a86b, 0xb1a34e47, - 0x6526438f, 0xb18f7071, 0x6516dacd, 0xb17b95a0, 0x65076e25, 0xb167bdd7, - 0x64f7fd98, 0xb153e915, - 0x64e88926, 0xb140175b, 0x64d910d1, 0xb12c48ab, 0x64c99498, 0xb1187d05, - 0x64ba147d, 0xb104b46a, - 0x64aa907f, 0xb0f0eeda, 0x649b08a0, 0xb0dd2c56, 0x648b7ce0, 0xb0c96ce0, - 0x647bed3f, 0xb0b5b077, - 0x646c59bf, 0xb0a1f71d, 0x645cc260, 0xb08e40d2, 0x644d2722, 0xb07a8d97, - 0x643d8806, 0xb066dd6d, - 0x642de50d, 0xb0533055, 0x641e3e38, 0xb03f864f, 0x640e9386, 0xb02bdf5c, - 0x63fee4f8, 0xb0183b7d, - 0x63ef3290, 0xb0049ab3, 0x63df7c4d, 0xaff0fcfe, 0x63cfc231, 0xafdd625f, - 0x63c0043b, 0xafc9cad7, - 0x63b0426d, 0xafb63667, 0x63a07cc7, 0xafa2a50f, 0x6390b34a, 0xaf8f16d1, - 0x6380e5f6, 0xaf7b8bac, - 0x637114cc, 0xaf6803a2, 0x63613fcd, 0xaf547eb3, 0x635166f9, 0xaf40fce1, - 0x63418a50, 0xaf2d7e2b, - 0x6331a9d4, 0xaf1a0293, 0x6321c585, 0xaf068a1a, 0x6311dd64, 0xaef314c0, - 0x6301f171, 0xaedfa285, - 0x62f201ac, 0xaecc336c, 0x62e20e17, 0xaeb8c774, 0x62d216b3, 0xaea55e9e, - 0x62c21b7e, 0xae91f8eb, - 0x62b21c7b, 0xae7e965b, 0x62a219aa, 0xae6b36f0, 0x6292130c, 0xae57daab, - 0x628208a1, 0xae44818b, - 0x6271fa69, 0xae312b92, 0x6261e866, 0xae1dd8c0, 0x6251d298, 0xae0a8916, - 0x6241b8ff, 0xadf73c96, - 0x62319b9d, 0xade3f33e, 0x62217a72, 0xadd0ad12, 0x6211557e, 0xadbd6a10, - 0x62012cc2, 0xadaa2a3b, - 0x61f1003f, 0xad96ed92, 0x61e0cff5, 0xad83b416, 0x61d09be5, 0xad707dc8, - 0x61c06410, 0xad5d4aaa, - 0x61b02876, 0xad4a1aba, 0x619fe918, 0xad36edfc, 0x618fa5f7, 0xad23c46e, - 0x617f5f12, 0xad109e12, - 0x616f146c, 0xacfd7ae8, 0x615ec603, 0xacea5af2, 0x614e73da, 0xacd73e30, - 0x613e1df0, 0xacc424a3, - 0x612dc447, 0xacb10e4b, 0x611d66de, 0xac9dfb29, 0x610d05b7, 0xac8aeb3e, - 0x60fca0d2, 0xac77de8b, - 0x60ec3830, 0xac64d510, 0x60dbcbd1, 0xac51cecf, 0x60cb5bb7, 0xac3ecbc7, - 0x60bae7e1, 0xac2bcbfa, - 0x60aa7050, 0xac18cf69, 0x6099f505, 0xac05d613, 0x60897601, 0xabf2dffb, - 0x6078f344, 0xabdfed1f, - 0x60686ccf, 0xabccfd83, 0x6057e2a2, 0xabba1125, 0x604754bf, 0xaba72807, - 0x6036c325, 0xab944229, - 0x60262dd6, 0xab815f8d, 0x601594d1, 0xab6e8032, 0x6004f819, 0xab5ba41a, - 0x5ff457ad, 0xab48cb46, - 0x5fe3b38d, 0xab35f5b5, 0x5fd30bbc, 0xab23236a, 0x5fc26038, 0xab105464, - 0x5fb1b104, 0xaafd88a4, - 0x5fa0fe1f, 0xaaeac02c, 0x5f90478a, 0xaad7fafb, 0x5f7f8d46, 0xaac53912, - 0x5f6ecf53, 0xaab27a73, - 0x5f5e0db3, 0xaa9fbf1e, 0x5f4d4865, 0xaa8d0713, 0x5f3c7f6b, 0xaa7a5253, - 0x5f2bb2c5, 0xaa67a0e0, - 0x5f1ae274, 0xaa54f2ba, 0x5f0a0e77, 0xaa4247e1, 0x5ef936d1, 0xaa2fa056, - 0x5ee85b82, 0xaa1cfc1a, - 0x5ed77c8a, 0xaa0a5b2e, 0x5ec699e9, 0xa9f7bd92, 0x5eb5b3a2, 0xa9e52347, - 0x5ea4c9b3, 0xa9d28c4e, - 0x5e93dc1f, 0xa9bff8a8, 0x5e82eae5, 0xa9ad6855, 0x5e71f606, 0xa99adb56, - 0x5e60fd84, 0xa98851ac, - 0x5e50015d, 0xa975cb57, 0x5e3f0194, 0xa9634858, 0x5e2dfe29, 0xa950c8b0, - 0x5e1cf71c, 0xa93e4c5f, - 0x5e0bec6e, 0xa92bd367, 0x5dfade20, 0xa9195dc7, 0x5de9cc33, 0xa906eb82, - 0x5dd8b6a7, 0xa8f47c97, - 0x5dc79d7c, 0xa8e21106, 0x5db680b4, 0xa8cfa8d2, 0x5da5604f, 0xa8bd43fa, - 0x5d943c4e, 0xa8aae280, - 0x5d8314b1, 0xa8988463, 0x5d71e979, 0xa88629a5, 0x5d60baa7, 0xa873d246, - 0x5d4f883b, 0xa8617e48, - 0x5d3e5237, 0xa84f2daa, 0x5d2d189a, 0xa83ce06e, 0x5d1bdb65, 0xa82a9693, - 0x5d0a9a9a, 0xa818501c, - 0x5cf95638, 0xa8060d08, 0x5ce80e41, 0xa7f3cd59, 0x5cd6c2b5, 0xa7e1910f, - 0x5cc57394, 0xa7cf582a, - 0x5cb420e0, 0xa7bd22ac, 0x5ca2ca99, 0xa7aaf094, 0x5c9170bf, 0xa798c1e5, - 0x5c801354, 0xa786969e, - 0x5c6eb258, 0xa7746ec0, 0x5c5d4dcc, 0xa7624a4d, 0x5c4be5b0, 0xa7502943, - 0x5c3a7a05, 0xa73e0ba5, - 0x5c290acc, 0xa72bf174, 0x5c179806, 0xa719daae, 0x5c0621b2, 0xa707c757, - 0x5bf4a7d2, 0xa6f5b76d, - 0x5be32a67, 0xa6e3aaf2, 0x5bd1a971, 0xa6d1a1e7, 0x5bc024f0, 0xa6bf9c4b, - 0x5bae9ce7, 0xa6ad9a21, - 0x5b9d1154, 0xa69b9b68, 0x5b8b8239, 0xa689a022, 0x5b79ef96, 0xa677a84e, - 0x5b68596d, 0xa665b3ee, - 0x5b56bfbd, 0xa653c303, 0x5b452288, 0xa641d58c, 0x5b3381ce, 0xa62feb8b, - 0x5b21dd90, 0xa61e0501, - 0x5b1035cf, 0xa60c21ee, 0x5afe8a8b, 0xa5fa4252, 0x5aecdbc5, 0xa5e8662f, - 0x5adb297d, 0xa5d68d85, - 0x5ac973b5, 0xa5c4b855, 0x5ab7ba6c, 0xa5b2e6a0, 0x5aa5fda5, 0xa5a11866, - 0x5a943d5e, 0xa58f4da8, - 0x5a82799a, 0xa57d8666, 0x5a70b258, 0xa56bc2a2, 0x5a5ee79a, 0xa55a025b, - 0x5a4d1960, 0xa5484594, - 0x5a3b47ab, 0xa5368c4b, 0x5a29727b, 0xa524d683, 0x5a1799d1, 0xa513243b, - 0x5a05bdae, 0xa5017575, - 0x59f3de12, 0xa4efca31, 0x59e1faff, 0xa4de2270, 0x59d01475, 0xa4cc7e32, - 0x59be2a74, 0xa4badd78, - 0x59ac3cfd, 0xa4a94043, 0x599a4c12, 0xa497a693, 0x598857b2, 0xa486106a, - 0x59765fde, 0xa4747dc7, - 0x59646498, 0xa462eeac, 0x595265df, 0xa4516319, 0x594063b5, 0xa43fdb10, - 0x592e5e19, 0xa42e568f, - 0x591c550e, 0xa41cd599, 0x590a4893, 0xa40b582e, 0x58f838a9, 0xa3f9de4e, - 0x58e62552, 0xa3e867fa, - 0x58d40e8c, 0xa3d6f534, 0x58c1f45b, 0xa3c585fb, 0x58afd6bd, 0xa3b41a50, - 0x589db5b3, 0xa3a2b234, - 0x588b9140, 0xa3914da8, 0x58796962, 0xa37fecac, 0x58673e1b, 0xa36e8f41, - 0x58550f6c, 0xa35d3567, - 0x5842dd54, 0xa34bdf20, 0x5830a7d6, 0xa33a8c6c, 0x581e6ef1, 0xa3293d4b, - 0x580c32a7, 0xa317f1bf, - 0x57f9f2f8, 0xa306a9c8, 0x57e7afe4, 0xa2f56566, 0x57d5696d, 0xa2e4249b, - 0x57c31f92, 0xa2d2e766, - 0x57b0d256, 0xa2c1adc9, 0x579e81b8, 0xa2b077c5, 0x578c2dba, 0xa29f4559, - 0x5779d65b, 0xa28e1687, - 0x57677b9d, 0xa27ceb4f, 0x57551d80, 0xa26bc3b2, 0x5742bc06, 0xa25a9fb1, - 0x5730572e, 0xa2497f4c, - 0x571deefa, 0xa2386284, 0x570b8369, 0xa2274959, 0x56f9147e, 0xa21633cd, - 0x56e6a239, 0xa20521e0, - 0x56d42c99, 0xa1f41392, 0x56c1b3a1, 0xa1e308e4, 0x56af3750, 0xa1d201d7, - 0x569cb7a8, 0xa1c0fe6c, - 0x568a34a9, 0xa1affea3, 0x5677ae54, 0xa19f027c, 0x566524aa, 0xa18e09fa, - 0x565297ab, 0xa17d151b, - 0x56400758, 0xa16c23e1, 0x562d73b2, 0xa15b364d, 0x561adcb9, 0xa14a4c5e, - 0x5608426e, 0xa1396617, - 0x55f5a4d2, 0xa1288376, 0x55e303e6, 0xa117a47e, 0x55d05faa, 0xa106c92f, - 0x55bdb81f, 0xa0f5f189, - 0x55ab0d46, 0xa0e51d8c, 0x55985f20, 0xa0d44d3b, 0x5585adad, 0xa0c38095, - 0x5572f8ed, 0xa0b2b79b, - 0x556040e2, 0xa0a1f24d, 0x554d858d, 0xa09130ad, 0x553ac6ee, 0xa08072ba, - 0x55280505, 0xa06fb876, - 0x55153fd4, 0xa05f01e1, 0x5502775c, 0xa04e4efc, 0x54efab9c, 0xa03d9fc8, - 0x54dcdc96, 0xa02cf444, - 0x54ca0a4b, 0xa01c4c73, 0x54b734ba, 0xa00ba853, 0x54a45be6, 0x9ffb07e7, - 0x54917fce, 0x9fea6b2f, - 0x547ea073, 0x9fd9d22a, 0x546bbdd7, 0x9fc93cdb, 0x5458d7f9, 0x9fb8ab41, - 0x5445eedb, 0x9fa81d5e, - 0x5433027d, 0x9f979331, 0x542012e1, 0x9f870cbc, 0x540d2005, 0x9f7689ff, - 0x53fa29ed, 0x9f660afb, - 0x53e73097, 0x9f558fb0, 0x53d43406, 0x9f45181f, 0x53c13439, 0x9f34a449, - 0x53ae3131, 0x9f24342f, - 0x539b2af0, 0x9f13c7d0, 0x53882175, 0x9f035f2e, 0x537514c2, 0x9ef2fa49, - 0x536204d7, 0x9ee29922, - 0x534ef1b5, 0x9ed23bb9, 0x533bdb5d, 0x9ec1e210, 0x5328c1d0, 0x9eb18c26, - 0x5315a50e, 0x9ea139fd, - 0x53028518, 0x9e90eb94, 0x52ef61ee, 0x9e80a0ee, 0x52dc3b92, 0x9e705a09, - 0x52c91204, 0x9e6016e8, - 0x52b5e546, 0x9e4fd78a, 0x52a2b556, 0x9e3f9bf0, 0x528f8238, 0x9e2f641b, - 0x527c4bea, 0x9e1f300b, - 0x5269126e, 0x9e0effc1, 0x5255d5c5, 0x9dfed33e, 0x524295f0, 0x9deeaa82, - 0x522f52ee, 0x9dde858e, - 0x521c0cc2, 0x9dce6463, 0x5208c36a, 0x9dbe4701, 0x51f576ea, 0x9dae2d68, - 0x51e22740, 0x9d9e179a, - 0x51ced46e, 0x9d8e0597, 0x51bb7e75, 0x9d7df75f, 0x51a82555, 0x9d6decf4, - 0x5194c910, 0x9d5de656, - 0x518169a5, 0x9d4de385, 0x516e0715, 0x9d3de482, 0x515aa162, 0x9d2de94d, - 0x5147388c, 0x9d1df1e9, - 0x5133cc94, 0x9d0dfe54, 0x51205d7b, 0x9cfe0e8f, 0x510ceb40, 0x9cee229c, - 0x50f975e6, 0x9cde3a7b, - 0x50e5fd6d, 0x9cce562c, 0x50d281d5, 0x9cbe75b0, 0x50bf031f, 0x9cae9907, - 0x50ab814d, 0x9c9ec033, - 0x5097fc5e, 0x9c8eeb34, 0x50847454, 0x9c7f1a0a, 0x5070e92f, 0x9c6f4cb6, - 0x505d5af1, 0x9c5f8339, - 0x5049c999, 0x9c4fbd93, 0x50363529, 0x9c3ffbc5, 0x50229da1, 0x9c303dcf, - 0x500f0302, 0x9c2083b3, - 0x4ffb654d, 0x9c10cd70, 0x4fe7c483, 0x9c011b08, 0x4fd420a4, 0x9bf16c7a, - 0x4fc079b1, 0x9be1c1c8, - 0x4faccfab, 0x9bd21af3, 0x4f992293, 0x9bc277fa, 0x4f857269, 0x9bb2d8de, - 0x4f71bf2e, 0x9ba33da0, - 0x4f5e08e3, 0x9b93a641, 0x4f4a4f89, 0x9b8412c1, 0x4f369320, 0x9b748320, - 0x4f22d3aa, 0x9b64f760, - 0x4f0f1126, 0x9b556f81, 0x4efb4b96, 0x9b45eb83, 0x4ee782fb, 0x9b366b68, - 0x4ed3b755, 0x9b26ef2f, - 0x4ebfe8a5, 0x9b1776da, 0x4eac16eb, 0x9b080268, 0x4e984229, 0x9af891db, - 0x4e846a60, 0x9ae92533, - 0x4e708f8f, 0x9ad9bc71, 0x4e5cb1b9, 0x9aca5795, 0x4e48d0dd, 0x9abaf6a1, - 0x4e34ecfc, 0x9aab9993, - 0x4e210617, 0x9a9c406e, 0x4e0d1c30, 0x9a8ceb31, 0x4df92f46, 0x9a7d99de, - 0x4de53f5a, 0x9a6e4c74, - 0x4dd14c6e, 0x9a5f02f5, 0x4dbd5682, 0x9a4fbd61, 0x4da95d96, 0x9a407bb9, - 0x4d9561ac, 0x9a313dfc, - 0x4d8162c4, 0x9a22042d, 0x4d6d60df, 0x9a12ce4b, 0x4d595bfe, 0x9a039c57, - 0x4d455422, 0x99f46e51, - 0x4d31494b, 0x99e5443b, 0x4d1d3b7a, 0x99d61e14, 0x4d092ab0, 0x99c6fbde, - 0x4cf516ee, 0x99b7dd99, - 0x4ce10034, 0x99a8c345, 0x4ccce684, 0x9999ace3, 0x4cb8c9dd, 0x998a9a74, - 0x4ca4aa41, 0x997b8bf8, - 0x4c9087b1, 0x996c816f, 0x4c7c622d, 0x995d7adc, 0x4c6839b7, 0x994e783d, - 0x4c540e4e, 0x993f7993, - 0x4c3fdff4, 0x99307ee0, 0x4c2baea9, 0x99218824, 0x4c177a6e, 0x9912955f, - 0x4c034345, 0x9903a691, - 0x4bef092d, 0x98f4bbbc, 0x4bdacc28, 0x98e5d4e0, 0x4bc68c36, 0x98d6f1fe, - 0x4bb24958, 0x98c81316, - 0x4b9e0390, 0x98b93828, 0x4b89badd, 0x98aa6136, 0x4b756f40, 0x989b8e40, - 0x4b6120bb, 0x988cbf46, - 0x4b4ccf4d, 0x987df449, 0x4b387af9, 0x986f2d4a, 0x4b2423be, 0x98606a49, - 0x4b0fc99d, 0x9851ab46, - 0x4afb6c98, 0x9842f043, 0x4ae70caf, 0x98343940, 0x4ad2a9e2, 0x9825863d, - 0x4abe4433, 0x9816d73b, - 0x4aa9dba2, 0x98082c3b, 0x4a957030, 0x97f9853d, 0x4a8101de, 0x97eae242, - 0x4a6c90ad, 0x97dc4349, - 0x4a581c9e, 0x97cda855, 0x4a43a5b0, 0x97bf1165, 0x4a2f2be6, 0x97b07e7a, - 0x4a1aaf3f, 0x97a1ef94, - 0x4a062fbd, 0x979364b5, 0x49f1ad61, 0x9784dddc, 0x49dd282a, 0x97765b0a, - 0x49c8a01b, 0x9767dc41, - 0x49b41533, 0x9759617f, 0x499f8774, 0x974aeac6, 0x498af6df, 0x973c7817, - 0x49766373, 0x972e0971, - 0x4961cd33, 0x971f9ed7, 0x494d341e, 0x97113847, 0x49389836, 0x9702d5c3, - 0x4923f97b, 0x96f4774b, - 0x490f57ee, 0x96e61ce0, 0x48fab391, 0x96d7c682, 0x48e60c62, 0x96c97432, - 0x48d16265, 0x96bb25f0, - 0x48bcb599, 0x96acdbbe, 0x48a805ff, 0x969e959b, 0x48935397, 0x96905388, - 0x487e9e64, 0x96821585, - 0x4869e665, 0x9673db94, 0x48552b9b, 0x9665a5b4, 0x48406e08, 0x965773e7, - 0x482badab, 0x9649462d, - 0x4816ea86, 0x963b1c86, 0x48022499, 0x962cf6f2, 0x47ed5be6, 0x961ed574, - 0x47d8906d, 0x9610b80a, - 0x47c3c22f, 0x96029eb6, 0x47aef12c, 0x95f48977, 0x479a1d67, 0x95e67850, - 0x478546de, 0x95d86b3f, - 0x47706d93, 0x95ca6247, 0x475b9188, 0x95bc5d66, 0x4746b2bc, 0x95ae5c9f, - 0x4731d131, 0x95a05ff0, - 0x471cece7, 0x9592675c, 0x470805df, 0x958472e2, 0x46f31c1a, 0x95768283, - 0x46de2f99, 0x9568963f, - 0x46c9405c, 0x955aae17, 0x46b44e65, 0x954cca0c, 0x469f59b4, 0x953eea1e, - 0x468a624a, 0x95310e4e, - 0x46756828, 0x9523369c, 0x46606b4e, 0x95156308, 0x464b6bbe, 0x95079394, - 0x46366978, 0x94f9c83f, - 0x4621647d, 0x94ec010b, 0x460c5cce, 0x94de3df8, 0x45f7526b, 0x94d07f05, - 0x45e24556, 0x94c2c435, - 0x45cd358f, 0x94b50d87, 0x45b82318, 0x94a75afd, 0x45a30df0, 0x9499ac95, - 0x458df619, 0x948c0252, - 0x4578db93, 0x947e5c33, 0x4563be60, 0x9470ba39, 0x454e9e80, 0x94631c65, - 0x45397bf4, 0x945582b7, - 0x452456bd, 0x9447ed2f, 0x450f2edb, 0x943a5bcf, 0x44fa0450, 0x942cce96, - 0x44e4d71c, 0x941f4585, - 0x44cfa740, 0x9411c09e, 0x44ba74bd, 0x94043fdf, 0x44a53f93, 0x93f6c34a, - 0x449007c4, 0x93e94adf, - 0x447acd50, 0x93dbd6a0, 0x44659039, 0x93ce668b, 0x4450507e, 0x93c0faa3, - 0x443b0e21, 0x93b392e6, - 0x4425c923, 0x93a62f57, 0x44108184, 0x9398cff5, 0x43fb3746, 0x938b74c1, - 0x43e5ea68, 0x937e1dbb, - 0x43d09aed, 0x9370cae4, 0x43bb48d4, 0x93637c3d, 0x43a5f41e, 0x935631c5, - 0x43909ccd, 0x9348eb7e, - 0x437b42e1, 0x933ba968, 0x4365e65b, 0x932e6b84, 0x4350873c, 0x932131d1, - 0x433b2585, 0x9313fc51, - 0x4325c135, 0x9306cb04, 0x43105a50, 0x92f99deb, 0x42faf0d4, 0x92ec7505, - 0x42e584c3, 0x92df5054, - 0x42d0161e, 0x92d22fd9, 0x42baa4e6, 0x92c51392, 0x42a5311b, 0x92b7fb82, - 0x428fbabe, 0x92aae7a8, - 0x427a41d0, 0x929dd806, 0x4264c653, 0x9290cc9b, 0x424f4845, 0x9283c568, - 0x4239c7aa, 0x9276c26d, - 0x42244481, 0x9269c3ac, 0x420ebecb, 0x925cc924, 0x41f93689, 0x924fd2d7, - 0x41e3abbc, 0x9242e0c4, - 0x41ce1e65, 0x9235f2ec, 0x41b88e84, 0x9229094f, 0x41a2fc1a, 0x921c23ef, - 0x418d6729, 0x920f42cb, - 0x4177cfb1, 0x920265e4, 0x416235b2, 0x91f58d3b, 0x414c992f, 0x91e8b8d0, - 0x4136fa27, 0x91dbe8a4, - 0x4121589b, 0x91cf1cb6, 0x410bb48c, 0x91c25508, 0x40f60dfb, 0x91b5919a, - 0x40e064ea, 0x91a8d26d, - 0x40cab958, 0x919c1781, 0x40b50b46, 0x918f60d6, 0x409f5ab6, 0x9182ae6d, - 0x4089a7a8, 0x91760047, - 0x4073f21d, 0x91695663, 0x405e3a16, 0x915cb0c3, 0x40487f94, 0x91500f67, - 0x4032c297, 0x91437250, - 0x401d0321, 0x9136d97d, 0x40074132, 0x912a44f0, 0x3ff17cca, 0x911db4a9, - 0x3fdbb5ec, 0x911128a8, - 0x3fc5ec98, 0x9104a0ee, 0x3fb020ce, 0x90f81d7b, 0x3f9a5290, 0x90eb9e50, - 0x3f8481dd, 0x90df236e, - 0x3f6eaeb8, 0x90d2acd4, 0x3f58d921, 0x90c63a83, 0x3f430119, 0x90b9cc7d, - 0x3f2d26a0, 0x90ad62c0, - 0x3f1749b8, 0x90a0fd4e, 0x3f016a61, 0x90949c28, 0x3eeb889c, 0x90883f4d, - 0x3ed5a46b, 0x907be6be, - 0x3ebfbdcd, 0x906f927c, 0x3ea9d4c3, 0x90634287, 0x3e93e950, 0x9056f6df, - 0x3e7dfb73, 0x904aaf86, - 0x3e680b2c, 0x903e6c7b, 0x3e52187f, 0x90322dbf, 0x3e3c2369, 0x9025f352, - 0x3e262bee, 0x9019bd36, - 0x3e10320d, 0x900d8b69, 0x3dfa35c8, 0x90015dee, 0x3de4371f, 0x8ff534c4, - 0x3dce3614, 0x8fe90fec, - 0x3db832a6, 0x8fdcef66, 0x3da22cd7, 0x8fd0d333, 0x3d8c24a8, 0x8fc4bb53, - 0x3d761a19, 0x8fb8a7c7, - 0x3d600d2c, 0x8fac988f, 0x3d49fde1, 0x8fa08dab, 0x3d33ec39, 0x8f94871d, - 0x3d1dd835, 0x8f8884e4, - 0x3d07c1d6, 0x8f7c8701, 0x3cf1a91c, 0x8f708d75, 0x3cdb8e09, 0x8f649840, - 0x3cc5709e, 0x8f58a761, - 0x3caf50da, 0x8f4cbadb, 0x3c992ec0, 0x8f40d2ad, 0x3c830a50, 0x8f34eed8, - 0x3c6ce38a, 0x8f290f5c, - 0x3c56ba70, 0x8f1d343a, 0x3c408f03, 0x8f115d72, 0x3c2a6142, 0x8f058b04, - 0x3c143130, 0x8ef9bcf2, - 0x3bfdfecd, 0x8eedf33b, 0x3be7ca1a, 0x8ee22de0, 0x3bd19318, 0x8ed66ce1, - 0x3bbb59c7, 0x8ecab040, - 0x3ba51e29, 0x8ebef7fb, 0x3b8ee03e, 0x8eb34415, 0x3b78a007, 0x8ea7948c, - 0x3b625d86, 0x8e9be963, - 0x3b4c18ba, 0x8e904298, 0x3b35d1a5, 0x8e84a02d, 0x3b1f8848, 0x8e790222, - 0x3b093ca3, 0x8e6d6877, - 0x3af2eeb7, 0x8e61d32e, 0x3adc9e86, 0x8e564246, 0x3ac64c0f, 0x8e4ab5bf, - 0x3aaff755, 0x8e3f2d9b, - 0x3a99a057, 0x8e33a9da, 0x3a834717, 0x8e282a7b, 0x3a6ceb96, 0x8e1caf80, - 0x3a568dd4, 0x8e1138ea, - 0x3a402dd2, 0x8e05c6b7, 0x3a29cb91, 0x8dfa58ea, 0x3a136712, 0x8deeef82, - 0x39fd0056, 0x8de38a80, - 0x39e6975e, 0x8dd829e4, 0x39d02c2a, 0x8dcccdaf, 0x39b9bebc, 0x8dc175e0, - 0x39a34f13, 0x8db6227a, - 0x398cdd32, 0x8daad37b, 0x39766919, 0x8d9f88e5, 0x395ff2c9, 0x8d9442b8, - 0x39497a43, 0x8d8900f3, - 0x3932ff87, 0x8d7dc399, 0x391c8297, 0x8d728aa9, 0x39060373, 0x8d675623, - 0x38ef821c, 0x8d5c2609, - 0x38d8fe93, 0x8d50fa59, 0x38c278d9, 0x8d45d316, 0x38abf0ef, 0x8d3ab03f, - 0x389566d6, 0x8d2f91d5, - 0x387eda8e, 0x8d2477d8, 0x38684c19, 0x8d196249, 0x3851bb77, 0x8d0e5127, - 0x383b28a9, 0x8d034474, - 0x382493b0, 0x8cf83c30, 0x380dfc8d, 0x8ced385b, 0x37f76341, 0x8ce238f6, - 0x37e0c7cc, 0x8cd73e01, - 0x37ca2a30, 0x8ccc477d, 0x37b38a6d, 0x8cc1556a, 0x379ce885, 0x8cb667c8, - 0x37864477, 0x8cab7e98, - 0x376f9e46, 0x8ca099da, 0x3758f5f2, 0x8c95b98f, 0x37424b7b, 0x8c8addb7, - 0x372b9ee3, 0x8c800652, - 0x3714f02a, 0x8c753362, 0x36fe3f52, 0x8c6a64e5, 0x36e78c5b, 0x8c5f9ade, - 0x36d0d746, 0x8c54d54c, - 0x36ba2014, 0x8c4a142f, 0x36a366c6, 0x8c3f5788, 0x368cab5c, 0x8c349f58, - 0x3675edd9, 0x8c29eb9f, - 0x365f2e3b, 0x8c1f3c5d, 0x36486c86, 0x8c149192, 0x3631a8b8, 0x8c09eb40, - 0x361ae2d3, 0x8bff4966, - 0x36041ad9, 0x8bf4ac05, 0x35ed50c9, 0x8bea131e, 0x35d684a6, 0x8bdf7eb0, - 0x35bfb66e, 0x8bd4eebc, - 0x35a8e625, 0x8bca6343, 0x359213c9, 0x8bbfdc44, 0x357b3f5d, 0x8bb559c1, - 0x356468e2, 0x8baadbba, - 0x354d9057, 0x8ba0622f, 0x3536b5be, 0x8b95ed21, 0x351fd918, 0x8b8b7c8f, - 0x3508fa66, 0x8b81107b, - 0x34f219a8, 0x8b76a8e4, 0x34db36df, 0x8b6c45cc, 0x34c4520d, 0x8b61e733, - 0x34ad6b32, 0x8b578d18, - 0x34968250, 0x8b4d377c, 0x347f9766, 0x8b42e661, 0x3468aa76, 0x8b3899c6, - 0x3451bb81, 0x8b2e51ab, - 0x343aca87, 0x8b240e11, 0x3423d78a, 0x8b19cef8, 0x340ce28b, 0x8b0f9462, - 0x33f5eb89, 0x8b055e4d, - 0x33def287, 0x8afb2cbb, 0x33c7f785, 0x8af0ffac, 0x33b0fa84, 0x8ae6d720, - 0x3399fb85, 0x8adcb318, - 0x3382fa88, 0x8ad29394, 0x336bf78f, 0x8ac87894, 0x3354f29b, 0x8abe6219, - 0x333debab, 0x8ab45024, - 0x3326e2c3, 0x8aaa42b4, 0x330fd7e1, 0x8aa039cb, 0x32f8cb07, 0x8a963567, - 0x32e1bc36, 0x8a8c358b, - 0x32caab6f, 0x8a823a36, 0x32b398b3, 0x8a784368, 0x329c8402, 0x8a6e5123, - 0x32856d5e, 0x8a646365, - 0x326e54c7, 0x8a5a7a31, 0x32573a3f, 0x8a509585, 0x32401dc6, 0x8a46b564, - 0x3228ff5c, 0x8a3cd9cc, - 0x3211df04, 0x8a3302be, 0x31fabcbd, 0x8a29303b, 0x31e39889, 0x8a1f6243, - 0x31cc7269, 0x8a1598d6, - 0x31b54a5e, 0x8a0bd3f5, 0x319e2067, 0x8a0213a0, 0x3186f487, 0x89f857d8, - 0x316fc6be, 0x89eea09d, - 0x3158970e, 0x89e4edef, 0x31416576, 0x89db3fcf, 0x312a31f8, 0x89d1963c, - 0x3112fc95, 0x89c7f138, - 0x30fbc54d, 0x89be50c3, 0x30e48c22, 0x89b4b4dd, 0x30cd5115, 0x89ab1d87, - 0x30b61426, 0x89a18ac0, - 0x309ed556, 0x8997fc8a, 0x308794a6, 0x898e72e4, 0x30705217, 0x8984edcf, - 0x30590dab, 0x897b6d4c, - 0x3041c761, 0x8971f15a, 0x302a7f3a, 0x896879fb, 0x30133539, 0x895f072e, - 0x2ffbe95d, 0x895598f3, - 0x2fe49ba7, 0x894c2f4c, 0x2fcd4c19, 0x8942ca39, 0x2fb5fab2, 0x893969b9, - 0x2f9ea775, 0x89300dce, - 0x2f875262, 0x8926b677, 0x2f6ffb7a, 0x891d63b5, 0x2f58a2be, 0x89141589, - 0x2f41482e, 0x890acbf2, - 0x2f29ebcc, 0x890186f2, 0x2f128d99, 0x88f84687, 0x2efb2d95, 0x88ef0ab4, - 0x2ee3cbc1, 0x88e5d378, - 0x2ecc681e, 0x88dca0d3, 0x2eb502ae, 0x88d372c6, 0x2e9d9b70, 0x88ca4951, - 0x2e863267, 0x88c12475, - 0x2e6ec792, 0x88b80432, 0x2e575af3, 0x88aee888, 0x2e3fec8b, 0x88a5d177, - 0x2e287c5a, 0x889cbf01, - 0x2e110a62, 0x8893b125, 0x2df996a3, 0x888aa7e3, 0x2de2211e, 0x8881a33d, - 0x2dcaa9d5, 0x8878a332, - 0x2db330c7, 0x886fa7c2, 0x2d9bb5f6, 0x8866b0ef, 0x2d843964, 0x885dbeb8, - 0x2d6cbb10, 0x8854d11e, - 0x2d553afc, 0x884be821, 0x2d3db928, 0x884303c1, 0x2d263596, 0x883a23ff, - 0x2d0eb046, 0x883148db, - 0x2cf72939, 0x88287256, 0x2cdfa071, 0x881fa06f, 0x2cc815ee, 0x8816d327, - 0x2cb089b1, 0x880e0a7f, - 0x2c98fbba, 0x88054677, 0x2c816c0c, 0x87fc870f, 0x2c69daa6, 0x87f3cc48, - 0x2c52478a, 0x87eb1621, - 0x2c3ab2b9, 0x87e2649b, 0x2c231c33, 0x87d9b7b7, 0x2c0b83fa, 0x87d10f75, - 0x2bf3ea0d, 0x87c86bd5, - 0x2bdc4e6f, 0x87bfccd7, 0x2bc4b120, 0x87b7327d, 0x2bad1221, 0x87ae9cc5, - 0x2b957173, 0x87a60bb1, - 0x2b7dcf17, 0x879d7f41, 0x2b662b0e, 0x8794f774, 0x2b4e8558, 0x878c744d, - 0x2b36ddf7, 0x8783f5ca, - 0x2b1f34eb, 0x877b7bec, 0x2b078a36, 0x877306b4, 0x2aefddd8, 0x876a9621, - 0x2ad82fd2, 0x87622a35, - 0x2ac08026, 0x8759c2ef, 0x2aa8ced3, 0x87516050, 0x2a911bdc, 0x87490258, - 0x2a796740, 0x8740a907, - 0x2a61b101, 0x8738545e, 0x2a49f920, 0x8730045d, 0x2a323f9e, 0x8727b905, - 0x2a1a847b, 0x871f7255, - 0x2a02c7b8, 0x8717304e, 0x29eb0957, 0x870ef2f1, 0x29d34958, 0x8706ba3d, - 0x29bb87bc, 0x86fe8633, - 0x29a3c485, 0x86f656d3, 0x298bffb2, 0x86ee2c1e, 0x29743946, 0x86e60614, - 0x295c7140, 0x86dde4b5, - 0x2944a7a2, 0x86d5c802, 0x292cdc6d, 0x86cdaffa, 0x29150fa1, 0x86c59c9f, - 0x28fd4140, 0x86bd8df0, - 0x28e5714b, 0x86b583ee, 0x28cd9fc1, 0x86ad7e99, 0x28b5cca5, 0x86a57df2, - 0x289df7f8, 0x869d81f8, - 0x288621b9, 0x86958aac, 0x286e49ea, 0x868d980e, 0x2856708d, 0x8685aa20, - 0x283e95a1, 0x867dc0e0, - 0x2826b928, 0x8675dc4f, 0x280edb23, 0x866dfc6e, 0x27f6fb92, 0x8666213c, - 0x27df1a77, 0x865e4abb, - 0x27c737d3, 0x865678eb, 0x27af53a6, 0x864eabcb, 0x27976df1, 0x8646e35c, - 0x277f86b5, 0x863f1f9e, - 0x27679df4, 0x86376092, 0x274fb3ae, 0x862fa638, 0x2737c7e3, 0x8627f091, - 0x271fda96, 0x86203f9c, - 0x2707ebc7, 0x86189359, 0x26effb76, 0x8610ebca, 0x26d809a5, 0x860948ef, - 0x26c01655, 0x8601aac7, - 0x26a82186, 0x85fa1153, 0x26902b39, 0x85f27c93, 0x26783370, 0x85eaec88, - 0x26603a2c, 0x85e36132, - 0x26483f6c, 0x85dbda91, 0x26304333, 0x85d458a6, 0x26184581, 0x85ccdb70, - 0x26004657, 0x85c562f1, - 0x25e845b6, 0x85bdef28, 0x25d0439f, 0x85b68015, 0x25b84012, 0x85af15b9, - 0x25a03b11, 0x85a7b015, - 0x2588349d, 0x85a04f28, 0x25702cb7, 0x8598f2f3, 0x2558235f, 0x85919b76, - 0x25401896, 0x858a48b1, - 0x25280c5e, 0x8582faa5, 0x250ffeb7, 0x857bb152, 0x24f7efa2, 0x85746cb8, - 0x24dfdf20, 0x856d2cd7, - 0x24c7cd33, 0x8565f1b0, 0x24afb9da, 0x855ebb44, 0x2497a517, 0x85578991, - 0x247f8eec, 0x85505c99, - 0x24677758, 0x8549345c, 0x244f5e5c, 0x854210db, 0x243743fa, 0x853af214, - 0x241f2833, 0x8533d809, - 0x24070b08, 0x852cc2bb, 0x23eeec78, 0x8525b228, 0x23d6cc87, 0x851ea652, - 0x23beab33, 0x85179f39, - 0x23a6887f, 0x85109cdd, 0x238e646a, 0x85099f3e, 0x23763ef7, 0x8502a65c, - 0x235e1826, 0x84fbb239, - 0x2345eff8, 0x84f4c2d4, 0x232dc66d, 0x84edd82d, 0x23159b88, 0x84e6f244, - 0x22fd6f48, 0x84e0111b, - 0x22e541af, 0x84d934b1, 0x22cd12bd, 0x84d25d06, 0x22b4e274, 0x84cb8a1b, - 0x229cb0d5, 0x84c4bbf0, - 0x22847de0, 0x84bdf286, 0x226c4996, 0x84b72ddb, 0x225413f8, 0x84b06df2, - 0x223bdd08, 0x84a9b2ca, - 0x2223a4c5, 0x84a2fc62, 0x220b6b32, 0x849c4abd, 0x21f3304f, 0x84959dd9, - 0x21daf41d, 0x848ef5b7, - 0x21c2b69c, 0x84885258, 0x21aa77cf, 0x8481b3bb, 0x219237b5, 0x847b19e1, - 0x2179f64f, 0x847484ca, - 0x2161b3a0, 0x846df477, 0x21496fa7, 0x846768e7, 0x21312a65, 0x8460e21a, - 0x2118e3dc, 0x845a6012, - 0x21009c0c, 0x8453e2cf, 0x20e852f6, 0x844d6a50, 0x20d0089c, 0x8446f695, - 0x20b7bcfe, 0x844087a0, - 0x209f701c, 0x843a1d70, 0x208721f9, 0x8433b806, 0x206ed295, 0x842d5762, - 0x205681f1, 0x8426fb84, - 0x203e300d, 0x8420a46c, 0x2025dcec, 0x841a521a, 0x200d888d, 0x84140490, - 0x1ff532f2, 0x840dbbcc, - 0x1fdcdc1b, 0x840777d0, 0x1fc4840a, 0x8401389b, 0x1fac2abf, 0x83fafe2e, - 0x1f93d03c, 0x83f4c889, - 0x1f7b7481, 0x83ee97ad, 0x1f63178f, 0x83e86b99, 0x1f4ab968, 0x83e2444d, - 0x1f325a0b, 0x83dc21cb, - 0x1f19f97b, 0x83d60412, 0x1f0197b8, 0x83cfeb22, 0x1ee934c3, 0x83c9d6fc, - 0x1ed0d09d, 0x83c3c7a0, - 0x1eb86b46, 0x83bdbd0e, 0x1ea004c1, 0x83b7b746, 0x1e879d0d, 0x83b1b649, - 0x1e6f342c, 0x83abba17, - 0x1e56ca1e, 0x83a5c2b0, 0x1e3e5ee5, 0x839fd014, 0x1e25f282, 0x8399e244, - 0x1e0d84f5, 0x8393f940, - 0x1df5163f, 0x838e1507, 0x1ddca662, 0x8388359b, 0x1dc4355e, 0x83825afb, - 0x1dabc334, 0x837c8528, - 0x1d934fe5, 0x8376b422, 0x1d7adb73, 0x8370e7e9, 0x1d6265dd, 0x836b207d, - 0x1d49ef26, 0x83655ddf, - 0x1d31774d, 0x835fa00f, 0x1d18fe54, 0x8359e70d, 0x1d00843d, 0x835432d8, - 0x1ce80906, 0x834e8373, - 0x1ccf8cb3, 0x8348d8dc, 0x1cb70f43, 0x83433314, 0x1c9e90b8, 0x833d921b, - 0x1c861113, 0x8337f5f1, - 0x1c6d9053, 0x83325e97, 0x1c550e7c, 0x832ccc0d, 0x1c3c8b8c, 0x83273e52, - 0x1c240786, 0x8321b568, - 0x1c0b826a, 0x831c314e, 0x1bf2fc3a, 0x8316b205, 0x1bda74f6, 0x8311378d, - 0x1bc1ec9e, 0x830bc1e6, - 0x1ba96335, 0x83065110, 0x1b90d8bb, 0x8300e50b, 0x1b784d30, 0x82fb7dd8, - 0x1b5fc097, 0x82f61b77, - 0x1b4732ef, 0x82f0bde8, 0x1b2ea43a, 0x82eb652b, 0x1b161479, 0x82e61141, - 0x1afd83ad, 0x82e0c22a, - 0x1ae4f1d6, 0x82db77e5, 0x1acc5ef6, 0x82d63274, 0x1ab3cb0d, 0x82d0f1d5, - 0x1a9b361d, 0x82cbb60b, - 0x1a82a026, 0x82c67f14, 0x1a6a0929, 0x82c14cf1, 0x1a517128, 0x82bc1fa2, - 0x1a38d823, 0x82b6f727, - 0x1a203e1b, 0x82b1d381, 0x1a07a311, 0x82acb4b0, 0x19ef0707, 0x82a79ab3, - 0x19d669fc, 0x82a2858c, - 0x19bdcbf3, 0x829d753a, 0x19a52ceb, 0x829869be, 0x198c8ce7, 0x82936317, - 0x1973ebe6, 0x828e6146, - 0x195b49ea, 0x8289644b, 0x1942a6f3, 0x82846c26, 0x192a0304, 0x827f78d8, - 0x19115e1c, 0x827a8a61, - 0x18f8b83c, 0x8275a0c0, 0x18e01167, 0x8270bbf7, 0x18c7699b, 0x826bdc04, - 0x18aec0db, 0x826700e9, - 0x18961728, 0x82622aa6, 0x187d6c82, 0x825d593a, 0x1864c0ea, 0x82588ca7, - 0x184c1461, 0x8253c4eb, - 0x183366e9, 0x824f0208, 0x181ab881, 0x824a43fe, 0x1802092c, 0x82458acc, - 0x17e958ea, 0x8240d673, - 0x17d0a7bc, 0x823c26f3, 0x17b7f5a3, 0x82377c4c, 0x179f429f, 0x8232d67f, - 0x17868eb3, 0x822e358b, - 0x176dd9de, 0x82299971, 0x17552422, 0x82250232, 0x173c6d80, 0x82206fcc, - 0x1723b5f9, 0x821be240, - 0x170afd8d, 0x82175990, 0x16f2443e, 0x8212d5b9, 0x16d98a0c, 0x820e56be, - 0x16c0cef9, 0x8209dc9e, - 0x16a81305, 0x82056758, 0x168f5632, 0x8200f6ef, 0x1676987f, 0x81fc8b60, - 0x165dd9f0, 0x81f824ae, - 0x16451a83, 0x81f3c2d7, 0x162c5a3b, 0x81ef65dc, 0x16139918, 0x81eb0dbe, - 0x15fad71b, 0x81e6ba7c, - 0x15e21445, 0x81e26c16, 0x15c95097, 0x81de228d, 0x15b08c12, 0x81d9dde1, - 0x1597c6b7, 0x81d59e13, - 0x157f0086, 0x81d16321, 0x15663982, 0x81cd2d0c, 0x154d71aa, 0x81c8fbd6, - 0x1534a901, 0x81c4cf7d, - 0x151bdf86, 0x81c0a801, 0x1503153a, 0x81bc8564, 0x14ea4a1f, 0x81b867a5, - 0x14d17e36, 0x81b44ec4, - 0x14b8b17f, 0x81b03ac2, 0x149fe3fc, 0x81ac2b9e, 0x148715ae, 0x81a82159, - 0x146e4694, 0x81a41bf4, - 0x145576b1, 0x81a01b6d, 0x143ca605, 0x819c1fc5, 0x1423d492, 0x819828fd, - 0x140b0258, 0x81943715, - 0x13f22f58, 0x81904a0c, 0x13d95b93, 0x818c61e3, 0x13c0870a, 0x81887e9a, - 0x13a7b1bf, 0x8184a032, - 0x138edbb1, 0x8180c6a9, 0x137604e2, 0x817cf201, 0x135d2d53, 0x8179223a, - 0x13445505, 0x81755754, - 0x132b7bf9, 0x8171914e, 0x1312a230, 0x816dd02a, 0x12f9c7aa, 0x816a13e6, - 0x12e0ec6a, 0x81665c84, - 0x12c8106f, 0x8162aa04, 0x12af33ba, 0x815efc65, 0x1296564d, 0x815b53a8, - 0x127d7829, 0x8157afcd, - 0x1264994e, 0x815410d4, 0x124bb9be, 0x815076bd, 0x1232d979, 0x814ce188, - 0x1219f880, 0x81495136, - 0x120116d5, 0x8145c5c7, 0x11e83478, 0x81423f3a, 0x11cf516a, 0x813ebd90, - 0x11b66dad, 0x813b40ca, - 0x119d8941, 0x8137c8e6, 0x1184a427, 0x813455e6, 0x116bbe60, 0x8130e7c9, - 0x1152d7ed, 0x812d7e8f, - 0x1139f0cf, 0x812a1a3a, 0x11210907, 0x8126bac8, 0x11082096, 0x8123603a, - 0x10ef377d, 0x81200a90, - 0x10d64dbd, 0x811cb9ca, 0x10bd6356, 0x81196de9, 0x10a4784b, 0x811626ec, - 0x108b8c9b, 0x8112e4d4, - 0x1072a048, 0x810fa7a0, 0x1059b352, 0x810c6f52, 0x1040c5bb, 0x81093be8, - 0x1027d784, 0x81060d63, - 0x100ee8ad, 0x8102e3c4, 0xff5f938, 0x80ffbf0a, 0xfdd0926, 0x80fc9f35, - 0xfc41876, 0x80f98446, - 0xfab272b, 0x80f66e3c, 0xf923546, 0x80f35d19, 0xf7942c7, 0x80f050db, - 0xf604faf, 0x80ed4984, - 0xf475bff, 0x80ea4712, 0xf2e67b8, 0x80e74987, 0xf1572dc, 0x80e450e2, - 0xefc7d6b, 0x80e15d24, - 0xee38766, 0x80de6e4c, 0xeca90ce, 0x80db845b, 0xeb199a4, 0x80d89f51, - 0xe98a1e9, 0x80d5bf2e, - 0xe7fa99e, 0x80d2e3f2, 0xe66b0c3, 0x80d00d9d, 0xe4db75b, 0x80cd3c2f, - 0xe34bd66, 0x80ca6fa9, - 0xe1bc2e4, 0x80c7a80a, 0xe02c7d7, 0x80c4e553, 0xde9cc40, 0x80c22784, - 0xdd0d01f, 0x80bf6e9c, - 0xdb7d376, 0x80bcba9d, 0xd9ed646, 0x80ba0b85, 0xd85d88f, 0x80b76156, - 0xd6cda53, 0x80b4bc0e, - 0xd53db92, 0x80b21baf, 0xd3adc4e, 0x80af8039, 0xd21dc87, 0x80ace9ab, - 0xd08dc3f, 0x80aa5806, - 0xcefdb76, 0x80a7cb49, 0xcd6da2d, 0x80a54376, 0xcbdd865, 0x80a2c08b, - 0xca4d620, 0x80a04289, - 0xc8bd35e, 0x809dc971, 0xc72d020, 0x809b5541, 0xc59cc68, 0x8098e5fb, - 0xc40c835, 0x80967b9f, - 0xc27c389, 0x8094162c, 0xc0ebe66, 0x8091b5a2, 0xbf5b8cb, 0x808f5a02, - 0xbdcb2bb, 0x808d034c, - 0xbc3ac35, 0x808ab180, 0xbaaa53b, 0x8088649e, 0xb919dcf, 0x80861ca6, - 0xb7895f0, 0x8083d998, - 0xb5f8d9f, 0x80819b74, 0xb4684df, 0x807f623b, 0xb2d7baf, 0x807d2dec, - 0xb147211, 0x807afe87, - 0xafb6805, 0x8078d40d, 0xae25d8d, 0x8076ae7e, 0xac952aa, 0x80748dd9, - 0xab0475c, 0x8072721f, - 0xa973ba5, 0x80705b50, 0xa7e2f85, 0x806e496c, 0xa6522fe, 0x806c3c74, - 0xa4c1610, 0x806a3466, - 0xa3308bd, 0x80683143, 0xa19fb04, 0x8066330c, 0xa00ece8, 0x806439c0, - 0x9e7de6a, 0x80624560, - 0x9cecf89, 0x806055eb, 0x9b5c048, 0x805e6b62, 0x99cb0a7, 0x805c85c4, - 0x983a0a7, 0x805aa512, - 0x96a9049, 0x8058c94c, 0x9517f8f, 0x8056f272, 0x9386e78, 0x80552084, - 0x91f5d06, 0x80535381, - 0x9064b3a, 0x80518b6b, 0x8ed3916, 0x804fc841, 0x8d42699, 0x804e0a04, - 0x8bb13c5, 0x804c50b2, - 0x8a2009a, 0x804a9c4d, 0x888ed1b, 0x8048ecd5, 0x86fd947, 0x80474248, - 0x856c520, 0x80459ca9, - 0x83db0a7, 0x8043fbf6, 0x8249bdd, 0x80426030, 0x80b86c2, 0x8040c956, - 0x7f27157, 0x803f376a, - 0x7d95b9e, 0x803daa6a, 0x7c04598, 0x803c2257, 0x7a72f45, 0x803a9f31, - 0x78e18a7, 0x803920f8, - 0x77501be, 0x8037a7ac, 0x75bea8c, 0x8036334e, 0x742d311, 0x8034c3dd, - 0x729bb4e, 0x80335959, - 0x710a345, 0x8031f3c2, 0x6f78af6, 0x80309318, 0x6de7262, 0x802f375d, - 0x6c5598a, 0x802de08e, - 0x6ac406f, 0x802c8ead, 0x6932713, 0x802b41ba, 0x67a0d76, 0x8029f9b4, - 0x660f398, 0x8028b69c, - 0x647d97c, 0x80277872, 0x62ebf22, 0x80263f36, 0x615a48b, 0x80250ae7, - 0x5fc89b8, 0x8023db86, - 0x5e36ea9, 0x8022b114, 0x5ca5361, 0x80218b8f, 0x5b137df, 0x80206af8, - 0x5981c26, 0x801f4f4f, - 0x57f0035, 0x801e3895, 0x565e40d, 0x801d26c8, 0x54cc7b1, 0x801c19ea, - 0x533ab20, 0x801b11fa, - 0x51a8e5c, 0x801a0ef8, 0x5017165, 0x801910e4, 0x4e8543e, 0x801817bf, - 0x4cf36e5, 0x80172388, - 0x4b6195d, 0x80163440, 0x49cfba7, 0x801549e6, 0x483ddc3, 0x8014647b, - 0x46abfb3, 0x801383fe, - 0x451a177, 0x8012a86f, 0x4388310, 0x8011d1d0, 0x41f6480, 0x8011001f, - 0x40645c7, 0x8010335c, - 0x3ed26e6, 0x800f6b88, 0x3d407df, 0x800ea8a3, 0x3bae8b2, 0x800deaad, - 0x3a1c960, 0x800d31a5, - 0x388a9ea, 0x800c7d8c, 0x36f8a51, 0x800bce63, 0x3566a96, 0x800b2427, - 0x33d4abb, 0x800a7edb, - 0x3242abf, 0x8009de7e, 0x30b0aa4, 0x80094310, 0x2f1ea6c, 0x8008ac90, - 0x2d8ca16, 0x80081b00, - 0x2bfa9a4, 0x80078e5e, 0x2a68917, 0x800706ac, 0x28d6870, 0x800683e8, - 0x27447b0, 0x80060614, - 0x25b26d7, 0x80058d2f, 0x24205e8, 0x80051939, 0x228e4e2, 0x8004aa32, - 0x20fc3c6, 0x8004401a, - 0x1f6a297, 0x8003daf1, 0x1dd8154, 0x80037ab7, 0x1c45ffe, 0x80031f6d, - 0x1ab3e97, 0x8002c912, - 0x1921d20, 0x800277a6, 0x178fb99, 0x80022b29, 0x15fda03, 0x8001e39b, - 0x146b860, 0x8001a0fd, - 0x12d96b1, 0x8001634e, 0x11474f6, 0x80012a8e, 0xfb5330, 0x8000f6bd, - 0xe23160, 0x8000c7dc, - 0xc90f88, 0x80009dea, 0xafeda8, 0x800078e7, 0x96cbc1, 0x800058d4, 0x7da9d4, - 0x80003daf, - 0x6487e3, 0x8000277a, 0x4b65ee, 0x80001635, 0x3243f5, 0x800009df, 0x1921fb, - 0x80000278, -}; - -/** -* \par -* cosFactor tables are generated using the formula :
cos_factors[n] = 2 * cos((2n+1)*pi/(4*N))
-* \par -* C command to generate the table -*
   
-* for(i = 0; i< N; i++)   
-* {   
-*   cos_factors[i]= 2 * cos((2*i+1)*c/2);   
-* } 
-* \par -* where N is the number of factors to generate and c is pi/(2*N) -* \par -* Then converted to q31 format by multiplying with 2^31 and saturated if required. -*/ - - -static const q31_t cos_factorsQ31_128[128] = { - 0x7fff6216, 0x7ffa72d1, 0x7ff09478, 0x7fe1c76b, 0x7fce0c3e, 0x7fb563b3, - 0x7f97cebd, 0x7f754e80, - 0x7f4de451, 0x7f2191b4, 0x7ef05860, 0x7eba3a39, 0x7e7f3957, 0x7e3f57ff, - 0x7dfa98a8, 0x7db0fdf8, - 0x7d628ac6, 0x7d0f4218, 0x7cb72724, 0x7c5a3d50, 0x7bf88830, 0x7b920b89, - 0x7b26cb4f, 0x7ab6cba4, - 0x7a4210d8, 0x79c89f6e, 0x794a7c12, 0x78c7aba2, 0x78403329, 0x77b417df, - 0x77235f2d, 0x768e0ea6, - 0x75f42c0b, 0x7555bd4c, 0x74b2c884, 0x740b53fb, 0x735f6626, 0x72af05a7, - 0x71fa3949, 0x71410805, - 0x708378ff, 0x6fc19385, 0x6efb5f12, 0x6e30e34a, 0x6d6227fa, 0x6c8f351c, - 0x6bb812d1, 0x6adcc964, - 0x69fd614a, 0x6919e320, 0x683257ab, 0x6746c7d8, 0x66573cbb, 0x6563bf92, - 0x646c59bf, 0x637114cc, - 0x6271fa69, 0x616f146c, 0x60686ccf, 0x5f5e0db3, 0x5e50015d, 0x5d3e5237, - 0x5c290acc, 0x5b1035cf, - 0x59f3de12, 0x58d40e8c, 0x57b0d256, 0x568a34a9, 0x556040e2, 0x5433027d, - 0x53028518, 0x51ced46e, - 0x5097fc5e, 0x4f5e08e3, 0x4e210617, 0x4ce10034, 0x4b9e0390, 0x4a581c9e, - 0x490f57ee, 0x47c3c22f, - 0x46756828, 0x452456bd, 0x43d09aed, 0x427a41d0, 0x4121589b, 0x3fc5ec98, - 0x3e680b2c, 0x3d07c1d6, - 0x3ba51e29, 0x3a402dd2, 0x38d8fe93, 0x376f9e46, 0x36041ad9, 0x34968250, - 0x3326e2c3, 0x31b54a5e, - 0x3041c761, 0x2ecc681e, 0x2d553afc, 0x2bdc4e6f, 0x2a61b101, 0x28e5714b, - 0x27679df4, 0x25e845b6, - 0x24677758, 0x22e541af, 0x2161b3a0, 0x1fdcdc1b, 0x1e56ca1e, 0x1ccf8cb3, - 0x1b4732ef, 0x19bdcbf3, - 0x183366e9, 0x16a81305, 0x151bdf86, 0x138edbb1, 0x120116d5, 0x1072a048, - 0xee38766, 0xd53db92, - 0xbc3ac35, 0xa3308bd, 0x8a2009a, 0x710a345, 0x57f0035, 0x3ed26e6, 0x25b26d7, - 0xc90f88, -}; - -static const q31_t cos_factorsQ31_512[512] = { - 0x7ffff621, 0x7fffa72c, 0x7fff0943, 0x7ffe1c65, 0x7ffce093, 0x7ffb55ce, - 0x7ff97c18, 0x7ff75370, - 0x7ff4dbd9, 0x7ff21553, 0x7feeffe1, 0x7feb9b85, 0x7fe7e841, 0x7fe3e616, - 0x7fdf9508, 0x7fdaf519, - 0x7fd6064c, 0x7fd0c8a3, 0x7fcb3c23, 0x7fc560cf, 0x7fbf36aa, 0x7fb8bdb8, - 0x7fb1f5fc, 0x7faadf7c, - 0x7fa37a3c, 0x7f9bc640, 0x7f93c38c, 0x7f8b7227, 0x7f82d214, 0x7f79e35a, - 0x7f70a5fe, 0x7f671a05, - 0x7f5d3f75, 0x7f531655, 0x7f489eaa, 0x7f3dd87c, 0x7f32c3d1, 0x7f2760af, - 0x7f1baf1e, 0x7f0faf25, - 0x7f0360cb, 0x7ef6c418, 0x7ee9d914, 0x7edc9fc6, 0x7ecf1837, 0x7ec14270, - 0x7eb31e78, 0x7ea4ac58, - 0x7e95ec1a, 0x7e86ddc6, 0x7e778166, 0x7e67d703, 0x7e57dea7, 0x7e47985b, - 0x7e37042a, 0x7e26221f, - 0x7e14f242, 0x7e0374a0, 0x7df1a942, 0x7ddf9034, 0x7dcd2981, 0x7dba7534, - 0x7da77359, 0x7d9423fc, - 0x7d808728, 0x7d6c9ce9, 0x7d58654d, 0x7d43e05e, 0x7d2f0e2b, 0x7d19eebf, - 0x7d048228, 0x7ceec873, - 0x7cd8c1ae, 0x7cc26de5, 0x7cabcd28, 0x7c94df83, 0x7c7da505, 0x7c661dbc, - 0x7c4e49b7, 0x7c362904, - 0x7c1dbbb3, 0x7c0501d2, 0x7bebfb70, 0x7bd2a89e, 0x7bb9096b, 0x7b9f1de6, - 0x7b84e61f, 0x7b6a6227, - 0x7b4f920e, 0x7b3475e5, 0x7b190dbc, 0x7afd59a4, 0x7ae159ae, 0x7ac50dec, - 0x7aa8766f, 0x7a8b9348, - 0x7a6e648a, 0x7a50ea47, 0x7a332490, 0x7a151378, 0x79f6b711, 0x79d80f6f, - 0x79b91ca4, 0x7999dec4, - 0x797a55e0, 0x795a820e, 0x793a6361, 0x7919f9ec, 0x78f945c3, 0x78d846fb, - 0x78b6fda8, 0x789569df, - 0x78738bb3, 0x7851633b, 0x782ef08b, 0x780c33b8, 0x77e92cd9, 0x77c5dc01, - 0x77a24148, 0x777e5cc3, - 0x775a2e89, 0x7735b6af, 0x7710f54c, 0x76ebea77, 0x76c69647, 0x76a0f8d2, - 0x767b1231, 0x7654e279, - 0x762e69c4, 0x7607a828, 0x75e09dbd, 0x75b94a9c, 0x7591aedd, 0x7569ca99, - 0x75419de7, 0x751928e0, - 0x74f06b9e, 0x74c7663a, 0x749e18cd, 0x74748371, 0x744aa63f, 0x74208150, - 0x73f614c0, 0x73cb60a8, - 0x73a06522, 0x73752249, 0x73499838, 0x731dc70a, 0x72f1aed9, 0x72c54fc1, - 0x7298a9dd, 0x726bbd48, - 0x723e8a20, 0x7211107e, 0x71e35080, 0x71b54a41, 0x7186fdde, 0x71586b74, - 0x7129931f, 0x70fa74fc, - 0x70cb1128, 0x709b67c0, 0x706b78e3, 0x703b44ad, 0x700acb3c, 0x6fda0cae, - 0x6fa90921, 0x6f77c0b3, - 0x6f463383, 0x6f1461b0, 0x6ee24b57, 0x6eaff099, 0x6e7d5193, 0x6e4a6e66, - 0x6e174730, 0x6de3dc11, - 0x6db02d29, 0x6d7c3a98, 0x6d48047e, 0x6d138afb, 0x6cdece2f, 0x6ca9ce3b, - 0x6c748b3f, 0x6c3f055d, - 0x6c093cb6, 0x6bd3316a, 0x6b9ce39b, 0x6b66536b, 0x6b2f80fb, 0x6af86c6c, - 0x6ac115e2, 0x6a897d7d, - 0x6a51a361, 0x6a1987b0, 0x69e12a8c, 0x69a88c19, 0x696fac78, 0x69368bce, - 0x68fd2a3d, 0x68c387e9, - 0x6889a4f6, 0x684f8186, 0x68151dbe, 0x67da79c3, 0x679f95b7, 0x676471c0, - 0x67290e02, 0x66ed6aa1, - 0x66b187c3, 0x6675658c, 0x66390422, 0x65fc63a9, 0x65bf8447, 0x65826622, - 0x6545095f, 0x65076e25, - 0x64c99498, 0x648b7ce0, 0x644d2722, 0x640e9386, 0x63cfc231, 0x6390b34a, - 0x635166f9, 0x6311dd64, - 0x62d216b3, 0x6292130c, 0x6251d298, 0x6211557e, 0x61d09be5, 0x618fa5f7, - 0x614e73da, 0x610d05b7, - 0x60cb5bb7, 0x60897601, 0x604754bf, 0x6004f819, 0x5fc26038, 0x5f7f8d46, - 0x5f3c7f6b, 0x5ef936d1, - 0x5eb5b3a2, 0x5e71f606, 0x5e2dfe29, 0x5de9cc33, 0x5da5604f, 0x5d60baa7, - 0x5d1bdb65, 0x5cd6c2b5, - 0x5c9170bf, 0x5c4be5b0, 0x5c0621b2, 0x5bc024f0, 0x5b79ef96, 0x5b3381ce, - 0x5aecdbc5, 0x5aa5fda5, - 0x5a5ee79a, 0x5a1799d1, 0x59d01475, 0x598857b2, 0x594063b5, 0x58f838a9, - 0x58afd6bd, 0x58673e1b, - 0x581e6ef1, 0x57d5696d, 0x578c2dba, 0x5742bc06, 0x56f9147e, 0x56af3750, - 0x566524aa, 0x561adcb9, - 0x55d05faa, 0x5585adad, 0x553ac6ee, 0x54efab9c, 0x54a45be6, 0x5458d7f9, - 0x540d2005, 0x53c13439, - 0x537514c2, 0x5328c1d0, 0x52dc3b92, 0x528f8238, 0x524295f0, 0x51f576ea, - 0x51a82555, 0x515aa162, - 0x510ceb40, 0x50bf031f, 0x5070e92f, 0x50229da1, 0x4fd420a4, 0x4f857269, - 0x4f369320, 0x4ee782fb, - 0x4e984229, 0x4e48d0dd, 0x4df92f46, 0x4da95d96, 0x4d595bfe, 0x4d092ab0, - 0x4cb8c9dd, 0x4c6839b7, - 0x4c177a6e, 0x4bc68c36, 0x4b756f40, 0x4b2423be, 0x4ad2a9e2, 0x4a8101de, - 0x4a2f2be6, 0x49dd282a, - 0x498af6df, 0x49389836, 0x48e60c62, 0x48935397, 0x48406e08, 0x47ed5be6, - 0x479a1d67, 0x4746b2bc, - 0x46f31c1a, 0x469f59b4, 0x464b6bbe, 0x45f7526b, 0x45a30df0, 0x454e9e80, - 0x44fa0450, 0x44a53f93, - 0x4450507e, 0x43fb3746, 0x43a5f41e, 0x4350873c, 0x42faf0d4, 0x42a5311b, - 0x424f4845, 0x41f93689, - 0x41a2fc1a, 0x414c992f, 0x40f60dfb, 0x409f5ab6, 0x40487f94, 0x3ff17cca, - 0x3f9a5290, 0x3f430119, - 0x3eeb889c, 0x3e93e950, 0x3e3c2369, 0x3de4371f, 0x3d8c24a8, 0x3d33ec39, - 0x3cdb8e09, 0x3c830a50, - 0x3c2a6142, 0x3bd19318, 0x3b78a007, 0x3b1f8848, 0x3ac64c0f, 0x3a6ceb96, - 0x3a136712, 0x39b9bebc, - 0x395ff2c9, 0x39060373, 0x38abf0ef, 0x3851bb77, 0x37f76341, 0x379ce885, - 0x37424b7b, 0x36e78c5b, - 0x368cab5c, 0x3631a8b8, 0x35d684a6, 0x357b3f5d, 0x351fd918, 0x34c4520d, - 0x3468aa76, 0x340ce28b, - 0x33b0fa84, 0x3354f29b, 0x32f8cb07, 0x329c8402, 0x32401dc6, 0x31e39889, - 0x3186f487, 0x312a31f8, - 0x30cd5115, 0x30705217, 0x30133539, 0x2fb5fab2, 0x2f58a2be, 0x2efb2d95, - 0x2e9d9b70, 0x2e3fec8b, - 0x2de2211e, 0x2d843964, 0x2d263596, 0x2cc815ee, 0x2c69daa6, 0x2c0b83fa, - 0x2bad1221, 0x2b4e8558, - 0x2aefddd8, 0x2a911bdc, 0x2a323f9e, 0x29d34958, 0x29743946, 0x29150fa1, - 0x28b5cca5, 0x2856708d, - 0x27f6fb92, 0x27976df1, 0x2737c7e3, 0x26d809a5, 0x26783370, 0x26184581, - 0x25b84012, 0x2558235f, - 0x24f7efa2, 0x2497a517, 0x243743fa, 0x23d6cc87, 0x23763ef7, 0x23159b88, - 0x22b4e274, 0x225413f8, - 0x21f3304f, 0x219237b5, 0x21312a65, 0x20d0089c, 0x206ed295, 0x200d888d, - 0x1fac2abf, 0x1f4ab968, - 0x1ee934c3, 0x1e879d0d, 0x1e25f282, 0x1dc4355e, 0x1d6265dd, 0x1d00843d, - 0x1c9e90b8, 0x1c3c8b8c, - 0x1bda74f6, 0x1b784d30, 0x1b161479, 0x1ab3cb0d, 0x1a517128, 0x19ef0707, - 0x198c8ce7, 0x192a0304, - 0x18c7699b, 0x1864c0ea, 0x1802092c, 0x179f429f, 0x173c6d80, 0x16d98a0c, - 0x1676987f, 0x16139918, - 0x15b08c12, 0x154d71aa, 0x14ea4a1f, 0x148715ae, 0x1423d492, 0x13c0870a, - 0x135d2d53, 0x12f9c7aa, - 0x1296564d, 0x1232d979, 0x11cf516a, 0x116bbe60, 0x11082096, 0x10a4784b, - 0x1040c5bb, 0xfdd0926, - 0xf7942c7, 0xf1572dc, 0xeb199a4, 0xe4db75b, 0xde9cc40, 0xd85d88f, 0xd21dc87, - 0xcbdd865, - 0xc59cc68, 0xbf5b8cb, 0xb919dcf, 0xb2d7baf, 0xac952aa, 0xa6522fe, 0xa00ece8, - 0x99cb0a7, - 0x9386e78, 0x8d42699, 0x86fd947, 0x80b86c2, 0x7a72f45, 0x742d311, 0x6de7262, - 0x67a0d76, - 0x615a48b, 0x5b137df, 0x54cc7b1, 0x4e8543e, 0x483ddc3, 0x41f6480, 0x3bae8b2, - 0x3566a96, - 0x2f1ea6c, 0x28d6870, 0x228e4e2, 0x1c45ffe, 0x15fda03, 0xfb5330, 0x96cbc1, - 0x3243f5, -}; - -static const q31_t cos_factorsQ31_2048[2048] = { - 0x7fffff62, 0x7ffffa73, 0x7ffff094, 0x7fffe1c6, 0x7fffce09, 0x7fffb55c, - 0x7fff97c1, 0x7fff7536, - 0x7fff4dbb, 0x7fff2151, 0x7ffeeff8, 0x7ffeb9b0, 0x7ffe7e79, 0x7ffe3e52, - 0x7ffdf93c, 0x7ffdaf37, - 0x7ffd6042, 0x7ffd0c5f, 0x7ffcb38c, 0x7ffc55ca, 0x7ffbf319, 0x7ffb8b78, - 0x7ffb1ee9, 0x7ffaad6a, - 0x7ffa36fc, 0x7ff9bba0, 0x7ff93b54, 0x7ff8b619, 0x7ff82bef, 0x7ff79cd6, - 0x7ff708ce, 0x7ff66fd7, - 0x7ff5d1f1, 0x7ff52f1d, 0x7ff48759, 0x7ff3daa6, 0x7ff32905, 0x7ff27275, - 0x7ff1b6f6, 0x7ff0f688, - 0x7ff0312c, 0x7fef66e1, 0x7fee97a7, 0x7fedc37e, 0x7fecea67, 0x7fec0c62, - 0x7feb296d, 0x7fea418b, - 0x7fe954ba, 0x7fe862fa, 0x7fe76c4c, 0x7fe670b0, 0x7fe57025, 0x7fe46aac, - 0x7fe36045, 0x7fe250ef, - 0x7fe13cac, 0x7fe0237a, 0x7fdf055a, 0x7fdde24d, 0x7fdcba51, 0x7fdb8d67, - 0x7fda5b8f, 0x7fd924ca, - 0x7fd7e917, 0x7fd6a875, 0x7fd562e7, 0x7fd4186a, 0x7fd2c900, 0x7fd174a8, - 0x7fd01b63, 0x7fcebd31, - 0x7fcd5a11, 0x7fcbf203, 0x7fca8508, 0x7fc91320, 0x7fc79c4b, 0x7fc62089, - 0x7fc49fda, 0x7fc31a3d, - 0x7fc18fb4, 0x7fc0003e, 0x7fbe6bdb, 0x7fbcd28b, 0x7fbb344e, 0x7fb99125, - 0x7fb7e90f, 0x7fb63c0d, - 0x7fb48a1e, 0x7fb2d343, 0x7fb1177b, 0x7faf56c7, 0x7fad9127, 0x7fabc69b, - 0x7fa9f723, 0x7fa822bf, - 0x7fa6496e, 0x7fa46b32, 0x7fa2880b, 0x7fa09ff7, 0x7f9eb2f8, 0x7f9cc10d, - 0x7f9aca37, 0x7f98ce76, - 0x7f96cdc9, 0x7f94c831, 0x7f92bdad, 0x7f90ae3f, 0x7f8e99e6, 0x7f8c80a1, - 0x7f8a6272, 0x7f883f58, - 0x7f861753, 0x7f83ea64, 0x7f81b88a, 0x7f7f81c6, 0x7f7d4617, 0x7f7b057e, - 0x7f78bffb, 0x7f76758e, - 0x7f742637, 0x7f71d1f6, 0x7f6f78cb, 0x7f6d1ab6, 0x7f6ab7b8, 0x7f684fd0, - 0x7f65e2ff, 0x7f637144, - 0x7f60faa0, 0x7f5e7f13, 0x7f5bfe9d, 0x7f59793e, 0x7f56eef5, 0x7f545fc5, - 0x7f51cbab, 0x7f4f32a9, - 0x7f4c94be, 0x7f49f1eb, 0x7f474a30, 0x7f449d8c, 0x7f41ec01, 0x7f3f358d, - 0x7f3c7a31, 0x7f39b9ee, - 0x7f36f4c3, 0x7f342ab1, 0x7f315bb7, 0x7f2e87d6, 0x7f2baf0d, 0x7f28d15d, - 0x7f25eec7, 0x7f230749, - 0x7f201ae5, 0x7f1d299a, 0x7f1a3368, 0x7f173850, 0x7f143852, 0x7f11336d, - 0x7f0e29a3, 0x7f0b1af2, - 0x7f08075c, 0x7f04eedf, 0x7f01d17d, 0x7efeaf36, 0x7efb8809, 0x7ef85bf7, - 0x7ef52b00, 0x7ef1f524, - 0x7eeeba62, 0x7eeb7abc, 0x7ee83632, 0x7ee4ecc3, 0x7ee19e6f, 0x7ede4b38, - 0x7edaf31c, 0x7ed7961c, - 0x7ed43438, 0x7ed0cd70, 0x7ecd61c5, 0x7ec9f137, 0x7ec67bc5, 0x7ec3016f, - 0x7ebf8237, 0x7ebbfe1c, - 0x7eb8751e, 0x7eb4e73d, 0x7eb1547a, 0x7eadbcd4, 0x7eaa204c, 0x7ea67ee2, - 0x7ea2d896, 0x7e9f2d68, - 0x7e9b7d58, 0x7e97c867, 0x7e940e94, 0x7e904fe0, 0x7e8c8c4b, 0x7e88c3d5, - 0x7e84f67e, 0x7e812447, - 0x7e7d4d2f, 0x7e797136, 0x7e75905d, 0x7e71aaa4, 0x7e6dc00c, 0x7e69d093, - 0x7e65dc3b, 0x7e61e303, - 0x7e5de4ec, 0x7e59e1f5, 0x7e55da20, 0x7e51cd6c, 0x7e4dbbd9, 0x7e49a567, - 0x7e458a17, 0x7e4169e9, - 0x7e3d44dd, 0x7e391af3, 0x7e34ec2b, 0x7e30b885, 0x7e2c8002, 0x7e2842a2, - 0x7e240064, 0x7e1fb94a, - 0x7e1b6d53, 0x7e171c7f, 0x7e12c6ce, 0x7e0e6c42, 0x7e0a0cd9, 0x7e05a894, - 0x7e013f74, 0x7dfcd178, - 0x7df85ea0, 0x7df3e6ee, 0x7def6a60, 0x7deae8f7, 0x7de662b3, 0x7de1d795, - 0x7ddd479d, 0x7dd8b2ca, - 0x7dd4191d, 0x7dcf7a96, 0x7dcad736, 0x7dc62efc, 0x7dc181e8, 0x7dbccffc, - 0x7db81936, 0x7db35d98, - 0x7dae9d21, 0x7da9d7d2, 0x7da50dab, 0x7da03eab, 0x7d9b6ad3, 0x7d969224, - 0x7d91b49e, 0x7d8cd240, - 0x7d87eb0a, 0x7d82fefe, 0x7d7e0e1c, 0x7d791862, 0x7d741dd2, 0x7d6f1e6c, - 0x7d6a1a31, 0x7d65111f, - 0x7d600338, 0x7d5af07b, 0x7d55d8e9, 0x7d50bc82, 0x7d4b9b46, 0x7d467536, - 0x7d414a51, 0x7d3c1a98, - 0x7d36e60b, 0x7d31acaa, 0x7d2c6e76, 0x7d272b6e, 0x7d21e393, 0x7d1c96e5, - 0x7d174564, 0x7d11ef11, - 0x7d0c93eb, 0x7d0733f3, 0x7d01cf29, 0x7cfc658d, 0x7cf6f720, 0x7cf183e1, - 0x7cec0bd1, 0x7ce68ef0, - 0x7ce10d3f, 0x7cdb86bd, 0x7cd5fb6a, 0x7cd06b48, 0x7ccad656, 0x7cc53c94, - 0x7cbf9e03, 0x7cb9faa2, - 0x7cb45272, 0x7caea574, 0x7ca8f3a7, 0x7ca33d0c, 0x7c9d81a3, 0x7c97c16b, - 0x7c91fc66, 0x7c8c3294, - 0x7c8663f4, 0x7c809088, 0x7c7ab84e, 0x7c74db48, 0x7c6ef976, 0x7c6912d7, - 0x7c63276d, 0x7c5d3737, - 0x7c574236, 0x7c514869, 0x7c4b49d2, 0x7c45466f, 0x7c3f3e42, 0x7c39314b, - 0x7c331f8a, 0x7c2d08ff, - 0x7c26edab, 0x7c20cd8d, 0x7c1aa8a6, 0x7c147ef6, 0x7c0e507e, 0x7c081d3d, - 0x7c01e534, 0x7bfba863, - 0x7bf566cb, 0x7bef206b, 0x7be8d544, 0x7be28556, 0x7bdc30a1, 0x7bd5d726, - 0x7bcf78e5, 0x7bc915dd, - 0x7bc2ae10, 0x7bbc417e, 0x7bb5d026, 0x7baf5a09, 0x7ba8df28, 0x7ba25f82, - 0x7b9bdb18, 0x7b9551ea, - 0x7b8ec3f8, 0x7b883143, 0x7b8199ca, 0x7b7afd8f, 0x7b745c91, 0x7b6db6d0, - 0x7b670c4d, 0x7b605d09, - 0x7b59a902, 0x7b52f03a, 0x7b4c32b1, 0x7b457068, 0x7b3ea95d, 0x7b37dd92, - 0x7b310d07, 0x7b2a37bc, - 0x7b235db2, 0x7b1c7ee8, 0x7b159b5f, 0x7b0eb318, 0x7b07c612, 0x7b00d44d, - 0x7af9ddcb, 0x7af2e28b, - 0x7aebe28d, 0x7ae4ddd2, 0x7addd45b, 0x7ad6c626, 0x7acfb336, 0x7ac89b89, - 0x7ac17f20, 0x7aba5dfc, - 0x7ab3381d, 0x7aac0d82, 0x7aa4de2d, 0x7a9daa1d, 0x7a967153, 0x7a8f33d0, - 0x7a87f192, 0x7a80aa9c, - 0x7a795eec, 0x7a720e84, 0x7a6ab963, 0x7a635f8a, 0x7a5c00f9, 0x7a549db0, - 0x7a4d35b0, 0x7a45c8f9, - 0x7a3e578b, 0x7a36e166, 0x7a2f668c, 0x7a27e6fb, 0x7a2062b5, 0x7a18d9b9, - 0x7a114c09, 0x7a09b9a4, - 0x7a02228a, 0x79fa86bc, 0x79f2e63a, 0x79eb4105, 0x79e3971c, 0x79dbe880, - 0x79d43532, 0x79cc7d31, - 0x79c4c07e, 0x79bcff19, 0x79b53903, 0x79ad6e3c, 0x79a59ec3, 0x799dca9a, - 0x7995f1c1, 0x798e1438, - 0x798631ff, 0x797e4b16, 0x79765f7f, 0x796e6f39, 0x79667a44, 0x795e80a1, - 0x79568250, 0x794e7f52, - 0x794677a6, 0x793e6b4e, 0x79365a49, 0x792e4497, 0x79262a3a, 0x791e0b31, - 0x7915e77c, 0x790dbf1d, - 0x79059212, 0x78fd605d, 0x78f529fe, 0x78eceef6, 0x78e4af44, 0x78dc6ae8, - 0x78d421e4, 0x78cbd437, - 0x78c381e2, 0x78bb2ae5, 0x78b2cf41, 0x78aa6ef5, 0x78a20a03, 0x7899a06a, - 0x7891322a, 0x7888bf45, - 0x788047ba, 0x7877cb89, 0x786f4ab4, 0x7866c53a, 0x785e3b1c, 0x7855ac5a, - 0x784d18f4, 0x784480ea, - 0x783be43e, 0x783342ef, 0x782a9cfe, 0x7821f26b, 0x78194336, 0x78108f60, - 0x7807d6e9, 0x77ff19d1, - 0x77f65819, 0x77ed91c0, 0x77e4c6c9, 0x77dbf732, 0x77d322fc, 0x77ca4a27, - 0x77c16cb4, 0x77b88aa3, - 0x77afa3f5, 0x77a6b8a9, 0x779dc8c0, 0x7794d43b, 0x778bdb19, 0x7782dd5c, - 0x7779db03, 0x7770d40f, - 0x7767c880, 0x775eb857, 0x7755a394, 0x774c8a36, 0x77436c40, 0x773a49b0, - 0x77312287, 0x7727f6c6, - 0x771ec66e, 0x7715917d, 0x770c57f5, 0x770319d6, 0x76f9d721, 0x76f08fd5, - 0x76e743f4, 0x76ddf37c, - 0x76d49e70, 0x76cb44cf, 0x76c1e699, 0x76b883d0, 0x76af1c72, 0x76a5b082, - 0x769c3ffe, 0x7692cae8, - 0x7689513f, 0x767fd304, 0x76765038, 0x766cc8db, 0x76633ced, 0x7659ac6f, - 0x76501760, 0x76467dc2, - 0x763cdf94, 0x76333cd8, 0x7629958c, 0x761fe9b3, 0x7616394c, 0x760c8457, - 0x7602cad5, 0x75f90cc7, - 0x75ef4a2c, 0x75e58305, 0x75dbb753, 0x75d1e715, 0x75c8124d, 0x75be38fa, - 0x75b45b1d, 0x75aa78b6, - 0x75a091c6, 0x7596a64d, 0x758cb64c, 0x7582c1c2, 0x7578c8b0, 0x756ecb18, - 0x7564c8f8, 0x755ac251, - 0x7550b725, 0x7546a772, 0x753c933a, 0x75327a7d, 0x75285d3b, 0x751e3b75, - 0x7514152b, 0x7509ea5d, - 0x74ffbb0d, 0x74f58739, 0x74eb4ee3, 0x74e1120c, 0x74d6d0b2, 0x74cc8ad8, - 0x74c2407d, 0x74b7f1a1, - 0x74ad9e46, 0x74a3466b, 0x7498ea11, 0x748e8938, 0x748423e0, 0x7479ba0b, - 0x746f4bb8, 0x7464d8e8, - 0x745a619b, 0x744fe5d2, 0x7445658d, 0x743ae0cc, 0x74305790, 0x7425c9da, - 0x741b37a9, 0x7410a0fe, - 0x740605d9, 0x73fb663c, 0x73f0c226, 0x73e61997, 0x73db6c91, 0x73d0bb13, - 0x73c6051f, 0x73bb4ab3, - 0x73b08bd1, 0x73a5c87a, 0x739b00ad, 0x7390346b, 0x738563b5, 0x737a8e8a, - 0x736fb4ec, 0x7364d6da, - 0x7359f456, 0x734f0d5f, 0x734421f6, 0x7339321b, 0x732e3dcf, 0x73234512, - 0x731847e5, 0x730d4648, - 0x7302403c, 0x72f735c0, 0x72ec26d6, 0x72e1137d, 0x72d5fbb7, 0x72cadf83, - 0x72bfbee3, 0x72b499d6, - 0x72a9705c, 0x729e4277, 0x72931027, 0x7287d96c, 0x727c9e47, 0x72715eb8, - 0x72661abf, 0x725ad25d, - 0x724f8593, 0x72443460, 0x7238dec5, 0x722d84c4, 0x7222265b, 0x7216c38c, - 0x720b5c57, 0x71fff0bc, - 0x71f480bc, 0x71e90c57, 0x71dd938f, 0x71d21662, 0x71c694d2, 0x71bb0edf, - 0x71af848a, 0x71a3f5d2, - 0x719862b9, 0x718ccb3f, 0x71812f65, 0x71758f29, 0x7169ea8f, 0x715e4194, - 0x7152943b, 0x7146e284, - 0x713b2c6e, 0x712f71fb, 0x7123b32b, 0x7117effe, 0x710c2875, 0x71005c90, - 0x70f48c50, 0x70e8b7b5, - 0x70dcdec0, 0x70d10171, 0x70c51fc8, 0x70b939c7, 0x70ad4f6d, 0x70a160ba, - 0x70956db1, 0x70897650, - 0x707d7a98, 0x70717a8a, 0x70657626, 0x70596d6d, 0x704d6060, 0x70414efd, - 0x70353947, 0x70291f3e, - 0x701d00e1, 0x7010de32, 0x7004b731, 0x6ff88bde, 0x6fec5c3b, 0x6fe02846, - 0x6fd3f001, 0x6fc7b36d, - 0x6fbb728a, 0x6faf2d57, 0x6fa2e3d7, 0x6f969608, 0x6f8a43ed, 0x6f7ded84, - 0x6f7192cf, 0x6f6533ce, - 0x6f58d082, 0x6f4c68eb, 0x6f3ffd09, 0x6f338cde, 0x6f271868, 0x6f1a9faa, - 0x6f0e22a3, 0x6f01a155, - 0x6ef51bbe, 0x6ee891e1, 0x6edc03bc, 0x6ecf7152, 0x6ec2daa2, 0x6eb63fad, - 0x6ea9a073, 0x6e9cfcf5, - 0x6e905534, 0x6e83a92f, 0x6e76f8e7, 0x6e6a445d, 0x6e5d8b91, 0x6e50ce84, - 0x6e440d37, 0x6e3747a9, - 0x6e2a7ddb, 0x6e1dafce, 0x6e10dd82, 0x6e0406f8, 0x6df72c30, 0x6dea4d2b, - 0x6ddd69e9, 0x6dd0826a, - 0x6dc396b0, 0x6db6a6ba, 0x6da9b28a, 0x6d9cba1f, 0x6d8fbd7a, 0x6d82bc9d, - 0x6d75b786, 0x6d68ae37, - 0x6d5ba0b0, 0x6d4e8ef2, 0x6d4178fd, 0x6d345ed1, 0x6d274070, 0x6d1a1dda, - 0x6d0cf70f, 0x6cffcc0f, - 0x6cf29cdc, 0x6ce56975, 0x6cd831dc, 0x6ccaf610, 0x6cbdb613, 0x6cb071e4, - 0x6ca32985, 0x6c95dcf6, - 0x6c888c36, 0x6c7b3748, 0x6c6dde2b, 0x6c6080e0, 0x6c531f67, 0x6c45b9c1, - 0x6c384fef, 0x6c2ae1f0, - 0x6c1d6fc6, 0x6c0ff971, 0x6c027ef1, 0x6bf50047, 0x6be77d74, 0x6bd9f677, - 0x6bcc6b53, 0x6bbedc06, - 0x6bb14892, 0x6ba3b0f7, 0x6b961536, 0x6b88754f, 0x6b7ad142, 0x6b6d2911, - 0x6b5f7cbc, 0x6b51cc42, - 0x6b4417a6, 0x6b365ee7, 0x6b28a206, 0x6b1ae103, 0x6b0d1bdf, 0x6aff529a, - 0x6af18536, 0x6ae3b3b2, - 0x6ad5de0f, 0x6ac8044e, 0x6aba266e, 0x6aac4472, 0x6a9e5e58, 0x6a907423, - 0x6a8285d1, 0x6a749365, - 0x6a669cdd, 0x6a58a23c, 0x6a4aa381, 0x6a3ca0ad, 0x6a2e99c0, 0x6a208ebb, - 0x6a127f9f, 0x6a046c6c, - 0x69f65523, 0x69e839c4, 0x69da1a50, 0x69cbf6c7, 0x69bdcf29, 0x69afa378, - 0x69a173b5, 0x69933fde, - 0x698507f6, 0x6976cbfc, 0x69688bf1, 0x695a47d6, 0x694bffab, 0x693db371, - 0x692f6328, 0x69210ed1, - 0x6912b66c, 0x690459fb, 0x68f5f97d, 0x68e794f3, 0x68d92c5d, 0x68cabfbd, - 0x68bc4f13, 0x68adda5f, - 0x689f61a1, 0x6890e4dc, 0x6882640e, 0x6873df38, 0x6865565c, 0x6856c979, - 0x68483891, 0x6839a3a4, - 0x682b0ab1, 0x681c6dbb, 0x680dccc1, 0x67ff27c4, 0x67f07ec5, 0x67e1d1c4, - 0x67d320c1, 0x67c46bbe, - 0x67b5b2bb, 0x67a6f5b8, 0x679834b6, 0x67896fb6, 0x677aa6b8, 0x676bd9bd, - 0x675d08c4, 0x674e33d0, - 0x673f5ae0, 0x67307df5, 0x67219d10, 0x6712b831, 0x6703cf58, 0x66f4e287, - 0x66e5f1be, 0x66d6fcfd, - 0x66c80445, 0x66b90797, 0x66aa06f3, 0x669b0259, 0x668bf9cb, 0x667ced49, - 0x666ddcd3, 0x665ec86b, - 0x664fb010, 0x664093c3, 0x66317385, 0x66224f56, 0x66132738, 0x6603fb2a, - 0x65f4cb2d, 0x65e59742, - 0x65d65f69, 0x65c723a3, 0x65b7e3f1, 0x65a8a052, 0x659958c9, 0x658a0d54, - 0x657abdf6, 0x656b6aae, - 0x655c137d, 0x654cb863, 0x653d5962, 0x652df679, 0x651e8faa, 0x650f24f5, - 0x64ffb65b, 0x64f043dc, - 0x64e0cd78, 0x64d15331, 0x64c1d507, 0x64b252fa, 0x64a2cd0c, 0x6493433c, - 0x6483b58c, 0x647423fb, - 0x64648e8c, 0x6454f53d, 0x64455810, 0x6435b706, 0x6426121e, 0x6416695a, - 0x6406bcba, 0x63f70c3f, - 0x63e757ea, 0x63d79fba, 0x63c7e3b1, 0x63b823cf, 0x63a86015, 0x63989884, - 0x6388cd1b, 0x6378fddc, - 0x63692ac7, 0x635953dd, 0x6349791f, 0x63399a8d, 0x6329b827, 0x6319d1ef, - 0x6309e7e4, 0x62f9fa09, - 0x62ea085c, 0x62da12df, 0x62ca1992, 0x62ba1c77, 0x62aa1b8d, 0x629a16d5, - 0x628a0e50, 0x627a01fe, - 0x6269f1e1, 0x6259ddf8, 0x6249c645, 0x6239aac7, 0x62298b81, 0x62196871, - 0x62094199, 0x61f916f9, - 0x61e8e893, 0x61d8b666, 0x61c88074, 0x61b846bc, 0x61a80940, 0x6197c800, - 0x618782fd, 0x61773a37, - 0x6166edb0, 0x61569d67, 0x6146495d, 0x6135f193, 0x6125960a, 0x611536c2, - 0x6104d3bc, 0x60f46cf9, - 0x60e40278, 0x60d3943b, 0x60c32243, 0x60b2ac8f, 0x60a23322, 0x6091b5fa, - 0x60813519, 0x6070b080, - 0x6060282f, 0x604f9c27, 0x603f0c69, 0x602e78f4, 0x601de1ca, 0x600d46ec, - 0x5ffca859, 0x5fec0613, - 0x5fdb601b, 0x5fcab670, 0x5fba0914, 0x5fa95807, 0x5f98a34a, 0x5f87eade, - 0x5f772ec2, 0x5f666ef9, - 0x5f55ab82, 0x5f44e45e, 0x5f34198e, 0x5f234b12, 0x5f1278eb, 0x5f01a31a, - 0x5ef0c99f, 0x5edfec7b, - 0x5ecf0baf, 0x5ebe273b, 0x5ead3f1f, 0x5e9c535e, 0x5e8b63f7, 0x5e7a70ea, - 0x5e697a39, 0x5e587fe5, - 0x5e4781ed, 0x5e368053, 0x5e257b17, 0x5e147239, 0x5e0365bb, 0x5df2559e, - 0x5de141e1, 0x5dd02a85, - 0x5dbf0f8c, 0x5dadf0f5, 0x5d9ccec2, 0x5d8ba8f3, 0x5d7a7f88, 0x5d695283, - 0x5d5821e4, 0x5d46edac, - 0x5d35b5db, 0x5d247a72, 0x5d133b72, 0x5d01f8dc, 0x5cf0b2af, 0x5cdf68ed, - 0x5cce1b97, 0x5cbccaac, - 0x5cab762f, 0x5c9a1e1e, 0x5c88c27c, 0x5c776348, 0x5c660084, 0x5c549a30, - 0x5c43304d, 0x5c31c2db, - 0x5c2051db, 0x5c0edd4e, 0x5bfd6534, 0x5bebe98e, 0x5bda6a5d, 0x5bc8e7a2, - 0x5bb7615d, 0x5ba5d78e, - 0x5b944a37, 0x5b82b958, 0x5b7124f2, 0x5b5f8d06, 0x5b4df193, 0x5b3c529c, - 0x5b2ab020, 0x5b190a20, - 0x5b07609d, 0x5af5b398, 0x5ae40311, 0x5ad24f09, 0x5ac09781, 0x5aaedc78, - 0x5a9d1df1, 0x5a8b5bec, - 0x5a799669, 0x5a67cd69, 0x5a5600ec, 0x5a4430f5, 0x5a325d82, 0x5a208695, - 0x5a0eac2e, 0x59fcce4f, - 0x59eaecf8, 0x59d90829, 0x59c71fe3, 0x59b53427, 0x59a344f6, 0x59915250, - 0x597f5c36, 0x596d62a9, - 0x595b65aa, 0x59496538, 0x59376155, 0x59255a02, 0x59134f3e, 0x5901410c, - 0x58ef2f6b, 0x58dd1a5d, - 0x58cb01e1, 0x58b8e5f9, 0x58a6c6a5, 0x5894a3e7, 0x58827dbe, 0x5870542c, - 0x585e2730, 0x584bf6cd, - 0x5839c302, 0x58278bd1, 0x58155139, 0x5803133c, 0x57f0d1da, 0x57de8d15, - 0x57cc44ec, 0x57b9f960, - 0x57a7aa73, 0x57955825, 0x57830276, 0x5770a968, 0x575e4cfa, 0x574bed2f, - 0x57398a05, 0x5727237f, - 0x5714b99d, 0x57024c5f, 0x56efdbc7, 0x56dd67d4, 0x56caf088, 0x56b875e4, - 0x56a5f7e7, 0x56937694, - 0x5680f1ea, 0x566e69ea, 0x565bde95, 0x56494fec, 0x5636bdef, 0x5624289f, - 0x56118ffe, 0x55fef40a, - 0x55ec54c6, 0x55d9b232, 0x55c70c4f, 0x55b4631d, 0x55a1b69d, 0x558f06d0, - 0x557c53b6, 0x55699d51, - 0x5556e3a1, 0x554426a7, 0x55316663, 0x551ea2d6, 0x550bdc01, 0x54f911e5, - 0x54e64482, 0x54d373d9, - 0x54c09feb, 0x54adc8b8, 0x549aee42, 0x54881089, 0x54752f8d, 0x54624b50, - 0x544f63d2, 0x543c7914, - 0x54298b17, 0x541699db, 0x5403a561, 0x53f0adaa, 0x53ddb2b6, 0x53cab486, - 0x53b7b31c, 0x53a4ae77, - 0x5391a699, 0x537e9b82, 0x536b8d33, 0x53587bad, 0x534566f0, 0x53324efd, - 0x531f33d5, 0x530c1579, - 0x52f8f3e9, 0x52e5cf27, 0x52d2a732, 0x52bf7c0b, 0x52ac4db4, 0x52991c2d, - 0x5285e777, 0x5272af92, - 0x525f7480, 0x524c3640, 0x5238f4d4, 0x5225b03d, 0x5212687b, 0x51ff1d8f, - 0x51ebcf7a, 0x51d87e3c, - 0x51c529d7, 0x51b1d24a, 0x519e7797, 0x518b19bf, 0x5177b8c2, 0x516454a0, - 0x5150ed5c, 0x513d82f4, - 0x512a156b, 0x5116a4c1, 0x510330f7, 0x50efba0d, 0x50dc4005, 0x50c8c2de, - 0x50b5429a, 0x50a1bf39, - 0x508e38bd, 0x507aaf25, 0x50672273, 0x505392a8, 0x503fffc4, 0x502c69c8, - 0x5018d0b4, 0x5005348a, - 0x4ff1954b, 0x4fddf2f6, 0x4fca4d8d, 0x4fb6a510, 0x4fa2f981, 0x4f8f4ae0, - 0x4f7b992d, 0x4f67e46a, - 0x4f542c98, 0x4f4071b6, 0x4f2cb3c7, 0x4f18f2c9, 0x4f052ec0, 0x4ef167aa, - 0x4edd9d89, 0x4ec9d05e, - 0x4eb60029, 0x4ea22ceb, 0x4e8e56a5, 0x4e7a7d58, 0x4e66a105, 0x4e52c1ab, - 0x4e3edf4d, 0x4e2af9ea, - 0x4e171184, 0x4e03261b, 0x4def37b0, 0x4ddb4644, 0x4dc751d8, 0x4db35a6c, - 0x4d9f6001, 0x4d8b6298, - 0x4d776231, 0x4d635ece, 0x4d4f5870, 0x4d3b4f16, 0x4d2742c2, 0x4d133374, - 0x4cff212e, 0x4ceb0bf0, - 0x4cd6f3bb, 0x4cc2d88f, 0x4caeba6e, 0x4c9a9958, 0x4c86754e, 0x4c724e50, - 0x4c5e2460, 0x4c49f77f, - 0x4c35c7ac, 0x4c2194e9, 0x4c0d5f37, 0x4bf92697, 0x4be4eb08, 0x4bd0ac8d, - 0x4bbc6b25, 0x4ba826d1, - 0x4b93df93, 0x4b7f956b, 0x4b6b485a, 0x4b56f861, 0x4b42a580, 0x4b2e4fb8, - 0x4b19f70a, 0x4b059b77, - 0x4af13d00, 0x4adcdba5, 0x4ac87767, 0x4ab41046, 0x4a9fa645, 0x4a8b3963, - 0x4a76c9a2, 0x4a625701, - 0x4a4de182, 0x4a396926, 0x4a24edee, 0x4a106fda, 0x49fbeeea, 0x49e76b21, - 0x49d2e47e, 0x49be5b02, - 0x49a9ceaf, 0x49953f84, 0x4980ad84, 0x496c18ae, 0x49578103, 0x4942e684, - 0x492e4933, 0x4919a90f, - 0x4905061a, 0x48f06054, 0x48dbb7be, 0x48c70c59, 0x48b25e25, 0x489dad25, - 0x4888f957, 0x487442be, - 0x485f8959, 0x484acd2a, 0x48360e32, 0x48214c71, 0x480c87e8, 0x47f7c099, - 0x47e2f682, 0x47ce29a7, - 0x47b95a06, 0x47a487a2, 0x478fb27b, 0x477ada91, 0x4765ffe6, 0x4751227a, - 0x473c424e, 0x47275f63, - 0x471279ba, 0x46fd9154, 0x46e8a631, 0x46d3b852, 0x46bec7b8, 0x46a9d464, - 0x4694de56, 0x467fe590, - 0x466aea12, 0x4655ebdd, 0x4640eaf2, 0x462be751, 0x4616e0fc, 0x4601d7f3, - 0x45eccc37, 0x45d7bdc9, - 0x45c2acaa, 0x45ad98da, 0x4598825a, 0x4583692c, 0x456e4d4f, 0x45592ec6, - 0x45440d90, 0x452ee9ae, - 0x4519c321, 0x450499eb, 0x44ef6e0b, 0x44da3f83, 0x44c50e53, 0x44afda7d, - 0x449aa400, 0x44856adf, - 0x44702f19, 0x445af0b0, 0x4445afa4, 0x44306bf6, 0x441b25a8, 0x4405dcb9, - 0x43f0912b, 0x43db42fe, - 0x43c5f234, 0x43b09ecc, 0x439b48c9, 0x4385f02a, 0x437094f1, 0x435b371f, - 0x4345d6b3, 0x433073b0, - 0x431b0e15, 0x4305a5e5, 0x42f03b1e, 0x42dacdc3, 0x42c55dd4, 0x42afeb53, - 0x429a763f, 0x4284fe99, - 0x426f8463, 0x425a079e, 0x42448849, 0x422f0667, 0x421981f7, 0x4203fafb, - 0x41ee7174, 0x41d8e561, - 0x41c356c5, 0x41adc5a0, 0x419831f3, 0x41829bbe, 0x416d0302, 0x415767c1, - 0x4141c9fb, 0x412c29b1, - 0x411686e4, 0x4100e194, 0x40eb39c3, 0x40d58f71, 0x40bfe29f, 0x40aa334e, - 0x4094817f, 0x407ecd32, - 0x40691669, 0x40535d24, 0x403da165, 0x4027e32b, 0x40122278, 0x3ffc5f4d, - 0x3fe699aa, 0x3fd0d191, - 0x3fbb0702, 0x3fa539fd, 0x3f8f6a85, 0x3f799899, 0x3f63c43b, 0x3f4ded6b, - 0x3f38142a, 0x3f22387a, - 0x3f0c5a5a, 0x3ef679cc, 0x3ee096d1, 0x3ecab169, 0x3eb4c995, 0x3e9edf57, - 0x3e88f2ae, 0x3e73039d, - 0x3e5d1222, 0x3e471e41, 0x3e3127f9, 0x3e1b2f4a, 0x3e053437, 0x3def36c0, - 0x3dd936e6, 0x3dc334a9, - 0x3dad300b, 0x3d97290b, 0x3d811fac, 0x3d6b13ee, 0x3d5505d2, 0x3d3ef559, - 0x3d28e282, 0x3d12cd51, - 0x3cfcb5c4, 0x3ce69bde, 0x3cd07f9f, 0x3cba6107, 0x3ca44018, 0x3c8e1cd3, - 0x3c77f737, 0x3c61cf48, - 0x3c4ba504, 0x3c35786d, 0x3c1f4983, 0x3c091849, 0x3bf2e4be, 0x3bdcaee3, - 0x3bc676b9, 0x3bb03c42, - 0x3b99ff7d, 0x3b83c06c, 0x3b6d7f10, 0x3b573b69, 0x3b40f579, 0x3b2aad3f, - 0x3b1462be, 0x3afe15f6, - 0x3ae7c6e7, 0x3ad17593, 0x3abb21fb, 0x3aa4cc1e, 0x3a8e7400, 0x3a78199f, - 0x3a61bcfd, 0x3a4b5e1b, - 0x3a34fcf9, 0x3a1e9999, 0x3a0833fc, 0x39f1cc21, 0x39db620b, 0x39c4f5ba, - 0x39ae872f, 0x3998166a, - 0x3981a36d, 0x396b2e38, 0x3954b6cd, 0x393e3d2c, 0x3927c155, 0x3911434b, - 0x38fac30e, 0x38e4409e, - 0x38cdbbfc, 0x38b7352a, 0x38a0ac29, 0x388a20f8, 0x38739399, 0x385d040d, - 0x38467255, 0x382fde72, - 0x38194864, 0x3802b02c, 0x37ec15cb, 0x37d57943, 0x37beda93, 0x37a839be, - 0x379196c3, 0x377af1a3, - 0x37644a60, 0x374da0fa, 0x3736f573, 0x372047ca, 0x37099802, 0x36f2e61a, - 0x36dc3214, 0x36c57bf0, - 0x36aec3b0, 0x36980954, 0x36814cde, 0x366a8e4d, 0x3653cda3, 0x363d0ae2, - 0x36264609, 0x360f7f19, - 0x35f8b614, 0x35e1eafa, 0x35cb1dcc, 0x35b44e8c, 0x359d7d39, 0x3586a9d5, - 0x356fd461, 0x3558fcde, - 0x3542234c, 0x352b47ad, 0x35146a00, 0x34fd8a48, 0x34e6a885, 0x34cfc4b7, - 0x34b8dee1, 0x34a1f702, - 0x348b0d1c, 0x3474212f, 0x345d333c, 0x34464345, 0x342f5149, 0x34185d4b, - 0x3401674a, 0x33ea6f48, - 0x33d37546, 0x33bc7944, 0x33a57b44, 0x338e7b46, 0x3377794b, 0x33607554, - 0x33496f62, 0x33326776, - 0x331b5d91, 0x330451b3, 0x32ed43de, 0x32d63412, 0x32bf2250, 0x32a80e99, - 0x3290f8ef, 0x3279e151, - 0x3262c7c1, 0x324bac40, 0x32348ecf, 0x321d6f6e, 0x32064e1e, 0x31ef2ae1, - 0x31d805b7, 0x31c0dea1, - 0x31a9b5a0, 0x31928ab4, 0x317b5de0, 0x31642f23, 0x314cfe7f, 0x3135cbf4, - 0x311e9783, 0x3107612e, - 0x30f028f4, 0x30d8eed8, 0x30c1b2da, 0x30aa74fa, 0x3093353a, 0x307bf39b, - 0x3064b01d, 0x304d6ac1, - 0x30362389, 0x301eda75, 0x30078f86, 0x2ff042bd, 0x2fd8f41b, 0x2fc1a3a0, - 0x2faa514f, 0x2f92fd26, - 0x2f7ba729, 0x2f644f56, 0x2f4cf5b0, 0x2f359a37, 0x2f1e3ced, 0x2f06ddd1, - 0x2eef7ce5, 0x2ed81a29, - 0x2ec0b5a0, 0x2ea94f49, 0x2e91e725, 0x2e7a7d36, 0x2e63117c, 0x2e4ba3f8, - 0x2e3434ac, 0x2e1cc397, - 0x2e0550bb, 0x2deddc19, 0x2dd665b2, 0x2dbeed86, 0x2da77397, 0x2d8ff7e5, - 0x2d787a72, 0x2d60fb3e, - 0x2d497a4a, 0x2d31f797, 0x2d1a7325, 0x2d02ecf7, 0x2ceb650d, 0x2cd3db67, - 0x2cbc5006, 0x2ca4c2ed, - 0x2c8d341a, 0x2c75a390, 0x2c5e114f, 0x2c467d58, 0x2c2ee7ad, 0x2c17504d, - 0x2bffb73a, 0x2be81c74, - 0x2bd07ffe, 0x2bb8e1d7, 0x2ba14200, 0x2b89a07b, 0x2b71fd48, 0x2b5a5868, - 0x2b42b1dd, 0x2b2b09a6, - 0x2b135fc6, 0x2afbb43c, 0x2ae4070a, 0x2acc5831, 0x2ab4a7b1, 0x2a9cf58c, - 0x2a8541c3, 0x2a6d8c55, - 0x2a55d545, 0x2a3e1c93, 0x2a266240, 0x2a0ea64d, 0x29f6e8bb, 0x29df298b, - 0x29c768be, 0x29afa654, - 0x2997e24f, 0x29801caf, 0x29685576, 0x29508ca4, 0x2938c23a, 0x2920f63a, - 0x290928a3, 0x28f15978, - 0x28d988b8, 0x28c1b666, 0x28a9e281, 0x28920d0a, 0x287a3604, 0x28625d6d, - 0x284a8349, 0x2832a796, - 0x281aca57, 0x2802eb8c, 0x27eb0b36, 0x27d32956, 0x27bb45ed, 0x27a360fc, - 0x278b7a84, 0x27739285, - 0x275ba901, 0x2743bdf9, 0x272bd16d, 0x2713e35f, 0x26fbf3ce, 0x26e402bd, - 0x26cc102d, 0x26b41c1d, - 0x269c268f, 0x26842f84, 0x266c36fe, 0x26543cfb, 0x263c417f, 0x26244489, - 0x260c461b, 0x25f44635, - 0x25dc44d9, 0x25c44207, 0x25ac3dc0, 0x25943806, 0x257c30d8, 0x25642839, - 0x254c1e28, 0x253412a8, - 0x251c05b8, 0x2503f75a, 0x24ebe78f, 0x24d3d657, 0x24bbc3b4, 0x24a3afa6, - 0x248b9a2f, 0x2473834f, - 0x245b6b07, 0x24435158, 0x242b3644, 0x241319ca, 0x23fafbec, 0x23e2dcac, - 0x23cabc09, 0x23b29a05, - 0x239a76a0, 0x238251dd, 0x236a2bba, 0x2352043b, 0x2339db5e, 0x2321b126, - 0x23098593, 0x22f158a7, - 0x22d92a61, 0x22c0fac4, 0x22a8c9cf, 0x22909785, 0x227863e5, 0x22602ef1, - 0x2247f8aa, 0x222fc111, - 0x22178826, 0x21ff4dea, 0x21e71260, 0x21ced586, 0x21b6975f, 0x219e57eb, - 0x2186172b, 0x216dd521, - 0x215591cc, 0x213d4d2f, 0x21250749, 0x210cc01d, 0x20f477aa, 0x20dc2df2, - 0x20c3e2f5, 0x20ab96b5, - 0x20934933, 0x207afa6f, 0x2062aa6b, 0x204a5927, 0x203206a4, 0x2019b2e4, - 0x20015de7, 0x1fe907ae, - 0x1fd0b03a, 0x1fb8578b, 0x1f9ffda4, 0x1f87a285, 0x1f6f462f, 0x1f56e8a2, - 0x1f3e89e0, 0x1f2629ea, - 0x1f0dc8c0, 0x1ef56664, 0x1edd02d6, 0x1ec49e17, 0x1eac3829, 0x1e93d10c, - 0x1e7b68c2, 0x1e62ff4a, - 0x1e4a94a7, 0x1e3228d9, 0x1e19bbe0, 0x1e014dbf, 0x1de8de75, 0x1dd06e04, - 0x1db7fc6d, 0x1d9f89b1, - 0x1d8715d0, 0x1d6ea0cc, 0x1d562aa6, 0x1d3db35e, 0x1d253af5, 0x1d0cc16c, - 0x1cf446c5, 0x1cdbcb00, - 0x1cc34e1f, 0x1caad021, 0x1c925109, 0x1c79d0d6, 0x1c614f8b, 0x1c48cd27, - 0x1c3049ac, 0x1c17c51b, - 0x1bff3f75, 0x1be6b8ba, 0x1bce30ec, 0x1bb5a80c, 0x1b9d1e1a, 0x1b849317, - 0x1b6c0705, 0x1b5379e5, - 0x1b3aebb6, 0x1b225c7b, 0x1b09cc34, 0x1af13ae3, 0x1ad8a887, 0x1ac01522, - 0x1aa780b6, 0x1a8eeb42, - 0x1a7654c8, 0x1a5dbd49, 0x1a4524c6, 0x1a2c8b3f, 0x1a13f0b6, 0x19fb552c, - 0x19e2b8a2, 0x19ca1b17, - 0x19b17c8f, 0x1998dd09, 0x19803c86, 0x19679b07, 0x194ef88e, 0x1936551b, - 0x191db0af, 0x19050b4b, - 0x18ec64f0, 0x18d3bda0, 0x18bb155a, 0x18a26c20, 0x1889c1f3, 0x187116d4, - 0x18586ac3, 0x183fbdc3, - 0x18270fd3, 0x180e60f4, 0x17f5b129, 0x17dd0070, 0x17c44ecd, 0x17ab9c3e, - 0x1792e8c6, 0x177a3466, - 0x17617f1d, 0x1748c8ee, 0x173011d9, 0x171759df, 0x16fea102, 0x16e5e741, - 0x16cd2c9f, 0x16b4711b, - 0x169bb4b7, 0x1682f774, 0x166a3953, 0x16517a55, 0x1638ba7a, 0x161ff9c4, - 0x16073834, 0x15ee75cb, - 0x15d5b288, 0x15bcee6f, 0x15a4297f, 0x158b63b9, 0x15729d1f, 0x1559d5b1, - 0x15410d70, 0x1528445d, - 0x150f7a7a, 0x14f6afc7, 0x14dde445, 0x14c517f4, 0x14ac4ad7, 0x14937cee, - 0x147aae3a, 0x1461debc, - 0x14490e74, 0x14303d65, 0x14176b8e, 0x13fe98f1, 0x13e5c58e, 0x13ccf167, - 0x13b41c7d, 0x139b46d0, - 0x13827062, 0x13699933, 0x1350c144, 0x1337e897, 0x131f0f2c, 0x13063505, - 0x12ed5a21, 0x12d47e83, - 0x12bba22b, 0x12a2c51b, 0x1289e752, 0x127108d2, 0x1258299c, 0x123f49b2, - 0x12266913, 0x120d87c1, - 0x11f4a5bd, 0x11dbc307, 0x11c2dfa2, 0x11a9fb8d, 0x119116c9, 0x11783159, - 0x115f4b3c, 0x11466473, - 0x112d7d00, 0x111494e4, 0x10fbac1e, 0x10e2c2b2, 0x10c9d89e, 0x10b0ede5, - 0x10980287, 0x107f1686, - 0x106629e1, 0x104d3c9b, 0x10344eb4, 0x101b602d, 0x10027107, 0xfe98143, - 0xfd090e1, 0xfb79fe4, - 0xf9eae4c, 0xf85bc19, 0xf6cc94e, 0xf53d5ea, 0xf3ae1ee, 0xf21ed5d, 0xf08f836, - 0xef0027b, - 0xed70c2c, 0xebe154b, 0xea51dd8, 0xe8c25d5, 0xe732d42, 0xe5a3421, 0xe413a72, - 0xe284036, - 0xe0f456f, 0xdf64a1c, 0xddd4e40, 0xdc451dc, 0xdab54ef, 0xd92577b, 0xd795982, - 0xd605b03, - 0xd475c00, 0xd2e5c7b, 0xd155c73, 0xcfc5bea, 0xce35ae1, 0xcca5959, 0xcb15752, - 0xc9854cf, - 0xc7f51cf, 0xc664e53, 0xc4d4a5d, 0xc3445ee, 0xc1b4107, 0xc023ba7, 0xbe935d2, - 0xbd02f87, - 0xbb728c7, 0xb9e2193, 0xb8519ed, 0xb6c11d5, 0xb53094d, 0xb3a0055, 0xb20f6ee, - 0xb07ed19, - 0xaeee2d7, 0xad5d829, 0xabccd11, 0xaa3c18e, 0xa8ab5a2, 0xa71a94f, 0xa589c94, - 0xa3f8f73, - 0xa2681ed, 0xa0d7403, 0x9f465b5, 0x9db5706, 0x9c247f5, 0x9a93884, 0x99028b3, - 0x9771884, - 0x95e07f8, 0x944f70f, 0x92be5ca, 0x912d42c, 0x8f9c233, 0x8e0afe2, 0x8c79d3a, - 0x8ae8a3a, - 0x89576e5, 0x87c633c, 0x8634f3e, 0x84a3aee, 0x831264c, 0x8181159, 0x7fefc16, - 0x7e5e685, - 0x7ccd0a5, 0x7b3ba78, 0x79aa400, 0x7818d3c, 0x768762e, 0x74f5ed7, 0x7364738, - 0x71d2f52, - 0x7041726, 0x6eafeb4, 0x6d1e5fe, 0x6b8cd05, 0x69fb3c9, 0x6869a4c, 0x66d808f, - 0x6546692, - 0x63b4c57, 0x62231de, 0x6091729, 0x5effc38, 0x5d6e10c, 0x5bdc5a7, 0x5a4aa09, - 0x58b8e34, - 0x5727228, 0x55955e6, 0x540396f, 0x5271cc4, 0x50dffe7, 0x4f4e2d8, 0x4dbc597, - 0x4c2a827, - 0x4a98a88, 0x4906cbb, 0x4774ec1, 0x45e309a, 0x4451249, 0x42bf3cd, 0x412d528, - 0x3f9b65b, - 0x3e09767, 0x3c7784d, 0x3ae590d, 0x39539a9, 0x37c1a22, 0x362fa78, 0x349daac, - 0x330bac1, - 0x3179ab5, 0x2fe7a8c, 0x2e55a44, 0x2cc39e1, 0x2b31961, 0x299f8c7, 0x280d813, - 0x267b747, - 0x24e9662, 0x2357567, 0x21c5457, 0x2033331, 0x1ea11f7, 0x1d0f0ab, 0x1b7cf4d, - 0x19eaddd, - 0x1858c5e, 0x16c6ad0, 0x1534934, 0x13a278a, 0x12105d5, 0x107e414, 0xeec249, - 0xd5a075, - 0xbc7e99, 0xa35cb5, 0x8a3acb, 0x7118dc, 0x57f6e9, 0x3ed4f2, 0x25b2f8, - 0xc90fe, - -}; - -/** - * @brief Initialization function for the Q31 DCT4/IDCT4. - * @param[in,out] *S points to an instance of Q31 DCT4/IDCT4 structure. - * @param[in] *S_RFFT points to an instance of Q31 RFFT/RIFFT structure - * @param[in] *S_CFFT points to an instance of Q31 CFFT/CIFFT structure - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. - * \par Normalizing factor: - * The normalizing factor is sqrt(2/N), which depends on the size of transform N. - * Normalizing factors in 1.31 format are mentioned in the table below for different DCT sizes: - * \image html dct4NormalizingQ31Table.gif - */ - -arm_status arm_dct4_init_q31( - arm_dct4_instance_q31 * S, - arm_rfft_instance_q31 * S_RFFT, - arm_cfft_radix4_instance_q31 * S_CFFT, - uint16_t N, - uint16_t Nby2, - q31_t normalize) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initializing the pointer array with the weight table base addresses of different lengths */ - q31_t *twiddlePtr[3] = { (q31_t *) WeightsQ31_128, (q31_t *) WeightsQ31_512, - (q31_t *) WeightsQ31_2048 - }; - - /* Initializing the pointer array with the cos factor table base addresses of different lengths */ - q31_t *pCosFactor[3] = - { (q31_t *) cos_factorsQ31_128, (q31_t *) cos_factorsQ31_512, - (q31_t *) cos_factorsQ31_2048 - }; - - /* Initialize the DCT4 length */ - S->N = N; - - /* Initialize the half of DCT4 length */ - S->Nby2 = Nby2; - - /* Initialize the DCT4 Normalizing factor */ - S->normalize = normalize; - - /* Initialize Real FFT Instance */ - S->pRfft = S_RFFT; - - /* Initialize Complex FFT Instance */ - S->pCfft = S_CFFT; - - switch (N) - { - /* Initialize the table modifier values */ - case 2048u: - S->pTwiddle = twiddlePtr[2]; - S->pCosFactor = pCosFactor[2]; - break; - case 512u: - S->pTwiddle = twiddlePtr[1]; - S->pCosFactor = pCosFactor[1]; - break; - case 128u: - S->pTwiddle = twiddlePtr[0]; - S->pCosFactor = pCosFactor[0]; - break; - default: - status = ARM_MATH_ARGUMENT_ERROR; - } - - /* Initialize the RFFT/RIFFT Function */ - arm_rfft_init_q31(S->pRfft, S->pCfft, S->N, 0, 1); - - /* return the status of DCT4 Init function */ - return (status); -} - -/** - * @} end of DCT4_IDCT4 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_dct4_init_q31.c +* +* Description: Initialization function of DCT-4 & IDCT4 Q31 +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup DCT4_IDCT4 + * @{ + */ + +/* +* @brief Weights Table +*/ + +/** +* \par +* Weights tables are generated using the formula :
weights[n] = e^(-j*n*pi/(2*N))
+* \par +* C command to generate the table +*
   
+* for(i = 0; i< N; i++)   
+* {   
+*   weights[2*i]= cos(i*c);   
+*   weights[(2*i)+1]= -sin(i * c);   
+* } 
+* \par +* where N is the Number of weights to be calculated and c is pi/(2*N) +* \par +* Convert the output to q31 format by multiplying with 2^31 and saturated if required. +* \par +* In the tables below the real and imaginary values are placed alternatively, hence the +* array length is 2*N. +*/ + +static const q31_t WeightsQ31_128[256] = { + 0x7fffffff, 0x0, 0x7ffd885a, 0xfe6de2e0, 0x7ff62182, 0xfcdbd541, 0x7fe9cbc0, + 0xfb49e6a3, + 0x7fd8878e, 0xf9b82684, 0x7fc25596, 0xf826a462, 0x7fa736b4, 0xf6956fb7, + 0x7f872bf3, 0xf50497fb, + 0x7f62368f, 0xf3742ca2, 0x7f3857f6, 0xf1e43d1c, 0x7f0991c4, 0xf054d8d5, + 0x7ed5e5c6, 0xeec60f31, + 0x7e9d55fc, 0xed37ef91, 0x7e5fe493, 0xebaa894f, 0x7e1d93ea, 0xea1debbb, + 0x7dd6668f, 0xe8922622, + 0x7d8a5f40, 0xe70747c4, 0x7d3980ec, 0xe57d5fda, 0x7ce3ceb2, 0xe3f47d96, + 0x7c894bde, 0xe26cb01b, + 0x7c29fbee, 0xe0e60685, 0x7bc5e290, 0xdf608fe4, 0x7b5d039e, 0xdddc5b3b, + 0x7aef6323, 0xdc597781, + 0x7a7d055b, 0xdad7f3a2, 0x7a05eead, 0xd957de7a, 0x798a23b1, 0xd7d946d8, + 0x7909a92d, 0xd65c3b7b, + 0x78848414, 0xd4e0cb15, 0x77fab989, 0xd3670446, 0x776c4edb, 0xd1eef59e, + 0x76d94989, 0xd078ad9e, + 0x7641af3d, 0xcf043ab3, 0x75a585cf, 0xcd91ab39, 0x7504d345, 0xcc210d79, + 0x745f9dd1, 0xcab26fa9, + 0x73b5ebd1, 0xc945dfec, 0x7307c3d0, 0xc7db6c50, 0x72552c85, 0xc67322ce, + 0x719e2cd2, 0xc50d1149, + 0x70e2cbc6, 0xc3a94590, 0x7023109a, 0xc247cd5a, 0x6f5f02b2, 0xc0e8b648, + 0x6e96a99d, 0xbf8c0de3, + 0x6dca0d14, 0xbe31e19b, 0x6cf934fc, 0xbcda3ecb, 0x6c242960, 0xbb8532b0, + 0x6b4af279, 0xba32ca71, + 0x6a6d98a4, 0xb8e31319, 0x698c246c, 0xb796199b, 0x68a69e81, 0xb64beacd, + 0x67bd0fbd, 0xb5049368, + 0x66cf8120, 0xb3c0200c, 0x65ddfbd3, 0xb27e9d3c, 0x64e88926, 0xb140175b, + 0x63ef3290, 0xb0049ab3, + 0x62f201ac, 0xaecc336c, 0x61f1003f, 0xad96ed92, 0x60ec3830, 0xac64d510, + 0x5fe3b38d, 0xab35f5b5, + 0x5ed77c8a, 0xaa0a5b2e, 0x5dc79d7c, 0xa8e21106, 0x5cb420e0, 0xa7bd22ac, + 0x5b9d1154, 0xa69b9b68, + 0x5a82799a, 0xa57d8666, 0x59646498, 0xa462eeac, 0x5842dd54, 0xa34bdf20, + 0x571deefa, 0xa2386284, + 0x55f5a4d2, 0xa1288376, 0x54ca0a4b, 0xa01c4c73, 0x539b2af0, 0x9f13c7d0, + 0x5269126e, 0x9e0effc1, + 0x5133cc94, 0x9d0dfe54, 0x4ffb654d, 0x9c10cd70, 0x4ebfe8a5, 0x9b1776da, + 0x4d8162c4, 0x9a22042d, + 0x4c3fdff4, 0x99307ee0, 0x4afb6c98, 0x9842f043, 0x49b41533, 0x9759617f, + 0x4869e665, 0x9673db94, + 0x471cece7, 0x9592675c, 0x45cd358f, 0x94b50d87, 0x447acd50, 0x93dbd6a0, + 0x4325c135, 0x9306cb04, + 0x41ce1e65, 0x9235f2ec, 0x4073f21d, 0x91695663, 0x3f1749b8, 0x90a0fd4e, + 0x3db832a6, 0x8fdcef66, + 0x3c56ba70, 0x8f1d343a, 0x3af2eeb7, 0x8e61d32e, 0x398cdd32, 0x8daad37b, + 0x382493b0, 0x8cf83c30, + 0x36ba2014, 0x8c4a142f, 0x354d9057, 0x8ba0622f, 0x33def287, 0x8afb2cbb, + 0x326e54c7, 0x8a5a7a31, + 0x30fbc54d, 0x89be50c3, 0x2f875262, 0x8926b677, 0x2e110a62, 0x8893b125, + 0x2c98fbba, 0x88054677, + 0x2b1f34eb, 0x877b7bec, 0x29a3c485, 0x86f656d3, 0x2826b928, 0x8675dc4f, + 0x26a82186, 0x85fa1153, + 0x25280c5e, 0x8582faa5, 0x23a6887f, 0x85109cdd, 0x2223a4c5, 0x84a2fc62, + 0x209f701c, 0x843a1d70, + 0x1f19f97b, 0x83d60412, 0x1d934fe5, 0x8376b422, 0x1c0b826a, 0x831c314e, + 0x1a82a026, 0x82c67f14, + 0x18f8b83c, 0x8275a0c0, 0x176dd9de, 0x82299971, 0x15e21445, 0x81e26c16, + 0x145576b1, 0x81a01b6d, + 0x12c8106f, 0x8162aa04, 0x1139f0cf, 0x812a1a3a, 0xfab272b, 0x80f66e3c, + 0xe1bc2e4, 0x80c7a80a, + 0xc8bd35e, 0x809dc971, 0xafb6805, 0x8078d40d, 0x96a9049, 0x8058c94c, + 0x7d95b9e, 0x803daa6a, + 0x647d97c, 0x80277872, 0x4b6195d, 0x80163440, 0x3242abf, 0x8009de7e, + 0x1921d20, 0x800277a6, +}; + +static const q31_t WeightsQ31_512[1024] = { + 0x7fffffff, 0x0, 0x7fffd886, 0xff9b781d, 0x7fff6216, 0xff36f078, 0x7ffe9cb2, + 0xfed2694f, + 0x7ffd885a, 0xfe6de2e0, 0x7ffc250f, 0xfe095d69, 0x7ffa72d1, 0xfda4d929, + 0x7ff871a2, 0xfd40565c, + 0x7ff62182, 0xfcdbd541, 0x7ff38274, 0xfc775616, 0x7ff09478, 0xfc12d91a, + 0x7fed5791, 0xfbae5e89, + 0x7fe9cbc0, 0xfb49e6a3, 0x7fe5f108, 0xfae571a4, 0x7fe1c76b, 0xfa80ffcb, + 0x7fdd4eec, 0xfa1c9157, + 0x7fd8878e, 0xf9b82684, 0x7fd37153, 0xf953bf91, 0x7fce0c3e, 0xf8ef5cbb, + 0x7fc85854, 0xf88afe42, + 0x7fc25596, 0xf826a462, 0x7fbc040a, 0xf7c24f59, 0x7fb563b3, 0xf75dff66, + 0x7fae7495, 0xf6f9b4c6, + 0x7fa736b4, 0xf6956fb7, 0x7f9faa15, 0xf6313077, 0x7f97cebd, 0xf5ccf743, + 0x7f8fa4b0, 0xf568c45b, + 0x7f872bf3, 0xf50497fb, 0x7f7e648c, 0xf4a07261, 0x7f754e80, 0xf43c53cb, + 0x7f6be9d4, 0xf3d83c77, + 0x7f62368f, 0xf3742ca2, 0x7f5834b7, 0xf310248a, 0x7f4de451, 0xf2ac246e, + 0x7f434563, 0xf2482c8a, + 0x7f3857f6, 0xf1e43d1c, 0x7f2d1c0e, 0xf1805662, 0x7f2191b4, 0xf11c789a, + 0x7f15b8ee, 0xf0b8a401, + 0x7f0991c4, 0xf054d8d5, 0x7efd1c3c, 0xeff11753, 0x7ef05860, 0xef8d5fb8, + 0x7ee34636, 0xef29b243, + 0x7ed5e5c6, 0xeec60f31, 0x7ec8371a, 0xee6276bf, 0x7eba3a39, 0xedfee92b, + 0x7eabef2c, 0xed9b66b2, + 0x7e9d55fc, 0xed37ef91, 0x7e8e6eb2, 0xecd48407, 0x7e7f3957, 0xec71244f, + 0x7e6fb5f4, 0xec0dd0a8, + 0x7e5fe493, 0xebaa894f, 0x7e4fc53e, 0xeb474e81, 0x7e3f57ff, 0xeae4207a, + 0x7e2e9cdf, 0xea80ff7a, + 0x7e1d93ea, 0xea1debbb, 0x7e0c3d29, 0xe9bae57d, 0x7dfa98a8, 0xe957ecfb, + 0x7de8a670, 0xe8f50273, + 0x7dd6668f, 0xe8922622, 0x7dc3d90d, 0xe82f5844, 0x7db0fdf8, 0xe7cc9917, + 0x7d9dd55a, 0xe769e8d8, + 0x7d8a5f40, 0xe70747c4, 0x7d769bb5, 0xe6a4b616, 0x7d628ac6, 0xe642340d, + 0x7d4e2c7f, 0xe5dfc1e5, + 0x7d3980ec, 0xe57d5fda, 0x7d24881b, 0xe51b0e2a, 0x7d0f4218, 0xe4b8cd11, + 0x7cf9aef0, 0xe4569ccb, + 0x7ce3ceb2, 0xe3f47d96, 0x7ccda169, 0xe3926fad, 0x7cb72724, 0xe330734d, + 0x7ca05ff1, 0xe2ce88b3, + 0x7c894bde, 0xe26cb01b, 0x7c71eaf9, 0xe20ae9c1, 0x7c5a3d50, 0xe1a935e2, + 0x7c4242f2, 0xe14794ba, + 0x7c29fbee, 0xe0e60685, 0x7c116853, 0xe0848b7f, 0x7bf88830, 0xe02323e5, + 0x7bdf5b94, 0xdfc1cff3, + 0x7bc5e290, 0xdf608fe4, 0x7bac1d31, 0xdeff63f4, 0x7b920b89, 0xde9e4c60, + 0x7b77ada8, 0xde3d4964, + 0x7b5d039e, 0xdddc5b3b, 0x7b420d7a, 0xdd7b8220, 0x7b26cb4f, 0xdd1abe51, + 0x7b0b3d2c, 0xdcba1008, + 0x7aef6323, 0xdc597781, 0x7ad33d45, 0xdbf8f4f8, 0x7ab6cba4, 0xdb9888a8, + 0x7a9a0e50, 0xdb3832cd, + 0x7a7d055b, 0xdad7f3a2, 0x7a5fb0d8, 0xda77cb63, 0x7a4210d8, 0xda17ba4a, + 0x7a24256f, 0xd9b7c094, + 0x7a05eead, 0xd957de7a, 0x79e76ca7, 0xd8f81439, 0x79c89f6e, 0xd898620c, + 0x79a98715, 0xd838c82d, + 0x798a23b1, 0xd7d946d8, 0x796a7554, 0xd779de47, 0x794a7c12, 0xd71a8eb5, + 0x792a37fe, 0xd6bb585e, + 0x7909a92d, 0xd65c3b7b, 0x78e8cfb2, 0xd5fd3848, 0x78c7aba2, 0xd59e4eff, + 0x78a63d11, 0xd53f7fda, + 0x78848414, 0xd4e0cb15, 0x786280bf, 0xd48230e9, 0x78403329, 0xd423b191, + 0x781d9b65, 0xd3c54d47, + 0x77fab989, 0xd3670446, 0x77d78daa, 0xd308d6c7, 0x77b417df, 0xd2aac504, + 0x7790583e, 0xd24ccf39, + 0x776c4edb, 0xd1eef59e, 0x7747fbce, 0xd191386e, 0x77235f2d, 0xd13397e2, + 0x76fe790e, 0xd0d61434, + 0x76d94989, 0xd078ad9e, 0x76b3d0b4, 0xd01b6459, 0x768e0ea6, 0xcfbe389f, + 0x76680376, 0xcf612aaa, + 0x7641af3d, 0xcf043ab3, 0x761b1211, 0xcea768f2, 0x75f42c0b, 0xce4ab5a2, + 0x75ccfd42, 0xcdee20fc, + 0x75a585cf, 0xcd91ab39, 0x757dc5ca, 0xcd355491, 0x7555bd4c, 0xccd91d3d, + 0x752d6c6c, 0xcc7d0578, + 0x7504d345, 0xcc210d79, 0x74dbf1ef, 0xcbc53579, 0x74b2c884, 0xcb697db0, + 0x7489571c, 0xcb0de658, + 0x745f9dd1, 0xcab26fa9, 0x74359cbd, 0xca5719db, 0x740b53fb, 0xc9fbe527, + 0x73e0c3a3, 0xc9a0d1c5, + 0x73b5ebd1, 0xc945dfec, 0x738acc9e, 0xc8eb0fd6, 0x735f6626, 0xc89061ba, + 0x7333b883, 0xc835d5d0, + 0x7307c3d0, 0xc7db6c50, 0x72db8828, 0xc7812572, 0x72af05a7, 0xc727016d, + 0x72823c67, 0xc6cd0079, + 0x72552c85, 0xc67322ce, 0x7227d61c, 0xc61968a2, 0x71fa3949, 0xc5bfd22e, + 0x71cc5626, 0xc5665fa9, + 0x719e2cd2, 0xc50d1149, 0x716fbd68, 0xc4b3e746, 0x71410805, 0xc45ae1d7, + 0x71120cc5, 0xc4020133, + 0x70e2cbc6, 0xc3a94590, 0x70b34525, 0xc350af26, 0x708378ff, 0xc2f83e2a, + 0x70536771, 0xc29ff2d4, + 0x7023109a, 0xc247cd5a, 0x6ff27497, 0xc1efcdf3, 0x6fc19385, 0xc197f4d4, + 0x6f906d84, 0xc1404233, + 0x6f5f02b2, 0xc0e8b648, 0x6f2d532c, 0xc0915148, 0x6efb5f12, 0xc03a1368, + 0x6ec92683, 0xbfe2fcdf, + 0x6e96a99d, 0xbf8c0de3, 0x6e63e87f, 0xbf3546a8, 0x6e30e34a, 0xbedea765, + 0x6dfd9a1c, 0xbe88304f, + 0x6dca0d14, 0xbe31e19b, 0x6d963c54, 0xbddbbb7f, 0x6d6227fa, 0xbd85be30, + 0x6d2dd027, 0xbd2fe9e2, + 0x6cf934fc, 0xbcda3ecb, 0x6cc45698, 0xbc84bd1f, 0x6c8f351c, 0xbc2f6513, + 0x6c59d0a9, 0xbbda36dd, + 0x6c242960, 0xbb8532b0, 0x6bee3f62, 0xbb3058c0, 0x6bb812d1, 0xbadba943, + 0x6b81a3cd, 0xba87246d, + 0x6b4af279, 0xba32ca71, 0x6b13fef5, 0xb9de9b83, 0x6adcc964, 0xb98a97d8, + 0x6aa551e9, 0xb936bfa4, + 0x6a6d98a4, 0xb8e31319, 0x6a359db9, 0xb88f926d, 0x69fd614a, 0xb83c3dd1, + 0x69c4e37a, 0xb7e9157a, + 0x698c246c, 0xb796199b, 0x69532442, 0xb7434a67, 0x6919e320, 0xb6f0a812, + 0x68e06129, 0xb69e32cd, + 0x68a69e81, 0xb64beacd, 0x686c9b4b, 0xb5f9d043, 0x683257ab, 0xb5a7e362, + 0x67f7d3c5, 0xb556245e, + 0x67bd0fbd, 0xb5049368, 0x67820bb7, 0xb4b330b3, 0x6746c7d8, 0xb461fc70, + 0x670b4444, 0xb410f6d3, + 0x66cf8120, 0xb3c0200c, 0x66937e91, 0xb36f784f, 0x66573cbb, 0xb31effcc, + 0x661abbc5, 0xb2ceb6b5, + 0x65ddfbd3, 0xb27e9d3c, 0x65a0fd0b, 0xb22eb392, 0x6563bf92, 0xb1def9e9, + 0x6526438f, 0xb18f7071, + 0x64e88926, 0xb140175b, 0x64aa907f, 0xb0f0eeda, 0x646c59bf, 0xb0a1f71d, + 0x642de50d, 0xb0533055, + 0x63ef3290, 0xb0049ab3, 0x63b0426d, 0xafb63667, 0x637114cc, 0xaf6803a2, + 0x6331a9d4, 0xaf1a0293, + 0x62f201ac, 0xaecc336c, 0x62b21c7b, 0xae7e965b, 0x6271fa69, 0xae312b92, + 0x62319b9d, 0xade3f33e, + 0x61f1003f, 0xad96ed92, 0x61b02876, 0xad4a1aba, 0x616f146c, 0xacfd7ae8, + 0x612dc447, 0xacb10e4b, + 0x60ec3830, 0xac64d510, 0x60aa7050, 0xac18cf69, 0x60686ccf, 0xabccfd83, + 0x60262dd6, 0xab815f8d, + 0x5fe3b38d, 0xab35f5b5, 0x5fa0fe1f, 0xaaeac02c, 0x5f5e0db3, 0xaa9fbf1e, + 0x5f1ae274, 0xaa54f2ba, + 0x5ed77c8a, 0xaa0a5b2e, 0x5e93dc1f, 0xa9bff8a8, 0x5e50015d, 0xa975cb57, + 0x5e0bec6e, 0xa92bd367, + 0x5dc79d7c, 0xa8e21106, 0x5d8314b1, 0xa8988463, 0x5d3e5237, 0xa84f2daa, + 0x5cf95638, 0xa8060d08, + 0x5cb420e0, 0xa7bd22ac, 0x5c6eb258, 0xa7746ec0, 0x5c290acc, 0xa72bf174, + 0x5be32a67, 0xa6e3aaf2, + 0x5b9d1154, 0xa69b9b68, 0x5b56bfbd, 0xa653c303, 0x5b1035cf, 0xa60c21ee, + 0x5ac973b5, 0xa5c4b855, + 0x5a82799a, 0xa57d8666, 0x5a3b47ab, 0xa5368c4b, 0x59f3de12, 0xa4efca31, + 0x59ac3cfd, 0xa4a94043, + 0x59646498, 0xa462eeac, 0x591c550e, 0xa41cd599, 0x58d40e8c, 0xa3d6f534, + 0x588b9140, 0xa3914da8, + 0x5842dd54, 0xa34bdf20, 0x57f9f2f8, 0xa306a9c8, 0x57b0d256, 0xa2c1adc9, + 0x57677b9d, 0xa27ceb4f, + 0x571deefa, 0xa2386284, 0x56d42c99, 0xa1f41392, 0x568a34a9, 0xa1affea3, + 0x56400758, 0xa16c23e1, + 0x55f5a4d2, 0xa1288376, 0x55ab0d46, 0xa0e51d8c, 0x556040e2, 0xa0a1f24d, + 0x55153fd4, 0xa05f01e1, + 0x54ca0a4b, 0xa01c4c73, 0x547ea073, 0x9fd9d22a, 0x5433027d, 0x9f979331, + 0x53e73097, 0x9f558fb0, + 0x539b2af0, 0x9f13c7d0, 0x534ef1b5, 0x9ed23bb9, 0x53028518, 0x9e90eb94, + 0x52b5e546, 0x9e4fd78a, + 0x5269126e, 0x9e0effc1, 0x521c0cc2, 0x9dce6463, 0x51ced46e, 0x9d8e0597, + 0x518169a5, 0x9d4de385, + 0x5133cc94, 0x9d0dfe54, 0x50e5fd6d, 0x9cce562c, 0x5097fc5e, 0x9c8eeb34, + 0x5049c999, 0x9c4fbd93, + 0x4ffb654d, 0x9c10cd70, 0x4faccfab, 0x9bd21af3, 0x4f5e08e3, 0x9b93a641, + 0x4f0f1126, 0x9b556f81, + 0x4ebfe8a5, 0x9b1776da, 0x4e708f8f, 0x9ad9bc71, 0x4e210617, 0x9a9c406e, + 0x4dd14c6e, 0x9a5f02f5, + 0x4d8162c4, 0x9a22042d, 0x4d31494b, 0x99e5443b, 0x4ce10034, 0x99a8c345, + 0x4c9087b1, 0x996c816f, + 0x4c3fdff4, 0x99307ee0, 0x4bef092d, 0x98f4bbbc, 0x4b9e0390, 0x98b93828, + 0x4b4ccf4d, 0x987df449, + 0x4afb6c98, 0x9842f043, 0x4aa9dba2, 0x98082c3b, 0x4a581c9e, 0x97cda855, + 0x4a062fbd, 0x979364b5, + 0x49b41533, 0x9759617f, 0x4961cd33, 0x971f9ed7, 0x490f57ee, 0x96e61ce0, + 0x48bcb599, 0x96acdbbe, + 0x4869e665, 0x9673db94, 0x4816ea86, 0x963b1c86, 0x47c3c22f, 0x96029eb6, + 0x47706d93, 0x95ca6247, + 0x471cece7, 0x9592675c, 0x46c9405c, 0x955aae17, 0x46756828, 0x9523369c, + 0x4621647d, 0x94ec010b, + 0x45cd358f, 0x94b50d87, 0x4578db93, 0x947e5c33, 0x452456bd, 0x9447ed2f, + 0x44cfa740, 0x9411c09e, + 0x447acd50, 0x93dbd6a0, 0x4425c923, 0x93a62f57, 0x43d09aed, 0x9370cae4, + 0x437b42e1, 0x933ba968, + 0x4325c135, 0x9306cb04, 0x42d0161e, 0x92d22fd9, 0x427a41d0, 0x929dd806, + 0x42244481, 0x9269c3ac, + 0x41ce1e65, 0x9235f2ec, 0x4177cfb1, 0x920265e4, 0x4121589b, 0x91cf1cb6, + 0x40cab958, 0x919c1781, + 0x4073f21d, 0x91695663, 0x401d0321, 0x9136d97d, 0x3fc5ec98, 0x9104a0ee, + 0x3f6eaeb8, 0x90d2acd4, + 0x3f1749b8, 0x90a0fd4e, 0x3ebfbdcd, 0x906f927c, 0x3e680b2c, 0x903e6c7b, + 0x3e10320d, 0x900d8b69, + 0x3db832a6, 0x8fdcef66, 0x3d600d2c, 0x8fac988f, 0x3d07c1d6, 0x8f7c8701, + 0x3caf50da, 0x8f4cbadb, + 0x3c56ba70, 0x8f1d343a, 0x3bfdfecd, 0x8eedf33b, 0x3ba51e29, 0x8ebef7fb, + 0x3b4c18ba, 0x8e904298, + 0x3af2eeb7, 0x8e61d32e, 0x3a99a057, 0x8e33a9da, 0x3a402dd2, 0x8e05c6b7, + 0x39e6975e, 0x8dd829e4, + 0x398cdd32, 0x8daad37b, 0x3932ff87, 0x8d7dc399, 0x38d8fe93, 0x8d50fa59, + 0x387eda8e, 0x8d2477d8, + 0x382493b0, 0x8cf83c30, 0x37ca2a30, 0x8ccc477d, 0x376f9e46, 0x8ca099da, + 0x3714f02a, 0x8c753362, + 0x36ba2014, 0x8c4a142f, 0x365f2e3b, 0x8c1f3c5d, 0x36041ad9, 0x8bf4ac05, + 0x35a8e625, 0x8bca6343, + 0x354d9057, 0x8ba0622f, 0x34f219a8, 0x8b76a8e4, 0x34968250, 0x8b4d377c, + 0x343aca87, 0x8b240e11, + 0x33def287, 0x8afb2cbb, 0x3382fa88, 0x8ad29394, 0x3326e2c3, 0x8aaa42b4, + 0x32caab6f, 0x8a823a36, + 0x326e54c7, 0x8a5a7a31, 0x3211df04, 0x8a3302be, 0x31b54a5e, 0x8a0bd3f5, + 0x3158970e, 0x89e4edef, + 0x30fbc54d, 0x89be50c3, 0x309ed556, 0x8997fc8a, 0x3041c761, 0x8971f15a, + 0x2fe49ba7, 0x894c2f4c, + 0x2f875262, 0x8926b677, 0x2f29ebcc, 0x890186f2, 0x2ecc681e, 0x88dca0d3, + 0x2e6ec792, 0x88b80432, + 0x2e110a62, 0x8893b125, 0x2db330c7, 0x886fa7c2, 0x2d553afc, 0x884be821, + 0x2cf72939, 0x88287256, + 0x2c98fbba, 0x88054677, 0x2c3ab2b9, 0x87e2649b, 0x2bdc4e6f, 0x87bfccd7, + 0x2b7dcf17, 0x879d7f41, + 0x2b1f34eb, 0x877b7bec, 0x2ac08026, 0x8759c2ef, 0x2a61b101, 0x8738545e, + 0x2a02c7b8, 0x8717304e, + 0x29a3c485, 0x86f656d3, 0x2944a7a2, 0x86d5c802, 0x28e5714b, 0x86b583ee, + 0x288621b9, 0x86958aac, + 0x2826b928, 0x8675dc4f, 0x27c737d3, 0x865678eb, 0x27679df4, 0x86376092, + 0x2707ebc7, 0x86189359, + 0x26a82186, 0x85fa1153, 0x26483f6c, 0x85dbda91, 0x25e845b6, 0x85bdef28, + 0x2588349d, 0x85a04f28, + 0x25280c5e, 0x8582faa5, 0x24c7cd33, 0x8565f1b0, 0x24677758, 0x8549345c, + 0x24070b08, 0x852cc2bb, + 0x23a6887f, 0x85109cdd, 0x2345eff8, 0x84f4c2d4, 0x22e541af, 0x84d934b1, + 0x22847de0, 0x84bdf286, + 0x2223a4c5, 0x84a2fc62, 0x21c2b69c, 0x84885258, 0x2161b3a0, 0x846df477, + 0x21009c0c, 0x8453e2cf, + 0x209f701c, 0x843a1d70, 0x203e300d, 0x8420a46c, 0x1fdcdc1b, 0x840777d0, + 0x1f7b7481, 0x83ee97ad, + 0x1f19f97b, 0x83d60412, 0x1eb86b46, 0x83bdbd0e, 0x1e56ca1e, 0x83a5c2b0, + 0x1df5163f, 0x838e1507, + 0x1d934fe5, 0x8376b422, 0x1d31774d, 0x835fa00f, 0x1ccf8cb3, 0x8348d8dc, + 0x1c6d9053, 0x83325e97, + 0x1c0b826a, 0x831c314e, 0x1ba96335, 0x83065110, 0x1b4732ef, 0x82f0bde8, + 0x1ae4f1d6, 0x82db77e5, + 0x1a82a026, 0x82c67f14, 0x1a203e1b, 0x82b1d381, 0x19bdcbf3, 0x829d753a, + 0x195b49ea, 0x8289644b, + 0x18f8b83c, 0x8275a0c0, 0x18961728, 0x82622aa6, 0x183366e9, 0x824f0208, + 0x17d0a7bc, 0x823c26f3, + 0x176dd9de, 0x82299971, 0x170afd8d, 0x82175990, 0x16a81305, 0x82056758, + 0x16451a83, 0x81f3c2d7, + 0x15e21445, 0x81e26c16, 0x157f0086, 0x81d16321, 0x151bdf86, 0x81c0a801, + 0x14b8b17f, 0x81b03ac2, + 0x145576b1, 0x81a01b6d, 0x13f22f58, 0x81904a0c, 0x138edbb1, 0x8180c6a9, + 0x132b7bf9, 0x8171914e, + 0x12c8106f, 0x8162aa04, 0x1264994e, 0x815410d4, 0x120116d5, 0x8145c5c7, + 0x119d8941, 0x8137c8e6, + 0x1139f0cf, 0x812a1a3a, 0x10d64dbd, 0x811cb9ca, 0x1072a048, 0x810fa7a0, + 0x100ee8ad, 0x8102e3c4, + 0xfab272b, 0x80f66e3c, 0xf475bff, 0x80ea4712, 0xee38766, 0x80de6e4c, + 0xe7fa99e, 0x80d2e3f2, + 0xe1bc2e4, 0x80c7a80a, 0xdb7d376, 0x80bcba9d, 0xd53db92, 0x80b21baf, + 0xcefdb76, 0x80a7cb49, + 0xc8bd35e, 0x809dc971, 0xc27c389, 0x8094162c, 0xbc3ac35, 0x808ab180, + 0xb5f8d9f, 0x80819b74, + 0xafb6805, 0x8078d40d, 0xa973ba5, 0x80705b50, 0xa3308bd, 0x80683143, + 0x9cecf89, 0x806055eb, + 0x96a9049, 0x8058c94c, 0x9064b3a, 0x80518b6b, 0x8a2009a, 0x804a9c4d, + 0x83db0a7, 0x8043fbf6, + 0x7d95b9e, 0x803daa6a, 0x77501be, 0x8037a7ac, 0x710a345, 0x8031f3c2, + 0x6ac406f, 0x802c8ead, + 0x647d97c, 0x80277872, 0x5e36ea9, 0x8022b114, 0x57f0035, 0x801e3895, + 0x51a8e5c, 0x801a0ef8, + 0x4b6195d, 0x80163440, 0x451a177, 0x8012a86f, 0x3ed26e6, 0x800f6b88, + 0x388a9ea, 0x800c7d8c, + 0x3242abf, 0x8009de7e, 0x2bfa9a4, 0x80078e5e, 0x25b26d7, 0x80058d2f, + 0x1f6a297, 0x8003daf1, + 0x1921d20, 0x800277a6, 0x12d96b1, 0x8001634e, 0xc90f88, 0x80009dea, + 0x6487e3, 0x8000277a, +}; + +static const q31_t WeightsQ31_2048[4096] = { + 0x7fffffff, 0x0, 0x7ffffd88, 0xffe6de05, 0x7ffff621, 0xffcdbc0b, 0x7fffe9cb, + 0xffb49a12, + 0x7fffd886, 0xff9b781d, 0x7fffc251, 0xff82562c, 0x7fffa72c, 0xff69343f, + 0x7fff8719, 0xff501258, + 0x7fff6216, 0xff36f078, 0x7fff3824, 0xff1dcea0, 0x7fff0943, 0xff04acd0, + 0x7ffed572, 0xfeeb8b0a, + 0x7ffe9cb2, 0xfed2694f, 0x7ffe5f03, 0xfeb947a0, 0x7ffe1c65, 0xfea025fd, + 0x7ffdd4d7, 0xfe870467, + 0x7ffd885a, 0xfe6de2e0, 0x7ffd36ee, 0xfe54c169, 0x7ffce093, 0xfe3ba002, + 0x7ffc8549, 0xfe227eac, + 0x7ffc250f, 0xfe095d69, 0x7ffbbfe6, 0xfdf03c3a, 0x7ffb55ce, 0xfdd71b1e, + 0x7ffae6c7, 0xfdbdfa18, + 0x7ffa72d1, 0xfda4d929, 0x7ff9f9ec, 0xfd8bb850, 0x7ff97c18, 0xfd729790, + 0x7ff8f954, 0xfd5976e9, + 0x7ff871a2, 0xfd40565c, 0x7ff7e500, 0xfd2735ea, 0x7ff75370, 0xfd0e1594, + 0x7ff6bcf0, 0xfcf4f55c, + 0x7ff62182, 0xfcdbd541, 0x7ff58125, 0xfcc2b545, 0x7ff4dbd9, 0xfca9956a, + 0x7ff4319d, 0xfc9075af, + 0x7ff38274, 0xfc775616, 0x7ff2ce5b, 0xfc5e36a0, 0x7ff21553, 0xfc45174e, + 0x7ff1575d, 0xfc2bf821, + 0x7ff09478, 0xfc12d91a, 0x7fefcca4, 0xfbf9ba39, 0x7feeffe1, 0xfbe09b80, + 0x7fee2e30, 0xfbc77cf0, + 0x7fed5791, 0xfbae5e89, 0x7fec7c02, 0xfb95404d, 0x7feb9b85, 0xfb7c223d, + 0x7feab61a, 0xfb630459, + 0x7fe9cbc0, 0xfb49e6a3, 0x7fe8dc78, 0xfb30c91b, 0x7fe7e841, 0xfb17abc2, + 0x7fe6ef1c, 0xfafe8e9b, + 0x7fe5f108, 0xfae571a4, 0x7fe4ee06, 0xfacc54e0, 0x7fe3e616, 0xfab3384f, + 0x7fe2d938, 0xfa9a1bf3, + 0x7fe1c76b, 0xfa80ffcb, 0x7fe0b0b1, 0xfa67e3da, 0x7fdf9508, 0xfa4ec821, + 0x7fde7471, 0xfa35ac9f, + 0x7fdd4eec, 0xfa1c9157, 0x7fdc247a, 0xfa037648, 0x7fdaf519, 0xf9ea5b75, + 0x7fd9c0ca, 0xf9d140de, + 0x7fd8878e, 0xf9b82684, 0x7fd74964, 0xf99f0c68, 0x7fd6064c, 0xf985f28a, + 0x7fd4be46, 0xf96cd8ed, + 0x7fd37153, 0xf953bf91, 0x7fd21f72, 0xf93aa676, 0x7fd0c8a3, 0xf9218d9e, + 0x7fcf6ce8, 0xf908750a, + 0x7fce0c3e, 0xf8ef5cbb, 0x7fcca6a7, 0xf8d644b2, 0x7fcb3c23, 0xf8bd2cef, + 0x7fc9ccb2, 0xf8a41574, + 0x7fc85854, 0xf88afe42, 0x7fc6df08, 0xf871e759, 0x7fc560cf, 0xf858d0bb, + 0x7fc3dda9, 0xf83fba68, + 0x7fc25596, 0xf826a462, 0x7fc0c896, 0xf80d8ea9, 0x7fbf36aa, 0xf7f4793e, + 0x7fbd9fd0, 0xf7db6423, + 0x7fbc040a, 0xf7c24f59, 0x7fba6357, 0xf7a93ae0, 0x7fb8bdb8, 0xf79026b9, + 0x7fb7132b, 0xf77712e5, + 0x7fb563b3, 0xf75dff66, 0x7fb3af4e, 0xf744ec3b, 0x7fb1f5fc, 0xf72bd967, + 0x7fb037bf, 0xf712c6ea, + 0x7fae7495, 0xf6f9b4c6, 0x7facac7f, 0xf6e0a2fa, 0x7faadf7c, 0xf6c79188, + 0x7fa90d8e, 0xf6ae8071, + 0x7fa736b4, 0xf6956fb7, 0x7fa55aee, 0xf67c5f59, 0x7fa37a3c, 0xf6634f59, + 0x7fa1949e, 0xf64a3fb8, + 0x7f9faa15, 0xf6313077, 0x7f9dbaa0, 0xf6182196, 0x7f9bc640, 0xf5ff1318, + 0x7f99ccf4, 0xf5e604fc, + 0x7f97cebd, 0xf5ccf743, 0x7f95cb9a, 0xf5b3e9f0, 0x7f93c38c, 0xf59add02, + 0x7f91b694, 0xf581d07b, + 0x7f8fa4b0, 0xf568c45b, 0x7f8d8de1, 0xf54fb8a4, 0x7f8b7227, 0xf536ad56, + 0x7f895182, 0xf51da273, + 0x7f872bf3, 0xf50497fb, 0x7f850179, 0xf4eb8def, 0x7f82d214, 0xf4d28451, + 0x7f809dc5, 0xf4b97b21, + 0x7f7e648c, 0xf4a07261, 0x7f7c2668, 0xf4876a10, 0x7f79e35a, 0xf46e6231, + 0x7f779b62, 0xf4555ac5, + 0x7f754e80, 0xf43c53cb, 0x7f72fcb4, 0xf4234d45, 0x7f70a5fe, 0xf40a4735, + 0x7f6e4a5e, 0xf3f1419a, + 0x7f6be9d4, 0xf3d83c77, 0x7f698461, 0xf3bf37cb, 0x7f671a05, 0xf3a63398, + 0x7f64aabf, 0xf38d2fe0, + 0x7f62368f, 0xf3742ca2, 0x7f5fbd77, 0xf35b29e0, 0x7f5d3f75, 0xf342279b, + 0x7f5abc8a, 0xf32925d3, + 0x7f5834b7, 0xf310248a, 0x7f55a7fa, 0xf2f723c1, 0x7f531655, 0xf2de2379, + 0x7f507fc7, 0xf2c523b2, + 0x7f4de451, 0xf2ac246e, 0x7f4b43f2, 0xf29325ad, 0x7f489eaa, 0xf27a2771, + 0x7f45f47b, 0xf26129ba, + 0x7f434563, 0xf2482c8a, 0x7f409164, 0xf22f2fe1, 0x7f3dd87c, 0xf21633c0, + 0x7f3b1aad, 0xf1fd3829, + 0x7f3857f6, 0xf1e43d1c, 0x7f359057, 0xf1cb429a, 0x7f32c3d1, 0xf1b248a5, + 0x7f2ff263, 0xf1994f3d, + 0x7f2d1c0e, 0xf1805662, 0x7f2a40d2, 0xf1675e17, 0x7f2760af, 0xf14e665c, + 0x7f247ba5, 0xf1356f32, + 0x7f2191b4, 0xf11c789a, 0x7f1ea2dc, 0xf1038295, 0x7f1baf1e, 0xf0ea8d24, + 0x7f18b679, 0xf0d19848, + 0x7f15b8ee, 0xf0b8a401, 0x7f12b67c, 0xf09fb051, 0x7f0faf25, 0xf086bd39, + 0x7f0ca2e7, 0xf06dcaba, + 0x7f0991c4, 0xf054d8d5, 0x7f067bba, 0xf03be78a, 0x7f0360cb, 0xf022f6da, + 0x7f0040f6, 0xf00a06c8, + 0x7efd1c3c, 0xeff11753, 0x7ef9f29d, 0xefd8287c, 0x7ef6c418, 0xefbf3a45, + 0x7ef390ae, 0xefa64cae, + 0x7ef05860, 0xef8d5fb8, 0x7eed1b2c, 0xef747365, 0x7ee9d914, 0xef5b87b5, + 0x7ee69217, 0xef429caa, + 0x7ee34636, 0xef29b243, 0x7edff570, 0xef10c883, 0x7edc9fc6, 0xeef7df6a, + 0x7ed94538, 0xeedef6f9, + 0x7ed5e5c6, 0xeec60f31, 0x7ed28171, 0xeead2813, 0x7ecf1837, 0xee9441a0, + 0x7ecbaa1a, 0xee7b5bd9, + 0x7ec8371a, 0xee6276bf, 0x7ec4bf36, 0xee499253, 0x7ec14270, 0xee30ae96, + 0x7ebdc0c6, 0xee17cb88, + 0x7eba3a39, 0xedfee92b, 0x7eb6aeca, 0xede60780, 0x7eb31e78, 0xedcd2687, + 0x7eaf8943, 0xedb44642, + 0x7eabef2c, 0xed9b66b2, 0x7ea85033, 0xed8287d7, 0x7ea4ac58, 0xed69a9b3, + 0x7ea1039b, 0xed50cc46, + 0x7e9d55fc, 0xed37ef91, 0x7e99a37c, 0xed1f1396, 0x7e95ec1a, 0xed063856, + 0x7e922fd6, 0xeced5dd0, + 0x7e8e6eb2, 0xecd48407, 0x7e8aa8ac, 0xecbbaafb, 0x7e86ddc6, 0xeca2d2ad, + 0x7e830dff, 0xec89fb1e, + 0x7e7f3957, 0xec71244f, 0x7e7b5fce, 0xec584e41, 0x7e778166, 0xec3f78f6, + 0x7e739e1d, 0xec26a46d, + 0x7e6fb5f4, 0xec0dd0a8, 0x7e6bc8eb, 0xebf4fda8, 0x7e67d703, 0xebdc2b6e, + 0x7e63e03b, 0xebc359fb, + 0x7e5fe493, 0xebaa894f, 0x7e5be40c, 0xeb91b96c, 0x7e57dea7, 0xeb78ea52, + 0x7e53d462, 0xeb601c04, + 0x7e4fc53e, 0xeb474e81, 0x7e4bb13c, 0xeb2e81ca, 0x7e47985b, 0xeb15b5e1, + 0x7e437a9c, 0xeafceac6, + 0x7e3f57ff, 0xeae4207a, 0x7e3b3083, 0xeacb56ff, 0x7e37042a, 0xeab28e56, + 0x7e32d2f4, 0xea99c67e, + 0x7e2e9cdf, 0xea80ff7a, 0x7e2a61ed, 0xea683949, 0x7e26221f, 0xea4f73ee, + 0x7e21dd73, 0xea36af69, + 0x7e1d93ea, 0xea1debbb, 0x7e194584, 0xea0528e5, 0x7e14f242, 0xe9ec66e8, + 0x7e109a24, 0xe9d3a5c5, + 0x7e0c3d29, 0xe9bae57d, 0x7e07db52, 0xe9a22610, 0x7e0374a0, 0xe9896781, + 0x7dff0911, 0xe970a9ce, + 0x7dfa98a8, 0xe957ecfb, 0x7df62362, 0xe93f3107, 0x7df1a942, 0xe92675f4, + 0x7ded2a47, 0xe90dbbc2, + 0x7de8a670, 0xe8f50273, 0x7de41dc0, 0xe8dc4a07, 0x7ddf9034, 0xe8c39280, + 0x7ddafdce, 0xe8aadbde, + 0x7dd6668f, 0xe8922622, 0x7dd1ca75, 0xe879714d, 0x7dcd2981, 0xe860bd61, + 0x7dc883b4, 0xe8480a5d, + 0x7dc3d90d, 0xe82f5844, 0x7dbf298d, 0xe816a716, 0x7dba7534, 0xe7fdf6d4, + 0x7db5bc02, 0xe7e5477f, + 0x7db0fdf8, 0xe7cc9917, 0x7dac3b15, 0xe7b3eb9f, 0x7da77359, 0xe79b3f16, + 0x7da2a6c6, 0xe782937e, + 0x7d9dd55a, 0xe769e8d8, 0x7d98ff17, 0xe7513f25, 0x7d9423fc, 0xe7389665, + 0x7d8f4409, 0xe71fee99, + 0x7d8a5f40, 0xe70747c4, 0x7d85759f, 0xe6eea1e4, 0x7d808728, 0xe6d5fcfc, + 0x7d7b93da, 0xe6bd590d, + 0x7d769bb5, 0xe6a4b616, 0x7d719eba, 0xe68c141a, 0x7d6c9ce9, 0xe6737319, + 0x7d679642, 0xe65ad315, + 0x7d628ac6, 0xe642340d, 0x7d5d7a74, 0xe6299604, 0x7d58654d, 0xe610f8f9, + 0x7d534b50, 0xe5f85cef, + 0x7d4e2c7f, 0xe5dfc1e5, 0x7d4908d9, 0xe5c727dd, 0x7d43e05e, 0xe5ae8ed8, + 0x7d3eb30f, 0xe595f6d7, + 0x7d3980ec, 0xe57d5fda, 0x7d3449f5, 0xe564c9e3, 0x7d2f0e2b, 0xe54c34f3, + 0x7d29cd8c, 0xe533a10a, + 0x7d24881b, 0xe51b0e2a, 0x7d1f3dd6, 0xe5027c53, 0x7d19eebf, 0xe4e9eb87, + 0x7d149ad5, 0xe4d15bc6, + 0x7d0f4218, 0xe4b8cd11, 0x7d09e489, 0xe4a03f69, 0x7d048228, 0xe487b2d0, + 0x7cff1af5, 0xe46f2745, + 0x7cf9aef0, 0xe4569ccb, 0x7cf43e1a, 0xe43e1362, 0x7ceec873, 0xe4258b0a, + 0x7ce94dfb, 0xe40d03c6, + 0x7ce3ceb2, 0xe3f47d96, 0x7cde4a98, 0xe3dbf87a, 0x7cd8c1ae, 0xe3c37474, + 0x7cd333f3, 0xe3aaf184, + 0x7ccda169, 0xe3926fad, 0x7cc80a0f, 0xe379eeed, 0x7cc26de5, 0xe3616f48, + 0x7cbcccec, 0xe348f0bd, + 0x7cb72724, 0xe330734d, 0x7cb17c8d, 0xe317f6fa, 0x7cabcd28, 0xe2ff7bc3, + 0x7ca618f3, 0xe2e701ac, + 0x7ca05ff1, 0xe2ce88b3, 0x7c9aa221, 0xe2b610da, 0x7c94df83, 0xe29d9a23, + 0x7c8f1817, 0xe285248d, + 0x7c894bde, 0xe26cb01b, 0x7c837ad8, 0xe2543ccc, 0x7c7da505, 0xe23bcaa2, + 0x7c77ca65, 0xe223599e, + 0x7c71eaf9, 0xe20ae9c1, 0x7c6c06c0, 0xe1f27b0b, 0x7c661dbc, 0xe1da0d7e, + 0x7c602fec, 0xe1c1a11b, + 0x7c5a3d50, 0xe1a935e2, 0x7c5445e9, 0xe190cbd4, 0x7c4e49b7, 0xe17862f3, + 0x7c4848ba, 0xe15ffb3f, + 0x7c4242f2, 0xe14794ba, 0x7c3c3860, 0xe12f2f63, 0x7c362904, 0xe116cb3d, + 0x7c3014de, 0xe0fe6848, + 0x7c29fbee, 0xe0e60685, 0x7c23de35, 0xe0cda5f5, 0x7c1dbbb3, 0xe0b54698, + 0x7c179467, 0xe09ce871, + 0x7c116853, 0xe0848b7f, 0x7c0b3777, 0xe06c2fc4, 0x7c0501d2, 0xe053d541, + 0x7bfec765, 0xe03b7bf6, + 0x7bf88830, 0xe02323e5, 0x7bf24434, 0xe00acd0e, 0x7bebfb70, 0xdff27773, + 0x7be5ade6, 0xdfda2314, + 0x7bdf5b94, 0xdfc1cff3, 0x7bd9047c, 0xdfa97e0f, 0x7bd2a89e, 0xdf912d6b, + 0x7bcc47fa, 0xdf78de07, + 0x7bc5e290, 0xdf608fe4, 0x7bbf7860, 0xdf484302, 0x7bb9096b, 0xdf2ff764, + 0x7bb295b0, 0xdf17ad0a, + 0x7bac1d31, 0xdeff63f4, 0x7ba59fee, 0xdee71c24, 0x7b9f1de6, 0xdeced59b, + 0x7b989719, 0xdeb69059, + 0x7b920b89, 0xde9e4c60, 0x7b8b7b36, 0xde8609b1, 0x7b84e61f, 0xde6dc84b, + 0x7b7e4c45, 0xde558831, + 0x7b77ada8, 0xde3d4964, 0x7b710a49, 0xde250be3, 0x7b6a6227, 0xde0ccfb1, + 0x7b63b543, 0xddf494ce, + 0x7b5d039e, 0xdddc5b3b, 0x7b564d36, 0xddc422f8, 0x7b4f920e, 0xddabec08, + 0x7b48d225, 0xdd93b66a, + 0x7b420d7a, 0xdd7b8220, 0x7b3b4410, 0xdd634f2b, 0x7b3475e5, 0xdd4b1d8c, + 0x7b2da2fa, 0xdd32ed43, + 0x7b26cb4f, 0xdd1abe51, 0x7b1feee5, 0xdd0290b8, 0x7b190dbc, 0xdcea6478, + 0x7b1227d3, 0xdcd23993, + 0x7b0b3d2c, 0xdcba1008, 0x7b044dc7, 0xdca1e7da, 0x7afd59a4, 0xdc89c109, + 0x7af660c2, 0xdc719b96, + 0x7aef6323, 0xdc597781, 0x7ae860c7, 0xdc4154cd, 0x7ae159ae, 0xdc293379, + 0x7ada4dd8, 0xdc111388, + 0x7ad33d45, 0xdbf8f4f8, 0x7acc27f7, 0xdbe0d7cd, 0x7ac50dec, 0xdbc8bc06, + 0x7abdef25, 0xdbb0a1a4, + 0x7ab6cba4, 0xdb9888a8, 0x7aafa367, 0xdb807114, 0x7aa8766f, 0xdb685ae9, + 0x7aa144bc, 0xdb504626, + 0x7a9a0e50, 0xdb3832cd, 0x7a92d329, 0xdb2020e0, 0x7a8b9348, 0xdb08105e, + 0x7a844eae, 0xdaf00149, + 0x7a7d055b, 0xdad7f3a2, 0x7a75b74f, 0xdabfe76a, 0x7a6e648a, 0xdaa7dca1, + 0x7a670d0d, 0xda8fd349, + 0x7a5fb0d8, 0xda77cb63, 0x7a584feb, 0xda5fc4ef, 0x7a50ea47, 0xda47bfee, + 0x7a497feb, 0xda2fbc61, + 0x7a4210d8, 0xda17ba4a, 0x7a3a9d0f, 0xd9ffb9a9, 0x7a332490, 0xd9e7ba7f, + 0x7a2ba75a, 0xd9cfbccd, + 0x7a24256f, 0xd9b7c094, 0x7a1c9ece, 0xd99fc5d4, 0x7a151378, 0xd987cc90, + 0x7a0d836d, 0xd96fd4c7, + 0x7a05eead, 0xd957de7a, 0x79fe5539, 0xd93fe9ab, 0x79f6b711, 0xd927f65b, + 0x79ef1436, 0xd910048a, + 0x79e76ca7, 0xd8f81439, 0x79dfc064, 0xd8e0256a, 0x79d80f6f, 0xd8c8381d, + 0x79d059c8, 0xd8b04c52, + 0x79c89f6e, 0xd898620c, 0x79c0e062, 0xd880794b, 0x79b91ca4, 0xd868920f, + 0x79b15435, 0xd850ac5a, + 0x79a98715, 0xd838c82d, 0x79a1b545, 0xd820e589, 0x7999dec4, 0xd809046e, + 0x79920392, 0xd7f124dd, + 0x798a23b1, 0xd7d946d8, 0x79823f20, 0xd7c16a5f, 0x797a55e0, 0xd7a98f73, + 0x797267f2, 0xd791b616, + 0x796a7554, 0xd779de47, 0x79627e08, 0xd7620808, 0x795a820e, 0xd74a335b, + 0x79528167, 0xd732603f, + 0x794a7c12, 0xd71a8eb5, 0x79427210, 0xd702bec0, 0x793a6361, 0xd6eaf05f, + 0x79325006, 0xd6d32393, + 0x792a37fe, 0xd6bb585e, 0x79221b4b, 0xd6a38ec0, 0x7919f9ec, 0xd68bc6ba, + 0x7911d3e2, 0xd674004e, + 0x7909a92d, 0xd65c3b7b, 0x790179cd, 0xd6447844, 0x78f945c3, 0xd62cb6a8, + 0x78f10d0f, 0xd614f6a9, + 0x78e8cfb2, 0xd5fd3848, 0x78e08dab, 0xd5e57b85, 0x78d846fb, 0xd5cdc062, + 0x78cffba3, 0xd5b606e0, + 0x78c7aba2, 0xd59e4eff, 0x78bf56f9, 0xd58698c0, 0x78b6fda8, 0xd56ee424, + 0x78ae9fb0, 0xd557312d, + 0x78a63d11, 0xd53f7fda, 0x789dd5cb, 0xd527d02e, 0x789569df, 0xd5102228, + 0x788cf94c, 0xd4f875ca, + 0x78848414, 0xd4e0cb15, 0x787c0a36, 0xd4c92209, 0x78738bb3, 0xd4b17aa8, + 0x786b088c, 0xd499d4f2, + 0x786280bf, 0xd48230e9, 0x7859f44f, 0xd46a8e8d, 0x7851633b, 0xd452eddf, + 0x7848cd83, 0xd43b4ee0, + 0x78403329, 0xd423b191, 0x7837942b, 0xd40c15f3, 0x782ef08b, 0xd3f47c06, + 0x78264849, 0xd3dce3cd, + 0x781d9b65, 0xd3c54d47, 0x7814e9df, 0xd3adb876, 0x780c33b8, 0xd396255a, + 0x780378f1, 0xd37e93f4, + 0x77fab989, 0xd3670446, 0x77f1f581, 0xd34f764f, 0x77e92cd9, 0xd337ea12, + 0x77e05f91, 0xd3205f8f, + 0x77d78daa, 0xd308d6c7, 0x77ceb725, 0xd2f14fba, 0x77c5dc01, 0xd2d9ca6a, + 0x77bcfc3f, 0xd2c246d8, + 0x77b417df, 0xd2aac504, 0x77ab2ee2, 0xd29344f0, 0x77a24148, 0xd27bc69c, + 0x77994f11, 0xd2644a0a, + 0x7790583e, 0xd24ccf39, 0x77875cce, 0xd235562b, 0x777e5cc3, 0xd21ddee2, + 0x7775581d, 0xd206695d, + 0x776c4edb, 0xd1eef59e, 0x776340ff, 0xd1d783a6, 0x775a2e89, 0xd1c01375, + 0x77511778, 0xd1a8a50d, + 0x7747fbce, 0xd191386e, 0x773edb8b, 0xd179cd99, 0x7735b6af, 0xd1626490, + 0x772c8d3a, 0xd14afd52, + 0x77235f2d, 0xd13397e2, 0x771a2c88, 0xd11c343f, 0x7710f54c, 0xd104d26b, + 0x7707b979, 0xd0ed7267, + 0x76fe790e, 0xd0d61434, 0x76f5340e, 0xd0beb7d2, 0x76ebea77, 0xd0a75d42, + 0x76e29c4b, 0xd0900486, + 0x76d94989, 0xd078ad9e, 0x76cff232, 0xd061588b, 0x76c69647, 0xd04a054e, + 0x76bd35c7, 0xd032b3e7, + 0x76b3d0b4, 0xd01b6459, 0x76aa670d, 0xd00416a3, 0x76a0f8d2, 0xcfeccac7, + 0x76978605, 0xcfd580c6, + 0x768e0ea6, 0xcfbe389f, 0x768492b4, 0xcfa6f255, 0x767b1231, 0xcf8fade9, + 0x76718d1c, 0xcf786b5a, + 0x76680376, 0xcf612aaa, 0x765e7540, 0xcf49ebda, 0x7654e279, 0xcf32aeeb, + 0x764b4b23, 0xcf1b73de, + 0x7641af3d, 0xcf043ab3, 0x76380ec8, 0xceed036b, 0x762e69c4, 0xced5ce08, + 0x7624c031, 0xcebe9a8a, + 0x761b1211, 0xcea768f2, 0x76115f63, 0xce903942, 0x7607a828, 0xce790b79, + 0x75fdec60, 0xce61df99, + 0x75f42c0b, 0xce4ab5a2, 0x75ea672a, 0xce338d97, 0x75e09dbd, 0xce1c6777, + 0x75d6cfc5, 0xce054343, + 0x75ccfd42, 0xcdee20fc, 0x75c32634, 0xcdd700a4, 0x75b94a9c, 0xcdbfe23a, + 0x75af6a7b, 0xcda8c5c1, + 0x75a585cf, 0xcd91ab39, 0x759b9c9b, 0xcd7a92a2, 0x7591aedd, 0xcd637bfe, + 0x7587bc98, 0xcd4c674d, + 0x757dc5ca, 0xcd355491, 0x7573ca75, 0xcd1e43ca, 0x7569ca99, 0xcd0734f9, + 0x755fc635, 0xccf0281f, + 0x7555bd4c, 0xccd91d3d, 0x754bafdc, 0xccc21455, 0x75419de7, 0xccab0d65, + 0x7537876c, 0xcc940871, + 0x752d6c6c, 0xcc7d0578, 0x75234ce8, 0xcc66047b, 0x751928e0, 0xcc4f057c, + 0x750f0054, 0xcc38087b, + 0x7504d345, 0xcc210d79, 0x74faa1b3, 0xcc0a1477, 0x74f06b9e, 0xcbf31d75, + 0x74e63108, 0xcbdc2876, + 0x74dbf1ef, 0xcbc53579, 0x74d1ae55, 0xcbae447f, 0x74c7663a, 0xcb97558a, + 0x74bd199f, 0xcb80689a, + 0x74b2c884, 0xcb697db0, 0x74a872e8, 0xcb5294ce, 0x749e18cd, 0xcb3badf3, + 0x7493ba34, 0xcb24c921, + 0x7489571c, 0xcb0de658, 0x747eef85, 0xcaf7059a, 0x74748371, 0xcae026e8, + 0x746a12df, 0xcac94a42, + 0x745f9dd1, 0xcab26fa9, 0x74552446, 0xca9b971e, 0x744aa63f, 0xca84c0a3, + 0x744023bc, 0xca6dec37, + 0x74359cbd, 0xca5719db, 0x742b1144, 0xca404992, 0x74208150, 0xca297b5a, + 0x7415ece2, 0xca12af37, + 0x740b53fb, 0xc9fbe527, 0x7400b69a, 0xc9e51d2d, 0x73f614c0, 0xc9ce5748, + 0x73eb6e6e, 0xc9b7937a, + 0x73e0c3a3, 0xc9a0d1c5, 0x73d61461, 0xc98a1227, 0x73cb60a8, 0xc97354a4, + 0x73c0a878, 0xc95c993a, + 0x73b5ebd1, 0xc945dfec, 0x73ab2ab4, 0xc92f28ba, 0x73a06522, 0xc91873a5, + 0x73959b1b, 0xc901c0ae, + 0x738acc9e, 0xc8eb0fd6, 0x737ff9ae, 0xc8d4611d, 0x73752249, 0xc8bdb485, + 0x736a4671, 0xc8a70a0e, + 0x735f6626, 0xc89061ba, 0x73548168, 0xc879bb89, 0x73499838, 0xc863177b, + 0x733eaa96, 0xc84c7593, + 0x7333b883, 0xc835d5d0, 0x7328c1ff, 0xc81f3834, 0x731dc70a, 0xc8089cbf, + 0x7312c7a5, 0xc7f20373, + 0x7307c3d0, 0xc7db6c50, 0x72fcbb8c, 0xc7c4d757, 0x72f1aed9, 0xc7ae4489, + 0x72e69db7, 0xc797b3e7, + 0x72db8828, 0xc7812572, 0x72d06e2b, 0xc76a992a, 0x72c54fc1, 0xc7540f11, + 0x72ba2cea, 0xc73d8727, + 0x72af05a7, 0xc727016d, 0x72a3d9f7, 0xc7107de4, 0x7298a9dd, 0xc6f9fc8d, + 0x728d7557, 0xc6e37d69, + 0x72823c67, 0xc6cd0079, 0x7276ff0d, 0xc6b685bd, 0x726bbd48, 0xc6a00d37, + 0x7260771b, 0xc68996e7, + 0x72552c85, 0xc67322ce, 0x7249dd86, 0xc65cb0ed, 0x723e8a20, 0xc6464144, + 0x72333251, 0xc62fd3d6, + 0x7227d61c, 0xc61968a2, 0x721c7580, 0xc602ffaa, 0x7211107e, 0xc5ec98ee, + 0x7205a716, 0xc5d6346f, + 0x71fa3949, 0xc5bfd22e, 0x71eec716, 0xc5a9722c, 0x71e35080, 0xc593146a, + 0x71d7d585, 0xc57cb8e9, + 0x71cc5626, 0xc5665fa9, 0x71c0d265, 0xc55008ab, 0x71b54a41, 0xc539b3f1, + 0x71a9bdba, 0xc523617a, + 0x719e2cd2, 0xc50d1149, 0x71929789, 0xc4f6c35d, 0x7186fdde, 0xc4e077b8, + 0x717b5fd3, 0xc4ca2e5b, + 0x716fbd68, 0xc4b3e746, 0x7164169d, 0xc49da27a, 0x71586b74, 0xc4875ff9, + 0x714cbbeb, 0xc4711fc2, + 0x71410805, 0xc45ae1d7, 0x71354fc0, 0xc444a639, 0x7129931f, 0xc42e6ce8, + 0x711dd220, 0xc41835e6, + 0x71120cc5, 0xc4020133, 0x7106430e, 0xc3ebced0, 0x70fa74fc, 0xc3d59ebe, + 0x70eea28e, 0xc3bf70fd, + 0x70e2cbc6, 0xc3a94590, 0x70d6f0a4, 0xc3931c76, 0x70cb1128, 0xc37cf5b0, + 0x70bf2d53, 0xc366d140, + 0x70b34525, 0xc350af26, 0x70a7589f, 0xc33a8f62, 0x709b67c0, 0xc32471f7, + 0x708f728b, 0xc30e56e4, + 0x708378ff, 0xc2f83e2a, 0x70777b1c, 0xc2e227cb, 0x706b78e3, 0xc2cc13c7, + 0x705f7255, 0xc2b6021f, + 0x70536771, 0xc29ff2d4, 0x70475839, 0xc289e5e7, 0x703b44ad, 0xc273db58, + 0x702f2ccd, 0xc25dd329, + 0x7023109a, 0xc247cd5a, 0x7016f014, 0xc231c9ec, 0x700acb3c, 0xc21bc8e1, + 0x6ffea212, 0xc205ca38, + 0x6ff27497, 0xc1efcdf3, 0x6fe642ca, 0xc1d9d412, 0x6fda0cae, 0xc1c3dc97, + 0x6fcdd241, 0xc1ade781, + 0x6fc19385, 0xc197f4d4, 0x6fb5507a, 0xc182048d, 0x6fa90921, 0xc16c16b0, + 0x6f9cbd79, 0xc1562b3d, + 0x6f906d84, 0xc1404233, 0x6f841942, 0xc12a5b95, 0x6f77c0b3, 0xc1147764, + 0x6f6b63d8, 0xc0fe959f, + 0x6f5f02b2, 0xc0e8b648, 0x6f529d40, 0xc0d2d960, 0x6f463383, 0xc0bcfee7, + 0x6f39c57d, 0xc0a726df, + 0x6f2d532c, 0xc0915148, 0x6f20dc92, 0xc07b7e23, 0x6f1461b0, 0xc065ad70, + 0x6f07e285, 0xc04fdf32, + 0x6efb5f12, 0xc03a1368, 0x6eeed758, 0xc0244a14, 0x6ee24b57, 0xc00e8336, + 0x6ed5bb10, 0xbff8bece, + 0x6ec92683, 0xbfe2fcdf, 0x6ebc8db0, 0xbfcd3d69, 0x6eaff099, 0xbfb7806c, + 0x6ea34f3d, 0xbfa1c5ea, + 0x6e96a99d, 0xbf8c0de3, 0x6e89ffb9, 0xbf765858, 0x6e7d5193, 0xbf60a54a, + 0x6e709f2a, 0xbf4af4ba, + 0x6e63e87f, 0xbf3546a8, 0x6e572d93, 0xbf1f9b16, 0x6e4a6e66, 0xbf09f205, + 0x6e3daaf8, 0xbef44b74, + 0x6e30e34a, 0xbedea765, 0x6e24175c, 0xbec905d9, 0x6e174730, 0xbeb366d1, + 0x6e0a72c5, 0xbe9dca4e, + 0x6dfd9a1c, 0xbe88304f, 0x6df0bd35, 0xbe7298d7, 0x6de3dc11, 0xbe5d03e6, + 0x6dd6f6b1, 0xbe47717c, + 0x6dca0d14, 0xbe31e19b, 0x6dbd1f3c, 0xbe1c5444, 0x6db02d29, 0xbe06c977, + 0x6da336dc, 0xbdf14135, + 0x6d963c54, 0xbddbbb7f, 0x6d893d93, 0xbdc63856, 0x6d7c3a98, 0xbdb0b7bb, + 0x6d6f3365, 0xbd9b39ad, + 0x6d6227fa, 0xbd85be30, 0x6d551858, 0xbd704542, 0x6d48047e, 0xbd5acee5, + 0x6d3aec6e, 0xbd455b1a, + 0x6d2dd027, 0xbd2fe9e2, 0x6d20afac, 0xbd1a7b3d, 0x6d138afb, 0xbd050f2c, + 0x6d066215, 0xbcefa5b0, + 0x6cf934fc, 0xbcda3ecb, 0x6cec03af, 0xbcc4da7b, 0x6cdece2f, 0xbcaf78c4, + 0x6cd1947c, 0xbc9a19a5, + 0x6cc45698, 0xbc84bd1f, 0x6cb71482, 0xbc6f6333, 0x6ca9ce3b, 0xbc5a0be2, + 0x6c9c83c3, 0xbc44b72c, + 0x6c8f351c, 0xbc2f6513, 0x6c81e245, 0xbc1a1598, 0x6c748b3f, 0xbc04c8ba, + 0x6c67300b, 0xbbef7e7c, + 0x6c59d0a9, 0xbbda36dd, 0x6c4c6d1a, 0xbbc4f1df, 0x6c3f055d, 0xbbafaf82, + 0x6c319975, 0xbb9a6fc7, + 0x6c242960, 0xbb8532b0, 0x6c16b521, 0xbb6ff83c, 0x6c093cb6, 0xbb5ac06d, + 0x6bfbc021, 0xbb458b43, + 0x6bee3f62, 0xbb3058c0, 0x6be0ba7b, 0xbb1b28e4, 0x6bd3316a, 0xbb05fbb0, + 0x6bc5a431, 0xbaf0d125, + 0x6bb812d1, 0xbadba943, 0x6baa7d49, 0xbac6840c, 0x6b9ce39b, 0xbab16180, + 0x6b8f45c7, 0xba9c41a0, + 0x6b81a3cd, 0xba87246d, 0x6b73fdae, 0xba7209e7, 0x6b66536b, 0xba5cf210, + 0x6b58a503, 0xba47dce8, + 0x6b4af279, 0xba32ca71, 0x6b3d3bcb, 0xba1dbaaa, 0x6b2f80fb, 0xba08ad95, + 0x6b21c208, 0xb9f3a332, + 0x6b13fef5, 0xb9de9b83, 0x6b0637c1, 0xb9c99688, 0x6af86c6c, 0xb9b49442, + 0x6aea9cf8, 0xb99f94b2, + 0x6adcc964, 0xb98a97d8, 0x6acef1b2, 0xb9759db6, 0x6ac115e2, 0xb960a64c, + 0x6ab335f4, 0xb94bb19b, + 0x6aa551e9, 0xb936bfa4, 0x6a9769c1, 0xb921d067, 0x6a897d7d, 0xb90ce3e6, + 0x6a7b8d1e, 0xb8f7fa21, + 0x6a6d98a4, 0xb8e31319, 0x6a5fa010, 0xb8ce2ecf, 0x6a51a361, 0xb8b94d44, + 0x6a43a29a, 0xb8a46e78, + 0x6a359db9, 0xb88f926d, 0x6a2794c1, 0xb87ab922, 0x6a1987b0, 0xb865e299, + 0x6a0b7689, 0xb8510ed4, + 0x69fd614a, 0xb83c3dd1, 0x69ef47f6, 0xb8276f93, 0x69e12a8c, 0xb812a41a, + 0x69d3090e, 0xb7fddb67, + 0x69c4e37a, 0xb7e9157a, 0x69b6b9d3, 0xb7d45255, 0x69a88c19, 0xb7bf91f8, + 0x699a5a4c, 0xb7aad465, + 0x698c246c, 0xb796199b, 0x697dea7b, 0xb781619c, 0x696fac78, 0xb76cac69, + 0x69616a65, 0xb757fa01, + 0x69532442, 0xb7434a67, 0x6944da10, 0xb72e9d9b, 0x69368bce, 0xb719f39e, + 0x6928397e, 0xb7054c6f, + 0x6919e320, 0xb6f0a812, 0x690b88b5, 0xb6dc0685, 0x68fd2a3d, 0xb6c767ca, + 0x68eec7b9, 0xb6b2cbe2, + 0x68e06129, 0xb69e32cd, 0x68d1f68f, 0xb6899c8d, 0x68c387e9, 0xb6750921, + 0x68b5153a, 0xb660788c, + 0x68a69e81, 0xb64beacd, 0x689823bf, 0xb6375fe5, 0x6889a4f6, 0xb622d7d6, + 0x687b2224, 0xb60e529f, + 0x686c9b4b, 0xb5f9d043, 0x685e106c, 0xb5e550c1, 0x684f8186, 0xb5d0d41a, + 0x6840ee9b, 0xb5bc5a50, + 0x683257ab, 0xb5a7e362, 0x6823bcb7, 0xb5936f53, 0x68151dbe, 0xb57efe22, + 0x68067ac3, 0xb56a8fd0, + 0x67f7d3c5, 0xb556245e, 0x67e928c5, 0xb541bbcd, 0x67da79c3, 0xb52d561e, + 0x67cbc6c0, 0xb518f351, + 0x67bd0fbd, 0xb5049368, 0x67ae54ba, 0xb4f03663, 0x679f95b7, 0xb4dbdc42, + 0x6790d2b6, 0xb4c78507, + 0x67820bb7, 0xb4b330b3, 0x677340ba, 0xb49edf45, 0x676471c0, 0xb48a90c0, + 0x67559eca, 0xb4764523, + 0x6746c7d8, 0xb461fc70, 0x6737ecea, 0xb44db6a8, 0x67290e02, 0xb43973ca, + 0x671a2b20, 0xb42533d8, + 0x670b4444, 0xb410f6d3, 0x66fc596f, 0xb3fcbcbb, 0x66ed6aa1, 0xb3e88592, + 0x66de77dc, 0xb3d45157, + 0x66cf8120, 0xb3c0200c, 0x66c0866d, 0xb3abf1b2, 0x66b187c3, 0xb397c649, + 0x66a28524, 0xb3839dd3, + 0x66937e91, 0xb36f784f, 0x66847408, 0xb35b55bf, 0x6675658c, 0xb3473623, + 0x6666531d, 0xb333197c, + 0x66573cbb, 0xb31effcc, 0x66482267, 0xb30ae912, 0x66390422, 0xb2f6d550, + 0x6629e1ec, 0xb2e2c486, + 0x661abbc5, 0xb2ceb6b5, 0x660b91af, 0xb2baabde, 0x65fc63a9, 0xb2a6a402, + 0x65ed31b5, 0xb2929f21, + 0x65ddfbd3, 0xb27e9d3c, 0x65cec204, 0xb26a9e54, 0x65bf8447, 0xb256a26a, + 0x65b0429f, 0xb242a97e, + 0x65a0fd0b, 0xb22eb392, 0x6591b38c, 0xb21ac0a6, 0x65826622, 0xb206d0ba, + 0x657314cf, 0xb1f2e3d0, + 0x6563bf92, 0xb1def9e9, 0x6554666d, 0xb1cb1304, 0x6545095f, 0xb1b72f23, + 0x6535a86b, 0xb1a34e47, + 0x6526438f, 0xb18f7071, 0x6516dacd, 0xb17b95a0, 0x65076e25, 0xb167bdd7, + 0x64f7fd98, 0xb153e915, + 0x64e88926, 0xb140175b, 0x64d910d1, 0xb12c48ab, 0x64c99498, 0xb1187d05, + 0x64ba147d, 0xb104b46a, + 0x64aa907f, 0xb0f0eeda, 0x649b08a0, 0xb0dd2c56, 0x648b7ce0, 0xb0c96ce0, + 0x647bed3f, 0xb0b5b077, + 0x646c59bf, 0xb0a1f71d, 0x645cc260, 0xb08e40d2, 0x644d2722, 0xb07a8d97, + 0x643d8806, 0xb066dd6d, + 0x642de50d, 0xb0533055, 0x641e3e38, 0xb03f864f, 0x640e9386, 0xb02bdf5c, + 0x63fee4f8, 0xb0183b7d, + 0x63ef3290, 0xb0049ab3, 0x63df7c4d, 0xaff0fcfe, 0x63cfc231, 0xafdd625f, + 0x63c0043b, 0xafc9cad7, + 0x63b0426d, 0xafb63667, 0x63a07cc7, 0xafa2a50f, 0x6390b34a, 0xaf8f16d1, + 0x6380e5f6, 0xaf7b8bac, + 0x637114cc, 0xaf6803a2, 0x63613fcd, 0xaf547eb3, 0x635166f9, 0xaf40fce1, + 0x63418a50, 0xaf2d7e2b, + 0x6331a9d4, 0xaf1a0293, 0x6321c585, 0xaf068a1a, 0x6311dd64, 0xaef314c0, + 0x6301f171, 0xaedfa285, + 0x62f201ac, 0xaecc336c, 0x62e20e17, 0xaeb8c774, 0x62d216b3, 0xaea55e9e, + 0x62c21b7e, 0xae91f8eb, + 0x62b21c7b, 0xae7e965b, 0x62a219aa, 0xae6b36f0, 0x6292130c, 0xae57daab, + 0x628208a1, 0xae44818b, + 0x6271fa69, 0xae312b92, 0x6261e866, 0xae1dd8c0, 0x6251d298, 0xae0a8916, + 0x6241b8ff, 0xadf73c96, + 0x62319b9d, 0xade3f33e, 0x62217a72, 0xadd0ad12, 0x6211557e, 0xadbd6a10, + 0x62012cc2, 0xadaa2a3b, + 0x61f1003f, 0xad96ed92, 0x61e0cff5, 0xad83b416, 0x61d09be5, 0xad707dc8, + 0x61c06410, 0xad5d4aaa, + 0x61b02876, 0xad4a1aba, 0x619fe918, 0xad36edfc, 0x618fa5f7, 0xad23c46e, + 0x617f5f12, 0xad109e12, + 0x616f146c, 0xacfd7ae8, 0x615ec603, 0xacea5af2, 0x614e73da, 0xacd73e30, + 0x613e1df0, 0xacc424a3, + 0x612dc447, 0xacb10e4b, 0x611d66de, 0xac9dfb29, 0x610d05b7, 0xac8aeb3e, + 0x60fca0d2, 0xac77de8b, + 0x60ec3830, 0xac64d510, 0x60dbcbd1, 0xac51cecf, 0x60cb5bb7, 0xac3ecbc7, + 0x60bae7e1, 0xac2bcbfa, + 0x60aa7050, 0xac18cf69, 0x6099f505, 0xac05d613, 0x60897601, 0xabf2dffb, + 0x6078f344, 0xabdfed1f, + 0x60686ccf, 0xabccfd83, 0x6057e2a2, 0xabba1125, 0x604754bf, 0xaba72807, + 0x6036c325, 0xab944229, + 0x60262dd6, 0xab815f8d, 0x601594d1, 0xab6e8032, 0x6004f819, 0xab5ba41a, + 0x5ff457ad, 0xab48cb46, + 0x5fe3b38d, 0xab35f5b5, 0x5fd30bbc, 0xab23236a, 0x5fc26038, 0xab105464, + 0x5fb1b104, 0xaafd88a4, + 0x5fa0fe1f, 0xaaeac02c, 0x5f90478a, 0xaad7fafb, 0x5f7f8d46, 0xaac53912, + 0x5f6ecf53, 0xaab27a73, + 0x5f5e0db3, 0xaa9fbf1e, 0x5f4d4865, 0xaa8d0713, 0x5f3c7f6b, 0xaa7a5253, + 0x5f2bb2c5, 0xaa67a0e0, + 0x5f1ae274, 0xaa54f2ba, 0x5f0a0e77, 0xaa4247e1, 0x5ef936d1, 0xaa2fa056, + 0x5ee85b82, 0xaa1cfc1a, + 0x5ed77c8a, 0xaa0a5b2e, 0x5ec699e9, 0xa9f7bd92, 0x5eb5b3a2, 0xa9e52347, + 0x5ea4c9b3, 0xa9d28c4e, + 0x5e93dc1f, 0xa9bff8a8, 0x5e82eae5, 0xa9ad6855, 0x5e71f606, 0xa99adb56, + 0x5e60fd84, 0xa98851ac, + 0x5e50015d, 0xa975cb57, 0x5e3f0194, 0xa9634858, 0x5e2dfe29, 0xa950c8b0, + 0x5e1cf71c, 0xa93e4c5f, + 0x5e0bec6e, 0xa92bd367, 0x5dfade20, 0xa9195dc7, 0x5de9cc33, 0xa906eb82, + 0x5dd8b6a7, 0xa8f47c97, + 0x5dc79d7c, 0xa8e21106, 0x5db680b4, 0xa8cfa8d2, 0x5da5604f, 0xa8bd43fa, + 0x5d943c4e, 0xa8aae280, + 0x5d8314b1, 0xa8988463, 0x5d71e979, 0xa88629a5, 0x5d60baa7, 0xa873d246, + 0x5d4f883b, 0xa8617e48, + 0x5d3e5237, 0xa84f2daa, 0x5d2d189a, 0xa83ce06e, 0x5d1bdb65, 0xa82a9693, + 0x5d0a9a9a, 0xa818501c, + 0x5cf95638, 0xa8060d08, 0x5ce80e41, 0xa7f3cd59, 0x5cd6c2b5, 0xa7e1910f, + 0x5cc57394, 0xa7cf582a, + 0x5cb420e0, 0xa7bd22ac, 0x5ca2ca99, 0xa7aaf094, 0x5c9170bf, 0xa798c1e5, + 0x5c801354, 0xa786969e, + 0x5c6eb258, 0xa7746ec0, 0x5c5d4dcc, 0xa7624a4d, 0x5c4be5b0, 0xa7502943, + 0x5c3a7a05, 0xa73e0ba5, + 0x5c290acc, 0xa72bf174, 0x5c179806, 0xa719daae, 0x5c0621b2, 0xa707c757, + 0x5bf4a7d2, 0xa6f5b76d, + 0x5be32a67, 0xa6e3aaf2, 0x5bd1a971, 0xa6d1a1e7, 0x5bc024f0, 0xa6bf9c4b, + 0x5bae9ce7, 0xa6ad9a21, + 0x5b9d1154, 0xa69b9b68, 0x5b8b8239, 0xa689a022, 0x5b79ef96, 0xa677a84e, + 0x5b68596d, 0xa665b3ee, + 0x5b56bfbd, 0xa653c303, 0x5b452288, 0xa641d58c, 0x5b3381ce, 0xa62feb8b, + 0x5b21dd90, 0xa61e0501, + 0x5b1035cf, 0xa60c21ee, 0x5afe8a8b, 0xa5fa4252, 0x5aecdbc5, 0xa5e8662f, + 0x5adb297d, 0xa5d68d85, + 0x5ac973b5, 0xa5c4b855, 0x5ab7ba6c, 0xa5b2e6a0, 0x5aa5fda5, 0xa5a11866, + 0x5a943d5e, 0xa58f4da8, + 0x5a82799a, 0xa57d8666, 0x5a70b258, 0xa56bc2a2, 0x5a5ee79a, 0xa55a025b, + 0x5a4d1960, 0xa5484594, + 0x5a3b47ab, 0xa5368c4b, 0x5a29727b, 0xa524d683, 0x5a1799d1, 0xa513243b, + 0x5a05bdae, 0xa5017575, + 0x59f3de12, 0xa4efca31, 0x59e1faff, 0xa4de2270, 0x59d01475, 0xa4cc7e32, + 0x59be2a74, 0xa4badd78, + 0x59ac3cfd, 0xa4a94043, 0x599a4c12, 0xa497a693, 0x598857b2, 0xa486106a, + 0x59765fde, 0xa4747dc7, + 0x59646498, 0xa462eeac, 0x595265df, 0xa4516319, 0x594063b5, 0xa43fdb10, + 0x592e5e19, 0xa42e568f, + 0x591c550e, 0xa41cd599, 0x590a4893, 0xa40b582e, 0x58f838a9, 0xa3f9de4e, + 0x58e62552, 0xa3e867fa, + 0x58d40e8c, 0xa3d6f534, 0x58c1f45b, 0xa3c585fb, 0x58afd6bd, 0xa3b41a50, + 0x589db5b3, 0xa3a2b234, + 0x588b9140, 0xa3914da8, 0x58796962, 0xa37fecac, 0x58673e1b, 0xa36e8f41, + 0x58550f6c, 0xa35d3567, + 0x5842dd54, 0xa34bdf20, 0x5830a7d6, 0xa33a8c6c, 0x581e6ef1, 0xa3293d4b, + 0x580c32a7, 0xa317f1bf, + 0x57f9f2f8, 0xa306a9c8, 0x57e7afe4, 0xa2f56566, 0x57d5696d, 0xa2e4249b, + 0x57c31f92, 0xa2d2e766, + 0x57b0d256, 0xa2c1adc9, 0x579e81b8, 0xa2b077c5, 0x578c2dba, 0xa29f4559, + 0x5779d65b, 0xa28e1687, + 0x57677b9d, 0xa27ceb4f, 0x57551d80, 0xa26bc3b2, 0x5742bc06, 0xa25a9fb1, + 0x5730572e, 0xa2497f4c, + 0x571deefa, 0xa2386284, 0x570b8369, 0xa2274959, 0x56f9147e, 0xa21633cd, + 0x56e6a239, 0xa20521e0, + 0x56d42c99, 0xa1f41392, 0x56c1b3a1, 0xa1e308e4, 0x56af3750, 0xa1d201d7, + 0x569cb7a8, 0xa1c0fe6c, + 0x568a34a9, 0xa1affea3, 0x5677ae54, 0xa19f027c, 0x566524aa, 0xa18e09fa, + 0x565297ab, 0xa17d151b, + 0x56400758, 0xa16c23e1, 0x562d73b2, 0xa15b364d, 0x561adcb9, 0xa14a4c5e, + 0x5608426e, 0xa1396617, + 0x55f5a4d2, 0xa1288376, 0x55e303e6, 0xa117a47e, 0x55d05faa, 0xa106c92f, + 0x55bdb81f, 0xa0f5f189, + 0x55ab0d46, 0xa0e51d8c, 0x55985f20, 0xa0d44d3b, 0x5585adad, 0xa0c38095, + 0x5572f8ed, 0xa0b2b79b, + 0x556040e2, 0xa0a1f24d, 0x554d858d, 0xa09130ad, 0x553ac6ee, 0xa08072ba, + 0x55280505, 0xa06fb876, + 0x55153fd4, 0xa05f01e1, 0x5502775c, 0xa04e4efc, 0x54efab9c, 0xa03d9fc8, + 0x54dcdc96, 0xa02cf444, + 0x54ca0a4b, 0xa01c4c73, 0x54b734ba, 0xa00ba853, 0x54a45be6, 0x9ffb07e7, + 0x54917fce, 0x9fea6b2f, + 0x547ea073, 0x9fd9d22a, 0x546bbdd7, 0x9fc93cdb, 0x5458d7f9, 0x9fb8ab41, + 0x5445eedb, 0x9fa81d5e, + 0x5433027d, 0x9f979331, 0x542012e1, 0x9f870cbc, 0x540d2005, 0x9f7689ff, + 0x53fa29ed, 0x9f660afb, + 0x53e73097, 0x9f558fb0, 0x53d43406, 0x9f45181f, 0x53c13439, 0x9f34a449, + 0x53ae3131, 0x9f24342f, + 0x539b2af0, 0x9f13c7d0, 0x53882175, 0x9f035f2e, 0x537514c2, 0x9ef2fa49, + 0x536204d7, 0x9ee29922, + 0x534ef1b5, 0x9ed23bb9, 0x533bdb5d, 0x9ec1e210, 0x5328c1d0, 0x9eb18c26, + 0x5315a50e, 0x9ea139fd, + 0x53028518, 0x9e90eb94, 0x52ef61ee, 0x9e80a0ee, 0x52dc3b92, 0x9e705a09, + 0x52c91204, 0x9e6016e8, + 0x52b5e546, 0x9e4fd78a, 0x52a2b556, 0x9e3f9bf0, 0x528f8238, 0x9e2f641b, + 0x527c4bea, 0x9e1f300b, + 0x5269126e, 0x9e0effc1, 0x5255d5c5, 0x9dfed33e, 0x524295f0, 0x9deeaa82, + 0x522f52ee, 0x9dde858e, + 0x521c0cc2, 0x9dce6463, 0x5208c36a, 0x9dbe4701, 0x51f576ea, 0x9dae2d68, + 0x51e22740, 0x9d9e179a, + 0x51ced46e, 0x9d8e0597, 0x51bb7e75, 0x9d7df75f, 0x51a82555, 0x9d6decf4, + 0x5194c910, 0x9d5de656, + 0x518169a5, 0x9d4de385, 0x516e0715, 0x9d3de482, 0x515aa162, 0x9d2de94d, + 0x5147388c, 0x9d1df1e9, + 0x5133cc94, 0x9d0dfe54, 0x51205d7b, 0x9cfe0e8f, 0x510ceb40, 0x9cee229c, + 0x50f975e6, 0x9cde3a7b, + 0x50e5fd6d, 0x9cce562c, 0x50d281d5, 0x9cbe75b0, 0x50bf031f, 0x9cae9907, + 0x50ab814d, 0x9c9ec033, + 0x5097fc5e, 0x9c8eeb34, 0x50847454, 0x9c7f1a0a, 0x5070e92f, 0x9c6f4cb6, + 0x505d5af1, 0x9c5f8339, + 0x5049c999, 0x9c4fbd93, 0x50363529, 0x9c3ffbc5, 0x50229da1, 0x9c303dcf, + 0x500f0302, 0x9c2083b3, + 0x4ffb654d, 0x9c10cd70, 0x4fe7c483, 0x9c011b08, 0x4fd420a4, 0x9bf16c7a, + 0x4fc079b1, 0x9be1c1c8, + 0x4faccfab, 0x9bd21af3, 0x4f992293, 0x9bc277fa, 0x4f857269, 0x9bb2d8de, + 0x4f71bf2e, 0x9ba33da0, + 0x4f5e08e3, 0x9b93a641, 0x4f4a4f89, 0x9b8412c1, 0x4f369320, 0x9b748320, + 0x4f22d3aa, 0x9b64f760, + 0x4f0f1126, 0x9b556f81, 0x4efb4b96, 0x9b45eb83, 0x4ee782fb, 0x9b366b68, + 0x4ed3b755, 0x9b26ef2f, + 0x4ebfe8a5, 0x9b1776da, 0x4eac16eb, 0x9b080268, 0x4e984229, 0x9af891db, + 0x4e846a60, 0x9ae92533, + 0x4e708f8f, 0x9ad9bc71, 0x4e5cb1b9, 0x9aca5795, 0x4e48d0dd, 0x9abaf6a1, + 0x4e34ecfc, 0x9aab9993, + 0x4e210617, 0x9a9c406e, 0x4e0d1c30, 0x9a8ceb31, 0x4df92f46, 0x9a7d99de, + 0x4de53f5a, 0x9a6e4c74, + 0x4dd14c6e, 0x9a5f02f5, 0x4dbd5682, 0x9a4fbd61, 0x4da95d96, 0x9a407bb9, + 0x4d9561ac, 0x9a313dfc, + 0x4d8162c4, 0x9a22042d, 0x4d6d60df, 0x9a12ce4b, 0x4d595bfe, 0x9a039c57, + 0x4d455422, 0x99f46e51, + 0x4d31494b, 0x99e5443b, 0x4d1d3b7a, 0x99d61e14, 0x4d092ab0, 0x99c6fbde, + 0x4cf516ee, 0x99b7dd99, + 0x4ce10034, 0x99a8c345, 0x4ccce684, 0x9999ace3, 0x4cb8c9dd, 0x998a9a74, + 0x4ca4aa41, 0x997b8bf8, + 0x4c9087b1, 0x996c816f, 0x4c7c622d, 0x995d7adc, 0x4c6839b7, 0x994e783d, + 0x4c540e4e, 0x993f7993, + 0x4c3fdff4, 0x99307ee0, 0x4c2baea9, 0x99218824, 0x4c177a6e, 0x9912955f, + 0x4c034345, 0x9903a691, + 0x4bef092d, 0x98f4bbbc, 0x4bdacc28, 0x98e5d4e0, 0x4bc68c36, 0x98d6f1fe, + 0x4bb24958, 0x98c81316, + 0x4b9e0390, 0x98b93828, 0x4b89badd, 0x98aa6136, 0x4b756f40, 0x989b8e40, + 0x4b6120bb, 0x988cbf46, + 0x4b4ccf4d, 0x987df449, 0x4b387af9, 0x986f2d4a, 0x4b2423be, 0x98606a49, + 0x4b0fc99d, 0x9851ab46, + 0x4afb6c98, 0x9842f043, 0x4ae70caf, 0x98343940, 0x4ad2a9e2, 0x9825863d, + 0x4abe4433, 0x9816d73b, + 0x4aa9dba2, 0x98082c3b, 0x4a957030, 0x97f9853d, 0x4a8101de, 0x97eae242, + 0x4a6c90ad, 0x97dc4349, + 0x4a581c9e, 0x97cda855, 0x4a43a5b0, 0x97bf1165, 0x4a2f2be6, 0x97b07e7a, + 0x4a1aaf3f, 0x97a1ef94, + 0x4a062fbd, 0x979364b5, 0x49f1ad61, 0x9784dddc, 0x49dd282a, 0x97765b0a, + 0x49c8a01b, 0x9767dc41, + 0x49b41533, 0x9759617f, 0x499f8774, 0x974aeac6, 0x498af6df, 0x973c7817, + 0x49766373, 0x972e0971, + 0x4961cd33, 0x971f9ed7, 0x494d341e, 0x97113847, 0x49389836, 0x9702d5c3, + 0x4923f97b, 0x96f4774b, + 0x490f57ee, 0x96e61ce0, 0x48fab391, 0x96d7c682, 0x48e60c62, 0x96c97432, + 0x48d16265, 0x96bb25f0, + 0x48bcb599, 0x96acdbbe, 0x48a805ff, 0x969e959b, 0x48935397, 0x96905388, + 0x487e9e64, 0x96821585, + 0x4869e665, 0x9673db94, 0x48552b9b, 0x9665a5b4, 0x48406e08, 0x965773e7, + 0x482badab, 0x9649462d, + 0x4816ea86, 0x963b1c86, 0x48022499, 0x962cf6f2, 0x47ed5be6, 0x961ed574, + 0x47d8906d, 0x9610b80a, + 0x47c3c22f, 0x96029eb6, 0x47aef12c, 0x95f48977, 0x479a1d67, 0x95e67850, + 0x478546de, 0x95d86b3f, + 0x47706d93, 0x95ca6247, 0x475b9188, 0x95bc5d66, 0x4746b2bc, 0x95ae5c9f, + 0x4731d131, 0x95a05ff0, + 0x471cece7, 0x9592675c, 0x470805df, 0x958472e2, 0x46f31c1a, 0x95768283, + 0x46de2f99, 0x9568963f, + 0x46c9405c, 0x955aae17, 0x46b44e65, 0x954cca0c, 0x469f59b4, 0x953eea1e, + 0x468a624a, 0x95310e4e, + 0x46756828, 0x9523369c, 0x46606b4e, 0x95156308, 0x464b6bbe, 0x95079394, + 0x46366978, 0x94f9c83f, + 0x4621647d, 0x94ec010b, 0x460c5cce, 0x94de3df8, 0x45f7526b, 0x94d07f05, + 0x45e24556, 0x94c2c435, + 0x45cd358f, 0x94b50d87, 0x45b82318, 0x94a75afd, 0x45a30df0, 0x9499ac95, + 0x458df619, 0x948c0252, + 0x4578db93, 0x947e5c33, 0x4563be60, 0x9470ba39, 0x454e9e80, 0x94631c65, + 0x45397bf4, 0x945582b7, + 0x452456bd, 0x9447ed2f, 0x450f2edb, 0x943a5bcf, 0x44fa0450, 0x942cce96, + 0x44e4d71c, 0x941f4585, + 0x44cfa740, 0x9411c09e, 0x44ba74bd, 0x94043fdf, 0x44a53f93, 0x93f6c34a, + 0x449007c4, 0x93e94adf, + 0x447acd50, 0x93dbd6a0, 0x44659039, 0x93ce668b, 0x4450507e, 0x93c0faa3, + 0x443b0e21, 0x93b392e6, + 0x4425c923, 0x93a62f57, 0x44108184, 0x9398cff5, 0x43fb3746, 0x938b74c1, + 0x43e5ea68, 0x937e1dbb, + 0x43d09aed, 0x9370cae4, 0x43bb48d4, 0x93637c3d, 0x43a5f41e, 0x935631c5, + 0x43909ccd, 0x9348eb7e, + 0x437b42e1, 0x933ba968, 0x4365e65b, 0x932e6b84, 0x4350873c, 0x932131d1, + 0x433b2585, 0x9313fc51, + 0x4325c135, 0x9306cb04, 0x43105a50, 0x92f99deb, 0x42faf0d4, 0x92ec7505, + 0x42e584c3, 0x92df5054, + 0x42d0161e, 0x92d22fd9, 0x42baa4e6, 0x92c51392, 0x42a5311b, 0x92b7fb82, + 0x428fbabe, 0x92aae7a8, + 0x427a41d0, 0x929dd806, 0x4264c653, 0x9290cc9b, 0x424f4845, 0x9283c568, + 0x4239c7aa, 0x9276c26d, + 0x42244481, 0x9269c3ac, 0x420ebecb, 0x925cc924, 0x41f93689, 0x924fd2d7, + 0x41e3abbc, 0x9242e0c4, + 0x41ce1e65, 0x9235f2ec, 0x41b88e84, 0x9229094f, 0x41a2fc1a, 0x921c23ef, + 0x418d6729, 0x920f42cb, + 0x4177cfb1, 0x920265e4, 0x416235b2, 0x91f58d3b, 0x414c992f, 0x91e8b8d0, + 0x4136fa27, 0x91dbe8a4, + 0x4121589b, 0x91cf1cb6, 0x410bb48c, 0x91c25508, 0x40f60dfb, 0x91b5919a, + 0x40e064ea, 0x91a8d26d, + 0x40cab958, 0x919c1781, 0x40b50b46, 0x918f60d6, 0x409f5ab6, 0x9182ae6d, + 0x4089a7a8, 0x91760047, + 0x4073f21d, 0x91695663, 0x405e3a16, 0x915cb0c3, 0x40487f94, 0x91500f67, + 0x4032c297, 0x91437250, + 0x401d0321, 0x9136d97d, 0x40074132, 0x912a44f0, 0x3ff17cca, 0x911db4a9, + 0x3fdbb5ec, 0x911128a8, + 0x3fc5ec98, 0x9104a0ee, 0x3fb020ce, 0x90f81d7b, 0x3f9a5290, 0x90eb9e50, + 0x3f8481dd, 0x90df236e, + 0x3f6eaeb8, 0x90d2acd4, 0x3f58d921, 0x90c63a83, 0x3f430119, 0x90b9cc7d, + 0x3f2d26a0, 0x90ad62c0, + 0x3f1749b8, 0x90a0fd4e, 0x3f016a61, 0x90949c28, 0x3eeb889c, 0x90883f4d, + 0x3ed5a46b, 0x907be6be, + 0x3ebfbdcd, 0x906f927c, 0x3ea9d4c3, 0x90634287, 0x3e93e950, 0x9056f6df, + 0x3e7dfb73, 0x904aaf86, + 0x3e680b2c, 0x903e6c7b, 0x3e52187f, 0x90322dbf, 0x3e3c2369, 0x9025f352, + 0x3e262bee, 0x9019bd36, + 0x3e10320d, 0x900d8b69, 0x3dfa35c8, 0x90015dee, 0x3de4371f, 0x8ff534c4, + 0x3dce3614, 0x8fe90fec, + 0x3db832a6, 0x8fdcef66, 0x3da22cd7, 0x8fd0d333, 0x3d8c24a8, 0x8fc4bb53, + 0x3d761a19, 0x8fb8a7c7, + 0x3d600d2c, 0x8fac988f, 0x3d49fde1, 0x8fa08dab, 0x3d33ec39, 0x8f94871d, + 0x3d1dd835, 0x8f8884e4, + 0x3d07c1d6, 0x8f7c8701, 0x3cf1a91c, 0x8f708d75, 0x3cdb8e09, 0x8f649840, + 0x3cc5709e, 0x8f58a761, + 0x3caf50da, 0x8f4cbadb, 0x3c992ec0, 0x8f40d2ad, 0x3c830a50, 0x8f34eed8, + 0x3c6ce38a, 0x8f290f5c, + 0x3c56ba70, 0x8f1d343a, 0x3c408f03, 0x8f115d72, 0x3c2a6142, 0x8f058b04, + 0x3c143130, 0x8ef9bcf2, + 0x3bfdfecd, 0x8eedf33b, 0x3be7ca1a, 0x8ee22de0, 0x3bd19318, 0x8ed66ce1, + 0x3bbb59c7, 0x8ecab040, + 0x3ba51e29, 0x8ebef7fb, 0x3b8ee03e, 0x8eb34415, 0x3b78a007, 0x8ea7948c, + 0x3b625d86, 0x8e9be963, + 0x3b4c18ba, 0x8e904298, 0x3b35d1a5, 0x8e84a02d, 0x3b1f8848, 0x8e790222, + 0x3b093ca3, 0x8e6d6877, + 0x3af2eeb7, 0x8e61d32e, 0x3adc9e86, 0x8e564246, 0x3ac64c0f, 0x8e4ab5bf, + 0x3aaff755, 0x8e3f2d9b, + 0x3a99a057, 0x8e33a9da, 0x3a834717, 0x8e282a7b, 0x3a6ceb96, 0x8e1caf80, + 0x3a568dd4, 0x8e1138ea, + 0x3a402dd2, 0x8e05c6b7, 0x3a29cb91, 0x8dfa58ea, 0x3a136712, 0x8deeef82, + 0x39fd0056, 0x8de38a80, + 0x39e6975e, 0x8dd829e4, 0x39d02c2a, 0x8dcccdaf, 0x39b9bebc, 0x8dc175e0, + 0x39a34f13, 0x8db6227a, + 0x398cdd32, 0x8daad37b, 0x39766919, 0x8d9f88e5, 0x395ff2c9, 0x8d9442b8, + 0x39497a43, 0x8d8900f3, + 0x3932ff87, 0x8d7dc399, 0x391c8297, 0x8d728aa9, 0x39060373, 0x8d675623, + 0x38ef821c, 0x8d5c2609, + 0x38d8fe93, 0x8d50fa59, 0x38c278d9, 0x8d45d316, 0x38abf0ef, 0x8d3ab03f, + 0x389566d6, 0x8d2f91d5, + 0x387eda8e, 0x8d2477d8, 0x38684c19, 0x8d196249, 0x3851bb77, 0x8d0e5127, + 0x383b28a9, 0x8d034474, + 0x382493b0, 0x8cf83c30, 0x380dfc8d, 0x8ced385b, 0x37f76341, 0x8ce238f6, + 0x37e0c7cc, 0x8cd73e01, + 0x37ca2a30, 0x8ccc477d, 0x37b38a6d, 0x8cc1556a, 0x379ce885, 0x8cb667c8, + 0x37864477, 0x8cab7e98, + 0x376f9e46, 0x8ca099da, 0x3758f5f2, 0x8c95b98f, 0x37424b7b, 0x8c8addb7, + 0x372b9ee3, 0x8c800652, + 0x3714f02a, 0x8c753362, 0x36fe3f52, 0x8c6a64e5, 0x36e78c5b, 0x8c5f9ade, + 0x36d0d746, 0x8c54d54c, + 0x36ba2014, 0x8c4a142f, 0x36a366c6, 0x8c3f5788, 0x368cab5c, 0x8c349f58, + 0x3675edd9, 0x8c29eb9f, + 0x365f2e3b, 0x8c1f3c5d, 0x36486c86, 0x8c149192, 0x3631a8b8, 0x8c09eb40, + 0x361ae2d3, 0x8bff4966, + 0x36041ad9, 0x8bf4ac05, 0x35ed50c9, 0x8bea131e, 0x35d684a6, 0x8bdf7eb0, + 0x35bfb66e, 0x8bd4eebc, + 0x35a8e625, 0x8bca6343, 0x359213c9, 0x8bbfdc44, 0x357b3f5d, 0x8bb559c1, + 0x356468e2, 0x8baadbba, + 0x354d9057, 0x8ba0622f, 0x3536b5be, 0x8b95ed21, 0x351fd918, 0x8b8b7c8f, + 0x3508fa66, 0x8b81107b, + 0x34f219a8, 0x8b76a8e4, 0x34db36df, 0x8b6c45cc, 0x34c4520d, 0x8b61e733, + 0x34ad6b32, 0x8b578d18, + 0x34968250, 0x8b4d377c, 0x347f9766, 0x8b42e661, 0x3468aa76, 0x8b3899c6, + 0x3451bb81, 0x8b2e51ab, + 0x343aca87, 0x8b240e11, 0x3423d78a, 0x8b19cef8, 0x340ce28b, 0x8b0f9462, + 0x33f5eb89, 0x8b055e4d, + 0x33def287, 0x8afb2cbb, 0x33c7f785, 0x8af0ffac, 0x33b0fa84, 0x8ae6d720, + 0x3399fb85, 0x8adcb318, + 0x3382fa88, 0x8ad29394, 0x336bf78f, 0x8ac87894, 0x3354f29b, 0x8abe6219, + 0x333debab, 0x8ab45024, + 0x3326e2c3, 0x8aaa42b4, 0x330fd7e1, 0x8aa039cb, 0x32f8cb07, 0x8a963567, + 0x32e1bc36, 0x8a8c358b, + 0x32caab6f, 0x8a823a36, 0x32b398b3, 0x8a784368, 0x329c8402, 0x8a6e5123, + 0x32856d5e, 0x8a646365, + 0x326e54c7, 0x8a5a7a31, 0x32573a3f, 0x8a509585, 0x32401dc6, 0x8a46b564, + 0x3228ff5c, 0x8a3cd9cc, + 0x3211df04, 0x8a3302be, 0x31fabcbd, 0x8a29303b, 0x31e39889, 0x8a1f6243, + 0x31cc7269, 0x8a1598d6, + 0x31b54a5e, 0x8a0bd3f5, 0x319e2067, 0x8a0213a0, 0x3186f487, 0x89f857d8, + 0x316fc6be, 0x89eea09d, + 0x3158970e, 0x89e4edef, 0x31416576, 0x89db3fcf, 0x312a31f8, 0x89d1963c, + 0x3112fc95, 0x89c7f138, + 0x30fbc54d, 0x89be50c3, 0x30e48c22, 0x89b4b4dd, 0x30cd5115, 0x89ab1d87, + 0x30b61426, 0x89a18ac0, + 0x309ed556, 0x8997fc8a, 0x308794a6, 0x898e72e4, 0x30705217, 0x8984edcf, + 0x30590dab, 0x897b6d4c, + 0x3041c761, 0x8971f15a, 0x302a7f3a, 0x896879fb, 0x30133539, 0x895f072e, + 0x2ffbe95d, 0x895598f3, + 0x2fe49ba7, 0x894c2f4c, 0x2fcd4c19, 0x8942ca39, 0x2fb5fab2, 0x893969b9, + 0x2f9ea775, 0x89300dce, + 0x2f875262, 0x8926b677, 0x2f6ffb7a, 0x891d63b5, 0x2f58a2be, 0x89141589, + 0x2f41482e, 0x890acbf2, + 0x2f29ebcc, 0x890186f2, 0x2f128d99, 0x88f84687, 0x2efb2d95, 0x88ef0ab4, + 0x2ee3cbc1, 0x88e5d378, + 0x2ecc681e, 0x88dca0d3, 0x2eb502ae, 0x88d372c6, 0x2e9d9b70, 0x88ca4951, + 0x2e863267, 0x88c12475, + 0x2e6ec792, 0x88b80432, 0x2e575af3, 0x88aee888, 0x2e3fec8b, 0x88a5d177, + 0x2e287c5a, 0x889cbf01, + 0x2e110a62, 0x8893b125, 0x2df996a3, 0x888aa7e3, 0x2de2211e, 0x8881a33d, + 0x2dcaa9d5, 0x8878a332, + 0x2db330c7, 0x886fa7c2, 0x2d9bb5f6, 0x8866b0ef, 0x2d843964, 0x885dbeb8, + 0x2d6cbb10, 0x8854d11e, + 0x2d553afc, 0x884be821, 0x2d3db928, 0x884303c1, 0x2d263596, 0x883a23ff, + 0x2d0eb046, 0x883148db, + 0x2cf72939, 0x88287256, 0x2cdfa071, 0x881fa06f, 0x2cc815ee, 0x8816d327, + 0x2cb089b1, 0x880e0a7f, + 0x2c98fbba, 0x88054677, 0x2c816c0c, 0x87fc870f, 0x2c69daa6, 0x87f3cc48, + 0x2c52478a, 0x87eb1621, + 0x2c3ab2b9, 0x87e2649b, 0x2c231c33, 0x87d9b7b7, 0x2c0b83fa, 0x87d10f75, + 0x2bf3ea0d, 0x87c86bd5, + 0x2bdc4e6f, 0x87bfccd7, 0x2bc4b120, 0x87b7327d, 0x2bad1221, 0x87ae9cc5, + 0x2b957173, 0x87a60bb1, + 0x2b7dcf17, 0x879d7f41, 0x2b662b0e, 0x8794f774, 0x2b4e8558, 0x878c744d, + 0x2b36ddf7, 0x8783f5ca, + 0x2b1f34eb, 0x877b7bec, 0x2b078a36, 0x877306b4, 0x2aefddd8, 0x876a9621, + 0x2ad82fd2, 0x87622a35, + 0x2ac08026, 0x8759c2ef, 0x2aa8ced3, 0x87516050, 0x2a911bdc, 0x87490258, + 0x2a796740, 0x8740a907, + 0x2a61b101, 0x8738545e, 0x2a49f920, 0x8730045d, 0x2a323f9e, 0x8727b905, + 0x2a1a847b, 0x871f7255, + 0x2a02c7b8, 0x8717304e, 0x29eb0957, 0x870ef2f1, 0x29d34958, 0x8706ba3d, + 0x29bb87bc, 0x86fe8633, + 0x29a3c485, 0x86f656d3, 0x298bffb2, 0x86ee2c1e, 0x29743946, 0x86e60614, + 0x295c7140, 0x86dde4b5, + 0x2944a7a2, 0x86d5c802, 0x292cdc6d, 0x86cdaffa, 0x29150fa1, 0x86c59c9f, + 0x28fd4140, 0x86bd8df0, + 0x28e5714b, 0x86b583ee, 0x28cd9fc1, 0x86ad7e99, 0x28b5cca5, 0x86a57df2, + 0x289df7f8, 0x869d81f8, + 0x288621b9, 0x86958aac, 0x286e49ea, 0x868d980e, 0x2856708d, 0x8685aa20, + 0x283e95a1, 0x867dc0e0, + 0x2826b928, 0x8675dc4f, 0x280edb23, 0x866dfc6e, 0x27f6fb92, 0x8666213c, + 0x27df1a77, 0x865e4abb, + 0x27c737d3, 0x865678eb, 0x27af53a6, 0x864eabcb, 0x27976df1, 0x8646e35c, + 0x277f86b5, 0x863f1f9e, + 0x27679df4, 0x86376092, 0x274fb3ae, 0x862fa638, 0x2737c7e3, 0x8627f091, + 0x271fda96, 0x86203f9c, + 0x2707ebc7, 0x86189359, 0x26effb76, 0x8610ebca, 0x26d809a5, 0x860948ef, + 0x26c01655, 0x8601aac7, + 0x26a82186, 0x85fa1153, 0x26902b39, 0x85f27c93, 0x26783370, 0x85eaec88, + 0x26603a2c, 0x85e36132, + 0x26483f6c, 0x85dbda91, 0x26304333, 0x85d458a6, 0x26184581, 0x85ccdb70, + 0x26004657, 0x85c562f1, + 0x25e845b6, 0x85bdef28, 0x25d0439f, 0x85b68015, 0x25b84012, 0x85af15b9, + 0x25a03b11, 0x85a7b015, + 0x2588349d, 0x85a04f28, 0x25702cb7, 0x8598f2f3, 0x2558235f, 0x85919b76, + 0x25401896, 0x858a48b1, + 0x25280c5e, 0x8582faa5, 0x250ffeb7, 0x857bb152, 0x24f7efa2, 0x85746cb8, + 0x24dfdf20, 0x856d2cd7, + 0x24c7cd33, 0x8565f1b0, 0x24afb9da, 0x855ebb44, 0x2497a517, 0x85578991, + 0x247f8eec, 0x85505c99, + 0x24677758, 0x8549345c, 0x244f5e5c, 0x854210db, 0x243743fa, 0x853af214, + 0x241f2833, 0x8533d809, + 0x24070b08, 0x852cc2bb, 0x23eeec78, 0x8525b228, 0x23d6cc87, 0x851ea652, + 0x23beab33, 0x85179f39, + 0x23a6887f, 0x85109cdd, 0x238e646a, 0x85099f3e, 0x23763ef7, 0x8502a65c, + 0x235e1826, 0x84fbb239, + 0x2345eff8, 0x84f4c2d4, 0x232dc66d, 0x84edd82d, 0x23159b88, 0x84e6f244, + 0x22fd6f48, 0x84e0111b, + 0x22e541af, 0x84d934b1, 0x22cd12bd, 0x84d25d06, 0x22b4e274, 0x84cb8a1b, + 0x229cb0d5, 0x84c4bbf0, + 0x22847de0, 0x84bdf286, 0x226c4996, 0x84b72ddb, 0x225413f8, 0x84b06df2, + 0x223bdd08, 0x84a9b2ca, + 0x2223a4c5, 0x84a2fc62, 0x220b6b32, 0x849c4abd, 0x21f3304f, 0x84959dd9, + 0x21daf41d, 0x848ef5b7, + 0x21c2b69c, 0x84885258, 0x21aa77cf, 0x8481b3bb, 0x219237b5, 0x847b19e1, + 0x2179f64f, 0x847484ca, + 0x2161b3a0, 0x846df477, 0x21496fa7, 0x846768e7, 0x21312a65, 0x8460e21a, + 0x2118e3dc, 0x845a6012, + 0x21009c0c, 0x8453e2cf, 0x20e852f6, 0x844d6a50, 0x20d0089c, 0x8446f695, + 0x20b7bcfe, 0x844087a0, + 0x209f701c, 0x843a1d70, 0x208721f9, 0x8433b806, 0x206ed295, 0x842d5762, + 0x205681f1, 0x8426fb84, + 0x203e300d, 0x8420a46c, 0x2025dcec, 0x841a521a, 0x200d888d, 0x84140490, + 0x1ff532f2, 0x840dbbcc, + 0x1fdcdc1b, 0x840777d0, 0x1fc4840a, 0x8401389b, 0x1fac2abf, 0x83fafe2e, + 0x1f93d03c, 0x83f4c889, + 0x1f7b7481, 0x83ee97ad, 0x1f63178f, 0x83e86b99, 0x1f4ab968, 0x83e2444d, + 0x1f325a0b, 0x83dc21cb, + 0x1f19f97b, 0x83d60412, 0x1f0197b8, 0x83cfeb22, 0x1ee934c3, 0x83c9d6fc, + 0x1ed0d09d, 0x83c3c7a0, + 0x1eb86b46, 0x83bdbd0e, 0x1ea004c1, 0x83b7b746, 0x1e879d0d, 0x83b1b649, + 0x1e6f342c, 0x83abba17, + 0x1e56ca1e, 0x83a5c2b0, 0x1e3e5ee5, 0x839fd014, 0x1e25f282, 0x8399e244, + 0x1e0d84f5, 0x8393f940, + 0x1df5163f, 0x838e1507, 0x1ddca662, 0x8388359b, 0x1dc4355e, 0x83825afb, + 0x1dabc334, 0x837c8528, + 0x1d934fe5, 0x8376b422, 0x1d7adb73, 0x8370e7e9, 0x1d6265dd, 0x836b207d, + 0x1d49ef26, 0x83655ddf, + 0x1d31774d, 0x835fa00f, 0x1d18fe54, 0x8359e70d, 0x1d00843d, 0x835432d8, + 0x1ce80906, 0x834e8373, + 0x1ccf8cb3, 0x8348d8dc, 0x1cb70f43, 0x83433314, 0x1c9e90b8, 0x833d921b, + 0x1c861113, 0x8337f5f1, + 0x1c6d9053, 0x83325e97, 0x1c550e7c, 0x832ccc0d, 0x1c3c8b8c, 0x83273e52, + 0x1c240786, 0x8321b568, + 0x1c0b826a, 0x831c314e, 0x1bf2fc3a, 0x8316b205, 0x1bda74f6, 0x8311378d, + 0x1bc1ec9e, 0x830bc1e6, + 0x1ba96335, 0x83065110, 0x1b90d8bb, 0x8300e50b, 0x1b784d30, 0x82fb7dd8, + 0x1b5fc097, 0x82f61b77, + 0x1b4732ef, 0x82f0bde8, 0x1b2ea43a, 0x82eb652b, 0x1b161479, 0x82e61141, + 0x1afd83ad, 0x82e0c22a, + 0x1ae4f1d6, 0x82db77e5, 0x1acc5ef6, 0x82d63274, 0x1ab3cb0d, 0x82d0f1d5, + 0x1a9b361d, 0x82cbb60b, + 0x1a82a026, 0x82c67f14, 0x1a6a0929, 0x82c14cf1, 0x1a517128, 0x82bc1fa2, + 0x1a38d823, 0x82b6f727, + 0x1a203e1b, 0x82b1d381, 0x1a07a311, 0x82acb4b0, 0x19ef0707, 0x82a79ab3, + 0x19d669fc, 0x82a2858c, + 0x19bdcbf3, 0x829d753a, 0x19a52ceb, 0x829869be, 0x198c8ce7, 0x82936317, + 0x1973ebe6, 0x828e6146, + 0x195b49ea, 0x8289644b, 0x1942a6f3, 0x82846c26, 0x192a0304, 0x827f78d8, + 0x19115e1c, 0x827a8a61, + 0x18f8b83c, 0x8275a0c0, 0x18e01167, 0x8270bbf7, 0x18c7699b, 0x826bdc04, + 0x18aec0db, 0x826700e9, + 0x18961728, 0x82622aa6, 0x187d6c82, 0x825d593a, 0x1864c0ea, 0x82588ca7, + 0x184c1461, 0x8253c4eb, + 0x183366e9, 0x824f0208, 0x181ab881, 0x824a43fe, 0x1802092c, 0x82458acc, + 0x17e958ea, 0x8240d673, + 0x17d0a7bc, 0x823c26f3, 0x17b7f5a3, 0x82377c4c, 0x179f429f, 0x8232d67f, + 0x17868eb3, 0x822e358b, + 0x176dd9de, 0x82299971, 0x17552422, 0x82250232, 0x173c6d80, 0x82206fcc, + 0x1723b5f9, 0x821be240, + 0x170afd8d, 0x82175990, 0x16f2443e, 0x8212d5b9, 0x16d98a0c, 0x820e56be, + 0x16c0cef9, 0x8209dc9e, + 0x16a81305, 0x82056758, 0x168f5632, 0x8200f6ef, 0x1676987f, 0x81fc8b60, + 0x165dd9f0, 0x81f824ae, + 0x16451a83, 0x81f3c2d7, 0x162c5a3b, 0x81ef65dc, 0x16139918, 0x81eb0dbe, + 0x15fad71b, 0x81e6ba7c, + 0x15e21445, 0x81e26c16, 0x15c95097, 0x81de228d, 0x15b08c12, 0x81d9dde1, + 0x1597c6b7, 0x81d59e13, + 0x157f0086, 0x81d16321, 0x15663982, 0x81cd2d0c, 0x154d71aa, 0x81c8fbd6, + 0x1534a901, 0x81c4cf7d, + 0x151bdf86, 0x81c0a801, 0x1503153a, 0x81bc8564, 0x14ea4a1f, 0x81b867a5, + 0x14d17e36, 0x81b44ec4, + 0x14b8b17f, 0x81b03ac2, 0x149fe3fc, 0x81ac2b9e, 0x148715ae, 0x81a82159, + 0x146e4694, 0x81a41bf4, + 0x145576b1, 0x81a01b6d, 0x143ca605, 0x819c1fc5, 0x1423d492, 0x819828fd, + 0x140b0258, 0x81943715, + 0x13f22f58, 0x81904a0c, 0x13d95b93, 0x818c61e3, 0x13c0870a, 0x81887e9a, + 0x13a7b1bf, 0x8184a032, + 0x138edbb1, 0x8180c6a9, 0x137604e2, 0x817cf201, 0x135d2d53, 0x8179223a, + 0x13445505, 0x81755754, + 0x132b7bf9, 0x8171914e, 0x1312a230, 0x816dd02a, 0x12f9c7aa, 0x816a13e6, + 0x12e0ec6a, 0x81665c84, + 0x12c8106f, 0x8162aa04, 0x12af33ba, 0x815efc65, 0x1296564d, 0x815b53a8, + 0x127d7829, 0x8157afcd, + 0x1264994e, 0x815410d4, 0x124bb9be, 0x815076bd, 0x1232d979, 0x814ce188, + 0x1219f880, 0x81495136, + 0x120116d5, 0x8145c5c7, 0x11e83478, 0x81423f3a, 0x11cf516a, 0x813ebd90, + 0x11b66dad, 0x813b40ca, + 0x119d8941, 0x8137c8e6, 0x1184a427, 0x813455e6, 0x116bbe60, 0x8130e7c9, + 0x1152d7ed, 0x812d7e8f, + 0x1139f0cf, 0x812a1a3a, 0x11210907, 0x8126bac8, 0x11082096, 0x8123603a, + 0x10ef377d, 0x81200a90, + 0x10d64dbd, 0x811cb9ca, 0x10bd6356, 0x81196de9, 0x10a4784b, 0x811626ec, + 0x108b8c9b, 0x8112e4d4, + 0x1072a048, 0x810fa7a0, 0x1059b352, 0x810c6f52, 0x1040c5bb, 0x81093be8, + 0x1027d784, 0x81060d63, + 0x100ee8ad, 0x8102e3c4, 0xff5f938, 0x80ffbf0a, 0xfdd0926, 0x80fc9f35, + 0xfc41876, 0x80f98446, + 0xfab272b, 0x80f66e3c, 0xf923546, 0x80f35d19, 0xf7942c7, 0x80f050db, + 0xf604faf, 0x80ed4984, + 0xf475bff, 0x80ea4712, 0xf2e67b8, 0x80e74987, 0xf1572dc, 0x80e450e2, + 0xefc7d6b, 0x80e15d24, + 0xee38766, 0x80de6e4c, 0xeca90ce, 0x80db845b, 0xeb199a4, 0x80d89f51, + 0xe98a1e9, 0x80d5bf2e, + 0xe7fa99e, 0x80d2e3f2, 0xe66b0c3, 0x80d00d9d, 0xe4db75b, 0x80cd3c2f, + 0xe34bd66, 0x80ca6fa9, + 0xe1bc2e4, 0x80c7a80a, 0xe02c7d7, 0x80c4e553, 0xde9cc40, 0x80c22784, + 0xdd0d01f, 0x80bf6e9c, + 0xdb7d376, 0x80bcba9d, 0xd9ed646, 0x80ba0b85, 0xd85d88f, 0x80b76156, + 0xd6cda53, 0x80b4bc0e, + 0xd53db92, 0x80b21baf, 0xd3adc4e, 0x80af8039, 0xd21dc87, 0x80ace9ab, + 0xd08dc3f, 0x80aa5806, + 0xcefdb76, 0x80a7cb49, 0xcd6da2d, 0x80a54376, 0xcbdd865, 0x80a2c08b, + 0xca4d620, 0x80a04289, + 0xc8bd35e, 0x809dc971, 0xc72d020, 0x809b5541, 0xc59cc68, 0x8098e5fb, + 0xc40c835, 0x80967b9f, + 0xc27c389, 0x8094162c, 0xc0ebe66, 0x8091b5a2, 0xbf5b8cb, 0x808f5a02, + 0xbdcb2bb, 0x808d034c, + 0xbc3ac35, 0x808ab180, 0xbaaa53b, 0x8088649e, 0xb919dcf, 0x80861ca6, + 0xb7895f0, 0x8083d998, + 0xb5f8d9f, 0x80819b74, 0xb4684df, 0x807f623b, 0xb2d7baf, 0x807d2dec, + 0xb147211, 0x807afe87, + 0xafb6805, 0x8078d40d, 0xae25d8d, 0x8076ae7e, 0xac952aa, 0x80748dd9, + 0xab0475c, 0x8072721f, + 0xa973ba5, 0x80705b50, 0xa7e2f85, 0x806e496c, 0xa6522fe, 0x806c3c74, + 0xa4c1610, 0x806a3466, + 0xa3308bd, 0x80683143, 0xa19fb04, 0x8066330c, 0xa00ece8, 0x806439c0, + 0x9e7de6a, 0x80624560, + 0x9cecf89, 0x806055eb, 0x9b5c048, 0x805e6b62, 0x99cb0a7, 0x805c85c4, + 0x983a0a7, 0x805aa512, + 0x96a9049, 0x8058c94c, 0x9517f8f, 0x8056f272, 0x9386e78, 0x80552084, + 0x91f5d06, 0x80535381, + 0x9064b3a, 0x80518b6b, 0x8ed3916, 0x804fc841, 0x8d42699, 0x804e0a04, + 0x8bb13c5, 0x804c50b2, + 0x8a2009a, 0x804a9c4d, 0x888ed1b, 0x8048ecd5, 0x86fd947, 0x80474248, + 0x856c520, 0x80459ca9, + 0x83db0a7, 0x8043fbf6, 0x8249bdd, 0x80426030, 0x80b86c2, 0x8040c956, + 0x7f27157, 0x803f376a, + 0x7d95b9e, 0x803daa6a, 0x7c04598, 0x803c2257, 0x7a72f45, 0x803a9f31, + 0x78e18a7, 0x803920f8, + 0x77501be, 0x8037a7ac, 0x75bea8c, 0x8036334e, 0x742d311, 0x8034c3dd, + 0x729bb4e, 0x80335959, + 0x710a345, 0x8031f3c2, 0x6f78af6, 0x80309318, 0x6de7262, 0x802f375d, + 0x6c5598a, 0x802de08e, + 0x6ac406f, 0x802c8ead, 0x6932713, 0x802b41ba, 0x67a0d76, 0x8029f9b4, + 0x660f398, 0x8028b69c, + 0x647d97c, 0x80277872, 0x62ebf22, 0x80263f36, 0x615a48b, 0x80250ae7, + 0x5fc89b8, 0x8023db86, + 0x5e36ea9, 0x8022b114, 0x5ca5361, 0x80218b8f, 0x5b137df, 0x80206af8, + 0x5981c26, 0x801f4f4f, + 0x57f0035, 0x801e3895, 0x565e40d, 0x801d26c8, 0x54cc7b1, 0x801c19ea, + 0x533ab20, 0x801b11fa, + 0x51a8e5c, 0x801a0ef8, 0x5017165, 0x801910e4, 0x4e8543e, 0x801817bf, + 0x4cf36e5, 0x80172388, + 0x4b6195d, 0x80163440, 0x49cfba7, 0x801549e6, 0x483ddc3, 0x8014647b, + 0x46abfb3, 0x801383fe, + 0x451a177, 0x8012a86f, 0x4388310, 0x8011d1d0, 0x41f6480, 0x8011001f, + 0x40645c7, 0x8010335c, + 0x3ed26e6, 0x800f6b88, 0x3d407df, 0x800ea8a3, 0x3bae8b2, 0x800deaad, + 0x3a1c960, 0x800d31a5, + 0x388a9ea, 0x800c7d8c, 0x36f8a51, 0x800bce63, 0x3566a96, 0x800b2427, + 0x33d4abb, 0x800a7edb, + 0x3242abf, 0x8009de7e, 0x30b0aa4, 0x80094310, 0x2f1ea6c, 0x8008ac90, + 0x2d8ca16, 0x80081b00, + 0x2bfa9a4, 0x80078e5e, 0x2a68917, 0x800706ac, 0x28d6870, 0x800683e8, + 0x27447b0, 0x80060614, + 0x25b26d7, 0x80058d2f, 0x24205e8, 0x80051939, 0x228e4e2, 0x8004aa32, + 0x20fc3c6, 0x8004401a, + 0x1f6a297, 0x8003daf1, 0x1dd8154, 0x80037ab7, 0x1c45ffe, 0x80031f6d, + 0x1ab3e97, 0x8002c912, + 0x1921d20, 0x800277a6, 0x178fb99, 0x80022b29, 0x15fda03, 0x8001e39b, + 0x146b860, 0x8001a0fd, + 0x12d96b1, 0x8001634e, 0x11474f6, 0x80012a8e, 0xfb5330, 0x8000f6bd, + 0xe23160, 0x8000c7dc, + 0xc90f88, 0x80009dea, 0xafeda8, 0x800078e7, 0x96cbc1, 0x800058d4, 0x7da9d4, + 0x80003daf, + 0x6487e3, 0x8000277a, 0x4b65ee, 0x80001635, 0x3243f5, 0x800009df, 0x1921fb, + 0x80000278, +}; + +/** +* \par +* cosFactor tables are generated using the formula :
cos_factors[n] = 2 * cos((2n+1)*pi/(4*N))
+* \par +* C command to generate the table +*
   
+* for(i = 0; i< N; i++)   
+* {   
+*   cos_factors[i]= 2 * cos((2*i+1)*c/2);   
+* } 
+* \par +* where N is the number of factors to generate and c is pi/(2*N) +* \par +* Then converted to q31 format by multiplying with 2^31 and saturated if required. +*/ + + +static const q31_t cos_factorsQ31_128[128] = { + 0x7fff6216, 0x7ffa72d1, 0x7ff09478, 0x7fe1c76b, 0x7fce0c3e, 0x7fb563b3, + 0x7f97cebd, 0x7f754e80, + 0x7f4de451, 0x7f2191b4, 0x7ef05860, 0x7eba3a39, 0x7e7f3957, 0x7e3f57ff, + 0x7dfa98a8, 0x7db0fdf8, + 0x7d628ac6, 0x7d0f4218, 0x7cb72724, 0x7c5a3d50, 0x7bf88830, 0x7b920b89, + 0x7b26cb4f, 0x7ab6cba4, + 0x7a4210d8, 0x79c89f6e, 0x794a7c12, 0x78c7aba2, 0x78403329, 0x77b417df, + 0x77235f2d, 0x768e0ea6, + 0x75f42c0b, 0x7555bd4c, 0x74b2c884, 0x740b53fb, 0x735f6626, 0x72af05a7, + 0x71fa3949, 0x71410805, + 0x708378ff, 0x6fc19385, 0x6efb5f12, 0x6e30e34a, 0x6d6227fa, 0x6c8f351c, + 0x6bb812d1, 0x6adcc964, + 0x69fd614a, 0x6919e320, 0x683257ab, 0x6746c7d8, 0x66573cbb, 0x6563bf92, + 0x646c59bf, 0x637114cc, + 0x6271fa69, 0x616f146c, 0x60686ccf, 0x5f5e0db3, 0x5e50015d, 0x5d3e5237, + 0x5c290acc, 0x5b1035cf, + 0x59f3de12, 0x58d40e8c, 0x57b0d256, 0x568a34a9, 0x556040e2, 0x5433027d, + 0x53028518, 0x51ced46e, + 0x5097fc5e, 0x4f5e08e3, 0x4e210617, 0x4ce10034, 0x4b9e0390, 0x4a581c9e, + 0x490f57ee, 0x47c3c22f, + 0x46756828, 0x452456bd, 0x43d09aed, 0x427a41d0, 0x4121589b, 0x3fc5ec98, + 0x3e680b2c, 0x3d07c1d6, + 0x3ba51e29, 0x3a402dd2, 0x38d8fe93, 0x376f9e46, 0x36041ad9, 0x34968250, + 0x3326e2c3, 0x31b54a5e, + 0x3041c761, 0x2ecc681e, 0x2d553afc, 0x2bdc4e6f, 0x2a61b101, 0x28e5714b, + 0x27679df4, 0x25e845b6, + 0x24677758, 0x22e541af, 0x2161b3a0, 0x1fdcdc1b, 0x1e56ca1e, 0x1ccf8cb3, + 0x1b4732ef, 0x19bdcbf3, + 0x183366e9, 0x16a81305, 0x151bdf86, 0x138edbb1, 0x120116d5, 0x1072a048, + 0xee38766, 0xd53db92, + 0xbc3ac35, 0xa3308bd, 0x8a2009a, 0x710a345, 0x57f0035, 0x3ed26e6, 0x25b26d7, + 0xc90f88, +}; + +static const q31_t cos_factorsQ31_512[512] = { + 0x7ffff621, 0x7fffa72c, 0x7fff0943, 0x7ffe1c65, 0x7ffce093, 0x7ffb55ce, + 0x7ff97c18, 0x7ff75370, + 0x7ff4dbd9, 0x7ff21553, 0x7feeffe1, 0x7feb9b85, 0x7fe7e841, 0x7fe3e616, + 0x7fdf9508, 0x7fdaf519, + 0x7fd6064c, 0x7fd0c8a3, 0x7fcb3c23, 0x7fc560cf, 0x7fbf36aa, 0x7fb8bdb8, + 0x7fb1f5fc, 0x7faadf7c, + 0x7fa37a3c, 0x7f9bc640, 0x7f93c38c, 0x7f8b7227, 0x7f82d214, 0x7f79e35a, + 0x7f70a5fe, 0x7f671a05, + 0x7f5d3f75, 0x7f531655, 0x7f489eaa, 0x7f3dd87c, 0x7f32c3d1, 0x7f2760af, + 0x7f1baf1e, 0x7f0faf25, + 0x7f0360cb, 0x7ef6c418, 0x7ee9d914, 0x7edc9fc6, 0x7ecf1837, 0x7ec14270, + 0x7eb31e78, 0x7ea4ac58, + 0x7e95ec1a, 0x7e86ddc6, 0x7e778166, 0x7e67d703, 0x7e57dea7, 0x7e47985b, + 0x7e37042a, 0x7e26221f, + 0x7e14f242, 0x7e0374a0, 0x7df1a942, 0x7ddf9034, 0x7dcd2981, 0x7dba7534, + 0x7da77359, 0x7d9423fc, + 0x7d808728, 0x7d6c9ce9, 0x7d58654d, 0x7d43e05e, 0x7d2f0e2b, 0x7d19eebf, + 0x7d048228, 0x7ceec873, + 0x7cd8c1ae, 0x7cc26de5, 0x7cabcd28, 0x7c94df83, 0x7c7da505, 0x7c661dbc, + 0x7c4e49b7, 0x7c362904, + 0x7c1dbbb3, 0x7c0501d2, 0x7bebfb70, 0x7bd2a89e, 0x7bb9096b, 0x7b9f1de6, + 0x7b84e61f, 0x7b6a6227, + 0x7b4f920e, 0x7b3475e5, 0x7b190dbc, 0x7afd59a4, 0x7ae159ae, 0x7ac50dec, + 0x7aa8766f, 0x7a8b9348, + 0x7a6e648a, 0x7a50ea47, 0x7a332490, 0x7a151378, 0x79f6b711, 0x79d80f6f, + 0x79b91ca4, 0x7999dec4, + 0x797a55e0, 0x795a820e, 0x793a6361, 0x7919f9ec, 0x78f945c3, 0x78d846fb, + 0x78b6fda8, 0x789569df, + 0x78738bb3, 0x7851633b, 0x782ef08b, 0x780c33b8, 0x77e92cd9, 0x77c5dc01, + 0x77a24148, 0x777e5cc3, + 0x775a2e89, 0x7735b6af, 0x7710f54c, 0x76ebea77, 0x76c69647, 0x76a0f8d2, + 0x767b1231, 0x7654e279, + 0x762e69c4, 0x7607a828, 0x75e09dbd, 0x75b94a9c, 0x7591aedd, 0x7569ca99, + 0x75419de7, 0x751928e0, + 0x74f06b9e, 0x74c7663a, 0x749e18cd, 0x74748371, 0x744aa63f, 0x74208150, + 0x73f614c0, 0x73cb60a8, + 0x73a06522, 0x73752249, 0x73499838, 0x731dc70a, 0x72f1aed9, 0x72c54fc1, + 0x7298a9dd, 0x726bbd48, + 0x723e8a20, 0x7211107e, 0x71e35080, 0x71b54a41, 0x7186fdde, 0x71586b74, + 0x7129931f, 0x70fa74fc, + 0x70cb1128, 0x709b67c0, 0x706b78e3, 0x703b44ad, 0x700acb3c, 0x6fda0cae, + 0x6fa90921, 0x6f77c0b3, + 0x6f463383, 0x6f1461b0, 0x6ee24b57, 0x6eaff099, 0x6e7d5193, 0x6e4a6e66, + 0x6e174730, 0x6de3dc11, + 0x6db02d29, 0x6d7c3a98, 0x6d48047e, 0x6d138afb, 0x6cdece2f, 0x6ca9ce3b, + 0x6c748b3f, 0x6c3f055d, + 0x6c093cb6, 0x6bd3316a, 0x6b9ce39b, 0x6b66536b, 0x6b2f80fb, 0x6af86c6c, + 0x6ac115e2, 0x6a897d7d, + 0x6a51a361, 0x6a1987b0, 0x69e12a8c, 0x69a88c19, 0x696fac78, 0x69368bce, + 0x68fd2a3d, 0x68c387e9, + 0x6889a4f6, 0x684f8186, 0x68151dbe, 0x67da79c3, 0x679f95b7, 0x676471c0, + 0x67290e02, 0x66ed6aa1, + 0x66b187c3, 0x6675658c, 0x66390422, 0x65fc63a9, 0x65bf8447, 0x65826622, + 0x6545095f, 0x65076e25, + 0x64c99498, 0x648b7ce0, 0x644d2722, 0x640e9386, 0x63cfc231, 0x6390b34a, + 0x635166f9, 0x6311dd64, + 0x62d216b3, 0x6292130c, 0x6251d298, 0x6211557e, 0x61d09be5, 0x618fa5f7, + 0x614e73da, 0x610d05b7, + 0x60cb5bb7, 0x60897601, 0x604754bf, 0x6004f819, 0x5fc26038, 0x5f7f8d46, + 0x5f3c7f6b, 0x5ef936d1, + 0x5eb5b3a2, 0x5e71f606, 0x5e2dfe29, 0x5de9cc33, 0x5da5604f, 0x5d60baa7, + 0x5d1bdb65, 0x5cd6c2b5, + 0x5c9170bf, 0x5c4be5b0, 0x5c0621b2, 0x5bc024f0, 0x5b79ef96, 0x5b3381ce, + 0x5aecdbc5, 0x5aa5fda5, + 0x5a5ee79a, 0x5a1799d1, 0x59d01475, 0x598857b2, 0x594063b5, 0x58f838a9, + 0x58afd6bd, 0x58673e1b, + 0x581e6ef1, 0x57d5696d, 0x578c2dba, 0x5742bc06, 0x56f9147e, 0x56af3750, + 0x566524aa, 0x561adcb9, + 0x55d05faa, 0x5585adad, 0x553ac6ee, 0x54efab9c, 0x54a45be6, 0x5458d7f9, + 0x540d2005, 0x53c13439, + 0x537514c2, 0x5328c1d0, 0x52dc3b92, 0x528f8238, 0x524295f0, 0x51f576ea, + 0x51a82555, 0x515aa162, + 0x510ceb40, 0x50bf031f, 0x5070e92f, 0x50229da1, 0x4fd420a4, 0x4f857269, + 0x4f369320, 0x4ee782fb, + 0x4e984229, 0x4e48d0dd, 0x4df92f46, 0x4da95d96, 0x4d595bfe, 0x4d092ab0, + 0x4cb8c9dd, 0x4c6839b7, + 0x4c177a6e, 0x4bc68c36, 0x4b756f40, 0x4b2423be, 0x4ad2a9e2, 0x4a8101de, + 0x4a2f2be6, 0x49dd282a, + 0x498af6df, 0x49389836, 0x48e60c62, 0x48935397, 0x48406e08, 0x47ed5be6, + 0x479a1d67, 0x4746b2bc, + 0x46f31c1a, 0x469f59b4, 0x464b6bbe, 0x45f7526b, 0x45a30df0, 0x454e9e80, + 0x44fa0450, 0x44a53f93, + 0x4450507e, 0x43fb3746, 0x43a5f41e, 0x4350873c, 0x42faf0d4, 0x42a5311b, + 0x424f4845, 0x41f93689, + 0x41a2fc1a, 0x414c992f, 0x40f60dfb, 0x409f5ab6, 0x40487f94, 0x3ff17cca, + 0x3f9a5290, 0x3f430119, + 0x3eeb889c, 0x3e93e950, 0x3e3c2369, 0x3de4371f, 0x3d8c24a8, 0x3d33ec39, + 0x3cdb8e09, 0x3c830a50, + 0x3c2a6142, 0x3bd19318, 0x3b78a007, 0x3b1f8848, 0x3ac64c0f, 0x3a6ceb96, + 0x3a136712, 0x39b9bebc, + 0x395ff2c9, 0x39060373, 0x38abf0ef, 0x3851bb77, 0x37f76341, 0x379ce885, + 0x37424b7b, 0x36e78c5b, + 0x368cab5c, 0x3631a8b8, 0x35d684a6, 0x357b3f5d, 0x351fd918, 0x34c4520d, + 0x3468aa76, 0x340ce28b, + 0x33b0fa84, 0x3354f29b, 0x32f8cb07, 0x329c8402, 0x32401dc6, 0x31e39889, + 0x3186f487, 0x312a31f8, + 0x30cd5115, 0x30705217, 0x30133539, 0x2fb5fab2, 0x2f58a2be, 0x2efb2d95, + 0x2e9d9b70, 0x2e3fec8b, + 0x2de2211e, 0x2d843964, 0x2d263596, 0x2cc815ee, 0x2c69daa6, 0x2c0b83fa, + 0x2bad1221, 0x2b4e8558, + 0x2aefddd8, 0x2a911bdc, 0x2a323f9e, 0x29d34958, 0x29743946, 0x29150fa1, + 0x28b5cca5, 0x2856708d, + 0x27f6fb92, 0x27976df1, 0x2737c7e3, 0x26d809a5, 0x26783370, 0x26184581, + 0x25b84012, 0x2558235f, + 0x24f7efa2, 0x2497a517, 0x243743fa, 0x23d6cc87, 0x23763ef7, 0x23159b88, + 0x22b4e274, 0x225413f8, + 0x21f3304f, 0x219237b5, 0x21312a65, 0x20d0089c, 0x206ed295, 0x200d888d, + 0x1fac2abf, 0x1f4ab968, + 0x1ee934c3, 0x1e879d0d, 0x1e25f282, 0x1dc4355e, 0x1d6265dd, 0x1d00843d, + 0x1c9e90b8, 0x1c3c8b8c, + 0x1bda74f6, 0x1b784d30, 0x1b161479, 0x1ab3cb0d, 0x1a517128, 0x19ef0707, + 0x198c8ce7, 0x192a0304, + 0x18c7699b, 0x1864c0ea, 0x1802092c, 0x179f429f, 0x173c6d80, 0x16d98a0c, + 0x1676987f, 0x16139918, + 0x15b08c12, 0x154d71aa, 0x14ea4a1f, 0x148715ae, 0x1423d492, 0x13c0870a, + 0x135d2d53, 0x12f9c7aa, + 0x1296564d, 0x1232d979, 0x11cf516a, 0x116bbe60, 0x11082096, 0x10a4784b, + 0x1040c5bb, 0xfdd0926, + 0xf7942c7, 0xf1572dc, 0xeb199a4, 0xe4db75b, 0xde9cc40, 0xd85d88f, 0xd21dc87, + 0xcbdd865, + 0xc59cc68, 0xbf5b8cb, 0xb919dcf, 0xb2d7baf, 0xac952aa, 0xa6522fe, 0xa00ece8, + 0x99cb0a7, + 0x9386e78, 0x8d42699, 0x86fd947, 0x80b86c2, 0x7a72f45, 0x742d311, 0x6de7262, + 0x67a0d76, + 0x615a48b, 0x5b137df, 0x54cc7b1, 0x4e8543e, 0x483ddc3, 0x41f6480, 0x3bae8b2, + 0x3566a96, + 0x2f1ea6c, 0x28d6870, 0x228e4e2, 0x1c45ffe, 0x15fda03, 0xfb5330, 0x96cbc1, + 0x3243f5, +}; + +static const q31_t cos_factorsQ31_2048[2048] = { + 0x7fffff62, 0x7ffffa73, 0x7ffff094, 0x7fffe1c6, 0x7fffce09, 0x7fffb55c, + 0x7fff97c1, 0x7fff7536, + 0x7fff4dbb, 0x7fff2151, 0x7ffeeff8, 0x7ffeb9b0, 0x7ffe7e79, 0x7ffe3e52, + 0x7ffdf93c, 0x7ffdaf37, + 0x7ffd6042, 0x7ffd0c5f, 0x7ffcb38c, 0x7ffc55ca, 0x7ffbf319, 0x7ffb8b78, + 0x7ffb1ee9, 0x7ffaad6a, + 0x7ffa36fc, 0x7ff9bba0, 0x7ff93b54, 0x7ff8b619, 0x7ff82bef, 0x7ff79cd6, + 0x7ff708ce, 0x7ff66fd7, + 0x7ff5d1f1, 0x7ff52f1d, 0x7ff48759, 0x7ff3daa6, 0x7ff32905, 0x7ff27275, + 0x7ff1b6f6, 0x7ff0f688, + 0x7ff0312c, 0x7fef66e1, 0x7fee97a7, 0x7fedc37e, 0x7fecea67, 0x7fec0c62, + 0x7feb296d, 0x7fea418b, + 0x7fe954ba, 0x7fe862fa, 0x7fe76c4c, 0x7fe670b0, 0x7fe57025, 0x7fe46aac, + 0x7fe36045, 0x7fe250ef, + 0x7fe13cac, 0x7fe0237a, 0x7fdf055a, 0x7fdde24d, 0x7fdcba51, 0x7fdb8d67, + 0x7fda5b8f, 0x7fd924ca, + 0x7fd7e917, 0x7fd6a875, 0x7fd562e7, 0x7fd4186a, 0x7fd2c900, 0x7fd174a8, + 0x7fd01b63, 0x7fcebd31, + 0x7fcd5a11, 0x7fcbf203, 0x7fca8508, 0x7fc91320, 0x7fc79c4b, 0x7fc62089, + 0x7fc49fda, 0x7fc31a3d, + 0x7fc18fb4, 0x7fc0003e, 0x7fbe6bdb, 0x7fbcd28b, 0x7fbb344e, 0x7fb99125, + 0x7fb7e90f, 0x7fb63c0d, + 0x7fb48a1e, 0x7fb2d343, 0x7fb1177b, 0x7faf56c7, 0x7fad9127, 0x7fabc69b, + 0x7fa9f723, 0x7fa822bf, + 0x7fa6496e, 0x7fa46b32, 0x7fa2880b, 0x7fa09ff7, 0x7f9eb2f8, 0x7f9cc10d, + 0x7f9aca37, 0x7f98ce76, + 0x7f96cdc9, 0x7f94c831, 0x7f92bdad, 0x7f90ae3f, 0x7f8e99e6, 0x7f8c80a1, + 0x7f8a6272, 0x7f883f58, + 0x7f861753, 0x7f83ea64, 0x7f81b88a, 0x7f7f81c6, 0x7f7d4617, 0x7f7b057e, + 0x7f78bffb, 0x7f76758e, + 0x7f742637, 0x7f71d1f6, 0x7f6f78cb, 0x7f6d1ab6, 0x7f6ab7b8, 0x7f684fd0, + 0x7f65e2ff, 0x7f637144, + 0x7f60faa0, 0x7f5e7f13, 0x7f5bfe9d, 0x7f59793e, 0x7f56eef5, 0x7f545fc5, + 0x7f51cbab, 0x7f4f32a9, + 0x7f4c94be, 0x7f49f1eb, 0x7f474a30, 0x7f449d8c, 0x7f41ec01, 0x7f3f358d, + 0x7f3c7a31, 0x7f39b9ee, + 0x7f36f4c3, 0x7f342ab1, 0x7f315bb7, 0x7f2e87d6, 0x7f2baf0d, 0x7f28d15d, + 0x7f25eec7, 0x7f230749, + 0x7f201ae5, 0x7f1d299a, 0x7f1a3368, 0x7f173850, 0x7f143852, 0x7f11336d, + 0x7f0e29a3, 0x7f0b1af2, + 0x7f08075c, 0x7f04eedf, 0x7f01d17d, 0x7efeaf36, 0x7efb8809, 0x7ef85bf7, + 0x7ef52b00, 0x7ef1f524, + 0x7eeeba62, 0x7eeb7abc, 0x7ee83632, 0x7ee4ecc3, 0x7ee19e6f, 0x7ede4b38, + 0x7edaf31c, 0x7ed7961c, + 0x7ed43438, 0x7ed0cd70, 0x7ecd61c5, 0x7ec9f137, 0x7ec67bc5, 0x7ec3016f, + 0x7ebf8237, 0x7ebbfe1c, + 0x7eb8751e, 0x7eb4e73d, 0x7eb1547a, 0x7eadbcd4, 0x7eaa204c, 0x7ea67ee2, + 0x7ea2d896, 0x7e9f2d68, + 0x7e9b7d58, 0x7e97c867, 0x7e940e94, 0x7e904fe0, 0x7e8c8c4b, 0x7e88c3d5, + 0x7e84f67e, 0x7e812447, + 0x7e7d4d2f, 0x7e797136, 0x7e75905d, 0x7e71aaa4, 0x7e6dc00c, 0x7e69d093, + 0x7e65dc3b, 0x7e61e303, + 0x7e5de4ec, 0x7e59e1f5, 0x7e55da20, 0x7e51cd6c, 0x7e4dbbd9, 0x7e49a567, + 0x7e458a17, 0x7e4169e9, + 0x7e3d44dd, 0x7e391af3, 0x7e34ec2b, 0x7e30b885, 0x7e2c8002, 0x7e2842a2, + 0x7e240064, 0x7e1fb94a, + 0x7e1b6d53, 0x7e171c7f, 0x7e12c6ce, 0x7e0e6c42, 0x7e0a0cd9, 0x7e05a894, + 0x7e013f74, 0x7dfcd178, + 0x7df85ea0, 0x7df3e6ee, 0x7def6a60, 0x7deae8f7, 0x7de662b3, 0x7de1d795, + 0x7ddd479d, 0x7dd8b2ca, + 0x7dd4191d, 0x7dcf7a96, 0x7dcad736, 0x7dc62efc, 0x7dc181e8, 0x7dbccffc, + 0x7db81936, 0x7db35d98, + 0x7dae9d21, 0x7da9d7d2, 0x7da50dab, 0x7da03eab, 0x7d9b6ad3, 0x7d969224, + 0x7d91b49e, 0x7d8cd240, + 0x7d87eb0a, 0x7d82fefe, 0x7d7e0e1c, 0x7d791862, 0x7d741dd2, 0x7d6f1e6c, + 0x7d6a1a31, 0x7d65111f, + 0x7d600338, 0x7d5af07b, 0x7d55d8e9, 0x7d50bc82, 0x7d4b9b46, 0x7d467536, + 0x7d414a51, 0x7d3c1a98, + 0x7d36e60b, 0x7d31acaa, 0x7d2c6e76, 0x7d272b6e, 0x7d21e393, 0x7d1c96e5, + 0x7d174564, 0x7d11ef11, + 0x7d0c93eb, 0x7d0733f3, 0x7d01cf29, 0x7cfc658d, 0x7cf6f720, 0x7cf183e1, + 0x7cec0bd1, 0x7ce68ef0, + 0x7ce10d3f, 0x7cdb86bd, 0x7cd5fb6a, 0x7cd06b48, 0x7ccad656, 0x7cc53c94, + 0x7cbf9e03, 0x7cb9faa2, + 0x7cb45272, 0x7caea574, 0x7ca8f3a7, 0x7ca33d0c, 0x7c9d81a3, 0x7c97c16b, + 0x7c91fc66, 0x7c8c3294, + 0x7c8663f4, 0x7c809088, 0x7c7ab84e, 0x7c74db48, 0x7c6ef976, 0x7c6912d7, + 0x7c63276d, 0x7c5d3737, + 0x7c574236, 0x7c514869, 0x7c4b49d2, 0x7c45466f, 0x7c3f3e42, 0x7c39314b, + 0x7c331f8a, 0x7c2d08ff, + 0x7c26edab, 0x7c20cd8d, 0x7c1aa8a6, 0x7c147ef6, 0x7c0e507e, 0x7c081d3d, + 0x7c01e534, 0x7bfba863, + 0x7bf566cb, 0x7bef206b, 0x7be8d544, 0x7be28556, 0x7bdc30a1, 0x7bd5d726, + 0x7bcf78e5, 0x7bc915dd, + 0x7bc2ae10, 0x7bbc417e, 0x7bb5d026, 0x7baf5a09, 0x7ba8df28, 0x7ba25f82, + 0x7b9bdb18, 0x7b9551ea, + 0x7b8ec3f8, 0x7b883143, 0x7b8199ca, 0x7b7afd8f, 0x7b745c91, 0x7b6db6d0, + 0x7b670c4d, 0x7b605d09, + 0x7b59a902, 0x7b52f03a, 0x7b4c32b1, 0x7b457068, 0x7b3ea95d, 0x7b37dd92, + 0x7b310d07, 0x7b2a37bc, + 0x7b235db2, 0x7b1c7ee8, 0x7b159b5f, 0x7b0eb318, 0x7b07c612, 0x7b00d44d, + 0x7af9ddcb, 0x7af2e28b, + 0x7aebe28d, 0x7ae4ddd2, 0x7addd45b, 0x7ad6c626, 0x7acfb336, 0x7ac89b89, + 0x7ac17f20, 0x7aba5dfc, + 0x7ab3381d, 0x7aac0d82, 0x7aa4de2d, 0x7a9daa1d, 0x7a967153, 0x7a8f33d0, + 0x7a87f192, 0x7a80aa9c, + 0x7a795eec, 0x7a720e84, 0x7a6ab963, 0x7a635f8a, 0x7a5c00f9, 0x7a549db0, + 0x7a4d35b0, 0x7a45c8f9, + 0x7a3e578b, 0x7a36e166, 0x7a2f668c, 0x7a27e6fb, 0x7a2062b5, 0x7a18d9b9, + 0x7a114c09, 0x7a09b9a4, + 0x7a02228a, 0x79fa86bc, 0x79f2e63a, 0x79eb4105, 0x79e3971c, 0x79dbe880, + 0x79d43532, 0x79cc7d31, + 0x79c4c07e, 0x79bcff19, 0x79b53903, 0x79ad6e3c, 0x79a59ec3, 0x799dca9a, + 0x7995f1c1, 0x798e1438, + 0x798631ff, 0x797e4b16, 0x79765f7f, 0x796e6f39, 0x79667a44, 0x795e80a1, + 0x79568250, 0x794e7f52, + 0x794677a6, 0x793e6b4e, 0x79365a49, 0x792e4497, 0x79262a3a, 0x791e0b31, + 0x7915e77c, 0x790dbf1d, + 0x79059212, 0x78fd605d, 0x78f529fe, 0x78eceef6, 0x78e4af44, 0x78dc6ae8, + 0x78d421e4, 0x78cbd437, + 0x78c381e2, 0x78bb2ae5, 0x78b2cf41, 0x78aa6ef5, 0x78a20a03, 0x7899a06a, + 0x7891322a, 0x7888bf45, + 0x788047ba, 0x7877cb89, 0x786f4ab4, 0x7866c53a, 0x785e3b1c, 0x7855ac5a, + 0x784d18f4, 0x784480ea, + 0x783be43e, 0x783342ef, 0x782a9cfe, 0x7821f26b, 0x78194336, 0x78108f60, + 0x7807d6e9, 0x77ff19d1, + 0x77f65819, 0x77ed91c0, 0x77e4c6c9, 0x77dbf732, 0x77d322fc, 0x77ca4a27, + 0x77c16cb4, 0x77b88aa3, + 0x77afa3f5, 0x77a6b8a9, 0x779dc8c0, 0x7794d43b, 0x778bdb19, 0x7782dd5c, + 0x7779db03, 0x7770d40f, + 0x7767c880, 0x775eb857, 0x7755a394, 0x774c8a36, 0x77436c40, 0x773a49b0, + 0x77312287, 0x7727f6c6, + 0x771ec66e, 0x7715917d, 0x770c57f5, 0x770319d6, 0x76f9d721, 0x76f08fd5, + 0x76e743f4, 0x76ddf37c, + 0x76d49e70, 0x76cb44cf, 0x76c1e699, 0x76b883d0, 0x76af1c72, 0x76a5b082, + 0x769c3ffe, 0x7692cae8, + 0x7689513f, 0x767fd304, 0x76765038, 0x766cc8db, 0x76633ced, 0x7659ac6f, + 0x76501760, 0x76467dc2, + 0x763cdf94, 0x76333cd8, 0x7629958c, 0x761fe9b3, 0x7616394c, 0x760c8457, + 0x7602cad5, 0x75f90cc7, + 0x75ef4a2c, 0x75e58305, 0x75dbb753, 0x75d1e715, 0x75c8124d, 0x75be38fa, + 0x75b45b1d, 0x75aa78b6, + 0x75a091c6, 0x7596a64d, 0x758cb64c, 0x7582c1c2, 0x7578c8b0, 0x756ecb18, + 0x7564c8f8, 0x755ac251, + 0x7550b725, 0x7546a772, 0x753c933a, 0x75327a7d, 0x75285d3b, 0x751e3b75, + 0x7514152b, 0x7509ea5d, + 0x74ffbb0d, 0x74f58739, 0x74eb4ee3, 0x74e1120c, 0x74d6d0b2, 0x74cc8ad8, + 0x74c2407d, 0x74b7f1a1, + 0x74ad9e46, 0x74a3466b, 0x7498ea11, 0x748e8938, 0x748423e0, 0x7479ba0b, + 0x746f4bb8, 0x7464d8e8, + 0x745a619b, 0x744fe5d2, 0x7445658d, 0x743ae0cc, 0x74305790, 0x7425c9da, + 0x741b37a9, 0x7410a0fe, + 0x740605d9, 0x73fb663c, 0x73f0c226, 0x73e61997, 0x73db6c91, 0x73d0bb13, + 0x73c6051f, 0x73bb4ab3, + 0x73b08bd1, 0x73a5c87a, 0x739b00ad, 0x7390346b, 0x738563b5, 0x737a8e8a, + 0x736fb4ec, 0x7364d6da, + 0x7359f456, 0x734f0d5f, 0x734421f6, 0x7339321b, 0x732e3dcf, 0x73234512, + 0x731847e5, 0x730d4648, + 0x7302403c, 0x72f735c0, 0x72ec26d6, 0x72e1137d, 0x72d5fbb7, 0x72cadf83, + 0x72bfbee3, 0x72b499d6, + 0x72a9705c, 0x729e4277, 0x72931027, 0x7287d96c, 0x727c9e47, 0x72715eb8, + 0x72661abf, 0x725ad25d, + 0x724f8593, 0x72443460, 0x7238dec5, 0x722d84c4, 0x7222265b, 0x7216c38c, + 0x720b5c57, 0x71fff0bc, + 0x71f480bc, 0x71e90c57, 0x71dd938f, 0x71d21662, 0x71c694d2, 0x71bb0edf, + 0x71af848a, 0x71a3f5d2, + 0x719862b9, 0x718ccb3f, 0x71812f65, 0x71758f29, 0x7169ea8f, 0x715e4194, + 0x7152943b, 0x7146e284, + 0x713b2c6e, 0x712f71fb, 0x7123b32b, 0x7117effe, 0x710c2875, 0x71005c90, + 0x70f48c50, 0x70e8b7b5, + 0x70dcdec0, 0x70d10171, 0x70c51fc8, 0x70b939c7, 0x70ad4f6d, 0x70a160ba, + 0x70956db1, 0x70897650, + 0x707d7a98, 0x70717a8a, 0x70657626, 0x70596d6d, 0x704d6060, 0x70414efd, + 0x70353947, 0x70291f3e, + 0x701d00e1, 0x7010de32, 0x7004b731, 0x6ff88bde, 0x6fec5c3b, 0x6fe02846, + 0x6fd3f001, 0x6fc7b36d, + 0x6fbb728a, 0x6faf2d57, 0x6fa2e3d7, 0x6f969608, 0x6f8a43ed, 0x6f7ded84, + 0x6f7192cf, 0x6f6533ce, + 0x6f58d082, 0x6f4c68eb, 0x6f3ffd09, 0x6f338cde, 0x6f271868, 0x6f1a9faa, + 0x6f0e22a3, 0x6f01a155, + 0x6ef51bbe, 0x6ee891e1, 0x6edc03bc, 0x6ecf7152, 0x6ec2daa2, 0x6eb63fad, + 0x6ea9a073, 0x6e9cfcf5, + 0x6e905534, 0x6e83a92f, 0x6e76f8e7, 0x6e6a445d, 0x6e5d8b91, 0x6e50ce84, + 0x6e440d37, 0x6e3747a9, + 0x6e2a7ddb, 0x6e1dafce, 0x6e10dd82, 0x6e0406f8, 0x6df72c30, 0x6dea4d2b, + 0x6ddd69e9, 0x6dd0826a, + 0x6dc396b0, 0x6db6a6ba, 0x6da9b28a, 0x6d9cba1f, 0x6d8fbd7a, 0x6d82bc9d, + 0x6d75b786, 0x6d68ae37, + 0x6d5ba0b0, 0x6d4e8ef2, 0x6d4178fd, 0x6d345ed1, 0x6d274070, 0x6d1a1dda, + 0x6d0cf70f, 0x6cffcc0f, + 0x6cf29cdc, 0x6ce56975, 0x6cd831dc, 0x6ccaf610, 0x6cbdb613, 0x6cb071e4, + 0x6ca32985, 0x6c95dcf6, + 0x6c888c36, 0x6c7b3748, 0x6c6dde2b, 0x6c6080e0, 0x6c531f67, 0x6c45b9c1, + 0x6c384fef, 0x6c2ae1f0, + 0x6c1d6fc6, 0x6c0ff971, 0x6c027ef1, 0x6bf50047, 0x6be77d74, 0x6bd9f677, + 0x6bcc6b53, 0x6bbedc06, + 0x6bb14892, 0x6ba3b0f7, 0x6b961536, 0x6b88754f, 0x6b7ad142, 0x6b6d2911, + 0x6b5f7cbc, 0x6b51cc42, + 0x6b4417a6, 0x6b365ee7, 0x6b28a206, 0x6b1ae103, 0x6b0d1bdf, 0x6aff529a, + 0x6af18536, 0x6ae3b3b2, + 0x6ad5de0f, 0x6ac8044e, 0x6aba266e, 0x6aac4472, 0x6a9e5e58, 0x6a907423, + 0x6a8285d1, 0x6a749365, + 0x6a669cdd, 0x6a58a23c, 0x6a4aa381, 0x6a3ca0ad, 0x6a2e99c0, 0x6a208ebb, + 0x6a127f9f, 0x6a046c6c, + 0x69f65523, 0x69e839c4, 0x69da1a50, 0x69cbf6c7, 0x69bdcf29, 0x69afa378, + 0x69a173b5, 0x69933fde, + 0x698507f6, 0x6976cbfc, 0x69688bf1, 0x695a47d6, 0x694bffab, 0x693db371, + 0x692f6328, 0x69210ed1, + 0x6912b66c, 0x690459fb, 0x68f5f97d, 0x68e794f3, 0x68d92c5d, 0x68cabfbd, + 0x68bc4f13, 0x68adda5f, + 0x689f61a1, 0x6890e4dc, 0x6882640e, 0x6873df38, 0x6865565c, 0x6856c979, + 0x68483891, 0x6839a3a4, + 0x682b0ab1, 0x681c6dbb, 0x680dccc1, 0x67ff27c4, 0x67f07ec5, 0x67e1d1c4, + 0x67d320c1, 0x67c46bbe, + 0x67b5b2bb, 0x67a6f5b8, 0x679834b6, 0x67896fb6, 0x677aa6b8, 0x676bd9bd, + 0x675d08c4, 0x674e33d0, + 0x673f5ae0, 0x67307df5, 0x67219d10, 0x6712b831, 0x6703cf58, 0x66f4e287, + 0x66e5f1be, 0x66d6fcfd, + 0x66c80445, 0x66b90797, 0x66aa06f3, 0x669b0259, 0x668bf9cb, 0x667ced49, + 0x666ddcd3, 0x665ec86b, + 0x664fb010, 0x664093c3, 0x66317385, 0x66224f56, 0x66132738, 0x6603fb2a, + 0x65f4cb2d, 0x65e59742, + 0x65d65f69, 0x65c723a3, 0x65b7e3f1, 0x65a8a052, 0x659958c9, 0x658a0d54, + 0x657abdf6, 0x656b6aae, + 0x655c137d, 0x654cb863, 0x653d5962, 0x652df679, 0x651e8faa, 0x650f24f5, + 0x64ffb65b, 0x64f043dc, + 0x64e0cd78, 0x64d15331, 0x64c1d507, 0x64b252fa, 0x64a2cd0c, 0x6493433c, + 0x6483b58c, 0x647423fb, + 0x64648e8c, 0x6454f53d, 0x64455810, 0x6435b706, 0x6426121e, 0x6416695a, + 0x6406bcba, 0x63f70c3f, + 0x63e757ea, 0x63d79fba, 0x63c7e3b1, 0x63b823cf, 0x63a86015, 0x63989884, + 0x6388cd1b, 0x6378fddc, + 0x63692ac7, 0x635953dd, 0x6349791f, 0x63399a8d, 0x6329b827, 0x6319d1ef, + 0x6309e7e4, 0x62f9fa09, + 0x62ea085c, 0x62da12df, 0x62ca1992, 0x62ba1c77, 0x62aa1b8d, 0x629a16d5, + 0x628a0e50, 0x627a01fe, + 0x6269f1e1, 0x6259ddf8, 0x6249c645, 0x6239aac7, 0x62298b81, 0x62196871, + 0x62094199, 0x61f916f9, + 0x61e8e893, 0x61d8b666, 0x61c88074, 0x61b846bc, 0x61a80940, 0x6197c800, + 0x618782fd, 0x61773a37, + 0x6166edb0, 0x61569d67, 0x6146495d, 0x6135f193, 0x6125960a, 0x611536c2, + 0x6104d3bc, 0x60f46cf9, + 0x60e40278, 0x60d3943b, 0x60c32243, 0x60b2ac8f, 0x60a23322, 0x6091b5fa, + 0x60813519, 0x6070b080, + 0x6060282f, 0x604f9c27, 0x603f0c69, 0x602e78f4, 0x601de1ca, 0x600d46ec, + 0x5ffca859, 0x5fec0613, + 0x5fdb601b, 0x5fcab670, 0x5fba0914, 0x5fa95807, 0x5f98a34a, 0x5f87eade, + 0x5f772ec2, 0x5f666ef9, + 0x5f55ab82, 0x5f44e45e, 0x5f34198e, 0x5f234b12, 0x5f1278eb, 0x5f01a31a, + 0x5ef0c99f, 0x5edfec7b, + 0x5ecf0baf, 0x5ebe273b, 0x5ead3f1f, 0x5e9c535e, 0x5e8b63f7, 0x5e7a70ea, + 0x5e697a39, 0x5e587fe5, + 0x5e4781ed, 0x5e368053, 0x5e257b17, 0x5e147239, 0x5e0365bb, 0x5df2559e, + 0x5de141e1, 0x5dd02a85, + 0x5dbf0f8c, 0x5dadf0f5, 0x5d9ccec2, 0x5d8ba8f3, 0x5d7a7f88, 0x5d695283, + 0x5d5821e4, 0x5d46edac, + 0x5d35b5db, 0x5d247a72, 0x5d133b72, 0x5d01f8dc, 0x5cf0b2af, 0x5cdf68ed, + 0x5cce1b97, 0x5cbccaac, + 0x5cab762f, 0x5c9a1e1e, 0x5c88c27c, 0x5c776348, 0x5c660084, 0x5c549a30, + 0x5c43304d, 0x5c31c2db, + 0x5c2051db, 0x5c0edd4e, 0x5bfd6534, 0x5bebe98e, 0x5bda6a5d, 0x5bc8e7a2, + 0x5bb7615d, 0x5ba5d78e, + 0x5b944a37, 0x5b82b958, 0x5b7124f2, 0x5b5f8d06, 0x5b4df193, 0x5b3c529c, + 0x5b2ab020, 0x5b190a20, + 0x5b07609d, 0x5af5b398, 0x5ae40311, 0x5ad24f09, 0x5ac09781, 0x5aaedc78, + 0x5a9d1df1, 0x5a8b5bec, + 0x5a799669, 0x5a67cd69, 0x5a5600ec, 0x5a4430f5, 0x5a325d82, 0x5a208695, + 0x5a0eac2e, 0x59fcce4f, + 0x59eaecf8, 0x59d90829, 0x59c71fe3, 0x59b53427, 0x59a344f6, 0x59915250, + 0x597f5c36, 0x596d62a9, + 0x595b65aa, 0x59496538, 0x59376155, 0x59255a02, 0x59134f3e, 0x5901410c, + 0x58ef2f6b, 0x58dd1a5d, + 0x58cb01e1, 0x58b8e5f9, 0x58a6c6a5, 0x5894a3e7, 0x58827dbe, 0x5870542c, + 0x585e2730, 0x584bf6cd, + 0x5839c302, 0x58278bd1, 0x58155139, 0x5803133c, 0x57f0d1da, 0x57de8d15, + 0x57cc44ec, 0x57b9f960, + 0x57a7aa73, 0x57955825, 0x57830276, 0x5770a968, 0x575e4cfa, 0x574bed2f, + 0x57398a05, 0x5727237f, + 0x5714b99d, 0x57024c5f, 0x56efdbc7, 0x56dd67d4, 0x56caf088, 0x56b875e4, + 0x56a5f7e7, 0x56937694, + 0x5680f1ea, 0x566e69ea, 0x565bde95, 0x56494fec, 0x5636bdef, 0x5624289f, + 0x56118ffe, 0x55fef40a, + 0x55ec54c6, 0x55d9b232, 0x55c70c4f, 0x55b4631d, 0x55a1b69d, 0x558f06d0, + 0x557c53b6, 0x55699d51, + 0x5556e3a1, 0x554426a7, 0x55316663, 0x551ea2d6, 0x550bdc01, 0x54f911e5, + 0x54e64482, 0x54d373d9, + 0x54c09feb, 0x54adc8b8, 0x549aee42, 0x54881089, 0x54752f8d, 0x54624b50, + 0x544f63d2, 0x543c7914, + 0x54298b17, 0x541699db, 0x5403a561, 0x53f0adaa, 0x53ddb2b6, 0x53cab486, + 0x53b7b31c, 0x53a4ae77, + 0x5391a699, 0x537e9b82, 0x536b8d33, 0x53587bad, 0x534566f0, 0x53324efd, + 0x531f33d5, 0x530c1579, + 0x52f8f3e9, 0x52e5cf27, 0x52d2a732, 0x52bf7c0b, 0x52ac4db4, 0x52991c2d, + 0x5285e777, 0x5272af92, + 0x525f7480, 0x524c3640, 0x5238f4d4, 0x5225b03d, 0x5212687b, 0x51ff1d8f, + 0x51ebcf7a, 0x51d87e3c, + 0x51c529d7, 0x51b1d24a, 0x519e7797, 0x518b19bf, 0x5177b8c2, 0x516454a0, + 0x5150ed5c, 0x513d82f4, + 0x512a156b, 0x5116a4c1, 0x510330f7, 0x50efba0d, 0x50dc4005, 0x50c8c2de, + 0x50b5429a, 0x50a1bf39, + 0x508e38bd, 0x507aaf25, 0x50672273, 0x505392a8, 0x503fffc4, 0x502c69c8, + 0x5018d0b4, 0x5005348a, + 0x4ff1954b, 0x4fddf2f6, 0x4fca4d8d, 0x4fb6a510, 0x4fa2f981, 0x4f8f4ae0, + 0x4f7b992d, 0x4f67e46a, + 0x4f542c98, 0x4f4071b6, 0x4f2cb3c7, 0x4f18f2c9, 0x4f052ec0, 0x4ef167aa, + 0x4edd9d89, 0x4ec9d05e, + 0x4eb60029, 0x4ea22ceb, 0x4e8e56a5, 0x4e7a7d58, 0x4e66a105, 0x4e52c1ab, + 0x4e3edf4d, 0x4e2af9ea, + 0x4e171184, 0x4e03261b, 0x4def37b0, 0x4ddb4644, 0x4dc751d8, 0x4db35a6c, + 0x4d9f6001, 0x4d8b6298, + 0x4d776231, 0x4d635ece, 0x4d4f5870, 0x4d3b4f16, 0x4d2742c2, 0x4d133374, + 0x4cff212e, 0x4ceb0bf0, + 0x4cd6f3bb, 0x4cc2d88f, 0x4caeba6e, 0x4c9a9958, 0x4c86754e, 0x4c724e50, + 0x4c5e2460, 0x4c49f77f, + 0x4c35c7ac, 0x4c2194e9, 0x4c0d5f37, 0x4bf92697, 0x4be4eb08, 0x4bd0ac8d, + 0x4bbc6b25, 0x4ba826d1, + 0x4b93df93, 0x4b7f956b, 0x4b6b485a, 0x4b56f861, 0x4b42a580, 0x4b2e4fb8, + 0x4b19f70a, 0x4b059b77, + 0x4af13d00, 0x4adcdba5, 0x4ac87767, 0x4ab41046, 0x4a9fa645, 0x4a8b3963, + 0x4a76c9a2, 0x4a625701, + 0x4a4de182, 0x4a396926, 0x4a24edee, 0x4a106fda, 0x49fbeeea, 0x49e76b21, + 0x49d2e47e, 0x49be5b02, + 0x49a9ceaf, 0x49953f84, 0x4980ad84, 0x496c18ae, 0x49578103, 0x4942e684, + 0x492e4933, 0x4919a90f, + 0x4905061a, 0x48f06054, 0x48dbb7be, 0x48c70c59, 0x48b25e25, 0x489dad25, + 0x4888f957, 0x487442be, + 0x485f8959, 0x484acd2a, 0x48360e32, 0x48214c71, 0x480c87e8, 0x47f7c099, + 0x47e2f682, 0x47ce29a7, + 0x47b95a06, 0x47a487a2, 0x478fb27b, 0x477ada91, 0x4765ffe6, 0x4751227a, + 0x473c424e, 0x47275f63, + 0x471279ba, 0x46fd9154, 0x46e8a631, 0x46d3b852, 0x46bec7b8, 0x46a9d464, + 0x4694de56, 0x467fe590, + 0x466aea12, 0x4655ebdd, 0x4640eaf2, 0x462be751, 0x4616e0fc, 0x4601d7f3, + 0x45eccc37, 0x45d7bdc9, + 0x45c2acaa, 0x45ad98da, 0x4598825a, 0x4583692c, 0x456e4d4f, 0x45592ec6, + 0x45440d90, 0x452ee9ae, + 0x4519c321, 0x450499eb, 0x44ef6e0b, 0x44da3f83, 0x44c50e53, 0x44afda7d, + 0x449aa400, 0x44856adf, + 0x44702f19, 0x445af0b0, 0x4445afa4, 0x44306bf6, 0x441b25a8, 0x4405dcb9, + 0x43f0912b, 0x43db42fe, + 0x43c5f234, 0x43b09ecc, 0x439b48c9, 0x4385f02a, 0x437094f1, 0x435b371f, + 0x4345d6b3, 0x433073b0, + 0x431b0e15, 0x4305a5e5, 0x42f03b1e, 0x42dacdc3, 0x42c55dd4, 0x42afeb53, + 0x429a763f, 0x4284fe99, + 0x426f8463, 0x425a079e, 0x42448849, 0x422f0667, 0x421981f7, 0x4203fafb, + 0x41ee7174, 0x41d8e561, + 0x41c356c5, 0x41adc5a0, 0x419831f3, 0x41829bbe, 0x416d0302, 0x415767c1, + 0x4141c9fb, 0x412c29b1, + 0x411686e4, 0x4100e194, 0x40eb39c3, 0x40d58f71, 0x40bfe29f, 0x40aa334e, + 0x4094817f, 0x407ecd32, + 0x40691669, 0x40535d24, 0x403da165, 0x4027e32b, 0x40122278, 0x3ffc5f4d, + 0x3fe699aa, 0x3fd0d191, + 0x3fbb0702, 0x3fa539fd, 0x3f8f6a85, 0x3f799899, 0x3f63c43b, 0x3f4ded6b, + 0x3f38142a, 0x3f22387a, + 0x3f0c5a5a, 0x3ef679cc, 0x3ee096d1, 0x3ecab169, 0x3eb4c995, 0x3e9edf57, + 0x3e88f2ae, 0x3e73039d, + 0x3e5d1222, 0x3e471e41, 0x3e3127f9, 0x3e1b2f4a, 0x3e053437, 0x3def36c0, + 0x3dd936e6, 0x3dc334a9, + 0x3dad300b, 0x3d97290b, 0x3d811fac, 0x3d6b13ee, 0x3d5505d2, 0x3d3ef559, + 0x3d28e282, 0x3d12cd51, + 0x3cfcb5c4, 0x3ce69bde, 0x3cd07f9f, 0x3cba6107, 0x3ca44018, 0x3c8e1cd3, + 0x3c77f737, 0x3c61cf48, + 0x3c4ba504, 0x3c35786d, 0x3c1f4983, 0x3c091849, 0x3bf2e4be, 0x3bdcaee3, + 0x3bc676b9, 0x3bb03c42, + 0x3b99ff7d, 0x3b83c06c, 0x3b6d7f10, 0x3b573b69, 0x3b40f579, 0x3b2aad3f, + 0x3b1462be, 0x3afe15f6, + 0x3ae7c6e7, 0x3ad17593, 0x3abb21fb, 0x3aa4cc1e, 0x3a8e7400, 0x3a78199f, + 0x3a61bcfd, 0x3a4b5e1b, + 0x3a34fcf9, 0x3a1e9999, 0x3a0833fc, 0x39f1cc21, 0x39db620b, 0x39c4f5ba, + 0x39ae872f, 0x3998166a, + 0x3981a36d, 0x396b2e38, 0x3954b6cd, 0x393e3d2c, 0x3927c155, 0x3911434b, + 0x38fac30e, 0x38e4409e, + 0x38cdbbfc, 0x38b7352a, 0x38a0ac29, 0x388a20f8, 0x38739399, 0x385d040d, + 0x38467255, 0x382fde72, + 0x38194864, 0x3802b02c, 0x37ec15cb, 0x37d57943, 0x37beda93, 0x37a839be, + 0x379196c3, 0x377af1a3, + 0x37644a60, 0x374da0fa, 0x3736f573, 0x372047ca, 0x37099802, 0x36f2e61a, + 0x36dc3214, 0x36c57bf0, + 0x36aec3b0, 0x36980954, 0x36814cde, 0x366a8e4d, 0x3653cda3, 0x363d0ae2, + 0x36264609, 0x360f7f19, + 0x35f8b614, 0x35e1eafa, 0x35cb1dcc, 0x35b44e8c, 0x359d7d39, 0x3586a9d5, + 0x356fd461, 0x3558fcde, + 0x3542234c, 0x352b47ad, 0x35146a00, 0x34fd8a48, 0x34e6a885, 0x34cfc4b7, + 0x34b8dee1, 0x34a1f702, + 0x348b0d1c, 0x3474212f, 0x345d333c, 0x34464345, 0x342f5149, 0x34185d4b, + 0x3401674a, 0x33ea6f48, + 0x33d37546, 0x33bc7944, 0x33a57b44, 0x338e7b46, 0x3377794b, 0x33607554, + 0x33496f62, 0x33326776, + 0x331b5d91, 0x330451b3, 0x32ed43de, 0x32d63412, 0x32bf2250, 0x32a80e99, + 0x3290f8ef, 0x3279e151, + 0x3262c7c1, 0x324bac40, 0x32348ecf, 0x321d6f6e, 0x32064e1e, 0x31ef2ae1, + 0x31d805b7, 0x31c0dea1, + 0x31a9b5a0, 0x31928ab4, 0x317b5de0, 0x31642f23, 0x314cfe7f, 0x3135cbf4, + 0x311e9783, 0x3107612e, + 0x30f028f4, 0x30d8eed8, 0x30c1b2da, 0x30aa74fa, 0x3093353a, 0x307bf39b, + 0x3064b01d, 0x304d6ac1, + 0x30362389, 0x301eda75, 0x30078f86, 0x2ff042bd, 0x2fd8f41b, 0x2fc1a3a0, + 0x2faa514f, 0x2f92fd26, + 0x2f7ba729, 0x2f644f56, 0x2f4cf5b0, 0x2f359a37, 0x2f1e3ced, 0x2f06ddd1, + 0x2eef7ce5, 0x2ed81a29, + 0x2ec0b5a0, 0x2ea94f49, 0x2e91e725, 0x2e7a7d36, 0x2e63117c, 0x2e4ba3f8, + 0x2e3434ac, 0x2e1cc397, + 0x2e0550bb, 0x2deddc19, 0x2dd665b2, 0x2dbeed86, 0x2da77397, 0x2d8ff7e5, + 0x2d787a72, 0x2d60fb3e, + 0x2d497a4a, 0x2d31f797, 0x2d1a7325, 0x2d02ecf7, 0x2ceb650d, 0x2cd3db67, + 0x2cbc5006, 0x2ca4c2ed, + 0x2c8d341a, 0x2c75a390, 0x2c5e114f, 0x2c467d58, 0x2c2ee7ad, 0x2c17504d, + 0x2bffb73a, 0x2be81c74, + 0x2bd07ffe, 0x2bb8e1d7, 0x2ba14200, 0x2b89a07b, 0x2b71fd48, 0x2b5a5868, + 0x2b42b1dd, 0x2b2b09a6, + 0x2b135fc6, 0x2afbb43c, 0x2ae4070a, 0x2acc5831, 0x2ab4a7b1, 0x2a9cf58c, + 0x2a8541c3, 0x2a6d8c55, + 0x2a55d545, 0x2a3e1c93, 0x2a266240, 0x2a0ea64d, 0x29f6e8bb, 0x29df298b, + 0x29c768be, 0x29afa654, + 0x2997e24f, 0x29801caf, 0x29685576, 0x29508ca4, 0x2938c23a, 0x2920f63a, + 0x290928a3, 0x28f15978, + 0x28d988b8, 0x28c1b666, 0x28a9e281, 0x28920d0a, 0x287a3604, 0x28625d6d, + 0x284a8349, 0x2832a796, + 0x281aca57, 0x2802eb8c, 0x27eb0b36, 0x27d32956, 0x27bb45ed, 0x27a360fc, + 0x278b7a84, 0x27739285, + 0x275ba901, 0x2743bdf9, 0x272bd16d, 0x2713e35f, 0x26fbf3ce, 0x26e402bd, + 0x26cc102d, 0x26b41c1d, + 0x269c268f, 0x26842f84, 0x266c36fe, 0x26543cfb, 0x263c417f, 0x26244489, + 0x260c461b, 0x25f44635, + 0x25dc44d9, 0x25c44207, 0x25ac3dc0, 0x25943806, 0x257c30d8, 0x25642839, + 0x254c1e28, 0x253412a8, + 0x251c05b8, 0x2503f75a, 0x24ebe78f, 0x24d3d657, 0x24bbc3b4, 0x24a3afa6, + 0x248b9a2f, 0x2473834f, + 0x245b6b07, 0x24435158, 0x242b3644, 0x241319ca, 0x23fafbec, 0x23e2dcac, + 0x23cabc09, 0x23b29a05, + 0x239a76a0, 0x238251dd, 0x236a2bba, 0x2352043b, 0x2339db5e, 0x2321b126, + 0x23098593, 0x22f158a7, + 0x22d92a61, 0x22c0fac4, 0x22a8c9cf, 0x22909785, 0x227863e5, 0x22602ef1, + 0x2247f8aa, 0x222fc111, + 0x22178826, 0x21ff4dea, 0x21e71260, 0x21ced586, 0x21b6975f, 0x219e57eb, + 0x2186172b, 0x216dd521, + 0x215591cc, 0x213d4d2f, 0x21250749, 0x210cc01d, 0x20f477aa, 0x20dc2df2, + 0x20c3e2f5, 0x20ab96b5, + 0x20934933, 0x207afa6f, 0x2062aa6b, 0x204a5927, 0x203206a4, 0x2019b2e4, + 0x20015de7, 0x1fe907ae, + 0x1fd0b03a, 0x1fb8578b, 0x1f9ffda4, 0x1f87a285, 0x1f6f462f, 0x1f56e8a2, + 0x1f3e89e0, 0x1f2629ea, + 0x1f0dc8c0, 0x1ef56664, 0x1edd02d6, 0x1ec49e17, 0x1eac3829, 0x1e93d10c, + 0x1e7b68c2, 0x1e62ff4a, + 0x1e4a94a7, 0x1e3228d9, 0x1e19bbe0, 0x1e014dbf, 0x1de8de75, 0x1dd06e04, + 0x1db7fc6d, 0x1d9f89b1, + 0x1d8715d0, 0x1d6ea0cc, 0x1d562aa6, 0x1d3db35e, 0x1d253af5, 0x1d0cc16c, + 0x1cf446c5, 0x1cdbcb00, + 0x1cc34e1f, 0x1caad021, 0x1c925109, 0x1c79d0d6, 0x1c614f8b, 0x1c48cd27, + 0x1c3049ac, 0x1c17c51b, + 0x1bff3f75, 0x1be6b8ba, 0x1bce30ec, 0x1bb5a80c, 0x1b9d1e1a, 0x1b849317, + 0x1b6c0705, 0x1b5379e5, + 0x1b3aebb6, 0x1b225c7b, 0x1b09cc34, 0x1af13ae3, 0x1ad8a887, 0x1ac01522, + 0x1aa780b6, 0x1a8eeb42, + 0x1a7654c8, 0x1a5dbd49, 0x1a4524c6, 0x1a2c8b3f, 0x1a13f0b6, 0x19fb552c, + 0x19e2b8a2, 0x19ca1b17, + 0x19b17c8f, 0x1998dd09, 0x19803c86, 0x19679b07, 0x194ef88e, 0x1936551b, + 0x191db0af, 0x19050b4b, + 0x18ec64f0, 0x18d3bda0, 0x18bb155a, 0x18a26c20, 0x1889c1f3, 0x187116d4, + 0x18586ac3, 0x183fbdc3, + 0x18270fd3, 0x180e60f4, 0x17f5b129, 0x17dd0070, 0x17c44ecd, 0x17ab9c3e, + 0x1792e8c6, 0x177a3466, + 0x17617f1d, 0x1748c8ee, 0x173011d9, 0x171759df, 0x16fea102, 0x16e5e741, + 0x16cd2c9f, 0x16b4711b, + 0x169bb4b7, 0x1682f774, 0x166a3953, 0x16517a55, 0x1638ba7a, 0x161ff9c4, + 0x16073834, 0x15ee75cb, + 0x15d5b288, 0x15bcee6f, 0x15a4297f, 0x158b63b9, 0x15729d1f, 0x1559d5b1, + 0x15410d70, 0x1528445d, + 0x150f7a7a, 0x14f6afc7, 0x14dde445, 0x14c517f4, 0x14ac4ad7, 0x14937cee, + 0x147aae3a, 0x1461debc, + 0x14490e74, 0x14303d65, 0x14176b8e, 0x13fe98f1, 0x13e5c58e, 0x13ccf167, + 0x13b41c7d, 0x139b46d0, + 0x13827062, 0x13699933, 0x1350c144, 0x1337e897, 0x131f0f2c, 0x13063505, + 0x12ed5a21, 0x12d47e83, + 0x12bba22b, 0x12a2c51b, 0x1289e752, 0x127108d2, 0x1258299c, 0x123f49b2, + 0x12266913, 0x120d87c1, + 0x11f4a5bd, 0x11dbc307, 0x11c2dfa2, 0x11a9fb8d, 0x119116c9, 0x11783159, + 0x115f4b3c, 0x11466473, + 0x112d7d00, 0x111494e4, 0x10fbac1e, 0x10e2c2b2, 0x10c9d89e, 0x10b0ede5, + 0x10980287, 0x107f1686, + 0x106629e1, 0x104d3c9b, 0x10344eb4, 0x101b602d, 0x10027107, 0xfe98143, + 0xfd090e1, 0xfb79fe4, + 0xf9eae4c, 0xf85bc19, 0xf6cc94e, 0xf53d5ea, 0xf3ae1ee, 0xf21ed5d, 0xf08f836, + 0xef0027b, + 0xed70c2c, 0xebe154b, 0xea51dd8, 0xe8c25d5, 0xe732d42, 0xe5a3421, 0xe413a72, + 0xe284036, + 0xe0f456f, 0xdf64a1c, 0xddd4e40, 0xdc451dc, 0xdab54ef, 0xd92577b, 0xd795982, + 0xd605b03, + 0xd475c00, 0xd2e5c7b, 0xd155c73, 0xcfc5bea, 0xce35ae1, 0xcca5959, 0xcb15752, + 0xc9854cf, + 0xc7f51cf, 0xc664e53, 0xc4d4a5d, 0xc3445ee, 0xc1b4107, 0xc023ba7, 0xbe935d2, + 0xbd02f87, + 0xbb728c7, 0xb9e2193, 0xb8519ed, 0xb6c11d5, 0xb53094d, 0xb3a0055, 0xb20f6ee, + 0xb07ed19, + 0xaeee2d7, 0xad5d829, 0xabccd11, 0xaa3c18e, 0xa8ab5a2, 0xa71a94f, 0xa589c94, + 0xa3f8f73, + 0xa2681ed, 0xa0d7403, 0x9f465b5, 0x9db5706, 0x9c247f5, 0x9a93884, 0x99028b3, + 0x9771884, + 0x95e07f8, 0x944f70f, 0x92be5ca, 0x912d42c, 0x8f9c233, 0x8e0afe2, 0x8c79d3a, + 0x8ae8a3a, + 0x89576e5, 0x87c633c, 0x8634f3e, 0x84a3aee, 0x831264c, 0x8181159, 0x7fefc16, + 0x7e5e685, + 0x7ccd0a5, 0x7b3ba78, 0x79aa400, 0x7818d3c, 0x768762e, 0x74f5ed7, 0x7364738, + 0x71d2f52, + 0x7041726, 0x6eafeb4, 0x6d1e5fe, 0x6b8cd05, 0x69fb3c9, 0x6869a4c, 0x66d808f, + 0x6546692, + 0x63b4c57, 0x62231de, 0x6091729, 0x5effc38, 0x5d6e10c, 0x5bdc5a7, 0x5a4aa09, + 0x58b8e34, + 0x5727228, 0x55955e6, 0x540396f, 0x5271cc4, 0x50dffe7, 0x4f4e2d8, 0x4dbc597, + 0x4c2a827, + 0x4a98a88, 0x4906cbb, 0x4774ec1, 0x45e309a, 0x4451249, 0x42bf3cd, 0x412d528, + 0x3f9b65b, + 0x3e09767, 0x3c7784d, 0x3ae590d, 0x39539a9, 0x37c1a22, 0x362fa78, 0x349daac, + 0x330bac1, + 0x3179ab5, 0x2fe7a8c, 0x2e55a44, 0x2cc39e1, 0x2b31961, 0x299f8c7, 0x280d813, + 0x267b747, + 0x24e9662, 0x2357567, 0x21c5457, 0x2033331, 0x1ea11f7, 0x1d0f0ab, 0x1b7cf4d, + 0x19eaddd, + 0x1858c5e, 0x16c6ad0, 0x1534934, 0x13a278a, 0x12105d5, 0x107e414, 0xeec249, + 0xd5a075, + 0xbc7e99, 0xa35cb5, 0x8a3acb, 0x7118dc, 0x57f6e9, 0x3ed4f2, 0x25b2f8, + 0xc90fe, + +}; + +/** + * @brief Initialization function for the Q31 DCT4/IDCT4. + * @param[in,out] *S points to an instance of Q31 DCT4/IDCT4 structure. + * @param[in] *S_RFFT points to an instance of Q31 RFFT/RIFFT structure + * @param[in] *S_CFFT points to an instance of Q31 CFFT/CIFFT structure + * @param[in] N length of the DCT4. + * @param[in] Nby2 half of the length of the DCT4. + * @param[in] normalize normalizing factor. + * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. + * \par Normalizing factor: + * The normalizing factor is sqrt(2/N), which depends on the size of transform N. + * Normalizing factors in 1.31 format are mentioned in the table below for different DCT sizes: + * \image html dct4NormalizingQ31Table.gif + */ + +arm_status arm_dct4_init_q31( + arm_dct4_instance_q31 * S, + arm_rfft_instance_q31 * S_RFFT, + arm_cfft_radix4_instance_q31 * S_CFFT, + uint16_t N, + uint16_t Nby2, + q31_t normalize) +{ + /* Initialise the default arm status */ + arm_status status = ARM_MATH_SUCCESS; + + /* Initializing the pointer array with the weight table base addresses of different lengths */ + q31_t *twiddlePtr[3] = { (q31_t *) WeightsQ31_128, (q31_t *) WeightsQ31_512, + (q31_t *) WeightsQ31_2048 + }; + + /* Initializing the pointer array with the cos factor table base addresses of different lengths */ + q31_t *pCosFactor[3] = + { (q31_t *) cos_factorsQ31_128, (q31_t *) cos_factorsQ31_512, + (q31_t *) cos_factorsQ31_2048 + }; + + /* Initialize the DCT4 length */ + S->N = N; + + /* Initialize the half of DCT4 length */ + S->Nby2 = Nby2; + + /* Initialize the DCT4 Normalizing factor */ + S->normalize = normalize; + + /* Initialize Real FFT Instance */ + S->pRfft = S_RFFT; + + /* Initialize Complex FFT Instance */ + S->pCfft = S_CFFT; + + switch (N) + { + /* Initialize the table modifier values */ + case 2048u: + S->pTwiddle = twiddlePtr[2]; + S->pCosFactor = pCosFactor[2]; + break; + case 512u: + S->pTwiddle = twiddlePtr[1]; + S->pCosFactor = pCosFactor[1]; + break; + case 128u: + S->pTwiddle = twiddlePtr[0]; + S->pCosFactor = pCosFactor[0]; + break; + default: + status = ARM_MATH_ARGUMENT_ERROR; + } + + /* Initialize the RFFT/RIFFT Function */ + arm_rfft_init_q31(S->pRfft, S->pCfft, S->N, 0, 1); + + /* return the status of DCT4 Init function */ + return (status); +} + +/** + * @} end of DCT4_IDCT4 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_q15.c index 77bce95e6..75199b452 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_q15.c @@ -1,383 +1,383 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_q15.c -* -* Description: Processing function of DCT4 & IDCT4 Q15. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/** - * @brief Processing function for the Q15 DCT4/IDCT4. - * @param[in] *S points to an instance of the Q15 DCT4 structure. - * @param[in] *pState points to state buffer. - * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. - * @return none. - * - * \par Input an output formats: - * Internally inputs are downscaled in the RFFT process function to avoid overflows. - * Number of bits downscaled, depends on the size of the transform. - * The input and output formats for different DCT sizes and number of bits to upscale are mentioned in the table below: - * - * \image html dct4FormatsQ15Table.gif - */ - -void arm_dct4_q15( - const arm_dct4_instance_q15 * S, - q15_t * pState, - q15_t * pInlineBuffer) -{ - uint32_t i; /* Loop counter */ - q15_t *weights = S->pTwiddle; /* Pointer to the Weights table */ - q15_t *cosFact = S->pCosFactor; /* Pointer to the cos factors table */ - q15_t *pS1, *pS2, *pbuff; /* Temporary pointers for input buffer and pState buffer */ - q15_t in; /* Temporary variable */ - - - /* DCT4 computation involves DCT2 (which is calculated using RFFT) - * along with some pre-processing and post-processing. - * Computational procedure is explained as follows: - * (a) Pre-processing involves multiplying input with cos factor, - * r(n) = 2 * u(n) * cos(pi*(2*n+1)/(4*n)) - * where, - * r(n) -- output of preprocessing - * u(n) -- input to preprocessing(actual Source buffer) - * (b) Calculation of DCT2 using FFT is divided into three steps: - * Step1: Re-ordering of even and odd elements of input. - * Step2: Calculating FFT of the re-ordered input. - * Step3: Taking the real part of the product of FFT output and weights. - * (c) Post-processing - DCT4 can be obtained from DCT2 output using the following equation: - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * where, - * Y4 -- DCT4 output, Y2 -- DCT2 output - * (d) Multiplying the output with the normalizing factor sqrt(2/N). - */ - - /*-------- Pre-processing ------------*/ - /* Multiplying input with cos factor i.e. r(n) = 2 * x(n) * cos(pi*(2*n+1)/(4*n)) */ - arm_mult_q15(pInlineBuffer, cosFact, pInlineBuffer, S->N); - arm_shift_q15(pInlineBuffer, 1, pInlineBuffer, S->N); - - /* ---------------------------------------------------------------- - * Step1: Re-ordering of even and odd elements as - * pState[i] = pInlineBuffer[2*i] and - * pState[N-i-1] = pInlineBuffer[2*i+1] where i = 0 to N/2 - ---------------------------------------------------------------------*/ - - /* pS1 initialized to pState */ - pS1 = pState; - - /* pS2 initialized to pState+N-1, so that it points to the end of the state buffer */ - pS2 = pState + (S->N - 1u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Initializing the loop counter to N/2 >> 2 for loop unrolling by 4 */ - i = (uint32_t) S->Nby2 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = (uint32_t) S->N >> 2u; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. - * Compute 4 outputs at a time */ - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_q15(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_q15(pState, weights, pState, S->N); - - /* The output of complex multiplication is in 3.13 format. - * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.15 format by shifting left by 2 bits. */ - arm_shift_q15(pState, 2, pState, S->N * 2); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* Initializing the loop counter to N >> 2 for loop unrolling by 4 */ - i = ((uint32_t) S->N - 1u) >> 2u; - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ >> 1u; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - i = ((uint32_t) S->N - 1u) % 0x4u; - - while(i > 0u) - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - /* Decrement the loop counter */ - i--; - } - - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = (uint32_t) S->N >> 2u; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. Compute 4 outputs at a time */ - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); - - in = *pbuff; - *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); - - in = *pbuff; - *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); - - in = *pbuff; - *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initializing the loop counter to N/2 */ - i = (uint32_t) S->Nby2; - - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter */ - i = (uint32_t) S->N; - - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_q15(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_q15(pState, weights, pState, S->N); - - /* The output of complex multiplication is in 3.13 format. - * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.15 format by shifting left by 2 bits. */ - arm_shift_q15(pState, 2, pState, S->N * 2); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* Initializing the loop counter */ - i = ((uint32_t) S->N - 1u); - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ >> 1u; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - do - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter */ - i = (uint32_t) S->N; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of DCT4_IDCT4 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_dct4_q15.c +* +* Description: Processing function of DCT4 & IDCT4 Q15. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @addtogroup DCT4_IDCT4 + * @{ + */ + +/** + * @brief Processing function for the Q15 DCT4/IDCT4. + * @param[in] *S points to an instance of the Q15 DCT4 structure. + * @param[in] *pState points to state buffer. + * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. + * @return none. + * + * \par Input an output formats: + * Internally inputs are downscaled in the RFFT process function to avoid overflows. + * Number of bits downscaled, depends on the size of the transform. + * The input and output formats for different DCT sizes and number of bits to upscale are mentioned in the table below: + * + * \image html dct4FormatsQ15Table.gif + */ + +void arm_dct4_q15( + const arm_dct4_instance_q15 * S, + q15_t * pState, + q15_t * pInlineBuffer) +{ + uint32_t i; /* Loop counter */ + q15_t *weights = S->pTwiddle; /* Pointer to the Weights table */ + q15_t *cosFact = S->pCosFactor; /* Pointer to the cos factors table */ + q15_t *pS1, *pS2, *pbuff; /* Temporary pointers for input buffer and pState buffer */ + q15_t in; /* Temporary variable */ + + + /* DCT4 computation involves DCT2 (which is calculated using RFFT) + * along with some pre-processing and post-processing. + * Computational procedure is explained as follows: + * (a) Pre-processing involves multiplying input with cos factor, + * r(n) = 2 * u(n) * cos(pi*(2*n+1)/(4*n)) + * where, + * r(n) -- output of preprocessing + * u(n) -- input to preprocessing(actual Source buffer) + * (b) Calculation of DCT2 using FFT is divided into three steps: + * Step1: Re-ordering of even and odd elements of input. + * Step2: Calculating FFT of the re-ordered input. + * Step3: Taking the real part of the product of FFT output and weights. + * (c) Post-processing - DCT4 can be obtained from DCT2 output using the following equation: + * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) + * where, + * Y4 -- DCT4 output, Y2 -- DCT2 output + * (d) Multiplying the output with the normalizing factor sqrt(2/N). + */ + + /*-------- Pre-processing ------------*/ + /* Multiplying input with cos factor i.e. r(n) = 2 * x(n) * cos(pi*(2*n+1)/(4*n)) */ + arm_mult_q15(pInlineBuffer, cosFact, pInlineBuffer, S->N); + arm_shift_q15(pInlineBuffer, 1, pInlineBuffer, S->N); + + /* ---------------------------------------------------------------- + * Step1: Re-ordering of even and odd elements as + * pState[i] = pInlineBuffer[2*i] and + * pState[N-i-1] = pInlineBuffer[2*i+1] where i = 0 to N/2 + ---------------------------------------------------------------------*/ + + /* pS1 initialized to pState */ + pS1 = pState; + + /* pS2 initialized to pState+N-1, so that it points to the end of the state buffer */ + pS2 = pState + (S->N - 1u); + + /* pbuff initialized to input buffer */ + pbuff = pInlineBuffer; + + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Initializing the loop counter to N/2 >> 2 for loop unrolling by 4 */ + i = (uint32_t) S->Nby2 >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + do + { + /* Re-ordering of even and odd elements */ + /* pState[i] = pInlineBuffer[2*i] */ + *pS1++ = *pbuff++; + /* pState[N-i-1] = pInlineBuffer[2*i+1] */ + *pS2-- = *pbuff++; + + *pS1++ = *pbuff++; + *pS2-- = *pbuff++; + + *pS1++ = *pbuff++; + *pS2-- = *pbuff++; + + *pS1++ = *pbuff++; + *pS2-- = *pbuff++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + /* pbuff initialized to input buffer */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Initializing the loop counter to N/4 instead of N for loop unrolling */ + i = (uint32_t) S->N >> 2u; + + /* Processing with loop unrolling 4 times as N is always multiple of 4. + * Compute 4 outputs at a time */ + do + { + /* Writing the re-ordered output back to inplace input buffer */ + *pbuff++ = *pS1++; + *pbuff++ = *pS1++; + *pbuff++ = *pS1++; + *pbuff++ = *pS1++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + + /* --------------------------------------------------------- + * Step2: Calculate RFFT for N-point input + * ---------------------------------------------------------- */ + /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ + arm_rfft_q15(S->pRfft, pInlineBuffer, pState); + + /*---------------------------------------------------------------------- + * Step3: Multiply the FFT output with the weights. + *----------------------------------------------------------------------*/ + arm_cmplx_mult_cmplx_q15(pState, weights, pState, S->N); + + /* The output of complex multiplication is in 3.13 format. + * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.15 format by shifting left by 2 bits. */ + arm_shift_q15(pState, 2, pState, S->N * 2); + + /* ----------- Post-processing ---------- */ + /* DCT-IV can be obtained from DCT-II by the equation, + * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) + * Hence, Y4(0) = Y2(0)/2 */ + /* Getting only real part from the output and Converting to DCT-IV */ + + /* Initializing the loop counter to N >> 2 for loop unrolling by 4 */ + i = ((uint32_t) S->N - 1u) >> 2u; + + /* pbuff initialized to input buffer. */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ + in = *pS1++ >> 1u; + /* input buffer acts as inplace, so output values are stored in the input itself. */ + *pbuff++ = in; + + /* pState pointer is incremented twice as the real values are located alternatively in the array */ + pS1++; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + do + { + /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ + /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ + in = *pS1++ - in; + *pbuff++ = in; + /* points to the next real value */ + pS1++; + + in = *pS1++ - in; + *pbuff++ = in; + pS1++; + + in = *pS1++ - in; + *pbuff++ = in; + pS1++; + + in = *pS1++ - in; + *pbuff++ = in; + pS1++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + i = ((uint32_t) S->N - 1u) % 0x4u; + + while(i > 0u) + { + /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ + /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ + in = *pS1++ - in; + *pbuff++ = in; + /* points to the next real value */ + pS1++; + + /* Decrement the loop counter */ + i--; + } + + + /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ + + /* Initializing the loop counter to N/4 instead of N for loop unrolling */ + i = (uint32_t) S->N >> 2u; + + /* pbuff initialized to the pInlineBuffer(now contains the output values) */ + pbuff = pInlineBuffer; + + /* Processing with loop unrolling 4 times as N is always multiple of 4. Compute 4 outputs at a time */ + do + { + /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ + in = *pbuff; + *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); + + in = *pbuff; + *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); + + in = *pbuff; + *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); + + in = *pbuff; + *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initializing the loop counter to N/2 */ + i = (uint32_t) S->Nby2; + + do + { + /* Re-ordering of even and odd elements */ + /* pState[i] = pInlineBuffer[2*i] */ + *pS1++ = *pbuff++; + /* pState[N-i-1] = pInlineBuffer[2*i+1] */ + *pS2-- = *pbuff++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + /* pbuff initialized to input buffer */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Initializing the loop counter */ + i = (uint32_t) S->N; + + do + { + /* Writing the re-ordered output back to inplace input buffer */ + *pbuff++ = *pS1++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + + /* --------------------------------------------------------- + * Step2: Calculate RFFT for N-point input + * ---------------------------------------------------------- */ + /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ + arm_rfft_q15(S->pRfft, pInlineBuffer, pState); + + /*---------------------------------------------------------------------- + * Step3: Multiply the FFT output with the weights. + *----------------------------------------------------------------------*/ + arm_cmplx_mult_cmplx_q15(pState, weights, pState, S->N); + + /* The output of complex multiplication is in 3.13 format. + * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.15 format by shifting left by 2 bits. */ + arm_shift_q15(pState, 2, pState, S->N * 2); + + /* ----------- Post-processing ---------- */ + /* DCT-IV can be obtained from DCT-II by the equation, + * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) + * Hence, Y4(0) = Y2(0)/2 */ + /* Getting only real part from the output and Converting to DCT-IV */ + + /* Initializing the loop counter */ + i = ((uint32_t) S->N - 1u); + + /* pbuff initialized to input buffer. */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ + in = *pS1++ >> 1u; + /* input buffer acts as inplace, so output values are stored in the input itself. */ + *pbuff++ = in; + + /* pState pointer is incremented twice as the real values are located alternatively in the array */ + pS1++; + + do + { + /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ + /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ + in = *pS1++ - in; + *pbuff++ = in; + /* points to the next real value */ + pS1++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ + + /* Initializing the loop counter */ + i = (uint32_t) S->N; + + /* pbuff initialized to the pInlineBuffer(now contains the output values) */ + pbuff = pInlineBuffer; + + do + { + /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ + in = *pbuff; + *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of DCT4_IDCT4 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_q31.c index f949d5ff4..1f2c8ce43 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_dct4_q31.c @@ -1,384 +1,384 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_q31.c -* -* Description: Processing function of DCT4 & IDCT4 Q31. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/** - * @brief Processing function for the Q31 DCT4/IDCT4. - * @param[in] *S points to an instance of the Q31 DCT4 structure. - * @param[in] *pState points to state buffer. - * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. - * @return none. - * \par Input an output formats: - * Input samples need to be downscaled by 1 bit to avoid saturations in the Q31 DCT process, - * as the conversion from DCT2 to DCT4 involves one subtraction. - * Internally inputs are downscaled in the RFFT process function to avoid overflows. - * Number of bits downscaled, depends on the size of the transform. - * The input and output formats for different DCT sizes and number of bits to upscale are mentioned in the table below: - * - * \image html dct4FormatsQ31Table.gif - */ - -void arm_dct4_q31( - const arm_dct4_instance_q31 * S, - q31_t * pState, - q31_t * pInlineBuffer) -{ - uint16_t i; /* Loop counter */ - q31_t *weights = S->pTwiddle; /* Pointer to the Weights table */ - q31_t *cosFact = S->pCosFactor; /* Pointer to the cos factors table */ - q31_t *pS1, *pS2, *pbuff; /* Temporary pointers for input buffer and pState buffer */ - q31_t in; /* Temporary variable */ - - - /* DCT4 computation involves DCT2 (which is calculated using RFFT) - * along with some pre-processing and post-processing. - * Computational procedure is explained as follows: - * (a) Pre-processing involves multiplying input with cos factor, - * r(n) = 2 * u(n) * cos(pi*(2*n+1)/(4*n)) - * where, - * r(n) -- output of preprocessing - * u(n) -- input to preprocessing(actual Source buffer) - * (b) Calculation of DCT2 using FFT is divided into three steps: - * Step1: Re-ordering of even and odd elements of input. - * Step2: Calculating FFT of the re-ordered input. - * Step3: Taking the real part of the product of FFT output and weights. - * (c) Post-processing - DCT4 can be obtained from DCT2 output using the following equation: - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * where, - * Y4 -- DCT4 output, Y2 -- DCT2 output - * (d) Multiplying the output with the normalizing factor sqrt(2/N). - */ - - /*-------- Pre-processing ------------*/ - /* Multiplying input with cos factor i.e. r(n) = 2 * x(n) * cos(pi*(2*n+1)/(4*n)) */ - arm_mult_q31(pInlineBuffer, cosFact, pInlineBuffer, S->N); - arm_shift_q31(pInlineBuffer, 1, pInlineBuffer, S->N); - - /* ---------------------------------------------------------------- - * Step1: Re-ordering of even and odd elements as - * pState[i] = pInlineBuffer[2*i] and - * pState[N-i-1] = pInlineBuffer[2*i+1] where i = 0 to N/2 - ---------------------------------------------------------------------*/ - - /* pS1 initialized to pState */ - pS1 = pState; - - /* pS2 initialized to pState+N-1, so that it points to the end of the state buffer */ - pS2 = pState + (S->N - 1u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Initializing the loop counter to N/2 >> 2 for loop unrolling by 4 */ - i = S->Nby2 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = S->N >> 2u; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. - * Compute 4 outputs at a time */ - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_q31(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_q31(pState, weights, pState, S->N); - - /* The output of complex multiplication is in 3.29 format. - * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.31 format by shifting left by 2 bits. */ - arm_shift_q31(pState, 2, pState, S->N * 2); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* Initializing the loop counter to N >> 2 for loop unrolling by 4 */ - i = (S->N - 1u) >> 2u; - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ >> 1u; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - i = (S->N - 1u) % 0x4u; - - while(i > 0u) - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - /* Decrement the loop counter */ - i--; - } - - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = S->N >> 2u; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. Compute 4 outputs at a time */ - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); - - in = *pbuff; - *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); - - in = *pbuff; - *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); - - in = *pbuff; - *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initializing the loop counter to N/2 */ - i = S->Nby2; - - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter */ - i = S->N; - - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_q31(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_q31(pState, weights, pState, S->N); - - /* The output of complex multiplication is in 3.29 format. - * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.31 format by shifting left by 2 bits. */ - arm_shift_q31(pState, 2, pState, S->N * 2); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ >> 1u; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - /* Initializing the loop counter */ - i = (S->N - 1u); - - while(i > 0u) - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - /* Decrement the loop counter */ - i--; - } - - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter */ - i = S->N; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of DCT4_IDCT4 group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_dct4_q31.c +* +* Description: Processing function of DCT4 & IDCT4 Q31. +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @addtogroup DCT4_IDCT4 + * @{ + */ + +/** + * @brief Processing function for the Q31 DCT4/IDCT4. + * @param[in] *S points to an instance of the Q31 DCT4 structure. + * @param[in] *pState points to state buffer. + * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. + * @return none. + * \par Input an output formats: + * Input samples need to be downscaled by 1 bit to avoid saturations in the Q31 DCT process, + * as the conversion from DCT2 to DCT4 involves one subtraction. + * Internally inputs are downscaled in the RFFT process function to avoid overflows. + * Number of bits downscaled, depends on the size of the transform. + * The input and output formats for different DCT sizes and number of bits to upscale are mentioned in the table below: + * + * \image html dct4FormatsQ31Table.gif + */ + +void arm_dct4_q31( + const arm_dct4_instance_q31 * S, + q31_t * pState, + q31_t * pInlineBuffer) +{ + uint16_t i; /* Loop counter */ + q31_t *weights = S->pTwiddle; /* Pointer to the Weights table */ + q31_t *cosFact = S->pCosFactor; /* Pointer to the cos factors table */ + q31_t *pS1, *pS2, *pbuff; /* Temporary pointers for input buffer and pState buffer */ + q31_t in; /* Temporary variable */ + + + /* DCT4 computation involves DCT2 (which is calculated using RFFT) + * along with some pre-processing and post-processing. + * Computational procedure is explained as follows: + * (a) Pre-processing involves multiplying input with cos factor, + * r(n) = 2 * u(n) * cos(pi*(2*n+1)/(4*n)) + * where, + * r(n) -- output of preprocessing + * u(n) -- input to preprocessing(actual Source buffer) + * (b) Calculation of DCT2 using FFT is divided into three steps: + * Step1: Re-ordering of even and odd elements of input. + * Step2: Calculating FFT of the re-ordered input. + * Step3: Taking the real part of the product of FFT output and weights. + * (c) Post-processing - DCT4 can be obtained from DCT2 output using the following equation: + * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) + * where, + * Y4 -- DCT4 output, Y2 -- DCT2 output + * (d) Multiplying the output with the normalizing factor sqrt(2/N). + */ + + /*-------- Pre-processing ------------*/ + /* Multiplying input with cos factor i.e. r(n) = 2 * x(n) * cos(pi*(2*n+1)/(4*n)) */ + arm_mult_q31(pInlineBuffer, cosFact, pInlineBuffer, S->N); + arm_shift_q31(pInlineBuffer, 1, pInlineBuffer, S->N); + + /* ---------------------------------------------------------------- + * Step1: Re-ordering of even and odd elements as + * pState[i] = pInlineBuffer[2*i] and + * pState[N-i-1] = pInlineBuffer[2*i+1] where i = 0 to N/2 + ---------------------------------------------------------------------*/ + + /* pS1 initialized to pState */ + pS1 = pState; + + /* pS2 initialized to pState+N-1, so that it points to the end of the state buffer */ + pS2 = pState + (S->N - 1u); + + /* pbuff initialized to input buffer */ + pbuff = pInlineBuffer; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + /* Initializing the loop counter to N/2 >> 2 for loop unrolling by 4 */ + i = S->Nby2 >> 2u; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + do + { + /* Re-ordering of even and odd elements */ + /* pState[i] = pInlineBuffer[2*i] */ + *pS1++ = *pbuff++; + /* pState[N-i-1] = pInlineBuffer[2*i+1] */ + *pS2-- = *pbuff++; + + *pS1++ = *pbuff++; + *pS2-- = *pbuff++; + + *pS1++ = *pbuff++; + *pS2-- = *pbuff++; + + *pS1++ = *pbuff++; + *pS2-- = *pbuff++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + /* pbuff initialized to input buffer */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Initializing the loop counter to N/4 instead of N for loop unrolling */ + i = S->N >> 2u; + + /* Processing with loop unrolling 4 times as N is always multiple of 4. + * Compute 4 outputs at a time */ + do + { + /* Writing the re-ordered output back to inplace input buffer */ + *pbuff++ = *pS1++; + *pbuff++ = *pS1++; + *pbuff++ = *pS1++; + *pbuff++ = *pS1++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + + /* --------------------------------------------------------- + * Step2: Calculate RFFT for N-point input + * ---------------------------------------------------------- */ + /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ + arm_rfft_q31(S->pRfft, pInlineBuffer, pState); + + /*---------------------------------------------------------------------- + * Step3: Multiply the FFT output with the weights. + *----------------------------------------------------------------------*/ + arm_cmplx_mult_cmplx_q31(pState, weights, pState, S->N); + + /* The output of complex multiplication is in 3.29 format. + * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.31 format by shifting left by 2 bits. */ + arm_shift_q31(pState, 2, pState, S->N * 2); + + /* ----------- Post-processing ---------- */ + /* DCT-IV can be obtained from DCT-II by the equation, + * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) + * Hence, Y4(0) = Y2(0)/2 */ + /* Getting only real part from the output and Converting to DCT-IV */ + + /* Initializing the loop counter to N >> 2 for loop unrolling by 4 */ + i = (S->N - 1u) >> 2u; + + /* pbuff initialized to input buffer. */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ + in = *pS1++ >> 1u; + /* input buffer acts as inplace, so output values are stored in the input itself. */ + *pbuff++ = in; + + /* pState pointer is incremented twice as the real values are located alternatively in the array */ + pS1++; + + /* First part of the processing with loop unrolling. Compute 4 outputs at a time. + ** a second loop below computes the remaining 1 to 3 samples. */ + do + { + /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ + /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ + in = *pS1++ - in; + *pbuff++ = in; + /* points to the next real value */ + pS1++; + + in = *pS1++ - in; + *pbuff++ = in; + pS1++; + + in = *pS1++ - in; + *pbuff++ = in; + pS1++; + + in = *pS1++ - in; + *pbuff++ = in; + pS1++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + /* If the blockSize is not a multiple of 4, compute any remaining output samples here. + ** No loop unrolling is used. */ + i = (S->N - 1u) % 0x4u; + + while(i > 0u) + { + /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ + /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ + in = *pS1++ - in; + *pbuff++ = in; + /* points to the next real value */ + pS1++; + + /* Decrement the loop counter */ + i--; + } + + + /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ + + /* Initializing the loop counter to N/4 instead of N for loop unrolling */ + i = S->N >> 2u; + + /* pbuff initialized to the pInlineBuffer(now contains the output values) */ + pbuff = pInlineBuffer; + + /* Processing with loop unrolling 4 times as N is always multiple of 4. Compute 4 outputs at a time */ + do + { + /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ + in = *pbuff; + *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); + + in = *pbuff; + *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); + + in = *pbuff; + *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); + + in = *pbuff; + *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + +#else + + /* Run the below code for Cortex-M0 */ + + /* Initializing the loop counter to N/2 */ + i = S->Nby2; + + do + { + /* Re-ordering of even and odd elements */ + /* pState[i] = pInlineBuffer[2*i] */ + *pS1++ = *pbuff++; + /* pState[N-i-1] = pInlineBuffer[2*i+1] */ + *pS2-- = *pbuff++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + /* pbuff initialized to input buffer */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Initializing the loop counter */ + i = S->N; + + do + { + /* Writing the re-ordered output back to inplace input buffer */ + *pbuff++ = *pS1++; + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + + + /* --------------------------------------------------------- + * Step2: Calculate RFFT for N-point input + * ---------------------------------------------------------- */ + /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ + arm_rfft_q31(S->pRfft, pInlineBuffer, pState); + + /*---------------------------------------------------------------------- + * Step3: Multiply the FFT output with the weights. + *----------------------------------------------------------------------*/ + arm_cmplx_mult_cmplx_q31(pState, weights, pState, S->N); + + /* The output of complex multiplication is in 3.29 format. + * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.31 format by shifting left by 2 bits. */ + arm_shift_q31(pState, 2, pState, S->N * 2); + + /* ----------- Post-processing ---------- */ + /* DCT-IV can be obtained from DCT-II by the equation, + * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) + * Hence, Y4(0) = Y2(0)/2 */ + /* Getting only real part from the output and Converting to DCT-IV */ + + /* pbuff initialized to input buffer. */ + pbuff = pInlineBuffer; + + /* pS1 initialized to pState */ + pS1 = pState; + + /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ + in = *pS1++ >> 1u; + /* input buffer acts as inplace, so output values are stored in the input itself. */ + *pbuff++ = in; + + /* pState pointer is incremented twice as the real values are located alternatively in the array */ + pS1++; + + /* Initializing the loop counter */ + i = (S->N - 1u); + + while(i > 0u) + { + /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ + /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ + in = *pS1++ - in; + *pbuff++ = in; + /* points to the next real value */ + pS1++; + + /* Decrement the loop counter */ + i--; + } + + + /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ + + /* Initializing the loop counter */ + i = S->N; + + /* pbuff initialized to the pInlineBuffer(now contains the output values) */ + pbuff = pInlineBuffer; + + do + { + /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ + in = *pbuff; + *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); + + /* Decrement the loop counter */ + i--; + } while(i > 0u); + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + +/** + * @} end of DCT4_IDCT4 group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_f32.c index dd91aacc3..c3c2f7697 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_f32.c @@ -1,383 +1,383 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_f32.c -* -* Description: RFFT & RIFFT Floating point process function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @defgroup RFFT_RIFFT Real FFT Functions - * - * \par - * Complex FFT/IFFT typically assumes complex input and output. However many applications use real valued data in time domain. - * Real FFT/IFFT efficiently process real valued sequences with the advantage of requirement of low memory and with less complexity. - * - * \par - * This set of functions implements Real Fast Fourier Transforms(RFFT) and Real Inverse Fast Fourier Transform(RIFFT) - * for Q15, Q31, and floating-point data types. - * - * - * \par Algorithm: - * - * Real Fast Fourier Transform: - * \par - * Real FFT of N-point is calculated using CFFT of N/2-point and Split RFFT process as shown below figure. - * \par - * \image html RFFT.gif "Real Fast Fourier Transform" - * \par - * The RFFT functions operate on blocks of input and output data and each call to the function processes - * fftLenR samples through the transform. pSrc points to input array containing fftLenR values. - * pDst points to output array containing 2*fftLenR values. \n - * Input for real FFT is in the order of - *
{real[0], real[1], real[2], real[3], ..}
- * Output for real FFT is complex and are in the order of - *
{real(0), imag(0), real(1), imag(1), ...}
- * - * Real Inverse Fast Fourier Transform: - * \par - * Real IFFT of N-point is calculated using Split RIFFT process and CFFT of N/2-point as shown below figure. - * \par - * \image html RIFFT.gif "Real Inverse Fast Fourier Transform" - * \par - * The RIFFT functions operate on blocks of input and output data and each call to the function processes - * 2*fftLenR samples through the transform. pSrc points to input array containing 2*fftLenR values. - * pDst points to output array containing fftLenR values. \n - * Input for real IFFT is complex and are in the order of - *
{real(0), imag(0), real(1), imag(1), ...}
- * Output for real IFFT is real and in the order of - *
{real[0], real[1], real[2], real[3], ..}
- * - * \par Lengths supported by the transform: - * \par - * Real FFT/IFFT supports the lengths [128, 512, 2048], as it internally uses CFFT/CIFFT. - * - * \par Instance Structure - * A separate instance structure must be defined for each Instance but the twiddle factors can be reused. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Initializes twiddle factor tables. - * - Initializes CFFT data structure fields. - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Manually initialize the instance structure as follows: - *
   
- *arm_rfft_instance_f32 S = {fftLenReal, fftLenBy2, ifftFlagR, bitReverseFlagR, twidCoefRModifier, pTwiddleAReal, pTwiddleBReal, pCfft};   
- *arm_rfft_instance_q31 S = {fftLenReal, fftLenBy2, ifftFlagR, bitReverseFlagR, twidCoefRModifier, pTwiddleAReal, pTwiddleBReal, pCfft};   
- *arm_rfft_instance_q15 S = {fftLenReal, fftLenBy2, ifftFlagR, bitReverseFlagR, twidCoefRModifier, pTwiddleAReal, pTwiddleBReal, pCfft};   
- * 
- * where fftLenReal length of RFFT/RIFFT; fftLenBy2 length of CFFT/CIFFT. - * ifftFlagR Flag for selection of RFFT or RIFFT(Set ifftFlagR to calculate RIFFT otherwise calculates RFFT); - * bitReverseFlagR Flag for selection of output order(Set bitReverseFlagR to output in normal order otherwise output in bit reversed order); - * twidCoefRModifier modifier for twiddle factor table which supports 128, 512, 2048 RFFT lengths with same table; - * pTwiddleARealpoints to A array of twiddle coefficients; pTwiddleBRealpoints to B array of twiddle coefficients; - * pCfft points to the CFFT Instance structure. The CFFT structure also needs to be initialized, refer to arm_cfft_radix4_f32() for details regarding - * static initialization of cfft structure. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the RFFT/RIFFT function. - * Refer to the function specific documentation below for usage guidelines. - */ - -/*-------------------------------------------------------------------- - * Internal functions prototypes - *--------------------------------------------------------------------*/ - -void arm_split_rfft_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pATable, - float32_t * pBTable, - float32_t * pDst, - uint32_t modifier); -void arm_split_rifft_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pATable, - float32_t * pBTable, - float32_t * pDst, - uint32_t modifier); - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - -/** - * @brief Processing function for the floating-point RFFT/RIFFT. - * @param[in] *S points to an instance of the floating-point RFFT/RIFFT structure. - * @param[in] *pSrc points to the input buffer. - * @param[out] *pDst points to the output buffer. - * @return none. - */ - -void arm_rfft_f32( - const arm_rfft_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst) -{ - const arm_cfft_radix4_instance_f32 *S_CFFT = S->pCfft; - - - /* Calculation of Real IFFT of input */ - if(S->ifftFlagR == 1u) - { - /* Real IFFT core process */ - arm_split_rifft_f32(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - - - /* Complex radix-4 IFFT process */ - arm_radix4_butterfly_inverse_f32(pDst, S_CFFT->fftLen, - S_CFFT->pTwiddle, - S_CFFT->twidCoefModifier, - S_CFFT->onebyfftLen); - - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_f32(pDst, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - } - else - { - - /* Calculation of RFFT of input */ - - /* Complex radix-4 FFT process */ - arm_radix4_butterfly_f32(pSrc, S_CFFT->fftLen, - S_CFFT->pTwiddle, S_CFFT->twidCoefModifier); - - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_f32(pSrc, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - - - /* Real FFT core process */ - arm_split_rfft_f32(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - } - -} - -/** - * @} end of RFFT_RIFFT group - */ - -/** - * @brief Core Real FFT process - * @param[in] *pSrc points to the input buffer. - * @param[in] fftLen length of FFT. - * @param[in] *pATable points to the twiddle Coef A buffer. - * @param[in] *pBTable points to the twiddle Coef B buffer. - * @param[out] *pDst points to the output buffer. - * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_split_rfft_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pATable, - float32_t * pBTable, - float32_t * pDst, - uint32_t modifier) -{ - uint32_t i; /* Loop Counter */ - float32_t outR, outI; /* Temporary variables for output */ - float32_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - float32_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ - float32_t *pDst1 = &pDst[2], *pDst2 = &pDst[(4u * fftLen) - 1u]; /* temp pointers for output buffer */ - float32_t *pSrc1 = &pSrc[2], *pSrc2 = &pSrc[(2u * fftLen) - 1u]; /* temp pointers for input buffer */ - - - pSrc[2u * fftLen] = pSrc[0]; - pSrc[(2u * fftLen) + 1u] = pSrc[1]; - - /* Init coefficient pointers */ - pCoefA = &pATable[modifier * 2u]; - pCoefB = &pBTable[modifier * 2u]; - - i = fftLen - 1u; - - while(i > 0u) - { - /* - outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] - + pSrc[2 * n - 2 * i] * pBTable[2 * i] + - pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - */ - - /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); */ - - /* read pATable[2 * i] */ - CoefA1 = *pCoefA++; - /* pATable[2 * i + 1] */ - CoefA2 = *pCoefA; - - /* pSrc[2 * i] * pATable[2 * i] */ - outR = *pSrc1 * CoefA1; - /* pSrc[2 * i] * CoefA2 */ - outI = *pSrc1++ * CoefA2; - - /* (pSrc[2 * i + 1] + pSrc[2 * fftLen - 2 * i + 1]) * CoefA2 */ - outR -= (*pSrc1 + *pSrc2) * CoefA2; - /* pSrc[2 * i + 1] * CoefA1 */ - outI += *pSrc1++ * CoefA1; - - CoefB1 = *pCoefB; - - /* pSrc[2 * fftLen - 2 * i + 1] * CoefB1 */ - outI -= *pSrc2-- * CoefB1; - /* pSrc[2 * fftLen - 2 * i] * CoefA2 */ - outI -= *pSrc2 * CoefA2; - - /* pSrc[2 * fftLen - 2 * i] * CoefB1 */ - outR += *pSrc2-- * CoefB1; - - /* write output */ - *pDst1++ = outR; - *pDst1++ = outI; - - /* write complex conjugate output */ - *pDst2-- = -outI; - *pDst2-- = outR; - - /* update coefficient pointer */ - pCoefB = pCoefB + (modifier * 2u); - pCoefA = pCoefA + ((modifier * 2u) - 1u); - - i--; - - } - - pDst[2u * fftLen] = pSrc[0] - pSrc[1]; - pDst[(2u * fftLen) + 1u] = 0.0f; - - pDst[0] = pSrc[0] + pSrc[1]; - pDst[1] = 0.0f; - -} - - -/** - * @brief Core Real IFFT process - * @param[in] *pSrc points to the input buffer. - * @param[in] fftLen length of FFT. - * @param[in] *pATable points to the twiddle Coef A buffer. - * @param[in] *pBTable points to the twiddle Coef B buffer. - * @param[out] *pDst points to the output buffer. - * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_split_rifft_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pATable, - float32_t * pBTable, - float32_t * pDst, - uint32_t modifier) -{ - float32_t outR, outI; /* Temporary variables for output */ - float32_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - float32_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ - float32_t *pSrc1 = &pSrc[0], *pSrc2 = &pSrc[(2u * fftLen) + 1u]; - - pCoefA = &pATable[0]; - pCoefB = &pBTable[0]; - - while(fftLen > 0u) - { - /* - outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - - outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); - - */ - - CoefA1 = *pCoefA++; - CoefA2 = *pCoefA; - - /* outR = (pSrc[2 * i] * CoefA1 */ - outR = *pSrc1 * CoefA1; - - /* - pSrc[2 * i] * CoefA2 */ - outI = -(*pSrc1++) * CoefA2; - - /* (pSrc[2 * i + 1] + pSrc[2 * fftLen - 2 * i + 1]) * CoefA2 */ - outR += (*pSrc1 + *pSrc2) * CoefA2; - - /* pSrc[2 * i + 1] * CoefA1 */ - outI += (*pSrc1++) * CoefA1; - - CoefB1 = *pCoefB; - - /* - pSrc[2 * fftLen - 2 * i + 1] * CoefB1 */ - outI -= *pSrc2-- * CoefB1; - - /* pSrc[2 * fftLen - 2 * i] * CoefB1 */ - outR += *pSrc2 * CoefB1; - - /* pSrc[2 * fftLen - 2 * i] * CoefA2 */ - outI += *pSrc2-- * CoefA2; - - /* write output */ - *pDst++ = outR; - *pDst++ = outI; - - /* update coefficient pointer */ - pCoefB = pCoefB + (modifier * 2u); - pCoefA = pCoefA + ((modifier * 2u) - 1u); - - /* Decrement loop count */ - fftLen--; - } - -} +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_rfft_f32.c +* +* Description: RFFT & RIFFT Floating point process function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @defgroup RFFT_RIFFT Real FFT Functions + * + * \par + * Complex FFT/IFFT typically assumes complex input and output. However many applications use real valued data in time domain. + * Real FFT/IFFT efficiently process real valued sequences with the advantage of requirement of low memory and with less complexity. + * + * \par + * This set of functions implements Real Fast Fourier Transforms(RFFT) and Real Inverse Fast Fourier Transform(RIFFT) + * for Q15, Q31, and floating-point data types. + * + * + * \par Algorithm: + * + * Real Fast Fourier Transform: + * \par + * Real FFT of N-point is calculated using CFFT of N/2-point and Split RFFT process as shown below figure. + * \par + * \image html RFFT.gif "Real Fast Fourier Transform" + * \par + * The RFFT functions operate on blocks of input and output data and each call to the function processes + * fftLenR samples through the transform. pSrc points to input array containing fftLenR values. + * pDst points to output array containing 2*fftLenR values. \n + * Input for real FFT is in the order of + *
{real[0], real[1], real[2], real[3], ..}
+ * Output for real FFT is complex and are in the order of + *
{real(0), imag(0), real(1), imag(1), ...}
+ * + * Real Inverse Fast Fourier Transform: + * \par + * Real IFFT of N-point is calculated using Split RIFFT process and CFFT of N/2-point as shown below figure. + * \par + * \image html RIFFT.gif "Real Inverse Fast Fourier Transform" + * \par + * The RIFFT functions operate on blocks of input and output data and each call to the function processes + * 2*fftLenR samples through the transform. pSrc points to input array containing 2*fftLenR values. + * pDst points to output array containing fftLenR values. \n + * Input for real IFFT is complex and are in the order of + *
{real(0), imag(0), real(1), imag(1), ...}
+ * Output for real IFFT is real and in the order of + *
{real[0], real[1], real[2], real[3], ..}
+ * + * \par Lengths supported by the transform: + * \par + * Real FFT/IFFT supports the lengths [128, 512, 2048], as it internally uses CFFT/CIFFT. + * + * \par Instance Structure + * A separate instance structure must be defined for each Instance but the twiddle factors can be reused. + * There are separate instance structure declarations for each of the 3 supported data types. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: + * - Sets the values of the internal structure fields. + * - Initializes twiddle factor tables. + * - Initializes CFFT data structure fields. + * \par + * Use of the initialization function is optional. + * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. + * To place an instance structure into a const data section, the instance structure must be manually initialized. + * Manually initialize the instance structure as follows: + *
   
+ *arm_rfft_instance_f32 S = {fftLenReal, fftLenBy2, ifftFlagR, bitReverseFlagR, twidCoefRModifier, pTwiddleAReal, pTwiddleBReal, pCfft};   
+ *arm_rfft_instance_q31 S = {fftLenReal, fftLenBy2, ifftFlagR, bitReverseFlagR, twidCoefRModifier, pTwiddleAReal, pTwiddleBReal, pCfft};   
+ *arm_rfft_instance_q15 S = {fftLenReal, fftLenBy2, ifftFlagR, bitReverseFlagR, twidCoefRModifier, pTwiddleAReal, pTwiddleBReal, pCfft};   
+ * 
+ * where fftLenReal length of RFFT/RIFFT; fftLenBy2 length of CFFT/CIFFT. + * ifftFlagR Flag for selection of RFFT or RIFFT(Set ifftFlagR to calculate RIFFT otherwise calculates RFFT); + * bitReverseFlagR Flag for selection of output order(Set bitReverseFlagR to output in normal order otherwise output in bit reversed order); + * twidCoefRModifier modifier for twiddle factor table which supports 128, 512, 2048 RFFT lengths with same table; + * pTwiddleARealpoints to A array of twiddle coefficients; pTwiddleBRealpoints to B array of twiddle coefficients; + * pCfft points to the CFFT Instance structure. The CFFT structure also needs to be initialized, refer to arm_cfft_radix4_f32() for details regarding + * static initialization of cfft structure. + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the RFFT/RIFFT function. + * Refer to the function specific documentation below for usage guidelines. + */ + +/*-------------------------------------------------------------------- + * Internal functions prototypes + *--------------------------------------------------------------------*/ + +void arm_split_rfft_f32( + float32_t * pSrc, + uint32_t fftLen, + float32_t * pATable, + float32_t * pBTable, + float32_t * pDst, + uint32_t modifier); +void arm_split_rifft_f32( + float32_t * pSrc, + uint32_t fftLen, + float32_t * pATable, + float32_t * pBTable, + float32_t * pDst, + uint32_t modifier); + +/** + * @addtogroup RFFT_RIFFT + * @{ + */ + +/** + * @brief Processing function for the floating-point RFFT/RIFFT. + * @param[in] *S points to an instance of the floating-point RFFT/RIFFT structure. + * @param[in] *pSrc points to the input buffer. + * @param[out] *pDst points to the output buffer. + * @return none. + */ + +void arm_rfft_f32( + const arm_rfft_instance_f32 * S, + float32_t * pSrc, + float32_t * pDst) +{ + const arm_cfft_radix4_instance_f32 *S_CFFT = S->pCfft; + + + /* Calculation of Real IFFT of input */ + if(S->ifftFlagR == 1u) + { + /* Real IFFT core process */ + arm_split_rifft_f32(pSrc, S->fftLenBy2, S->pTwiddleAReal, + S->pTwiddleBReal, pDst, S->twidCoefRModifier); + + + /* Complex radix-4 IFFT process */ + arm_radix4_butterfly_inverse_f32(pDst, S_CFFT->fftLen, + S_CFFT->pTwiddle, + S_CFFT->twidCoefModifier, + S_CFFT->onebyfftLen); + + /* Bit reversal process */ + if(S->bitReverseFlagR == 1u) + { + arm_bitreversal_f32(pDst, S_CFFT->fftLen, + S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); + } + } + else + { + + /* Calculation of RFFT of input */ + + /* Complex radix-4 FFT process */ + arm_radix4_butterfly_f32(pSrc, S_CFFT->fftLen, + S_CFFT->pTwiddle, S_CFFT->twidCoefModifier); + + /* Bit reversal process */ + if(S->bitReverseFlagR == 1u) + { + arm_bitreversal_f32(pSrc, S_CFFT->fftLen, + S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); + } + + + /* Real FFT core process */ + arm_split_rfft_f32(pSrc, S->fftLenBy2, S->pTwiddleAReal, + S->pTwiddleBReal, pDst, S->twidCoefRModifier); + } + +} + +/** + * @} end of RFFT_RIFFT group + */ + +/** + * @brief Core Real FFT process + * @param[in] *pSrc points to the input buffer. + * @param[in] fftLen length of FFT. + * @param[in] *pATable points to the twiddle Coef A buffer. + * @param[in] *pBTable points to the twiddle Coef B buffer. + * @param[out] *pDst points to the output buffer. + * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + +void arm_split_rfft_f32( + float32_t * pSrc, + uint32_t fftLen, + float32_t * pATable, + float32_t * pBTable, + float32_t * pDst, + uint32_t modifier) +{ + uint32_t i; /* Loop Counter */ + float32_t outR, outI; /* Temporary variables for output */ + float32_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ + float32_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ + float32_t *pDst1 = &pDst[2], *pDst2 = &pDst[(4u * fftLen) - 1u]; /* temp pointers for output buffer */ + float32_t *pSrc1 = &pSrc[2], *pSrc2 = &pSrc[(2u * fftLen) - 1u]; /* temp pointers for input buffer */ + + + pSrc[2u * fftLen] = pSrc[0]; + pSrc[(2u * fftLen) + 1u] = pSrc[1]; + + /* Init coefficient pointers */ + pCoefA = &pATable[modifier * 2u]; + pCoefB = &pBTable[modifier * 2u]; + + i = fftLen - 1u; + + while(i > 0u) + { + /* + outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] + + pSrc[2 * n - 2 * i] * pBTable[2 * i] + + pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); + */ + + /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + + pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); */ + + /* read pATable[2 * i] */ + CoefA1 = *pCoefA++; + /* pATable[2 * i + 1] */ + CoefA2 = *pCoefA; + + /* pSrc[2 * i] * pATable[2 * i] */ + outR = *pSrc1 * CoefA1; + /* pSrc[2 * i] * CoefA2 */ + outI = *pSrc1++ * CoefA2; + + /* (pSrc[2 * i + 1] + pSrc[2 * fftLen - 2 * i + 1]) * CoefA2 */ + outR -= (*pSrc1 + *pSrc2) * CoefA2; + /* pSrc[2 * i + 1] * CoefA1 */ + outI += *pSrc1++ * CoefA1; + + CoefB1 = *pCoefB; + + /* pSrc[2 * fftLen - 2 * i + 1] * CoefB1 */ + outI -= *pSrc2-- * CoefB1; + /* pSrc[2 * fftLen - 2 * i] * CoefA2 */ + outI -= *pSrc2 * CoefA2; + + /* pSrc[2 * fftLen - 2 * i] * CoefB1 */ + outR += *pSrc2-- * CoefB1; + + /* write output */ + *pDst1++ = outR; + *pDst1++ = outI; + + /* write complex conjugate output */ + *pDst2-- = -outI; + *pDst2-- = outR; + + /* update coefficient pointer */ + pCoefB = pCoefB + (modifier * 2u); + pCoefA = pCoefA + ((modifier * 2u) - 1u); + + i--; + + } + + pDst[2u * fftLen] = pSrc[0] - pSrc[1]; + pDst[(2u * fftLen) + 1u] = 0.0f; + + pDst[0] = pSrc[0] + pSrc[1]; + pDst[1] = 0.0f; + +} + + +/** + * @brief Core Real IFFT process + * @param[in] *pSrc points to the input buffer. + * @param[in] fftLen length of FFT. + * @param[in] *pATable points to the twiddle Coef A buffer. + * @param[in] *pBTable points to the twiddle Coef B buffer. + * @param[out] *pDst points to the output buffer. + * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + +void arm_split_rifft_f32( + float32_t * pSrc, + uint32_t fftLen, + float32_t * pATable, + float32_t * pBTable, + float32_t * pDst, + uint32_t modifier) +{ + float32_t outR, outI; /* Temporary variables for output */ + float32_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ + float32_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ + float32_t *pSrc1 = &pSrc[0], *pSrc2 = &pSrc[(2u * fftLen) + 1u]; + + pCoefA = &pATable[0]; + pCoefB = &pBTable[0]; + + while(fftLen > 0u) + { + /* + outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + + pIn[2 * n - 2 * i] * pBTable[2 * i] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); + + outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - + pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); + + */ + + CoefA1 = *pCoefA++; + CoefA2 = *pCoefA; + + /* outR = (pSrc[2 * i] * CoefA1 */ + outR = *pSrc1 * CoefA1; + + /* - pSrc[2 * i] * CoefA2 */ + outI = -(*pSrc1++) * CoefA2; + + /* (pSrc[2 * i + 1] + pSrc[2 * fftLen - 2 * i + 1]) * CoefA2 */ + outR += (*pSrc1 + *pSrc2) * CoefA2; + + /* pSrc[2 * i + 1] * CoefA1 */ + outI += (*pSrc1++) * CoefA1; + + CoefB1 = *pCoefB; + + /* - pSrc[2 * fftLen - 2 * i + 1] * CoefB1 */ + outI -= *pSrc2-- * CoefB1; + + /* pSrc[2 * fftLen - 2 * i] * CoefB1 */ + outR += *pSrc2 * CoefB1; + + /* pSrc[2 * fftLen - 2 * i] * CoefA2 */ + outI += *pSrc2-- * CoefA2; + + /* write output */ + *pDst++ = outR; + *pDst++ = outI; + + /* update coefficient pointer */ + pCoefB = pCoefB + (modifier * 2u); + pCoefA = pCoefA + ((modifier * 2u) - 1u); + + /* Decrement loop count */ + fftLen--; + } + +} diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_f32.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_f32.c index c144cbea9..de0a47abc 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_f32.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_f32.c @@ -1,1707 +1,1707 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_init_f32.c -* -* Description: RFFT & RIFFT Floating point initialisation function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - -/** -* \par -* Generation of realCoefA array: -* \par -* n = 1024 -*
for (i = 0; i < n; i++)   
-*  {   
-*    pATable[2 * i] = 0.5 * (1.0 - sin (2 * PI / (double) (2 * n) * (double) i));   
-*    pATable[2 * i + 1] = 0.5 * (-1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
-*  } 
-*/ - - - -static const float32_t realCoefA[2048] = { - 0.500000000000000000f, -0.500000000000000000f, 0.498466014862060550f, - -0.499997645616531370f, 0.496932059526443480f, -0.499990582466125490f, - 0.495398133993148800f, -0.499978810548782350f, - 0.493864238262176510f, -0.499962359666824340f, 0.492330402135849000f, - -0.499941170215606690f, 0.490796625614166260f, -0.499915301799774170f, - 0.489262968301773070f, -0.499884694814682010f, - 0.487729400396347050f, -0.499849408864974980f, 0.486195921897888180f, - -0.499809414148330690f, 0.484662592411041260f, -0.499764710664749150f, - 0.483129411935806270f, -0.499715298414230350f, - 0.481596380472183230f, -0.499661177396774290f, 0.480063527822494510f, - -0.499602377414703370f, 0.478530883789062500f, -0.499538868665695190f, - 0.476998418569564820f, -0.499470651149749760f, - 0.475466161966323850f, -0.499397724866867070f, 0.473934143781661990f, - -0.499320119619369510f, 0.472402364015579220f, -0.499237775802612300f, - 0.470870882272720340f, -0.499150782823562620f, - 0.469339638948440550f, -0.499059051275253300f, 0.467808693647384640f, - -0.498962640762329100f, 0.466278046369552610f, -0.498861521482467650f, - 0.464747726917266850f, -0.498755723237991330f, - 0.463217705488204960f, -0.498645216226577760f, 0.461688071489334110f, - -0.498530030250549320f, 0.460158795118331910f, -0.498410135507583620f, - 0.458629876375198360f, -0.498285561800003050f, - 0.457101345062255860f, -0.498156309127807620f, 0.455573230981826780f, - -0.498022347688674930f, 0.454045534133911130f, -0.497883707284927370f, - 0.452518254518508910f, -0.497740387916564940f, - 0.450991421937942500f, -0.497592359781265260f, 0.449465066194534300f, - -0.497439652681350710f, 0.447939187288284300f, -0.497282296419143680f, - 0.446413785219192500f, -0.497120231389999390f, - 0.444888889789581300f, -0.496953487396240230f, 0.443364530801773070f, - -0.496782064437866210f, 0.441840678453445430f, -0.496605962514877320f, - 0.440317392349243160f, -0.496425211429595950f, - 0.438794672489166260f, -0.496239781379699710f, 0.437272518873214720f, - -0.496049642562866210f, 0.435750931501388550f, -0.495854884386062620f, - 0.434229999780654910f, -0.495655417442321780f, - 0.432709634304046630f, -0.495451331138610840f, 0.431189924478530880f, - -0.495242536067962650f, 0.429670870304107670f, -0.495029091835021970f, - 0.428152471780776980f, -0.494810998439788820f, - 0.426634758710861210f, -0.494588255882263180f, 0.425117731094360350f, - -0.494360834360122680f, 0.423601418733596800f, -0.494128793478012080f, - 0.422085791826248170f, -0.493892073631286620f, - 0.420570939779281620f, -0.493650704622268680f, 0.419056802988052370f, - -0.493404686450958250f, 0.417543441057205200f, -0.493154048919677730f, - 0.416030853986740110f, -0.492898762226104740f, - 0.414519041776657100f, -0.492638826370239260f, 0.413008064031600950f, - -0.492374241352081300f, 0.411497890949249270f, -0.492105036973953250f, - 0.409988552331924440f, -0.491831213235855100f, - 0.408480048179626460f, -0.491552740335464480f, 0.406972438097000120f, - -0.491269648075103760f, 0.405465662479400630f, -0.490981936454772950f, - 0.403959810733795170f, -0.490689605474472050f, - 0.402454853057861330f, -0.490392625331878660f, 0.400950789451599120f, - -0.490091055631637570f, 0.399447679519653320f, -0.489784896373748780f, - 0.397945523262023930f, -0.489474087953567500f, - 0.396444320678710940f, -0.489158689975738530f, 0.394944071769714360f, - -0.488838672637939450f, 0.393444836139678960f, -0.488514065742492680f, - 0.391946613788604740f, -0.488184869289398190f, - 0.390449374914169310f, -0.487851053476333620f, 0.388953179121017460f, - -0.487512677907943730f, 0.387458056211471560f, -0.487169682979583740f, - 0.385963946580886840f, -0.486822128295898440f, - 0.384470939636230470f, -0.486469984054565430f, 0.382979035377502440f, - -0.486113250255584720f, 0.381488204002380370f, -0.485751956701278690f, - 0.379998475313186650f, -0.485386073589324950f, - 0.378509908914566040f, -0.485015630722045900f, 0.377022475004196170f, - -0.484640628099441530f, 0.375536203384399410f, -0.484261035919189450f, - 0.374051094055175780f, -0.483876913785934450f, - 0.372567176818847660f, -0.483488231897354130f, 0.371084451675415040f, - -0.483094990253448490f, 0.369602948427200320f, -0.482697218656539920f, - 0.368122667074203490f, -0.482294887304306030f, - 0.366643607616424560f, -0.481888025999069210f, 0.365165829658508300f, - -0.481476634740829470f, 0.363689333200454710f, -0.481060713529586790f, - 0.362214088439941410f, -0.480640232563018800f, - 0.360740154981613160f, -0.480215251445770260f, 0.359267532825469970f, - -0.479785770177841190f, 0.357796221971511840f, -0.479351729154586790f, - 0.356326282024383540f, -0.478913217782974240f, - 0.354857653379440310f, -0.478470176458358760f, 0.353390425443649290f, - -0.478022634983062740f, 0.351924568414688110f, -0.477570593357086180f, - 0.350460082292556760f, -0.477114051580429080f, - 0.348997026681900020f, -0.476653009653091430f, 0.347535371780395510f, - -0.476187497377395630f, 0.346075177192687990f, -0.475717514753341670f, - 0.344616413116455080f, -0.475243031978607180f, - 0.343159139156341550f, -0.474764078855514530f, 0.341703325510025020f, - -0.474280685186386110f, 0.340248972177505490f, -0.473792791366577150f, - 0.338796168565750120f, -0.473300457000732420f, - 0.337344855070114140f, -0.472803652286529540f, 0.335895091295242310f, - -0.472302407026290890f, 0.334446847438812260f, -0.471796721220016480f, - 0.333000183105468750f, -0.471286594867706300f, - 0.331555068492889400f, -0.470772027969360350f, 0.330111563205718990f, - -0.470253020524978640f, 0.328669637441635130f, -0.469729602336883540f, - 0.327229350805282590f, -0.469201773405075070f, - 0.325790673494338990f, -0.468669503927230830f, 0.324353635311126710f, - -0.468132823705673220f, 0.322918236255645750f, -0.467591762542724610f, - 0.321484506130218510f, -0.467046260833740230f, - 0.320052474737167360f, -0.466496407985687260f, 0.318622142076492310f, - -0.465942144393920900f, 0.317193508148193360f, -0.465383470058441160f, - 0.315766572952270510f, -0.464820444583892820f, - 0.314341396093368530f, -0.464253038167953490f, 0.312917977571487430f, - -0.463681250810623170f, 0.311496287584304810f, -0.463105112314224240f, - 0.310076385736465450f, -0.462524622678756710f, - 0.308658272027969360f, -0.461939752101898190f, 0.307241976261138920f, - -0.461350560188293460f, 0.305827468633651730f, -0.460757017135620120f, - 0.304414808750152590f, -0.460159152746200560f, - 0.303003966808319090f, -0.459556937217712400f, 0.301595002412796020f, - -0.458950400352478030f, 0.300187885761260990f, -0.458339542150497440f, - 0.298782676458358760f, -0.457724362611770630f, - 0.297379344701766970f, -0.457104891538620000f, 0.295977920293807980f, - -0.456481099128723140f, 0.294578403234481810f, -0.455853015184402470f, - 0.293180853128433230f, -0.455220639705657960f, - 0.291785210371017460f, -0.454584002494812010f, 0.290391564369201660f, - -0.453943043947219850f, 0.288999855518341060f, -0.453297853469848630f, - 0.287610173225402830f, -0.452648371458053590f, - 0.286222457885742190f, -0.451994657516479490f, 0.284836769104003910f, - -0.451336652040481570f, 0.283453077077865600f, -0.450674414634704590f, - 0.282071471214294430f, -0.450007945299148560f, - 0.280691891908645630f, -0.449337244033813480f, 0.279314368963241580f, - -0.448662281036376950f, 0.277938932180404660f, -0.447983115911483760f, - 0.276565581560134890f, -0.447299748659133910f, - 0.275194346904754640f, -0.446612149477005000f, 0.273825198411941530f, - -0.445920348167419430f, 0.272458195686340330f, -0.445224374532699580f, - 0.271093338727951050f, -0.444524168968200680f, - 0.269730657339096070f, -0.443819820880889890f, 0.268370121717453000f, - -0.443111270666122440f, 0.267011761665344240f, -0.442398548126220700f, - 0.265655577182769780f, -0.441681683063507080f, - 0.264301627874374390f, -0.440960645675659180f, 0.262949883937835690f, - -0.440235435962677000f, 0.261600375175476070f, -0.439506113529205320f, - 0.260253131389617920f, -0.438772648572921750f, - 0.258908122777938840f, -0.438035041093826290f, 0.257565379142761230f, - -0.437293320894241330f, 0.256224930286407470f, -0.436547487974166870f, - 0.254886746406555180f, -0.435797542333602910f, - 0.253550916910171510f, -0.435043483972549440f, 0.252217382192611690f, - -0.434285342693328860f, 0.250886172056198120f, -0.433523118495941160f, - 0.249557301402091980f, -0.432756811380386350f, - 0.248230814933776860f, -0.431986421346664430f, 0.246906682848930360f, - -0.431211978197097780f, 0.245584934949874880f, -0.430433481931686400f, - 0.244265571236610410f, -0.429650902748107910f, - 0.242948621511459350f, -0.428864300251007080f, 0.241634100675582890f, - -0.428073674440383910f, 0.240322008728981020f, -0.427278995513916020f, - 0.239012360572814940f, -0.426480293273925780f, - 0.237705156207084660f, -0.425677597522735600f, 0.236400425434112550f, - -0.424870878458023070f, 0.235098183155059810f, -0.424060165882110600f, - 0.233798429369926450f, -0.423245459794998170f, - 0.232501193881034850f, -0.422426789999008180f, 0.231206461787223820f, - -0.421604126691818240f, 0.229914262890815730f, -0.420777499675750730f, - 0.228624612092971800f, -0.419946908950805660f, - 0.227337509393692020f, -0.419112354516983030f, 0.226052969694137570f, - -0.418273866176605220f, 0.224771007895469670f, -0.417431443929672240f, - 0.223491653800010680f, -0.416585087776184080f, - 0.222214877605438230f, -0.415734797716140750f, 0.220940738916397090f, - -0.414880603551864620f, 0.219669207930564880f, -0.414022535085678100f, - 0.218400329351425170f, -0.413160532712936400f, - 0.217134088277816770f, -0.412294656038284300f, 0.215870529413223270f, - -0.411424905061721800f, 0.214609622955322270f, -0.410551249980926510f, - 0.213351413607597350f, -0.409673750400543210f, - 0.212095901370048520f, -0.408792406320571900f, 0.210843101143836980f, - -0.407907217741012570f, 0.209593027830123900f, -0.407018154859542850f, - 0.208345666527748110f, -0.406125307083129880f, - 0.207101076841354370f, -0.405228585004806520f, 0.205859228968620300f, - -0.404328078031539920f, 0.204620152711868290f, -0.403423786163330080f, - 0.203383848071098330f, -0.402515679597854610f, - 0.202150344848632810f, -0.401603758335113530f, 0.200919643044471740f, - -0.400688081979751590f, 0.199691757559776310f, -0.399768620729446410f, - 0.198466703295707700f, -0.398845434188842770f, - 0.197244480252265930f, -0.397918462753295900f, 0.196025103330612180f, - -0.396987736225128170f, 0.194808602333068850f, -0.396053284406661990f, - 0.193594962358474730f, -0.395115107297897340f, - 0.192384198307991030f, -0.394173204898834230f, 0.191176339983940120f, - -0.393227607011795040f, 0.189971387386322020f, -0.392278283834457400f, - 0.188769355416297910f, -0.391325294971466060f, - 0.187570258975028990f, -0.390368610620498660f, 0.186374098062515260f, - -0.389408260583877560f, 0.185180887579917910f, -0.388444244861602780f, - 0.183990627527236940f, -0.387476563453674320f, - 0.182803362607955930f, -0.386505216360092160f, 0.181619063019752500f, - -0.385530263185501100f, 0.180437773466110230f, -0.384551674127578740f, - 0.179259493947029110f, -0.383569449186325070f, - 0.178084224462509160f, -0.382583618164062500f, 0.176911994814872740f, - -0.381594210863113400f, 0.175742805004119870f, -0.380601197481155400f, - 0.174576655030250550f, -0.379604607820510860f, - 0.173413574695587160f, -0.378604412078857420f, 0.172253578901290890f, - -0.377600699663162230f, 0.171096652746200560f, -0.376593410968780520f, - 0.169942826032638550f, -0.375582575798034670f, - 0.168792113661766050f, -0.374568194150924680f, 0.167644515633583070f, - -0.373550295829772950f, 0.166500031948089600f, -0.372528880834579470f, - 0.165358707308769230f, -0.371503978967666630f, - 0.164220526814460750f, -0.370475560426712040f, 0.163085505366325380f, - -0.369443655014038090f, 0.161953642964363100f, -0.368408292531967160f, - 0.160824984312057500f, -0.367369443178176880f, - 0.159699499607086180f, -0.366327136754989620f, 0.158577233552932740f, - -0.365281373262405400f, 0.157458171248435970f, -0.364232182502746580f, - 0.156342327594757080f, -0.363179564476013180f, - 0.155229732394218440f, -0.362123548984527590f, 0.154120370745658870f, - -0.361064106225967410f, 0.153014272451400760f, -0.360001266002655030f, - 0.151911437511444090f, -0.358935028314590450f, - 0.150811880826950070f, -0.357865422964096070f, 0.149715602397918700f, - -0.356792420148849490f, 0.148622632026672360f, -0.355716109275817870f, - 0.147532954812049870f, -0.354636400938034060f, - 0.146446615457534790f, -0.353553384542465210f, 0.145363584160804750f, - -0.352467030286788940f, 0.144283905625343320f, -0.351377367973327640f, - 0.143207564949989320f, -0.350284397602081300f, - 0.142134591937065120f, -0.349188119173049930f, 0.141064971685409550f, - -0.348088562488555910f, 0.139998748898506160f, -0.346985727548599240f, - 0.138935908675193790f, -0.345879614353179930f, - 0.137876465916633610f, -0.344770282506942750f, 0.136820420622825620f, - -0.343657672405242920f, 0.135767802596092220f, -0.342541843652725220f, - 0.134718611836433410f, -0.341422766447067260f, - 0.133672863245010380f, -0.340300500392913820f, 0.132630556821823120f, - -0.339175015687942500f, 0.131591722369194030f, -0.338046342134475710f, - 0.130556344985961910f, -0.336914509534835820f, - 0.129524439573287960f, -0.335779488086700440f, 0.128496021032333370f, - -0.334641307592391970f, 0.127471104264259340f, -0.333499968051910400f, - 0.126449704170227050f, -0.332355499267578130f, - 0.125431805849075320f, -0.331207901239395140f, 0.124417431652545930f, - -0.330057173967361450f, 0.123406603932380680f, -0.328903347253799440f, - 0.122399315237998960f, -0.327746421098709110f, - 0.121395580470561980f, -0.326586425304412840f, 0.120395407080650330f, - -0.325423330068588260f, 0.119398809969425200f, -0.324257194995880130f, - 0.118405789136886600f, -0.323088020086288450f, - 0.117416366934776310f, -0.321915775537490840f, 0.116430543363094330f, - -0.320740520954132080f, 0.115448333323001860f, -0.319562226533889770f, - 0.114469736814498900f, -0.318380922079086300f, - 0.113494776189327240f, -0.317196637392044070f, 0.112523443996906280f, - -0.316009372472763060f, 0.111555770039558410f, -0.314819127321243290f, - 0.110591746866703030f, -0.313625901937484740f, - 0.109631389379501340f, -0.312429755926132200f, 0.108674705028533940f, - -0.311230629682540890f, 0.107721701264381410f, -0.310028612613677980f, - 0.106772392988204960f, -0.308823645114898680f, - 0.105826787650585170f, -0.307615786790847780f, 0.104884892702102660f, - -0.306405037641525270f, 0.103946708142757420f, -0.305191397666931150f, - 0.103012263774871830f, -0.303974896669387820f, - 0.102081544697284700f, -0.302755534648895260f, 0.101154580712318420f, - -0.301533311605453490f, 0.100231364369392400f, -0.300308227539062500f, - 0.099311910569667816f, -0.299080342054367070f, - 0.098396234214305878f, -0.297849655151367190f, 0.097484335303306580f, - -0.296616137027740480f, 0.096576221287250519f, -0.295379847288131710f, - 0.095671907067298889f, -0.294140785932540890f, - 0.094771400094032288f, -0.292898923158645630f, 0.093874707818031311f, - -0.291654318571090700f, 0.092981837689876556f, -0.290406972169876100f, - 0.092092797160148621f, -0.289156883955001830f, - 0.091207593679428101f, -0.287904083728790280f, 0.090326242148876190f, - -0.286648571491241460f, 0.089448742568492889f, -0.285390377044677730f, - 0.088575109839439392f, -0.284129470586776730f, - 0.087705351412296295f, -0.282865911722183230f, 0.086839467287063599f, - -0.281599670648574830f, 0.085977479815483093f, -0.280330777168273930f, - 0.085119381546974182f, -0.279059261083602910f, - 0.084265194833278656f, -0.277785122394561770f, 0.083414919674396515f, - -0.276508361101150510f, 0.082568563520908356f, -0.275228977203369140f, - 0.081726133823394775f, -0.273947030305862430f, - 0.080887645483016968f, -0.272662490606307980f, 0.080053105950355530f, - -0.271375387907028200f, 0.079222507774829865f, -0.270085722208023070f, - 0.078395880758762360f, -0.268793523311614990f, - 0.077573217451572418f, -0.267498821020126340f, 0.076754532754421234f, - -0.266201555728912350f, 0.075939826667308807f, -0.264901816844940190f, - 0.075129114091396332f, -0.263599574565887450f, - 0.074322402477264404f, -0.262294828891754150f, 0.073519699275493622f, - -0.260987639427185060f, 0.072721004486083984f, -0.259678006172180180f, - 0.071926333010196686f, -0.258365899324417110f, - 0.071135692298412323f, -0.257051378488540650f, 0.070349089801311493f, - -0.255734413862228390f, 0.069566532969474792f, -0.254415065050125120f, - 0.068788021802902222f, -0.253093332052230830f, - 0.068013571202754974f, -0.251769185066223140f, 0.067243188619613647f, - -0.250442683696746830f, 0.066476874053478241f, -0.249113827943801880f, - 0.065714649856090546f, -0.247782632708549500f, - 0.064956501126289368f, -0.246449097990989690f, 0.064202457666397095f, - -0.245113238692283630f, 0.063452512025833130f, -0.243775084614753720f, - 0.062706671655178070f, -0.242434620857238770f, - 0.061964951455593109f, -0.241091892123222350f, 0.061227355152368546f, - -0.239746883511543270f, 0.060493886470794678f, -0.238399609923362730f, - 0.059764556586742401f, -0.237050101161003110f, - 0.059039369225502014f, -0.235698372125625610f, 0.058318331837654114f, - -0.234344407916069030f, 0.057601451873779297f, -0.232988253235816960f, - 0.056888736784458160f, -0.231629893183708190f, - 0.056180190294981003f, -0.230269357562065120f, 0.055475823581218719f, - -0.228906646370887760f, 0.054775636643171310f, -0.227541789412498470f, - 0.054079644381999969f, -0.226174786686897280f, - 0.053387850522994995f, -0.224805667996406560f, 0.052700258791446686f, - -0.223434418439865110f, 0.052016876637935638f, -0.222061067819595340f, - 0.051337707787752151f, -0.220685631036758420f, - 0.050662767142057419f, -0.219308122992515560f, 0.049992054700851440f, - -0.217928543686866760f, 0.049325577914714813f, -0.216546908020973210f, - 0.048663340508937836f, -0.215163245797157290f, - 0.048005353659391403f, -0.213777542114257810f, 0.047351621091365814f, - -0.212389841675758360f, 0.046702146530151367f, -0.211000129580497740f, - 0.046056941151618958f, -0.209608450531959530f, - 0.045416008681058884f, -0.208214774727821350f, 0.044779352843761444f, - -0.206819161772727970f, 0.044146984815597534f, -0.205421581864356990f, - 0.043518904596567154f, -0.204022079706192020f, - 0.042895123362541199f, -0.202620655298233030f, 0.042275641113519669f, - -0.201217323541641240f, 0.041660469025373459f, -0.199812099337577820f, - 0.041049610823392868f, -0.198404997587203980f, - 0.040443073958158493f, -0.196996018290519710f, 0.039840862154960632f, - -0.195585191249847410f, 0.039242979139089584f, -0.194172516465187070f, - 0.038649436086416245f, -0.192758023738861080f, - 0.038060232996940613f, -0.191341713070869450f, 0.037475381046533585f, - -0.189923599362373350f, 0.036894880235195160f, -0.188503712415695190f, - 0.036318738013505936f, -0.187082037329673770f, - 0.035746958106756210f, -0.185658603906631470f, 0.035179551690816879f, - -0.184233412146568300f, 0.034616518765687943f, -0.182806491851806640f, - 0.034057866781949997f, -0.181377857923507690f, - 0.033503599464893341f, -0.179947525262832640f, 0.032953724265098572f, - -0.178515478968620300f, 0.032408244907855988f, -0.177081763744354250f, - 0.031867165118455887f, -0.175646379590034480f, - 0.031330492347478867f, -0.174209341406822200f, 0.030798232182860374f, - -0.172770664095878600f, 0.030270388349890709f, -0.171330362558364870f, - 0.029746964573860168f, -0.169888436794281010f, - 0.029227968305349350f, -0.168444931507110600f, 0.028713401407003403f, - -0.166999831795692440f, 0.028203271329402924f, -0.165553152561187740f, - 0.027697581797838211f, -0.164104923605918880f, - 0.027196336537599564f, -0.162655144929885860f, 0.026699542999267578f, - -0.161203846335411070f, 0.026207204908132553f, -0.159751012921333310f, - 0.025719324126839638f, -0.158296689391136170f, - 0.025235909968614578f, -0.156840875744819640f, 0.024756962433457375f, - -0.155383571982383730f, 0.024282488971948624f, -0.153924822807312010f, - 0.023812493309378624f, -0.152464613318443300f, - 0.023346979171037674f, -0.151002973318099980f, 0.022885952144861221f, - -0.149539917707443240f, 0.022429415956139565f, -0.148075446486473080f, - 0.021977374330163002f, -0.146609574556350710f, - 0.021529832854866982f, -0.145142331719398500f, 0.021086793392896652f, - -0.143673732876777650f, 0.020648263394832611f, -0.142203763127326970f, - 0.020214242860674858f, -0.140732467174530030f, - 0.019784741103649139f, -0.139259845018386840f, 0.019359756261110306f, - -0.137785911560058590f, 0.018939297646284103f, -0.136310681700706480f, - 0.018523367121815681f, -0.134834155440330510f, - 0.018111966550350189f, -0.133356377482414250f, 0.017705103382468224f, - -0.131877332925796510f, 0.017302779480814934f, -0.130397051572799680f, - 0.016904998570680618f, -0.128915548324584960f, - 0.016511764377355576f, -0.127432823181152340f, 0.016123080626130104f, - -0.125948905944824220f, 0.015738952904939651f, -0.124463804066181180f, - 0.015359382145106792f, -0.122977524995803830f, - 0.014984373003244400f, -0.121490091085433960f, 0.014613929204642773f, - -0.120001509785652160f, 0.014248054474592209f, -0.118511803448200230f, - 0.013886751607060432f, -0.117020979523658750f, - 0.013530024327337742f, -0.115529052913188930f, 0.013177875429391861f, - -0.114036038517951970f, 0.012830308638513088f, -0.112541958689689640f, - 0.012487327679991722f, -0.111046813428401950f, - 0.012148935347795486f, -0.109550617635250090f, 0.011815134435892105f, - -0.108053401112556460f, 0.011485928669571877f, -0.106555156409740450f, - 0.011161320842802525f, -0.105055920779705050f, - 0.010841314680874348f, -0.103555686771869660f, 0.010525912046432495f, - -0.102054484188556670f, 0.010215117596089840f, -0.100552320480346680f, - 0.009908932261168957f, -0.099049203097820282f, - 0.009607359766960144f, -0.097545161843299866f, 0.009310402907431126f, - -0.096040196716785431f, 0.009018065407872200f, -0.094534330070018768f, - 0.008730349130928516f, -0.093027576804161072f, - 0.008447255939245224f, -0.091519944369792938f, 0.008168790489435196f, - -0.090011447668075562f, 0.007894953712821007f, -0.088502109050750732f, - 0.007625748869031668f, -0.086991935968399048f, - 0.007361178752034903f, -0.085480943322181702f, 0.007101245224475861f, - -0.083969146013259888f, 0.006845951545983553f, -0.082456558942794800f, - 0.006595299113541842f, -0.080943197011947632f, - 0.006349290721118450f, -0.079429075121879578f, 0.006107929162681103f, - -0.077914200723171234f, 0.005871216300874949f, -0.076398596167564392f, - 0.005639153998345137f, -0.074882268905639648f, - 0.005411745049059391f, -0.073365233838558197f, 0.005188991315662861f, - -0.071847513318061829f, 0.004970894660800695f, -0.070329122245311737f, - 0.004757457878440619f, -0.068810060620307922f, - 0.004548682365566492f, -0.067290350794792175f, 0.004344569984823465f, - -0.065770015120506287f, 0.004145123064517975f, -0.064249053597450256f, - 0.003950343467295170f, -0.062727488577365875f, - 0.003760232590138912f, -0.061205338686704636f, 0.003574792761355639f, - -0.059682607650756836f, 0.003394025377929211f, -0.058159314095973969f, - 0.003217932302504778f, -0.056635476648807526f, - 0.003046514932066202f, -0.055111102759838104f, 0.002879775362089276f, - -0.053586211055517197f, 0.002717714523896575f, -0.052060816437005997f, - 0.002560334512963891f, -0.050534930080175400f, - 0.002407636726275086f, -0.049008570611476898f, 0.002259622327983379f, - -0.047481749206781387f, 0.002116292715072632f, -0.045954477041959763f, - 0.001977649517357349f, -0.044426776468753815f, - 0.001843693898990750f, -0.042898654937744141f, 0.001714427140541375f, - -0.041370131075382233f, 0.001589850406162441f, -0.039841219782829285f, - 0.001469964860007167f, -0.038311932235956192f, - 0.001354771666228771f, -0.036782283335924149f, 0.001244271872565150f, - -0.035252287983894348f, 0.001138466643169522f, -0.033721961081027985f, - 0.001037356909364462f, -0.032191313803195953f, - 0.000940943544264883f, -0.030660368502140045f, 0.000849227537401021f, - -0.029129132628440857f, 0.000762209703680128f, -0.027597622945904732f, - 0.000679890916217119f, -0.026065852493047714f, - 0.000602271873503923f, -0.024533838033676147f, 0.000529353390447795f, - -0.023001590743660927f, 0.000461136136436835f, -0.021469129249453545f, - 0.000397620693547651f, -0.019936462864279747f, - 0.000338807702064514f, -0.018403612077236176f, 0.000284697714960203f, - -0.016870586201548576f, 0.000235291256103665f, -0.015337402001023293f, - 0.000190588747500442f, -0.013804072514176369f, - 0.000150590654811822f, -0.012270614504814148f, 0.000115297327283770f, - -0.010737040080130100f, 0.000084709099610336f, -0.009203365072607994f, - 0.000058826273743762f, -0.007669602986425161f, - 0.000037649078876711f, -0.006135769188404083f, 0.000021177724192967f, - -0.004601877182722092f, 0.000009412358849659f, -0.003067942336201668f, - 0.000002353095169383f, -0.001533978385850787f, - 0.000000000000000000f, -0.000000000000023345f, 0.000002353095169383f, - 0.001533978385850787f, 0.000009412358849659f, 0.003067942336201668f, - 0.000021177724192967f, 0.004601877182722092f, - 0.000037649078876711f, 0.006135769188404083f, 0.000058826273743762f, - 0.007669602986425161f, 0.000084709099610336f, 0.009203365072607994f, - 0.000115297327283770f, 0.010737040080130100f, - 0.000150590654811822f, 0.012270614504814148f, 0.000190588747500442f, - 0.013804072514176369f, 0.000235291256103665f, 0.015337402001023293f, - 0.000284697714960203f, 0.016870586201548576f, - 0.000338807702064514f, 0.018403612077236176f, 0.000397620693547651f, - 0.019936462864279747f, 0.000461136136436835f, 0.021469129249453545f, - 0.000529353390447795f, 0.023001590743660927f, - 0.000602271873503923f, 0.024533838033676147f, 0.000679890916217119f, - 0.026065852493047714f, 0.000762209703680128f, 0.027597622945904732f, - 0.000849227537401021f, 0.029129132628440857f, - 0.000940943544264883f, 0.030660368502140045f, 0.001037356909364462f, - 0.032191313803195953f, 0.001138466643169522f, 0.033721961081027985f, - 0.001244271872565150f, 0.035252287983894348f, - 0.001354771666228771f, 0.036782283335924149f, 0.001469964860007167f, - 0.038311932235956192f, 0.001589850406162441f, 0.039841219782829285f, - 0.001714427140541375f, 0.041370131075382233f, - 0.001843693898990750f, 0.042898654937744141f, 0.001977649517357349f, - 0.044426776468753815f, 0.002116292715072632f, 0.045954477041959763f, - 0.002259622327983379f, 0.047481749206781387f, - 0.002407636726275086f, 0.049008570611476898f, 0.002560334512963891f, - 0.050534930080175400f, 0.002717714523896575f, 0.052060816437005997f, - 0.002879775362089276f, 0.053586211055517197f, - 0.003046514932066202f, 0.055111102759838104f, 0.003217932302504778f, - 0.056635476648807526f, 0.003394025377929211f, 0.058159314095973969f, - 0.003574792761355639f, 0.059682607650756836f, - 0.003760232590138912f, 0.061205338686704636f, 0.003950343467295170f, - 0.062727488577365875f, 0.004145123064517975f, 0.064249053597450256f, - 0.004344569984823465f, 0.065770015120506287f, - 0.004548682365566492f, 0.067290350794792175f, 0.004757457878440619f, - 0.068810060620307922f, 0.004970894660800695f, 0.070329122245311737f, - 0.005188991315662861f, 0.071847513318061829f, - 0.005411745049059391f, 0.073365233838558197f, 0.005639153998345137f, - 0.074882268905639648f, 0.005871216300874949f, 0.076398596167564392f, - 0.006107929162681103f, 0.077914200723171234f, - 0.006349290721118450f, 0.079429075121879578f, 0.006595299113541842f, - 0.080943197011947632f, 0.006845951545983553f, 0.082456558942794800f, - 0.007101245224475861f, 0.083969146013259888f, - 0.007361178752034903f, 0.085480943322181702f, 0.007625748869031668f, - 0.086991935968399048f, 0.007894953712821007f, 0.088502109050750732f, - 0.008168790489435196f, 0.090011447668075562f, - 0.008447255939245224f, 0.091519944369792938f, 0.008730349130928516f, - 0.093027576804161072f, 0.009018065407872200f, 0.094534330070018768f, - 0.009310402907431126f, 0.096040196716785431f, - 0.009607359766960144f, 0.097545161843299866f, 0.009908932261168957f, - 0.099049203097820282f, 0.010215117596089840f, 0.100552320480346680f, - 0.010525912046432495f, 0.102054484188556670f, - 0.010841314680874348f, 0.103555686771869660f, 0.011161320842802525f, - 0.105055920779705050f, 0.011485928669571877f, 0.106555156409740450f, - 0.011815134435892105f, 0.108053401112556460f, - 0.012148935347795486f, 0.109550617635250090f, 0.012487327679991722f, - 0.111046813428401950f, 0.012830308638513088f, 0.112541958689689640f, - 0.013177875429391861f, 0.114036038517951970f, - 0.013530024327337742f, 0.115529052913188930f, 0.013886751607060432f, - 0.117020979523658750f, 0.014248054474592209f, 0.118511803448200230f, - 0.014613929204642773f, 0.120001509785652160f, - 0.014984373003244400f, 0.121490091085433960f, 0.015359382145106792f, - 0.122977524995803830f, 0.015738952904939651f, 0.124463804066181180f, - 0.016123080626130104f, 0.125948905944824220f, - 0.016511764377355576f, 0.127432823181152340f, 0.016904998570680618f, - 0.128915548324584960f, 0.017302779480814934f, 0.130397051572799680f, - 0.017705103382468224f, 0.131877332925796510f, - 0.018111966550350189f, 0.133356377482414250f, 0.018523367121815681f, - 0.134834155440330510f, 0.018939297646284103f, 0.136310681700706480f, - 0.019359756261110306f, 0.137785911560058590f, - 0.019784741103649139f, 0.139259845018386840f, 0.020214242860674858f, - 0.140732467174530030f, 0.020648263394832611f, 0.142203763127326970f, - 0.021086793392896652f, 0.143673732876777650f, - 0.021529832854866982f, 0.145142331719398500f, 0.021977374330163002f, - 0.146609574556350710f, 0.022429415956139565f, 0.148075446486473080f, - 0.022885952144861221f, 0.149539917707443240f, - 0.023346979171037674f, 0.151002973318099980f, 0.023812493309378624f, - 0.152464613318443300f, 0.024282488971948624f, 0.153924822807312010f, - 0.024756962433457375f, 0.155383571982383730f, - 0.025235909968614578f, 0.156840875744819640f, 0.025719324126839638f, - 0.158296689391136170f, 0.026207204908132553f, 0.159751012921333310f, - 0.026699542999267578f, 0.161203846335411070f, - 0.027196336537599564f, 0.162655144929885860f, 0.027697581797838211f, - 0.164104923605918880f, 0.028203271329402924f, 0.165553152561187740f, - 0.028713401407003403f, 0.166999831795692440f, - 0.029227968305349350f, 0.168444931507110600f, 0.029746964573860168f, - 0.169888436794281010f, 0.030270388349890709f, 0.171330362558364870f, - 0.030798232182860374f, 0.172770664095878600f, - 0.031330492347478867f, 0.174209341406822200f, 0.031867165118455887f, - 0.175646379590034480f, 0.032408244907855988f, 0.177081763744354250f, - 0.032953724265098572f, 0.178515478968620300f, - 0.033503599464893341f, 0.179947525262832640f, 0.034057866781949997f, - 0.181377857923507690f, 0.034616518765687943f, 0.182806491851806640f, - 0.035179551690816879f, 0.184233412146568300f, - 0.035746958106756210f, 0.185658603906631470f, 0.036318738013505936f, - 0.187082037329673770f, 0.036894880235195160f, 0.188503712415695190f, - 0.037475381046533585f, 0.189923599362373350f, - 0.038060232996940613f, 0.191341713070869450f, 0.038649436086416245f, - 0.192758023738861080f, 0.039242979139089584f, 0.194172516465187070f, - 0.039840862154960632f, 0.195585191249847410f, - 0.040443073958158493f, 0.196996018290519710f, 0.041049610823392868f, - 0.198404997587203980f, 0.041660469025373459f, 0.199812099337577820f, - 0.042275641113519669f, 0.201217323541641240f, - 0.042895123362541199f, 0.202620655298233030f, 0.043518904596567154f, - 0.204022079706192020f, 0.044146984815597534f, 0.205421581864356990f, - 0.044779352843761444f, 0.206819161772727970f, - 0.045416008681058884f, 0.208214774727821350f, 0.046056941151618958f, - 0.209608450531959530f, 0.046702146530151367f, 0.211000129580497740f, - 0.047351621091365814f, 0.212389841675758360f, - 0.048005353659391403f, 0.213777542114257810f, 0.048663340508937836f, - 0.215163245797157290f, 0.049325577914714813f, 0.216546908020973210f, - 0.049992054700851440f, 0.217928543686866760f, - 0.050662767142057419f, 0.219308122992515560f, 0.051337707787752151f, - 0.220685631036758420f, 0.052016876637935638f, 0.222061067819595340f, - 0.052700258791446686f, 0.223434418439865110f, - 0.053387850522994995f, 0.224805667996406560f, 0.054079644381999969f, - 0.226174786686897280f, 0.054775636643171310f, 0.227541789412498470f, - 0.055475823581218719f, 0.228906646370887760f, - 0.056180190294981003f, 0.230269357562065120f, 0.056888736784458160f, - 0.231629893183708190f, 0.057601451873779297f, 0.232988253235816960f, - 0.058318331837654114f, 0.234344407916069030f, - 0.059039369225502014f, 0.235698372125625610f, 0.059764556586742401f, - 0.237050101161003110f, 0.060493886470794678f, 0.238399609923362730f, - 0.061227355152368546f, 0.239746883511543270f, - 0.061964951455593109f, 0.241091892123222350f, 0.062706671655178070f, - 0.242434620857238770f, 0.063452512025833130f, 0.243775084614753720f, - 0.064202457666397095f, 0.245113238692283630f, - 0.064956501126289368f, 0.246449097990989690f, 0.065714649856090546f, - 0.247782632708549500f, 0.066476874053478241f, 0.249113827943801880f, - 0.067243188619613647f, 0.250442683696746830f, - 0.068013571202754974f, 0.251769185066223140f, 0.068788021802902222f, - 0.253093332052230830f, 0.069566532969474792f, 0.254415065050125120f, - 0.070349089801311493f, 0.255734413862228390f, - 0.071135692298412323f, 0.257051378488540650f, 0.071926333010196686f, - 0.258365899324417110f, 0.072721004486083984f, 0.259678006172180180f, - 0.073519699275493622f, 0.260987639427185060f, - 0.074322402477264404f, 0.262294828891754150f, 0.075129114091396332f, - 0.263599574565887450f, 0.075939826667308807f, 0.264901816844940190f, - 0.076754532754421234f, 0.266201555728912350f, - 0.077573217451572418f, 0.267498821020126340f, 0.078395880758762360f, - 0.268793523311614990f, 0.079222507774829865f, 0.270085722208023070f, - 0.080053105950355530f, 0.271375387907028200f, - 0.080887645483016968f, 0.272662490606307980f, 0.081726133823394775f, - 0.273947030305862430f, 0.082568563520908356f, 0.275228977203369140f, - 0.083414919674396515f, 0.276508361101150510f, - 0.084265194833278656f, 0.277785122394561770f, 0.085119381546974182f, - 0.279059261083602910f, 0.085977479815483093f, 0.280330777168273930f, - 0.086839467287063599f, 0.281599670648574830f, - 0.087705351412296295f, 0.282865911722183230f, 0.088575109839439392f, - 0.284129470586776730f, 0.089448742568492889f, 0.285390377044677730f, - 0.090326242148876190f, 0.286648571491241460f, - 0.091207593679428101f, 0.287904083728790280f, 0.092092797160148621f, - 0.289156883955001830f, 0.092981837689876556f, 0.290406972169876100f, - 0.093874707818031311f, 0.291654318571090700f, - 0.094771400094032288f, 0.292898923158645630f, 0.095671907067298889f, - 0.294140785932540890f, 0.096576221287250519f, 0.295379847288131710f, - 0.097484335303306580f, 0.296616137027740480f, - 0.098396234214305878f, 0.297849655151367190f, 0.099311910569667816f, - 0.299080342054367070f, 0.100231364369392400f, 0.300308227539062500f, - 0.101154580712318420f, 0.301533311605453490f, - 0.102081544697284700f, 0.302755534648895260f, 0.103012263774871830f, - 0.303974896669387820f, 0.103946708142757420f, 0.305191397666931150f, - 0.104884892702102660f, 0.306405037641525270f, - 0.105826787650585170f, 0.307615786790847780f, 0.106772392988204960f, - 0.308823645114898680f, 0.107721701264381410f, 0.310028612613677980f, - 0.108674705028533940f, 0.311230629682540890f, - 0.109631389379501340f, 0.312429755926132200f, 0.110591746866703030f, - 0.313625901937484740f, 0.111555770039558410f, 0.314819127321243290f, - 0.112523443996906280f, 0.316009372472763060f, - 0.113494776189327240f, 0.317196637392044070f, 0.114469736814498900f, - 0.318380922079086300f, 0.115448333323001860f, 0.319562226533889770f, - 0.116430543363094330f, 0.320740520954132080f, - 0.117416366934776310f, 0.321915775537490840f, 0.118405789136886600f, - 0.323088020086288450f, 0.119398809969425200f, 0.324257194995880130f, - 0.120395407080650330f, 0.325423330068588260f, - 0.121395580470561980f, 0.326586425304412840f, 0.122399315237998960f, - 0.327746421098709110f, 0.123406603932380680f, 0.328903347253799440f, - 0.124417431652545930f, 0.330057173967361450f, - 0.125431805849075320f, 0.331207901239395140f, 0.126449704170227050f, - 0.332355499267578130f, 0.127471104264259340f, 0.333499968051910400f, - 0.128496021032333370f, 0.334641307592391970f, - 0.129524439573287960f, 0.335779488086700440f, 0.130556344985961910f, - 0.336914509534835820f, 0.131591722369194030f, 0.338046342134475710f, - 0.132630556821823120f, 0.339175015687942500f, - 0.133672863245010380f, 0.340300500392913820f, 0.134718611836433410f, - 0.341422766447067260f, 0.135767802596092220f, 0.342541843652725220f, - 0.136820420622825620f, 0.343657672405242920f, - 0.137876465916633610f, 0.344770282506942750f, 0.138935908675193790f, - 0.345879614353179930f, 0.139998748898506160f, 0.346985727548599240f, - 0.141064971685409550f, 0.348088562488555910f, - 0.142134591937065120f, 0.349188119173049930f, 0.143207564949989320f, - 0.350284397602081300f, 0.144283905625343320f, 0.351377367973327640f, - 0.145363584160804750f, 0.352467030286788940f, - 0.146446615457534790f, 0.353553384542465210f, 0.147532954812049870f, - 0.354636400938034060f, 0.148622632026672360f, 0.355716109275817870f, - 0.149715602397918700f, 0.356792420148849490f, - 0.150811880826950070f, 0.357865422964096070f, 0.151911437511444090f, - 0.358935028314590450f, 0.153014272451400760f, 0.360001266002655030f, - 0.154120370745658870f, 0.361064106225967410f, - 0.155229732394218440f, 0.362123548984527590f, 0.156342327594757080f, - 0.363179564476013180f, 0.157458171248435970f, 0.364232182502746580f, - 0.158577233552932740f, 0.365281373262405400f, - 0.159699499607086180f, 0.366327136754989620f, 0.160824984312057500f, - 0.367369443178176880f, 0.161953642964363100f, 0.368408292531967160f, - 0.163085505366325380f, 0.369443655014038090f, - 0.164220526814460750f, 0.370475560426712040f, 0.165358707308769230f, - 0.371503978967666630f, 0.166500031948089600f, 0.372528880834579470f, - 0.167644515633583070f, 0.373550295829772950f, - 0.168792113661766050f, 0.374568194150924680f, 0.169942826032638550f, - 0.375582575798034670f, 0.171096652746200560f, 0.376593410968780520f, - 0.172253578901290890f, 0.377600699663162230f, - 0.173413574695587160f, 0.378604412078857420f, 0.174576655030250550f, - 0.379604607820510860f, 0.175742805004119870f, 0.380601197481155400f, - 0.176911994814872740f, 0.381594210863113400f, - 0.178084224462509160f, 0.382583618164062500f, 0.179259493947029110f, - 0.383569449186325070f, 0.180437773466110230f, 0.384551674127578740f, - 0.181619063019752500f, 0.385530263185501100f, - 0.182803362607955930f, 0.386505216360092160f, 0.183990627527236940f, - 0.387476563453674320f, 0.185180887579917910f, 0.388444244861602780f, - 0.186374098062515260f, 0.389408260583877560f, - 0.187570258975028990f, 0.390368610620498660f, 0.188769355416297910f, - 0.391325294971466060f, 0.189971387386322020f, 0.392278283834457400f, - 0.191176339983940120f, 0.393227607011795040f, - 0.192384198307991030f, 0.394173204898834230f, 0.193594962358474730f, - 0.395115107297897340f, 0.194808602333068850f, 0.396053284406661990f, - 0.196025103330612180f, 0.396987736225128170f, - 0.197244480252265930f, 0.397918462753295900f, 0.198466703295707700f, - 0.398845434188842770f, 0.199691757559776310f, 0.399768620729446410f, - 0.200919643044471740f, 0.400688081979751590f, - 0.202150344848632810f, 0.401603758335113530f, 0.203383848071098330f, - 0.402515679597854610f, 0.204620152711868290f, 0.403423786163330080f, - 0.205859228968620300f, 0.404328078031539920f, - 0.207101076841354370f, 0.405228585004806520f, 0.208345666527748110f, - 0.406125307083129880f, 0.209593027830123900f, 0.407018154859542850f, - 0.210843101143836980f, 0.407907217741012570f, - 0.212095901370048520f, 0.408792406320571900f, 0.213351413607597350f, - 0.409673750400543210f, 0.214609622955322270f, 0.410551249980926510f, - 0.215870529413223270f, 0.411424905061721800f, - 0.217134088277816770f, 0.412294656038284300f, 0.218400329351425170f, - 0.413160532712936400f, 0.219669207930564880f, 0.414022535085678100f, - 0.220940738916397090f, 0.414880603551864620f, - 0.222214877605438230f, 0.415734797716140750f, 0.223491653800010680f, - 0.416585087776184080f, 0.224771007895469670f, 0.417431443929672240f, - 0.226052969694137570f, 0.418273866176605220f, - 0.227337509393692020f, 0.419112354516983030f, 0.228624612092971800f, - 0.419946908950805660f, 0.229914262890815730f, 0.420777499675750730f, - 0.231206461787223820f, 0.421604126691818240f, - 0.232501193881034850f, 0.422426789999008180f, 0.233798429369926450f, - 0.423245459794998170f, 0.235098183155059810f, 0.424060165882110600f, - 0.236400425434112550f, 0.424870878458023070f, - 0.237705156207084660f, 0.425677597522735600f, 0.239012360572814940f, - 0.426480293273925780f, 0.240322008728981020f, 0.427278995513916020f, - 0.241634100675582890f, 0.428073674440383910f, - 0.242948621511459350f, 0.428864300251007080f, 0.244265571236610410f, - 0.429650902748107910f, 0.245584934949874880f, 0.430433481931686400f, - 0.246906682848930360f, 0.431211978197097780f, - 0.248230814933776860f, 0.431986421346664430f, 0.249557301402091980f, - 0.432756811380386350f, 0.250886172056198120f, 0.433523118495941160f, - 0.252217382192611690f, 0.434285342693328860f, - 0.253550916910171510f, 0.435043483972549440f, 0.254886746406555180f, - 0.435797542333602910f, 0.256224930286407470f, 0.436547487974166870f, - 0.257565379142761230f, 0.437293320894241330f, - 0.258908122777938840f, 0.438035041093826290f, 0.260253131389617920f, - 0.438772648572921750f, 0.261600375175476070f, 0.439506113529205320f, - 0.262949883937835690f, 0.440235435962677000f, - 0.264301627874374390f, 0.440960645675659180f, 0.265655577182769780f, - 0.441681683063507080f, 0.267011761665344240f, 0.442398548126220700f, - 0.268370121717453000f, 0.443111270666122440f, - 0.269730657339096070f, 0.443819820880889890f, 0.271093338727951050f, - 0.444524168968200680f, 0.272458195686340330f, 0.445224374532699580f, - 0.273825198411941530f, 0.445920348167419430f, - 0.275194346904754640f, 0.446612149477005000f, 0.276565581560134890f, - 0.447299748659133910f, 0.277938932180404660f, 0.447983115911483760f, - 0.279314368963241580f, 0.448662281036376950f, - 0.280691891908645630f, 0.449337244033813480f, 0.282071471214294430f, - 0.450007945299148560f, 0.283453077077865600f, 0.450674414634704590f, - 0.284836769104003910f, 0.451336652040481570f, - 0.286222457885742190f, 0.451994657516479490f, 0.287610173225402830f, - 0.452648371458053590f, 0.288999855518341060f, 0.453297853469848630f, - 0.290391564369201660f, 0.453943043947219850f, - 0.291785210371017460f, 0.454584002494812010f, 0.293180853128433230f, - 0.455220639705657960f, 0.294578403234481810f, 0.455853015184402470f, - 0.295977920293807980f, 0.456481099128723140f, - 0.297379344701766970f, 0.457104891538620000f, 0.298782676458358760f, - 0.457724362611770630f, 0.300187885761260990f, 0.458339542150497440f, - 0.301595002412796020f, 0.458950400352478030f, - 0.303003966808319090f, 0.459556937217712400f, 0.304414808750152590f, - 0.460159152746200560f, 0.305827468633651730f, 0.460757017135620120f, - 0.307241976261138920f, 0.461350560188293460f, - 0.308658272027969360f, 0.461939752101898190f, 0.310076385736465450f, - 0.462524622678756710f, 0.311496287584304810f, 0.463105112314224240f, - 0.312917977571487430f, 0.463681250810623170f, - 0.314341396093368530f, 0.464253038167953490f, 0.315766572952270510f, - 0.464820444583892820f, 0.317193508148193360f, 0.465383470058441160f, - 0.318622142076492310f, 0.465942144393920900f, - 0.320052474737167360f, 0.466496407985687260f, 0.321484506130218510f, - 0.467046260833740230f, 0.322918236255645750f, 0.467591762542724610f, - 0.324353635311126710f, 0.468132823705673220f, - 0.325790673494338990f, 0.468669503927230830f, 0.327229350805282590f, - 0.469201773405075070f, 0.328669637441635130f, 0.469729602336883540f, - 0.330111563205718990f, 0.470253020524978640f, - 0.331555068492889400f, 0.470772027969360350f, 0.333000183105468750f, - 0.471286594867706300f, 0.334446847438812260f, 0.471796721220016480f, - 0.335895091295242310f, 0.472302407026290890f, - 0.337344855070114140f, 0.472803652286529540f, 0.338796168565750120f, - 0.473300457000732420f, 0.340248972177505490f, 0.473792791366577150f, - 0.341703325510025020f, 0.474280685186386110f, - 0.343159139156341550f, 0.474764078855514530f, 0.344616413116455080f, - 0.475243031978607180f, 0.346075177192687990f, 0.475717514753341670f, - 0.347535371780395510f, 0.476187497377395630f, - 0.348997026681900020f, 0.476653009653091430f, 0.350460082292556760f, - 0.477114051580429080f, 0.351924568414688110f, 0.477570593357086180f, - 0.353390425443649290f, 0.478022634983062740f, - 0.354857653379440310f, 0.478470176458358760f, 0.356326282024383540f, - 0.478913217782974240f, 0.357796221971511840f, 0.479351729154586790f, - 0.359267532825469970f, 0.479785770177841190f, - 0.360740154981613160f, 0.480215251445770260f, 0.362214088439941410f, - 0.480640232563018800f, 0.363689333200454710f, 0.481060713529586790f, - 0.365165829658508300f, 0.481476634740829470f, - 0.366643607616424560f, 0.481888025999069210f, 0.368122667074203490f, - 0.482294887304306030f, 0.369602948427200320f, 0.482697218656539920f, - 0.371084451675415040f, 0.483094990253448490f, - 0.372567176818847660f, 0.483488231897354130f, 0.374051094055175780f, - 0.483876913785934450f, 0.375536203384399410f, 0.484261035919189450f, - 0.377022475004196170f, 0.484640628099441530f, - 0.378509908914566040f, 0.485015630722045900f, 0.379998475313186650f, - 0.485386073589324950f, 0.381488204002380370f, 0.485751956701278690f, - 0.382979035377502440f, 0.486113250255584720f, - 0.384470939636230470f, 0.486469984054565430f, 0.385963946580886840f, - 0.486822128295898440f, 0.387458056211471560f, 0.487169682979583740f, - 0.388953179121017460f, 0.487512677907943730f, - 0.390449374914169310f, 0.487851053476333620f, 0.391946613788604740f, - 0.488184869289398190f, 0.393444836139678960f, 0.488514065742492680f, - 0.394944071769714360f, 0.488838672637939450f, - 0.396444320678710940f, 0.489158689975738530f, 0.397945523262023930f, - 0.489474087953567500f, 0.399447679519653320f, 0.489784896373748780f, - 0.400950789451599120f, 0.490091055631637570f, - 0.402454853057861330f, 0.490392625331878660f, 0.403959810733795170f, - 0.490689605474472050f, 0.405465662479400630f, 0.490981936454772950f, - 0.406972438097000120f, 0.491269648075103760f, - 0.408480048179626460f, 0.491552740335464480f, 0.409988552331924440f, - 0.491831213235855100f, 0.411497890949249270f, 0.492105036973953250f, - 0.413008064031600950f, 0.492374241352081300f, - 0.414519041776657100f, 0.492638826370239260f, 0.416030853986740110f, - 0.492898762226104740f, 0.417543441057205200f, 0.493154048919677730f, - 0.419056802988052370f, 0.493404686450958250f, - 0.420570939779281620f, 0.493650704622268680f, 0.422085791826248170f, - 0.493892073631286620f, 0.423601418733596800f, 0.494128793478012080f, - 0.425117731094360350f, 0.494360834360122680f, - 0.426634758710861210f, 0.494588255882263180f, 0.428152471780776980f, - 0.494810998439788820f, 0.429670870304107670f, 0.495029091835021970f, - 0.431189924478530880f, 0.495242536067962650f, - 0.432709634304046630f, 0.495451331138610840f, 0.434229999780654910f, - 0.495655417442321780f, 0.435750931501388550f, 0.495854884386062620f, - 0.437272518873214720f, 0.496049642562866210f, - 0.438794672489166260f, 0.496239781379699710f, 0.440317392349243160f, - 0.496425211429595950f, 0.441840678453445430f, 0.496605962514877320f, - 0.443364530801773070f, 0.496782064437866210f, - 0.444888889789581300f, 0.496953487396240230f, 0.446413785219192500f, - 0.497120231389999390f, 0.447939187288284300f, 0.497282296419143680f, - 0.449465066194534300f, 0.497439652681350710f, - 0.450991421937942500f, 0.497592359781265260f, 0.452518254518508910f, - 0.497740387916564940f, 0.454045534133911130f, 0.497883707284927370f, - 0.455573230981826780f, 0.498022347688674930f, - 0.457101345062255860f, 0.498156309127807620f, 0.458629876375198360f, - 0.498285561800003050f, 0.460158795118331910f, 0.498410135507583620f, - 0.461688071489334110f, 0.498530030250549320f, - 0.463217705488204960f, 0.498645216226577760f, 0.464747726917266850f, - 0.498755723237991330f, 0.466278046369552610f, 0.498861521482467650f, - 0.467808693647384640f, 0.498962640762329100f, - 0.469339638948440550f, 0.499059051275253300f, 0.470870882272720340f, - 0.499150782823562620f, 0.472402364015579220f, 0.499237775802612300f, - 0.473934143781661990f, 0.499320119619369510f, - 0.475466161966323850f, 0.499397724866867070f, 0.476998418569564820f, - 0.499470651149749760f, 0.478530883789062500f, 0.499538868665695190f, - 0.480063527822494510f, 0.499602377414703370f, - 0.481596380472183230f, 0.499661177396774290f, 0.483129411935806270f, - 0.499715298414230350f, 0.484662592411041260f, 0.499764710664749150f, - 0.486195921897888180f, 0.499809414148330690f, - 0.487729400396347050f, 0.499849408864974980f, 0.489262968301773070f, - 0.499884694814682010f, 0.490796625614166260f, 0.499915301799774170f, - 0.492330402135849000f, 0.499941170215606690f, - 0.493864238262176510f, 0.499962359666824340f, 0.495398133993148800f, - 0.499978810548782350f, 0.496932059526443480f, 0.499990582466125490f, - 0.498466014862060550f, 0.499997645616531370f -}; - - -/** -* \par -* Generation of realCoefB array: -* \par -* n = 1024 -*
for (i = 0; i < n; i++)   
-* {   
-*    pBTable[2 * i] = 0.5 * (1.0 + sin (2 * PI / (double) (2 * n) * (double) i));   
-*    pBTable[2 * i + 1] = 0.5 * (1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
-*  } 
-* -*/ -static const float32_t realCoefB[2048] = { - 0.500000000000000000f, 0.500000000000000000f, 0.501533985137939450f, - 0.499997645616531370f, 0.503067970275878910f, 0.499990582466125490f, - 0.504601895809173580f, 0.499978810548782350f, - 0.506135761737823490f, 0.499962359666824340f, 0.507669627666473390f, - 0.499941170215606690f, 0.509203374385833740f, 0.499915301799774170f, - 0.510737061500549320f, 0.499884694814682010f, - 0.512270629405975340f, 0.499849408864974980f, 0.513804078102111820f, - 0.499809414148330690f, 0.515337407588958740f, 0.499764710664749150f, - 0.516870558261871340f, 0.499715298414230350f, - 0.518403589725494380f, 0.499661177396774290f, 0.519936442375183110f, - 0.499602377414703370f, 0.521469116210937500f, 0.499538868665695190f, - 0.523001611232757570f, 0.499470651149749760f, - 0.524533808231353760f, 0.499397724866867070f, 0.526065826416015630f, - 0.499320119619369510f, 0.527597606182098390f, 0.499237775802612300f, - 0.529129147529602050f, 0.499150782823562620f, - 0.530660390853881840f, 0.499059051275253300f, 0.532191336154937740f, - 0.498962640762329100f, 0.533721983432769780f, 0.498861521482467650f, - 0.535252273082733150f, 0.498755723237991330f, - 0.536782264709472660f, 0.498645216226577760f, 0.538311958312988280f, - 0.498530030250549320f, 0.539841234683990480f, 0.498410135507583620f, - 0.541370153427124020f, 0.498285561800003050f, - 0.542898654937744140f, 0.498156309127807620f, 0.544426798820495610f, - 0.498022347688674930f, 0.545954465866088870f, 0.497883707284927370f, - 0.547481775283813480f, 0.497740387916564940f, - 0.549008548259735110f, 0.497592359781265260f, 0.550534904003143310f, - 0.497439652681350710f, 0.552060842514038090f, 0.497282296419143680f, - 0.553586184978485110f, 0.497120231389999390f, - 0.555111110210418700f, 0.496953487396240230f, 0.556635499000549320f, - 0.496782064437866210f, 0.558159291744232180f, 0.496605962514877320f, - 0.559682607650756840f, 0.496425211429595950f, - 0.561205327510833740f, 0.496239781379699710f, 0.562727510929107670f, - 0.496049642562866210f, 0.564249038696289060f, 0.495854884386062620f, - 0.565770030021667480f, 0.495655417442321780f, - 0.567290365695953370f, 0.495451331138610840f, 0.568810045719146730f, - 0.495242536067962650f, 0.570329129695892330f, 0.495029091835021970f, - 0.571847498416900630f, 0.494810998439788820f, - 0.573365211486816410f, 0.494588255882263180f, 0.574882268905639650f, - 0.494360834360122680f, 0.576398611068725590f, 0.494128793478012080f, - 0.577914178371429440f, 0.493892073631286620f, - 0.579429090023040770f, 0.493650704622268680f, 0.580943167209625240f, - 0.493404686450958250f, 0.582456588745117190f, 0.493154048919677730f, - 0.583969175815582280f, 0.492898762226104740f, - 0.585480928421020510f, 0.492638826370239260f, 0.586991965770721440f, - 0.492374241352081300f, 0.588502109050750730f, 0.492105036973953250f, - 0.590011477470397950f, 0.491831213235855100f, - 0.591519951820373540f, 0.491552740335464480f, 0.593027591705322270f, - 0.491269648075103760f, 0.594534337520599370f, 0.490981936454772950f, - 0.596040189266204830f, 0.490689605474472050f, - 0.597545146942138670f, 0.490392625331878660f, 0.599049210548400880f, - 0.490091055631637570f, 0.600552320480346680f, 0.489784896373748780f, - 0.602054476737976070f, 0.489474087953567500f, - 0.603555679321289060f, 0.489158689975738530f, 0.605055928230285640f, - 0.488838672637939450f, 0.606555163860321040f, 0.488514065742492680f, - 0.608053386211395260f, 0.488184869289398190f, - 0.609550595283508300f, 0.487851053476333620f, 0.611046791076660160f, - 0.487512677907943730f, 0.612541973590850830f, 0.487169682979583740f, - 0.614036023616790770f, 0.486822128295898440f, - 0.615529060363769530f, 0.486469984054565430f, 0.617020964622497560f, - 0.486113250255584720f, 0.618511795997619630f, 0.485751956701278690f, - 0.620001494884490970f, 0.485386073589324950f, - 0.621490061283111570f, 0.485015630722045900f, 0.622977554798126220f, - 0.484640628099441530f, 0.624463796615600590f, 0.484261035919189450f, - 0.625948905944824220f, 0.483876913785934450f, - 0.627432823181152340f, 0.483488231897354130f, 0.628915548324584960f, - 0.483094990253448490f, 0.630397081375122070f, 0.482697218656539920f, - 0.631877362728118900f, 0.482294887304306030f, - 0.633356392383575440f, 0.481888025999069210f, 0.634834170341491700f, - 0.481476634740829470f, 0.636310696601867680f, 0.481060713529586790f, - 0.637785911560058590f, 0.480640232563018800f, - 0.639259815216064450f, 0.480215251445770260f, 0.640732467174530030f, - 0.479785770177841190f, 0.642203748226165770f, 0.479351729154586790f, - 0.643673717975616460f, 0.478913217782974240f, - 0.645142316818237300f, 0.478470176458358760f, 0.646609604358673100f, - 0.478022634983062740f, 0.648075461387634280f, 0.477570593357086180f, - 0.649539887905120850f, 0.477114051580429080f, - 0.651003003120422360f, 0.476653009653091430f, 0.652464628219604490f, - 0.476187497377395630f, 0.653924822807312010f, 0.475717514753341670f, - 0.655383586883544920f, 0.475243031978607180f, - 0.656840860843658450f, 0.474764078855514530f, 0.658296704292297360f, - 0.474280685186386110f, 0.659750998020172120f, 0.473792791366577150f, - 0.661203861236572270f, 0.473300457000732420f, - 0.662655174732208250f, 0.472803652286529540f, 0.664104938507080080f, - 0.472302407026290890f, 0.665553152561187740f, 0.471796721220016480f, - 0.666999816894531250f, 0.471286594867706300f, - 0.668444931507110600f, 0.470772027969360350f, 0.669888436794281010f, - 0.470253020524978640f, 0.671330332756042480f, 0.469729602336883540f, - 0.672770678997039790f, 0.469201773405075070f, - 0.674209356307983400f, 0.468669503927230830f, 0.675646364688873290f, - 0.468132823705673220f, 0.677081763744354250f, 0.467591762542724610f, - 0.678515493869781490f, 0.467046260833740230f, - 0.679947495460510250f, 0.466496407985687260f, 0.681377887725830080f, - 0.465942144393920900f, 0.682806491851806640f, 0.465383470058441160f, - 0.684233427047729490f, 0.464820444583892820f, - 0.685658574104309080f, 0.464253038167953490f, 0.687082052230834960f, - 0.463681250810623170f, 0.688503682613372800f, 0.463105112314224240f, - 0.689923584461212160f, 0.462524622678756710f, - 0.691341698169708250f, 0.461939752101898190f, 0.692758023738861080f, - 0.461350560188293460f, 0.694172501564025880f, 0.460757017135620120f, - 0.695585191249847410f, 0.460159152746200560f, - 0.696996033191680910f, 0.459556937217712400f, 0.698404967784881590f, - 0.458950400352478030f, 0.699812114238739010f, 0.458339542150497440f, - 0.701217353343963620f, 0.457724362611770630f, - 0.702620685100555420f, 0.457104891538620000f, 0.704022109508514400f, - 0.456481099128723140f, 0.705421566963195800f, 0.455853015184402470f, - 0.706819176673889160f, 0.455220639705657960f, - 0.708214759826660160f, 0.454584002494812010f, 0.709608435630798340f, - 0.453943043947219850f, 0.711000144481658940f, 0.453297853469848630f, - 0.712389826774597170f, 0.452648371458053590f, - 0.713777542114257810f, 0.451994657516479490f, 0.715163230895996090f, - 0.451336652040481570f, 0.716546893119812010f, 0.450674414634704590f, - 0.717928528785705570f, 0.450007945299148560f, - 0.719308137893676760f, 0.449337244033813480f, 0.720685660839080810f, - 0.448662281036376950f, 0.722061097621917720f, 0.447983115911483760f, - 0.723434448242187500f, 0.447299748659133910f, - 0.724805653095245360f, 0.446612149477005000f, 0.726174771785736080f, - 0.445920348167419430f, 0.727541804313659670f, 0.445224374532699580f, - 0.728906631469726560f, 0.444524168968200680f, - 0.730269372463226320f, 0.443819820880889890f, 0.731629908084869380f, - 0.443111270666122440f, 0.732988238334655760f, 0.442398548126220700f, - 0.734344422817230220f, 0.441681683063507080f, - 0.735698342323303220f, 0.440960645675659180f, 0.737050116062164310f, - 0.440235435962677000f, 0.738399624824523930f, 0.439506113529205320f, - 0.739746868610382080f, 0.438772648572921750f, - 0.741091907024383540f, 0.438035041093826290f, 0.742434620857238770f, - 0.437293320894241330f, 0.743775069713592530f, 0.436547487974166870f, - 0.745113253593444820f, 0.435797542333602910f, - 0.746449112892150880f, 0.435043483972549440f, 0.747782647609710690f, - 0.434285342693328860f, 0.749113857746124270f, 0.433523118495941160f, - 0.750442683696746830f, 0.432756811380386350f, - 0.751769185066223140f, 0.431986421346664430f, 0.753093302249908450f, - 0.431211978197097780f, 0.754415094852447510f, 0.430433481931686400f, - 0.755734443664550780f, 0.429650902748107910f, - 0.757051348686218260f, 0.428864300251007080f, 0.758365929126739500f, - 0.428073674440383910f, 0.759678006172180180f, 0.427278995513916020f, - 0.760987639427185060f, 0.426480293273925780f, - 0.762294828891754150f, 0.425677597522735600f, 0.763599574565887450f, - 0.424870878458023070f, 0.764901816844940190f, 0.424060165882110600f, - 0.766201555728912350f, 0.423245459794998170f, - 0.767498791217803960f, 0.422426789999008180f, 0.768793523311614990f, - 0.421604126691818240f, 0.770085752010345460f, 0.420777499675750730f, - 0.771375417709350590f, 0.419946908950805660f, - 0.772662520408630370f, 0.419112354516983030f, 0.773947000503540040f, - 0.418273866176605220f, 0.775228977203369140f, 0.417431443929672240f, - 0.776508331298828130f, 0.416585087776184080f, - 0.777785122394561770f, 0.415734797716140750f, 0.779059290885925290f, - 0.414880603551864620f, 0.780330777168273930f, 0.414022535085678100f, - 0.781599700450897220f, 0.413160532712936400f, - 0.782865881919860840f, 0.412294656038284300f, 0.784129500389099120f, - 0.411424905061721800f, 0.785390377044677730f, 0.410551249980926510f, - 0.786648571491241460f, 0.409673750400543210f, - 0.787904083728790280f, 0.408792406320571900f, 0.789156913757324220f, - 0.407907217741012570f, 0.790407001972198490f, 0.407018154859542850f, - 0.791654348373413090f, 0.406125307083129880f, - 0.792898952960968020f, 0.405228585004806520f, 0.794140756130218510f, - 0.404328078031539920f, 0.795379877090454100f, 0.403423786163330080f, - 0.796616137027740480f, 0.402515679597854610f, - 0.797849655151367190f, 0.401603758335113530f, 0.799080371856689450f, - 0.400688081979751590f, 0.800308227539062500f, 0.399768620729446410f, - 0.801533281803131100f, 0.398845434188842770f, - 0.802755534648895260f, 0.397918462753295900f, 0.803974866867065430f, - 0.396987736225128170f, 0.805191397666931150f, 0.396053284406661990f, - 0.806405067443847660f, 0.395115107297897340f, - 0.807615816593170170f, 0.394173204898834230f, 0.808823645114898680f, - 0.393227607011795040f, 0.810028612613677980f, 0.392278283834457400f, - 0.811230659484863280f, 0.391325294971466060f, - 0.812429726123809810f, 0.390368610620498660f, 0.813625931739807130f, - 0.389408260583877560f, 0.814819097518920900f, 0.388444244861602780f, - 0.816009342670440670f, 0.387476563453674320f, - 0.817196667194366460f, 0.386505216360092160f, 0.818380951881408690f, - 0.385530263185501100f, 0.819562196731567380f, 0.384551674127578740f, - 0.820740520954132080f, 0.383569449186325070f, - 0.821915745735168460f, 0.382583618164062500f, 0.823087990283966060f, - 0.381594210863113400f, 0.824257194995880130f, 0.380601197481155400f, - 0.825423359870910640f, 0.379604607820510860f, - 0.826586425304412840f, 0.378604412078857420f, 0.827746450901031490f, - 0.377600699663162230f, 0.828903317451477050f, 0.376593410968780520f, - 0.830057144165039060f, 0.375582575798034670f, - 0.831207871437072750f, 0.374568194150924680f, 0.832355499267578130f, - 0.373550295829772950f, 0.833499968051910400f, 0.372528880834579470f, - 0.834641277790069580f, 0.371503978967666630f, - 0.835779488086700440f, 0.370475560426712040f, 0.836914479732513430f, - 0.369443655014038090f, 0.838046371936798100f, 0.368408292531967160f, - 0.839175045490264890f, 0.367369443178176880f, - 0.840300500392913820f, 0.366327136754989620f, 0.841422796249389650f, - 0.365281373262405400f, 0.842541813850402830f, 0.364232182502746580f, - 0.843657672405242920f, 0.363179564476013180f, - 0.844770252704620360f, 0.362123548984527590f, 0.845879614353179930f, - 0.361064106225967410f, 0.846985757350921630f, 0.360001266002655030f, - 0.848088562488555910f, 0.358935028314590450f, - 0.849188148975372310f, 0.357865422964096070f, 0.850284397602081300f, - 0.356792420148849490f, 0.851377367973327640f, 0.355716109275817870f, - 0.852467060089111330f, 0.354636400938034060f, - 0.853553414344787600f, 0.353553384542465210f, 0.854636430740356450f, - 0.352467030286788940f, 0.855716109275817870f, 0.351377367973327640f, - 0.856792449951171880f, 0.350284397602081300f, - 0.857865393161773680f, 0.349188119173049930f, 0.858934998512268070f, - 0.348088562488555910f, 0.860001266002655030f, 0.346985727548599240f, - 0.861064076423645020f, 0.345879614353179930f, - 0.862123548984527590f, 0.344770282506942750f, 0.863179564476013180f, - 0.343657672405242920f, 0.864232182502746580f, 0.342541843652725220f, - 0.865281403064727780f, 0.341422766447067260f, - 0.866327106952667240f, 0.340300500392913820f, 0.867369413375854490f, - 0.339175015687942500f, 0.868408262729644780f, 0.338046342134475710f, - 0.869443655014038090f, 0.336914509534835820f, - 0.870475590229034420f, 0.335779488086700440f, 0.871503949165344240f, - 0.334641307592391970f, 0.872528910636901860f, 0.333499968051910400f, - 0.873550295829772950f, 0.332355499267578130f, - 0.874568223953247070f, 0.331207901239395140f, 0.875582575798034670f, - 0.330057173967361450f, 0.876593410968780520f, 0.328903347253799440f, - 0.877600669860839840f, 0.327746421098709110f, - 0.878604412078857420f, 0.326586425304412840f, 0.879604578018188480f, - 0.325423330068588260f, 0.880601167678833010f, 0.324257194995880130f, - 0.881594181060791020f, 0.323088020086288450f, - 0.882583618164062500f, 0.321915775537490840f, 0.883569478988647460f, - 0.320740520954132080f, 0.884551644325256350f, 0.319562226533889770f, - 0.885530233383178710f, 0.318380922079086300f, - 0.886505246162414550f, 0.317196637392044070f, 0.887476563453674320f, - 0.316009372472763060f, 0.888444244861602780f, 0.314819127321243290f, - 0.889408230781555180f, 0.313625901937484740f, - 0.890368640422821040f, 0.312429755926132200f, 0.891325294971466060f, - 0.311230629682540890f, 0.892278313636779790f, 0.310028612613677980f, - 0.893227577209472660f, 0.308823645114898680f, - 0.894173204898834230f, 0.307615786790847780f, 0.895115137100219730f, - 0.306405037641525270f, 0.896053314208984380f, 0.305191397666931150f, - 0.896987736225128170f, 0.303974896669387820f, - 0.897918462753295900f, 0.302755534648895260f, 0.898845434188842770f, - 0.301533311605453490f, 0.899768650531768800f, 0.300308227539062500f, - 0.900688111782073970f, 0.299080342054367070f, - 0.901603758335113530f, 0.297849655151367190f, 0.902515649795532230f, - 0.296616137027740480f, 0.903423786163330080f, 0.295379847288131710f, - 0.904328107833862300f, 0.294140785932540890f, - 0.905228614807128910f, 0.292898923158645630f, 0.906125307083129880f, - 0.291654318571090700f, 0.907018184661865230f, 0.290406972169876100f, - 0.907907187938690190f, 0.289156883955001830f, - 0.908792436122894290f, 0.287904083728790280f, 0.909673750400543210f, - 0.286648571491241460f, 0.910551249980926510f, 0.285390377044677730f, - 0.911424875259399410f, 0.284129470586776730f, - 0.912294626235961910f, 0.282865911722183230f, 0.913160502910614010f, - 0.281599670648574830f, 0.914022505283355710f, 0.280330777168273930f, - 0.914880633354187010f, 0.279059261083602910f, - 0.915734827518463130f, 0.277785122394561770f, 0.916585087776184080f, - 0.276508361101150510f, 0.917431414127349850f, 0.275228977203369140f, - 0.918273866176605220f, 0.273947030305862430f, - 0.919112324714660640f, 0.272662490606307980f, 0.919946908950805660f, - 0.271375387907028200f, 0.920777499675750730f, 0.270085722208023070f, - 0.921604096889495850f, 0.268793523311614990f, - 0.922426760196685790f, 0.267498821020126340f, 0.923245489597320560f, - 0.266201555728912350f, 0.924060165882110600f, 0.264901816844940190f, - 0.924870908260345460f, 0.263599574565887450f, - 0.925677597522735600f, 0.262294828891754150f, 0.926480293273925780f, - 0.260987639427185060f, 0.927278995513916020f, 0.259678006172180180f, - 0.928073644638061520f, 0.258365899324417110f, - 0.928864300251007080f, 0.257051378488540650f, 0.929650902748107910f, - 0.255734413862228390f, 0.930433452129364010f, 0.254415065050125120f, - 0.931211948394775390f, 0.253093332052230830f, - 0.931986451148986820f, 0.251769185066223140f, 0.932756841182708740f, - 0.250442683696746830f, 0.933523118495941160f, 0.249113827943801880f, - 0.934285342693328860f, 0.247782632708549500f, - 0.935043513774871830f, 0.246449097990989690f, 0.935797572135925290f, - 0.245113238692283630f, 0.936547517776489260f, 0.243775084614753720f, - 0.937293350696563720f, 0.242434620857238770f, - 0.938035070896148680f, 0.241091892123222350f, 0.938772618770599370f, - 0.239746883511543270f, 0.939506113529205320f, 0.238399609923362730f, - 0.940235435962677000f, 0.237050101161003110f, - 0.940960645675659180f, 0.235698372125625610f, 0.941681683063507080f, - 0.234344407916069030f, 0.942398548126220700f, 0.232988253235816960f, - 0.943111240863800050f, 0.231629893183708190f, - 0.943819820880889890f, 0.230269357562065120f, 0.944524168968200680f, - 0.228906646370887760f, 0.945224344730377200f, 0.227541789412498470f, - 0.945920348167419430f, 0.226174786686897280f, - 0.946612179279327390f, 0.224805667996406560f, 0.947299718856811520f, - 0.223434418439865110f, 0.947983145713806150f, 0.222061067819595340f, - 0.948662281036376950f, 0.220685631036758420f, - 0.949337244033813480f, 0.219308122992515560f, 0.950007975101470950f, - 0.217928543686866760f, 0.950674414634704590f, 0.216546908020973210f, - 0.951336681842803960f, 0.215163245797157290f, - 0.951994657516479490f, 0.213777542114257810f, 0.952648401260375980f, - 0.212389841675758360f, 0.953297853469848630f, 0.211000129580497740f, - 0.953943073749542240f, 0.209608450531959530f, - 0.954584002494812010f, 0.208214774727821350f, 0.955220639705657960f, - 0.206819161772727970f, 0.955853044986724850f, 0.205421581864356990f, - 0.956481099128723140f, 0.204022079706192020f, - 0.957104861736297610f, 0.202620655298233030f, 0.957724332809448240f, - 0.201217323541641240f, 0.958339512348175050f, 0.199812099337577820f, - 0.958950400352478030f, 0.198404997587203980f, - 0.959556937217712400f, 0.196996018290519710f, 0.960159122943878170f, - 0.195585191249847410f, 0.960757017135620120f, 0.194172516465187070f, - 0.961350560188293460f, 0.192758023738861080f, - 0.961939752101898190f, 0.191341713070869450f, 0.962524592876434330f, - 0.189923599362373350f, 0.963105142116546630f, 0.188503712415695190f, - 0.963681280612945560f, 0.187082037329673770f, - 0.964253067970275880f, 0.185658603906631470f, 0.964820444583892820f, - 0.184233412146568300f, 0.965383470058441160f, 0.182806491851806640f, - 0.965942144393920900f, 0.181377857923507690f, - 0.966496407985687260f, 0.179947525262832640f, 0.967046260833740230f, - 0.178515478968620300f, 0.967591762542724610f, 0.177081763744354250f, - 0.968132853507995610f, 0.175646379590034480f, - 0.968669533729553220f, 0.174209341406822200f, 0.969201743602752690f, - 0.172770664095878600f, 0.969729602336883540f, 0.171330362558364870f, - 0.970253050327301030f, 0.169888436794281010f, - 0.970772027969360350f, 0.168444931507110600f, 0.971286594867706300f, - 0.166999831795692440f, 0.971796751022338870f, 0.165553152561187740f, - 0.972302436828613280f, 0.164104923605918880f, - 0.972803652286529540f, 0.162655144929885860f, 0.973300457000732420f, - 0.161203846335411070f, 0.973792791366577150f, 0.159751012921333310f, - 0.974280655384063720f, 0.158296689391136170f, - 0.974764108657836910f, 0.156840875744819640f, 0.975243031978607180f, - 0.155383571982383730f, 0.975717484951019290f, 0.153924822807312010f, - 0.976187527179718020f, 0.152464613318443300f, - 0.976653039455413820f, 0.151002973318099980f, 0.977114021778106690f, - 0.149539917707443240f, 0.977570593357086180f, 0.148075446486473080f, - 0.978022634983062740f, 0.146609574556350710f, - 0.978470146656036380f, 0.145142331719398500f, 0.978913187980651860f, - 0.143673732876777650f, 0.979351758956909180f, 0.142203763127326970f, - 0.979785740375518800f, 0.140732467174530030f, - 0.980215251445770260f, 0.139259845018386840f, 0.980640232563018800f, - 0.137785911560058590f, 0.981060683727264400f, 0.136310681700706480f, - 0.981476604938507080f, 0.134834155440330510f, - 0.981888055801391600f, 0.133356377482414250f, 0.982294917106628420f, - 0.131877332925796510f, 0.982697248458862300f, 0.130397051572799680f, - 0.983094990253448490f, 0.128915548324584960f, - 0.983488261699676510f, 0.127432823181152340f, 0.983876943588256840f, - 0.125948905944824220f, 0.984261035919189450f, 0.124463804066181180f, - 0.984640598297119140f, 0.122977524995803830f, - 0.985015630722045900f, 0.121490091085433960f, 0.985386073589324950f, - 0.120001509785652160f, 0.985751926898956300f, 0.118511803448200230f, - 0.986113250255584720f, 0.117020979523658750f, - 0.986469984054565430f, 0.115529052913188930f, 0.986822128295898440f, - 0.114036038517951970f, 0.987169682979583740f, 0.112541958689689640f, - 0.987512648105621340f, 0.111046813428401950f, - 0.987851083278656010f, 0.109550617635250090f, 0.988184869289398190f, - 0.108053401112556460f, 0.988514065742492680f, 0.106555156409740450f, - 0.988838672637939450f, 0.105055920779705050f, - 0.989158689975738530f, 0.103555686771869660f, 0.989474058151245120f, - 0.102054484188556670f, 0.989784896373748780f, 0.100552320480346680f, - 0.990091085433959960f, 0.099049203097820282f, - 0.990392625331878660f, 0.097545161843299866f, 0.990689575672149660f, - 0.096040196716785431f, 0.990981936454772950f, 0.094534330070018768f, - 0.991269648075103760f, 0.093027576804161072f, - 0.991552770137786870f, 0.091519944369792938f, 0.991831183433532710f, - 0.090011447668075562f, 0.992105066776275630f, 0.088502109050750732f, - 0.992374241352081300f, 0.086991935968399048f, - 0.992638826370239260f, 0.085480943322181702f, 0.992898762226104740f, - 0.083969146013259888f, 0.993154048919677730f, 0.082456558942794800f, - 0.993404686450958250f, 0.080943197011947632f, - 0.993650734424591060f, 0.079429075121879578f, 0.993892073631286620f, - 0.077914200723171234f, 0.994128763675689700f, 0.076398596167564392f, - 0.994360864162445070f, 0.074882268905639648f, - 0.994588255882263180f, 0.073365233838558197f, 0.994810998439788820f, - 0.071847513318061829f, 0.995029091835021970f, 0.070329122245311737f, - 0.995242536067962650f, 0.068810060620307922f, - 0.995451331138610840f, 0.067290350794792175f, 0.995655417442321780f, - 0.065770015120506287f, 0.995854854583740230f, 0.064249053597450256f, - 0.996049642562866210f, 0.062727488577365875f, - 0.996239781379699710f, 0.061205338686704636f, 0.996425211429595950f, - 0.059682607650756836f, 0.996605992317199710f, 0.058159314095973969f, - 0.996782064437866210f, 0.056635476648807526f, - 0.996953487396240230f, 0.055111102759838104f, 0.997120201587677000f, - 0.053586211055517197f, 0.997282266616821290f, 0.052060816437005997f, - 0.997439682483673100f, 0.050534930080175400f, - 0.997592389583587650f, 0.049008570611476898f, 0.997740387916564940f, - 0.047481749206781387f, 0.997883677482604980f, 0.045954477041959763f, - 0.998022377490997310f, 0.044426776468753815f, - 0.998156309127807620f, 0.042898654937744141f, 0.998285591602325440f, - 0.041370131075382233f, 0.998410165309906010f, 0.039841219782829285f, - 0.998530030250549320f, 0.038311932235956192f, - 0.998645246028900150f, 0.036782283335924149f, 0.998755753040313720f, - 0.035252287983894348f, 0.998861551284790040f, 0.033721961081027985f, - 0.998962640762329100f, 0.032191313803195953f, - 0.999059081077575680f, 0.030660368502140045f, 0.999150753021240230f, - 0.029129132628440857f, 0.999237775802612300f, 0.027597622945904732f, - 0.999320089817047120f, 0.026065852493047714f, - 0.999397754669189450f, 0.024533838033676147f, 0.999470651149749760f, - 0.023001590743660927f, 0.999538838863372800f, 0.021469129249453545f, - 0.999602377414703370f, 0.019936462864279747f, - 0.999661207199096680f, 0.018403612077236176f, 0.999715328216552730f, - 0.016870586201548576f, 0.999764680862426760f, 0.015337402001023293f, - 0.999809384346008300f, 0.013804072514176369f, - 0.999849438667297360f, 0.012270614504814148f, 0.999884724617004390f, - 0.010737040080130100f, 0.999915301799774170f, 0.009203365072607994f, - 0.999941170215606690f, 0.007669602986425161f, - 0.999962329864501950f, 0.006135769188404083f, 0.999978840351104740f, - 0.004601877182722092f, 0.999990582466125490f, 0.003067942336201668f, - 0.999997675418853760f, 0.001533978385850787f, - 1.000000000000000000f, 0.000000000000023345f, 0.999997675418853760f, - -0.001533978385850787f, 0.999990582466125490f, -0.003067942336201668f, - 0.999978840351104740f, -0.004601877182722092f, - 0.999962329864501950f, -0.006135769188404083f, 0.999941170215606690f, - -0.007669602986425161f, 0.999915301799774170f, -0.009203365072607994f, - 0.999884724617004390f, -0.010737040080130100f, - 0.999849438667297360f, -0.012270614504814148f, 0.999809384346008300f, - -0.013804072514176369f, 0.999764680862426760f, -0.015337402001023293f, - 0.999715328216552730f, -0.016870586201548576f, - 0.999661207199096680f, -0.018403612077236176f, 0.999602377414703370f, - -0.019936462864279747f, 0.999538838863372800f, -0.021469129249453545f, - 0.999470651149749760f, -0.023001590743660927f, - 0.999397754669189450f, -0.024533838033676147f, 0.999320089817047120f, - -0.026065852493047714f, 0.999237775802612300f, -0.027597622945904732f, - 0.999150753021240230f, -0.029129132628440857f, - 0.999059081077575680f, -0.030660368502140045f, 0.998962640762329100f, - -0.032191313803195953f, 0.998861551284790040f, -0.033721961081027985f, - 0.998755753040313720f, -0.035252287983894348f, - 0.998645246028900150f, -0.036782283335924149f, 0.998530030250549320f, - -0.038311932235956192f, 0.998410165309906010f, -0.039841219782829285f, - 0.998285591602325440f, -0.041370131075382233f, - 0.998156309127807620f, -0.042898654937744141f, 0.998022377490997310f, - -0.044426776468753815f, 0.997883677482604980f, -0.045954477041959763f, - 0.997740387916564940f, -0.047481749206781387f, - 0.997592389583587650f, -0.049008570611476898f, 0.997439682483673100f, - -0.050534930080175400f, 0.997282266616821290f, -0.052060816437005997f, - 0.997120201587677000f, -0.053586211055517197f, - 0.996953487396240230f, -0.055111102759838104f, 0.996782064437866210f, - -0.056635476648807526f, 0.996605992317199710f, -0.058159314095973969f, - 0.996425211429595950f, -0.059682607650756836f, - 0.996239781379699710f, -0.061205338686704636f, 0.996049642562866210f, - -0.062727488577365875f, 0.995854854583740230f, -0.064249053597450256f, - 0.995655417442321780f, -0.065770015120506287f, - 0.995451331138610840f, -0.067290350794792175f, 0.995242536067962650f, - -0.068810060620307922f, 0.995029091835021970f, -0.070329122245311737f, - 0.994810998439788820f, -0.071847513318061829f, - 0.994588255882263180f, -0.073365233838558197f, 0.994360864162445070f, - -0.074882268905639648f, 0.994128763675689700f, -0.076398596167564392f, - 0.993892073631286620f, -0.077914200723171234f, - 0.993650734424591060f, -0.079429075121879578f, 0.993404686450958250f, - -0.080943197011947632f, 0.993154048919677730f, -0.082456558942794800f, - 0.992898762226104740f, -0.083969146013259888f, - 0.992638826370239260f, -0.085480943322181702f, 0.992374241352081300f, - -0.086991935968399048f, 0.992105066776275630f, -0.088502109050750732f, - 0.991831183433532710f, -0.090011447668075562f, - 0.991552770137786870f, -0.091519944369792938f, 0.991269648075103760f, - -0.093027576804161072f, 0.990981936454772950f, -0.094534330070018768f, - 0.990689575672149660f, -0.096040196716785431f, - 0.990392625331878660f, -0.097545161843299866f, 0.990091085433959960f, - -0.099049203097820282f, 0.989784896373748780f, -0.100552320480346680f, - 0.989474058151245120f, -0.102054484188556670f, - 0.989158689975738530f, -0.103555686771869660f, 0.988838672637939450f, - -0.105055920779705050f, 0.988514065742492680f, -0.106555156409740450f, - 0.988184869289398190f, -0.108053401112556460f, - 0.987851083278656010f, -0.109550617635250090f, 0.987512648105621340f, - -0.111046813428401950f, 0.987169682979583740f, -0.112541958689689640f, - 0.986822128295898440f, -0.114036038517951970f, - 0.986469984054565430f, -0.115529052913188930f, 0.986113250255584720f, - -0.117020979523658750f, 0.985751926898956300f, -0.118511803448200230f, - 0.985386073589324950f, -0.120001509785652160f, - 0.985015630722045900f, -0.121490091085433960f, 0.984640598297119140f, - -0.122977524995803830f, 0.984261035919189450f, -0.124463804066181180f, - 0.983876943588256840f, -0.125948905944824220f, - 0.983488261699676510f, -0.127432823181152340f, 0.983094990253448490f, - -0.128915548324584960f, 0.982697248458862300f, -0.130397051572799680f, - 0.982294917106628420f, -0.131877332925796510f, - 0.981888055801391600f, -0.133356377482414250f, 0.981476604938507080f, - -0.134834155440330510f, 0.981060683727264400f, -0.136310681700706480f, - 0.980640232563018800f, -0.137785911560058590f, - 0.980215251445770260f, -0.139259845018386840f, 0.979785740375518800f, - -0.140732467174530030f, 0.979351758956909180f, -0.142203763127326970f, - 0.978913187980651860f, -0.143673732876777650f, - 0.978470146656036380f, -0.145142331719398500f, 0.978022634983062740f, - -0.146609574556350710f, 0.977570593357086180f, -0.148075446486473080f, - 0.977114021778106690f, -0.149539917707443240f, - 0.976653039455413820f, -0.151002973318099980f, 0.976187527179718020f, - -0.152464613318443300f, 0.975717484951019290f, -0.153924822807312010f, - 0.975243031978607180f, -0.155383571982383730f, - 0.974764108657836910f, -0.156840875744819640f, 0.974280655384063720f, - -0.158296689391136170f, 0.973792791366577150f, -0.159751012921333310f, - 0.973300457000732420f, -0.161203846335411070f, - 0.972803652286529540f, -0.162655144929885860f, 0.972302436828613280f, - -0.164104923605918880f, 0.971796751022338870f, -0.165553152561187740f, - 0.971286594867706300f, -0.166999831795692440f, - 0.970772027969360350f, -0.168444931507110600f, 0.970253050327301030f, - -0.169888436794281010f, 0.969729602336883540f, -0.171330362558364870f, - 0.969201743602752690f, -0.172770664095878600f, - 0.968669533729553220f, -0.174209341406822200f, 0.968132853507995610f, - -0.175646379590034480f, 0.967591762542724610f, -0.177081763744354250f, - 0.967046260833740230f, -0.178515478968620300f, - 0.966496407985687260f, -0.179947525262832640f, 0.965942144393920900f, - -0.181377857923507690f, 0.965383470058441160f, -0.182806491851806640f, - 0.964820444583892820f, -0.184233412146568300f, - 0.964253067970275880f, -0.185658603906631470f, 0.963681280612945560f, - -0.187082037329673770f, 0.963105142116546630f, -0.188503712415695190f, - 0.962524592876434330f, -0.189923599362373350f, - 0.961939752101898190f, -0.191341713070869450f, 0.961350560188293460f, - -0.192758023738861080f, 0.960757017135620120f, -0.194172516465187070f, - 0.960159122943878170f, -0.195585191249847410f, - 0.959556937217712400f, -0.196996018290519710f, 0.958950400352478030f, - -0.198404997587203980f, 0.958339512348175050f, -0.199812099337577820f, - 0.957724332809448240f, -0.201217323541641240f, - 0.957104861736297610f, -0.202620655298233030f, 0.956481099128723140f, - -0.204022079706192020f, 0.955853044986724850f, -0.205421581864356990f, - 0.955220639705657960f, -0.206819161772727970f, - 0.954584002494812010f, -0.208214774727821350f, 0.953943073749542240f, - -0.209608450531959530f, 0.953297853469848630f, -0.211000129580497740f, - 0.952648401260375980f, -0.212389841675758360f, - 0.951994657516479490f, -0.213777542114257810f, 0.951336681842803960f, - -0.215163245797157290f, 0.950674414634704590f, -0.216546908020973210f, - 0.950007975101470950f, -0.217928543686866760f, - 0.949337244033813480f, -0.219308122992515560f, 0.948662281036376950f, - -0.220685631036758420f, 0.947983145713806150f, -0.222061067819595340f, - 0.947299718856811520f, -0.223434418439865110f, - 0.946612179279327390f, -0.224805667996406560f, 0.945920348167419430f, - -0.226174786686897280f, 0.945224344730377200f, -0.227541789412498470f, - 0.944524168968200680f, -0.228906646370887760f, - 0.943819820880889890f, -0.230269357562065120f, 0.943111240863800050f, - -0.231629893183708190f, 0.942398548126220700f, -0.232988253235816960f, - 0.941681683063507080f, -0.234344407916069030f, - 0.940960645675659180f, -0.235698372125625610f, 0.940235435962677000f, - -0.237050101161003110f, 0.939506113529205320f, -0.238399609923362730f, - 0.938772618770599370f, -0.239746883511543270f, - 0.938035070896148680f, -0.241091892123222350f, 0.937293350696563720f, - -0.242434620857238770f, 0.936547517776489260f, -0.243775084614753720f, - 0.935797572135925290f, -0.245113238692283630f, - 0.935043513774871830f, -0.246449097990989690f, 0.934285342693328860f, - -0.247782632708549500f, 0.933523118495941160f, -0.249113827943801880f, - 0.932756841182708740f, -0.250442683696746830f, - 0.931986451148986820f, -0.251769185066223140f, 0.931211948394775390f, - -0.253093332052230830f, 0.930433452129364010f, -0.254415065050125120f, - 0.929650902748107910f, -0.255734413862228390f, - 0.928864300251007080f, -0.257051378488540650f, 0.928073644638061520f, - -0.258365899324417110f, 0.927278995513916020f, -0.259678006172180180f, - 0.926480293273925780f, -0.260987639427185060f, - 0.925677597522735600f, -0.262294828891754150f, 0.924870908260345460f, - -0.263599574565887450f, 0.924060165882110600f, -0.264901816844940190f, - 0.923245489597320560f, -0.266201555728912350f, - 0.922426760196685790f, -0.267498821020126340f, 0.921604096889495850f, - -0.268793523311614990f, 0.920777499675750730f, -0.270085722208023070f, - 0.919946908950805660f, -0.271375387907028200f, - 0.919112324714660640f, -0.272662490606307980f, 0.918273866176605220f, - -0.273947030305862430f, 0.917431414127349850f, -0.275228977203369140f, - 0.916585087776184080f, -0.276508361101150510f, - 0.915734827518463130f, -0.277785122394561770f, 0.914880633354187010f, - -0.279059261083602910f, 0.914022505283355710f, -0.280330777168273930f, - 0.913160502910614010f, -0.281599670648574830f, - 0.912294626235961910f, -0.282865911722183230f, 0.911424875259399410f, - -0.284129470586776730f, 0.910551249980926510f, -0.285390377044677730f, - 0.909673750400543210f, -0.286648571491241460f, - 0.908792436122894290f, -0.287904083728790280f, 0.907907187938690190f, - -0.289156883955001830f, 0.907018184661865230f, -0.290406972169876100f, - 0.906125307083129880f, -0.291654318571090700f, - 0.905228614807128910f, -0.292898923158645630f, 0.904328107833862300f, - -0.294140785932540890f, 0.903423786163330080f, -0.295379847288131710f, - 0.902515649795532230f, -0.296616137027740480f, - 0.901603758335113530f, -0.297849655151367190f, 0.900688111782073970f, - -0.299080342054367070f, 0.899768650531768800f, -0.300308227539062500f, - 0.898845434188842770f, -0.301533311605453490f, - 0.897918462753295900f, -0.302755534648895260f, 0.896987736225128170f, - -0.303974896669387820f, 0.896053314208984380f, -0.305191397666931150f, - 0.895115137100219730f, -0.306405037641525270f, - 0.894173204898834230f, -0.307615786790847780f, 0.893227577209472660f, - -0.308823645114898680f, 0.892278313636779790f, -0.310028612613677980f, - 0.891325294971466060f, -0.311230629682540890f, - 0.890368640422821040f, -0.312429755926132200f, 0.889408230781555180f, - -0.313625901937484740f, 0.888444244861602780f, -0.314819127321243290f, - 0.887476563453674320f, -0.316009372472763060f, - 0.886505246162414550f, -0.317196637392044070f, 0.885530233383178710f, - -0.318380922079086300f, 0.884551644325256350f, -0.319562226533889770f, - 0.883569478988647460f, -0.320740520954132080f, - 0.882583618164062500f, -0.321915775537490840f, 0.881594181060791020f, - -0.323088020086288450f, 0.880601167678833010f, -0.324257194995880130f, - 0.879604578018188480f, -0.325423330068588260f, - 0.878604412078857420f, -0.326586425304412840f, 0.877600669860839840f, - -0.327746421098709110f, 0.876593410968780520f, -0.328903347253799440f, - 0.875582575798034670f, -0.330057173967361450f, - 0.874568223953247070f, -0.331207901239395140f, 0.873550295829772950f, - -0.332355499267578130f, 0.872528910636901860f, -0.333499968051910400f, - 0.871503949165344240f, -0.334641307592391970f, - 0.870475590229034420f, -0.335779488086700440f, 0.869443655014038090f, - -0.336914509534835820f, 0.868408262729644780f, -0.338046342134475710f, - 0.867369413375854490f, -0.339175015687942500f, - 0.866327106952667240f, -0.340300500392913820f, 0.865281403064727780f, - -0.341422766447067260f, 0.864232182502746580f, -0.342541843652725220f, - 0.863179564476013180f, -0.343657672405242920f, - 0.862123548984527590f, -0.344770282506942750f, 0.861064076423645020f, - -0.345879614353179930f, 0.860001266002655030f, -0.346985727548599240f, - 0.858934998512268070f, -0.348088562488555910f, - 0.857865393161773680f, -0.349188119173049930f, 0.856792449951171880f, - -0.350284397602081300f, 0.855716109275817870f, -0.351377367973327640f, - 0.854636430740356450f, -0.352467030286788940f, - 0.853553414344787600f, -0.353553384542465210f, 0.852467060089111330f, - -0.354636400938034060f, 0.851377367973327640f, -0.355716109275817870f, - 0.850284397602081300f, -0.356792420148849490f, - 0.849188148975372310f, -0.357865422964096070f, 0.848088562488555910f, - -0.358935028314590450f, 0.846985757350921630f, -0.360001266002655030f, - 0.845879614353179930f, -0.361064106225967410f, - 0.844770252704620360f, -0.362123548984527590f, 0.843657672405242920f, - -0.363179564476013180f, 0.842541813850402830f, -0.364232182502746580f, - 0.841422796249389650f, -0.365281373262405400f, - 0.840300500392913820f, -0.366327136754989620f, 0.839175045490264890f, - -0.367369443178176880f, 0.838046371936798100f, -0.368408292531967160f, - 0.836914479732513430f, -0.369443655014038090f, - 0.835779488086700440f, -0.370475560426712040f, 0.834641277790069580f, - -0.371503978967666630f, 0.833499968051910400f, -0.372528880834579470f, - 0.832355499267578130f, -0.373550295829772950f, - 0.831207871437072750f, -0.374568194150924680f, 0.830057144165039060f, - -0.375582575798034670f, 0.828903317451477050f, -0.376593410968780520f, - 0.827746450901031490f, -0.377600699663162230f, - 0.826586425304412840f, -0.378604412078857420f, 0.825423359870910640f, - -0.379604607820510860f, 0.824257194995880130f, -0.380601197481155400f, - 0.823087990283966060f, -0.381594210863113400f, - 0.821915745735168460f, -0.382583618164062500f, 0.820740520954132080f, - -0.383569449186325070f, 0.819562196731567380f, -0.384551674127578740f, - 0.818380951881408690f, -0.385530263185501100f, - 0.817196667194366460f, -0.386505216360092160f, 0.816009342670440670f, - -0.387476563453674320f, 0.814819097518920900f, -0.388444244861602780f, - 0.813625931739807130f, -0.389408260583877560f, - 0.812429726123809810f, -0.390368610620498660f, 0.811230659484863280f, - -0.391325294971466060f, 0.810028612613677980f, -0.392278283834457400f, - 0.808823645114898680f, -0.393227607011795040f, - 0.807615816593170170f, -0.394173204898834230f, 0.806405067443847660f, - -0.395115107297897340f, 0.805191397666931150f, -0.396053284406661990f, - 0.803974866867065430f, -0.396987736225128170f, - 0.802755534648895260f, -0.397918462753295900f, 0.801533281803131100f, - -0.398845434188842770f, 0.800308227539062500f, -0.399768620729446410f, - 0.799080371856689450f, -0.400688081979751590f, - 0.797849655151367190f, -0.401603758335113530f, 0.796616137027740480f, - -0.402515679597854610f, 0.795379877090454100f, -0.403423786163330080f, - 0.794140756130218510f, -0.404328078031539920f, - 0.792898952960968020f, -0.405228585004806520f, 0.791654348373413090f, - -0.406125307083129880f, 0.790407001972198490f, -0.407018154859542850f, - 0.789156913757324220f, -0.407907217741012570f, - 0.787904083728790280f, -0.408792406320571900f, 0.786648571491241460f, - -0.409673750400543210f, 0.785390377044677730f, -0.410551249980926510f, - 0.784129500389099120f, -0.411424905061721800f, - 0.782865881919860840f, -0.412294656038284300f, 0.781599700450897220f, - -0.413160532712936400f, 0.780330777168273930f, -0.414022535085678100f, - 0.779059290885925290f, -0.414880603551864620f, - 0.777785122394561770f, -0.415734797716140750f, 0.776508331298828130f, - -0.416585087776184080f, 0.775228977203369140f, -0.417431443929672240f, - 0.773947000503540040f, -0.418273866176605220f, - 0.772662520408630370f, -0.419112354516983030f, 0.771375417709350590f, - -0.419946908950805660f, 0.770085752010345460f, -0.420777499675750730f, - 0.768793523311614990f, -0.421604126691818240f, - 0.767498791217803960f, -0.422426789999008180f, 0.766201555728912350f, - -0.423245459794998170f, 0.764901816844940190f, -0.424060165882110600f, - 0.763599574565887450f, -0.424870878458023070f, - 0.762294828891754150f, -0.425677597522735600f, 0.760987639427185060f, - -0.426480293273925780f, 0.759678006172180180f, -0.427278995513916020f, - 0.758365929126739500f, -0.428073674440383910f, - 0.757051348686218260f, -0.428864300251007080f, 0.755734443664550780f, - -0.429650902748107910f, 0.754415094852447510f, -0.430433481931686400f, - 0.753093302249908450f, -0.431211978197097780f, - 0.751769185066223140f, -0.431986421346664430f, 0.750442683696746830f, - -0.432756811380386350f, 0.749113857746124270f, -0.433523118495941160f, - 0.747782647609710690f, -0.434285342693328860f, - 0.746449112892150880f, -0.435043483972549440f, 0.745113253593444820f, - -0.435797542333602910f, 0.743775069713592530f, -0.436547487974166870f, - 0.742434620857238770f, -0.437293320894241330f, - 0.741091907024383540f, -0.438035041093826290f, 0.739746868610382080f, - -0.438772648572921750f, 0.738399624824523930f, -0.439506113529205320f, - 0.737050116062164310f, -0.440235435962677000f, - 0.735698342323303220f, -0.440960645675659180f, 0.734344422817230220f, - -0.441681683063507080f, 0.732988238334655760f, -0.442398548126220700f, - 0.731629908084869380f, -0.443111270666122440f, - 0.730269372463226320f, -0.443819820880889890f, 0.728906631469726560f, - -0.444524168968200680f, 0.727541804313659670f, -0.445224374532699580f, - 0.726174771785736080f, -0.445920348167419430f, - 0.724805653095245360f, -0.446612149477005000f, 0.723434448242187500f, - -0.447299748659133910f, 0.722061097621917720f, -0.447983115911483760f, - 0.720685660839080810f, -0.448662281036376950f, - 0.719308137893676760f, -0.449337244033813480f, 0.717928528785705570f, - -0.450007945299148560f, 0.716546893119812010f, -0.450674414634704590f, - 0.715163230895996090f, -0.451336652040481570f, - 0.713777542114257810f, -0.451994657516479490f, 0.712389826774597170f, - -0.452648371458053590f, 0.711000144481658940f, -0.453297853469848630f, - 0.709608435630798340f, -0.453943043947219850f, - 0.708214759826660160f, -0.454584002494812010f, 0.706819176673889160f, - -0.455220639705657960f, 0.705421566963195800f, -0.455853015184402470f, - 0.704022109508514400f, -0.456481099128723140f, - 0.702620685100555420f, -0.457104891538620000f, 0.701217353343963620f, - -0.457724362611770630f, 0.699812114238739010f, -0.458339542150497440f, - 0.698404967784881590f, -0.458950400352478030f, - 0.696996033191680910f, -0.459556937217712400f, 0.695585191249847410f, - -0.460159152746200560f, 0.694172501564025880f, -0.460757017135620120f, - 0.692758023738861080f, -0.461350560188293460f, - 0.691341698169708250f, -0.461939752101898190f, 0.689923584461212160f, - -0.462524622678756710f, 0.688503682613372800f, -0.463105112314224240f, - 0.687082052230834960f, -0.463681250810623170f, - 0.685658574104309080f, -0.464253038167953490f, 0.684233427047729490f, - -0.464820444583892820f, 0.682806491851806640f, -0.465383470058441160f, - 0.681377887725830080f, -0.465942144393920900f, - 0.679947495460510250f, -0.466496407985687260f, 0.678515493869781490f, - -0.467046260833740230f, 0.677081763744354250f, -0.467591762542724610f, - 0.675646364688873290f, -0.468132823705673220f, - 0.674209356307983400f, -0.468669503927230830f, 0.672770678997039790f, - -0.469201773405075070f, 0.671330332756042480f, -0.469729602336883540f, - 0.669888436794281010f, -0.470253020524978640f, - 0.668444931507110600f, -0.470772027969360350f, 0.666999816894531250f, - -0.471286594867706300f, 0.665553152561187740f, -0.471796721220016480f, - 0.664104938507080080f, -0.472302407026290890f, - 0.662655174732208250f, -0.472803652286529540f, 0.661203861236572270f, - -0.473300457000732420f, 0.659750998020172120f, -0.473792791366577150f, - 0.658296704292297360f, -0.474280685186386110f, - 0.656840860843658450f, -0.474764078855514530f, 0.655383586883544920f, - -0.475243031978607180f, 0.653924822807312010f, -0.475717514753341670f, - 0.652464628219604490f, -0.476187497377395630f, - 0.651003003120422360f, -0.476653009653091430f, 0.649539887905120850f, - -0.477114051580429080f, 0.648075461387634280f, -0.477570593357086180f, - 0.646609604358673100f, -0.478022634983062740f, - 0.645142316818237300f, -0.478470176458358760f, 0.643673717975616460f, - -0.478913217782974240f, 0.642203748226165770f, -0.479351729154586790f, - 0.640732467174530030f, -0.479785770177841190f, - 0.639259815216064450f, -0.480215251445770260f, 0.637785911560058590f, - -0.480640232563018800f, 0.636310696601867680f, -0.481060713529586790f, - 0.634834170341491700f, -0.481476634740829470f, - 0.633356392383575440f, -0.481888025999069210f, 0.631877362728118900f, - -0.482294887304306030f, 0.630397081375122070f, -0.482697218656539920f, - 0.628915548324584960f, -0.483094990253448490f, - 0.627432823181152340f, -0.483488231897354130f, 0.625948905944824220f, - -0.483876913785934450f, 0.624463796615600590f, -0.484261035919189450f, - 0.622977554798126220f, -0.484640628099441530f, - 0.621490061283111570f, -0.485015630722045900f, 0.620001494884490970f, - -0.485386073589324950f, 0.618511795997619630f, -0.485751956701278690f, - 0.617020964622497560f, -0.486113250255584720f, - 0.615529060363769530f, -0.486469984054565430f, 0.614036023616790770f, - -0.486822128295898440f, 0.612541973590850830f, -0.487169682979583740f, - 0.611046791076660160f, -0.487512677907943730f, - 0.609550595283508300f, -0.487851053476333620f, 0.608053386211395260f, - -0.488184869289398190f, 0.606555163860321040f, -0.488514065742492680f, - 0.605055928230285640f, -0.488838672637939450f, - 0.603555679321289060f, -0.489158689975738530f, 0.602054476737976070f, - -0.489474087953567500f, 0.600552320480346680f, -0.489784896373748780f, - 0.599049210548400880f, -0.490091055631637570f, - 0.597545146942138670f, -0.490392625331878660f, 0.596040189266204830f, - -0.490689605474472050f, 0.594534337520599370f, -0.490981936454772950f, - 0.593027591705322270f, -0.491269648075103760f, - 0.591519951820373540f, -0.491552740335464480f, 0.590011477470397950f, - -0.491831213235855100f, 0.588502109050750730f, -0.492105036973953250f, - 0.586991965770721440f, -0.492374241352081300f, - 0.585480928421020510f, -0.492638826370239260f, 0.583969175815582280f, - -0.492898762226104740f, 0.582456588745117190f, -0.493154048919677730f, - 0.580943167209625240f, -0.493404686450958250f, - 0.579429090023040770f, -0.493650704622268680f, 0.577914178371429440f, - -0.493892073631286620f, 0.576398611068725590f, -0.494128793478012080f, - 0.574882268905639650f, -0.494360834360122680f, - 0.573365211486816410f, -0.494588255882263180f, 0.571847498416900630f, - -0.494810998439788820f, 0.570329129695892330f, -0.495029091835021970f, - 0.568810045719146730f, -0.495242536067962650f, - 0.567290365695953370f, -0.495451331138610840f, 0.565770030021667480f, - -0.495655417442321780f, 0.564249038696289060f, -0.495854884386062620f, - 0.562727510929107670f, -0.496049642562866210f, - 0.561205327510833740f, -0.496239781379699710f, 0.559682607650756840f, - -0.496425211429595950f, 0.558159291744232180f, -0.496605962514877320f, - 0.556635499000549320f, -0.496782064437866210f, - 0.555111110210418700f, -0.496953487396240230f, 0.553586184978485110f, - -0.497120231389999390f, 0.552060842514038090f, -0.497282296419143680f, - 0.550534904003143310f, -0.497439652681350710f, - 0.549008548259735110f, -0.497592359781265260f, 0.547481775283813480f, - -0.497740387916564940f, 0.545954465866088870f, -0.497883707284927370f, - 0.544426798820495610f, -0.498022347688674930f, - 0.542898654937744140f, -0.498156309127807620f, 0.541370153427124020f, - -0.498285561800003050f, 0.539841234683990480f, -0.498410135507583620f, - 0.538311958312988280f, -0.498530030250549320f, - 0.536782264709472660f, -0.498645216226577760f, 0.535252273082733150f, - -0.498755723237991330f, 0.533721983432769780f, -0.498861521482467650f, - 0.532191336154937740f, -0.498962640762329100f, - 0.530660390853881840f, -0.499059051275253300f, 0.529129147529602050f, - -0.499150782823562620f, 0.527597606182098390f, -0.499237775802612300f, - 0.526065826416015630f, -0.499320119619369510f, - 0.524533808231353760f, -0.499397724866867070f, 0.523001611232757570f, - -0.499470651149749760f, 0.521469116210937500f, -0.499538868665695190f, - 0.519936442375183110f, -0.499602377414703370f, - 0.518403589725494380f, -0.499661177396774290f, 0.516870558261871340f, - -0.499715298414230350f, 0.515337407588958740f, -0.499764710664749150f, - 0.513804078102111820f, -0.499809414148330690f, - 0.512270629405975340f, -0.499849408864974980f, 0.510737061500549320f, - -0.499884694814682010f, 0.509203374385833740f, -0.499915301799774170f, - 0.507669627666473390f, -0.499941170215606690f, - 0.506135761737823490f, -0.499962359666824340f, 0.504601895809173580f, - -0.499978810548782350f, 0.503067970275878910f, -0.499990582466125490f, - 0.501533985137939450f, -0.499997645616531370f -}; - - - -/** -* @brief Initialization function for the floating-point RFFT/RIFFT. -* @param[in,out] *S points to an instance of the floating-point RFFT/RIFFT structure. -* @param[in,out] *S_CFFT points to an instance of the floating-point CFFT/CIFFT structure. -* @param[in] fftLenReal length of the FFT. -* @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. -* -* \par Description: -* \par -* The parameter fftLenReal Specifies length of RFFT/RIFFT Process. Supported FFT Lengths are 128, 512, 2048. -* \par -* The parameter ifftFlagR controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlagR to calculate RIFFT, otherwise RFFT is calculated. -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* This function also initializes Twiddle factor table. -*/ - -arm_status arm_rfft_init_f32( - arm_rfft_instance_f32 * S, - arm_cfft_radix4_instance_f32 * S_CFFT, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag) -{ - - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialize the Real FFT length */ - S->fftLenReal = (uint16_t) fftLenReal; - - /* Initialize the Complex FFT length */ - S->fftLenBy2 = (uint16_t) fftLenReal / 2u; - - /* Initialize the Twiddle coefficientA pointer */ - S->pTwiddleAReal = (float32_t *) realCoefA; - - /* Initialize the Twiddle coefficientB pointer */ - S->pTwiddleBReal = (float32_t *) realCoefB; - - /* Initialize the Flag for selection of RFFT or RIFFT */ - S->ifftFlagR = (uint8_t) ifftFlagR; - - /* Initialize the Flag for calculation Bit reversal or not */ - S->bitReverseFlagR = (uint8_t) bitReverseFlag; - - /* Initializations of structure parameters depending on the FFT length */ - switch (S->fftLenReal) - { - /* Init table modifier value */ - case 2048u: - S->twidCoefRModifier = 1u; - break; - case 512u: - S->twidCoefRModifier = 4u; - break; - case 128u: - S->twidCoefRModifier = 16u; - break; - default: - /* Reporting argument error if rfftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - /* Init Complex FFT Instance */ - S->pCfft = S_CFFT; - - if(S->ifftFlagR) - { - /* Initializes the CIFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_f32(S->pCfft, S->fftLenBy2, 1u, 0u); - } - else - { - /* Initializes the CFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_f32(S->pCfft, S->fftLenBy2, 0u, 0u); - } - - /* return the status of RFFT Init function */ - return (status); - -} - - /** - * @} end of RFFT_RIFFT group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_rfft_init_f32.c +* +* Description: RFFT & RIFFT Floating point initialisation function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup RFFT_RIFFT + * @{ + */ + +/** +* \par +* Generation of realCoefA array: +* \par +* n = 1024 +*
for (i = 0; i < n; i++)   
+*  {   
+*    pATable[2 * i] = 0.5 * (1.0 - sin (2 * PI / (double) (2 * n) * (double) i));   
+*    pATable[2 * i + 1] = 0.5 * (-1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
+*  } 
+*/ + + + +static const float32_t realCoefA[2048] = { + 0.500000000000000000f, -0.500000000000000000f, 0.498466014862060550f, + -0.499997645616531370f, 0.496932059526443480f, -0.499990582466125490f, + 0.495398133993148800f, -0.499978810548782350f, + 0.493864238262176510f, -0.499962359666824340f, 0.492330402135849000f, + -0.499941170215606690f, 0.490796625614166260f, -0.499915301799774170f, + 0.489262968301773070f, -0.499884694814682010f, + 0.487729400396347050f, -0.499849408864974980f, 0.486195921897888180f, + -0.499809414148330690f, 0.484662592411041260f, -0.499764710664749150f, + 0.483129411935806270f, -0.499715298414230350f, + 0.481596380472183230f, -0.499661177396774290f, 0.480063527822494510f, + -0.499602377414703370f, 0.478530883789062500f, -0.499538868665695190f, + 0.476998418569564820f, -0.499470651149749760f, + 0.475466161966323850f, -0.499397724866867070f, 0.473934143781661990f, + -0.499320119619369510f, 0.472402364015579220f, -0.499237775802612300f, + 0.470870882272720340f, -0.499150782823562620f, + 0.469339638948440550f, -0.499059051275253300f, 0.467808693647384640f, + -0.498962640762329100f, 0.466278046369552610f, -0.498861521482467650f, + 0.464747726917266850f, -0.498755723237991330f, + 0.463217705488204960f, -0.498645216226577760f, 0.461688071489334110f, + -0.498530030250549320f, 0.460158795118331910f, -0.498410135507583620f, + 0.458629876375198360f, -0.498285561800003050f, + 0.457101345062255860f, -0.498156309127807620f, 0.455573230981826780f, + -0.498022347688674930f, 0.454045534133911130f, -0.497883707284927370f, + 0.452518254518508910f, -0.497740387916564940f, + 0.450991421937942500f, -0.497592359781265260f, 0.449465066194534300f, + -0.497439652681350710f, 0.447939187288284300f, -0.497282296419143680f, + 0.446413785219192500f, -0.497120231389999390f, + 0.444888889789581300f, -0.496953487396240230f, 0.443364530801773070f, + -0.496782064437866210f, 0.441840678453445430f, -0.496605962514877320f, + 0.440317392349243160f, -0.496425211429595950f, + 0.438794672489166260f, -0.496239781379699710f, 0.437272518873214720f, + -0.496049642562866210f, 0.435750931501388550f, -0.495854884386062620f, + 0.434229999780654910f, -0.495655417442321780f, + 0.432709634304046630f, -0.495451331138610840f, 0.431189924478530880f, + -0.495242536067962650f, 0.429670870304107670f, -0.495029091835021970f, + 0.428152471780776980f, -0.494810998439788820f, + 0.426634758710861210f, -0.494588255882263180f, 0.425117731094360350f, + -0.494360834360122680f, 0.423601418733596800f, -0.494128793478012080f, + 0.422085791826248170f, -0.493892073631286620f, + 0.420570939779281620f, -0.493650704622268680f, 0.419056802988052370f, + -0.493404686450958250f, 0.417543441057205200f, -0.493154048919677730f, + 0.416030853986740110f, -0.492898762226104740f, + 0.414519041776657100f, -0.492638826370239260f, 0.413008064031600950f, + -0.492374241352081300f, 0.411497890949249270f, -0.492105036973953250f, + 0.409988552331924440f, -0.491831213235855100f, + 0.408480048179626460f, -0.491552740335464480f, 0.406972438097000120f, + -0.491269648075103760f, 0.405465662479400630f, -0.490981936454772950f, + 0.403959810733795170f, -0.490689605474472050f, + 0.402454853057861330f, -0.490392625331878660f, 0.400950789451599120f, + -0.490091055631637570f, 0.399447679519653320f, -0.489784896373748780f, + 0.397945523262023930f, -0.489474087953567500f, + 0.396444320678710940f, -0.489158689975738530f, 0.394944071769714360f, + -0.488838672637939450f, 0.393444836139678960f, -0.488514065742492680f, + 0.391946613788604740f, -0.488184869289398190f, + 0.390449374914169310f, -0.487851053476333620f, 0.388953179121017460f, + -0.487512677907943730f, 0.387458056211471560f, -0.487169682979583740f, + 0.385963946580886840f, -0.486822128295898440f, + 0.384470939636230470f, -0.486469984054565430f, 0.382979035377502440f, + -0.486113250255584720f, 0.381488204002380370f, -0.485751956701278690f, + 0.379998475313186650f, -0.485386073589324950f, + 0.378509908914566040f, -0.485015630722045900f, 0.377022475004196170f, + -0.484640628099441530f, 0.375536203384399410f, -0.484261035919189450f, + 0.374051094055175780f, -0.483876913785934450f, + 0.372567176818847660f, -0.483488231897354130f, 0.371084451675415040f, + -0.483094990253448490f, 0.369602948427200320f, -0.482697218656539920f, + 0.368122667074203490f, -0.482294887304306030f, + 0.366643607616424560f, -0.481888025999069210f, 0.365165829658508300f, + -0.481476634740829470f, 0.363689333200454710f, -0.481060713529586790f, + 0.362214088439941410f, -0.480640232563018800f, + 0.360740154981613160f, -0.480215251445770260f, 0.359267532825469970f, + -0.479785770177841190f, 0.357796221971511840f, -0.479351729154586790f, + 0.356326282024383540f, -0.478913217782974240f, + 0.354857653379440310f, -0.478470176458358760f, 0.353390425443649290f, + -0.478022634983062740f, 0.351924568414688110f, -0.477570593357086180f, + 0.350460082292556760f, -0.477114051580429080f, + 0.348997026681900020f, -0.476653009653091430f, 0.347535371780395510f, + -0.476187497377395630f, 0.346075177192687990f, -0.475717514753341670f, + 0.344616413116455080f, -0.475243031978607180f, + 0.343159139156341550f, -0.474764078855514530f, 0.341703325510025020f, + -0.474280685186386110f, 0.340248972177505490f, -0.473792791366577150f, + 0.338796168565750120f, -0.473300457000732420f, + 0.337344855070114140f, -0.472803652286529540f, 0.335895091295242310f, + -0.472302407026290890f, 0.334446847438812260f, -0.471796721220016480f, + 0.333000183105468750f, -0.471286594867706300f, + 0.331555068492889400f, -0.470772027969360350f, 0.330111563205718990f, + -0.470253020524978640f, 0.328669637441635130f, -0.469729602336883540f, + 0.327229350805282590f, -0.469201773405075070f, + 0.325790673494338990f, -0.468669503927230830f, 0.324353635311126710f, + -0.468132823705673220f, 0.322918236255645750f, -0.467591762542724610f, + 0.321484506130218510f, -0.467046260833740230f, + 0.320052474737167360f, -0.466496407985687260f, 0.318622142076492310f, + -0.465942144393920900f, 0.317193508148193360f, -0.465383470058441160f, + 0.315766572952270510f, -0.464820444583892820f, + 0.314341396093368530f, -0.464253038167953490f, 0.312917977571487430f, + -0.463681250810623170f, 0.311496287584304810f, -0.463105112314224240f, + 0.310076385736465450f, -0.462524622678756710f, + 0.308658272027969360f, -0.461939752101898190f, 0.307241976261138920f, + -0.461350560188293460f, 0.305827468633651730f, -0.460757017135620120f, + 0.304414808750152590f, -0.460159152746200560f, + 0.303003966808319090f, -0.459556937217712400f, 0.301595002412796020f, + -0.458950400352478030f, 0.300187885761260990f, -0.458339542150497440f, + 0.298782676458358760f, -0.457724362611770630f, + 0.297379344701766970f, -0.457104891538620000f, 0.295977920293807980f, + -0.456481099128723140f, 0.294578403234481810f, -0.455853015184402470f, + 0.293180853128433230f, -0.455220639705657960f, + 0.291785210371017460f, -0.454584002494812010f, 0.290391564369201660f, + -0.453943043947219850f, 0.288999855518341060f, -0.453297853469848630f, + 0.287610173225402830f, -0.452648371458053590f, + 0.286222457885742190f, -0.451994657516479490f, 0.284836769104003910f, + -0.451336652040481570f, 0.283453077077865600f, -0.450674414634704590f, + 0.282071471214294430f, -0.450007945299148560f, + 0.280691891908645630f, -0.449337244033813480f, 0.279314368963241580f, + -0.448662281036376950f, 0.277938932180404660f, -0.447983115911483760f, + 0.276565581560134890f, -0.447299748659133910f, + 0.275194346904754640f, -0.446612149477005000f, 0.273825198411941530f, + -0.445920348167419430f, 0.272458195686340330f, -0.445224374532699580f, + 0.271093338727951050f, -0.444524168968200680f, + 0.269730657339096070f, -0.443819820880889890f, 0.268370121717453000f, + -0.443111270666122440f, 0.267011761665344240f, -0.442398548126220700f, + 0.265655577182769780f, -0.441681683063507080f, + 0.264301627874374390f, -0.440960645675659180f, 0.262949883937835690f, + -0.440235435962677000f, 0.261600375175476070f, -0.439506113529205320f, + 0.260253131389617920f, -0.438772648572921750f, + 0.258908122777938840f, -0.438035041093826290f, 0.257565379142761230f, + -0.437293320894241330f, 0.256224930286407470f, -0.436547487974166870f, + 0.254886746406555180f, -0.435797542333602910f, + 0.253550916910171510f, -0.435043483972549440f, 0.252217382192611690f, + -0.434285342693328860f, 0.250886172056198120f, -0.433523118495941160f, + 0.249557301402091980f, -0.432756811380386350f, + 0.248230814933776860f, -0.431986421346664430f, 0.246906682848930360f, + -0.431211978197097780f, 0.245584934949874880f, -0.430433481931686400f, + 0.244265571236610410f, -0.429650902748107910f, + 0.242948621511459350f, -0.428864300251007080f, 0.241634100675582890f, + -0.428073674440383910f, 0.240322008728981020f, -0.427278995513916020f, + 0.239012360572814940f, -0.426480293273925780f, + 0.237705156207084660f, -0.425677597522735600f, 0.236400425434112550f, + -0.424870878458023070f, 0.235098183155059810f, -0.424060165882110600f, + 0.233798429369926450f, -0.423245459794998170f, + 0.232501193881034850f, -0.422426789999008180f, 0.231206461787223820f, + -0.421604126691818240f, 0.229914262890815730f, -0.420777499675750730f, + 0.228624612092971800f, -0.419946908950805660f, + 0.227337509393692020f, -0.419112354516983030f, 0.226052969694137570f, + -0.418273866176605220f, 0.224771007895469670f, -0.417431443929672240f, + 0.223491653800010680f, -0.416585087776184080f, + 0.222214877605438230f, -0.415734797716140750f, 0.220940738916397090f, + -0.414880603551864620f, 0.219669207930564880f, -0.414022535085678100f, + 0.218400329351425170f, -0.413160532712936400f, + 0.217134088277816770f, -0.412294656038284300f, 0.215870529413223270f, + -0.411424905061721800f, 0.214609622955322270f, -0.410551249980926510f, + 0.213351413607597350f, -0.409673750400543210f, + 0.212095901370048520f, -0.408792406320571900f, 0.210843101143836980f, + -0.407907217741012570f, 0.209593027830123900f, -0.407018154859542850f, + 0.208345666527748110f, -0.406125307083129880f, + 0.207101076841354370f, -0.405228585004806520f, 0.205859228968620300f, + -0.404328078031539920f, 0.204620152711868290f, -0.403423786163330080f, + 0.203383848071098330f, -0.402515679597854610f, + 0.202150344848632810f, -0.401603758335113530f, 0.200919643044471740f, + -0.400688081979751590f, 0.199691757559776310f, -0.399768620729446410f, + 0.198466703295707700f, -0.398845434188842770f, + 0.197244480252265930f, -0.397918462753295900f, 0.196025103330612180f, + -0.396987736225128170f, 0.194808602333068850f, -0.396053284406661990f, + 0.193594962358474730f, -0.395115107297897340f, + 0.192384198307991030f, -0.394173204898834230f, 0.191176339983940120f, + -0.393227607011795040f, 0.189971387386322020f, -0.392278283834457400f, + 0.188769355416297910f, -0.391325294971466060f, + 0.187570258975028990f, -0.390368610620498660f, 0.186374098062515260f, + -0.389408260583877560f, 0.185180887579917910f, -0.388444244861602780f, + 0.183990627527236940f, -0.387476563453674320f, + 0.182803362607955930f, -0.386505216360092160f, 0.181619063019752500f, + -0.385530263185501100f, 0.180437773466110230f, -0.384551674127578740f, + 0.179259493947029110f, -0.383569449186325070f, + 0.178084224462509160f, -0.382583618164062500f, 0.176911994814872740f, + -0.381594210863113400f, 0.175742805004119870f, -0.380601197481155400f, + 0.174576655030250550f, -0.379604607820510860f, + 0.173413574695587160f, -0.378604412078857420f, 0.172253578901290890f, + -0.377600699663162230f, 0.171096652746200560f, -0.376593410968780520f, + 0.169942826032638550f, -0.375582575798034670f, + 0.168792113661766050f, -0.374568194150924680f, 0.167644515633583070f, + -0.373550295829772950f, 0.166500031948089600f, -0.372528880834579470f, + 0.165358707308769230f, -0.371503978967666630f, + 0.164220526814460750f, -0.370475560426712040f, 0.163085505366325380f, + -0.369443655014038090f, 0.161953642964363100f, -0.368408292531967160f, + 0.160824984312057500f, -0.367369443178176880f, + 0.159699499607086180f, -0.366327136754989620f, 0.158577233552932740f, + -0.365281373262405400f, 0.157458171248435970f, -0.364232182502746580f, + 0.156342327594757080f, -0.363179564476013180f, + 0.155229732394218440f, -0.362123548984527590f, 0.154120370745658870f, + -0.361064106225967410f, 0.153014272451400760f, -0.360001266002655030f, + 0.151911437511444090f, -0.358935028314590450f, + 0.150811880826950070f, -0.357865422964096070f, 0.149715602397918700f, + -0.356792420148849490f, 0.148622632026672360f, -0.355716109275817870f, + 0.147532954812049870f, -0.354636400938034060f, + 0.146446615457534790f, -0.353553384542465210f, 0.145363584160804750f, + -0.352467030286788940f, 0.144283905625343320f, -0.351377367973327640f, + 0.143207564949989320f, -0.350284397602081300f, + 0.142134591937065120f, -0.349188119173049930f, 0.141064971685409550f, + -0.348088562488555910f, 0.139998748898506160f, -0.346985727548599240f, + 0.138935908675193790f, -0.345879614353179930f, + 0.137876465916633610f, -0.344770282506942750f, 0.136820420622825620f, + -0.343657672405242920f, 0.135767802596092220f, -0.342541843652725220f, + 0.134718611836433410f, -0.341422766447067260f, + 0.133672863245010380f, -0.340300500392913820f, 0.132630556821823120f, + -0.339175015687942500f, 0.131591722369194030f, -0.338046342134475710f, + 0.130556344985961910f, -0.336914509534835820f, + 0.129524439573287960f, -0.335779488086700440f, 0.128496021032333370f, + -0.334641307592391970f, 0.127471104264259340f, -0.333499968051910400f, + 0.126449704170227050f, -0.332355499267578130f, + 0.125431805849075320f, -0.331207901239395140f, 0.124417431652545930f, + -0.330057173967361450f, 0.123406603932380680f, -0.328903347253799440f, + 0.122399315237998960f, -0.327746421098709110f, + 0.121395580470561980f, -0.326586425304412840f, 0.120395407080650330f, + -0.325423330068588260f, 0.119398809969425200f, -0.324257194995880130f, + 0.118405789136886600f, -0.323088020086288450f, + 0.117416366934776310f, -0.321915775537490840f, 0.116430543363094330f, + -0.320740520954132080f, 0.115448333323001860f, -0.319562226533889770f, + 0.114469736814498900f, -0.318380922079086300f, + 0.113494776189327240f, -0.317196637392044070f, 0.112523443996906280f, + -0.316009372472763060f, 0.111555770039558410f, -0.314819127321243290f, + 0.110591746866703030f, -0.313625901937484740f, + 0.109631389379501340f, -0.312429755926132200f, 0.108674705028533940f, + -0.311230629682540890f, 0.107721701264381410f, -0.310028612613677980f, + 0.106772392988204960f, -0.308823645114898680f, + 0.105826787650585170f, -0.307615786790847780f, 0.104884892702102660f, + -0.306405037641525270f, 0.103946708142757420f, -0.305191397666931150f, + 0.103012263774871830f, -0.303974896669387820f, + 0.102081544697284700f, -0.302755534648895260f, 0.101154580712318420f, + -0.301533311605453490f, 0.100231364369392400f, -0.300308227539062500f, + 0.099311910569667816f, -0.299080342054367070f, + 0.098396234214305878f, -0.297849655151367190f, 0.097484335303306580f, + -0.296616137027740480f, 0.096576221287250519f, -0.295379847288131710f, + 0.095671907067298889f, -0.294140785932540890f, + 0.094771400094032288f, -0.292898923158645630f, 0.093874707818031311f, + -0.291654318571090700f, 0.092981837689876556f, -0.290406972169876100f, + 0.092092797160148621f, -0.289156883955001830f, + 0.091207593679428101f, -0.287904083728790280f, 0.090326242148876190f, + -0.286648571491241460f, 0.089448742568492889f, -0.285390377044677730f, + 0.088575109839439392f, -0.284129470586776730f, + 0.087705351412296295f, -0.282865911722183230f, 0.086839467287063599f, + -0.281599670648574830f, 0.085977479815483093f, -0.280330777168273930f, + 0.085119381546974182f, -0.279059261083602910f, + 0.084265194833278656f, -0.277785122394561770f, 0.083414919674396515f, + -0.276508361101150510f, 0.082568563520908356f, -0.275228977203369140f, + 0.081726133823394775f, -0.273947030305862430f, + 0.080887645483016968f, -0.272662490606307980f, 0.080053105950355530f, + -0.271375387907028200f, 0.079222507774829865f, -0.270085722208023070f, + 0.078395880758762360f, -0.268793523311614990f, + 0.077573217451572418f, -0.267498821020126340f, 0.076754532754421234f, + -0.266201555728912350f, 0.075939826667308807f, -0.264901816844940190f, + 0.075129114091396332f, -0.263599574565887450f, + 0.074322402477264404f, -0.262294828891754150f, 0.073519699275493622f, + -0.260987639427185060f, 0.072721004486083984f, -0.259678006172180180f, + 0.071926333010196686f, -0.258365899324417110f, + 0.071135692298412323f, -0.257051378488540650f, 0.070349089801311493f, + -0.255734413862228390f, 0.069566532969474792f, -0.254415065050125120f, + 0.068788021802902222f, -0.253093332052230830f, + 0.068013571202754974f, -0.251769185066223140f, 0.067243188619613647f, + -0.250442683696746830f, 0.066476874053478241f, -0.249113827943801880f, + 0.065714649856090546f, -0.247782632708549500f, + 0.064956501126289368f, -0.246449097990989690f, 0.064202457666397095f, + -0.245113238692283630f, 0.063452512025833130f, -0.243775084614753720f, + 0.062706671655178070f, -0.242434620857238770f, + 0.061964951455593109f, -0.241091892123222350f, 0.061227355152368546f, + -0.239746883511543270f, 0.060493886470794678f, -0.238399609923362730f, + 0.059764556586742401f, -0.237050101161003110f, + 0.059039369225502014f, -0.235698372125625610f, 0.058318331837654114f, + -0.234344407916069030f, 0.057601451873779297f, -0.232988253235816960f, + 0.056888736784458160f, -0.231629893183708190f, + 0.056180190294981003f, -0.230269357562065120f, 0.055475823581218719f, + -0.228906646370887760f, 0.054775636643171310f, -0.227541789412498470f, + 0.054079644381999969f, -0.226174786686897280f, + 0.053387850522994995f, -0.224805667996406560f, 0.052700258791446686f, + -0.223434418439865110f, 0.052016876637935638f, -0.222061067819595340f, + 0.051337707787752151f, -0.220685631036758420f, + 0.050662767142057419f, -0.219308122992515560f, 0.049992054700851440f, + -0.217928543686866760f, 0.049325577914714813f, -0.216546908020973210f, + 0.048663340508937836f, -0.215163245797157290f, + 0.048005353659391403f, -0.213777542114257810f, 0.047351621091365814f, + -0.212389841675758360f, 0.046702146530151367f, -0.211000129580497740f, + 0.046056941151618958f, -0.209608450531959530f, + 0.045416008681058884f, -0.208214774727821350f, 0.044779352843761444f, + -0.206819161772727970f, 0.044146984815597534f, -0.205421581864356990f, + 0.043518904596567154f, -0.204022079706192020f, + 0.042895123362541199f, -0.202620655298233030f, 0.042275641113519669f, + -0.201217323541641240f, 0.041660469025373459f, -0.199812099337577820f, + 0.041049610823392868f, -0.198404997587203980f, + 0.040443073958158493f, -0.196996018290519710f, 0.039840862154960632f, + -0.195585191249847410f, 0.039242979139089584f, -0.194172516465187070f, + 0.038649436086416245f, -0.192758023738861080f, + 0.038060232996940613f, -0.191341713070869450f, 0.037475381046533585f, + -0.189923599362373350f, 0.036894880235195160f, -0.188503712415695190f, + 0.036318738013505936f, -0.187082037329673770f, + 0.035746958106756210f, -0.185658603906631470f, 0.035179551690816879f, + -0.184233412146568300f, 0.034616518765687943f, -0.182806491851806640f, + 0.034057866781949997f, -0.181377857923507690f, + 0.033503599464893341f, -0.179947525262832640f, 0.032953724265098572f, + -0.178515478968620300f, 0.032408244907855988f, -0.177081763744354250f, + 0.031867165118455887f, -0.175646379590034480f, + 0.031330492347478867f, -0.174209341406822200f, 0.030798232182860374f, + -0.172770664095878600f, 0.030270388349890709f, -0.171330362558364870f, + 0.029746964573860168f, -0.169888436794281010f, + 0.029227968305349350f, -0.168444931507110600f, 0.028713401407003403f, + -0.166999831795692440f, 0.028203271329402924f, -0.165553152561187740f, + 0.027697581797838211f, -0.164104923605918880f, + 0.027196336537599564f, -0.162655144929885860f, 0.026699542999267578f, + -0.161203846335411070f, 0.026207204908132553f, -0.159751012921333310f, + 0.025719324126839638f, -0.158296689391136170f, + 0.025235909968614578f, -0.156840875744819640f, 0.024756962433457375f, + -0.155383571982383730f, 0.024282488971948624f, -0.153924822807312010f, + 0.023812493309378624f, -0.152464613318443300f, + 0.023346979171037674f, -0.151002973318099980f, 0.022885952144861221f, + -0.149539917707443240f, 0.022429415956139565f, -0.148075446486473080f, + 0.021977374330163002f, -0.146609574556350710f, + 0.021529832854866982f, -0.145142331719398500f, 0.021086793392896652f, + -0.143673732876777650f, 0.020648263394832611f, -0.142203763127326970f, + 0.020214242860674858f, -0.140732467174530030f, + 0.019784741103649139f, -0.139259845018386840f, 0.019359756261110306f, + -0.137785911560058590f, 0.018939297646284103f, -0.136310681700706480f, + 0.018523367121815681f, -0.134834155440330510f, + 0.018111966550350189f, -0.133356377482414250f, 0.017705103382468224f, + -0.131877332925796510f, 0.017302779480814934f, -0.130397051572799680f, + 0.016904998570680618f, -0.128915548324584960f, + 0.016511764377355576f, -0.127432823181152340f, 0.016123080626130104f, + -0.125948905944824220f, 0.015738952904939651f, -0.124463804066181180f, + 0.015359382145106792f, -0.122977524995803830f, + 0.014984373003244400f, -0.121490091085433960f, 0.014613929204642773f, + -0.120001509785652160f, 0.014248054474592209f, -0.118511803448200230f, + 0.013886751607060432f, -0.117020979523658750f, + 0.013530024327337742f, -0.115529052913188930f, 0.013177875429391861f, + -0.114036038517951970f, 0.012830308638513088f, -0.112541958689689640f, + 0.012487327679991722f, -0.111046813428401950f, + 0.012148935347795486f, -0.109550617635250090f, 0.011815134435892105f, + -0.108053401112556460f, 0.011485928669571877f, -0.106555156409740450f, + 0.011161320842802525f, -0.105055920779705050f, + 0.010841314680874348f, -0.103555686771869660f, 0.010525912046432495f, + -0.102054484188556670f, 0.010215117596089840f, -0.100552320480346680f, + 0.009908932261168957f, -0.099049203097820282f, + 0.009607359766960144f, -0.097545161843299866f, 0.009310402907431126f, + -0.096040196716785431f, 0.009018065407872200f, -0.094534330070018768f, + 0.008730349130928516f, -0.093027576804161072f, + 0.008447255939245224f, -0.091519944369792938f, 0.008168790489435196f, + -0.090011447668075562f, 0.007894953712821007f, -0.088502109050750732f, + 0.007625748869031668f, -0.086991935968399048f, + 0.007361178752034903f, -0.085480943322181702f, 0.007101245224475861f, + -0.083969146013259888f, 0.006845951545983553f, -0.082456558942794800f, + 0.006595299113541842f, -0.080943197011947632f, + 0.006349290721118450f, -0.079429075121879578f, 0.006107929162681103f, + -0.077914200723171234f, 0.005871216300874949f, -0.076398596167564392f, + 0.005639153998345137f, -0.074882268905639648f, + 0.005411745049059391f, -0.073365233838558197f, 0.005188991315662861f, + -0.071847513318061829f, 0.004970894660800695f, -0.070329122245311737f, + 0.004757457878440619f, -0.068810060620307922f, + 0.004548682365566492f, -0.067290350794792175f, 0.004344569984823465f, + -0.065770015120506287f, 0.004145123064517975f, -0.064249053597450256f, + 0.003950343467295170f, -0.062727488577365875f, + 0.003760232590138912f, -0.061205338686704636f, 0.003574792761355639f, + -0.059682607650756836f, 0.003394025377929211f, -0.058159314095973969f, + 0.003217932302504778f, -0.056635476648807526f, + 0.003046514932066202f, -0.055111102759838104f, 0.002879775362089276f, + -0.053586211055517197f, 0.002717714523896575f, -0.052060816437005997f, + 0.002560334512963891f, -0.050534930080175400f, + 0.002407636726275086f, -0.049008570611476898f, 0.002259622327983379f, + -0.047481749206781387f, 0.002116292715072632f, -0.045954477041959763f, + 0.001977649517357349f, -0.044426776468753815f, + 0.001843693898990750f, -0.042898654937744141f, 0.001714427140541375f, + -0.041370131075382233f, 0.001589850406162441f, -0.039841219782829285f, + 0.001469964860007167f, -0.038311932235956192f, + 0.001354771666228771f, -0.036782283335924149f, 0.001244271872565150f, + -0.035252287983894348f, 0.001138466643169522f, -0.033721961081027985f, + 0.001037356909364462f, -0.032191313803195953f, + 0.000940943544264883f, -0.030660368502140045f, 0.000849227537401021f, + -0.029129132628440857f, 0.000762209703680128f, -0.027597622945904732f, + 0.000679890916217119f, -0.026065852493047714f, + 0.000602271873503923f, -0.024533838033676147f, 0.000529353390447795f, + -0.023001590743660927f, 0.000461136136436835f, -0.021469129249453545f, + 0.000397620693547651f, -0.019936462864279747f, + 0.000338807702064514f, -0.018403612077236176f, 0.000284697714960203f, + -0.016870586201548576f, 0.000235291256103665f, -0.015337402001023293f, + 0.000190588747500442f, -0.013804072514176369f, + 0.000150590654811822f, -0.012270614504814148f, 0.000115297327283770f, + -0.010737040080130100f, 0.000084709099610336f, -0.009203365072607994f, + 0.000058826273743762f, -0.007669602986425161f, + 0.000037649078876711f, -0.006135769188404083f, 0.000021177724192967f, + -0.004601877182722092f, 0.000009412358849659f, -0.003067942336201668f, + 0.000002353095169383f, -0.001533978385850787f, + 0.000000000000000000f, -0.000000000000023345f, 0.000002353095169383f, + 0.001533978385850787f, 0.000009412358849659f, 0.003067942336201668f, + 0.000021177724192967f, 0.004601877182722092f, + 0.000037649078876711f, 0.006135769188404083f, 0.000058826273743762f, + 0.007669602986425161f, 0.000084709099610336f, 0.009203365072607994f, + 0.000115297327283770f, 0.010737040080130100f, + 0.000150590654811822f, 0.012270614504814148f, 0.000190588747500442f, + 0.013804072514176369f, 0.000235291256103665f, 0.015337402001023293f, + 0.000284697714960203f, 0.016870586201548576f, + 0.000338807702064514f, 0.018403612077236176f, 0.000397620693547651f, + 0.019936462864279747f, 0.000461136136436835f, 0.021469129249453545f, + 0.000529353390447795f, 0.023001590743660927f, + 0.000602271873503923f, 0.024533838033676147f, 0.000679890916217119f, + 0.026065852493047714f, 0.000762209703680128f, 0.027597622945904732f, + 0.000849227537401021f, 0.029129132628440857f, + 0.000940943544264883f, 0.030660368502140045f, 0.001037356909364462f, + 0.032191313803195953f, 0.001138466643169522f, 0.033721961081027985f, + 0.001244271872565150f, 0.035252287983894348f, + 0.001354771666228771f, 0.036782283335924149f, 0.001469964860007167f, + 0.038311932235956192f, 0.001589850406162441f, 0.039841219782829285f, + 0.001714427140541375f, 0.041370131075382233f, + 0.001843693898990750f, 0.042898654937744141f, 0.001977649517357349f, + 0.044426776468753815f, 0.002116292715072632f, 0.045954477041959763f, + 0.002259622327983379f, 0.047481749206781387f, + 0.002407636726275086f, 0.049008570611476898f, 0.002560334512963891f, + 0.050534930080175400f, 0.002717714523896575f, 0.052060816437005997f, + 0.002879775362089276f, 0.053586211055517197f, + 0.003046514932066202f, 0.055111102759838104f, 0.003217932302504778f, + 0.056635476648807526f, 0.003394025377929211f, 0.058159314095973969f, + 0.003574792761355639f, 0.059682607650756836f, + 0.003760232590138912f, 0.061205338686704636f, 0.003950343467295170f, + 0.062727488577365875f, 0.004145123064517975f, 0.064249053597450256f, + 0.004344569984823465f, 0.065770015120506287f, + 0.004548682365566492f, 0.067290350794792175f, 0.004757457878440619f, + 0.068810060620307922f, 0.004970894660800695f, 0.070329122245311737f, + 0.005188991315662861f, 0.071847513318061829f, + 0.005411745049059391f, 0.073365233838558197f, 0.005639153998345137f, + 0.074882268905639648f, 0.005871216300874949f, 0.076398596167564392f, + 0.006107929162681103f, 0.077914200723171234f, + 0.006349290721118450f, 0.079429075121879578f, 0.006595299113541842f, + 0.080943197011947632f, 0.006845951545983553f, 0.082456558942794800f, + 0.007101245224475861f, 0.083969146013259888f, + 0.007361178752034903f, 0.085480943322181702f, 0.007625748869031668f, + 0.086991935968399048f, 0.007894953712821007f, 0.088502109050750732f, + 0.008168790489435196f, 0.090011447668075562f, + 0.008447255939245224f, 0.091519944369792938f, 0.008730349130928516f, + 0.093027576804161072f, 0.009018065407872200f, 0.094534330070018768f, + 0.009310402907431126f, 0.096040196716785431f, + 0.009607359766960144f, 0.097545161843299866f, 0.009908932261168957f, + 0.099049203097820282f, 0.010215117596089840f, 0.100552320480346680f, + 0.010525912046432495f, 0.102054484188556670f, + 0.010841314680874348f, 0.103555686771869660f, 0.011161320842802525f, + 0.105055920779705050f, 0.011485928669571877f, 0.106555156409740450f, + 0.011815134435892105f, 0.108053401112556460f, + 0.012148935347795486f, 0.109550617635250090f, 0.012487327679991722f, + 0.111046813428401950f, 0.012830308638513088f, 0.112541958689689640f, + 0.013177875429391861f, 0.114036038517951970f, + 0.013530024327337742f, 0.115529052913188930f, 0.013886751607060432f, + 0.117020979523658750f, 0.014248054474592209f, 0.118511803448200230f, + 0.014613929204642773f, 0.120001509785652160f, + 0.014984373003244400f, 0.121490091085433960f, 0.015359382145106792f, + 0.122977524995803830f, 0.015738952904939651f, 0.124463804066181180f, + 0.016123080626130104f, 0.125948905944824220f, + 0.016511764377355576f, 0.127432823181152340f, 0.016904998570680618f, + 0.128915548324584960f, 0.017302779480814934f, 0.130397051572799680f, + 0.017705103382468224f, 0.131877332925796510f, + 0.018111966550350189f, 0.133356377482414250f, 0.018523367121815681f, + 0.134834155440330510f, 0.018939297646284103f, 0.136310681700706480f, + 0.019359756261110306f, 0.137785911560058590f, + 0.019784741103649139f, 0.139259845018386840f, 0.020214242860674858f, + 0.140732467174530030f, 0.020648263394832611f, 0.142203763127326970f, + 0.021086793392896652f, 0.143673732876777650f, + 0.021529832854866982f, 0.145142331719398500f, 0.021977374330163002f, + 0.146609574556350710f, 0.022429415956139565f, 0.148075446486473080f, + 0.022885952144861221f, 0.149539917707443240f, + 0.023346979171037674f, 0.151002973318099980f, 0.023812493309378624f, + 0.152464613318443300f, 0.024282488971948624f, 0.153924822807312010f, + 0.024756962433457375f, 0.155383571982383730f, + 0.025235909968614578f, 0.156840875744819640f, 0.025719324126839638f, + 0.158296689391136170f, 0.026207204908132553f, 0.159751012921333310f, + 0.026699542999267578f, 0.161203846335411070f, + 0.027196336537599564f, 0.162655144929885860f, 0.027697581797838211f, + 0.164104923605918880f, 0.028203271329402924f, 0.165553152561187740f, + 0.028713401407003403f, 0.166999831795692440f, + 0.029227968305349350f, 0.168444931507110600f, 0.029746964573860168f, + 0.169888436794281010f, 0.030270388349890709f, 0.171330362558364870f, + 0.030798232182860374f, 0.172770664095878600f, + 0.031330492347478867f, 0.174209341406822200f, 0.031867165118455887f, + 0.175646379590034480f, 0.032408244907855988f, 0.177081763744354250f, + 0.032953724265098572f, 0.178515478968620300f, + 0.033503599464893341f, 0.179947525262832640f, 0.034057866781949997f, + 0.181377857923507690f, 0.034616518765687943f, 0.182806491851806640f, + 0.035179551690816879f, 0.184233412146568300f, + 0.035746958106756210f, 0.185658603906631470f, 0.036318738013505936f, + 0.187082037329673770f, 0.036894880235195160f, 0.188503712415695190f, + 0.037475381046533585f, 0.189923599362373350f, + 0.038060232996940613f, 0.191341713070869450f, 0.038649436086416245f, + 0.192758023738861080f, 0.039242979139089584f, 0.194172516465187070f, + 0.039840862154960632f, 0.195585191249847410f, + 0.040443073958158493f, 0.196996018290519710f, 0.041049610823392868f, + 0.198404997587203980f, 0.041660469025373459f, 0.199812099337577820f, + 0.042275641113519669f, 0.201217323541641240f, + 0.042895123362541199f, 0.202620655298233030f, 0.043518904596567154f, + 0.204022079706192020f, 0.044146984815597534f, 0.205421581864356990f, + 0.044779352843761444f, 0.206819161772727970f, + 0.045416008681058884f, 0.208214774727821350f, 0.046056941151618958f, + 0.209608450531959530f, 0.046702146530151367f, 0.211000129580497740f, + 0.047351621091365814f, 0.212389841675758360f, + 0.048005353659391403f, 0.213777542114257810f, 0.048663340508937836f, + 0.215163245797157290f, 0.049325577914714813f, 0.216546908020973210f, + 0.049992054700851440f, 0.217928543686866760f, + 0.050662767142057419f, 0.219308122992515560f, 0.051337707787752151f, + 0.220685631036758420f, 0.052016876637935638f, 0.222061067819595340f, + 0.052700258791446686f, 0.223434418439865110f, + 0.053387850522994995f, 0.224805667996406560f, 0.054079644381999969f, + 0.226174786686897280f, 0.054775636643171310f, 0.227541789412498470f, + 0.055475823581218719f, 0.228906646370887760f, + 0.056180190294981003f, 0.230269357562065120f, 0.056888736784458160f, + 0.231629893183708190f, 0.057601451873779297f, 0.232988253235816960f, + 0.058318331837654114f, 0.234344407916069030f, + 0.059039369225502014f, 0.235698372125625610f, 0.059764556586742401f, + 0.237050101161003110f, 0.060493886470794678f, 0.238399609923362730f, + 0.061227355152368546f, 0.239746883511543270f, + 0.061964951455593109f, 0.241091892123222350f, 0.062706671655178070f, + 0.242434620857238770f, 0.063452512025833130f, 0.243775084614753720f, + 0.064202457666397095f, 0.245113238692283630f, + 0.064956501126289368f, 0.246449097990989690f, 0.065714649856090546f, + 0.247782632708549500f, 0.066476874053478241f, 0.249113827943801880f, + 0.067243188619613647f, 0.250442683696746830f, + 0.068013571202754974f, 0.251769185066223140f, 0.068788021802902222f, + 0.253093332052230830f, 0.069566532969474792f, 0.254415065050125120f, + 0.070349089801311493f, 0.255734413862228390f, + 0.071135692298412323f, 0.257051378488540650f, 0.071926333010196686f, + 0.258365899324417110f, 0.072721004486083984f, 0.259678006172180180f, + 0.073519699275493622f, 0.260987639427185060f, + 0.074322402477264404f, 0.262294828891754150f, 0.075129114091396332f, + 0.263599574565887450f, 0.075939826667308807f, 0.264901816844940190f, + 0.076754532754421234f, 0.266201555728912350f, + 0.077573217451572418f, 0.267498821020126340f, 0.078395880758762360f, + 0.268793523311614990f, 0.079222507774829865f, 0.270085722208023070f, + 0.080053105950355530f, 0.271375387907028200f, + 0.080887645483016968f, 0.272662490606307980f, 0.081726133823394775f, + 0.273947030305862430f, 0.082568563520908356f, 0.275228977203369140f, + 0.083414919674396515f, 0.276508361101150510f, + 0.084265194833278656f, 0.277785122394561770f, 0.085119381546974182f, + 0.279059261083602910f, 0.085977479815483093f, 0.280330777168273930f, + 0.086839467287063599f, 0.281599670648574830f, + 0.087705351412296295f, 0.282865911722183230f, 0.088575109839439392f, + 0.284129470586776730f, 0.089448742568492889f, 0.285390377044677730f, + 0.090326242148876190f, 0.286648571491241460f, + 0.091207593679428101f, 0.287904083728790280f, 0.092092797160148621f, + 0.289156883955001830f, 0.092981837689876556f, 0.290406972169876100f, + 0.093874707818031311f, 0.291654318571090700f, + 0.094771400094032288f, 0.292898923158645630f, 0.095671907067298889f, + 0.294140785932540890f, 0.096576221287250519f, 0.295379847288131710f, + 0.097484335303306580f, 0.296616137027740480f, + 0.098396234214305878f, 0.297849655151367190f, 0.099311910569667816f, + 0.299080342054367070f, 0.100231364369392400f, 0.300308227539062500f, + 0.101154580712318420f, 0.301533311605453490f, + 0.102081544697284700f, 0.302755534648895260f, 0.103012263774871830f, + 0.303974896669387820f, 0.103946708142757420f, 0.305191397666931150f, + 0.104884892702102660f, 0.306405037641525270f, + 0.105826787650585170f, 0.307615786790847780f, 0.106772392988204960f, + 0.308823645114898680f, 0.107721701264381410f, 0.310028612613677980f, + 0.108674705028533940f, 0.311230629682540890f, + 0.109631389379501340f, 0.312429755926132200f, 0.110591746866703030f, + 0.313625901937484740f, 0.111555770039558410f, 0.314819127321243290f, + 0.112523443996906280f, 0.316009372472763060f, + 0.113494776189327240f, 0.317196637392044070f, 0.114469736814498900f, + 0.318380922079086300f, 0.115448333323001860f, 0.319562226533889770f, + 0.116430543363094330f, 0.320740520954132080f, + 0.117416366934776310f, 0.321915775537490840f, 0.118405789136886600f, + 0.323088020086288450f, 0.119398809969425200f, 0.324257194995880130f, + 0.120395407080650330f, 0.325423330068588260f, + 0.121395580470561980f, 0.326586425304412840f, 0.122399315237998960f, + 0.327746421098709110f, 0.123406603932380680f, 0.328903347253799440f, + 0.124417431652545930f, 0.330057173967361450f, + 0.125431805849075320f, 0.331207901239395140f, 0.126449704170227050f, + 0.332355499267578130f, 0.127471104264259340f, 0.333499968051910400f, + 0.128496021032333370f, 0.334641307592391970f, + 0.129524439573287960f, 0.335779488086700440f, 0.130556344985961910f, + 0.336914509534835820f, 0.131591722369194030f, 0.338046342134475710f, + 0.132630556821823120f, 0.339175015687942500f, + 0.133672863245010380f, 0.340300500392913820f, 0.134718611836433410f, + 0.341422766447067260f, 0.135767802596092220f, 0.342541843652725220f, + 0.136820420622825620f, 0.343657672405242920f, + 0.137876465916633610f, 0.344770282506942750f, 0.138935908675193790f, + 0.345879614353179930f, 0.139998748898506160f, 0.346985727548599240f, + 0.141064971685409550f, 0.348088562488555910f, + 0.142134591937065120f, 0.349188119173049930f, 0.143207564949989320f, + 0.350284397602081300f, 0.144283905625343320f, 0.351377367973327640f, + 0.145363584160804750f, 0.352467030286788940f, + 0.146446615457534790f, 0.353553384542465210f, 0.147532954812049870f, + 0.354636400938034060f, 0.148622632026672360f, 0.355716109275817870f, + 0.149715602397918700f, 0.356792420148849490f, + 0.150811880826950070f, 0.357865422964096070f, 0.151911437511444090f, + 0.358935028314590450f, 0.153014272451400760f, 0.360001266002655030f, + 0.154120370745658870f, 0.361064106225967410f, + 0.155229732394218440f, 0.362123548984527590f, 0.156342327594757080f, + 0.363179564476013180f, 0.157458171248435970f, 0.364232182502746580f, + 0.158577233552932740f, 0.365281373262405400f, + 0.159699499607086180f, 0.366327136754989620f, 0.160824984312057500f, + 0.367369443178176880f, 0.161953642964363100f, 0.368408292531967160f, + 0.163085505366325380f, 0.369443655014038090f, + 0.164220526814460750f, 0.370475560426712040f, 0.165358707308769230f, + 0.371503978967666630f, 0.166500031948089600f, 0.372528880834579470f, + 0.167644515633583070f, 0.373550295829772950f, + 0.168792113661766050f, 0.374568194150924680f, 0.169942826032638550f, + 0.375582575798034670f, 0.171096652746200560f, 0.376593410968780520f, + 0.172253578901290890f, 0.377600699663162230f, + 0.173413574695587160f, 0.378604412078857420f, 0.174576655030250550f, + 0.379604607820510860f, 0.175742805004119870f, 0.380601197481155400f, + 0.176911994814872740f, 0.381594210863113400f, + 0.178084224462509160f, 0.382583618164062500f, 0.179259493947029110f, + 0.383569449186325070f, 0.180437773466110230f, 0.384551674127578740f, + 0.181619063019752500f, 0.385530263185501100f, + 0.182803362607955930f, 0.386505216360092160f, 0.183990627527236940f, + 0.387476563453674320f, 0.185180887579917910f, 0.388444244861602780f, + 0.186374098062515260f, 0.389408260583877560f, + 0.187570258975028990f, 0.390368610620498660f, 0.188769355416297910f, + 0.391325294971466060f, 0.189971387386322020f, 0.392278283834457400f, + 0.191176339983940120f, 0.393227607011795040f, + 0.192384198307991030f, 0.394173204898834230f, 0.193594962358474730f, + 0.395115107297897340f, 0.194808602333068850f, 0.396053284406661990f, + 0.196025103330612180f, 0.396987736225128170f, + 0.197244480252265930f, 0.397918462753295900f, 0.198466703295707700f, + 0.398845434188842770f, 0.199691757559776310f, 0.399768620729446410f, + 0.200919643044471740f, 0.400688081979751590f, + 0.202150344848632810f, 0.401603758335113530f, 0.203383848071098330f, + 0.402515679597854610f, 0.204620152711868290f, 0.403423786163330080f, + 0.205859228968620300f, 0.404328078031539920f, + 0.207101076841354370f, 0.405228585004806520f, 0.208345666527748110f, + 0.406125307083129880f, 0.209593027830123900f, 0.407018154859542850f, + 0.210843101143836980f, 0.407907217741012570f, + 0.212095901370048520f, 0.408792406320571900f, 0.213351413607597350f, + 0.409673750400543210f, 0.214609622955322270f, 0.410551249980926510f, + 0.215870529413223270f, 0.411424905061721800f, + 0.217134088277816770f, 0.412294656038284300f, 0.218400329351425170f, + 0.413160532712936400f, 0.219669207930564880f, 0.414022535085678100f, + 0.220940738916397090f, 0.414880603551864620f, + 0.222214877605438230f, 0.415734797716140750f, 0.223491653800010680f, + 0.416585087776184080f, 0.224771007895469670f, 0.417431443929672240f, + 0.226052969694137570f, 0.418273866176605220f, + 0.227337509393692020f, 0.419112354516983030f, 0.228624612092971800f, + 0.419946908950805660f, 0.229914262890815730f, 0.420777499675750730f, + 0.231206461787223820f, 0.421604126691818240f, + 0.232501193881034850f, 0.422426789999008180f, 0.233798429369926450f, + 0.423245459794998170f, 0.235098183155059810f, 0.424060165882110600f, + 0.236400425434112550f, 0.424870878458023070f, + 0.237705156207084660f, 0.425677597522735600f, 0.239012360572814940f, + 0.426480293273925780f, 0.240322008728981020f, 0.427278995513916020f, + 0.241634100675582890f, 0.428073674440383910f, + 0.242948621511459350f, 0.428864300251007080f, 0.244265571236610410f, + 0.429650902748107910f, 0.245584934949874880f, 0.430433481931686400f, + 0.246906682848930360f, 0.431211978197097780f, + 0.248230814933776860f, 0.431986421346664430f, 0.249557301402091980f, + 0.432756811380386350f, 0.250886172056198120f, 0.433523118495941160f, + 0.252217382192611690f, 0.434285342693328860f, + 0.253550916910171510f, 0.435043483972549440f, 0.254886746406555180f, + 0.435797542333602910f, 0.256224930286407470f, 0.436547487974166870f, + 0.257565379142761230f, 0.437293320894241330f, + 0.258908122777938840f, 0.438035041093826290f, 0.260253131389617920f, + 0.438772648572921750f, 0.261600375175476070f, 0.439506113529205320f, + 0.262949883937835690f, 0.440235435962677000f, + 0.264301627874374390f, 0.440960645675659180f, 0.265655577182769780f, + 0.441681683063507080f, 0.267011761665344240f, 0.442398548126220700f, + 0.268370121717453000f, 0.443111270666122440f, + 0.269730657339096070f, 0.443819820880889890f, 0.271093338727951050f, + 0.444524168968200680f, 0.272458195686340330f, 0.445224374532699580f, + 0.273825198411941530f, 0.445920348167419430f, + 0.275194346904754640f, 0.446612149477005000f, 0.276565581560134890f, + 0.447299748659133910f, 0.277938932180404660f, 0.447983115911483760f, + 0.279314368963241580f, 0.448662281036376950f, + 0.280691891908645630f, 0.449337244033813480f, 0.282071471214294430f, + 0.450007945299148560f, 0.283453077077865600f, 0.450674414634704590f, + 0.284836769104003910f, 0.451336652040481570f, + 0.286222457885742190f, 0.451994657516479490f, 0.287610173225402830f, + 0.452648371458053590f, 0.288999855518341060f, 0.453297853469848630f, + 0.290391564369201660f, 0.453943043947219850f, + 0.291785210371017460f, 0.454584002494812010f, 0.293180853128433230f, + 0.455220639705657960f, 0.294578403234481810f, 0.455853015184402470f, + 0.295977920293807980f, 0.456481099128723140f, + 0.297379344701766970f, 0.457104891538620000f, 0.298782676458358760f, + 0.457724362611770630f, 0.300187885761260990f, 0.458339542150497440f, + 0.301595002412796020f, 0.458950400352478030f, + 0.303003966808319090f, 0.459556937217712400f, 0.304414808750152590f, + 0.460159152746200560f, 0.305827468633651730f, 0.460757017135620120f, + 0.307241976261138920f, 0.461350560188293460f, + 0.308658272027969360f, 0.461939752101898190f, 0.310076385736465450f, + 0.462524622678756710f, 0.311496287584304810f, 0.463105112314224240f, + 0.312917977571487430f, 0.463681250810623170f, + 0.314341396093368530f, 0.464253038167953490f, 0.315766572952270510f, + 0.464820444583892820f, 0.317193508148193360f, 0.465383470058441160f, + 0.318622142076492310f, 0.465942144393920900f, + 0.320052474737167360f, 0.466496407985687260f, 0.321484506130218510f, + 0.467046260833740230f, 0.322918236255645750f, 0.467591762542724610f, + 0.324353635311126710f, 0.468132823705673220f, + 0.325790673494338990f, 0.468669503927230830f, 0.327229350805282590f, + 0.469201773405075070f, 0.328669637441635130f, 0.469729602336883540f, + 0.330111563205718990f, 0.470253020524978640f, + 0.331555068492889400f, 0.470772027969360350f, 0.333000183105468750f, + 0.471286594867706300f, 0.334446847438812260f, 0.471796721220016480f, + 0.335895091295242310f, 0.472302407026290890f, + 0.337344855070114140f, 0.472803652286529540f, 0.338796168565750120f, + 0.473300457000732420f, 0.340248972177505490f, 0.473792791366577150f, + 0.341703325510025020f, 0.474280685186386110f, + 0.343159139156341550f, 0.474764078855514530f, 0.344616413116455080f, + 0.475243031978607180f, 0.346075177192687990f, 0.475717514753341670f, + 0.347535371780395510f, 0.476187497377395630f, + 0.348997026681900020f, 0.476653009653091430f, 0.350460082292556760f, + 0.477114051580429080f, 0.351924568414688110f, 0.477570593357086180f, + 0.353390425443649290f, 0.478022634983062740f, + 0.354857653379440310f, 0.478470176458358760f, 0.356326282024383540f, + 0.478913217782974240f, 0.357796221971511840f, 0.479351729154586790f, + 0.359267532825469970f, 0.479785770177841190f, + 0.360740154981613160f, 0.480215251445770260f, 0.362214088439941410f, + 0.480640232563018800f, 0.363689333200454710f, 0.481060713529586790f, + 0.365165829658508300f, 0.481476634740829470f, + 0.366643607616424560f, 0.481888025999069210f, 0.368122667074203490f, + 0.482294887304306030f, 0.369602948427200320f, 0.482697218656539920f, + 0.371084451675415040f, 0.483094990253448490f, + 0.372567176818847660f, 0.483488231897354130f, 0.374051094055175780f, + 0.483876913785934450f, 0.375536203384399410f, 0.484261035919189450f, + 0.377022475004196170f, 0.484640628099441530f, + 0.378509908914566040f, 0.485015630722045900f, 0.379998475313186650f, + 0.485386073589324950f, 0.381488204002380370f, 0.485751956701278690f, + 0.382979035377502440f, 0.486113250255584720f, + 0.384470939636230470f, 0.486469984054565430f, 0.385963946580886840f, + 0.486822128295898440f, 0.387458056211471560f, 0.487169682979583740f, + 0.388953179121017460f, 0.487512677907943730f, + 0.390449374914169310f, 0.487851053476333620f, 0.391946613788604740f, + 0.488184869289398190f, 0.393444836139678960f, 0.488514065742492680f, + 0.394944071769714360f, 0.488838672637939450f, + 0.396444320678710940f, 0.489158689975738530f, 0.397945523262023930f, + 0.489474087953567500f, 0.399447679519653320f, 0.489784896373748780f, + 0.400950789451599120f, 0.490091055631637570f, + 0.402454853057861330f, 0.490392625331878660f, 0.403959810733795170f, + 0.490689605474472050f, 0.405465662479400630f, 0.490981936454772950f, + 0.406972438097000120f, 0.491269648075103760f, + 0.408480048179626460f, 0.491552740335464480f, 0.409988552331924440f, + 0.491831213235855100f, 0.411497890949249270f, 0.492105036973953250f, + 0.413008064031600950f, 0.492374241352081300f, + 0.414519041776657100f, 0.492638826370239260f, 0.416030853986740110f, + 0.492898762226104740f, 0.417543441057205200f, 0.493154048919677730f, + 0.419056802988052370f, 0.493404686450958250f, + 0.420570939779281620f, 0.493650704622268680f, 0.422085791826248170f, + 0.493892073631286620f, 0.423601418733596800f, 0.494128793478012080f, + 0.425117731094360350f, 0.494360834360122680f, + 0.426634758710861210f, 0.494588255882263180f, 0.428152471780776980f, + 0.494810998439788820f, 0.429670870304107670f, 0.495029091835021970f, + 0.431189924478530880f, 0.495242536067962650f, + 0.432709634304046630f, 0.495451331138610840f, 0.434229999780654910f, + 0.495655417442321780f, 0.435750931501388550f, 0.495854884386062620f, + 0.437272518873214720f, 0.496049642562866210f, + 0.438794672489166260f, 0.496239781379699710f, 0.440317392349243160f, + 0.496425211429595950f, 0.441840678453445430f, 0.496605962514877320f, + 0.443364530801773070f, 0.496782064437866210f, + 0.444888889789581300f, 0.496953487396240230f, 0.446413785219192500f, + 0.497120231389999390f, 0.447939187288284300f, 0.497282296419143680f, + 0.449465066194534300f, 0.497439652681350710f, + 0.450991421937942500f, 0.497592359781265260f, 0.452518254518508910f, + 0.497740387916564940f, 0.454045534133911130f, 0.497883707284927370f, + 0.455573230981826780f, 0.498022347688674930f, + 0.457101345062255860f, 0.498156309127807620f, 0.458629876375198360f, + 0.498285561800003050f, 0.460158795118331910f, 0.498410135507583620f, + 0.461688071489334110f, 0.498530030250549320f, + 0.463217705488204960f, 0.498645216226577760f, 0.464747726917266850f, + 0.498755723237991330f, 0.466278046369552610f, 0.498861521482467650f, + 0.467808693647384640f, 0.498962640762329100f, + 0.469339638948440550f, 0.499059051275253300f, 0.470870882272720340f, + 0.499150782823562620f, 0.472402364015579220f, 0.499237775802612300f, + 0.473934143781661990f, 0.499320119619369510f, + 0.475466161966323850f, 0.499397724866867070f, 0.476998418569564820f, + 0.499470651149749760f, 0.478530883789062500f, 0.499538868665695190f, + 0.480063527822494510f, 0.499602377414703370f, + 0.481596380472183230f, 0.499661177396774290f, 0.483129411935806270f, + 0.499715298414230350f, 0.484662592411041260f, 0.499764710664749150f, + 0.486195921897888180f, 0.499809414148330690f, + 0.487729400396347050f, 0.499849408864974980f, 0.489262968301773070f, + 0.499884694814682010f, 0.490796625614166260f, 0.499915301799774170f, + 0.492330402135849000f, 0.499941170215606690f, + 0.493864238262176510f, 0.499962359666824340f, 0.495398133993148800f, + 0.499978810548782350f, 0.496932059526443480f, 0.499990582466125490f, + 0.498466014862060550f, 0.499997645616531370f +}; + + +/** +* \par +* Generation of realCoefB array: +* \par +* n = 1024 +*
for (i = 0; i < n; i++)   
+* {   
+*    pBTable[2 * i] = 0.5 * (1.0 + sin (2 * PI / (double) (2 * n) * (double) i));   
+*    pBTable[2 * i + 1] = 0.5 * (1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
+*  } 
+* +*/ +static const float32_t realCoefB[2048] = { + 0.500000000000000000f, 0.500000000000000000f, 0.501533985137939450f, + 0.499997645616531370f, 0.503067970275878910f, 0.499990582466125490f, + 0.504601895809173580f, 0.499978810548782350f, + 0.506135761737823490f, 0.499962359666824340f, 0.507669627666473390f, + 0.499941170215606690f, 0.509203374385833740f, 0.499915301799774170f, + 0.510737061500549320f, 0.499884694814682010f, + 0.512270629405975340f, 0.499849408864974980f, 0.513804078102111820f, + 0.499809414148330690f, 0.515337407588958740f, 0.499764710664749150f, + 0.516870558261871340f, 0.499715298414230350f, + 0.518403589725494380f, 0.499661177396774290f, 0.519936442375183110f, + 0.499602377414703370f, 0.521469116210937500f, 0.499538868665695190f, + 0.523001611232757570f, 0.499470651149749760f, + 0.524533808231353760f, 0.499397724866867070f, 0.526065826416015630f, + 0.499320119619369510f, 0.527597606182098390f, 0.499237775802612300f, + 0.529129147529602050f, 0.499150782823562620f, + 0.530660390853881840f, 0.499059051275253300f, 0.532191336154937740f, + 0.498962640762329100f, 0.533721983432769780f, 0.498861521482467650f, + 0.535252273082733150f, 0.498755723237991330f, + 0.536782264709472660f, 0.498645216226577760f, 0.538311958312988280f, + 0.498530030250549320f, 0.539841234683990480f, 0.498410135507583620f, + 0.541370153427124020f, 0.498285561800003050f, + 0.542898654937744140f, 0.498156309127807620f, 0.544426798820495610f, + 0.498022347688674930f, 0.545954465866088870f, 0.497883707284927370f, + 0.547481775283813480f, 0.497740387916564940f, + 0.549008548259735110f, 0.497592359781265260f, 0.550534904003143310f, + 0.497439652681350710f, 0.552060842514038090f, 0.497282296419143680f, + 0.553586184978485110f, 0.497120231389999390f, + 0.555111110210418700f, 0.496953487396240230f, 0.556635499000549320f, + 0.496782064437866210f, 0.558159291744232180f, 0.496605962514877320f, + 0.559682607650756840f, 0.496425211429595950f, + 0.561205327510833740f, 0.496239781379699710f, 0.562727510929107670f, + 0.496049642562866210f, 0.564249038696289060f, 0.495854884386062620f, + 0.565770030021667480f, 0.495655417442321780f, + 0.567290365695953370f, 0.495451331138610840f, 0.568810045719146730f, + 0.495242536067962650f, 0.570329129695892330f, 0.495029091835021970f, + 0.571847498416900630f, 0.494810998439788820f, + 0.573365211486816410f, 0.494588255882263180f, 0.574882268905639650f, + 0.494360834360122680f, 0.576398611068725590f, 0.494128793478012080f, + 0.577914178371429440f, 0.493892073631286620f, + 0.579429090023040770f, 0.493650704622268680f, 0.580943167209625240f, + 0.493404686450958250f, 0.582456588745117190f, 0.493154048919677730f, + 0.583969175815582280f, 0.492898762226104740f, + 0.585480928421020510f, 0.492638826370239260f, 0.586991965770721440f, + 0.492374241352081300f, 0.588502109050750730f, 0.492105036973953250f, + 0.590011477470397950f, 0.491831213235855100f, + 0.591519951820373540f, 0.491552740335464480f, 0.593027591705322270f, + 0.491269648075103760f, 0.594534337520599370f, 0.490981936454772950f, + 0.596040189266204830f, 0.490689605474472050f, + 0.597545146942138670f, 0.490392625331878660f, 0.599049210548400880f, + 0.490091055631637570f, 0.600552320480346680f, 0.489784896373748780f, + 0.602054476737976070f, 0.489474087953567500f, + 0.603555679321289060f, 0.489158689975738530f, 0.605055928230285640f, + 0.488838672637939450f, 0.606555163860321040f, 0.488514065742492680f, + 0.608053386211395260f, 0.488184869289398190f, + 0.609550595283508300f, 0.487851053476333620f, 0.611046791076660160f, + 0.487512677907943730f, 0.612541973590850830f, 0.487169682979583740f, + 0.614036023616790770f, 0.486822128295898440f, + 0.615529060363769530f, 0.486469984054565430f, 0.617020964622497560f, + 0.486113250255584720f, 0.618511795997619630f, 0.485751956701278690f, + 0.620001494884490970f, 0.485386073589324950f, + 0.621490061283111570f, 0.485015630722045900f, 0.622977554798126220f, + 0.484640628099441530f, 0.624463796615600590f, 0.484261035919189450f, + 0.625948905944824220f, 0.483876913785934450f, + 0.627432823181152340f, 0.483488231897354130f, 0.628915548324584960f, + 0.483094990253448490f, 0.630397081375122070f, 0.482697218656539920f, + 0.631877362728118900f, 0.482294887304306030f, + 0.633356392383575440f, 0.481888025999069210f, 0.634834170341491700f, + 0.481476634740829470f, 0.636310696601867680f, 0.481060713529586790f, + 0.637785911560058590f, 0.480640232563018800f, + 0.639259815216064450f, 0.480215251445770260f, 0.640732467174530030f, + 0.479785770177841190f, 0.642203748226165770f, 0.479351729154586790f, + 0.643673717975616460f, 0.478913217782974240f, + 0.645142316818237300f, 0.478470176458358760f, 0.646609604358673100f, + 0.478022634983062740f, 0.648075461387634280f, 0.477570593357086180f, + 0.649539887905120850f, 0.477114051580429080f, + 0.651003003120422360f, 0.476653009653091430f, 0.652464628219604490f, + 0.476187497377395630f, 0.653924822807312010f, 0.475717514753341670f, + 0.655383586883544920f, 0.475243031978607180f, + 0.656840860843658450f, 0.474764078855514530f, 0.658296704292297360f, + 0.474280685186386110f, 0.659750998020172120f, 0.473792791366577150f, + 0.661203861236572270f, 0.473300457000732420f, + 0.662655174732208250f, 0.472803652286529540f, 0.664104938507080080f, + 0.472302407026290890f, 0.665553152561187740f, 0.471796721220016480f, + 0.666999816894531250f, 0.471286594867706300f, + 0.668444931507110600f, 0.470772027969360350f, 0.669888436794281010f, + 0.470253020524978640f, 0.671330332756042480f, 0.469729602336883540f, + 0.672770678997039790f, 0.469201773405075070f, + 0.674209356307983400f, 0.468669503927230830f, 0.675646364688873290f, + 0.468132823705673220f, 0.677081763744354250f, 0.467591762542724610f, + 0.678515493869781490f, 0.467046260833740230f, + 0.679947495460510250f, 0.466496407985687260f, 0.681377887725830080f, + 0.465942144393920900f, 0.682806491851806640f, 0.465383470058441160f, + 0.684233427047729490f, 0.464820444583892820f, + 0.685658574104309080f, 0.464253038167953490f, 0.687082052230834960f, + 0.463681250810623170f, 0.688503682613372800f, 0.463105112314224240f, + 0.689923584461212160f, 0.462524622678756710f, + 0.691341698169708250f, 0.461939752101898190f, 0.692758023738861080f, + 0.461350560188293460f, 0.694172501564025880f, 0.460757017135620120f, + 0.695585191249847410f, 0.460159152746200560f, + 0.696996033191680910f, 0.459556937217712400f, 0.698404967784881590f, + 0.458950400352478030f, 0.699812114238739010f, 0.458339542150497440f, + 0.701217353343963620f, 0.457724362611770630f, + 0.702620685100555420f, 0.457104891538620000f, 0.704022109508514400f, + 0.456481099128723140f, 0.705421566963195800f, 0.455853015184402470f, + 0.706819176673889160f, 0.455220639705657960f, + 0.708214759826660160f, 0.454584002494812010f, 0.709608435630798340f, + 0.453943043947219850f, 0.711000144481658940f, 0.453297853469848630f, + 0.712389826774597170f, 0.452648371458053590f, + 0.713777542114257810f, 0.451994657516479490f, 0.715163230895996090f, + 0.451336652040481570f, 0.716546893119812010f, 0.450674414634704590f, + 0.717928528785705570f, 0.450007945299148560f, + 0.719308137893676760f, 0.449337244033813480f, 0.720685660839080810f, + 0.448662281036376950f, 0.722061097621917720f, 0.447983115911483760f, + 0.723434448242187500f, 0.447299748659133910f, + 0.724805653095245360f, 0.446612149477005000f, 0.726174771785736080f, + 0.445920348167419430f, 0.727541804313659670f, 0.445224374532699580f, + 0.728906631469726560f, 0.444524168968200680f, + 0.730269372463226320f, 0.443819820880889890f, 0.731629908084869380f, + 0.443111270666122440f, 0.732988238334655760f, 0.442398548126220700f, + 0.734344422817230220f, 0.441681683063507080f, + 0.735698342323303220f, 0.440960645675659180f, 0.737050116062164310f, + 0.440235435962677000f, 0.738399624824523930f, 0.439506113529205320f, + 0.739746868610382080f, 0.438772648572921750f, + 0.741091907024383540f, 0.438035041093826290f, 0.742434620857238770f, + 0.437293320894241330f, 0.743775069713592530f, 0.436547487974166870f, + 0.745113253593444820f, 0.435797542333602910f, + 0.746449112892150880f, 0.435043483972549440f, 0.747782647609710690f, + 0.434285342693328860f, 0.749113857746124270f, 0.433523118495941160f, + 0.750442683696746830f, 0.432756811380386350f, + 0.751769185066223140f, 0.431986421346664430f, 0.753093302249908450f, + 0.431211978197097780f, 0.754415094852447510f, 0.430433481931686400f, + 0.755734443664550780f, 0.429650902748107910f, + 0.757051348686218260f, 0.428864300251007080f, 0.758365929126739500f, + 0.428073674440383910f, 0.759678006172180180f, 0.427278995513916020f, + 0.760987639427185060f, 0.426480293273925780f, + 0.762294828891754150f, 0.425677597522735600f, 0.763599574565887450f, + 0.424870878458023070f, 0.764901816844940190f, 0.424060165882110600f, + 0.766201555728912350f, 0.423245459794998170f, + 0.767498791217803960f, 0.422426789999008180f, 0.768793523311614990f, + 0.421604126691818240f, 0.770085752010345460f, 0.420777499675750730f, + 0.771375417709350590f, 0.419946908950805660f, + 0.772662520408630370f, 0.419112354516983030f, 0.773947000503540040f, + 0.418273866176605220f, 0.775228977203369140f, 0.417431443929672240f, + 0.776508331298828130f, 0.416585087776184080f, + 0.777785122394561770f, 0.415734797716140750f, 0.779059290885925290f, + 0.414880603551864620f, 0.780330777168273930f, 0.414022535085678100f, + 0.781599700450897220f, 0.413160532712936400f, + 0.782865881919860840f, 0.412294656038284300f, 0.784129500389099120f, + 0.411424905061721800f, 0.785390377044677730f, 0.410551249980926510f, + 0.786648571491241460f, 0.409673750400543210f, + 0.787904083728790280f, 0.408792406320571900f, 0.789156913757324220f, + 0.407907217741012570f, 0.790407001972198490f, 0.407018154859542850f, + 0.791654348373413090f, 0.406125307083129880f, + 0.792898952960968020f, 0.405228585004806520f, 0.794140756130218510f, + 0.404328078031539920f, 0.795379877090454100f, 0.403423786163330080f, + 0.796616137027740480f, 0.402515679597854610f, + 0.797849655151367190f, 0.401603758335113530f, 0.799080371856689450f, + 0.400688081979751590f, 0.800308227539062500f, 0.399768620729446410f, + 0.801533281803131100f, 0.398845434188842770f, + 0.802755534648895260f, 0.397918462753295900f, 0.803974866867065430f, + 0.396987736225128170f, 0.805191397666931150f, 0.396053284406661990f, + 0.806405067443847660f, 0.395115107297897340f, + 0.807615816593170170f, 0.394173204898834230f, 0.808823645114898680f, + 0.393227607011795040f, 0.810028612613677980f, 0.392278283834457400f, + 0.811230659484863280f, 0.391325294971466060f, + 0.812429726123809810f, 0.390368610620498660f, 0.813625931739807130f, + 0.389408260583877560f, 0.814819097518920900f, 0.388444244861602780f, + 0.816009342670440670f, 0.387476563453674320f, + 0.817196667194366460f, 0.386505216360092160f, 0.818380951881408690f, + 0.385530263185501100f, 0.819562196731567380f, 0.384551674127578740f, + 0.820740520954132080f, 0.383569449186325070f, + 0.821915745735168460f, 0.382583618164062500f, 0.823087990283966060f, + 0.381594210863113400f, 0.824257194995880130f, 0.380601197481155400f, + 0.825423359870910640f, 0.379604607820510860f, + 0.826586425304412840f, 0.378604412078857420f, 0.827746450901031490f, + 0.377600699663162230f, 0.828903317451477050f, 0.376593410968780520f, + 0.830057144165039060f, 0.375582575798034670f, + 0.831207871437072750f, 0.374568194150924680f, 0.832355499267578130f, + 0.373550295829772950f, 0.833499968051910400f, 0.372528880834579470f, + 0.834641277790069580f, 0.371503978967666630f, + 0.835779488086700440f, 0.370475560426712040f, 0.836914479732513430f, + 0.369443655014038090f, 0.838046371936798100f, 0.368408292531967160f, + 0.839175045490264890f, 0.367369443178176880f, + 0.840300500392913820f, 0.366327136754989620f, 0.841422796249389650f, + 0.365281373262405400f, 0.842541813850402830f, 0.364232182502746580f, + 0.843657672405242920f, 0.363179564476013180f, + 0.844770252704620360f, 0.362123548984527590f, 0.845879614353179930f, + 0.361064106225967410f, 0.846985757350921630f, 0.360001266002655030f, + 0.848088562488555910f, 0.358935028314590450f, + 0.849188148975372310f, 0.357865422964096070f, 0.850284397602081300f, + 0.356792420148849490f, 0.851377367973327640f, 0.355716109275817870f, + 0.852467060089111330f, 0.354636400938034060f, + 0.853553414344787600f, 0.353553384542465210f, 0.854636430740356450f, + 0.352467030286788940f, 0.855716109275817870f, 0.351377367973327640f, + 0.856792449951171880f, 0.350284397602081300f, + 0.857865393161773680f, 0.349188119173049930f, 0.858934998512268070f, + 0.348088562488555910f, 0.860001266002655030f, 0.346985727548599240f, + 0.861064076423645020f, 0.345879614353179930f, + 0.862123548984527590f, 0.344770282506942750f, 0.863179564476013180f, + 0.343657672405242920f, 0.864232182502746580f, 0.342541843652725220f, + 0.865281403064727780f, 0.341422766447067260f, + 0.866327106952667240f, 0.340300500392913820f, 0.867369413375854490f, + 0.339175015687942500f, 0.868408262729644780f, 0.338046342134475710f, + 0.869443655014038090f, 0.336914509534835820f, + 0.870475590229034420f, 0.335779488086700440f, 0.871503949165344240f, + 0.334641307592391970f, 0.872528910636901860f, 0.333499968051910400f, + 0.873550295829772950f, 0.332355499267578130f, + 0.874568223953247070f, 0.331207901239395140f, 0.875582575798034670f, + 0.330057173967361450f, 0.876593410968780520f, 0.328903347253799440f, + 0.877600669860839840f, 0.327746421098709110f, + 0.878604412078857420f, 0.326586425304412840f, 0.879604578018188480f, + 0.325423330068588260f, 0.880601167678833010f, 0.324257194995880130f, + 0.881594181060791020f, 0.323088020086288450f, + 0.882583618164062500f, 0.321915775537490840f, 0.883569478988647460f, + 0.320740520954132080f, 0.884551644325256350f, 0.319562226533889770f, + 0.885530233383178710f, 0.318380922079086300f, + 0.886505246162414550f, 0.317196637392044070f, 0.887476563453674320f, + 0.316009372472763060f, 0.888444244861602780f, 0.314819127321243290f, + 0.889408230781555180f, 0.313625901937484740f, + 0.890368640422821040f, 0.312429755926132200f, 0.891325294971466060f, + 0.311230629682540890f, 0.892278313636779790f, 0.310028612613677980f, + 0.893227577209472660f, 0.308823645114898680f, + 0.894173204898834230f, 0.307615786790847780f, 0.895115137100219730f, + 0.306405037641525270f, 0.896053314208984380f, 0.305191397666931150f, + 0.896987736225128170f, 0.303974896669387820f, + 0.897918462753295900f, 0.302755534648895260f, 0.898845434188842770f, + 0.301533311605453490f, 0.899768650531768800f, 0.300308227539062500f, + 0.900688111782073970f, 0.299080342054367070f, + 0.901603758335113530f, 0.297849655151367190f, 0.902515649795532230f, + 0.296616137027740480f, 0.903423786163330080f, 0.295379847288131710f, + 0.904328107833862300f, 0.294140785932540890f, + 0.905228614807128910f, 0.292898923158645630f, 0.906125307083129880f, + 0.291654318571090700f, 0.907018184661865230f, 0.290406972169876100f, + 0.907907187938690190f, 0.289156883955001830f, + 0.908792436122894290f, 0.287904083728790280f, 0.909673750400543210f, + 0.286648571491241460f, 0.910551249980926510f, 0.285390377044677730f, + 0.911424875259399410f, 0.284129470586776730f, + 0.912294626235961910f, 0.282865911722183230f, 0.913160502910614010f, + 0.281599670648574830f, 0.914022505283355710f, 0.280330777168273930f, + 0.914880633354187010f, 0.279059261083602910f, + 0.915734827518463130f, 0.277785122394561770f, 0.916585087776184080f, + 0.276508361101150510f, 0.917431414127349850f, 0.275228977203369140f, + 0.918273866176605220f, 0.273947030305862430f, + 0.919112324714660640f, 0.272662490606307980f, 0.919946908950805660f, + 0.271375387907028200f, 0.920777499675750730f, 0.270085722208023070f, + 0.921604096889495850f, 0.268793523311614990f, + 0.922426760196685790f, 0.267498821020126340f, 0.923245489597320560f, + 0.266201555728912350f, 0.924060165882110600f, 0.264901816844940190f, + 0.924870908260345460f, 0.263599574565887450f, + 0.925677597522735600f, 0.262294828891754150f, 0.926480293273925780f, + 0.260987639427185060f, 0.927278995513916020f, 0.259678006172180180f, + 0.928073644638061520f, 0.258365899324417110f, + 0.928864300251007080f, 0.257051378488540650f, 0.929650902748107910f, + 0.255734413862228390f, 0.930433452129364010f, 0.254415065050125120f, + 0.931211948394775390f, 0.253093332052230830f, + 0.931986451148986820f, 0.251769185066223140f, 0.932756841182708740f, + 0.250442683696746830f, 0.933523118495941160f, 0.249113827943801880f, + 0.934285342693328860f, 0.247782632708549500f, + 0.935043513774871830f, 0.246449097990989690f, 0.935797572135925290f, + 0.245113238692283630f, 0.936547517776489260f, 0.243775084614753720f, + 0.937293350696563720f, 0.242434620857238770f, + 0.938035070896148680f, 0.241091892123222350f, 0.938772618770599370f, + 0.239746883511543270f, 0.939506113529205320f, 0.238399609923362730f, + 0.940235435962677000f, 0.237050101161003110f, + 0.940960645675659180f, 0.235698372125625610f, 0.941681683063507080f, + 0.234344407916069030f, 0.942398548126220700f, 0.232988253235816960f, + 0.943111240863800050f, 0.231629893183708190f, + 0.943819820880889890f, 0.230269357562065120f, 0.944524168968200680f, + 0.228906646370887760f, 0.945224344730377200f, 0.227541789412498470f, + 0.945920348167419430f, 0.226174786686897280f, + 0.946612179279327390f, 0.224805667996406560f, 0.947299718856811520f, + 0.223434418439865110f, 0.947983145713806150f, 0.222061067819595340f, + 0.948662281036376950f, 0.220685631036758420f, + 0.949337244033813480f, 0.219308122992515560f, 0.950007975101470950f, + 0.217928543686866760f, 0.950674414634704590f, 0.216546908020973210f, + 0.951336681842803960f, 0.215163245797157290f, + 0.951994657516479490f, 0.213777542114257810f, 0.952648401260375980f, + 0.212389841675758360f, 0.953297853469848630f, 0.211000129580497740f, + 0.953943073749542240f, 0.209608450531959530f, + 0.954584002494812010f, 0.208214774727821350f, 0.955220639705657960f, + 0.206819161772727970f, 0.955853044986724850f, 0.205421581864356990f, + 0.956481099128723140f, 0.204022079706192020f, + 0.957104861736297610f, 0.202620655298233030f, 0.957724332809448240f, + 0.201217323541641240f, 0.958339512348175050f, 0.199812099337577820f, + 0.958950400352478030f, 0.198404997587203980f, + 0.959556937217712400f, 0.196996018290519710f, 0.960159122943878170f, + 0.195585191249847410f, 0.960757017135620120f, 0.194172516465187070f, + 0.961350560188293460f, 0.192758023738861080f, + 0.961939752101898190f, 0.191341713070869450f, 0.962524592876434330f, + 0.189923599362373350f, 0.963105142116546630f, 0.188503712415695190f, + 0.963681280612945560f, 0.187082037329673770f, + 0.964253067970275880f, 0.185658603906631470f, 0.964820444583892820f, + 0.184233412146568300f, 0.965383470058441160f, 0.182806491851806640f, + 0.965942144393920900f, 0.181377857923507690f, + 0.966496407985687260f, 0.179947525262832640f, 0.967046260833740230f, + 0.178515478968620300f, 0.967591762542724610f, 0.177081763744354250f, + 0.968132853507995610f, 0.175646379590034480f, + 0.968669533729553220f, 0.174209341406822200f, 0.969201743602752690f, + 0.172770664095878600f, 0.969729602336883540f, 0.171330362558364870f, + 0.970253050327301030f, 0.169888436794281010f, + 0.970772027969360350f, 0.168444931507110600f, 0.971286594867706300f, + 0.166999831795692440f, 0.971796751022338870f, 0.165553152561187740f, + 0.972302436828613280f, 0.164104923605918880f, + 0.972803652286529540f, 0.162655144929885860f, 0.973300457000732420f, + 0.161203846335411070f, 0.973792791366577150f, 0.159751012921333310f, + 0.974280655384063720f, 0.158296689391136170f, + 0.974764108657836910f, 0.156840875744819640f, 0.975243031978607180f, + 0.155383571982383730f, 0.975717484951019290f, 0.153924822807312010f, + 0.976187527179718020f, 0.152464613318443300f, + 0.976653039455413820f, 0.151002973318099980f, 0.977114021778106690f, + 0.149539917707443240f, 0.977570593357086180f, 0.148075446486473080f, + 0.978022634983062740f, 0.146609574556350710f, + 0.978470146656036380f, 0.145142331719398500f, 0.978913187980651860f, + 0.143673732876777650f, 0.979351758956909180f, 0.142203763127326970f, + 0.979785740375518800f, 0.140732467174530030f, + 0.980215251445770260f, 0.139259845018386840f, 0.980640232563018800f, + 0.137785911560058590f, 0.981060683727264400f, 0.136310681700706480f, + 0.981476604938507080f, 0.134834155440330510f, + 0.981888055801391600f, 0.133356377482414250f, 0.982294917106628420f, + 0.131877332925796510f, 0.982697248458862300f, 0.130397051572799680f, + 0.983094990253448490f, 0.128915548324584960f, + 0.983488261699676510f, 0.127432823181152340f, 0.983876943588256840f, + 0.125948905944824220f, 0.984261035919189450f, 0.124463804066181180f, + 0.984640598297119140f, 0.122977524995803830f, + 0.985015630722045900f, 0.121490091085433960f, 0.985386073589324950f, + 0.120001509785652160f, 0.985751926898956300f, 0.118511803448200230f, + 0.986113250255584720f, 0.117020979523658750f, + 0.986469984054565430f, 0.115529052913188930f, 0.986822128295898440f, + 0.114036038517951970f, 0.987169682979583740f, 0.112541958689689640f, + 0.987512648105621340f, 0.111046813428401950f, + 0.987851083278656010f, 0.109550617635250090f, 0.988184869289398190f, + 0.108053401112556460f, 0.988514065742492680f, 0.106555156409740450f, + 0.988838672637939450f, 0.105055920779705050f, + 0.989158689975738530f, 0.103555686771869660f, 0.989474058151245120f, + 0.102054484188556670f, 0.989784896373748780f, 0.100552320480346680f, + 0.990091085433959960f, 0.099049203097820282f, + 0.990392625331878660f, 0.097545161843299866f, 0.990689575672149660f, + 0.096040196716785431f, 0.990981936454772950f, 0.094534330070018768f, + 0.991269648075103760f, 0.093027576804161072f, + 0.991552770137786870f, 0.091519944369792938f, 0.991831183433532710f, + 0.090011447668075562f, 0.992105066776275630f, 0.088502109050750732f, + 0.992374241352081300f, 0.086991935968399048f, + 0.992638826370239260f, 0.085480943322181702f, 0.992898762226104740f, + 0.083969146013259888f, 0.993154048919677730f, 0.082456558942794800f, + 0.993404686450958250f, 0.080943197011947632f, + 0.993650734424591060f, 0.079429075121879578f, 0.993892073631286620f, + 0.077914200723171234f, 0.994128763675689700f, 0.076398596167564392f, + 0.994360864162445070f, 0.074882268905639648f, + 0.994588255882263180f, 0.073365233838558197f, 0.994810998439788820f, + 0.071847513318061829f, 0.995029091835021970f, 0.070329122245311737f, + 0.995242536067962650f, 0.068810060620307922f, + 0.995451331138610840f, 0.067290350794792175f, 0.995655417442321780f, + 0.065770015120506287f, 0.995854854583740230f, 0.064249053597450256f, + 0.996049642562866210f, 0.062727488577365875f, + 0.996239781379699710f, 0.061205338686704636f, 0.996425211429595950f, + 0.059682607650756836f, 0.996605992317199710f, 0.058159314095973969f, + 0.996782064437866210f, 0.056635476648807526f, + 0.996953487396240230f, 0.055111102759838104f, 0.997120201587677000f, + 0.053586211055517197f, 0.997282266616821290f, 0.052060816437005997f, + 0.997439682483673100f, 0.050534930080175400f, + 0.997592389583587650f, 0.049008570611476898f, 0.997740387916564940f, + 0.047481749206781387f, 0.997883677482604980f, 0.045954477041959763f, + 0.998022377490997310f, 0.044426776468753815f, + 0.998156309127807620f, 0.042898654937744141f, 0.998285591602325440f, + 0.041370131075382233f, 0.998410165309906010f, 0.039841219782829285f, + 0.998530030250549320f, 0.038311932235956192f, + 0.998645246028900150f, 0.036782283335924149f, 0.998755753040313720f, + 0.035252287983894348f, 0.998861551284790040f, 0.033721961081027985f, + 0.998962640762329100f, 0.032191313803195953f, + 0.999059081077575680f, 0.030660368502140045f, 0.999150753021240230f, + 0.029129132628440857f, 0.999237775802612300f, 0.027597622945904732f, + 0.999320089817047120f, 0.026065852493047714f, + 0.999397754669189450f, 0.024533838033676147f, 0.999470651149749760f, + 0.023001590743660927f, 0.999538838863372800f, 0.021469129249453545f, + 0.999602377414703370f, 0.019936462864279747f, + 0.999661207199096680f, 0.018403612077236176f, 0.999715328216552730f, + 0.016870586201548576f, 0.999764680862426760f, 0.015337402001023293f, + 0.999809384346008300f, 0.013804072514176369f, + 0.999849438667297360f, 0.012270614504814148f, 0.999884724617004390f, + 0.010737040080130100f, 0.999915301799774170f, 0.009203365072607994f, + 0.999941170215606690f, 0.007669602986425161f, + 0.999962329864501950f, 0.006135769188404083f, 0.999978840351104740f, + 0.004601877182722092f, 0.999990582466125490f, 0.003067942336201668f, + 0.999997675418853760f, 0.001533978385850787f, + 1.000000000000000000f, 0.000000000000023345f, 0.999997675418853760f, + -0.001533978385850787f, 0.999990582466125490f, -0.003067942336201668f, + 0.999978840351104740f, -0.004601877182722092f, + 0.999962329864501950f, -0.006135769188404083f, 0.999941170215606690f, + -0.007669602986425161f, 0.999915301799774170f, -0.009203365072607994f, + 0.999884724617004390f, -0.010737040080130100f, + 0.999849438667297360f, -0.012270614504814148f, 0.999809384346008300f, + -0.013804072514176369f, 0.999764680862426760f, -0.015337402001023293f, + 0.999715328216552730f, -0.016870586201548576f, + 0.999661207199096680f, -0.018403612077236176f, 0.999602377414703370f, + -0.019936462864279747f, 0.999538838863372800f, -0.021469129249453545f, + 0.999470651149749760f, -0.023001590743660927f, + 0.999397754669189450f, -0.024533838033676147f, 0.999320089817047120f, + -0.026065852493047714f, 0.999237775802612300f, -0.027597622945904732f, + 0.999150753021240230f, -0.029129132628440857f, + 0.999059081077575680f, -0.030660368502140045f, 0.998962640762329100f, + -0.032191313803195953f, 0.998861551284790040f, -0.033721961081027985f, + 0.998755753040313720f, -0.035252287983894348f, + 0.998645246028900150f, -0.036782283335924149f, 0.998530030250549320f, + -0.038311932235956192f, 0.998410165309906010f, -0.039841219782829285f, + 0.998285591602325440f, -0.041370131075382233f, + 0.998156309127807620f, -0.042898654937744141f, 0.998022377490997310f, + -0.044426776468753815f, 0.997883677482604980f, -0.045954477041959763f, + 0.997740387916564940f, -0.047481749206781387f, + 0.997592389583587650f, -0.049008570611476898f, 0.997439682483673100f, + -0.050534930080175400f, 0.997282266616821290f, -0.052060816437005997f, + 0.997120201587677000f, -0.053586211055517197f, + 0.996953487396240230f, -0.055111102759838104f, 0.996782064437866210f, + -0.056635476648807526f, 0.996605992317199710f, -0.058159314095973969f, + 0.996425211429595950f, -0.059682607650756836f, + 0.996239781379699710f, -0.061205338686704636f, 0.996049642562866210f, + -0.062727488577365875f, 0.995854854583740230f, -0.064249053597450256f, + 0.995655417442321780f, -0.065770015120506287f, + 0.995451331138610840f, -0.067290350794792175f, 0.995242536067962650f, + -0.068810060620307922f, 0.995029091835021970f, -0.070329122245311737f, + 0.994810998439788820f, -0.071847513318061829f, + 0.994588255882263180f, -0.073365233838558197f, 0.994360864162445070f, + -0.074882268905639648f, 0.994128763675689700f, -0.076398596167564392f, + 0.993892073631286620f, -0.077914200723171234f, + 0.993650734424591060f, -0.079429075121879578f, 0.993404686450958250f, + -0.080943197011947632f, 0.993154048919677730f, -0.082456558942794800f, + 0.992898762226104740f, -0.083969146013259888f, + 0.992638826370239260f, -0.085480943322181702f, 0.992374241352081300f, + -0.086991935968399048f, 0.992105066776275630f, -0.088502109050750732f, + 0.991831183433532710f, -0.090011447668075562f, + 0.991552770137786870f, -0.091519944369792938f, 0.991269648075103760f, + -0.093027576804161072f, 0.990981936454772950f, -0.094534330070018768f, + 0.990689575672149660f, -0.096040196716785431f, + 0.990392625331878660f, -0.097545161843299866f, 0.990091085433959960f, + -0.099049203097820282f, 0.989784896373748780f, -0.100552320480346680f, + 0.989474058151245120f, -0.102054484188556670f, + 0.989158689975738530f, -0.103555686771869660f, 0.988838672637939450f, + -0.105055920779705050f, 0.988514065742492680f, -0.106555156409740450f, + 0.988184869289398190f, -0.108053401112556460f, + 0.987851083278656010f, -0.109550617635250090f, 0.987512648105621340f, + -0.111046813428401950f, 0.987169682979583740f, -0.112541958689689640f, + 0.986822128295898440f, -0.114036038517951970f, + 0.986469984054565430f, -0.115529052913188930f, 0.986113250255584720f, + -0.117020979523658750f, 0.985751926898956300f, -0.118511803448200230f, + 0.985386073589324950f, -0.120001509785652160f, + 0.985015630722045900f, -0.121490091085433960f, 0.984640598297119140f, + -0.122977524995803830f, 0.984261035919189450f, -0.124463804066181180f, + 0.983876943588256840f, -0.125948905944824220f, + 0.983488261699676510f, -0.127432823181152340f, 0.983094990253448490f, + -0.128915548324584960f, 0.982697248458862300f, -0.130397051572799680f, + 0.982294917106628420f, -0.131877332925796510f, + 0.981888055801391600f, -0.133356377482414250f, 0.981476604938507080f, + -0.134834155440330510f, 0.981060683727264400f, -0.136310681700706480f, + 0.980640232563018800f, -0.137785911560058590f, + 0.980215251445770260f, -0.139259845018386840f, 0.979785740375518800f, + -0.140732467174530030f, 0.979351758956909180f, -0.142203763127326970f, + 0.978913187980651860f, -0.143673732876777650f, + 0.978470146656036380f, -0.145142331719398500f, 0.978022634983062740f, + -0.146609574556350710f, 0.977570593357086180f, -0.148075446486473080f, + 0.977114021778106690f, -0.149539917707443240f, + 0.976653039455413820f, -0.151002973318099980f, 0.976187527179718020f, + -0.152464613318443300f, 0.975717484951019290f, -0.153924822807312010f, + 0.975243031978607180f, -0.155383571982383730f, + 0.974764108657836910f, -0.156840875744819640f, 0.974280655384063720f, + -0.158296689391136170f, 0.973792791366577150f, -0.159751012921333310f, + 0.973300457000732420f, -0.161203846335411070f, + 0.972803652286529540f, -0.162655144929885860f, 0.972302436828613280f, + -0.164104923605918880f, 0.971796751022338870f, -0.165553152561187740f, + 0.971286594867706300f, -0.166999831795692440f, + 0.970772027969360350f, -0.168444931507110600f, 0.970253050327301030f, + -0.169888436794281010f, 0.969729602336883540f, -0.171330362558364870f, + 0.969201743602752690f, -0.172770664095878600f, + 0.968669533729553220f, -0.174209341406822200f, 0.968132853507995610f, + -0.175646379590034480f, 0.967591762542724610f, -0.177081763744354250f, + 0.967046260833740230f, -0.178515478968620300f, + 0.966496407985687260f, -0.179947525262832640f, 0.965942144393920900f, + -0.181377857923507690f, 0.965383470058441160f, -0.182806491851806640f, + 0.964820444583892820f, -0.184233412146568300f, + 0.964253067970275880f, -0.185658603906631470f, 0.963681280612945560f, + -0.187082037329673770f, 0.963105142116546630f, -0.188503712415695190f, + 0.962524592876434330f, -0.189923599362373350f, + 0.961939752101898190f, -0.191341713070869450f, 0.961350560188293460f, + -0.192758023738861080f, 0.960757017135620120f, -0.194172516465187070f, + 0.960159122943878170f, -0.195585191249847410f, + 0.959556937217712400f, -0.196996018290519710f, 0.958950400352478030f, + -0.198404997587203980f, 0.958339512348175050f, -0.199812099337577820f, + 0.957724332809448240f, -0.201217323541641240f, + 0.957104861736297610f, -0.202620655298233030f, 0.956481099128723140f, + -0.204022079706192020f, 0.955853044986724850f, -0.205421581864356990f, + 0.955220639705657960f, -0.206819161772727970f, + 0.954584002494812010f, -0.208214774727821350f, 0.953943073749542240f, + -0.209608450531959530f, 0.953297853469848630f, -0.211000129580497740f, + 0.952648401260375980f, -0.212389841675758360f, + 0.951994657516479490f, -0.213777542114257810f, 0.951336681842803960f, + -0.215163245797157290f, 0.950674414634704590f, -0.216546908020973210f, + 0.950007975101470950f, -0.217928543686866760f, + 0.949337244033813480f, -0.219308122992515560f, 0.948662281036376950f, + -0.220685631036758420f, 0.947983145713806150f, -0.222061067819595340f, + 0.947299718856811520f, -0.223434418439865110f, + 0.946612179279327390f, -0.224805667996406560f, 0.945920348167419430f, + -0.226174786686897280f, 0.945224344730377200f, -0.227541789412498470f, + 0.944524168968200680f, -0.228906646370887760f, + 0.943819820880889890f, -0.230269357562065120f, 0.943111240863800050f, + -0.231629893183708190f, 0.942398548126220700f, -0.232988253235816960f, + 0.941681683063507080f, -0.234344407916069030f, + 0.940960645675659180f, -0.235698372125625610f, 0.940235435962677000f, + -0.237050101161003110f, 0.939506113529205320f, -0.238399609923362730f, + 0.938772618770599370f, -0.239746883511543270f, + 0.938035070896148680f, -0.241091892123222350f, 0.937293350696563720f, + -0.242434620857238770f, 0.936547517776489260f, -0.243775084614753720f, + 0.935797572135925290f, -0.245113238692283630f, + 0.935043513774871830f, -0.246449097990989690f, 0.934285342693328860f, + -0.247782632708549500f, 0.933523118495941160f, -0.249113827943801880f, + 0.932756841182708740f, -0.250442683696746830f, + 0.931986451148986820f, -0.251769185066223140f, 0.931211948394775390f, + -0.253093332052230830f, 0.930433452129364010f, -0.254415065050125120f, + 0.929650902748107910f, -0.255734413862228390f, + 0.928864300251007080f, -0.257051378488540650f, 0.928073644638061520f, + -0.258365899324417110f, 0.927278995513916020f, -0.259678006172180180f, + 0.926480293273925780f, -0.260987639427185060f, + 0.925677597522735600f, -0.262294828891754150f, 0.924870908260345460f, + -0.263599574565887450f, 0.924060165882110600f, -0.264901816844940190f, + 0.923245489597320560f, -0.266201555728912350f, + 0.922426760196685790f, -0.267498821020126340f, 0.921604096889495850f, + -0.268793523311614990f, 0.920777499675750730f, -0.270085722208023070f, + 0.919946908950805660f, -0.271375387907028200f, + 0.919112324714660640f, -0.272662490606307980f, 0.918273866176605220f, + -0.273947030305862430f, 0.917431414127349850f, -0.275228977203369140f, + 0.916585087776184080f, -0.276508361101150510f, + 0.915734827518463130f, -0.277785122394561770f, 0.914880633354187010f, + -0.279059261083602910f, 0.914022505283355710f, -0.280330777168273930f, + 0.913160502910614010f, -0.281599670648574830f, + 0.912294626235961910f, -0.282865911722183230f, 0.911424875259399410f, + -0.284129470586776730f, 0.910551249980926510f, -0.285390377044677730f, + 0.909673750400543210f, -0.286648571491241460f, + 0.908792436122894290f, -0.287904083728790280f, 0.907907187938690190f, + -0.289156883955001830f, 0.907018184661865230f, -0.290406972169876100f, + 0.906125307083129880f, -0.291654318571090700f, + 0.905228614807128910f, -0.292898923158645630f, 0.904328107833862300f, + -0.294140785932540890f, 0.903423786163330080f, -0.295379847288131710f, + 0.902515649795532230f, -0.296616137027740480f, + 0.901603758335113530f, -0.297849655151367190f, 0.900688111782073970f, + -0.299080342054367070f, 0.899768650531768800f, -0.300308227539062500f, + 0.898845434188842770f, -0.301533311605453490f, + 0.897918462753295900f, -0.302755534648895260f, 0.896987736225128170f, + -0.303974896669387820f, 0.896053314208984380f, -0.305191397666931150f, + 0.895115137100219730f, -0.306405037641525270f, + 0.894173204898834230f, -0.307615786790847780f, 0.893227577209472660f, + -0.308823645114898680f, 0.892278313636779790f, -0.310028612613677980f, + 0.891325294971466060f, -0.311230629682540890f, + 0.890368640422821040f, -0.312429755926132200f, 0.889408230781555180f, + -0.313625901937484740f, 0.888444244861602780f, -0.314819127321243290f, + 0.887476563453674320f, -0.316009372472763060f, + 0.886505246162414550f, -0.317196637392044070f, 0.885530233383178710f, + -0.318380922079086300f, 0.884551644325256350f, -0.319562226533889770f, + 0.883569478988647460f, -0.320740520954132080f, + 0.882583618164062500f, -0.321915775537490840f, 0.881594181060791020f, + -0.323088020086288450f, 0.880601167678833010f, -0.324257194995880130f, + 0.879604578018188480f, -0.325423330068588260f, + 0.878604412078857420f, -0.326586425304412840f, 0.877600669860839840f, + -0.327746421098709110f, 0.876593410968780520f, -0.328903347253799440f, + 0.875582575798034670f, -0.330057173967361450f, + 0.874568223953247070f, -0.331207901239395140f, 0.873550295829772950f, + -0.332355499267578130f, 0.872528910636901860f, -0.333499968051910400f, + 0.871503949165344240f, -0.334641307592391970f, + 0.870475590229034420f, -0.335779488086700440f, 0.869443655014038090f, + -0.336914509534835820f, 0.868408262729644780f, -0.338046342134475710f, + 0.867369413375854490f, -0.339175015687942500f, + 0.866327106952667240f, -0.340300500392913820f, 0.865281403064727780f, + -0.341422766447067260f, 0.864232182502746580f, -0.342541843652725220f, + 0.863179564476013180f, -0.343657672405242920f, + 0.862123548984527590f, -0.344770282506942750f, 0.861064076423645020f, + -0.345879614353179930f, 0.860001266002655030f, -0.346985727548599240f, + 0.858934998512268070f, -0.348088562488555910f, + 0.857865393161773680f, -0.349188119173049930f, 0.856792449951171880f, + -0.350284397602081300f, 0.855716109275817870f, -0.351377367973327640f, + 0.854636430740356450f, -0.352467030286788940f, + 0.853553414344787600f, -0.353553384542465210f, 0.852467060089111330f, + -0.354636400938034060f, 0.851377367973327640f, -0.355716109275817870f, + 0.850284397602081300f, -0.356792420148849490f, + 0.849188148975372310f, -0.357865422964096070f, 0.848088562488555910f, + -0.358935028314590450f, 0.846985757350921630f, -0.360001266002655030f, + 0.845879614353179930f, -0.361064106225967410f, + 0.844770252704620360f, -0.362123548984527590f, 0.843657672405242920f, + -0.363179564476013180f, 0.842541813850402830f, -0.364232182502746580f, + 0.841422796249389650f, -0.365281373262405400f, + 0.840300500392913820f, -0.366327136754989620f, 0.839175045490264890f, + -0.367369443178176880f, 0.838046371936798100f, -0.368408292531967160f, + 0.836914479732513430f, -0.369443655014038090f, + 0.835779488086700440f, -0.370475560426712040f, 0.834641277790069580f, + -0.371503978967666630f, 0.833499968051910400f, -0.372528880834579470f, + 0.832355499267578130f, -0.373550295829772950f, + 0.831207871437072750f, -0.374568194150924680f, 0.830057144165039060f, + -0.375582575798034670f, 0.828903317451477050f, -0.376593410968780520f, + 0.827746450901031490f, -0.377600699663162230f, + 0.826586425304412840f, -0.378604412078857420f, 0.825423359870910640f, + -0.379604607820510860f, 0.824257194995880130f, -0.380601197481155400f, + 0.823087990283966060f, -0.381594210863113400f, + 0.821915745735168460f, -0.382583618164062500f, 0.820740520954132080f, + -0.383569449186325070f, 0.819562196731567380f, -0.384551674127578740f, + 0.818380951881408690f, -0.385530263185501100f, + 0.817196667194366460f, -0.386505216360092160f, 0.816009342670440670f, + -0.387476563453674320f, 0.814819097518920900f, -0.388444244861602780f, + 0.813625931739807130f, -0.389408260583877560f, + 0.812429726123809810f, -0.390368610620498660f, 0.811230659484863280f, + -0.391325294971466060f, 0.810028612613677980f, -0.392278283834457400f, + 0.808823645114898680f, -0.393227607011795040f, + 0.807615816593170170f, -0.394173204898834230f, 0.806405067443847660f, + -0.395115107297897340f, 0.805191397666931150f, -0.396053284406661990f, + 0.803974866867065430f, -0.396987736225128170f, + 0.802755534648895260f, -0.397918462753295900f, 0.801533281803131100f, + -0.398845434188842770f, 0.800308227539062500f, -0.399768620729446410f, + 0.799080371856689450f, -0.400688081979751590f, + 0.797849655151367190f, -0.401603758335113530f, 0.796616137027740480f, + -0.402515679597854610f, 0.795379877090454100f, -0.403423786163330080f, + 0.794140756130218510f, -0.404328078031539920f, + 0.792898952960968020f, -0.405228585004806520f, 0.791654348373413090f, + -0.406125307083129880f, 0.790407001972198490f, -0.407018154859542850f, + 0.789156913757324220f, -0.407907217741012570f, + 0.787904083728790280f, -0.408792406320571900f, 0.786648571491241460f, + -0.409673750400543210f, 0.785390377044677730f, -0.410551249980926510f, + 0.784129500389099120f, -0.411424905061721800f, + 0.782865881919860840f, -0.412294656038284300f, 0.781599700450897220f, + -0.413160532712936400f, 0.780330777168273930f, -0.414022535085678100f, + 0.779059290885925290f, -0.414880603551864620f, + 0.777785122394561770f, -0.415734797716140750f, 0.776508331298828130f, + -0.416585087776184080f, 0.775228977203369140f, -0.417431443929672240f, + 0.773947000503540040f, -0.418273866176605220f, + 0.772662520408630370f, -0.419112354516983030f, 0.771375417709350590f, + -0.419946908950805660f, 0.770085752010345460f, -0.420777499675750730f, + 0.768793523311614990f, -0.421604126691818240f, + 0.767498791217803960f, -0.422426789999008180f, 0.766201555728912350f, + -0.423245459794998170f, 0.764901816844940190f, -0.424060165882110600f, + 0.763599574565887450f, -0.424870878458023070f, + 0.762294828891754150f, -0.425677597522735600f, 0.760987639427185060f, + -0.426480293273925780f, 0.759678006172180180f, -0.427278995513916020f, + 0.758365929126739500f, -0.428073674440383910f, + 0.757051348686218260f, -0.428864300251007080f, 0.755734443664550780f, + -0.429650902748107910f, 0.754415094852447510f, -0.430433481931686400f, + 0.753093302249908450f, -0.431211978197097780f, + 0.751769185066223140f, -0.431986421346664430f, 0.750442683696746830f, + -0.432756811380386350f, 0.749113857746124270f, -0.433523118495941160f, + 0.747782647609710690f, -0.434285342693328860f, + 0.746449112892150880f, -0.435043483972549440f, 0.745113253593444820f, + -0.435797542333602910f, 0.743775069713592530f, -0.436547487974166870f, + 0.742434620857238770f, -0.437293320894241330f, + 0.741091907024383540f, -0.438035041093826290f, 0.739746868610382080f, + -0.438772648572921750f, 0.738399624824523930f, -0.439506113529205320f, + 0.737050116062164310f, -0.440235435962677000f, + 0.735698342323303220f, -0.440960645675659180f, 0.734344422817230220f, + -0.441681683063507080f, 0.732988238334655760f, -0.442398548126220700f, + 0.731629908084869380f, -0.443111270666122440f, + 0.730269372463226320f, -0.443819820880889890f, 0.728906631469726560f, + -0.444524168968200680f, 0.727541804313659670f, -0.445224374532699580f, + 0.726174771785736080f, -0.445920348167419430f, + 0.724805653095245360f, -0.446612149477005000f, 0.723434448242187500f, + -0.447299748659133910f, 0.722061097621917720f, -0.447983115911483760f, + 0.720685660839080810f, -0.448662281036376950f, + 0.719308137893676760f, -0.449337244033813480f, 0.717928528785705570f, + -0.450007945299148560f, 0.716546893119812010f, -0.450674414634704590f, + 0.715163230895996090f, -0.451336652040481570f, + 0.713777542114257810f, -0.451994657516479490f, 0.712389826774597170f, + -0.452648371458053590f, 0.711000144481658940f, -0.453297853469848630f, + 0.709608435630798340f, -0.453943043947219850f, + 0.708214759826660160f, -0.454584002494812010f, 0.706819176673889160f, + -0.455220639705657960f, 0.705421566963195800f, -0.455853015184402470f, + 0.704022109508514400f, -0.456481099128723140f, + 0.702620685100555420f, -0.457104891538620000f, 0.701217353343963620f, + -0.457724362611770630f, 0.699812114238739010f, -0.458339542150497440f, + 0.698404967784881590f, -0.458950400352478030f, + 0.696996033191680910f, -0.459556937217712400f, 0.695585191249847410f, + -0.460159152746200560f, 0.694172501564025880f, -0.460757017135620120f, + 0.692758023738861080f, -0.461350560188293460f, + 0.691341698169708250f, -0.461939752101898190f, 0.689923584461212160f, + -0.462524622678756710f, 0.688503682613372800f, -0.463105112314224240f, + 0.687082052230834960f, -0.463681250810623170f, + 0.685658574104309080f, -0.464253038167953490f, 0.684233427047729490f, + -0.464820444583892820f, 0.682806491851806640f, -0.465383470058441160f, + 0.681377887725830080f, -0.465942144393920900f, + 0.679947495460510250f, -0.466496407985687260f, 0.678515493869781490f, + -0.467046260833740230f, 0.677081763744354250f, -0.467591762542724610f, + 0.675646364688873290f, -0.468132823705673220f, + 0.674209356307983400f, -0.468669503927230830f, 0.672770678997039790f, + -0.469201773405075070f, 0.671330332756042480f, -0.469729602336883540f, + 0.669888436794281010f, -0.470253020524978640f, + 0.668444931507110600f, -0.470772027969360350f, 0.666999816894531250f, + -0.471286594867706300f, 0.665553152561187740f, -0.471796721220016480f, + 0.664104938507080080f, -0.472302407026290890f, + 0.662655174732208250f, -0.472803652286529540f, 0.661203861236572270f, + -0.473300457000732420f, 0.659750998020172120f, -0.473792791366577150f, + 0.658296704292297360f, -0.474280685186386110f, + 0.656840860843658450f, -0.474764078855514530f, 0.655383586883544920f, + -0.475243031978607180f, 0.653924822807312010f, -0.475717514753341670f, + 0.652464628219604490f, -0.476187497377395630f, + 0.651003003120422360f, -0.476653009653091430f, 0.649539887905120850f, + -0.477114051580429080f, 0.648075461387634280f, -0.477570593357086180f, + 0.646609604358673100f, -0.478022634983062740f, + 0.645142316818237300f, -0.478470176458358760f, 0.643673717975616460f, + -0.478913217782974240f, 0.642203748226165770f, -0.479351729154586790f, + 0.640732467174530030f, -0.479785770177841190f, + 0.639259815216064450f, -0.480215251445770260f, 0.637785911560058590f, + -0.480640232563018800f, 0.636310696601867680f, -0.481060713529586790f, + 0.634834170341491700f, -0.481476634740829470f, + 0.633356392383575440f, -0.481888025999069210f, 0.631877362728118900f, + -0.482294887304306030f, 0.630397081375122070f, -0.482697218656539920f, + 0.628915548324584960f, -0.483094990253448490f, + 0.627432823181152340f, -0.483488231897354130f, 0.625948905944824220f, + -0.483876913785934450f, 0.624463796615600590f, -0.484261035919189450f, + 0.622977554798126220f, -0.484640628099441530f, + 0.621490061283111570f, -0.485015630722045900f, 0.620001494884490970f, + -0.485386073589324950f, 0.618511795997619630f, -0.485751956701278690f, + 0.617020964622497560f, -0.486113250255584720f, + 0.615529060363769530f, -0.486469984054565430f, 0.614036023616790770f, + -0.486822128295898440f, 0.612541973590850830f, -0.487169682979583740f, + 0.611046791076660160f, -0.487512677907943730f, + 0.609550595283508300f, -0.487851053476333620f, 0.608053386211395260f, + -0.488184869289398190f, 0.606555163860321040f, -0.488514065742492680f, + 0.605055928230285640f, -0.488838672637939450f, + 0.603555679321289060f, -0.489158689975738530f, 0.602054476737976070f, + -0.489474087953567500f, 0.600552320480346680f, -0.489784896373748780f, + 0.599049210548400880f, -0.490091055631637570f, + 0.597545146942138670f, -0.490392625331878660f, 0.596040189266204830f, + -0.490689605474472050f, 0.594534337520599370f, -0.490981936454772950f, + 0.593027591705322270f, -0.491269648075103760f, + 0.591519951820373540f, -0.491552740335464480f, 0.590011477470397950f, + -0.491831213235855100f, 0.588502109050750730f, -0.492105036973953250f, + 0.586991965770721440f, -0.492374241352081300f, + 0.585480928421020510f, -0.492638826370239260f, 0.583969175815582280f, + -0.492898762226104740f, 0.582456588745117190f, -0.493154048919677730f, + 0.580943167209625240f, -0.493404686450958250f, + 0.579429090023040770f, -0.493650704622268680f, 0.577914178371429440f, + -0.493892073631286620f, 0.576398611068725590f, -0.494128793478012080f, + 0.574882268905639650f, -0.494360834360122680f, + 0.573365211486816410f, -0.494588255882263180f, 0.571847498416900630f, + -0.494810998439788820f, 0.570329129695892330f, -0.495029091835021970f, + 0.568810045719146730f, -0.495242536067962650f, + 0.567290365695953370f, -0.495451331138610840f, 0.565770030021667480f, + -0.495655417442321780f, 0.564249038696289060f, -0.495854884386062620f, + 0.562727510929107670f, -0.496049642562866210f, + 0.561205327510833740f, -0.496239781379699710f, 0.559682607650756840f, + -0.496425211429595950f, 0.558159291744232180f, -0.496605962514877320f, + 0.556635499000549320f, -0.496782064437866210f, + 0.555111110210418700f, -0.496953487396240230f, 0.553586184978485110f, + -0.497120231389999390f, 0.552060842514038090f, -0.497282296419143680f, + 0.550534904003143310f, -0.497439652681350710f, + 0.549008548259735110f, -0.497592359781265260f, 0.547481775283813480f, + -0.497740387916564940f, 0.545954465866088870f, -0.497883707284927370f, + 0.544426798820495610f, -0.498022347688674930f, + 0.542898654937744140f, -0.498156309127807620f, 0.541370153427124020f, + -0.498285561800003050f, 0.539841234683990480f, -0.498410135507583620f, + 0.538311958312988280f, -0.498530030250549320f, + 0.536782264709472660f, -0.498645216226577760f, 0.535252273082733150f, + -0.498755723237991330f, 0.533721983432769780f, -0.498861521482467650f, + 0.532191336154937740f, -0.498962640762329100f, + 0.530660390853881840f, -0.499059051275253300f, 0.529129147529602050f, + -0.499150782823562620f, 0.527597606182098390f, -0.499237775802612300f, + 0.526065826416015630f, -0.499320119619369510f, + 0.524533808231353760f, -0.499397724866867070f, 0.523001611232757570f, + -0.499470651149749760f, 0.521469116210937500f, -0.499538868665695190f, + 0.519936442375183110f, -0.499602377414703370f, + 0.518403589725494380f, -0.499661177396774290f, 0.516870558261871340f, + -0.499715298414230350f, 0.515337407588958740f, -0.499764710664749150f, + 0.513804078102111820f, -0.499809414148330690f, + 0.512270629405975340f, -0.499849408864974980f, 0.510737061500549320f, + -0.499884694814682010f, 0.509203374385833740f, -0.499915301799774170f, + 0.507669627666473390f, -0.499941170215606690f, + 0.506135761737823490f, -0.499962359666824340f, 0.504601895809173580f, + -0.499978810548782350f, 0.503067970275878910f, -0.499990582466125490f, + 0.501533985137939450f, -0.499997645616531370f +}; + + + +/** +* @brief Initialization function for the floating-point RFFT/RIFFT. +* @param[in,out] *S points to an instance of the floating-point RFFT/RIFFT structure. +* @param[in,out] *S_CFFT points to an instance of the floating-point CFFT/CIFFT structure. +* @param[in] fftLenReal length of the FFT. +* @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. +* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. +* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. +* +* \par Description: +* \par +* The parameter fftLenReal Specifies length of RFFT/RIFFT Process. Supported FFT Lengths are 128, 512, 2048. +* \par +* The parameter ifftFlagR controls whether a forward or inverse transform is computed. +* Set(=1) ifftFlagR to calculate RIFFT, otherwise RFFT is calculated. +* \par +* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. +* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. +* \par +* This function also initializes Twiddle factor table. +*/ + +arm_status arm_rfft_init_f32( + arm_rfft_instance_f32 * S, + arm_cfft_radix4_instance_f32 * S_CFFT, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag) +{ + + /* Initialise the default arm status */ + arm_status status = ARM_MATH_SUCCESS; + + /* Initialize the Real FFT length */ + S->fftLenReal = (uint16_t) fftLenReal; + + /* Initialize the Complex FFT length */ + S->fftLenBy2 = (uint16_t) fftLenReal / 2u; + + /* Initialize the Twiddle coefficientA pointer */ + S->pTwiddleAReal = (float32_t *) realCoefA; + + /* Initialize the Twiddle coefficientB pointer */ + S->pTwiddleBReal = (float32_t *) realCoefB; + + /* Initialize the Flag for selection of RFFT or RIFFT */ + S->ifftFlagR = (uint8_t) ifftFlagR; + + /* Initialize the Flag for calculation Bit reversal or not */ + S->bitReverseFlagR = (uint8_t) bitReverseFlag; + + /* Initializations of structure parameters depending on the FFT length */ + switch (S->fftLenReal) + { + /* Init table modifier value */ + case 2048u: + S->twidCoefRModifier = 1u; + break; + case 512u: + S->twidCoefRModifier = 4u; + break; + case 128u: + S->twidCoefRModifier = 16u; + break; + default: + /* Reporting argument error if rfftSize is not valid value */ + status = ARM_MATH_ARGUMENT_ERROR; + break; + } + + /* Init Complex FFT Instance */ + S->pCfft = S_CFFT; + + if(S->ifftFlagR) + { + /* Initializes the CIFFT Module for fftLenreal/2 length */ + arm_cfft_radix4_init_f32(S->pCfft, S->fftLenBy2, 1u, 0u); + } + else + { + /* Initializes the CFFT Module for fftLenreal/2 length */ + arm_cfft_radix4_init_f32(S->pCfft, S->fftLenBy2, 0u, 0u); + } + + /* return the status of RFFT Init function */ + return (status); + +} + + /** + * @} end of RFFT_RIFFT group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q15.c index 61bcc556a..843a33bce 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q15.c @@ -1,688 +1,688 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_init_q15.c -* -* Description: RFFT & RIFFT Q15 initialisation function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - - - -/** -* \par -* Generation floating point real_CoefA array: -* \par -* n = 1024 -*
for (i = 0; i < n; i++)   
-*  {   
-*    pATable[2 * i] = 0.5 * (1.0 - sin (2 * PI / (double) (2 * n) * (double) i));   
-*    pATable[2 * i + 1] = 0.5 * (-1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
-*  } 
-* \par -* Convert to fixed point Q15 format -* round(pATable[i] * pow(2, 15)) -*/ - - -static const q15_t realCoefAQ15[2048] = { - - 0x4000, 0xc000, 0x3fce, 0xc000, 0x3f9b, 0xc000, 0x3f69, 0xc001, - 0x3f37, 0xc001, 0x3f05, 0xc002, 0x3ed2, 0xc003, 0x3ea0, 0xc004, - 0x3e6e, 0xc005, 0x3e3c, 0xc006, 0x3e09, 0xc008, 0x3dd7, 0xc009, - 0x3da5, 0xc00b, 0x3d73, 0xc00d, 0x3d40, 0xc00f, 0x3d0e, 0xc011, - 0x3cdc, 0xc014, 0x3caa, 0xc016, 0x3c78, 0xc019, 0x3c45, 0xc01c, - 0x3c13, 0xc01f, 0x3be1, 0xc022, 0x3baf, 0xc025, 0x3b7d, 0xc029, - 0x3b4b, 0xc02c, 0x3b19, 0xc030, 0x3ae6, 0xc034, 0x3ab4, 0xc038, - 0x3a82, 0xc03c, 0x3a50, 0xc041, 0x3a1e, 0xc045, 0x39ec, 0xc04a, - 0x39ba, 0xc04f, 0x3988, 0xc054, 0x3956, 0xc059, 0x3924, 0xc05e, - 0x38f2, 0xc064, 0x38c0, 0xc069, 0x388e, 0xc06f, 0x385c, 0xc075, - 0x382a, 0xc07b, 0x37f9, 0xc081, 0x37c7, 0xc088, 0x3795, 0xc08e, - 0x3763, 0xc095, 0x3731, 0xc09c, 0x36ff, 0xc0a3, 0x36ce, 0xc0aa, - 0x369c, 0xc0b1, 0x366a, 0xc0b9, 0x3639, 0xc0c0, 0x3607, 0xc0c8, - 0x35d5, 0xc0d0, 0x35a4, 0xc0d8, 0x3572, 0xc0e0, 0x3540, 0xc0e9, - 0x350f, 0xc0f1, 0x34dd, 0xc0fa, 0x34ac, 0xc103, 0x347b, 0xc10c, - 0x3449, 0xc115, 0x3418, 0xc11e, 0x33e6, 0xc128, 0x33b5, 0xc131, - 0x3384, 0xc13b, 0x3352, 0xc145, 0x3321, 0xc14f, 0x32f0, 0xc159, - 0x32bf, 0xc163, 0x328e, 0xc16e, 0x325c, 0xc178, 0x322b, 0xc183, - 0x31fa, 0xc18e, 0x31c9, 0xc199, 0x3198, 0xc1a4, 0x3167, 0xc1b0, - 0x3136, 0xc1bb, 0x3105, 0xc1c7, 0x30d5, 0xc1d3, 0x30a4, 0xc1df, - 0x3073, 0xc1eb, 0x3042, 0xc1f7, 0x3012, 0xc204, 0x2fe1, 0xc210, - 0x2fb0, 0xc21d, 0x2f80, 0xc22a, 0x2f4f, 0xc237, 0x2f1f, 0xc244, - 0x2eee, 0xc251, 0x2ebe, 0xc25f, 0x2e8d, 0xc26d, 0x2e5d, 0xc27a, - 0x2e2d, 0xc288, 0x2dfc, 0xc296, 0x2dcc, 0xc2a5, 0x2d9c, 0xc2b3, - 0x2d6c, 0xc2c1, 0x2d3c, 0xc2d0, 0x2d0c, 0xc2df, 0x2cdc, 0xc2ee, - 0x2cac, 0xc2fd, 0x2c7c, 0xc30c, 0x2c4c, 0xc31c, 0x2c1c, 0xc32b, - 0x2bed, 0xc33b, 0x2bbd, 0xc34b, 0x2b8d, 0xc35b, 0x2b5e, 0xc36b, - 0x2b2e, 0xc37b, 0x2aff, 0xc38c, 0x2acf, 0xc39c, 0x2aa0, 0xc3ad, - 0x2a70, 0xc3be, 0x2a41, 0xc3cf, 0x2a12, 0xc3e0, 0x29e3, 0xc3f1, - 0x29b4, 0xc403, 0x2984, 0xc414, 0x2955, 0xc426, 0x2926, 0xc438, - 0x28f7, 0xc44a, 0x28c9, 0xc45c, 0x289a, 0xc46e, 0x286b, 0xc481, - 0x283c, 0xc493, 0x280e, 0xc4a6, 0x27df, 0xc4b9, 0x27b1, 0xc4cc, - 0x2782, 0xc4df, 0x2754, 0xc4f2, 0x2725, 0xc506, 0x26f7, 0xc51a, - 0x26c9, 0xc52d, 0x269b, 0xc541, 0x266d, 0xc555, 0x263f, 0xc569, - 0x2611, 0xc57e, 0x25e3, 0xc592, 0x25b5, 0xc5a7, 0x2587, 0xc5bb, - 0x2559, 0xc5d0, 0x252c, 0xc5e5, 0x24fe, 0xc5fa, 0x24d0, 0xc610, - 0x24a3, 0xc625, 0x2476, 0xc63b, 0x2448, 0xc650, 0x241b, 0xc666, - 0x23ee, 0xc67c, 0x23c1, 0xc692, 0x2394, 0xc6a8, 0x2367, 0xc6bf, - 0x233a, 0xc6d5, 0x230d, 0xc6ec, 0x22e0, 0xc703, 0x22b3, 0xc71a, - 0x2287, 0xc731, 0x225a, 0xc748, 0x222d, 0xc75f, 0x2201, 0xc777, - 0x21d5, 0xc78f, 0x21a8, 0xc7a6, 0x217c, 0xc7be, 0x2150, 0xc7d6, - 0x2124, 0xc7ee, 0x20f8, 0xc807, 0x20cc, 0xc81f, 0x20a0, 0xc838, - 0x2074, 0xc850, 0x2049, 0xc869, 0x201d, 0xc882, 0x1ff1, 0xc89b, - 0x1fc6, 0xc8b5, 0x1f9b, 0xc8ce, 0x1f6f, 0xc8e8, 0x1f44, 0xc901, - 0x1f19, 0xc91b, 0x1eee, 0xc935, 0x1ec3, 0xc94f, 0x1e98, 0xc969, - 0x1e6d, 0xc983, 0x1e42, 0xc99e, 0x1e18, 0xc9b8, 0x1ded, 0xc9d3, - 0x1dc3, 0xc9ee, 0x1d98, 0xca09, 0x1d6e, 0xca24, 0x1d44, 0xca3f, - 0x1d19, 0xca5b, 0x1cef, 0xca76, 0x1cc5, 0xca92, 0x1c9b, 0xcaad, - 0x1c72, 0xcac9, 0x1c48, 0xcae5, 0x1c1e, 0xcb01, 0x1bf5, 0xcb1e, - 0x1bcb, 0xcb3a, 0x1ba2, 0xcb56, 0x1b78, 0xcb73, 0x1b4f, 0xcb90, - 0x1b26, 0xcbad, 0x1afd, 0xcbca, 0x1ad4, 0xcbe7, 0x1aab, 0xcc04, - 0x1a82, 0xcc21, 0x1a5a, 0xcc3f, 0x1a31, 0xcc5d, 0x1a08, 0xcc7a, - 0x19e0, 0xcc98, 0x19b8, 0xccb6, 0x198f, 0xccd4, 0x1967, 0xccf3, - 0x193f, 0xcd11, 0x1917, 0xcd30, 0x18ef, 0xcd4e, 0x18c8, 0xcd6d, - 0x18a0, 0xcd8c, 0x1878, 0xcdab, 0x1851, 0xcdca, 0x182a, 0xcde9, - 0x1802, 0xce08, 0x17db, 0xce28, 0x17b4, 0xce47, 0x178d, 0xce67, - 0x1766, 0xce87, 0x173f, 0xcea7, 0x1719, 0xcec7, 0x16f2, 0xcee7, - 0x16cb, 0xcf07, 0x16a5, 0xcf28, 0x167f, 0xcf48, 0x1659, 0xcf69, - 0x1632, 0xcf8a, 0x160c, 0xcfab, 0x15e6, 0xcfcc, 0x15c1, 0xcfed, - 0x159b, 0xd00e, 0x1575, 0xd030, 0x1550, 0xd051, 0x152a, 0xd073, - 0x1505, 0xd094, 0x14e0, 0xd0b6, 0x14bb, 0xd0d8, 0x1496, 0xd0fa, - 0x1471, 0xd11c, 0x144c, 0xd13e, 0x1428, 0xd161, 0x1403, 0xd183, - 0x13df, 0xd1a6, 0x13ba, 0xd1c9, 0x1396, 0xd1eb, 0x1372, 0xd20e, - 0x134e, 0xd231, 0x132a, 0xd255, 0x1306, 0xd278, 0x12e2, 0xd29b, - 0x12bf, 0xd2bf, 0x129b, 0xd2e2, 0x1278, 0xd306, 0x1255, 0xd32a, - 0x1231, 0xd34e, 0x120e, 0xd372, 0x11eb, 0xd396, 0x11c9, 0xd3ba, - 0x11a6, 0xd3df, 0x1183, 0xd403, 0x1161, 0xd428, 0x113e, 0xd44c, - 0x111c, 0xd471, 0x10fa, 0xd496, 0x10d8, 0xd4bb, 0x10b6, 0xd4e0, - 0x1094, 0xd505, 0x1073, 0xd52a, 0x1051, 0xd550, 0x1030, 0xd575, - 0x100e, 0xd59b, 0xfed, 0xd5c1, 0xfcc, 0xd5e6, 0xfab, 0xd60c, - 0xf8a, 0xd632, 0xf69, 0xd659, 0xf48, 0xd67f, 0xf28, 0xd6a5, - 0xf07, 0xd6cb, 0xee7, 0xd6f2, 0xec7, 0xd719, 0xea7, 0xd73f, - 0xe87, 0xd766, 0xe67, 0xd78d, 0xe47, 0xd7b4, 0xe28, 0xd7db, - 0xe08, 0xd802, 0xde9, 0xd82a, 0xdca, 0xd851, 0xdab, 0xd878, - 0xd8c, 0xd8a0, 0xd6d, 0xd8c8, 0xd4e, 0xd8ef, 0xd30, 0xd917, - 0xd11, 0xd93f, 0xcf3, 0xd967, 0xcd4, 0xd98f, 0xcb6, 0xd9b8, - 0xc98, 0xd9e0, 0xc7a, 0xda08, 0xc5d, 0xda31, 0xc3f, 0xda5a, - 0xc21, 0xda82, 0xc04, 0xdaab, 0xbe7, 0xdad4, 0xbca, 0xdafd, - 0xbad, 0xdb26, 0xb90, 0xdb4f, 0xb73, 0xdb78, 0xb56, 0xdba2, - 0xb3a, 0xdbcb, 0xb1e, 0xdbf5, 0xb01, 0xdc1e, 0xae5, 0xdc48, - 0xac9, 0xdc72, 0xaad, 0xdc9b, 0xa92, 0xdcc5, 0xa76, 0xdcef, - 0xa5b, 0xdd19, 0xa3f, 0xdd44, 0xa24, 0xdd6e, 0xa09, 0xdd98, - 0x9ee, 0xddc3, 0x9d3, 0xdded, 0x9b8, 0xde18, 0x99e, 0xde42, - 0x983, 0xde6d, 0x969, 0xde98, 0x94f, 0xdec3, 0x935, 0xdeee, - 0x91b, 0xdf19, 0x901, 0xdf44, 0x8e8, 0xdf6f, 0x8ce, 0xdf9b, - 0x8b5, 0xdfc6, 0x89b, 0xdff1, 0x882, 0xe01d, 0x869, 0xe049, - 0x850, 0xe074, 0x838, 0xe0a0, 0x81f, 0xe0cc, 0x807, 0xe0f8, - 0x7ee, 0xe124, 0x7d6, 0xe150, 0x7be, 0xe17c, 0x7a6, 0xe1a8, - 0x78f, 0xe1d5, 0x777, 0xe201, 0x75f, 0xe22d, 0x748, 0xe25a, - 0x731, 0xe287, 0x71a, 0xe2b3, 0x703, 0xe2e0, 0x6ec, 0xe30d, - 0x6d5, 0xe33a, 0x6bf, 0xe367, 0x6a8, 0xe394, 0x692, 0xe3c1, - 0x67c, 0xe3ee, 0x666, 0xe41b, 0x650, 0xe448, 0x63b, 0xe476, - 0x625, 0xe4a3, 0x610, 0xe4d0, 0x5fa, 0xe4fe, 0x5e5, 0xe52c, - 0x5d0, 0xe559, 0x5bb, 0xe587, 0x5a7, 0xe5b5, 0x592, 0xe5e3, - 0x57e, 0xe611, 0x569, 0xe63f, 0x555, 0xe66d, 0x541, 0xe69b, - 0x52d, 0xe6c9, 0x51a, 0xe6f7, 0x506, 0xe725, 0x4f2, 0xe754, - 0x4df, 0xe782, 0x4cc, 0xe7b1, 0x4b9, 0xe7df, 0x4a6, 0xe80e, - 0x493, 0xe83c, 0x481, 0xe86b, 0x46e, 0xe89a, 0x45c, 0xe8c9, - 0x44a, 0xe8f7, 0x438, 0xe926, 0x426, 0xe955, 0x414, 0xe984, - 0x403, 0xe9b4, 0x3f1, 0xe9e3, 0x3e0, 0xea12, 0x3cf, 0xea41, - 0x3be, 0xea70, 0x3ad, 0xeaa0, 0x39c, 0xeacf, 0x38c, 0xeaff, - 0x37b, 0xeb2e, 0x36b, 0xeb5e, 0x35b, 0xeb8d, 0x34b, 0xebbd, - 0x33b, 0xebed, 0x32b, 0xec1c, 0x31c, 0xec4c, 0x30c, 0xec7c, - 0x2fd, 0xecac, 0x2ee, 0xecdc, 0x2df, 0xed0c, 0x2d0, 0xed3c, - 0x2c1, 0xed6c, 0x2b3, 0xed9c, 0x2a5, 0xedcc, 0x296, 0xedfc, - 0x288, 0xee2d, 0x27a, 0xee5d, 0x26d, 0xee8d, 0x25f, 0xeebe, - 0x251, 0xeeee, 0x244, 0xef1f, 0x237, 0xef4f, 0x22a, 0xef80, - 0x21d, 0xefb0, 0x210, 0xefe1, 0x204, 0xf012, 0x1f7, 0xf042, - 0x1eb, 0xf073, 0x1df, 0xf0a4, 0x1d3, 0xf0d5, 0x1c7, 0xf105, - 0x1bb, 0xf136, 0x1b0, 0xf167, 0x1a4, 0xf198, 0x199, 0xf1c9, - 0x18e, 0xf1fa, 0x183, 0xf22b, 0x178, 0xf25c, 0x16e, 0xf28e, - 0x163, 0xf2bf, 0x159, 0xf2f0, 0x14f, 0xf321, 0x145, 0xf352, - 0x13b, 0xf384, 0x131, 0xf3b5, 0x128, 0xf3e6, 0x11e, 0xf418, - 0x115, 0xf449, 0x10c, 0xf47b, 0x103, 0xf4ac, 0xfa, 0xf4dd, - 0xf1, 0xf50f, 0xe9, 0xf540, 0xe0, 0xf572, 0xd8, 0xf5a4, - 0xd0, 0xf5d5, 0xc8, 0xf607, 0xc0, 0xf639, 0xb9, 0xf66a, - 0xb1, 0xf69c, 0xaa, 0xf6ce, 0xa3, 0xf6ff, 0x9c, 0xf731, - 0x95, 0xf763, 0x8e, 0xf795, 0x88, 0xf7c7, 0x81, 0xf7f9, - 0x7b, 0xf82a, 0x75, 0xf85c, 0x6f, 0xf88e, 0x69, 0xf8c0, - 0x64, 0xf8f2, 0x5e, 0xf924, 0x59, 0xf956, 0x54, 0xf988, - 0x4f, 0xf9ba, 0x4a, 0xf9ec, 0x45, 0xfa1e, 0x41, 0xfa50, - 0x3c, 0xfa82, 0x38, 0xfab4, 0x34, 0xfae6, 0x30, 0xfb19, - 0x2c, 0xfb4b, 0x29, 0xfb7d, 0x25, 0xfbaf, 0x22, 0xfbe1, - 0x1f, 0xfc13, 0x1c, 0xfc45, 0x19, 0xfc78, 0x16, 0xfcaa, - 0x14, 0xfcdc, 0x11, 0xfd0e, 0xf, 0xfd40, 0xd, 0xfd73, - 0xb, 0xfda5, 0x9, 0xfdd7, 0x8, 0xfe09, 0x6, 0xfe3c, - 0x5, 0xfe6e, 0x4, 0xfea0, 0x3, 0xfed2, 0x2, 0xff05, - 0x1, 0xff37, 0x1, 0xff69, 0x0, 0xff9b, 0x0, 0xffce, - 0x0, 0x0, 0x0, 0x32, 0x0, 0x65, 0x1, 0x97, - 0x1, 0xc9, 0x2, 0xfb, 0x3, 0x12e, 0x4, 0x160, - 0x5, 0x192, 0x6, 0x1c4, 0x8, 0x1f7, 0x9, 0x229, - 0xb, 0x25b, 0xd, 0x28d, 0xf, 0x2c0, 0x11, 0x2f2, - 0x14, 0x324, 0x16, 0x356, 0x19, 0x388, 0x1c, 0x3bb, - 0x1f, 0x3ed, 0x22, 0x41f, 0x25, 0x451, 0x29, 0x483, - 0x2c, 0x4b5, 0x30, 0x4e7, 0x34, 0x51a, 0x38, 0x54c, - 0x3c, 0x57e, 0x41, 0x5b0, 0x45, 0x5e2, 0x4a, 0x614, - 0x4f, 0x646, 0x54, 0x678, 0x59, 0x6aa, 0x5e, 0x6dc, - 0x64, 0x70e, 0x69, 0x740, 0x6f, 0x772, 0x75, 0x7a4, - 0x7b, 0x7d6, 0x81, 0x807, 0x88, 0x839, 0x8e, 0x86b, - 0x95, 0x89d, 0x9c, 0x8cf, 0xa3, 0x901, 0xaa, 0x932, - 0xb1, 0x964, 0xb9, 0x996, 0xc0, 0x9c7, 0xc8, 0x9f9, - 0xd0, 0xa2b, 0xd8, 0xa5c, 0xe0, 0xa8e, 0xe9, 0xac0, - 0xf1, 0xaf1, 0xfa, 0xb23, 0x103, 0xb54, 0x10c, 0xb85, - 0x115, 0xbb7, 0x11e, 0xbe8, 0x128, 0xc1a, 0x131, 0xc4b, - 0x13b, 0xc7c, 0x145, 0xcae, 0x14f, 0xcdf, 0x159, 0xd10, - 0x163, 0xd41, 0x16e, 0xd72, 0x178, 0xda4, 0x183, 0xdd5, - 0x18e, 0xe06, 0x199, 0xe37, 0x1a4, 0xe68, 0x1b0, 0xe99, - 0x1bb, 0xeca, 0x1c7, 0xefb, 0x1d3, 0xf2b, 0x1df, 0xf5c, - 0x1eb, 0xf8d, 0x1f7, 0xfbe, 0x204, 0xfee, 0x210, 0x101f, - 0x21d, 0x1050, 0x22a, 0x1080, 0x237, 0x10b1, 0x244, 0x10e1, - 0x251, 0x1112, 0x25f, 0x1142, 0x26d, 0x1173, 0x27a, 0x11a3, - 0x288, 0x11d3, 0x296, 0x1204, 0x2a5, 0x1234, 0x2b3, 0x1264, - 0x2c1, 0x1294, 0x2d0, 0x12c4, 0x2df, 0x12f4, 0x2ee, 0x1324, - 0x2fd, 0x1354, 0x30c, 0x1384, 0x31c, 0x13b4, 0x32b, 0x13e4, - 0x33b, 0x1413, 0x34b, 0x1443, 0x35b, 0x1473, 0x36b, 0x14a2, - 0x37b, 0x14d2, 0x38c, 0x1501, 0x39c, 0x1531, 0x3ad, 0x1560, - 0x3be, 0x1590, 0x3cf, 0x15bf, 0x3e0, 0x15ee, 0x3f1, 0x161d, - 0x403, 0x164c, 0x414, 0x167c, 0x426, 0x16ab, 0x438, 0x16da, - 0x44a, 0x1709, 0x45c, 0x1737, 0x46e, 0x1766, 0x481, 0x1795, - 0x493, 0x17c4, 0x4a6, 0x17f2, 0x4b9, 0x1821, 0x4cc, 0x184f, - 0x4df, 0x187e, 0x4f2, 0x18ac, 0x506, 0x18db, 0x51a, 0x1909, - 0x52d, 0x1937, 0x541, 0x1965, 0x555, 0x1993, 0x569, 0x19c1, - 0x57e, 0x19ef, 0x592, 0x1a1d, 0x5a7, 0x1a4b, 0x5bb, 0x1a79, - 0x5d0, 0x1aa7, 0x5e5, 0x1ad4, 0x5fa, 0x1b02, 0x610, 0x1b30, - 0x625, 0x1b5d, 0x63b, 0x1b8a, 0x650, 0x1bb8, 0x666, 0x1be5, - 0x67c, 0x1c12, 0x692, 0x1c3f, 0x6a8, 0x1c6c, 0x6bf, 0x1c99, - 0x6d5, 0x1cc6, 0x6ec, 0x1cf3, 0x703, 0x1d20, 0x71a, 0x1d4d, - 0x731, 0x1d79, 0x748, 0x1da6, 0x75f, 0x1dd3, 0x777, 0x1dff, - 0x78f, 0x1e2b, 0x7a6, 0x1e58, 0x7be, 0x1e84, 0x7d6, 0x1eb0, - 0x7ee, 0x1edc, 0x807, 0x1f08, 0x81f, 0x1f34, 0x838, 0x1f60, - 0x850, 0x1f8c, 0x869, 0x1fb7, 0x882, 0x1fe3, 0x89b, 0x200f, - 0x8b5, 0x203a, 0x8ce, 0x2065, 0x8e8, 0x2091, 0x901, 0x20bc, - 0x91b, 0x20e7, 0x935, 0x2112, 0x94f, 0x213d, 0x969, 0x2168, - 0x983, 0x2193, 0x99e, 0x21be, 0x9b8, 0x21e8, 0x9d3, 0x2213, - 0x9ee, 0x223d, 0xa09, 0x2268, 0xa24, 0x2292, 0xa3f, 0x22bc, - 0xa5b, 0x22e7, 0xa76, 0x2311, 0xa92, 0x233b, 0xaad, 0x2365, - 0xac9, 0x238e, 0xae5, 0x23b8, 0xb01, 0x23e2, 0xb1e, 0x240b, - 0xb3a, 0x2435, 0xb56, 0x245e, 0xb73, 0x2488, 0xb90, 0x24b1, - 0xbad, 0x24da, 0xbca, 0x2503, 0xbe7, 0x252c, 0xc04, 0x2555, - 0xc21, 0x257e, 0xc3f, 0x25a6, 0xc5d, 0x25cf, 0xc7a, 0x25f8, - 0xc98, 0x2620, 0xcb6, 0x2648, 0xcd4, 0x2671, 0xcf3, 0x2699, - 0xd11, 0x26c1, 0xd30, 0x26e9, 0xd4e, 0x2711, 0xd6d, 0x2738, - 0xd8c, 0x2760, 0xdab, 0x2788, 0xdca, 0x27af, 0xde9, 0x27d6, - 0xe08, 0x27fe, 0xe28, 0x2825, 0xe47, 0x284c, 0xe67, 0x2873, - 0xe87, 0x289a, 0xea7, 0x28c1, 0xec7, 0x28e7, 0xee7, 0x290e, - 0xf07, 0x2935, 0xf28, 0x295b, 0xf48, 0x2981, 0xf69, 0x29a7, - 0xf8a, 0x29ce, 0xfab, 0x29f4, 0xfcc, 0x2a1a, 0xfed, 0x2a3f, - 0x100e, 0x2a65, 0x1030, 0x2a8b, 0x1051, 0x2ab0, 0x1073, 0x2ad6, - 0x1094, 0x2afb, 0x10b6, 0x2b20, 0x10d8, 0x2b45, 0x10fa, 0x2b6a, - 0x111c, 0x2b8f, 0x113e, 0x2bb4, 0x1161, 0x2bd8, 0x1183, 0x2bfd, - 0x11a6, 0x2c21, 0x11c9, 0x2c46, 0x11eb, 0x2c6a, 0x120e, 0x2c8e, - 0x1231, 0x2cb2, 0x1255, 0x2cd6, 0x1278, 0x2cfa, 0x129b, 0x2d1e, - 0x12bf, 0x2d41, 0x12e2, 0x2d65, 0x1306, 0x2d88, 0x132a, 0x2dab, - 0x134e, 0x2dcf, 0x1372, 0x2df2, 0x1396, 0x2e15, 0x13ba, 0x2e37, - 0x13df, 0x2e5a, 0x1403, 0x2e7d, 0x1428, 0x2e9f, 0x144c, 0x2ec2, - 0x1471, 0x2ee4, 0x1496, 0x2f06, 0x14bb, 0x2f28, 0x14e0, 0x2f4a, - 0x1505, 0x2f6c, 0x152a, 0x2f8d, 0x1550, 0x2faf, 0x1575, 0x2fd0, - 0x159b, 0x2ff2, 0x15c1, 0x3013, 0x15e6, 0x3034, 0x160c, 0x3055, - 0x1632, 0x3076, 0x1659, 0x3097, 0x167f, 0x30b8, 0x16a5, 0x30d8, - 0x16cb, 0x30f9, 0x16f2, 0x3119, 0x1719, 0x3139, 0x173f, 0x3159, - 0x1766, 0x3179, 0x178d, 0x3199, 0x17b4, 0x31b9, 0x17db, 0x31d8, - 0x1802, 0x31f8, 0x182a, 0x3217, 0x1851, 0x3236, 0x1878, 0x3255, - 0x18a0, 0x3274, 0x18c8, 0x3293, 0x18ef, 0x32b2, 0x1917, 0x32d0, - 0x193f, 0x32ef, 0x1967, 0x330d, 0x198f, 0x332c, 0x19b8, 0x334a, - 0x19e0, 0x3368, 0x1a08, 0x3386, 0x1a31, 0x33a3, 0x1a5a, 0x33c1, - 0x1a82, 0x33df, 0x1aab, 0x33fc, 0x1ad4, 0x3419, 0x1afd, 0x3436, - 0x1b26, 0x3453, 0x1b4f, 0x3470, 0x1b78, 0x348d, 0x1ba2, 0x34aa, - 0x1bcb, 0x34c6, 0x1bf5, 0x34e2, 0x1c1e, 0x34ff, 0x1c48, 0x351b, - 0x1c72, 0x3537, 0x1c9b, 0x3553, 0x1cc5, 0x356e, 0x1cef, 0x358a, - 0x1d19, 0x35a5, 0x1d44, 0x35c1, 0x1d6e, 0x35dc, 0x1d98, 0x35f7, - 0x1dc3, 0x3612, 0x1ded, 0x362d, 0x1e18, 0x3648, 0x1e42, 0x3662, - 0x1e6d, 0x367d, 0x1e98, 0x3697, 0x1ec3, 0x36b1, 0x1eee, 0x36cb, - 0x1f19, 0x36e5, 0x1f44, 0x36ff, 0x1f6f, 0x3718, 0x1f9b, 0x3732, - 0x1fc6, 0x374b, 0x1ff1, 0x3765, 0x201d, 0x377e, 0x2049, 0x3797, - 0x2074, 0x37b0, 0x20a0, 0x37c8, 0x20cc, 0x37e1, 0x20f8, 0x37f9, - 0x2124, 0x3812, 0x2150, 0x382a, 0x217c, 0x3842, 0x21a8, 0x385a, - 0x21d5, 0x3871, 0x2201, 0x3889, 0x222d, 0x38a1, 0x225a, 0x38b8, - 0x2287, 0x38cf, 0x22b3, 0x38e6, 0x22e0, 0x38fd, 0x230d, 0x3914, - 0x233a, 0x392b, 0x2367, 0x3941, 0x2394, 0x3958, 0x23c1, 0x396e, - 0x23ee, 0x3984, 0x241b, 0x399a, 0x2448, 0x39b0, 0x2476, 0x39c5, - 0x24a3, 0x39db, 0x24d0, 0x39f0, 0x24fe, 0x3a06, 0x252c, 0x3a1b, - 0x2559, 0x3a30, 0x2587, 0x3a45, 0x25b5, 0x3a59, 0x25e3, 0x3a6e, - 0x2611, 0x3a82, 0x263f, 0x3a97, 0x266d, 0x3aab, 0x269b, 0x3abf, - 0x26c9, 0x3ad3, 0x26f7, 0x3ae6, 0x2725, 0x3afa, 0x2754, 0x3b0e, - 0x2782, 0x3b21, 0x27b1, 0x3b34, 0x27df, 0x3b47, 0x280e, 0x3b5a, - 0x283c, 0x3b6d, 0x286b, 0x3b7f, 0x289a, 0x3b92, 0x28c9, 0x3ba4, - 0x28f7, 0x3bb6, 0x2926, 0x3bc8, 0x2955, 0x3bda, 0x2984, 0x3bec, - 0x29b4, 0x3bfd, 0x29e3, 0x3c0f, 0x2a12, 0x3c20, 0x2a41, 0x3c31, - 0x2a70, 0x3c42, 0x2aa0, 0x3c53, 0x2acf, 0x3c64, 0x2aff, 0x3c74, - 0x2b2e, 0x3c85, 0x2b5e, 0x3c95, 0x2b8d, 0x3ca5, 0x2bbd, 0x3cb5, - 0x2bed, 0x3cc5, 0x2c1c, 0x3cd5, 0x2c4c, 0x3ce4, 0x2c7c, 0x3cf4, - 0x2cac, 0x3d03, 0x2cdc, 0x3d12, 0x2d0c, 0x3d21, 0x2d3c, 0x3d30, - 0x2d6c, 0x3d3f, 0x2d9c, 0x3d4d, 0x2dcc, 0x3d5b, 0x2dfc, 0x3d6a, - 0x2e2d, 0x3d78, 0x2e5d, 0x3d86, 0x2e8d, 0x3d93, 0x2ebe, 0x3da1, - 0x2eee, 0x3daf, 0x2f1f, 0x3dbc, 0x2f4f, 0x3dc9, 0x2f80, 0x3dd6, - 0x2fb0, 0x3de3, 0x2fe1, 0x3df0, 0x3012, 0x3dfc, 0x3042, 0x3e09, - 0x3073, 0x3e15, 0x30a4, 0x3e21, 0x30d5, 0x3e2d, 0x3105, 0x3e39, - 0x3136, 0x3e45, 0x3167, 0x3e50, 0x3198, 0x3e5c, 0x31c9, 0x3e67, - 0x31fa, 0x3e72, 0x322b, 0x3e7d, 0x325c, 0x3e88, 0x328e, 0x3e92, - 0x32bf, 0x3e9d, 0x32f0, 0x3ea7, 0x3321, 0x3eb1, 0x3352, 0x3ebb, - 0x3384, 0x3ec5, 0x33b5, 0x3ecf, 0x33e6, 0x3ed8, 0x3418, 0x3ee2, - 0x3449, 0x3eeb, 0x347b, 0x3ef4, 0x34ac, 0x3efd, 0x34dd, 0x3f06, - 0x350f, 0x3f0f, 0x3540, 0x3f17, 0x3572, 0x3f20, 0x35a4, 0x3f28, - 0x35d5, 0x3f30, 0x3607, 0x3f38, 0x3639, 0x3f40, 0x366a, 0x3f47, - 0x369c, 0x3f4f, 0x36ce, 0x3f56, 0x36ff, 0x3f5d, 0x3731, 0x3f64, - 0x3763, 0x3f6b, 0x3795, 0x3f72, 0x37c7, 0x3f78, 0x37f9, 0x3f7f, - 0x382a, 0x3f85, 0x385c, 0x3f8b, 0x388e, 0x3f91, 0x38c0, 0x3f97, - 0x38f2, 0x3f9c, 0x3924, 0x3fa2, 0x3956, 0x3fa7, 0x3988, 0x3fac, - 0x39ba, 0x3fb1, 0x39ec, 0x3fb6, 0x3a1e, 0x3fbb, 0x3a50, 0x3fbf, - 0x3a82, 0x3fc4, 0x3ab4, 0x3fc8, 0x3ae6, 0x3fcc, 0x3b19, 0x3fd0, - 0x3b4b, 0x3fd4, 0x3b7d, 0x3fd7, 0x3baf, 0x3fdb, 0x3be1, 0x3fde, - 0x3c13, 0x3fe1, 0x3c45, 0x3fe4, 0x3c78, 0x3fe7, 0x3caa, 0x3fea, - 0x3cdc, 0x3fec, 0x3d0e, 0x3fef, 0x3d40, 0x3ff1, 0x3d73, 0x3ff3, - 0x3da5, 0x3ff5, 0x3dd7, 0x3ff7, 0x3e09, 0x3ff8, 0x3e3c, 0x3ffa, - 0x3e6e, 0x3ffb, 0x3ea0, 0x3ffc, 0x3ed2, 0x3ffd, 0x3f05, 0x3ffe, - 0x3f37, 0x3fff, 0x3f69, 0x3fff, 0x3f9b, 0x4000, 0x3fce, 0x4000 -}; - -/** -* \par -* Generation of real_CoefB array: -* \par -* n = 1024 -*
for (i = 0; i < n; i++)   
-*  {   
-*    pBTable[2 * i] = 0.5 * (1.0 + sin (2 * PI / (double) (2 * n) * (double) i));   
-*    pBTable[2 * i + 1] = 0.5 * (1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
-*  } 
-* \par -* Convert to fixed point Q15 format -* round(pBTable[i] * pow(2, 15)) -* -*/ - -static const q15_t realCoefBQ15[2048] = { - 0x4000, 0x4000, 0x4032, 0x4000, 0x4065, 0x4000, 0x4097, 0x3fff, - 0x40c9, 0x3fff, 0x40fb, 0x3ffe, 0x412e, 0x3ffd, 0x4160, 0x3ffc, - 0x4192, 0x3ffb, 0x41c4, 0x3ffa, 0x41f7, 0x3ff8, 0x4229, 0x3ff7, - 0x425b, 0x3ff5, 0x428d, 0x3ff3, 0x42c0, 0x3ff1, 0x42f2, 0x3fef, - 0x4324, 0x3fec, 0x4356, 0x3fea, 0x4388, 0x3fe7, 0x43bb, 0x3fe4, - 0x43ed, 0x3fe1, 0x441f, 0x3fde, 0x4451, 0x3fdb, 0x4483, 0x3fd7, - 0x44b5, 0x3fd4, 0x44e7, 0x3fd0, 0x451a, 0x3fcc, 0x454c, 0x3fc8, - 0x457e, 0x3fc4, 0x45b0, 0x3fbf, 0x45e2, 0x3fbb, 0x4614, 0x3fb6, - 0x4646, 0x3fb1, 0x4678, 0x3fac, 0x46aa, 0x3fa7, 0x46dc, 0x3fa2, - 0x470e, 0x3f9c, 0x4740, 0x3f97, 0x4772, 0x3f91, 0x47a4, 0x3f8b, - 0x47d6, 0x3f85, 0x4807, 0x3f7f, 0x4839, 0x3f78, 0x486b, 0x3f72, - 0x489d, 0x3f6b, 0x48cf, 0x3f64, 0x4901, 0x3f5d, 0x4932, 0x3f56, - 0x4964, 0x3f4f, 0x4996, 0x3f47, 0x49c7, 0x3f40, 0x49f9, 0x3f38, - 0x4a2b, 0x3f30, 0x4a5c, 0x3f28, 0x4a8e, 0x3f20, 0x4ac0, 0x3f17, - 0x4af1, 0x3f0f, 0x4b23, 0x3f06, 0x4b54, 0x3efd, 0x4b85, 0x3ef4, - 0x4bb7, 0x3eeb, 0x4be8, 0x3ee2, 0x4c1a, 0x3ed8, 0x4c4b, 0x3ecf, - 0x4c7c, 0x3ec5, 0x4cae, 0x3ebb, 0x4cdf, 0x3eb1, 0x4d10, 0x3ea7, - 0x4d41, 0x3e9d, 0x4d72, 0x3e92, 0x4da4, 0x3e88, 0x4dd5, 0x3e7d, - 0x4e06, 0x3e72, 0x4e37, 0x3e67, 0x4e68, 0x3e5c, 0x4e99, 0x3e50, - 0x4eca, 0x3e45, 0x4efb, 0x3e39, 0x4f2b, 0x3e2d, 0x4f5c, 0x3e21, - 0x4f8d, 0x3e15, 0x4fbe, 0x3e09, 0x4fee, 0x3dfc, 0x501f, 0x3df0, - 0x5050, 0x3de3, 0x5080, 0x3dd6, 0x50b1, 0x3dc9, 0x50e1, 0x3dbc, - 0x5112, 0x3daf, 0x5142, 0x3da1, 0x5173, 0x3d93, 0x51a3, 0x3d86, - 0x51d3, 0x3d78, 0x5204, 0x3d6a, 0x5234, 0x3d5b, 0x5264, 0x3d4d, - 0x5294, 0x3d3f, 0x52c4, 0x3d30, 0x52f4, 0x3d21, 0x5324, 0x3d12, - 0x5354, 0x3d03, 0x5384, 0x3cf4, 0x53b4, 0x3ce4, 0x53e4, 0x3cd5, - 0x5413, 0x3cc5, 0x5443, 0x3cb5, 0x5473, 0x3ca5, 0x54a2, 0x3c95, - 0x54d2, 0x3c85, 0x5501, 0x3c74, 0x5531, 0x3c64, 0x5560, 0x3c53, - 0x5590, 0x3c42, 0x55bf, 0x3c31, 0x55ee, 0x3c20, 0x561d, 0x3c0f, - 0x564c, 0x3bfd, 0x567c, 0x3bec, 0x56ab, 0x3bda, 0x56da, 0x3bc8, - 0x5709, 0x3bb6, 0x5737, 0x3ba4, 0x5766, 0x3b92, 0x5795, 0x3b7f, - 0x57c4, 0x3b6d, 0x57f2, 0x3b5a, 0x5821, 0x3b47, 0x584f, 0x3b34, - 0x587e, 0x3b21, 0x58ac, 0x3b0e, 0x58db, 0x3afa, 0x5909, 0x3ae6, - 0x5937, 0x3ad3, 0x5965, 0x3abf, 0x5993, 0x3aab, 0x59c1, 0x3a97, - 0x59ef, 0x3a82, 0x5a1d, 0x3a6e, 0x5a4b, 0x3a59, 0x5a79, 0x3a45, - 0x5aa7, 0x3a30, 0x5ad4, 0x3a1b, 0x5b02, 0x3a06, 0x5b30, 0x39f0, - 0x5b5d, 0x39db, 0x5b8a, 0x39c5, 0x5bb8, 0x39b0, 0x5be5, 0x399a, - 0x5c12, 0x3984, 0x5c3f, 0x396e, 0x5c6c, 0x3958, 0x5c99, 0x3941, - 0x5cc6, 0x392b, 0x5cf3, 0x3914, 0x5d20, 0x38fd, 0x5d4d, 0x38e6, - 0x5d79, 0x38cf, 0x5da6, 0x38b8, 0x5dd3, 0x38a1, 0x5dff, 0x3889, - 0x5e2b, 0x3871, 0x5e58, 0x385a, 0x5e84, 0x3842, 0x5eb0, 0x382a, - 0x5edc, 0x3812, 0x5f08, 0x37f9, 0x5f34, 0x37e1, 0x5f60, 0x37c8, - 0x5f8c, 0x37b0, 0x5fb7, 0x3797, 0x5fe3, 0x377e, 0x600f, 0x3765, - 0x603a, 0x374b, 0x6065, 0x3732, 0x6091, 0x3718, 0x60bc, 0x36ff, - 0x60e7, 0x36e5, 0x6112, 0x36cb, 0x613d, 0x36b1, 0x6168, 0x3697, - 0x6193, 0x367d, 0x61be, 0x3662, 0x61e8, 0x3648, 0x6213, 0x362d, - 0x623d, 0x3612, 0x6268, 0x35f7, 0x6292, 0x35dc, 0x62bc, 0x35c1, - 0x62e7, 0x35a5, 0x6311, 0x358a, 0x633b, 0x356e, 0x6365, 0x3553, - 0x638e, 0x3537, 0x63b8, 0x351b, 0x63e2, 0x34ff, 0x640b, 0x34e2, - 0x6435, 0x34c6, 0x645e, 0x34aa, 0x6488, 0x348d, 0x64b1, 0x3470, - 0x64da, 0x3453, 0x6503, 0x3436, 0x652c, 0x3419, 0x6555, 0x33fc, - 0x657e, 0x33df, 0x65a6, 0x33c1, 0x65cf, 0x33a3, 0x65f8, 0x3386, - 0x6620, 0x3368, 0x6648, 0x334a, 0x6671, 0x332c, 0x6699, 0x330d, - 0x66c1, 0x32ef, 0x66e9, 0x32d0, 0x6711, 0x32b2, 0x6738, 0x3293, - 0x6760, 0x3274, 0x6788, 0x3255, 0x67af, 0x3236, 0x67d6, 0x3217, - 0x67fe, 0x31f8, 0x6825, 0x31d8, 0x684c, 0x31b9, 0x6873, 0x3199, - 0x689a, 0x3179, 0x68c1, 0x3159, 0x68e7, 0x3139, 0x690e, 0x3119, - 0x6935, 0x30f9, 0x695b, 0x30d8, 0x6981, 0x30b8, 0x69a7, 0x3097, - 0x69ce, 0x3076, 0x69f4, 0x3055, 0x6a1a, 0x3034, 0x6a3f, 0x3013, - 0x6a65, 0x2ff2, 0x6a8b, 0x2fd0, 0x6ab0, 0x2faf, 0x6ad6, 0x2f8d, - 0x6afb, 0x2f6c, 0x6b20, 0x2f4a, 0x6b45, 0x2f28, 0x6b6a, 0x2f06, - 0x6b8f, 0x2ee4, 0x6bb4, 0x2ec2, 0x6bd8, 0x2e9f, 0x6bfd, 0x2e7d, - 0x6c21, 0x2e5a, 0x6c46, 0x2e37, 0x6c6a, 0x2e15, 0x6c8e, 0x2df2, - 0x6cb2, 0x2dcf, 0x6cd6, 0x2dab, 0x6cfa, 0x2d88, 0x6d1e, 0x2d65, - 0x6d41, 0x2d41, 0x6d65, 0x2d1e, 0x6d88, 0x2cfa, 0x6dab, 0x2cd6, - 0x6dcf, 0x2cb2, 0x6df2, 0x2c8e, 0x6e15, 0x2c6a, 0x6e37, 0x2c46, - 0x6e5a, 0x2c21, 0x6e7d, 0x2bfd, 0x6e9f, 0x2bd8, 0x6ec2, 0x2bb4, - 0x6ee4, 0x2b8f, 0x6f06, 0x2b6a, 0x6f28, 0x2b45, 0x6f4a, 0x2b20, - 0x6f6c, 0x2afb, 0x6f8d, 0x2ad6, 0x6faf, 0x2ab0, 0x6fd0, 0x2a8b, - 0x6ff2, 0x2a65, 0x7013, 0x2a3f, 0x7034, 0x2a1a, 0x7055, 0x29f4, - 0x7076, 0x29ce, 0x7097, 0x29a7, 0x70b8, 0x2981, 0x70d8, 0x295b, - 0x70f9, 0x2935, 0x7119, 0x290e, 0x7139, 0x28e7, 0x7159, 0x28c1, - 0x7179, 0x289a, 0x7199, 0x2873, 0x71b9, 0x284c, 0x71d8, 0x2825, - 0x71f8, 0x27fe, 0x7217, 0x27d6, 0x7236, 0x27af, 0x7255, 0x2788, - 0x7274, 0x2760, 0x7293, 0x2738, 0x72b2, 0x2711, 0x72d0, 0x26e9, - 0x72ef, 0x26c1, 0x730d, 0x2699, 0x732c, 0x2671, 0x734a, 0x2648, - 0x7368, 0x2620, 0x7386, 0x25f8, 0x73a3, 0x25cf, 0x73c1, 0x25a6, - 0x73df, 0x257e, 0x73fc, 0x2555, 0x7419, 0x252c, 0x7436, 0x2503, - 0x7453, 0x24da, 0x7470, 0x24b1, 0x748d, 0x2488, 0x74aa, 0x245e, - 0x74c6, 0x2435, 0x74e2, 0x240b, 0x74ff, 0x23e2, 0x751b, 0x23b8, - 0x7537, 0x238e, 0x7553, 0x2365, 0x756e, 0x233b, 0x758a, 0x2311, - 0x75a5, 0x22e7, 0x75c1, 0x22bc, 0x75dc, 0x2292, 0x75f7, 0x2268, - 0x7612, 0x223d, 0x762d, 0x2213, 0x7648, 0x21e8, 0x7662, 0x21be, - 0x767d, 0x2193, 0x7697, 0x2168, 0x76b1, 0x213d, 0x76cb, 0x2112, - 0x76e5, 0x20e7, 0x76ff, 0x20bc, 0x7718, 0x2091, 0x7732, 0x2065, - 0x774b, 0x203a, 0x7765, 0x200f, 0x777e, 0x1fe3, 0x7797, 0x1fb7, - 0x77b0, 0x1f8c, 0x77c8, 0x1f60, 0x77e1, 0x1f34, 0x77f9, 0x1f08, - 0x7812, 0x1edc, 0x782a, 0x1eb0, 0x7842, 0x1e84, 0x785a, 0x1e58, - 0x7871, 0x1e2b, 0x7889, 0x1dff, 0x78a1, 0x1dd3, 0x78b8, 0x1da6, - 0x78cf, 0x1d79, 0x78e6, 0x1d4d, 0x78fd, 0x1d20, 0x7914, 0x1cf3, - 0x792b, 0x1cc6, 0x7941, 0x1c99, 0x7958, 0x1c6c, 0x796e, 0x1c3f, - 0x7984, 0x1c12, 0x799a, 0x1be5, 0x79b0, 0x1bb8, 0x79c5, 0x1b8a, - 0x79db, 0x1b5d, 0x79f0, 0x1b30, 0x7a06, 0x1b02, 0x7a1b, 0x1ad4, - 0x7a30, 0x1aa7, 0x7a45, 0x1a79, 0x7a59, 0x1a4b, 0x7a6e, 0x1a1d, - 0x7a82, 0x19ef, 0x7a97, 0x19c1, 0x7aab, 0x1993, 0x7abf, 0x1965, - 0x7ad3, 0x1937, 0x7ae6, 0x1909, 0x7afa, 0x18db, 0x7b0e, 0x18ac, - 0x7b21, 0x187e, 0x7b34, 0x184f, 0x7b47, 0x1821, 0x7b5a, 0x17f2, - 0x7b6d, 0x17c4, 0x7b7f, 0x1795, 0x7b92, 0x1766, 0x7ba4, 0x1737, - 0x7bb6, 0x1709, 0x7bc8, 0x16da, 0x7bda, 0x16ab, 0x7bec, 0x167c, - 0x7bfd, 0x164c, 0x7c0f, 0x161d, 0x7c20, 0x15ee, 0x7c31, 0x15bf, - 0x7c42, 0x1590, 0x7c53, 0x1560, 0x7c64, 0x1531, 0x7c74, 0x1501, - 0x7c85, 0x14d2, 0x7c95, 0x14a2, 0x7ca5, 0x1473, 0x7cb5, 0x1443, - 0x7cc5, 0x1413, 0x7cd5, 0x13e4, 0x7ce4, 0x13b4, 0x7cf4, 0x1384, - 0x7d03, 0x1354, 0x7d12, 0x1324, 0x7d21, 0x12f4, 0x7d30, 0x12c4, - 0x7d3f, 0x1294, 0x7d4d, 0x1264, 0x7d5b, 0x1234, 0x7d6a, 0x1204, - 0x7d78, 0x11d3, 0x7d86, 0x11a3, 0x7d93, 0x1173, 0x7da1, 0x1142, - 0x7daf, 0x1112, 0x7dbc, 0x10e1, 0x7dc9, 0x10b1, 0x7dd6, 0x1080, - 0x7de3, 0x1050, 0x7df0, 0x101f, 0x7dfc, 0xfee, 0x7e09, 0xfbe, - 0x7e15, 0xf8d, 0x7e21, 0xf5c, 0x7e2d, 0xf2b, 0x7e39, 0xefb, - 0x7e45, 0xeca, 0x7e50, 0xe99, 0x7e5c, 0xe68, 0x7e67, 0xe37, - 0x7e72, 0xe06, 0x7e7d, 0xdd5, 0x7e88, 0xda4, 0x7e92, 0xd72, - 0x7e9d, 0xd41, 0x7ea7, 0xd10, 0x7eb1, 0xcdf, 0x7ebb, 0xcae, - 0x7ec5, 0xc7c, 0x7ecf, 0xc4b, 0x7ed8, 0xc1a, 0x7ee2, 0xbe8, - 0x7eeb, 0xbb7, 0x7ef4, 0xb85, 0x7efd, 0xb54, 0x7f06, 0xb23, - 0x7f0f, 0xaf1, 0x7f17, 0xac0, 0x7f20, 0xa8e, 0x7f28, 0xa5c, - 0x7f30, 0xa2b, 0x7f38, 0x9f9, 0x7f40, 0x9c7, 0x7f47, 0x996, - 0x7f4f, 0x964, 0x7f56, 0x932, 0x7f5d, 0x901, 0x7f64, 0x8cf, - 0x7f6b, 0x89d, 0x7f72, 0x86b, 0x7f78, 0x839, 0x7f7f, 0x807, - 0x7f85, 0x7d6, 0x7f8b, 0x7a4, 0x7f91, 0x772, 0x7f97, 0x740, - 0x7f9c, 0x70e, 0x7fa2, 0x6dc, 0x7fa7, 0x6aa, 0x7fac, 0x678, - 0x7fb1, 0x646, 0x7fb6, 0x614, 0x7fbb, 0x5e2, 0x7fbf, 0x5b0, - 0x7fc4, 0x57e, 0x7fc8, 0x54c, 0x7fcc, 0x51a, 0x7fd0, 0x4e7, - 0x7fd4, 0x4b5, 0x7fd7, 0x483, 0x7fdb, 0x451, 0x7fde, 0x41f, - 0x7fe1, 0x3ed, 0x7fe4, 0x3bb, 0x7fe7, 0x388, 0x7fea, 0x356, - 0x7fec, 0x324, 0x7fef, 0x2f2, 0x7ff1, 0x2c0, 0x7ff3, 0x28d, - 0x7ff5, 0x25b, 0x7ff7, 0x229, 0x7ff8, 0x1f7, 0x7ffa, 0x1c4, - 0x7ffb, 0x192, 0x7ffc, 0x160, 0x7ffd, 0x12e, 0x7ffe, 0xfb, - 0x7fff, 0xc9, 0x7fff, 0x97, 0x7fff, 0x65, 0x7fff, 0x32, - 0x7fff, 0x0, 0x7fff, 0xffce, 0x7fff, 0xff9b, 0x7fff, 0xff69, - 0x7fff, 0xff37, 0x7ffe, 0xff05, 0x7ffd, 0xfed2, 0x7ffc, 0xfea0, - 0x7ffb, 0xfe6e, 0x7ffa, 0xfe3c, 0x7ff8, 0xfe09, 0x7ff7, 0xfdd7, - 0x7ff5, 0xfda5, 0x7ff3, 0xfd73, 0x7ff1, 0xfd40, 0x7fef, 0xfd0e, - 0x7fec, 0xfcdc, 0x7fea, 0xfcaa, 0x7fe7, 0xfc78, 0x7fe4, 0xfc45, - 0x7fe1, 0xfc13, 0x7fde, 0xfbe1, 0x7fdb, 0xfbaf, 0x7fd7, 0xfb7d, - 0x7fd4, 0xfb4b, 0x7fd0, 0xfb19, 0x7fcc, 0xfae6, 0x7fc8, 0xfab4, - 0x7fc4, 0xfa82, 0x7fbf, 0xfa50, 0x7fbb, 0xfa1e, 0x7fb6, 0xf9ec, - 0x7fb1, 0xf9ba, 0x7fac, 0xf988, 0x7fa7, 0xf956, 0x7fa2, 0xf924, - 0x7f9c, 0xf8f2, 0x7f97, 0xf8c0, 0x7f91, 0xf88e, 0x7f8b, 0xf85c, - 0x7f85, 0xf82a, 0x7f7f, 0xf7f9, 0x7f78, 0xf7c7, 0x7f72, 0xf795, - 0x7f6b, 0xf763, 0x7f64, 0xf731, 0x7f5d, 0xf6ff, 0x7f56, 0xf6ce, - 0x7f4f, 0xf69c, 0x7f47, 0xf66a, 0x7f40, 0xf639, 0x7f38, 0xf607, - 0x7f30, 0xf5d5, 0x7f28, 0xf5a4, 0x7f20, 0xf572, 0x7f17, 0xf540, - 0x7f0f, 0xf50f, 0x7f06, 0xf4dd, 0x7efd, 0xf4ac, 0x7ef4, 0xf47b, - 0x7eeb, 0xf449, 0x7ee2, 0xf418, 0x7ed8, 0xf3e6, 0x7ecf, 0xf3b5, - 0x7ec5, 0xf384, 0x7ebb, 0xf352, 0x7eb1, 0xf321, 0x7ea7, 0xf2f0, - 0x7e9d, 0xf2bf, 0x7e92, 0xf28e, 0x7e88, 0xf25c, 0x7e7d, 0xf22b, - 0x7e72, 0xf1fa, 0x7e67, 0xf1c9, 0x7e5c, 0xf198, 0x7e50, 0xf167, - 0x7e45, 0xf136, 0x7e39, 0xf105, 0x7e2d, 0xf0d5, 0x7e21, 0xf0a4, - 0x7e15, 0xf073, 0x7e09, 0xf042, 0x7dfc, 0xf012, 0x7df0, 0xefe1, - 0x7de3, 0xefb0, 0x7dd6, 0xef80, 0x7dc9, 0xef4f, 0x7dbc, 0xef1f, - 0x7daf, 0xeeee, 0x7da1, 0xeebe, 0x7d93, 0xee8d, 0x7d86, 0xee5d, - 0x7d78, 0xee2d, 0x7d6a, 0xedfc, 0x7d5b, 0xedcc, 0x7d4d, 0xed9c, - 0x7d3f, 0xed6c, 0x7d30, 0xed3c, 0x7d21, 0xed0c, 0x7d12, 0xecdc, - 0x7d03, 0xecac, 0x7cf4, 0xec7c, 0x7ce4, 0xec4c, 0x7cd5, 0xec1c, - 0x7cc5, 0xebed, 0x7cb5, 0xebbd, 0x7ca5, 0xeb8d, 0x7c95, 0xeb5e, - 0x7c85, 0xeb2e, 0x7c74, 0xeaff, 0x7c64, 0xeacf, 0x7c53, 0xeaa0, - 0x7c42, 0xea70, 0x7c31, 0xea41, 0x7c20, 0xea12, 0x7c0f, 0xe9e3, - 0x7bfd, 0xe9b4, 0x7bec, 0xe984, 0x7bda, 0xe955, 0x7bc8, 0xe926, - 0x7bb6, 0xe8f7, 0x7ba4, 0xe8c9, 0x7b92, 0xe89a, 0x7b7f, 0xe86b, - 0x7b6d, 0xe83c, 0x7b5a, 0xe80e, 0x7b47, 0xe7df, 0x7b34, 0xe7b1, - 0x7b21, 0xe782, 0x7b0e, 0xe754, 0x7afa, 0xe725, 0x7ae6, 0xe6f7, - 0x7ad3, 0xe6c9, 0x7abf, 0xe69b, 0x7aab, 0xe66d, 0x7a97, 0xe63f, - 0x7a82, 0xe611, 0x7a6e, 0xe5e3, 0x7a59, 0xe5b5, 0x7a45, 0xe587, - 0x7a30, 0xe559, 0x7a1b, 0xe52c, 0x7a06, 0xe4fe, 0x79f0, 0xe4d0, - 0x79db, 0xe4a3, 0x79c5, 0xe476, 0x79b0, 0xe448, 0x799a, 0xe41b, - 0x7984, 0xe3ee, 0x796e, 0xe3c1, 0x7958, 0xe394, 0x7941, 0xe367, - 0x792b, 0xe33a, 0x7914, 0xe30d, 0x78fd, 0xe2e0, 0x78e6, 0xe2b3, - 0x78cf, 0xe287, 0x78b8, 0xe25a, 0x78a1, 0xe22d, 0x7889, 0xe201, - 0x7871, 0xe1d5, 0x785a, 0xe1a8, 0x7842, 0xe17c, 0x782a, 0xe150, - 0x7812, 0xe124, 0x77f9, 0xe0f8, 0x77e1, 0xe0cc, 0x77c8, 0xe0a0, - 0x77b0, 0xe074, 0x7797, 0xe049, 0x777e, 0xe01d, 0x7765, 0xdff1, - 0x774b, 0xdfc6, 0x7732, 0xdf9b, 0x7718, 0xdf6f, 0x76ff, 0xdf44, - 0x76e5, 0xdf19, 0x76cb, 0xdeee, 0x76b1, 0xdec3, 0x7697, 0xde98, - 0x767d, 0xde6d, 0x7662, 0xde42, 0x7648, 0xde18, 0x762d, 0xdded, - 0x7612, 0xddc3, 0x75f7, 0xdd98, 0x75dc, 0xdd6e, 0x75c1, 0xdd44, - 0x75a5, 0xdd19, 0x758a, 0xdcef, 0x756e, 0xdcc5, 0x7553, 0xdc9b, - 0x7537, 0xdc72, 0x751b, 0xdc48, 0x74ff, 0xdc1e, 0x74e2, 0xdbf5, - 0x74c6, 0xdbcb, 0x74aa, 0xdba2, 0x748d, 0xdb78, 0x7470, 0xdb4f, - 0x7453, 0xdb26, 0x7436, 0xdafd, 0x7419, 0xdad4, 0x73fc, 0xdaab, - 0x73df, 0xda82, 0x73c1, 0xda5a, 0x73a3, 0xda31, 0x7386, 0xda08, - 0x7368, 0xd9e0, 0x734a, 0xd9b8, 0x732c, 0xd98f, 0x730d, 0xd967, - 0x72ef, 0xd93f, 0x72d0, 0xd917, 0x72b2, 0xd8ef, 0x7293, 0xd8c8, - 0x7274, 0xd8a0, 0x7255, 0xd878, 0x7236, 0xd851, 0x7217, 0xd82a, - 0x71f8, 0xd802, 0x71d8, 0xd7db, 0x71b9, 0xd7b4, 0x7199, 0xd78d, - 0x7179, 0xd766, 0x7159, 0xd73f, 0x7139, 0xd719, 0x7119, 0xd6f2, - 0x70f9, 0xd6cb, 0x70d8, 0xd6a5, 0x70b8, 0xd67f, 0x7097, 0xd659, - 0x7076, 0xd632, 0x7055, 0xd60c, 0x7034, 0xd5e6, 0x7013, 0xd5c1, - 0x6ff2, 0xd59b, 0x6fd0, 0xd575, 0x6faf, 0xd550, 0x6f8d, 0xd52a, - 0x6f6c, 0xd505, 0x6f4a, 0xd4e0, 0x6f28, 0xd4bb, 0x6f06, 0xd496, - 0x6ee4, 0xd471, 0x6ec2, 0xd44c, 0x6e9f, 0xd428, 0x6e7d, 0xd403, - 0x6e5a, 0xd3df, 0x6e37, 0xd3ba, 0x6e15, 0xd396, 0x6df2, 0xd372, - 0x6dcf, 0xd34e, 0x6dab, 0xd32a, 0x6d88, 0xd306, 0x6d65, 0xd2e2, - 0x6d41, 0xd2bf, 0x6d1e, 0xd29b, 0x6cfa, 0xd278, 0x6cd6, 0xd255, - 0x6cb2, 0xd231, 0x6c8e, 0xd20e, 0x6c6a, 0xd1eb, 0x6c46, 0xd1c9, - 0x6c21, 0xd1a6, 0x6bfd, 0xd183, 0x6bd8, 0xd161, 0x6bb4, 0xd13e, - 0x6b8f, 0xd11c, 0x6b6a, 0xd0fa, 0x6b45, 0xd0d8, 0x6b20, 0xd0b6, - 0x6afb, 0xd094, 0x6ad6, 0xd073, 0x6ab0, 0xd051, 0x6a8b, 0xd030, - 0x6a65, 0xd00e, 0x6a3f, 0xcfed, 0x6a1a, 0xcfcc, 0x69f4, 0xcfab, - 0x69ce, 0xcf8a, 0x69a7, 0xcf69, 0x6981, 0xcf48, 0x695b, 0xcf28, - 0x6935, 0xcf07, 0x690e, 0xcee7, 0x68e7, 0xcec7, 0x68c1, 0xcea7, - 0x689a, 0xce87, 0x6873, 0xce67, 0x684c, 0xce47, 0x6825, 0xce28, - 0x67fe, 0xce08, 0x67d6, 0xcde9, 0x67af, 0xcdca, 0x6788, 0xcdab, - 0x6760, 0xcd8c, 0x6738, 0xcd6d, 0x6711, 0xcd4e, 0x66e9, 0xcd30, - 0x66c1, 0xcd11, 0x6699, 0xccf3, 0x6671, 0xccd4, 0x6648, 0xccb6, - 0x6620, 0xcc98, 0x65f8, 0xcc7a, 0x65cf, 0xcc5d, 0x65a6, 0xcc3f, - 0x657e, 0xcc21, 0x6555, 0xcc04, 0x652c, 0xcbe7, 0x6503, 0xcbca, - 0x64da, 0xcbad, 0x64b1, 0xcb90, 0x6488, 0xcb73, 0x645e, 0xcb56, - 0x6435, 0xcb3a, 0x640b, 0xcb1e, 0x63e2, 0xcb01, 0x63b8, 0xcae5, - 0x638e, 0xcac9, 0x6365, 0xcaad, 0x633b, 0xca92, 0x6311, 0xca76, - 0x62e7, 0xca5b, 0x62bc, 0xca3f, 0x6292, 0xca24, 0x6268, 0xca09, - 0x623d, 0xc9ee, 0x6213, 0xc9d3, 0x61e8, 0xc9b8, 0x61be, 0xc99e, - 0x6193, 0xc983, 0x6168, 0xc969, 0x613d, 0xc94f, 0x6112, 0xc935, - 0x60e7, 0xc91b, 0x60bc, 0xc901, 0x6091, 0xc8e8, 0x6065, 0xc8ce, - 0x603a, 0xc8b5, 0x600f, 0xc89b, 0x5fe3, 0xc882, 0x5fb7, 0xc869, - 0x5f8c, 0xc850, 0x5f60, 0xc838, 0x5f34, 0xc81f, 0x5f08, 0xc807, - 0x5edc, 0xc7ee, 0x5eb0, 0xc7d6, 0x5e84, 0xc7be, 0x5e58, 0xc7a6, - 0x5e2b, 0xc78f, 0x5dff, 0xc777, 0x5dd3, 0xc75f, 0x5da6, 0xc748, - 0x5d79, 0xc731, 0x5d4d, 0xc71a, 0x5d20, 0xc703, 0x5cf3, 0xc6ec, - 0x5cc6, 0xc6d5, 0x5c99, 0xc6bf, 0x5c6c, 0xc6a8, 0x5c3f, 0xc692, - 0x5c12, 0xc67c, 0x5be5, 0xc666, 0x5bb8, 0xc650, 0x5b8a, 0xc63b, - 0x5b5d, 0xc625, 0x5b30, 0xc610, 0x5b02, 0xc5fa, 0x5ad4, 0xc5e5, - 0x5aa7, 0xc5d0, 0x5a79, 0xc5bb, 0x5a4b, 0xc5a7, 0x5a1d, 0xc592, - 0x59ef, 0xc57e, 0x59c1, 0xc569, 0x5993, 0xc555, 0x5965, 0xc541, - 0x5937, 0xc52d, 0x5909, 0xc51a, 0x58db, 0xc506, 0x58ac, 0xc4f2, - 0x587e, 0xc4df, 0x584f, 0xc4cc, 0x5821, 0xc4b9, 0x57f2, 0xc4a6, - 0x57c4, 0xc493, 0x5795, 0xc481, 0x5766, 0xc46e, 0x5737, 0xc45c, - 0x5709, 0xc44a, 0x56da, 0xc438, 0x56ab, 0xc426, 0x567c, 0xc414, - 0x564c, 0xc403, 0x561d, 0xc3f1, 0x55ee, 0xc3e0, 0x55bf, 0xc3cf, - 0x5590, 0xc3be, 0x5560, 0xc3ad, 0x5531, 0xc39c, 0x5501, 0xc38c, - 0x54d2, 0xc37b, 0x54a2, 0xc36b, 0x5473, 0xc35b, 0x5443, 0xc34b, - 0x5413, 0xc33b, 0x53e4, 0xc32b, 0x53b4, 0xc31c, 0x5384, 0xc30c, - 0x5354, 0xc2fd, 0x5324, 0xc2ee, 0x52f4, 0xc2df, 0x52c4, 0xc2d0, - 0x5294, 0xc2c1, 0x5264, 0xc2b3, 0x5234, 0xc2a5, 0x5204, 0xc296, - 0x51d3, 0xc288, 0x51a3, 0xc27a, 0x5173, 0xc26d, 0x5142, 0xc25f, - 0x5112, 0xc251, 0x50e1, 0xc244, 0x50b1, 0xc237, 0x5080, 0xc22a, - 0x5050, 0xc21d, 0x501f, 0xc210, 0x4fee, 0xc204, 0x4fbe, 0xc1f7, - 0x4f8d, 0xc1eb, 0x4f5c, 0xc1df, 0x4f2b, 0xc1d3, 0x4efb, 0xc1c7, - 0x4eca, 0xc1bb, 0x4e99, 0xc1b0, 0x4e68, 0xc1a4, 0x4e37, 0xc199, - 0x4e06, 0xc18e, 0x4dd5, 0xc183, 0x4da4, 0xc178, 0x4d72, 0xc16e, - 0x4d41, 0xc163, 0x4d10, 0xc159, 0x4cdf, 0xc14f, 0x4cae, 0xc145, - 0x4c7c, 0xc13b, 0x4c4b, 0xc131, 0x4c1a, 0xc128, 0x4be8, 0xc11e, - 0x4bb7, 0xc115, 0x4b85, 0xc10c, 0x4b54, 0xc103, 0x4b23, 0xc0fa, - 0x4af1, 0xc0f1, 0x4ac0, 0xc0e9, 0x4a8e, 0xc0e0, 0x4a5c, 0xc0d8, - 0x4a2b, 0xc0d0, 0x49f9, 0xc0c8, 0x49c7, 0xc0c0, 0x4996, 0xc0b9, - 0x4964, 0xc0b1, 0x4932, 0xc0aa, 0x4901, 0xc0a3, 0x48cf, 0xc09c, - 0x489d, 0xc095, 0x486b, 0xc08e, 0x4839, 0xc088, 0x4807, 0xc081, - 0x47d6, 0xc07b, 0x47a4, 0xc075, 0x4772, 0xc06f, 0x4740, 0xc069, - 0x470e, 0xc064, 0x46dc, 0xc05e, 0x46aa, 0xc059, 0x4678, 0xc054, - 0x4646, 0xc04f, 0x4614, 0xc04a, 0x45e2, 0xc045, 0x45b0, 0xc041, - 0x457e, 0xc03c, 0x454c, 0xc038, 0x451a, 0xc034, 0x44e7, 0xc030, - 0x44b5, 0xc02c, 0x4483, 0xc029, 0x4451, 0xc025, 0x441f, 0xc022, - 0x43ed, 0xc01f, 0x43bb, 0xc01c, 0x4388, 0xc019, 0x4356, 0xc016, - 0x4324, 0xc014, 0x42f2, 0xc011, 0x42c0, 0xc00f, 0x428d, 0xc00d, - 0x425b, 0xc00b, 0x4229, 0xc009, 0x41f7, 0xc008, 0x41c4, 0xc006, - 0x4192, 0xc005, 0x4160, 0xc004, 0x412e, 0xc003, 0x40fb, 0xc002, - 0x40c9, 0xc001, 0x4097, 0xc001, 0x4065, 0xc000, 0x4032, 0xc000 -}; - -/** -* @brief Initialization function for the Q15 RFFT/RIFFT. -* @param[in, out] *S points to an instance of the Q15 RFFT/RIFFT structure. -* @param[in] *S_CFFT points to an instance of the Q15 CFFT/CIFFT structure. -* @param[in] fftLenReal length of the FFT. -* @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. -* -* \par Description: -* \par -* The parameter fftLenReal Specifies length of RFFT/RIFFT Process. Supported FFT Lengths are 128, 512, 2048. -* \par -* The parameter ifftFlagR controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlagR to calculate RIFFT, otherwise RFFT is calculated. -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* This function also initializes Twiddle factor table. -*/ - -arm_status arm_rfft_init_q15( - arm_rfft_instance_q15 * S, - arm_cfft_radix4_instance_q15 * S_CFFT, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag) -{ - - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialize the Real FFT length */ - S->fftLenReal = (uint16_t) fftLenReal; - - /* Initialize the Complex FFT length */ - S->fftLenBy2 = (uint16_t) fftLenReal / 2u; - - /* Initialize the Twiddle coefficientA pointer */ - S->pTwiddleAReal = (q15_t *) realCoefAQ15; - - /* Initialize the Twiddle coefficientB pointer */ - S->pTwiddleBReal = (q15_t *) realCoefBQ15; - - /* Initialize the Flag for selection of RFFT or RIFFT */ - S->ifftFlagR = (uint8_t) ifftFlagR; - - /* Initialize the Flag for calculation Bit reversal or not */ - S->bitReverseFlagR = (uint8_t) bitReverseFlag; - - /* Initialization of coef modifier depending on the FFT length */ - switch (S->fftLenReal) - { - case 2048u: - S->twidCoefRModifier = 1u; - break; - case 512u: - S->twidCoefRModifier = 4u; - break; - case 128u: - S->twidCoefRModifier = 16u; - break; - default: - /* Reporting argument error if rfftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - /* Init Complex FFT Instance */ - S->pCfft = S_CFFT; - - if(S->ifftFlagR) - { - /* Initializes the CIFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_q15(S->pCfft, S->fftLenBy2, 1u, 1u); - } - else - { - /* Initializes the CFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_q15(S->pCfft, S->fftLenBy2, 0u, 1u); - } - - /* return the status of RFFT Init function */ - return (status); - -} - - /** - * @} end of RFFT_RIFFT group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_rfft_init_q15.c +* +* Description: RFFT & RIFFT Q15 initialisation function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup RFFT_RIFFT + * @{ + */ + + + +/** +* \par +* Generation floating point real_CoefA array: +* \par +* n = 1024 +*
for (i = 0; i < n; i++)   
+*  {   
+*    pATable[2 * i] = 0.5 * (1.0 - sin (2 * PI / (double) (2 * n) * (double) i));   
+*    pATable[2 * i + 1] = 0.5 * (-1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
+*  } 
+* \par +* Convert to fixed point Q15 format +* round(pATable[i] * pow(2, 15)) +*/ + + +static const q15_t realCoefAQ15[2048] = { + + 0x4000, 0xc000, 0x3fce, 0xc000, 0x3f9b, 0xc000, 0x3f69, 0xc001, + 0x3f37, 0xc001, 0x3f05, 0xc002, 0x3ed2, 0xc003, 0x3ea0, 0xc004, + 0x3e6e, 0xc005, 0x3e3c, 0xc006, 0x3e09, 0xc008, 0x3dd7, 0xc009, + 0x3da5, 0xc00b, 0x3d73, 0xc00d, 0x3d40, 0xc00f, 0x3d0e, 0xc011, + 0x3cdc, 0xc014, 0x3caa, 0xc016, 0x3c78, 0xc019, 0x3c45, 0xc01c, + 0x3c13, 0xc01f, 0x3be1, 0xc022, 0x3baf, 0xc025, 0x3b7d, 0xc029, + 0x3b4b, 0xc02c, 0x3b19, 0xc030, 0x3ae6, 0xc034, 0x3ab4, 0xc038, + 0x3a82, 0xc03c, 0x3a50, 0xc041, 0x3a1e, 0xc045, 0x39ec, 0xc04a, + 0x39ba, 0xc04f, 0x3988, 0xc054, 0x3956, 0xc059, 0x3924, 0xc05e, + 0x38f2, 0xc064, 0x38c0, 0xc069, 0x388e, 0xc06f, 0x385c, 0xc075, + 0x382a, 0xc07b, 0x37f9, 0xc081, 0x37c7, 0xc088, 0x3795, 0xc08e, + 0x3763, 0xc095, 0x3731, 0xc09c, 0x36ff, 0xc0a3, 0x36ce, 0xc0aa, + 0x369c, 0xc0b1, 0x366a, 0xc0b9, 0x3639, 0xc0c0, 0x3607, 0xc0c8, + 0x35d5, 0xc0d0, 0x35a4, 0xc0d8, 0x3572, 0xc0e0, 0x3540, 0xc0e9, + 0x350f, 0xc0f1, 0x34dd, 0xc0fa, 0x34ac, 0xc103, 0x347b, 0xc10c, + 0x3449, 0xc115, 0x3418, 0xc11e, 0x33e6, 0xc128, 0x33b5, 0xc131, + 0x3384, 0xc13b, 0x3352, 0xc145, 0x3321, 0xc14f, 0x32f0, 0xc159, + 0x32bf, 0xc163, 0x328e, 0xc16e, 0x325c, 0xc178, 0x322b, 0xc183, + 0x31fa, 0xc18e, 0x31c9, 0xc199, 0x3198, 0xc1a4, 0x3167, 0xc1b0, + 0x3136, 0xc1bb, 0x3105, 0xc1c7, 0x30d5, 0xc1d3, 0x30a4, 0xc1df, + 0x3073, 0xc1eb, 0x3042, 0xc1f7, 0x3012, 0xc204, 0x2fe1, 0xc210, + 0x2fb0, 0xc21d, 0x2f80, 0xc22a, 0x2f4f, 0xc237, 0x2f1f, 0xc244, + 0x2eee, 0xc251, 0x2ebe, 0xc25f, 0x2e8d, 0xc26d, 0x2e5d, 0xc27a, + 0x2e2d, 0xc288, 0x2dfc, 0xc296, 0x2dcc, 0xc2a5, 0x2d9c, 0xc2b3, + 0x2d6c, 0xc2c1, 0x2d3c, 0xc2d0, 0x2d0c, 0xc2df, 0x2cdc, 0xc2ee, + 0x2cac, 0xc2fd, 0x2c7c, 0xc30c, 0x2c4c, 0xc31c, 0x2c1c, 0xc32b, + 0x2bed, 0xc33b, 0x2bbd, 0xc34b, 0x2b8d, 0xc35b, 0x2b5e, 0xc36b, + 0x2b2e, 0xc37b, 0x2aff, 0xc38c, 0x2acf, 0xc39c, 0x2aa0, 0xc3ad, + 0x2a70, 0xc3be, 0x2a41, 0xc3cf, 0x2a12, 0xc3e0, 0x29e3, 0xc3f1, + 0x29b4, 0xc403, 0x2984, 0xc414, 0x2955, 0xc426, 0x2926, 0xc438, + 0x28f7, 0xc44a, 0x28c9, 0xc45c, 0x289a, 0xc46e, 0x286b, 0xc481, + 0x283c, 0xc493, 0x280e, 0xc4a6, 0x27df, 0xc4b9, 0x27b1, 0xc4cc, + 0x2782, 0xc4df, 0x2754, 0xc4f2, 0x2725, 0xc506, 0x26f7, 0xc51a, + 0x26c9, 0xc52d, 0x269b, 0xc541, 0x266d, 0xc555, 0x263f, 0xc569, + 0x2611, 0xc57e, 0x25e3, 0xc592, 0x25b5, 0xc5a7, 0x2587, 0xc5bb, + 0x2559, 0xc5d0, 0x252c, 0xc5e5, 0x24fe, 0xc5fa, 0x24d0, 0xc610, + 0x24a3, 0xc625, 0x2476, 0xc63b, 0x2448, 0xc650, 0x241b, 0xc666, + 0x23ee, 0xc67c, 0x23c1, 0xc692, 0x2394, 0xc6a8, 0x2367, 0xc6bf, + 0x233a, 0xc6d5, 0x230d, 0xc6ec, 0x22e0, 0xc703, 0x22b3, 0xc71a, + 0x2287, 0xc731, 0x225a, 0xc748, 0x222d, 0xc75f, 0x2201, 0xc777, + 0x21d5, 0xc78f, 0x21a8, 0xc7a6, 0x217c, 0xc7be, 0x2150, 0xc7d6, + 0x2124, 0xc7ee, 0x20f8, 0xc807, 0x20cc, 0xc81f, 0x20a0, 0xc838, + 0x2074, 0xc850, 0x2049, 0xc869, 0x201d, 0xc882, 0x1ff1, 0xc89b, + 0x1fc6, 0xc8b5, 0x1f9b, 0xc8ce, 0x1f6f, 0xc8e8, 0x1f44, 0xc901, + 0x1f19, 0xc91b, 0x1eee, 0xc935, 0x1ec3, 0xc94f, 0x1e98, 0xc969, + 0x1e6d, 0xc983, 0x1e42, 0xc99e, 0x1e18, 0xc9b8, 0x1ded, 0xc9d3, + 0x1dc3, 0xc9ee, 0x1d98, 0xca09, 0x1d6e, 0xca24, 0x1d44, 0xca3f, + 0x1d19, 0xca5b, 0x1cef, 0xca76, 0x1cc5, 0xca92, 0x1c9b, 0xcaad, + 0x1c72, 0xcac9, 0x1c48, 0xcae5, 0x1c1e, 0xcb01, 0x1bf5, 0xcb1e, + 0x1bcb, 0xcb3a, 0x1ba2, 0xcb56, 0x1b78, 0xcb73, 0x1b4f, 0xcb90, + 0x1b26, 0xcbad, 0x1afd, 0xcbca, 0x1ad4, 0xcbe7, 0x1aab, 0xcc04, + 0x1a82, 0xcc21, 0x1a5a, 0xcc3f, 0x1a31, 0xcc5d, 0x1a08, 0xcc7a, + 0x19e0, 0xcc98, 0x19b8, 0xccb6, 0x198f, 0xccd4, 0x1967, 0xccf3, + 0x193f, 0xcd11, 0x1917, 0xcd30, 0x18ef, 0xcd4e, 0x18c8, 0xcd6d, + 0x18a0, 0xcd8c, 0x1878, 0xcdab, 0x1851, 0xcdca, 0x182a, 0xcde9, + 0x1802, 0xce08, 0x17db, 0xce28, 0x17b4, 0xce47, 0x178d, 0xce67, + 0x1766, 0xce87, 0x173f, 0xcea7, 0x1719, 0xcec7, 0x16f2, 0xcee7, + 0x16cb, 0xcf07, 0x16a5, 0xcf28, 0x167f, 0xcf48, 0x1659, 0xcf69, + 0x1632, 0xcf8a, 0x160c, 0xcfab, 0x15e6, 0xcfcc, 0x15c1, 0xcfed, + 0x159b, 0xd00e, 0x1575, 0xd030, 0x1550, 0xd051, 0x152a, 0xd073, + 0x1505, 0xd094, 0x14e0, 0xd0b6, 0x14bb, 0xd0d8, 0x1496, 0xd0fa, + 0x1471, 0xd11c, 0x144c, 0xd13e, 0x1428, 0xd161, 0x1403, 0xd183, + 0x13df, 0xd1a6, 0x13ba, 0xd1c9, 0x1396, 0xd1eb, 0x1372, 0xd20e, + 0x134e, 0xd231, 0x132a, 0xd255, 0x1306, 0xd278, 0x12e2, 0xd29b, + 0x12bf, 0xd2bf, 0x129b, 0xd2e2, 0x1278, 0xd306, 0x1255, 0xd32a, + 0x1231, 0xd34e, 0x120e, 0xd372, 0x11eb, 0xd396, 0x11c9, 0xd3ba, + 0x11a6, 0xd3df, 0x1183, 0xd403, 0x1161, 0xd428, 0x113e, 0xd44c, + 0x111c, 0xd471, 0x10fa, 0xd496, 0x10d8, 0xd4bb, 0x10b6, 0xd4e0, + 0x1094, 0xd505, 0x1073, 0xd52a, 0x1051, 0xd550, 0x1030, 0xd575, + 0x100e, 0xd59b, 0xfed, 0xd5c1, 0xfcc, 0xd5e6, 0xfab, 0xd60c, + 0xf8a, 0xd632, 0xf69, 0xd659, 0xf48, 0xd67f, 0xf28, 0xd6a5, + 0xf07, 0xd6cb, 0xee7, 0xd6f2, 0xec7, 0xd719, 0xea7, 0xd73f, + 0xe87, 0xd766, 0xe67, 0xd78d, 0xe47, 0xd7b4, 0xe28, 0xd7db, + 0xe08, 0xd802, 0xde9, 0xd82a, 0xdca, 0xd851, 0xdab, 0xd878, + 0xd8c, 0xd8a0, 0xd6d, 0xd8c8, 0xd4e, 0xd8ef, 0xd30, 0xd917, + 0xd11, 0xd93f, 0xcf3, 0xd967, 0xcd4, 0xd98f, 0xcb6, 0xd9b8, + 0xc98, 0xd9e0, 0xc7a, 0xda08, 0xc5d, 0xda31, 0xc3f, 0xda5a, + 0xc21, 0xda82, 0xc04, 0xdaab, 0xbe7, 0xdad4, 0xbca, 0xdafd, + 0xbad, 0xdb26, 0xb90, 0xdb4f, 0xb73, 0xdb78, 0xb56, 0xdba2, + 0xb3a, 0xdbcb, 0xb1e, 0xdbf5, 0xb01, 0xdc1e, 0xae5, 0xdc48, + 0xac9, 0xdc72, 0xaad, 0xdc9b, 0xa92, 0xdcc5, 0xa76, 0xdcef, + 0xa5b, 0xdd19, 0xa3f, 0xdd44, 0xa24, 0xdd6e, 0xa09, 0xdd98, + 0x9ee, 0xddc3, 0x9d3, 0xdded, 0x9b8, 0xde18, 0x99e, 0xde42, + 0x983, 0xde6d, 0x969, 0xde98, 0x94f, 0xdec3, 0x935, 0xdeee, + 0x91b, 0xdf19, 0x901, 0xdf44, 0x8e8, 0xdf6f, 0x8ce, 0xdf9b, + 0x8b5, 0xdfc6, 0x89b, 0xdff1, 0x882, 0xe01d, 0x869, 0xe049, + 0x850, 0xe074, 0x838, 0xe0a0, 0x81f, 0xe0cc, 0x807, 0xe0f8, + 0x7ee, 0xe124, 0x7d6, 0xe150, 0x7be, 0xe17c, 0x7a6, 0xe1a8, + 0x78f, 0xe1d5, 0x777, 0xe201, 0x75f, 0xe22d, 0x748, 0xe25a, + 0x731, 0xe287, 0x71a, 0xe2b3, 0x703, 0xe2e0, 0x6ec, 0xe30d, + 0x6d5, 0xe33a, 0x6bf, 0xe367, 0x6a8, 0xe394, 0x692, 0xe3c1, + 0x67c, 0xe3ee, 0x666, 0xe41b, 0x650, 0xe448, 0x63b, 0xe476, + 0x625, 0xe4a3, 0x610, 0xe4d0, 0x5fa, 0xe4fe, 0x5e5, 0xe52c, + 0x5d0, 0xe559, 0x5bb, 0xe587, 0x5a7, 0xe5b5, 0x592, 0xe5e3, + 0x57e, 0xe611, 0x569, 0xe63f, 0x555, 0xe66d, 0x541, 0xe69b, + 0x52d, 0xe6c9, 0x51a, 0xe6f7, 0x506, 0xe725, 0x4f2, 0xe754, + 0x4df, 0xe782, 0x4cc, 0xe7b1, 0x4b9, 0xe7df, 0x4a6, 0xe80e, + 0x493, 0xe83c, 0x481, 0xe86b, 0x46e, 0xe89a, 0x45c, 0xe8c9, + 0x44a, 0xe8f7, 0x438, 0xe926, 0x426, 0xe955, 0x414, 0xe984, + 0x403, 0xe9b4, 0x3f1, 0xe9e3, 0x3e0, 0xea12, 0x3cf, 0xea41, + 0x3be, 0xea70, 0x3ad, 0xeaa0, 0x39c, 0xeacf, 0x38c, 0xeaff, + 0x37b, 0xeb2e, 0x36b, 0xeb5e, 0x35b, 0xeb8d, 0x34b, 0xebbd, + 0x33b, 0xebed, 0x32b, 0xec1c, 0x31c, 0xec4c, 0x30c, 0xec7c, + 0x2fd, 0xecac, 0x2ee, 0xecdc, 0x2df, 0xed0c, 0x2d0, 0xed3c, + 0x2c1, 0xed6c, 0x2b3, 0xed9c, 0x2a5, 0xedcc, 0x296, 0xedfc, + 0x288, 0xee2d, 0x27a, 0xee5d, 0x26d, 0xee8d, 0x25f, 0xeebe, + 0x251, 0xeeee, 0x244, 0xef1f, 0x237, 0xef4f, 0x22a, 0xef80, + 0x21d, 0xefb0, 0x210, 0xefe1, 0x204, 0xf012, 0x1f7, 0xf042, + 0x1eb, 0xf073, 0x1df, 0xf0a4, 0x1d3, 0xf0d5, 0x1c7, 0xf105, + 0x1bb, 0xf136, 0x1b0, 0xf167, 0x1a4, 0xf198, 0x199, 0xf1c9, + 0x18e, 0xf1fa, 0x183, 0xf22b, 0x178, 0xf25c, 0x16e, 0xf28e, + 0x163, 0xf2bf, 0x159, 0xf2f0, 0x14f, 0xf321, 0x145, 0xf352, + 0x13b, 0xf384, 0x131, 0xf3b5, 0x128, 0xf3e6, 0x11e, 0xf418, + 0x115, 0xf449, 0x10c, 0xf47b, 0x103, 0xf4ac, 0xfa, 0xf4dd, + 0xf1, 0xf50f, 0xe9, 0xf540, 0xe0, 0xf572, 0xd8, 0xf5a4, + 0xd0, 0xf5d5, 0xc8, 0xf607, 0xc0, 0xf639, 0xb9, 0xf66a, + 0xb1, 0xf69c, 0xaa, 0xf6ce, 0xa3, 0xf6ff, 0x9c, 0xf731, + 0x95, 0xf763, 0x8e, 0xf795, 0x88, 0xf7c7, 0x81, 0xf7f9, + 0x7b, 0xf82a, 0x75, 0xf85c, 0x6f, 0xf88e, 0x69, 0xf8c0, + 0x64, 0xf8f2, 0x5e, 0xf924, 0x59, 0xf956, 0x54, 0xf988, + 0x4f, 0xf9ba, 0x4a, 0xf9ec, 0x45, 0xfa1e, 0x41, 0xfa50, + 0x3c, 0xfa82, 0x38, 0xfab4, 0x34, 0xfae6, 0x30, 0xfb19, + 0x2c, 0xfb4b, 0x29, 0xfb7d, 0x25, 0xfbaf, 0x22, 0xfbe1, + 0x1f, 0xfc13, 0x1c, 0xfc45, 0x19, 0xfc78, 0x16, 0xfcaa, + 0x14, 0xfcdc, 0x11, 0xfd0e, 0xf, 0xfd40, 0xd, 0xfd73, + 0xb, 0xfda5, 0x9, 0xfdd7, 0x8, 0xfe09, 0x6, 0xfe3c, + 0x5, 0xfe6e, 0x4, 0xfea0, 0x3, 0xfed2, 0x2, 0xff05, + 0x1, 0xff37, 0x1, 0xff69, 0x0, 0xff9b, 0x0, 0xffce, + 0x0, 0x0, 0x0, 0x32, 0x0, 0x65, 0x1, 0x97, + 0x1, 0xc9, 0x2, 0xfb, 0x3, 0x12e, 0x4, 0x160, + 0x5, 0x192, 0x6, 0x1c4, 0x8, 0x1f7, 0x9, 0x229, + 0xb, 0x25b, 0xd, 0x28d, 0xf, 0x2c0, 0x11, 0x2f2, + 0x14, 0x324, 0x16, 0x356, 0x19, 0x388, 0x1c, 0x3bb, + 0x1f, 0x3ed, 0x22, 0x41f, 0x25, 0x451, 0x29, 0x483, + 0x2c, 0x4b5, 0x30, 0x4e7, 0x34, 0x51a, 0x38, 0x54c, + 0x3c, 0x57e, 0x41, 0x5b0, 0x45, 0x5e2, 0x4a, 0x614, + 0x4f, 0x646, 0x54, 0x678, 0x59, 0x6aa, 0x5e, 0x6dc, + 0x64, 0x70e, 0x69, 0x740, 0x6f, 0x772, 0x75, 0x7a4, + 0x7b, 0x7d6, 0x81, 0x807, 0x88, 0x839, 0x8e, 0x86b, + 0x95, 0x89d, 0x9c, 0x8cf, 0xa3, 0x901, 0xaa, 0x932, + 0xb1, 0x964, 0xb9, 0x996, 0xc0, 0x9c7, 0xc8, 0x9f9, + 0xd0, 0xa2b, 0xd8, 0xa5c, 0xe0, 0xa8e, 0xe9, 0xac0, + 0xf1, 0xaf1, 0xfa, 0xb23, 0x103, 0xb54, 0x10c, 0xb85, + 0x115, 0xbb7, 0x11e, 0xbe8, 0x128, 0xc1a, 0x131, 0xc4b, + 0x13b, 0xc7c, 0x145, 0xcae, 0x14f, 0xcdf, 0x159, 0xd10, + 0x163, 0xd41, 0x16e, 0xd72, 0x178, 0xda4, 0x183, 0xdd5, + 0x18e, 0xe06, 0x199, 0xe37, 0x1a4, 0xe68, 0x1b0, 0xe99, + 0x1bb, 0xeca, 0x1c7, 0xefb, 0x1d3, 0xf2b, 0x1df, 0xf5c, + 0x1eb, 0xf8d, 0x1f7, 0xfbe, 0x204, 0xfee, 0x210, 0x101f, + 0x21d, 0x1050, 0x22a, 0x1080, 0x237, 0x10b1, 0x244, 0x10e1, + 0x251, 0x1112, 0x25f, 0x1142, 0x26d, 0x1173, 0x27a, 0x11a3, + 0x288, 0x11d3, 0x296, 0x1204, 0x2a5, 0x1234, 0x2b3, 0x1264, + 0x2c1, 0x1294, 0x2d0, 0x12c4, 0x2df, 0x12f4, 0x2ee, 0x1324, + 0x2fd, 0x1354, 0x30c, 0x1384, 0x31c, 0x13b4, 0x32b, 0x13e4, + 0x33b, 0x1413, 0x34b, 0x1443, 0x35b, 0x1473, 0x36b, 0x14a2, + 0x37b, 0x14d2, 0x38c, 0x1501, 0x39c, 0x1531, 0x3ad, 0x1560, + 0x3be, 0x1590, 0x3cf, 0x15bf, 0x3e0, 0x15ee, 0x3f1, 0x161d, + 0x403, 0x164c, 0x414, 0x167c, 0x426, 0x16ab, 0x438, 0x16da, + 0x44a, 0x1709, 0x45c, 0x1737, 0x46e, 0x1766, 0x481, 0x1795, + 0x493, 0x17c4, 0x4a6, 0x17f2, 0x4b9, 0x1821, 0x4cc, 0x184f, + 0x4df, 0x187e, 0x4f2, 0x18ac, 0x506, 0x18db, 0x51a, 0x1909, + 0x52d, 0x1937, 0x541, 0x1965, 0x555, 0x1993, 0x569, 0x19c1, + 0x57e, 0x19ef, 0x592, 0x1a1d, 0x5a7, 0x1a4b, 0x5bb, 0x1a79, + 0x5d0, 0x1aa7, 0x5e5, 0x1ad4, 0x5fa, 0x1b02, 0x610, 0x1b30, + 0x625, 0x1b5d, 0x63b, 0x1b8a, 0x650, 0x1bb8, 0x666, 0x1be5, + 0x67c, 0x1c12, 0x692, 0x1c3f, 0x6a8, 0x1c6c, 0x6bf, 0x1c99, + 0x6d5, 0x1cc6, 0x6ec, 0x1cf3, 0x703, 0x1d20, 0x71a, 0x1d4d, + 0x731, 0x1d79, 0x748, 0x1da6, 0x75f, 0x1dd3, 0x777, 0x1dff, + 0x78f, 0x1e2b, 0x7a6, 0x1e58, 0x7be, 0x1e84, 0x7d6, 0x1eb0, + 0x7ee, 0x1edc, 0x807, 0x1f08, 0x81f, 0x1f34, 0x838, 0x1f60, + 0x850, 0x1f8c, 0x869, 0x1fb7, 0x882, 0x1fe3, 0x89b, 0x200f, + 0x8b5, 0x203a, 0x8ce, 0x2065, 0x8e8, 0x2091, 0x901, 0x20bc, + 0x91b, 0x20e7, 0x935, 0x2112, 0x94f, 0x213d, 0x969, 0x2168, + 0x983, 0x2193, 0x99e, 0x21be, 0x9b8, 0x21e8, 0x9d3, 0x2213, + 0x9ee, 0x223d, 0xa09, 0x2268, 0xa24, 0x2292, 0xa3f, 0x22bc, + 0xa5b, 0x22e7, 0xa76, 0x2311, 0xa92, 0x233b, 0xaad, 0x2365, + 0xac9, 0x238e, 0xae5, 0x23b8, 0xb01, 0x23e2, 0xb1e, 0x240b, + 0xb3a, 0x2435, 0xb56, 0x245e, 0xb73, 0x2488, 0xb90, 0x24b1, + 0xbad, 0x24da, 0xbca, 0x2503, 0xbe7, 0x252c, 0xc04, 0x2555, + 0xc21, 0x257e, 0xc3f, 0x25a6, 0xc5d, 0x25cf, 0xc7a, 0x25f8, + 0xc98, 0x2620, 0xcb6, 0x2648, 0xcd4, 0x2671, 0xcf3, 0x2699, + 0xd11, 0x26c1, 0xd30, 0x26e9, 0xd4e, 0x2711, 0xd6d, 0x2738, + 0xd8c, 0x2760, 0xdab, 0x2788, 0xdca, 0x27af, 0xde9, 0x27d6, + 0xe08, 0x27fe, 0xe28, 0x2825, 0xe47, 0x284c, 0xe67, 0x2873, + 0xe87, 0x289a, 0xea7, 0x28c1, 0xec7, 0x28e7, 0xee7, 0x290e, + 0xf07, 0x2935, 0xf28, 0x295b, 0xf48, 0x2981, 0xf69, 0x29a7, + 0xf8a, 0x29ce, 0xfab, 0x29f4, 0xfcc, 0x2a1a, 0xfed, 0x2a3f, + 0x100e, 0x2a65, 0x1030, 0x2a8b, 0x1051, 0x2ab0, 0x1073, 0x2ad6, + 0x1094, 0x2afb, 0x10b6, 0x2b20, 0x10d8, 0x2b45, 0x10fa, 0x2b6a, + 0x111c, 0x2b8f, 0x113e, 0x2bb4, 0x1161, 0x2bd8, 0x1183, 0x2bfd, + 0x11a6, 0x2c21, 0x11c9, 0x2c46, 0x11eb, 0x2c6a, 0x120e, 0x2c8e, + 0x1231, 0x2cb2, 0x1255, 0x2cd6, 0x1278, 0x2cfa, 0x129b, 0x2d1e, + 0x12bf, 0x2d41, 0x12e2, 0x2d65, 0x1306, 0x2d88, 0x132a, 0x2dab, + 0x134e, 0x2dcf, 0x1372, 0x2df2, 0x1396, 0x2e15, 0x13ba, 0x2e37, + 0x13df, 0x2e5a, 0x1403, 0x2e7d, 0x1428, 0x2e9f, 0x144c, 0x2ec2, + 0x1471, 0x2ee4, 0x1496, 0x2f06, 0x14bb, 0x2f28, 0x14e0, 0x2f4a, + 0x1505, 0x2f6c, 0x152a, 0x2f8d, 0x1550, 0x2faf, 0x1575, 0x2fd0, + 0x159b, 0x2ff2, 0x15c1, 0x3013, 0x15e6, 0x3034, 0x160c, 0x3055, + 0x1632, 0x3076, 0x1659, 0x3097, 0x167f, 0x30b8, 0x16a5, 0x30d8, + 0x16cb, 0x30f9, 0x16f2, 0x3119, 0x1719, 0x3139, 0x173f, 0x3159, + 0x1766, 0x3179, 0x178d, 0x3199, 0x17b4, 0x31b9, 0x17db, 0x31d8, + 0x1802, 0x31f8, 0x182a, 0x3217, 0x1851, 0x3236, 0x1878, 0x3255, + 0x18a0, 0x3274, 0x18c8, 0x3293, 0x18ef, 0x32b2, 0x1917, 0x32d0, + 0x193f, 0x32ef, 0x1967, 0x330d, 0x198f, 0x332c, 0x19b8, 0x334a, + 0x19e0, 0x3368, 0x1a08, 0x3386, 0x1a31, 0x33a3, 0x1a5a, 0x33c1, + 0x1a82, 0x33df, 0x1aab, 0x33fc, 0x1ad4, 0x3419, 0x1afd, 0x3436, + 0x1b26, 0x3453, 0x1b4f, 0x3470, 0x1b78, 0x348d, 0x1ba2, 0x34aa, + 0x1bcb, 0x34c6, 0x1bf5, 0x34e2, 0x1c1e, 0x34ff, 0x1c48, 0x351b, + 0x1c72, 0x3537, 0x1c9b, 0x3553, 0x1cc5, 0x356e, 0x1cef, 0x358a, + 0x1d19, 0x35a5, 0x1d44, 0x35c1, 0x1d6e, 0x35dc, 0x1d98, 0x35f7, + 0x1dc3, 0x3612, 0x1ded, 0x362d, 0x1e18, 0x3648, 0x1e42, 0x3662, + 0x1e6d, 0x367d, 0x1e98, 0x3697, 0x1ec3, 0x36b1, 0x1eee, 0x36cb, + 0x1f19, 0x36e5, 0x1f44, 0x36ff, 0x1f6f, 0x3718, 0x1f9b, 0x3732, + 0x1fc6, 0x374b, 0x1ff1, 0x3765, 0x201d, 0x377e, 0x2049, 0x3797, + 0x2074, 0x37b0, 0x20a0, 0x37c8, 0x20cc, 0x37e1, 0x20f8, 0x37f9, + 0x2124, 0x3812, 0x2150, 0x382a, 0x217c, 0x3842, 0x21a8, 0x385a, + 0x21d5, 0x3871, 0x2201, 0x3889, 0x222d, 0x38a1, 0x225a, 0x38b8, + 0x2287, 0x38cf, 0x22b3, 0x38e6, 0x22e0, 0x38fd, 0x230d, 0x3914, + 0x233a, 0x392b, 0x2367, 0x3941, 0x2394, 0x3958, 0x23c1, 0x396e, + 0x23ee, 0x3984, 0x241b, 0x399a, 0x2448, 0x39b0, 0x2476, 0x39c5, + 0x24a3, 0x39db, 0x24d0, 0x39f0, 0x24fe, 0x3a06, 0x252c, 0x3a1b, + 0x2559, 0x3a30, 0x2587, 0x3a45, 0x25b5, 0x3a59, 0x25e3, 0x3a6e, + 0x2611, 0x3a82, 0x263f, 0x3a97, 0x266d, 0x3aab, 0x269b, 0x3abf, + 0x26c9, 0x3ad3, 0x26f7, 0x3ae6, 0x2725, 0x3afa, 0x2754, 0x3b0e, + 0x2782, 0x3b21, 0x27b1, 0x3b34, 0x27df, 0x3b47, 0x280e, 0x3b5a, + 0x283c, 0x3b6d, 0x286b, 0x3b7f, 0x289a, 0x3b92, 0x28c9, 0x3ba4, + 0x28f7, 0x3bb6, 0x2926, 0x3bc8, 0x2955, 0x3bda, 0x2984, 0x3bec, + 0x29b4, 0x3bfd, 0x29e3, 0x3c0f, 0x2a12, 0x3c20, 0x2a41, 0x3c31, + 0x2a70, 0x3c42, 0x2aa0, 0x3c53, 0x2acf, 0x3c64, 0x2aff, 0x3c74, + 0x2b2e, 0x3c85, 0x2b5e, 0x3c95, 0x2b8d, 0x3ca5, 0x2bbd, 0x3cb5, + 0x2bed, 0x3cc5, 0x2c1c, 0x3cd5, 0x2c4c, 0x3ce4, 0x2c7c, 0x3cf4, + 0x2cac, 0x3d03, 0x2cdc, 0x3d12, 0x2d0c, 0x3d21, 0x2d3c, 0x3d30, + 0x2d6c, 0x3d3f, 0x2d9c, 0x3d4d, 0x2dcc, 0x3d5b, 0x2dfc, 0x3d6a, + 0x2e2d, 0x3d78, 0x2e5d, 0x3d86, 0x2e8d, 0x3d93, 0x2ebe, 0x3da1, + 0x2eee, 0x3daf, 0x2f1f, 0x3dbc, 0x2f4f, 0x3dc9, 0x2f80, 0x3dd6, + 0x2fb0, 0x3de3, 0x2fe1, 0x3df0, 0x3012, 0x3dfc, 0x3042, 0x3e09, + 0x3073, 0x3e15, 0x30a4, 0x3e21, 0x30d5, 0x3e2d, 0x3105, 0x3e39, + 0x3136, 0x3e45, 0x3167, 0x3e50, 0x3198, 0x3e5c, 0x31c9, 0x3e67, + 0x31fa, 0x3e72, 0x322b, 0x3e7d, 0x325c, 0x3e88, 0x328e, 0x3e92, + 0x32bf, 0x3e9d, 0x32f0, 0x3ea7, 0x3321, 0x3eb1, 0x3352, 0x3ebb, + 0x3384, 0x3ec5, 0x33b5, 0x3ecf, 0x33e6, 0x3ed8, 0x3418, 0x3ee2, + 0x3449, 0x3eeb, 0x347b, 0x3ef4, 0x34ac, 0x3efd, 0x34dd, 0x3f06, + 0x350f, 0x3f0f, 0x3540, 0x3f17, 0x3572, 0x3f20, 0x35a4, 0x3f28, + 0x35d5, 0x3f30, 0x3607, 0x3f38, 0x3639, 0x3f40, 0x366a, 0x3f47, + 0x369c, 0x3f4f, 0x36ce, 0x3f56, 0x36ff, 0x3f5d, 0x3731, 0x3f64, + 0x3763, 0x3f6b, 0x3795, 0x3f72, 0x37c7, 0x3f78, 0x37f9, 0x3f7f, + 0x382a, 0x3f85, 0x385c, 0x3f8b, 0x388e, 0x3f91, 0x38c0, 0x3f97, + 0x38f2, 0x3f9c, 0x3924, 0x3fa2, 0x3956, 0x3fa7, 0x3988, 0x3fac, + 0x39ba, 0x3fb1, 0x39ec, 0x3fb6, 0x3a1e, 0x3fbb, 0x3a50, 0x3fbf, + 0x3a82, 0x3fc4, 0x3ab4, 0x3fc8, 0x3ae6, 0x3fcc, 0x3b19, 0x3fd0, + 0x3b4b, 0x3fd4, 0x3b7d, 0x3fd7, 0x3baf, 0x3fdb, 0x3be1, 0x3fde, + 0x3c13, 0x3fe1, 0x3c45, 0x3fe4, 0x3c78, 0x3fe7, 0x3caa, 0x3fea, + 0x3cdc, 0x3fec, 0x3d0e, 0x3fef, 0x3d40, 0x3ff1, 0x3d73, 0x3ff3, + 0x3da5, 0x3ff5, 0x3dd7, 0x3ff7, 0x3e09, 0x3ff8, 0x3e3c, 0x3ffa, + 0x3e6e, 0x3ffb, 0x3ea0, 0x3ffc, 0x3ed2, 0x3ffd, 0x3f05, 0x3ffe, + 0x3f37, 0x3fff, 0x3f69, 0x3fff, 0x3f9b, 0x4000, 0x3fce, 0x4000 +}; + +/** +* \par +* Generation of real_CoefB array: +* \par +* n = 1024 +*
for (i = 0; i < n; i++)   
+*  {   
+*    pBTable[2 * i] = 0.5 * (1.0 + sin (2 * PI / (double) (2 * n) * (double) i));   
+*    pBTable[2 * i + 1] = 0.5 * (1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
+*  } 
+* \par +* Convert to fixed point Q15 format +* round(pBTable[i] * pow(2, 15)) +* +*/ + +static const q15_t realCoefBQ15[2048] = { + 0x4000, 0x4000, 0x4032, 0x4000, 0x4065, 0x4000, 0x4097, 0x3fff, + 0x40c9, 0x3fff, 0x40fb, 0x3ffe, 0x412e, 0x3ffd, 0x4160, 0x3ffc, + 0x4192, 0x3ffb, 0x41c4, 0x3ffa, 0x41f7, 0x3ff8, 0x4229, 0x3ff7, + 0x425b, 0x3ff5, 0x428d, 0x3ff3, 0x42c0, 0x3ff1, 0x42f2, 0x3fef, + 0x4324, 0x3fec, 0x4356, 0x3fea, 0x4388, 0x3fe7, 0x43bb, 0x3fe4, + 0x43ed, 0x3fe1, 0x441f, 0x3fde, 0x4451, 0x3fdb, 0x4483, 0x3fd7, + 0x44b5, 0x3fd4, 0x44e7, 0x3fd0, 0x451a, 0x3fcc, 0x454c, 0x3fc8, + 0x457e, 0x3fc4, 0x45b0, 0x3fbf, 0x45e2, 0x3fbb, 0x4614, 0x3fb6, + 0x4646, 0x3fb1, 0x4678, 0x3fac, 0x46aa, 0x3fa7, 0x46dc, 0x3fa2, + 0x470e, 0x3f9c, 0x4740, 0x3f97, 0x4772, 0x3f91, 0x47a4, 0x3f8b, + 0x47d6, 0x3f85, 0x4807, 0x3f7f, 0x4839, 0x3f78, 0x486b, 0x3f72, + 0x489d, 0x3f6b, 0x48cf, 0x3f64, 0x4901, 0x3f5d, 0x4932, 0x3f56, + 0x4964, 0x3f4f, 0x4996, 0x3f47, 0x49c7, 0x3f40, 0x49f9, 0x3f38, + 0x4a2b, 0x3f30, 0x4a5c, 0x3f28, 0x4a8e, 0x3f20, 0x4ac0, 0x3f17, + 0x4af1, 0x3f0f, 0x4b23, 0x3f06, 0x4b54, 0x3efd, 0x4b85, 0x3ef4, + 0x4bb7, 0x3eeb, 0x4be8, 0x3ee2, 0x4c1a, 0x3ed8, 0x4c4b, 0x3ecf, + 0x4c7c, 0x3ec5, 0x4cae, 0x3ebb, 0x4cdf, 0x3eb1, 0x4d10, 0x3ea7, + 0x4d41, 0x3e9d, 0x4d72, 0x3e92, 0x4da4, 0x3e88, 0x4dd5, 0x3e7d, + 0x4e06, 0x3e72, 0x4e37, 0x3e67, 0x4e68, 0x3e5c, 0x4e99, 0x3e50, + 0x4eca, 0x3e45, 0x4efb, 0x3e39, 0x4f2b, 0x3e2d, 0x4f5c, 0x3e21, + 0x4f8d, 0x3e15, 0x4fbe, 0x3e09, 0x4fee, 0x3dfc, 0x501f, 0x3df0, + 0x5050, 0x3de3, 0x5080, 0x3dd6, 0x50b1, 0x3dc9, 0x50e1, 0x3dbc, + 0x5112, 0x3daf, 0x5142, 0x3da1, 0x5173, 0x3d93, 0x51a3, 0x3d86, + 0x51d3, 0x3d78, 0x5204, 0x3d6a, 0x5234, 0x3d5b, 0x5264, 0x3d4d, + 0x5294, 0x3d3f, 0x52c4, 0x3d30, 0x52f4, 0x3d21, 0x5324, 0x3d12, + 0x5354, 0x3d03, 0x5384, 0x3cf4, 0x53b4, 0x3ce4, 0x53e4, 0x3cd5, + 0x5413, 0x3cc5, 0x5443, 0x3cb5, 0x5473, 0x3ca5, 0x54a2, 0x3c95, + 0x54d2, 0x3c85, 0x5501, 0x3c74, 0x5531, 0x3c64, 0x5560, 0x3c53, + 0x5590, 0x3c42, 0x55bf, 0x3c31, 0x55ee, 0x3c20, 0x561d, 0x3c0f, + 0x564c, 0x3bfd, 0x567c, 0x3bec, 0x56ab, 0x3bda, 0x56da, 0x3bc8, + 0x5709, 0x3bb6, 0x5737, 0x3ba4, 0x5766, 0x3b92, 0x5795, 0x3b7f, + 0x57c4, 0x3b6d, 0x57f2, 0x3b5a, 0x5821, 0x3b47, 0x584f, 0x3b34, + 0x587e, 0x3b21, 0x58ac, 0x3b0e, 0x58db, 0x3afa, 0x5909, 0x3ae6, + 0x5937, 0x3ad3, 0x5965, 0x3abf, 0x5993, 0x3aab, 0x59c1, 0x3a97, + 0x59ef, 0x3a82, 0x5a1d, 0x3a6e, 0x5a4b, 0x3a59, 0x5a79, 0x3a45, + 0x5aa7, 0x3a30, 0x5ad4, 0x3a1b, 0x5b02, 0x3a06, 0x5b30, 0x39f0, + 0x5b5d, 0x39db, 0x5b8a, 0x39c5, 0x5bb8, 0x39b0, 0x5be5, 0x399a, + 0x5c12, 0x3984, 0x5c3f, 0x396e, 0x5c6c, 0x3958, 0x5c99, 0x3941, + 0x5cc6, 0x392b, 0x5cf3, 0x3914, 0x5d20, 0x38fd, 0x5d4d, 0x38e6, + 0x5d79, 0x38cf, 0x5da6, 0x38b8, 0x5dd3, 0x38a1, 0x5dff, 0x3889, + 0x5e2b, 0x3871, 0x5e58, 0x385a, 0x5e84, 0x3842, 0x5eb0, 0x382a, + 0x5edc, 0x3812, 0x5f08, 0x37f9, 0x5f34, 0x37e1, 0x5f60, 0x37c8, + 0x5f8c, 0x37b0, 0x5fb7, 0x3797, 0x5fe3, 0x377e, 0x600f, 0x3765, + 0x603a, 0x374b, 0x6065, 0x3732, 0x6091, 0x3718, 0x60bc, 0x36ff, + 0x60e7, 0x36e5, 0x6112, 0x36cb, 0x613d, 0x36b1, 0x6168, 0x3697, + 0x6193, 0x367d, 0x61be, 0x3662, 0x61e8, 0x3648, 0x6213, 0x362d, + 0x623d, 0x3612, 0x6268, 0x35f7, 0x6292, 0x35dc, 0x62bc, 0x35c1, + 0x62e7, 0x35a5, 0x6311, 0x358a, 0x633b, 0x356e, 0x6365, 0x3553, + 0x638e, 0x3537, 0x63b8, 0x351b, 0x63e2, 0x34ff, 0x640b, 0x34e2, + 0x6435, 0x34c6, 0x645e, 0x34aa, 0x6488, 0x348d, 0x64b1, 0x3470, + 0x64da, 0x3453, 0x6503, 0x3436, 0x652c, 0x3419, 0x6555, 0x33fc, + 0x657e, 0x33df, 0x65a6, 0x33c1, 0x65cf, 0x33a3, 0x65f8, 0x3386, + 0x6620, 0x3368, 0x6648, 0x334a, 0x6671, 0x332c, 0x6699, 0x330d, + 0x66c1, 0x32ef, 0x66e9, 0x32d0, 0x6711, 0x32b2, 0x6738, 0x3293, + 0x6760, 0x3274, 0x6788, 0x3255, 0x67af, 0x3236, 0x67d6, 0x3217, + 0x67fe, 0x31f8, 0x6825, 0x31d8, 0x684c, 0x31b9, 0x6873, 0x3199, + 0x689a, 0x3179, 0x68c1, 0x3159, 0x68e7, 0x3139, 0x690e, 0x3119, + 0x6935, 0x30f9, 0x695b, 0x30d8, 0x6981, 0x30b8, 0x69a7, 0x3097, + 0x69ce, 0x3076, 0x69f4, 0x3055, 0x6a1a, 0x3034, 0x6a3f, 0x3013, + 0x6a65, 0x2ff2, 0x6a8b, 0x2fd0, 0x6ab0, 0x2faf, 0x6ad6, 0x2f8d, + 0x6afb, 0x2f6c, 0x6b20, 0x2f4a, 0x6b45, 0x2f28, 0x6b6a, 0x2f06, + 0x6b8f, 0x2ee4, 0x6bb4, 0x2ec2, 0x6bd8, 0x2e9f, 0x6bfd, 0x2e7d, + 0x6c21, 0x2e5a, 0x6c46, 0x2e37, 0x6c6a, 0x2e15, 0x6c8e, 0x2df2, + 0x6cb2, 0x2dcf, 0x6cd6, 0x2dab, 0x6cfa, 0x2d88, 0x6d1e, 0x2d65, + 0x6d41, 0x2d41, 0x6d65, 0x2d1e, 0x6d88, 0x2cfa, 0x6dab, 0x2cd6, + 0x6dcf, 0x2cb2, 0x6df2, 0x2c8e, 0x6e15, 0x2c6a, 0x6e37, 0x2c46, + 0x6e5a, 0x2c21, 0x6e7d, 0x2bfd, 0x6e9f, 0x2bd8, 0x6ec2, 0x2bb4, + 0x6ee4, 0x2b8f, 0x6f06, 0x2b6a, 0x6f28, 0x2b45, 0x6f4a, 0x2b20, + 0x6f6c, 0x2afb, 0x6f8d, 0x2ad6, 0x6faf, 0x2ab0, 0x6fd0, 0x2a8b, + 0x6ff2, 0x2a65, 0x7013, 0x2a3f, 0x7034, 0x2a1a, 0x7055, 0x29f4, + 0x7076, 0x29ce, 0x7097, 0x29a7, 0x70b8, 0x2981, 0x70d8, 0x295b, + 0x70f9, 0x2935, 0x7119, 0x290e, 0x7139, 0x28e7, 0x7159, 0x28c1, + 0x7179, 0x289a, 0x7199, 0x2873, 0x71b9, 0x284c, 0x71d8, 0x2825, + 0x71f8, 0x27fe, 0x7217, 0x27d6, 0x7236, 0x27af, 0x7255, 0x2788, + 0x7274, 0x2760, 0x7293, 0x2738, 0x72b2, 0x2711, 0x72d0, 0x26e9, + 0x72ef, 0x26c1, 0x730d, 0x2699, 0x732c, 0x2671, 0x734a, 0x2648, + 0x7368, 0x2620, 0x7386, 0x25f8, 0x73a3, 0x25cf, 0x73c1, 0x25a6, + 0x73df, 0x257e, 0x73fc, 0x2555, 0x7419, 0x252c, 0x7436, 0x2503, + 0x7453, 0x24da, 0x7470, 0x24b1, 0x748d, 0x2488, 0x74aa, 0x245e, + 0x74c6, 0x2435, 0x74e2, 0x240b, 0x74ff, 0x23e2, 0x751b, 0x23b8, + 0x7537, 0x238e, 0x7553, 0x2365, 0x756e, 0x233b, 0x758a, 0x2311, + 0x75a5, 0x22e7, 0x75c1, 0x22bc, 0x75dc, 0x2292, 0x75f7, 0x2268, + 0x7612, 0x223d, 0x762d, 0x2213, 0x7648, 0x21e8, 0x7662, 0x21be, + 0x767d, 0x2193, 0x7697, 0x2168, 0x76b1, 0x213d, 0x76cb, 0x2112, + 0x76e5, 0x20e7, 0x76ff, 0x20bc, 0x7718, 0x2091, 0x7732, 0x2065, + 0x774b, 0x203a, 0x7765, 0x200f, 0x777e, 0x1fe3, 0x7797, 0x1fb7, + 0x77b0, 0x1f8c, 0x77c8, 0x1f60, 0x77e1, 0x1f34, 0x77f9, 0x1f08, + 0x7812, 0x1edc, 0x782a, 0x1eb0, 0x7842, 0x1e84, 0x785a, 0x1e58, + 0x7871, 0x1e2b, 0x7889, 0x1dff, 0x78a1, 0x1dd3, 0x78b8, 0x1da6, + 0x78cf, 0x1d79, 0x78e6, 0x1d4d, 0x78fd, 0x1d20, 0x7914, 0x1cf3, + 0x792b, 0x1cc6, 0x7941, 0x1c99, 0x7958, 0x1c6c, 0x796e, 0x1c3f, + 0x7984, 0x1c12, 0x799a, 0x1be5, 0x79b0, 0x1bb8, 0x79c5, 0x1b8a, + 0x79db, 0x1b5d, 0x79f0, 0x1b30, 0x7a06, 0x1b02, 0x7a1b, 0x1ad4, + 0x7a30, 0x1aa7, 0x7a45, 0x1a79, 0x7a59, 0x1a4b, 0x7a6e, 0x1a1d, + 0x7a82, 0x19ef, 0x7a97, 0x19c1, 0x7aab, 0x1993, 0x7abf, 0x1965, + 0x7ad3, 0x1937, 0x7ae6, 0x1909, 0x7afa, 0x18db, 0x7b0e, 0x18ac, + 0x7b21, 0x187e, 0x7b34, 0x184f, 0x7b47, 0x1821, 0x7b5a, 0x17f2, + 0x7b6d, 0x17c4, 0x7b7f, 0x1795, 0x7b92, 0x1766, 0x7ba4, 0x1737, + 0x7bb6, 0x1709, 0x7bc8, 0x16da, 0x7bda, 0x16ab, 0x7bec, 0x167c, + 0x7bfd, 0x164c, 0x7c0f, 0x161d, 0x7c20, 0x15ee, 0x7c31, 0x15bf, + 0x7c42, 0x1590, 0x7c53, 0x1560, 0x7c64, 0x1531, 0x7c74, 0x1501, + 0x7c85, 0x14d2, 0x7c95, 0x14a2, 0x7ca5, 0x1473, 0x7cb5, 0x1443, + 0x7cc5, 0x1413, 0x7cd5, 0x13e4, 0x7ce4, 0x13b4, 0x7cf4, 0x1384, + 0x7d03, 0x1354, 0x7d12, 0x1324, 0x7d21, 0x12f4, 0x7d30, 0x12c4, + 0x7d3f, 0x1294, 0x7d4d, 0x1264, 0x7d5b, 0x1234, 0x7d6a, 0x1204, + 0x7d78, 0x11d3, 0x7d86, 0x11a3, 0x7d93, 0x1173, 0x7da1, 0x1142, + 0x7daf, 0x1112, 0x7dbc, 0x10e1, 0x7dc9, 0x10b1, 0x7dd6, 0x1080, + 0x7de3, 0x1050, 0x7df0, 0x101f, 0x7dfc, 0xfee, 0x7e09, 0xfbe, + 0x7e15, 0xf8d, 0x7e21, 0xf5c, 0x7e2d, 0xf2b, 0x7e39, 0xefb, + 0x7e45, 0xeca, 0x7e50, 0xe99, 0x7e5c, 0xe68, 0x7e67, 0xe37, + 0x7e72, 0xe06, 0x7e7d, 0xdd5, 0x7e88, 0xda4, 0x7e92, 0xd72, + 0x7e9d, 0xd41, 0x7ea7, 0xd10, 0x7eb1, 0xcdf, 0x7ebb, 0xcae, + 0x7ec5, 0xc7c, 0x7ecf, 0xc4b, 0x7ed8, 0xc1a, 0x7ee2, 0xbe8, + 0x7eeb, 0xbb7, 0x7ef4, 0xb85, 0x7efd, 0xb54, 0x7f06, 0xb23, + 0x7f0f, 0xaf1, 0x7f17, 0xac0, 0x7f20, 0xa8e, 0x7f28, 0xa5c, + 0x7f30, 0xa2b, 0x7f38, 0x9f9, 0x7f40, 0x9c7, 0x7f47, 0x996, + 0x7f4f, 0x964, 0x7f56, 0x932, 0x7f5d, 0x901, 0x7f64, 0x8cf, + 0x7f6b, 0x89d, 0x7f72, 0x86b, 0x7f78, 0x839, 0x7f7f, 0x807, + 0x7f85, 0x7d6, 0x7f8b, 0x7a4, 0x7f91, 0x772, 0x7f97, 0x740, + 0x7f9c, 0x70e, 0x7fa2, 0x6dc, 0x7fa7, 0x6aa, 0x7fac, 0x678, + 0x7fb1, 0x646, 0x7fb6, 0x614, 0x7fbb, 0x5e2, 0x7fbf, 0x5b0, + 0x7fc4, 0x57e, 0x7fc8, 0x54c, 0x7fcc, 0x51a, 0x7fd0, 0x4e7, + 0x7fd4, 0x4b5, 0x7fd7, 0x483, 0x7fdb, 0x451, 0x7fde, 0x41f, + 0x7fe1, 0x3ed, 0x7fe4, 0x3bb, 0x7fe7, 0x388, 0x7fea, 0x356, + 0x7fec, 0x324, 0x7fef, 0x2f2, 0x7ff1, 0x2c0, 0x7ff3, 0x28d, + 0x7ff5, 0x25b, 0x7ff7, 0x229, 0x7ff8, 0x1f7, 0x7ffa, 0x1c4, + 0x7ffb, 0x192, 0x7ffc, 0x160, 0x7ffd, 0x12e, 0x7ffe, 0xfb, + 0x7fff, 0xc9, 0x7fff, 0x97, 0x7fff, 0x65, 0x7fff, 0x32, + 0x7fff, 0x0, 0x7fff, 0xffce, 0x7fff, 0xff9b, 0x7fff, 0xff69, + 0x7fff, 0xff37, 0x7ffe, 0xff05, 0x7ffd, 0xfed2, 0x7ffc, 0xfea0, + 0x7ffb, 0xfe6e, 0x7ffa, 0xfe3c, 0x7ff8, 0xfe09, 0x7ff7, 0xfdd7, + 0x7ff5, 0xfda5, 0x7ff3, 0xfd73, 0x7ff1, 0xfd40, 0x7fef, 0xfd0e, + 0x7fec, 0xfcdc, 0x7fea, 0xfcaa, 0x7fe7, 0xfc78, 0x7fe4, 0xfc45, + 0x7fe1, 0xfc13, 0x7fde, 0xfbe1, 0x7fdb, 0xfbaf, 0x7fd7, 0xfb7d, + 0x7fd4, 0xfb4b, 0x7fd0, 0xfb19, 0x7fcc, 0xfae6, 0x7fc8, 0xfab4, + 0x7fc4, 0xfa82, 0x7fbf, 0xfa50, 0x7fbb, 0xfa1e, 0x7fb6, 0xf9ec, + 0x7fb1, 0xf9ba, 0x7fac, 0xf988, 0x7fa7, 0xf956, 0x7fa2, 0xf924, + 0x7f9c, 0xf8f2, 0x7f97, 0xf8c0, 0x7f91, 0xf88e, 0x7f8b, 0xf85c, + 0x7f85, 0xf82a, 0x7f7f, 0xf7f9, 0x7f78, 0xf7c7, 0x7f72, 0xf795, + 0x7f6b, 0xf763, 0x7f64, 0xf731, 0x7f5d, 0xf6ff, 0x7f56, 0xf6ce, + 0x7f4f, 0xf69c, 0x7f47, 0xf66a, 0x7f40, 0xf639, 0x7f38, 0xf607, + 0x7f30, 0xf5d5, 0x7f28, 0xf5a4, 0x7f20, 0xf572, 0x7f17, 0xf540, + 0x7f0f, 0xf50f, 0x7f06, 0xf4dd, 0x7efd, 0xf4ac, 0x7ef4, 0xf47b, + 0x7eeb, 0xf449, 0x7ee2, 0xf418, 0x7ed8, 0xf3e6, 0x7ecf, 0xf3b5, + 0x7ec5, 0xf384, 0x7ebb, 0xf352, 0x7eb1, 0xf321, 0x7ea7, 0xf2f0, + 0x7e9d, 0xf2bf, 0x7e92, 0xf28e, 0x7e88, 0xf25c, 0x7e7d, 0xf22b, + 0x7e72, 0xf1fa, 0x7e67, 0xf1c9, 0x7e5c, 0xf198, 0x7e50, 0xf167, + 0x7e45, 0xf136, 0x7e39, 0xf105, 0x7e2d, 0xf0d5, 0x7e21, 0xf0a4, + 0x7e15, 0xf073, 0x7e09, 0xf042, 0x7dfc, 0xf012, 0x7df0, 0xefe1, + 0x7de3, 0xefb0, 0x7dd6, 0xef80, 0x7dc9, 0xef4f, 0x7dbc, 0xef1f, + 0x7daf, 0xeeee, 0x7da1, 0xeebe, 0x7d93, 0xee8d, 0x7d86, 0xee5d, + 0x7d78, 0xee2d, 0x7d6a, 0xedfc, 0x7d5b, 0xedcc, 0x7d4d, 0xed9c, + 0x7d3f, 0xed6c, 0x7d30, 0xed3c, 0x7d21, 0xed0c, 0x7d12, 0xecdc, + 0x7d03, 0xecac, 0x7cf4, 0xec7c, 0x7ce4, 0xec4c, 0x7cd5, 0xec1c, + 0x7cc5, 0xebed, 0x7cb5, 0xebbd, 0x7ca5, 0xeb8d, 0x7c95, 0xeb5e, + 0x7c85, 0xeb2e, 0x7c74, 0xeaff, 0x7c64, 0xeacf, 0x7c53, 0xeaa0, + 0x7c42, 0xea70, 0x7c31, 0xea41, 0x7c20, 0xea12, 0x7c0f, 0xe9e3, + 0x7bfd, 0xe9b4, 0x7bec, 0xe984, 0x7bda, 0xe955, 0x7bc8, 0xe926, + 0x7bb6, 0xe8f7, 0x7ba4, 0xe8c9, 0x7b92, 0xe89a, 0x7b7f, 0xe86b, + 0x7b6d, 0xe83c, 0x7b5a, 0xe80e, 0x7b47, 0xe7df, 0x7b34, 0xe7b1, + 0x7b21, 0xe782, 0x7b0e, 0xe754, 0x7afa, 0xe725, 0x7ae6, 0xe6f7, + 0x7ad3, 0xe6c9, 0x7abf, 0xe69b, 0x7aab, 0xe66d, 0x7a97, 0xe63f, + 0x7a82, 0xe611, 0x7a6e, 0xe5e3, 0x7a59, 0xe5b5, 0x7a45, 0xe587, + 0x7a30, 0xe559, 0x7a1b, 0xe52c, 0x7a06, 0xe4fe, 0x79f0, 0xe4d0, + 0x79db, 0xe4a3, 0x79c5, 0xe476, 0x79b0, 0xe448, 0x799a, 0xe41b, + 0x7984, 0xe3ee, 0x796e, 0xe3c1, 0x7958, 0xe394, 0x7941, 0xe367, + 0x792b, 0xe33a, 0x7914, 0xe30d, 0x78fd, 0xe2e0, 0x78e6, 0xe2b3, + 0x78cf, 0xe287, 0x78b8, 0xe25a, 0x78a1, 0xe22d, 0x7889, 0xe201, + 0x7871, 0xe1d5, 0x785a, 0xe1a8, 0x7842, 0xe17c, 0x782a, 0xe150, + 0x7812, 0xe124, 0x77f9, 0xe0f8, 0x77e1, 0xe0cc, 0x77c8, 0xe0a0, + 0x77b0, 0xe074, 0x7797, 0xe049, 0x777e, 0xe01d, 0x7765, 0xdff1, + 0x774b, 0xdfc6, 0x7732, 0xdf9b, 0x7718, 0xdf6f, 0x76ff, 0xdf44, + 0x76e5, 0xdf19, 0x76cb, 0xdeee, 0x76b1, 0xdec3, 0x7697, 0xde98, + 0x767d, 0xde6d, 0x7662, 0xde42, 0x7648, 0xde18, 0x762d, 0xdded, + 0x7612, 0xddc3, 0x75f7, 0xdd98, 0x75dc, 0xdd6e, 0x75c1, 0xdd44, + 0x75a5, 0xdd19, 0x758a, 0xdcef, 0x756e, 0xdcc5, 0x7553, 0xdc9b, + 0x7537, 0xdc72, 0x751b, 0xdc48, 0x74ff, 0xdc1e, 0x74e2, 0xdbf5, + 0x74c6, 0xdbcb, 0x74aa, 0xdba2, 0x748d, 0xdb78, 0x7470, 0xdb4f, + 0x7453, 0xdb26, 0x7436, 0xdafd, 0x7419, 0xdad4, 0x73fc, 0xdaab, + 0x73df, 0xda82, 0x73c1, 0xda5a, 0x73a3, 0xda31, 0x7386, 0xda08, + 0x7368, 0xd9e0, 0x734a, 0xd9b8, 0x732c, 0xd98f, 0x730d, 0xd967, + 0x72ef, 0xd93f, 0x72d0, 0xd917, 0x72b2, 0xd8ef, 0x7293, 0xd8c8, + 0x7274, 0xd8a0, 0x7255, 0xd878, 0x7236, 0xd851, 0x7217, 0xd82a, + 0x71f8, 0xd802, 0x71d8, 0xd7db, 0x71b9, 0xd7b4, 0x7199, 0xd78d, + 0x7179, 0xd766, 0x7159, 0xd73f, 0x7139, 0xd719, 0x7119, 0xd6f2, + 0x70f9, 0xd6cb, 0x70d8, 0xd6a5, 0x70b8, 0xd67f, 0x7097, 0xd659, + 0x7076, 0xd632, 0x7055, 0xd60c, 0x7034, 0xd5e6, 0x7013, 0xd5c1, + 0x6ff2, 0xd59b, 0x6fd0, 0xd575, 0x6faf, 0xd550, 0x6f8d, 0xd52a, + 0x6f6c, 0xd505, 0x6f4a, 0xd4e0, 0x6f28, 0xd4bb, 0x6f06, 0xd496, + 0x6ee4, 0xd471, 0x6ec2, 0xd44c, 0x6e9f, 0xd428, 0x6e7d, 0xd403, + 0x6e5a, 0xd3df, 0x6e37, 0xd3ba, 0x6e15, 0xd396, 0x6df2, 0xd372, + 0x6dcf, 0xd34e, 0x6dab, 0xd32a, 0x6d88, 0xd306, 0x6d65, 0xd2e2, + 0x6d41, 0xd2bf, 0x6d1e, 0xd29b, 0x6cfa, 0xd278, 0x6cd6, 0xd255, + 0x6cb2, 0xd231, 0x6c8e, 0xd20e, 0x6c6a, 0xd1eb, 0x6c46, 0xd1c9, + 0x6c21, 0xd1a6, 0x6bfd, 0xd183, 0x6bd8, 0xd161, 0x6bb4, 0xd13e, + 0x6b8f, 0xd11c, 0x6b6a, 0xd0fa, 0x6b45, 0xd0d8, 0x6b20, 0xd0b6, + 0x6afb, 0xd094, 0x6ad6, 0xd073, 0x6ab0, 0xd051, 0x6a8b, 0xd030, + 0x6a65, 0xd00e, 0x6a3f, 0xcfed, 0x6a1a, 0xcfcc, 0x69f4, 0xcfab, + 0x69ce, 0xcf8a, 0x69a7, 0xcf69, 0x6981, 0xcf48, 0x695b, 0xcf28, + 0x6935, 0xcf07, 0x690e, 0xcee7, 0x68e7, 0xcec7, 0x68c1, 0xcea7, + 0x689a, 0xce87, 0x6873, 0xce67, 0x684c, 0xce47, 0x6825, 0xce28, + 0x67fe, 0xce08, 0x67d6, 0xcde9, 0x67af, 0xcdca, 0x6788, 0xcdab, + 0x6760, 0xcd8c, 0x6738, 0xcd6d, 0x6711, 0xcd4e, 0x66e9, 0xcd30, + 0x66c1, 0xcd11, 0x6699, 0xccf3, 0x6671, 0xccd4, 0x6648, 0xccb6, + 0x6620, 0xcc98, 0x65f8, 0xcc7a, 0x65cf, 0xcc5d, 0x65a6, 0xcc3f, + 0x657e, 0xcc21, 0x6555, 0xcc04, 0x652c, 0xcbe7, 0x6503, 0xcbca, + 0x64da, 0xcbad, 0x64b1, 0xcb90, 0x6488, 0xcb73, 0x645e, 0xcb56, + 0x6435, 0xcb3a, 0x640b, 0xcb1e, 0x63e2, 0xcb01, 0x63b8, 0xcae5, + 0x638e, 0xcac9, 0x6365, 0xcaad, 0x633b, 0xca92, 0x6311, 0xca76, + 0x62e7, 0xca5b, 0x62bc, 0xca3f, 0x6292, 0xca24, 0x6268, 0xca09, + 0x623d, 0xc9ee, 0x6213, 0xc9d3, 0x61e8, 0xc9b8, 0x61be, 0xc99e, + 0x6193, 0xc983, 0x6168, 0xc969, 0x613d, 0xc94f, 0x6112, 0xc935, + 0x60e7, 0xc91b, 0x60bc, 0xc901, 0x6091, 0xc8e8, 0x6065, 0xc8ce, + 0x603a, 0xc8b5, 0x600f, 0xc89b, 0x5fe3, 0xc882, 0x5fb7, 0xc869, + 0x5f8c, 0xc850, 0x5f60, 0xc838, 0x5f34, 0xc81f, 0x5f08, 0xc807, + 0x5edc, 0xc7ee, 0x5eb0, 0xc7d6, 0x5e84, 0xc7be, 0x5e58, 0xc7a6, + 0x5e2b, 0xc78f, 0x5dff, 0xc777, 0x5dd3, 0xc75f, 0x5da6, 0xc748, + 0x5d79, 0xc731, 0x5d4d, 0xc71a, 0x5d20, 0xc703, 0x5cf3, 0xc6ec, + 0x5cc6, 0xc6d5, 0x5c99, 0xc6bf, 0x5c6c, 0xc6a8, 0x5c3f, 0xc692, + 0x5c12, 0xc67c, 0x5be5, 0xc666, 0x5bb8, 0xc650, 0x5b8a, 0xc63b, + 0x5b5d, 0xc625, 0x5b30, 0xc610, 0x5b02, 0xc5fa, 0x5ad4, 0xc5e5, + 0x5aa7, 0xc5d0, 0x5a79, 0xc5bb, 0x5a4b, 0xc5a7, 0x5a1d, 0xc592, + 0x59ef, 0xc57e, 0x59c1, 0xc569, 0x5993, 0xc555, 0x5965, 0xc541, + 0x5937, 0xc52d, 0x5909, 0xc51a, 0x58db, 0xc506, 0x58ac, 0xc4f2, + 0x587e, 0xc4df, 0x584f, 0xc4cc, 0x5821, 0xc4b9, 0x57f2, 0xc4a6, + 0x57c4, 0xc493, 0x5795, 0xc481, 0x5766, 0xc46e, 0x5737, 0xc45c, + 0x5709, 0xc44a, 0x56da, 0xc438, 0x56ab, 0xc426, 0x567c, 0xc414, + 0x564c, 0xc403, 0x561d, 0xc3f1, 0x55ee, 0xc3e0, 0x55bf, 0xc3cf, + 0x5590, 0xc3be, 0x5560, 0xc3ad, 0x5531, 0xc39c, 0x5501, 0xc38c, + 0x54d2, 0xc37b, 0x54a2, 0xc36b, 0x5473, 0xc35b, 0x5443, 0xc34b, + 0x5413, 0xc33b, 0x53e4, 0xc32b, 0x53b4, 0xc31c, 0x5384, 0xc30c, + 0x5354, 0xc2fd, 0x5324, 0xc2ee, 0x52f4, 0xc2df, 0x52c4, 0xc2d0, + 0x5294, 0xc2c1, 0x5264, 0xc2b3, 0x5234, 0xc2a5, 0x5204, 0xc296, + 0x51d3, 0xc288, 0x51a3, 0xc27a, 0x5173, 0xc26d, 0x5142, 0xc25f, + 0x5112, 0xc251, 0x50e1, 0xc244, 0x50b1, 0xc237, 0x5080, 0xc22a, + 0x5050, 0xc21d, 0x501f, 0xc210, 0x4fee, 0xc204, 0x4fbe, 0xc1f7, + 0x4f8d, 0xc1eb, 0x4f5c, 0xc1df, 0x4f2b, 0xc1d3, 0x4efb, 0xc1c7, + 0x4eca, 0xc1bb, 0x4e99, 0xc1b0, 0x4e68, 0xc1a4, 0x4e37, 0xc199, + 0x4e06, 0xc18e, 0x4dd5, 0xc183, 0x4da4, 0xc178, 0x4d72, 0xc16e, + 0x4d41, 0xc163, 0x4d10, 0xc159, 0x4cdf, 0xc14f, 0x4cae, 0xc145, + 0x4c7c, 0xc13b, 0x4c4b, 0xc131, 0x4c1a, 0xc128, 0x4be8, 0xc11e, + 0x4bb7, 0xc115, 0x4b85, 0xc10c, 0x4b54, 0xc103, 0x4b23, 0xc0fa, + 0x4af1, 0xc0f1, 0x4ac0, 0xc0e9, 0x4a8e, 0xc0e0, 0x4a5c, 0xc0d8, + 0x4a2b, 0xc0d0, 0x49f9, 0xc0c8, 0x49c7, 0xc0c0, 0x4996, 0xc0b9, + 0x4964, 0xc0b1, 0x4932, 0xc0aa, 0x4901, 0xc0a3, 0x48cf, 0xc09c, + 0x489d, 0xc095, 0x486b, 0xc08e, 0x4839, 0xc088, 0x4807, 0xc081, + 0x47d6, 0xc07b, 0x47a4, 0xc075, 0x4772, 0xc06f, 0x4740, 0xc069, + 0x470e, 0xc064, 0x46dc, 0xc05e, 0x46aa, 0xc059, 0x4678, 0xc054, + 0x4646, 0xc04f, 0x4614, 0xc04a, 0x45e2, 0xc045, 0x45b0, 0xc041, + 0x457e, 0xc03c, 0x454c, 0xc038, 0x451a, 0xc034, 0x44e7, 0xc030, + 0x44b5, 0xc02c, 0x4483, 0xc029, 0x4451, 0xc025, 0x441f, 0xc022, + 0x43ed, 0xc01f, 0x43bb, 0xc01c, 0x4388, 0xc019, 0x4356, 0xc016, + 0x4324, 0xc014, 0x42f2, 0xc011, 0x42c0, 0xc00f, 0x428d, 0xc00d, + 0x425b, 0xc00b, 0x4229, 0xc009, 0x41f7, 0xc008, 0x41c4, 0xc006, + 0x4192, 0xc005, 0x4160, 0xc004, 0x412e, 0xc003, 0x40fb, 0xc002, + 0x40c9, 0xc001, 0x4097, 0xc001, 0x4065, 0xc000, 0x4032, 0xc000 +}; + +/** +* @brief Initialization function for the Q15 RFFT/RIFFT. +* @param[in, out] *S points to an instance of the Q15 RFFT/RIFFT structure. +* @param[in] *S_CFFT points to an instance of the Q15 CFFT/CIFFT structure. +* @param[in] fftLenReal length of the FFT. +* @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. +* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. +* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. +* +* \par Description: +* \par +* The parameter fftLenReal Specifies length of RFFT/RIFFT Process. Supported FFT Lengths are 128, 512, 2048. +* \par +* The parameter ifftFlagR controls whether a forward or inverse transform is computed. +* Set(=1) ifftFlagR to calculate RIFFT, otherwise RFFT is calculated. +* \par +* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. +* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. +* \par +* This function also initializes Twiddle factor table. +*/ + +arm_status arm_rfft_init_q15( + arm_rfft_instance_q15 * S, + arm_cfft_radix4_instance_q15 * S_CFFT, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag) +{ + + /* Initialise the default arm status */ + arm_status status = ARM_MATH_SUCCESS; + + /* Initialize the Real FFT length */ + S->fftLenReal = (uint16_t) fftLenReal; + + /* Initialize the Complex FFT length */ + S->fftLenBy2 = (uint16_t) fftLenReal / 2u; + + /* Initialize the Twiddle coefficientA pointer */ + S->pTwiddleAReal = (q15_t *) realCoefAQ15; + + /* Initialize the Twiddle coefficientB pointer */ + S->pTwiddleBReal = (q15_t *) realCoefBQ15; + + /* Initialize the Flag for selection of RFFT or RIFFT */ + S->ifftFlagR = (uint8_t) ifftFlagR; + + /* Initialize the Flag for calculation Bit reversal or not */ + S->bitReverseFlagR = (uint8_t) bitReverseFlag; + + /* Initialization of coef modifier depending on the FFT length */ + switch (S->fftLenReal) + { + case 2048u: + S->twidCoefRModifier = 1u; + break; + case 512u: + S->twidCoefRModifier = 4u; + break; + case 128u: + S->twidCoefRModifier = 16u; + break; + default: + /* Reporting argument error if rfftSize is not valid value */ + status = ARM_MATH_ARGUMENT_ERROR; + break; + } + + /* Init Complex FFT Instance */ + S->pCfft = S_CFFT; + + if(S->ifftFlagR) + { + /* Initializes the CIFFT Module for fftLenreal/2 length */ + arm_cfft_radix4_init_q15(S->pCfft, S->fftLenBy2, 1u, 1u); + } + else + { + /* Initializes the CFFT Module for fftLenreal/2 length */ + arm_cfft_radix4_init_q15(S->pCfft, S->fftLenBy2, 0u, 1u); + } + + /* return the status of RFFT Init function */ + return (status); + +} + + /** + * @} end of RFFT_RIFFT group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q31.c index 94d0c1d59..cabb994c2 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q31.c @@ -1,681 +1,681 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_init_q31.c -* -* Description: RFFT & RIFFT Q31 initialisation function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - -/** -* \par -* Generation floating point realCoefAQ31 array: -* \par -* n = 1024 -*
for (i = 0; i < n; i++)   
-* {   
-*    pATable[2 * i] = 0.5 * (1.0 - sin (2 * PI / (double) (2 * n) * (double) i));   
-*    pATable[2 * i + 1] = 0.5 * (-1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
-* }
-* \par -* Convert to fixed point Q31 format -* round(pATable[i] * pow(2, 31)) -*/ - - -const q31_t realCoefAQ31[1024] = { - 0x40000000, 0xc0000000, 0x3f9b783c, 0xc0004ef5, - 0x3f36f170, 0xc0013bd3, 0x3ed26c94, 0xc002c697, - 0x3e6deaa1, 0xc004ef3f, 0x3e096c8d, 0xc007b5c4, - 0x3da4f351, 0xc00b1a20, 0x3d407fe6, 0xc00f1c4a, - 0x3cdc1342, 0xc013bc39, 0x3c77ae5e, 0xc018f9e1, - 0x3c135231, 0xc01ed535, 0x3baeffb3, 0xc0254e27, - 0x3b4ab7db, 0xc02c64a6, 0x3ae67ba2, 0xc03418a2, - 0x3a824bfd, 0xc03c6a07, 0x3a1e29e5, 0xc04558c0, - 0x39ba1651, 0xc04ee4b8, 0x39561237, 0xc0590dd8, - 0x38f21e8e, 0xc063d405, 0x388e3c4d, 0xc06f3726, - 0x382a6c6a, 0xc07b371e, 0x37c6afdc, 0xc087d3d0, - 0x37630799, 0xc0950d1d, 0x36ff7496, 0xc0a2e2e3, - 0x369bf7c9, 0xc0b15502, 0x36389228, 0xc0c06355, - 0x35d544a7, 0xc0d00db6, 0x3572103d, 0xc0e05401, - 0x350ef5de, 0xc0f1360b, 0x34abf67e, 0xc102b3ac, - 0x34491311, 0xc114ccb9, 0x33e64c8c, 0xc1278104, - 0x3383a3e2, 0xc13ad060, 0x33211a07, 0xc14eba9d, - 0x32beafed, 0xc1633f8a, 0x325c6688, 0xc1785ef4, - 0x31fa3ecb, 0xc18e18a7, 0x319839a6, 0xc1a46c6e, - 0x3136580d, 0xc1bb5a11, 0x30d49af1, 0xc1d2e158, - 0x30730342, 0xc1eb0209, 0x301191f3, 0xc203bbe8, - 0x2fb047f2, 0xc21d0eb8, 0x2f4f2630, 0xc236fa3b, - 0x2eee2d9d, 0xc2517e31, 0x2e8d5f29, 0xc26c9a58, - 0x2e2cbbc1, 0xc2884e6e, 0x2dcc4454, 0xc2a49a2e, - 0x2d6bf9d1, 0xc2c17d52, 0x2d0bdd25, 0xc2def794, - 0x2cabef3d, 0xc2fd08a9, 0x2c4c3106, 0xc31bb049, - 0x2beca36c, 0xc33aee27, 0x2b8d475b, 0xc35ac1f7, - 0x2b2e1dbe, 0xc37b2b6a, 0x2acf277f, 0xc39c2a2f, - 0x2a70658a, 0xc3bdbdf6, 0x2a11d8c8, 0xc3dfe66c, - 0x29b38223, 0xc402a33c, 0x29556282, 0xc425f410, - 0x28f77acf, 0xc449d892, 0x2899cbf1, 0xc46e5069, - 0x283c56cf, 0xc4935b3c, 0x27df1c50, 0xc4b8f8ad, - 0x27821d59, 0xc4df2862, 0x27255ad1, 0xc505e9fb, - 0x26c8d59c, 0xc52d3d18, 0x266c8e9f, 0xc555215a, - 0x261086bc, 0xc57d965d, 0x25b4bed8, 0xc5a69bbe, - 0x255937d5, 0xc5d03118, 0x24fdf294, 0xc5fa5603, - 0x24a2eff6, 0xc6250a18, 0x244830dd, 0xc6504ced, - 0x23edb628, 0xc67c1e18, 0x239380b6, 0xc6a87d2d, - 0x23399167, 0xc6d569be, 0x22dfe917, 0xc702e35c, - 0x228688a4, 0xc730e997, 0x222d70eb, 0xc75f7bfe, - 0x21d4a2c8, 0xc78e9a1d, 0x217c1f15, 0xc7be4381, - 0x2123e6ad, 0xc7ee77b3, 0x20cbfa6a, 0xc81f363d, - 0x20745b24, 0xc8507ea7, 0x201d09b4, 0xc8825077, - 0x1fc606f1, 0xc8b4ab32, 0x1f6f53b3, 0xc8e78e5b, - 0x1f18f0ce, 0xc91af976, 0x1ec2df18, 0xc94eec03, - 0x1e6d1f65, 0xc9836582, 0x1e17b28a, 0xc9b86572, - 0x1dc29958, 0xc9edeb50, 0x1d6dd4a2, 0xca23f698, - 0x1d196538, 0xca5a86c4, 0x1cc54bec, 0xca919b4e, - 0x1c71898d, 0xcac933ae, 0x1c1e1ee9, 0xcb014f5b, - 0x1bcb0cce, 0xcb39edca, 0x1b785409, 0xcb730e70, - 0x1b25f566, 0xcbacb0bf, 0x1ad3f1b1, 0xcbe6d42b, - 0x1a8249b4, 0xcc217822, 0x1a30fe38, 0xcc5c9c14, - 0x19e01006, 0xcc983f70, 0x198f7fe6, 0xccd461a2, - 0x193f4e9e, 0xcd110216, 0x18ef7cf4, 0xcd4e2037, - 0x18a00bae, 0xcd8bbb6d, 0x1850fb8e, 0xcdc9d320, - 0x18024d59, 0xce0866b8, 0x17b401d1, 0xce47759a, - 0x176619b6, 0xce86ff2a, 0x171895c9, 0xcec702cb, - 0x16cb76c9, 0xcf077fe1, 0x167ebd74, 0xcf4875ca, - 0x16326a88, 0xcf89e3e8, 0x15e67ec1, 0xcfcbc999, - 0x159afadb, 0xd00e2639, 0x154fdf8f, 0xd050f926, - 0x15052d97, 0xd09441bb, 0x14bae5ab, 0xd0d7ff51, - 0x14710883, 0xd11c3142, 0x142796d5, 0xd160d6e5, - 0x13de9156, 0xd1a5ef90, 0x1395f8ba, 0xd1eb7a9a, - 0x134dcdb4, 0xd2317756, 0x130610f7, 0xd277e518, - 0x12bec333, 0xd2bec333, 0x1277e518, 0xd30610f7, - 0x12317756, 0xd34dcdb4, 0x11eb7a9a, 0xd395f8ba, - 0x11a5ef90, 0xd3de9156, 0x1160d6e5, 0xd42796d5, - 0x111c3142, 0xd4710883, 0x10d7ff51, 0xd4bae5ab, - 0x109441bb, 0xd5052d97, 0x1050f926, 0xd54fdf8f, - 0x100e2639, 0xd59afadb, 0xfcbc999, 0xd5e67ec1, - 0xf89e3e8, 0xd6326a88, 0xf4875ca, 0xd67ebd74, - 0xf077fe1, 0xd6cb76c9, 0xec702cb, 0xd71895c9, - 0xe86ff2a, 0xd76619b6, 0xe47759a, 0xd7b401d1, - 0xe0866b8, 0xd8024d59, 0xdc9d320, 0xd850fb8e, - 0xd8bbb6d, 0xd8a00bae, 0xd4e2037, 0xd8ef7cf4, - 0xd110216, 0xd93f4e9e, 0xcd461a2, 0xd98f7fe6, - 0xc983f70, 0xd9e01006, 0xc5c9c14, 0xda30fe38, - 0xc217822, 0xda8249b4, 0xbe6d42b, 0xdad3f1b1, - 0xbacb0bf, 0xdb25f566, 0xb730e70, 0xdb785409, - 0xb39edca, 0xdbcb0cce, 0xb014f5b, 0xdc1e1ee9, - 0xac933ae, 0xdc71898d, 0xa919b4e, 0xdcc54bec, - 0xa5a86c4, 0xdd196538, 0xa23f698, 0xdd6dd4a2, - 0x9edeb50, 0xddc29958, 0x9b86572, 0xde17b28a, - 0x9836582, 0xde6d1f65, 0x94eec03, 0xdec2df18, - 0x91af976, 0xdf18f0ce, 0x8e78e5b, 0xdf6f53b3, - 0x8b4ab32, 0xdfc606f1, 0x8825077, 0xe01d09b4, - 0x8507ea7, 0xe0745b24, 0x81f363d, 0xe0cbfa6a, - 0x7ee77b3, 0xe123e6ad, 0x7be4381, 0xe17c1f15, - 0x78e9a1d, 0xe1d4a2c8, 0x75f7bfe, 0xe22d70eb, - 0x730e997, 0xe28688a4, 0x702e35c, 0xe2dfe917, - 0x6d569be, 0xe3399167, 0x6a87d2d, 0xe39380b6, - 0x67c1e18, 0xe3edb628, 0x6504ced, 0xe44830dd, - 0x6250a18, 0xe4a2eff6, 0x5fa5603, 0xe4fdf294, - 0x5d03118, 0xe55937d5, 0x5a69bbe, 0xe5b4bed8, - 0x57d965d, 0xe61086bc, 0x555215a, 0xe66c8e9f, - 0x52d3d18, 0xe6c8d59c, 0x505e9fb, 0xe7255ad1, - 0x4df2862, 0xe7821d59, 0x4b8f8ad, 0xe7df1c50, - 0x4935b3c, 0xe83c56cf, 0x46e5069, 0xe899cbf1, - 0x449d892, 0xe8f77acf, 0x425f410, 0xe9556282, - 0x402a33c, 0xe9b38223, 0x3dfe66c, 0xea11d8c8, - 0x3bdbdf6, 0xea70658a, 0x39c2a2f, 0xeacf277f, - 0x37b2b6a, 0xeb2e1dbe, 0x35ac1f7, 0xeb8d475b, - 0x33aee27, 0xebeca36c, 0x31bb049, 0xec4c3106, - 0x2fd08a9, 0xecabef3d, 0x2def794, 0xed0bdd25, - 0x2c17d52, 0xed6bf9d1, 0x2a49a2e, 0xedcc4454, - 0x2884e6e, 0xee2cbbc1, 0x26c9a58, 0xee8d5f29, - 0x2517e31, 0xeeee2d9d, 0x236fa3b, 0xef4f2630, - 0x21d0eb8, 0xefb047f2, 0x203bbe8, 0xf01191f3, - 0x1eb0209, 0xf0730342, 0x1d2e158, 0xf0d49af1, - 0x1bb5a11, 0xf136580d, 0x1a46c6e, 0xf19839a6, - 0x18e18a7, 0xf1fa3ecb, 0x1785ef4, 0xf25c6688, - 0x1633f8a, 0xf2beafed, 0x14eba9d, 0xf3211a07, - 0x13ad060, 0xf383a3e2, 0x1278104, 0xf3e64c8c, - 0x114ccb9, 0xf4491311, 0x102b3ac, 0xf4abf67e, - 0xf1360b, 0xf50ef5de, 0xe05401, 0xf572103d, - 0xd00db6, 0xf5d544a7, 0xc06355, 0xf6389228, - 0xb15502, 0xf69bf7c9, 0xa2e2e3, 0xf6ff7496, - 0x950d1d, 0xf7630799, 0x87d3d0, 0xf7c6afdc, - 0x7b371e, 0xf82a6c6a, 0x6f3726, 0xf88e3c4d, - 0x63d405, 0xf8f21e8e, 0x590dd8, 0xf9561237, - 0x4ee4b8, 0xf9ba1651, 0x4558c0, 0xfa1e29e5, - 0x3c6a07, 0xfa824bfd, 0x3418a2, 0xfae67ba2, - 0x2c64a6, 0xfb4ab7db, 0x254e27, 0xfbaeffb3, - 0x1ed535, 0xfc135231, 0x18f9e1, 0xfc77ae5e, - 0x13bc39, 0xfcdc1342, 0xf1c4a, 0xfd407fe6, - 0xb1a20, 0xfda4f351, 0x7b5c4, 0xfe096c8d, - 0x4ef3f, 0xfe6deaa1, 0x2c697, 0xfed26c94, - 0x13bd3, 0xff36f170, 0x4ef5, 0xff9b783c, - 0x0, 0x0, 0x4ef5, 0x6487c4, - 0x13bd3, 0xc90e90, 0x2c697, 0x12d936c, - 0x4ef3f, 0x192155f, 0x7b5c4, 0x1f69373, - 0xb1a20, 0x25b0caf, 0xf1c4a, 0x2bf801a, - 0x13bc39, 0x323ecbe, 0x18f9e1, 0x38851a2, - 0x1ed535, 0x3ecadcf, 0x254e27, 0x451004d, - 0x2c64a6, 0x4b54825, 0x3418a2, 0x519845e, - 0x3c6a07, 0x57db403, 0x4558c0, 0x5e1d61b, - 0x4ee4b8, 0x645e9af, 0x590dd8, 0x6a9edc9, - 0x63d405, 0x70de172, 0x6f3726, 0x771c3b3, - 0x7b371e, 0x7d59396, 0x87d3d0, 0x8395024, - 0x950d1d, 0x89cf867, 0xa2e2e3, 0x9008b6a, - 0xb15502, 0x9640837, 0xc06355, 0x9c76dd8, - 0xd00db6, 0xa2abb59, 0xe05401, 0xa8defc3, - 0xf1360b, 0xaf10a22, 0x102b3ac, 0xb540982, - 0x114ccb9, 0xbb6ecef, 0x1278104, 0xc19b374, - 0x13ad060, 0xc7c5c1e, 0x14eba9d, 0xcdee5f9, - 0x1633f8a, 0xd415013, 0x1785ef4, 0xda39978, - 0x18e18a7, 0xe05c135, 0x1a46c6e, 0xe67c65a, - 0x1bb5a11, 0xec9a7f3, 0x1d2e158, 0xf2b650f, - 0x1eb0209, 0xf8cfcbe, 0x203bbe8, 0xfee6e0d, - 0x21d0eb8, 0x104fb80e, 0x236fa3b, 0x10b0d9d0, - 0x2517e31, 0x1111d263, 0x26c9a58, 0x1172a0d7, - 0x2884e6e, 0x11d3443f, 0x2a49a2e, 0x1233bbac, - 0x2c17d52, 0x1294062f, 0x2def794, 0x12f422db, - 0x2fd08a9, 0x135410c3, 0x31bb049, 0x13b3cefa, - 0x33aee27, 0x14135c94, 0x35ac1f7, 0x1472b8a5, - 0x37b2b6a, 0x14d1e242, 0x39c2a2f, 0x1530d881, - 0x3bdbdf6, 0x158f9a76, 0x3dfe66c, 0x15ee2738, - 0x402a33c, 0x164c7ddd, 0x425f410, 0x16aa9d7e, - 0x449d892, 0x17088531, 0x46e5069, 0x1766340f, - 0x4935b3c, 0x17c3a931, 0x4b8f8ad, 0x1820e3b0, - 0x4df2862, 0x187de2a7, 0x505e9fb, 0x18daa52f, - 0x52d3d18, 0x19372a64, 0x555215a, 0x19937161, - 0x57d965d, 0x19ef7944, 0x5a69bbe, 0x1a4b4128, - 0x5d03118, 0x1aa6c82b, 0x5fa5603, 0x1b020d6c, - 0x6250a18, 0x1b5d100a, 0x6504ced, 0x1bb7cf23, - 0x67c1e18, 0x1c1249d8, 0x6a87d2d, 0x1c6c7f4a, - 0x6d569be, 0x1cc66e99, 0x702e35c, 0x1d2016e9, - 0x730e997, 0x1d79775c, 0x75f7bfe, 0x1dd28f15, - 0x78e9a1d, 0x1e2b5d38, 0x7be4381, 0x1e83e0eb, - 0x7ee77b3, 0x1edc1953, 0x81f363d, 0x1f340596, - 0x8507ea7, 0x1f8ba4dc, 0x8825077, 0x1fe2f64c, - 0x8b4ab32, 0x2039f90f, 0x8e78e5b, 0x2090ac4d, - 0x91af976, 0x20e70f32, 0x94eec03, 0x213d20e8, - 0x9836582, 0x2192e09b, 0x9b86572, 0x21e84d76, - 0x9edeb50, 0x223d66a8, 0xa23f698, 0x22922b5e, - 0xa5a86c4, 0x22e69ac8, 0xa919b4e, 0x233ab414, - 0xac933ae, 0x238e7673, 0xb014f5b, 0x23e1e117, - 0xb39edca, 0x2434f332, 0xb730e70, 0x2487abf7, - 0xbacb0bf, 0x24da0a9a, 0xbe6d42b, 0x252c0e4f, - 0xc217822, 0x257db64c, 0xc5c9c14, 0x25cf01c8, - 0xc983f70, 0x261feffa, 0xcd461a2, 0x2670801a, - 0xd110216, 0x26c0b162, 0xd4e2037, 0x2710830c, - 0xd8bbb6d, 0x275ff452, 0xdc9d320, 0x27af0472, - 0xe0866b8, 0x27fdb2a7, 0xe47759a, 0x284bfe2f, - 0xe86ff2a, 0x2899e64a, 0xec702cb, 0x28e76a37, - 0xf077fe1, 0x29348937, 0xf4875ca, 0x2981428c, - 0xf89e3e8, 0x29cd9578, 0xfcbc999, 0x2a19813f, - 0x100e2639, 0x2a650525, 0x1050f926, 0x2ab02071, - 0x109441bb, 0x2afad269, 0x10d7ff51, 0x2b451a55, - 0x111c3142, 0x2b8ef77d, 0x1160d6e5, 0x2bd8692b, - 0x11a5ef90, 0x2c216eaa, 0x11eb7a9a, 0x2c6a0746, - 0x12317756, 0x2cb2324c, 0x1277e518, 0x2cf9ef09, - 0x12bec333, 0x2d413ccd, 0x130610f7, 0x2d881ae8, - 0x134dcdb4, 0x2dce88aa, 0x1395f8ba, 0x2e148566, - 0x13de9156, 0x2e5a1070, 0x142796d5, 0x2e9f291b, - 0x14710883, 0x2ee3cebe, 0x14bae5ab, 0x2f2800af, - 0x15052d97, 0x2f6bbe45, 0x154fdf8f, 0x2faf06da, - 0x159afadb, 0x2ff1d9c7, 0x15e67ec1, 0x30343667, - 0x16326a88, 0x30761c18, 0x167ebd74, 0x30b78a36, - 0x16cb76c9, 0x30f8801f, 0x171895c9, 0x3138fd35, - 0x176619b6, 0x317900d6, 0x17b401d1, 0x31b88a66, - 0x18024d59, 0x31f79948, 0x1850fb8e, 0x32362ce0, - 0x18a00bae, 0x32744493, 0x18ef7cf4, 0x32b1dfc9, - 0x193f4e9e, 0x32eefdea, 0x198f7fe6, 0x332b9e5e, - 0x19e01006, 0x3367c090, 0x1a30fe38, 0x33a363ec, - 0x1a8249b4, 0x33de87de, 0x1ad3f1b1, 0x34192bd5, - 0x1b25f566, 0x34534f41, 0x1b785409, 0x348cf190, - 0x1bcb0cce, 0x34c61236, 0x1c1e1ee9, 0x34feb0a5, - 0x1c71898d, 0x3536cc52, 0x1cc54bec, 0x356e64b2, - 0x1d196538, 0x35a5793c, 0x1d6dd4a2, 0x35dc0968, - 0x1dc29958, 0x361214b0, 0x1e17b28a, 0x36479a8e, - 0x1e6d1f65, 0x367c9a7e, 0x1ec2df18, 0x36b113fd, - 0x1f18f0ce, 0x36e5068a, 0x1f6f53b3, 0x371871a5, - 0x1fc606f1, 0x374b54ce, 0x201d09b4, 0x377daf89, - 0x20745b24, 0x37af8159, 0x20cbfa6a, 0x37e0c9c3, - 0x2123e6ad, 0x3811884d, 0x217c1f15, 0x3841bc7f, - 0x21d4a2c8, 0x387165e3, 0x222d70eb, 0x38a08402, - 0x228688a4, 0x38cf1669, 0x22dfe917, 0x38fd1ca4, - 0x23399167, 0x392a9642, 0x239380b6, 0x395782d3, - 0x23edb628, 0x3983e1e8, 0x244830dd, 0x39afb313, - 0x24a2eff6, 0x39daf5e8, 0x24fdf294, 0x3a05a9fd, - 0x255937d5, 0x3a2fcee8, 0x25b4bed8, 0x3a596442, - 0x261086bc, 0x3a8269a3, 0x266c8e9f, 0x3aaadea6, - 0x26c8d59c, 0x3ad2c2e8, 0x27255ad1, 0x3afa1605, - 0x27821d59, 0x3b20d79e, 0x27df1c50, 0x3b470753, - 0x283c56cf, 0x3b6ca4c4, 0x2899cbf1, 0x3b91af97, - 0x28f77acf, 0x3bb6276e, 0x29556282, 0x3bda0bf0, - 0x29b38223, 0x3bfd5cc4, 0x2a11d8c8, 0x3c201994, - 0x2a70658a, 0x3c42420a, 0x2acf277f, 0x3c63d5d1, - 0x2b2e1dbe, 0x3c84d496, 0x2b8d475b, 0x3ca53e09, - 0x2beca36c, 0x3cc511d9, 0x2c4c3106, 0x3ce44fb7, - 0x2cabef3d, 0x3d02f757, 0x2d0bdd25, 0x3d21086c, - 0x2d6bf9d1, 0x3d3e82ae, 0x2dcc4454, 0x3d5b65d2, - 0x2e2cbbc1, 0x3d77b192, 0x2e8d5f29, 0x3d9365a8, - 0x2eee2d9d, 0x3dae81cf, 0x2f4f2630, 0x3dc905c5, - 0x2fb047f2, 0x3de2f148, 0x301191f3, 0x3dfc4418, - 0x30730342, 0x3e14fdf7, 0x30d49af1, 0x3e2d1ea8, - 0x3136580d, 0x3e44a5ef, 0x319839a6, 0x3e5b9392, - 0x31fa3ecb, 0x3e71e759, 0x325c6688, 0x3e87a10c, - 0x32beafed, 0x3e9cc076, 0x33211a07, 0x3eb14563, - 0x3383a3e2, 0x3ec52fa0, 0x33e64c8c, 0x3ed87efc, - 0x34491311, 0x3eeb3347, 0x34abf67e, 0x3efd4c54, - 0x350ef5de, 0x3f0ec9f5, 0x3572103d, 0x3f1fabff, - 0x35d544a7, 0x3f2ff24a, 0x36389228, 0x3f3f9cab, - 0x369bf7c9, 0x3f4eaafe, 0x36ff7496, 0x3f5d1d1d, - 0x37630799, 0x3f6af2e3, 0x37c6afdc, 0x3f782c30, - 0x382a6c6a, 0x3f84c8e2, 0x388e3c4d, 0x3f90c8da, - 0x38f21e8e, 0x3f9c2bfb, 0x39561237, 0x3fa6f228, - 0x39ba1651, 0x3fb11b48, 0x3a1e29e5, 0x3fbaa740, - 0x3a824bfd, 0x3fc395f9, 0x3ae67ba2, 0x3fcbe75e, - 0x3b4ab7db, 0x3fd39b5a, 0x3baeffb3, 0x3fdab1d9, - 0x3c135231, 0x3fe12acb, 0x3c77ae5e, 0x3fe7061f, - 0x3cdc1342, 0x3fec43c7, 0x3d407fe6, 0x3ff0e3b6, - 0x3da4f351, 0x3ff4e5e0, 0x3e096c8d, 0x3ff84a3c, - 0x3e6deaa1, 0x3ffb10c1, 0x3ed26c94, 0x3ffd3969, - 0x3f36f170, 0x3ffec42d, 0x3f9b783c, 0x3fffb10b -}; - - -/** -* \par -* Generation of realCoefBQ31 array: -* \par -* n = 512 -*
for (i = 0; i < n; i++)   
-* {   
-*    pBTable[2 * i] = 0.5 * (1.0 + sin (2 * PI / (double) (2 * n) * (double) i));   
-*    pBTable[2 * i + 1] = 0.5 * (1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
-* } 
-* \par -* Convert to fixed point Q31 format -* round(pBTable[i] * pow(2, 31)) -* -*/ - -const q31_t realCoefBQ31[1024] = { - 0x40000000, 0x40000000, 0x406487c4, 0x3fffb10b, - 0x40c90e90, 0x3ffec42d, 0x412d936c, 0x3ffd3969, - 0x4192155f, 0x3ffb10c1, 0x41f69373, 0x3ff84a3c, - 0x425b0caf, 0x3ff4e5e0, 0x42bf801a, 0x3ff0e3b6, - 0x4323ecbe, 0x3fec43c7, 0x438851a2, 0x3fe7061f, - 0x43ecadcf, 0x3fe12acb, 0x4451004d, 0x3fdab1d9, - 0x44b54825, 0x3fd39b5a, 0x4519845e, 0x3fcbe75e, - 0x457db403, 0x3fc395f9, 0x45e1d61b, 0x3fbaa740, - 0x4645e9af, 0x3fb11b48, 0x46a9edc9, 0x3fa6f228, - 0x470de172, 0x3f9c2bfb, 0x4771c3b3, 0x3f90c8da, - 0x47d59396, 0x3f84c8e2, 0x48395024, 0x3f782c30, - 0x489cf867, 0x3f6af2e3, 0x49008b6a, 0x3f5d1d1d, - 0x49640837, 0x3f4eaafe, 0x49c76dd8, 0x3f3f9cab, - 0x4a2abb59, 0x3f2ff24a, 0x4a8defc3, 0x3f1fabff, - 0x4af10a22, 0x3f0ec9f5, 0x4b540982, 0x3efd4c54, - 0x4bb6ecef, 0x3eeb3347, 0x4c19b374, 0x3ed87efc, - 0x4c7c5c1e, 0x3ec52fa0, 0x4cdee5f9, 0x3eb14563, - 0x4d415013, 0x3e9cc076, 0x4da39978, 0x3e87a10c, - 0x4e05c135, 0x3e71e759, 0x4e67c65a, 0x3e5b9392, - 0x4ec9a7f3, 0x3e44a5ef, 0x4f2b650f, 0x3e2d1ea8, - 0x4f8cfcbe, 0x3e14fdf7, 0x4fee6e0d, 0x3dfc4418, - 0x504fb80e, 0x3de2f148, 0x50b0d9d0, 0x3dc905c5, - 0x5111d263, 0x3dae81cf, 0x5172a0d7, 0x3d9365a8, - 0x51d3443f, 0x3d77b192, 0x5233bbac, 0x3d5b65d2, - 0x5294062f, 0x3d3e82ae, 0x52f422db, 0x3d21086c, - 0x535410c3, 0x3d02f757, 0x53b3cefa, 0x3ce44fb7, - 0x54135c94, 0x3cc511d9, 0x5472b8a5, 0x3ca53e09, - 0x54d1e242, 0x3c84d496, 0x5530d881, 0x3c63d5d1, - 0x558f9a76, 0x3c42420a, 0x55ee2738, 0x3c201994, - 0x564c7ddd, 0x3bfd5cc4, 0x56aa9d7e, 0x3bda0bf0, - 0x57088531, 0x3bb6276e, 0x5766340f, 0x3b91af97, - 0x57c3a931, 0x3b6ca4c4, 0x5820e3b0, 0x3b470753, - 0x587de2a7, 0x3b20d79e, 0x58daa52f, 0x3afa1605, - 0x59372a64, 0x3ad2c2e8, 0x59937161, 0x3aaadea6, - 0x59ef7944, 0x3a8269a3, 0x5a4b4128, 0x3a596442, - 0x5aa6c82b, 0x3a2fcee8, 0x5b020d6c, 0x3a05a9fd, - 0x5b5d100a, 0x39daf5e8, 0x5bb7cf23, 0x39afb313, - 0x5c1249d8, 0x3983e1e8, 0x5c6c7f4a, 0x395782d3, - 0x5cc66e99, 0x392a9642, 0x5d2016e9, 0x38fd1ca4, - 0x5d79775c, 0x38cf1669, 0x5dd28f15, 0x38a08402, - 0x5e2b5d38, 0x387165e3, 0x5e83e0eb, 0x3841bc7f, - 0x5edc1953, 0x3811884d, 0x5f340596, 0x37e0c9c3, - 0x5f8ba4dc, 0x37af8159, 0x5fe2f64c, 0x377daf89, - 0x6039f90f, 0x374b54ce, 0x6090ac4d, 0x371871a5, - 0x60e70f32, 0x36e5068a, 0x613d20e8, 0x36b113fd, - 0x6192e09b, 0x367c9a7e, 0x61e84d76, 0x36479a8e, - 0x623d66a8, 0x361214b0, 0x62922b5e, 0x35dc0968, - 0x62e69ac8, 0x35a5793c, 0x633ab414, 0x356e64b2, - 0x638e7673, 0x3536cc52, 0x63e1e117, 0x34feb0a5, - 0x6434f332, 0x34c61236, 0x6487abf7, 0x348cf190, - 0x64da0a9a, 0x34534f41, 0x652c0e4f, 0x34192bd5, - 0x657db64c, 0x33de87de, 0x65cf01c8, 0x33a363ec, - 0x661feffa, 0x3367c090, 0x6670801a, 0x332b9e5e, - 0x66c0b162, 0x32eefdea, 0x6710830c, 0x32b1dfc9, - 0x675ff452, 0x32744493, 0x67af0472, 0x32362ce0, - 0x67fdb2a7, 0x31f79948, 0x684bfe2f, 0x31b88a66, - 0x6899e64a, 0x317900d6, 0x68e76a37, 0x3138fd35, - 0x69348937, 0x30f8801f, 0x6981428c, 0x30b78a36, - 0x69cd9578, 0x30761c18, 0x6a19813f, 0x30343667, - 0x6a650525, 0x2ff1d9c7, 0x6ab02071, 0x2faf06da, - 0x6afad269, 0x2f6bbe45, 0x6b451a55, 0x2f2800af, - 0x6b8ef77d, 0x2ee3cebe, 0x6bd8692b, 0x2e9f291b, - 0x6c216eaa, 0x2e5a1070, 0x6c6a0746, 0x2e148566, - 0x6cb2324c, 0x2dce88aa, 0x6cf9ef09, 0x2d881ae8, - 0x6d413ccd, 0x2d413ccd, 0x6d881ae8, 0x2cf9ef09, - 0x6dce88aa, 0x2cb2324c, 0x6e148566, 0x2c6a0746, - 0x6e5a1070, 0x2c216eaa, 0x6e9f291b, 0x2bd8692b, - 0x6ee3cebe, 0x2b8ef77d, 0x6f2800af, 0x2b451a55, - 0x6f6bbe45, 0x2afad269, 0x6faf06da, 0x2ab02071, - 0x6ff1d9c7, 0x2a650525, 0x70343667, 0x2a19813f, - 0x70761c18, 0x29cd9578, 0x70b78a36, 0x2981428c, - 0x70f8801f, 0x29348937, 0x7138fd35, 0x28e76a37, - 0x717900d6, 0x2899e64a, 0x71b88a66, 0x284bfe2f, - 0x71f79948, 0x27fdb2a7, 0x72362ce0, 0x27af0472, - 0x72744493, 0x275ff452, 0x72b1dfc9, 0x2710830c, - 0x72eefdea, 0x26c0b162, 0x732b9e5e, 0x2670801a, - 0x7367c090, 0x261feffa, 0x73a363ec, 0x25cf01c8, - 0x73de87de, 0x257db64c, 0x74192bd5, 0x252c0e4f, - 0x74534f41, 0x24da0a9a, 0x748cf190, 0x2487abf7, - 0x74c61236, 0x2434f332, 0x74feb0a5, 0x23e1e117, - 0x7536cc52, 0x238e7673, 0x756e64b2, 0x233ab414, - 0x75a5793c, 0x22e69ac8, 0x75dc0968, 0x22922b5e, - 0x761214b0, 0x223d66a8, 0x76479a8e, 0x21e84d76, - 0x767c9a7e, 0x2192e09b, 0x76b113fd, 0x213d20e8, - 0x76e5068a, 0x20e70f32, 0x771871a5, 0x2090ac4d, - 0x774b54ce, 0x2039f90f, 0x777daf89, 0x1fe2f64c, - 0x77af8159, 0x1f8ba4dc, 0x77e0c9c3, 0x1f340596, - 0x7811884d, 0x1edc1953, 0x7841bc7f, 0x1e83e0eb, - 0x787165e3, 0x1e2b5d38, 0x78a08402, 0x1dd28f15, - 0x78cf1669, 0x1d79775c, 0x78fd1ca4, 0x1d2016e9, - 0x792a9642, 0x1cc66e99, 0x795782d3, 0x1c6c7f4a, - 0x7983e1e8, 0x1c1249d8, 0x79afb313, 0x1bb7cf23, - 0x79daf5e8, 0x1b5d100a, 0x7a05a9fd, 0x1b020d6c, - 0x7a2fcee8, 0x1aa6c82b, 0x7a596442, 0x1a4b4128, - 0x7a8269a3, 0x19ef7944, 0x7aaadea6, 0x19937161, - 0x7ad2c2e8, 0x19372a64, 0x7afa1605, 0x18daa52f, - 0x7b20d79e, 0x187de2a7, 0x7b470753, 0x1820e3b0, - 0x7b6ca4c4, 0x17c3a931, 0x7b91af97, 0x1766340f, - 0x7bb6276e, 0x17088531, 0x7bda0bf0, 0x16aa9d7e, - 0x7bfd5cc4, 0x164c7ddd, 0x7c201994, 0x15ee2738, - 0x7c42420a, 0x158f9a76, 0x7c63d5d1, 0x1530d881, - 0x7c84d496, 0x14d1e242, 0x7ca53e09, 0x1472b8a5, - 0x7cc511d9, 0x14135c94, 0x7ce44fb7, 0x13b3cefa, - 0x7d02f757, 0x135410c3, 0x7d21086c, 0x12f422db, - 0x7d3e82ae, 0x1294062f, 0x7d5b65d2, 0x1233bbac, - 0x7d77b192, 0x11d3443f, 0x7d9365a8, 0x1172a0d7, - 0x7dae81cf, 0x1111d263, 0x7dc905c5, 0x10b0d9d0, - 0x7de2f148, 0x104fb80e, 0x7dfc4418, 0xfee6e0d, - 0x7e14fdf7, 0xf8cfcbe, 0x7e2d1ea8, 0xf2b650f, - 0x7e44a5ef, 0xec9a7f3, 0x7e5b9392, 0xe67c65a, - 0x7e71e759, 0xe05c135, 0x7e87a10c, 0xda39978, - 0x7e9cc076, 0xd415013, 0x7eb14563, 0xcdee5f9, - 0x7ec52fa0, 0xc7c5c1e, 0x7ed87efc, 0xc19b374, - 0x7eeb3347, 0xbb6ecef, 0x7efd4c54, 0xb540982, - 0x7f0ec9f5, 0xaf10a22, 0x7f1fabff, 0xa8defc3, - 0x7f2ff24a, 0xa2abb59, 0x7f3f9cab, 0x9c76dd8, - 0x7f4eaafe, 0x9640837, 0x7f5d1d1d, 0x9008b6a, - 0x7f6af2e3, 0x89cf867, 0x7f782c30, 0x8395024, - 0x7f84c8e2, 0x7d59396, 0x7f90c8da, 0x771c3b3, - 0x7f9c2bfb, 0x70de172, 0x7fa6f228, 0x6a9edc9, - 0x7fb11b48, 0x645e9af, 0x7fbaa740, 0x5e1d61b, - 0x7fc395f9, 0x57db403, 0x7fcbe75e, 0x519845e, - 0x7fd39b5a, 0x4b54825, 0x7fdab1d9, 0x451004d, - 0x7fe12acb, 0x3ecadcf, 0x7fe7061f, 0x38851a2, - 0x7fec43c7, 0x323ecbe, 0x7ff0e3b6, 0x2bf801a, - 0x7ff4e5e0, 0x25b0caf, 0x7ff84a3c, 0x1f69373, - 0x7ffb10c1, 0x192155f, 0x7ffd3969, 0x12d936c, - 0x7ffec42d, 0xc90e90, 0x7fffb10b, 0x6487c4, - 0x7fffffff, 0x0, 0x7fffb10b, 0xff9b783c, - 0x7ffec42d, 0xff36f170, 0x7ffd3969, 0xfed26c94, - 0x7ffb10c1, 0xfe6deaa1, 0x7ff84a3c, 0xfe096c8d, - 0x7ff4e5e0, 0xfda4f351, 0x7ff0e3b6, 0xfd407fe6, - 0x7fec43c7, 0xfcdc1342, 0x7fe7061f, 0xfc77ae5e, - 0x7fe12acb, 0xfc135231, 0x7fdab1d9, 0xfbaeffb3, - 0x7fd39b5a, 0xfb4ab7db, 0x7fcbe75e, 0xfae67ba2, - 0x7fc395f9, 0xfa824bfd, 0x7fbaa740, 0xfa1e29e5, - 0x7fb11b48, 0xf9ba1651, 0x7fa6f228, 0xf9561237, - 0x7f9c2bfb, 0xf8f21e8e, 0x7f90c8da, 0xf88e3c4d, - 0x7f84c8e2, 0xf82a6c6a, 0x7f782c30, 0xf7c6afdc, - 0x7f6af2e3, 0xf7630799, 0x7f5d1d1d, 0xf6ff7496, - 0x7f4eaafe, 0xf69bf7c9, 0x7f3f9cab, 0xf6389228, - 0x7f2ff24a, 0xf5d544a7, 0x7f1fabff, 0xf572103d, - 0x7f0ec9f5, 0xf50ef5de, 0x7efd4c54, 0xf4abf67e, - 0x7eeb3347, 0xf4491311, 0x7ed87efc, 0xf3e64c8c, - 0x7ec52fa0, 0xf383a3e2, 0x7eb14563, 0xf3211a07, - 0x7e9cc076, 0xf2beafed, 0x7e87a10c, 0xf25c6688, - 0x7e71e759, 0xf1fa3ecb, 0x7e5b9392, 0xf19839a6, - 0x7e44a5ef, 0xf136580d, 0x7e2d1ea8, 0xf0d49af1, - 0x7e14fdf7, 0xf0730342, 0x7dfc4418, 0xf01191f3, - 0x7de2f148, 0xefb047f2, 0x7dc905c5, 0xef4f2630, - 0x7dae81cf, 0xeeee2d9d, 0x7d9365a8, 0xee8d5f29, - 0x7d77b192, 0xee2cbbc1, 0x7d5b65d2, 0xedcc4454, - 0x7d3e82ae, 0xed6bf9d1, 0x7d21086c, 0xed0bdd25, - 0x7d02f757, 0xecabef3d, 0x7ce44fb7, 0xec4c3106, - 0x7cc511d9, 0xebeca36c, 0x7ca53e09, 0xeb8d475b, - 0x7c84d496, 0xeb2e1dbe, 0x7c63d5d1, 0xeacf277f, - 0x7c42420a, 0xea70658a, 0x7c201994, 0xea11d8c8, - 0x7bfd5cc4, 0xe9b38223, 0x7bda0bf0, 0xe9556282, - 0x7bb6276e, 0xe8f77acf, 0x7b91af97, 0xe899cbf1, - 0x7b6ca4c4, 0xe83c56cf, 0x7b470753, 0xe7df1c50, - 0x7b20d79e, 0xe7821d59, 0x7afa1605, 0xe7255ad1, - 0x7ad2c2e8, 0xe6c8d59c, 0x7aaadea6, 0xe66c8e9f, - 0x7a8269a3, 0xe61086bc, 0x7a596442, 0xe5b4bed8, - 0x7a2fcee8, 0xe55937d5, 0x7a05a9fd, 0xe4fdf294, - 0x79daf5e8, 0xe4a2eff6, 0x79afb313, 0xe44830dd, - 0x7983e1e8, 0xe3edb628, 0x795782d3, 0xe39380b6, - 0x792a9642, 0xe3399167, 0x78fd1ca4, 0xe2dfe917, - 0x78cf1669, 0xe28688a4, 0x78a08402, 0xe22d70eb, - 0x787165e3, 0xe1d4a2c8, 0x7841bc7f, 0xe17c1f15, - 0x7811884d, 0xe123e6ad, 0x77e0c9c3, 0xe0cbfa6a, - 0x77af8159, 0xe0745b24, 0x777daf89, 0xe01d09b4, - 0x774b54ce, 0xdfc606f1, 0x771871a5, 0xdf6f53b3, - 0x76e5068a, 0xdf18f0ce, 0x76b113fd, 0xdec2df18, - 0x767c9a7e, 0xde6d1f65, 0x76479a8e, 0xde17b28a, - 0x761214b0, 0xddc29958, 0x75dc0968, 0xdd6dd4a2, - 0x75a5793c, 0xdd196538, 0x756e64b2, 0xdcc54bec, - 0x7536cc52, 0xdc71898d, 0x74feb0a5, 0xdc1e1ee9, - 0x74c61236, 0xdbcb0cce, 0x748cf190, 0xdb785409, - 0x74534f41, 0xdb25f566, 0x74192bd5, 0xdad3f1b1, - 0x73de87de, 0xda8249b4, 0x73a363ec, 0xda30fe38, - 0x7367c090, 0xd9e01006, 0x732b9e5e, 0xd98f7fe6, - 0x72eefdea, 0xd93f4e9e, 0x72b1dfc9, 0xd8ef7cf4, - 0x72744493, 0xd8a00bae, 0x72362ce0, 0xd850fb8e, - 0x71f79948, 0xd8024d59, 0x71b88a66, 0xd7b401d1, - 0x717900d6, 0xd76619b6, 0x7138fd35, 0xd71895c9, - 0x70f8801f, 0xd6cb76c9, 0x70b78a36, 0xd67ebd74, - 0x70761c18, 0xd6326a88, 0x70343667, 0xd5e67ec1, - 0x6ff1d9c7, 0xd59afadb, 0x6faf06da, 0xd54fdf8f, - 0x6f6bbe45, 0xd5052d97, 0x6f2800af, 0xd4bae5ab, - 0x6ee3cebe, 0xd4710883, 0x6e9f291b, 0xd42796d5, - 0x6e5a1070, 0xd3de9156, 0x6e148566, 0xd395f8ba, - 0x6dce88aa, 0xd34dcdb4, 0x6d881ae8, 0xd30610f7, - 0x6d413ccd, 0xd2bec333, 0x6cf9ef09, 0xd277e518, - 0x6cb2324c, 0xd2317756, 0x6c6a0746, 0xd1eb7a9a, - 0x6c216eaa, 0xd1a5ef90, 0x6bd8692b, 0xd160d6e5, - 0x6b8ef77d, 0xd11c3142, 0x6b451a55, 0xd0d7ff51, - 0x6afad269, 0xd09441bb, 0x6ab02071, 0xd050f926, - 0x6a650525, 0xd00e2639, 0x6a19813f, 0xcfcbc999, - 0x69cd9578, 0xcf89e3e8, 0x6981428c, 0xcf4875ca, - 0x69348937, 0xcf077fe1, 0x68e76a37, 0xcec702cb, - 0x6899e64a, 0xce86ff2a, 0x684bfe2f, 0xce47759a, - 0x67fdb2a7, 0xce0866b8, 0x67af0472, 0xcdc9d320, - 0x675ff452, 0xcd8bbb6d, 0x6710830c, 0xcd4e2037, - 0x66c0b162, 0xcd110216, 0x6670801a, 0xccd461a2, - 0x661feffa, 0xcc983f70, 0x65cf01c8, 0xcc5c9c14, - 0x657db64c, 0xcc217822, 0x652c0e4f, 0xcbe6d42b, - 0x64da0a9a, 0xcbacb0bf, 0x6487abf7, 0xcb730e70, - 0x6434f332, 0xcb39edca, 0x63e1e117, 0xcb014f5b, - 0x638e7673, 0xcac933ae, 0x633ab414, 0xca919b4e, - 0x62e69ac8, 0xca5a86c4, 0x62922b5e, 0xca23f698, - 0x623d66a8, 0xc9edeb50, 0x61e84d76, 0xc9b86572, - 0x6192e09b, 0xc9836582, 0x613d20e8, 0xc94eec03, - 0x60e70f32, 0xc91af976, 0x6090ac4d, 0xc8e78e5b, - 0x6039f90f, 0xc8b4ab32, 0x5fe2f64c, 0xc8825077, - 0x5f8ba4dc, 0xc8507ea7, 0x5f340596, 0xc81f363d, - 0x5edc1953, 0xc7ee77b3, 0x5e83e0eb, 0xc7be4381, - 0x5e2b5d38, 0xc78e9a1d, 0x5dd28f15, 0xc75f7bfe, - 0x5d79775c, 0xc730e997, 0x5d2016e9, 0xc702e35c, - 0x5cc66e99, 0xc6d569be, 0x5c6c7f4a, 0xc6a87d2d, - 0x5c1249d8, 0xc67c1e18, 0x5bb7cf23, 0xc6504ced, - 0x5b5d100a, 0xc6250a18, 0x5b020d6c, 0xc5fa5603, - 0x5aa6c82b, 0xc5d03118, 0x5a4b4128, 0xc5a69bbe, - 0x59ef7944, 0xc57d965d, 0x59937161, 0xc555215a, - 0x59372a64, 0xc52d3d18, 0x58daa52f, 0xc505e9fb, - 0x587de2a7, 0xc4df2862, 0x5820e3b0, 0xc4b8f8ad, - 0x57c3a931, 0xc4935b3c, 0x5766340f, 0xc46e5069, - 0x57088531, 0xc449d892, 0x56aa9d7e, 0xc425f410, - 0x564c7ddd, 0xc402a33c, 0x55ee2738, 0xc3dfe66c, - 0x558f9a76, 0xc3bdbdf6, 0x5530d881, 0xc39c2a2f, - 0x54d1e242, 0xc37b2b6a, 0x5472b8a5, 0xc35ac1f7, - 0x54135c94, 0xc33aee27, 0x53b3cefa, 0xc31bb049, - 0x535410c3, 0xc2fd08a9, 0x52f422db, 0xc2def794, - 0x5294062f, 0xc2c17d52, 0x5233bbac, 0xc2a49a2e, - 0x51d3443f, 0xc2884e6e, 0x5172a0d7, 0xc26c9a58, - 0x5111d263, 0xc2517e31, 0x50b0d9d0, 0xc236fa3b, - 0x504fb80e, 0xc21d0eb8, 0x4fee6e0d, 0xc203bbe8, - 0x4f8cfcbe, 0xc1eb0209, 0x4f2b650f, 0xc1d2e158, - 0x4ec9a7f3, 0xc1bb5a11, 0x4e67c65a, 0xc1a46c6e, - 0x4e05c135, 0xc18e18a7, 0x4da39978, 0xc1785ef4, - 0x4d415013, 0xc1633f8a, 0x4cdee5f9, 0xc14eba9d, - 0x4c7c5c1e, 0xc13ad060, 0x4c19b374, 0xc1278104, - 0x4bb6ecef, 0xc114ccb9, 0x4b540982, 0xc102b3ac, - 0x4af10a22, 0xc0f1360b, 0x4a8defc3, 0xc0e05401, - 0x4a2abb59, 0xc0d00db6, 0x49c76dd8, 0xc0c06355, - 0x49640837, 0xc0b15502, 0x49008b6a, 0xc0a2e2e3, - 0x489cf867, 0xc0950d1d, 0x48395024, 0xc087d3d0, - 0x47d59396, 0xc07b371e, 0x4771c3b3, 0xc06f3726, - 0x470de172, 0xc063d405, 0x46a9edc9, 0xc0590dd8, - 0x4645e9af, 0xc04ee4b8, 0x45e1d61b, 0xc04558c0, - 0x457db403, 0xc03c6a07, 0x4519845e, 0xc03418a2, - 0x44b54825, 0xc02c64a6, 0x4451004d, 0xc0254e27, - 0x43ecadcf, 0xc01ed535, 0x438851a2, 0xc018f9e1, - 0x4323ecbe, 0xc013bc39, 0x42bf801a, 0xc00f1c4a, - 0x425b0caf, 0xc00b1a20, 0x41f69373, 0xc007b5c4, - 0x4192155f, 0xc004ef3f, 0x412d936c, 0xc002c697, - 0x40c90e90, 0xc0013bd3, 0x406487c4, 0xc0004ef5 -}; - -/** -* @brief Initialization function for the Q31 RFFT/RIFFT. -* @param[in, out] *S points to an instance of the Q31 RFFT/RIFFT structure. -* @param[in, out] *S_CFFT points to an instance of the Q31 CFFT/CIFFT structure. -* @param[in] fftLenReal length of the FFT. -* @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. -* -* \par Description: -* \par -* The parameter fftLenReal Specifies length of RFFT/RIFFT Process. Supported FFT Lengths are 128, 512, 2048. -* \par -* The parameter ifftFlagR controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlagR to calculate RIFFT, otherwise RFFT is calculated. -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* This function also initializes Twiddle factor table. -*/ - -arm_status arm_rfft_init_q31( - arm_rfft_instance_q31 * S, - arm_cfft_radix4_instance_q31 * S_CFFT, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialize the Real FFT length */ - S->fftLenReal = (uint16_t) fftLenReal; - - /* Initialize the Complex FFT length */ - S->fftLenBy2 = (uint16_t) fftLenReal / 2u; - - /* Initialize the Twiddle coefficientA pointer */ - S->pTwiddleAReal = (q31_t *) realCoefAQ31; - - /* Initialize the Twiddle coefficientB pointer */ - S->pTwiddleBReal = (q31_t *) realCoefBQ31; - - /* Initialize the Flag for selection of RFFT or RIFFT */ - S->ifftFlagR = (uint8_t) ifftFlagR; - - /* Initialize the Flag for calculation Bit reversal or not */ - S->bitReverseFlagR = (uint8_t) bitReverseFlag; - - /* Initialization of coef modifier depending on the FFT length */ - switch (S->fftLenReal) - { - case 512u: - S->twidCoefRModifier = 2u; - break; - case 128u: - S->twidCoefRModifier = 8u; - break; - default: - /* Reporting argument error if rfftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - /* Init Complex FFT Instance */ - S->pCfft = S_CFFT; - - if(S->ifftFlagR) - { - /* Initializes the CIFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_q31(S->pCfft, (uint16_t) S->fftLenBy2, 1u, 1u); - } - else - { - /* Initializes the CFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_q31(S->pCfft, (uint16_t) S->fftLenBy2, 0u, 1u); - } - - /* return the status of RFFT Init function */ - return (status); - -} - - /** - * @} end of RFFT_RIFFT group - */ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_rfft_init_q31.c +* +* Description: RFFT & RIFFT Q31 initialisation function +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/** + * @ingroup groupTransforms + */ + +/** + * @addtogroup RFFT_RIFFT + * @{ + */ + +/** +* \par +* Generation floating point realCoefAQ31 array: +* \par +* n = 1024 +*
for (i = 0; i < n; i++)   
+* {   
+*    pATable[2 * i] = 0.5 * (1.0 - sin (2 * PI / (double) (2 * n) * (double) i));   
+*    pATable[2 * i + 1] = 0.5 * (-1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
+* }
+* \par +* Convert to fixed point Q31 format +* round(pATable[i] * pow(2, 31)) +*/ + + +const q31_t realCoefAQ31[1024] = { + 0x40000000, 0xc0000000, 0x3f9b783c, 0xc0004ef5, + 0x3f36f170, 0xc0013bd3, 0x3ed26c94, 0xc002c697, + 0x3e6deaa1, 0xc004ef3f, 0x3e096c8d, 0xc007b5c4, + 0x3da4f351, 0xc00b1a20, 0x3d407fe6, 0xc00f1c4a, + 0x3cdc1342, 0xc013bc39, 0x3c77ae5e, 0xc018f9e1, + 0x3c135231, 0xc01ed535, 0x3baeffb3, 0xc0254e27, + 0x3b4ab7db, 0xc02c64a6, 0x3ae67ba2, 0xc03418a2, + 0x3a824bfd, 0xc03c6a07, 0x3a1e29e5, 0xc04558c0, + 0x39ba1651, 0xc04ee4b8, 0x39561237, 0xc0590dd8, + 0x38f21e8e, 0xc063d405, 0x388e3c4d, 0xc06f3726, + 0x382a6c6a, 0xc07b371e, 0x37c6afdc, 0xc087d3d0, + 0x37630799, 0xc0950d1d, 0x36ff7496, 0xc0a2e2e3, + 0x369bf7c9, 0xc0b15502, 0x36389228, 0xc0c06355, + 0x35d544a7, 0xc0d00db6, 0x3572103d, 0xc0e05401, + 0x350ef5de, 0xc0f1360b, 0x34abf67e, 0xc102b3ac, + 0x34491311, 0xc114ccb9, 0x33e64c8c, 0xc1278104, + 0x3383a3e2, 0xc13ad060, 0x33211a07, 0xc14eba9d, + 0x32beafed, 0xc1633f8a, 0x325c6688, 0xc1785ef4, + 0x31fa3ecb, 0xc18e18a7, 0x319839a6, 0xc1a46c6e, + 0x3136580d, 0xc1bb5a11, 0x30d49af1, 0xc1d2e158, + 0x30730342, 0xc1eb0209, 0x301191f3, 0xc203bbe8, + 0x2fb047f2, 0xc21d0eb8, 0x2f4f2630, 0xc236fa3b, + 0x2eee2d9d, 0xc2517e31, 0x2e8d5f29, 0xc26c9a58, + 0x2e2cbbc1, 0xc2884e6e, 0x2dcc4454, 0xc2a49a2e, + 0x2d6bf9d1, 0xc2c17d52, 0x2d0bdd25, 0xc2def794, + 0x2cabef3d, 0xc2fd08a9, 0x2c4c3106, 0xc31bb049, + 0x2beca36c, 0xc33aee27, 0x2b8d475b, 0xc35ac1f7, + 0x2b2e1dbe, 0xc37b2b6a, 0x2acf277f, 0xc39c2a2f, + 0x2a70658a, 0xc3bdbdf6, 0x2a11d8c8, 0xc3dfe66c, + 0x29b38223, 0xc402a33c, 0x29556282, 0xc425f410, + 0x28f77acf, 0xc449d892, 0x2899cbf1, 0xc46e5069, + 0x283c56cf, 0xc4935b3c, 0x27df1c50, 0xc4b8f8ad, + 0x27821d59, 0xc4df2862, 0x27255ad1, 0xc505e9fb, + 0x26c8d59c, 0xc52d3d18, 0x266c8e9f, 0xc555215a, + 0x261086bc, 0xc57d965d, 0x25b4bed8, 0xc5a69bbe, + 0x255937d5, 0xc5d03118, 0x24fdf294, 0xc5fa5603, + 0x24a2eff6, 0xc6250a18, 0x244830dd, 0xc6504ced, + 0x23edb628, 0xc67c1e18, 0x239380b6, 0xc6a87d2d, + 0x23399167, 0xc6d569be, 0x22dfe917, 0xc702e35c, + 0x228688a4, 0xc730e997, 0x222d70eb, 0xc75f7bfe, + 0x21d4a2c8, 0xc78e9a1d, 0x217c1f15, 0xc7be4381, + 0x2123e6ad, 0xc7ee77b3, 0x20cbfa6a, 0xc81f363d, + 0x20745b24, 0xc8507ea7, 0x201d09b4, 0xc8825077, + 0x1fc606f1, 0xc8b4ab32, 0x1f6f53b3, 0xc8e78e5b, + 0x1f18f0ce, 0xc91af976, 0x1ec2df18, 0xc94eec03, + 0x1e6d1f65, 0xc9836582, 0x1e17b28a, 0xc9b86572, + 0x1dc29958, 0xc9edeb50, 0x1d6dd4a2, 0xca23f698, + 0x1d196538, 0xca5a86c4, 0x1cc54bec, 0xca919b4e, + 0x1c71898d, 0xcac933ae, 0x1c1e1ee9, 0xcb014f5b, + 0x1bcb0cce, 0xcb39edca, 0x1b785409, 0xcb730e70, + 0x1b25f566, 0xcbacb0bf, 0x1ad3f1b1, 0xcbe6d42b, + 0x1a8249b4, 0xcc217822, 0x1a30fe38, 0xcc5c9c14, + 0x19e01006, 0xcc983f70, 0x198f7fe6, 0xccd461a2, + 0x193f4e9e, 0xcd110216, 0x18ef7cf4, 0xcd4e2037, + 0x18a00bae, 0xcd8bbb6d, 0x1850fb8e, 0xcdc9d320, + 0x18024d59, 0xce0866b8, 0x17b401d1, 0xce47759a, + 0x176619b6, 0xce86ff2a, 0x171895c9, 0xcec702cb, + 0x16cb76c9, 0xcf077fe1, 0x167ebd74, 0xcf4875ca, + 0x16326a88, 0xcf89e3e8, 0x15e67ec1, 0xcfcbc999, + 0x159afadb, 0xd00e2639, 0x154fdf8f, 0xd050f926, + 0x15052d97, 0xd09441bb, 0x14bae5ab, 0xd0d7ff51, + 0x14710883, 0xd11c3142, 0x142796d5, 0xd160d6e5, + 0x13de9156, 0xd1a5ef90, 0x1395f8ba, 0xd1eb7a9a, + 0x134dcdb4, 0xd2317756, 0x130610f7, 0xd277e518, + 0x12bec333, 0xd2bec333, 0x1277e518, 0xd30610f7, + 0x12317756, 0xd34dcdb4, 0x11eb7a9a, 0xd395f8ba, + 0x11a5ef90, 0xd3de9156, 0x1160d6e5, 0xd42796d5, + 0x111c3142, 0xd4710883, 0x10d7ff51, 0xd4bae5ab, + 0x109441bb, 0xd5052d97, 0x1050f926, 0xd54fdf8f, + 0x100e2639, 0xd59afadb, 0xfcbc999, 0xd5e67ec1, + 0xf89e3e8, 0xd6326a88, 0xf4875ca, 0xd67ebd74, + 0xf077fe1, 0xd6cb76c9, 0xec702cb, 0xd71895c9, + 0xe86ff2a, 0xd76619b6, 0xe47759a, 0xd7b401d1, + 0xe0866b8, 0xd8024d59, 0xdc9d320, 0xd850fb8e, + 0xd8bbb6d, 0xd8a00bae, 0xd4e2037, 0xd8ef7cf4, + 0xd110216, 0xd93f4e9e, 0xcd461a2, 0xd98f7fe6, + 0xc983f70, 0xd9e01006, 0xc5c9c14, 0xda30fe38, + 0xc217822, 0xda8249b4, 0xbe6d42b, 0xdad3f1b1, + 0xbacb0bf, 0xdb25f566, 0xb730e70, 0xdb785409, + 0xb39edca, 0xdbcb0cce, 0xb014f5b, 0xdc1e1ee9, + 0xac933ae, 0xdc71898d, 0xa919b4e, 0xdcc54bec, + 0xa5a86c4, 0xdd196538, 0xa23f698, 0xdd6dd4a2, + 0x9edeb50, 0xddc29958, 0x9b86572, 0xde17b28a, + 0x9836582, 0xde6d1f65, 0x94eec03, 0xdec2df18, + 0x91af976, 0xdf18f0ce, 0x8e78e5b, 0xdf6f53b3, + 0x8b4ab32, 0xdfc606f1, 0x8825077, 0xe01d09b4, + 0x8507ea7, 0xe0745b24, 0x81f363d, 0xe0cbfa6a, + 0x7ee77b3, 0xe123e6ad, 0x7be4381, 0xe17c1f15, + 0x78e9a1d, 0xe1d4a2c8, 0x75f7bfe, 0xe22d70eb, + 0x730e997, 0xe28688a4, 0x702e35c, 0xe2dfe917, + 0x6d569be, 0xe3399167, 0x6a87d2d, 0xe39380b6, + 0x67c1e18, 0xe3edb628, 0x6504ced, 0xe44830dd, + 0x6250a18, 0xe4a2eff6, 0x5fa5603, 0xe4fdf294, + 0x5d03118, 0xe55937d5, 0x5a69bbe, 0xe5b4bed8, + 0x57d965d, 0xe61086bc, 0x555215a, 0xe66c8e9f, + 0x52d3d18, 0xe6c8d59c, 0x505e9fb, 0xe7255ad1, + 0x4df2862, 0xe7821d59, 0x4b8f8ad, 0xe7df1c50, + 0x4935b3c, 0xe83c56cf, 0x46e5069, 0xe899cbf1, + 0x449d892, 0xe8f77acf, 0x425f410, 0xe9556282, + 0x402a33c, 0xe9b38223, 0x3dfe66c, 0xea11d8c8, + 0x3bdbdf6, 0xea70658a, 0x39c2a2f, 0xeacf277f, + 0x37b2b6a, 0xeb2e1dbe, 0x35ac1f7, 0xeb8d475b, + 0x33aee27, 0xebeca36c, 0x31bb049, 0xec4c3106, + 0x2fd08a9, 0xecabef3d, 0x2def794, 0xed0bdd25, + 0x2c17d52, 0xed6bf9d1, 0x2a49a2e, 0xedcc4454, + 0x2884e6e, 0xee2cbbc1, 0x26c9a58, 0xee8d5f29, + 0x2517e31, 0xeeee2d9d, 0x236fa3b, 0xef4f2630, + 0x21d0eb8, 0xefb047f2, 0x203bbe8, 0xf01191f3, + 0x1eb0209, 0xf0730342, 0x1d2e158, 0xf0d49af1, + 0x1bb5a11, 0xf136580d, 0x1a46c6e, 0xf19839a6, + 0x18e18a7, 0xf1fa3ecb, 0x1785ef4, 0xf25c6688, + 0x1633f8a, 0xf2beafed, 0x14eba9d, 0xf3211a07, + 0x13ad060, 0xf383a3e2, 0x1278104, 0xf3e64c8c, + 0x114ccb9, 0xf4491311, 0x102b3ac, 0xf4abf67e, + 0xf1360b, 0xf50ef5de, 0xe05401, 0xf572103d, + 0xd00db6, 0xf5d544a7, 0xc06355, 0xf6389228, + 0xb15502, 0xf69bf7c9, 0xa2e2e3, 0xf6ff7496, + 0x950d1d, 0xf7630799, 0x87d3d0, 0xf7c6afdc, + 0x7b371e, 0xf82a6c6a, 0x6f3726, 0xf88e3c4d, + 0x63d405, 0xf8f21e8e, 0x590dd8, 0xf9561237, + 0x4ee4b8, 0xf9ba1651, 0x4558c0, 0xfa1e29e5, + 0x3c6a07, 0xfa824bfd, 0x3418a2, 0xfae67ba2, + 0x2c64a6, 0xfb4ab7db, 0x254e27, 0xfbaeffb3, + 0x1ed535, 0xfc135231, 0x18f9e1, 0xfc77ae5e, + 0x13bc39, 0xfcdc1342, 0xf1c4a, 0xfd407fe6, + 0xb1a20, 0xfda4f351, 0x7b5c4, 0xfe096c8d, + 0x4ef3f, 0xfe6deaa1, 0x2c697, 0xfed26c94, + 0x13bd3, 0xff36f170, 0x4ef5, 0xff9b783c, + 0x0, 0x0, 0x4ef5, 0x6487c4, + 0x13bd3, 0xc90e90, 0x2c697, 0x12d936c, + 0x4ef3f, 0x192155f, 0x7b5c4, 0x1f69373, + 0xb1a20, 0x25b0caf, 0xf1c4a, 0x2bf801a, + 0x13bc39, 0x323ecbe, 0x18f9e1, 0x38851a2, + 0x1ed535, 0x3ecadcf, 0x254e27, 0x451004d, + 0x2c64a6, 0x4b54825, 0x3418a2, 0x519845e, + 0x3c6a07, 0x57db403, 0x4558c0, 0x5e1d61b, + 0x4ee4b8, 0x645e9af, 0x590dd8, 0x6a9edc9, + 0x63d405, 0x70de172, 0x6f3726, 0x771c3b3, + 0x7b371e, 0x7d59396, 0x87d3d0, 0x8395024, + 0x950d1d, 0x89cf867, 0xa2e2e3, 0x9008b6a, + 0xb15502, 0x9640837, 0xc06355, 0x9c76dd8, + 0xd00db6, 0xa2abb59, 0xe05401, 0xa8defc3, + 0xf1360b, 0xaf10a22, 0x102b3ac, 0xb540982, + 0x114ccb9, 0xbb6ecef, 0x1278104, 0xc19b374, + 0x13ad060, 0xc7c5c1e, 0x14eba9d, 0xcdee5f9, + 0x1633f8a, 0xd415013, 0x1785ef4, 0xda39978, + 0x18e18a7, 0xe05c135, 0x1a46c6e, 0xe67c65a, + 0x1bb5a11, 0xec9a7f3, 0x1d2e158, 0xf2b650f, + 0x1eb0209, 0xf8cfcbe, 0x203bbe8, 0xfee6e0d, + 0x21d0eb8, 0x104fb80e, 0x236fa3b, 0x10b0d9d0, + 0x2517e31, 0x1111d263, 0x26c9a58, 0x1172a0d7, + 0x2884e6e, 0x11d3443f, 0x2a49a2e, 0x1233bbac, + 0x2c17d52, 0x1294062f, 0x2def794, 0x12f422db, + 0x2fd08a9, 0x135410c3, 0x31bb049, 0x13b3cefa, + 0x33aee27, 0x14135c94, 0x35ac1f7, 0x1472b8a5, + 0x37b2b6a, 0x14d1e242, 0x39c2a2f, 0x1530d881, + 0x3bdbdf6, 0x158f9a76, 0x3dfe66c, 0x15ee2738, + 0x402a33c, 0x164c7ddd, 0x425f410, 0x16aa9d7e, + 0x449d892, 0x17088531, 0x46e5069, 0x1766340f, + 0x4935b3c, 0x17c3a931, 0x4b8f8ad, 0x1820e3b0, + 0x4df2862, 0x187de2a7, 0x505e9fb, 0x18daa52f, + 0x52d3d18, 0x19372a64, 0x555215a, 0x19937161, + 0x57d965d, 0x19ef7944, 0x5a69bbe, 0x1a4b4128, + 0x5d03118, 0x1aa6c82b, 0x5fa5603, 0x1b020d6c, + 0x6250a18, 0x1b5d100a, 0x6504ced, 0x1bb7cf23, + 0x67c1e18, 0x1c1249d8, 0x6a87d2d, 0x1c6c7f4a, + 0x6d569be, 0x1cc66e99, 0x702e35c, 0x1d2016e9, + 0x730e997, 0x1d79775c, 0x75f7bfe, 0x1dd28f15, + 0x78e9a1d, 0x1e2b5d38, 0x7be4381, 0x1e83e0eb, + 0x7ee77b3, 0x1edc1953, 0x81f363d, 0x1f340596, + 0x8507ea7, 0x1f8ba4dc, 0x8825077, 0x1fe2f64c, + 0x8b4ab32, 0x2039f90f, 0x8e78e5b, 0x2090ac4d, + 0x91af976, 0x20e70f32, 0x94eec03, 0x213d20e8, + 0x9836582, 0x2192e09b, 0x9b86572, 0x21e84d76, + 0x9edeb50, 0x223d66a8, 0xa23f698, 0x22922b5e, + 0xa5a86c4, 0x22e69ac8, 0xa919b4e, 0x233ab414, + 0xac933ae, 0x238e7673, 0xb014f5b, 0x23e1e117, + 0xb39edca, 0x2434f332, 0xb730e70, 0x2487abf7, + 0xbacb0bf, 0x24da0a9a, 0xbe6d42b, 0x252c0e4f, + 0xc217822, 0x257db64c, 0xc5c9c14, 0x25cf01c8, + 0xc983f70, 0x261feffa, 0xcd461a2, 0x2670801a, + 0xd110216, 0x26c0b162, 0xd4e2037, 0x2710830c, + 0xd8bbb6d, 0x275ff452, 0xdc9d320, 0x27af0472, + 0xe0866b8, 0x27fdb2a7, 0xe47759a, 0x284bfe2f, + 0xe86ff2a, 0x2899e64a, 0xec702cb, 0x28e76a37, + 0xf077fe1, 0x29348937, 0xf4875ca, 0x2981428c, + 0xf89e3e8, 0x29cd9578, 0xfcbc999, 0x2a19813f, + 0x100e2639, 0x2a650525, 0x1050f926, 0x2ab02071, + 0x109441bb, 0x2afad269, 0x10d7ff51, 0x2b451a55, + 0x111c3142, 0x2b8ef77d, 0x1160d6e5, 0x2bd8692b, + 0x11a5ef90, 0x2c216eaa, 0x11eb7a9a, 0x2c6a0746, + 0x12317756, 0x2cb2324c, 0x1277e518, 0x2cf9ef09, + 0x12bec333, 0x2d413ccd, 0x130610f7, 0x2d881ae8, + 0x134dcdb4, 0x2dce88aa, 0x1395f8ba, 0x2e148566, + 0x13de9156, 0x2e5a1070, 0x142796d5, 0x2e9f291b, + 0x14710883, 0x2ee3cebe, 0x14bae5ab, 0x2f2800af, + 0x15052d97, 0x2f6bbe45, 0x154fdf8f, 0x2faf06da, + 0x159afadb, 0x2ff1d9c7, 0x15e67ec1, 0x30343667, + 0x16326a88, 0x30761c18, 0x167ebd74, 0x30b78a36, + 0x16cb76c9, 0x30f8801f, 0x171895c9, 0x3138fd35, + 0x176619b6, 0x317900d6, 0x17b401d1, 0x31b88a66, + 0x18024d59, 0x31f79948, 0x1850fb8e, 0x32362ce0, + 0x18a00bae, 0x32744493, 0x18ef7cf4, 0x32b1dfc9, + 0x193f4e9e, 0x32eefdea, 0x198f7fe6, 0x332b9e5e, + 0x19e01006, 0x3367c090, 0x1a30fe38, 0x33a363ec, + 0x1a8249b4, 0x33de87de, 0x1ad3f1b1, 0x34192bd5, + 0x1b25f566, 0x34534f41, 0x1b785409, 0x348cf190, + 0x1bcb0cce, 0x34c61236, 0x1c1e1ee9, 0x34feb0a5, + 0x1c71898d, 0x3536cc52, 0x1cc54bec, 0x356e64b2, + 0x1d196538, 0x35a5793c, 0x1d6dd4a2, 0x35dc0968, + 0x1dc29958, 0x361214b0, 0x1e17b28a, 0x36479a8e, + 0x1e6d1f65, 0x367c9a7e, 0x1ec2df18, 0x36b113fd, + 0x1f18f0ce, 0x36e5068a, 0x1f6f53b3, 0x371871a5, + 0x1fc606f1, 0x374b54ce, 0x201d09b4, 0x377daf89, + 0x20745b24, 0x37af8159, 0x20cbfa6a, 0x37e0c9c3, + 0x2123e6ad, 0x3811884d, 0x217c1f15, 0x3841bc7f, + 0x21d4a2c8, 0x387165e3, 0x222d70eb, 0x38a08402, + 0x228688a4, 0x38cf1669, 0x22dfe917, 0x38fd1ca4, + 0x23399167, 0x392a9642, 0x239380b6, 0x395782d3, + 0x23edb628, 0x3983e1e8, 0x244830dd, 0x39afb313, + 0x24a2eff6, 0x39daf5e8, 0x24fdf294, 0x3a05a9fd, + 0x255937d5, 0x3a2fcee8, 0x25b4bed8, 0x3a596442, + 0x261086bc, 0x3a8269a3, 0x266c8e9f, 0x3aaadea6, + 0x26c8d59c, 0x3ad2c2e8, 0x27255ad1, 0x3afa1605, + 0x27821d59, 0x3b20d79e, 0x27df1c50, 0x3b470753, + 0x283c56cf, 0x3b6ca4c4, 0x2899cbf1, 0x3b91af97, + 0x28f77acf, 0x3bb6276e, 0x29556282, 0x3bda0bf0, + 0x29b38223, 0x3bfd5cc4, 0x2a11d8c8, 0x3c201994, + 0x2a70658a, 0x3c42420a, 0x2acf277f, 0x3c63d5d1, + 0x2b2e1dbe, 0x3c84d496, 0x2b8d475b, 0x3ca53e09, + 0x2beca36c, 0x3cc511d9, 0x2c4c3106, 0x3ce44fb7, + 0x2cabef3d, 0x3d02f757, 0x2d0bdd25, 0x3d21086c, + 0x2d6bf9d1, 0x3d3e82ae, 0x2dcc4454, 0x3d5b65d2, + 0x2e2cbbc1, 0x3d77b192, 0x2e8d5f29, 0x3d9365a8, + 0x2eee2d9d, 0x3dae81cf, 0x2f4f2630, 0x3dc905c5, + 0x2fb047f2, 0x3de2f148, 0x301191f3, 0x3dfc4418, + 0x30730342, 0x3e14fdf7, 0x30d49af1, 0x3e2d1ea8, + 0x3136580d, 0x3e44a5ef, 0x319839a6, 0x3e5b9392, + 0x31fa3ecb, 0x3e71e759, 0x325c6688, 0x3e87a10c, + 0x32beafed, 0x3e9cc076, 0x33211a07, 0x3eb14563, + 0x3383a3e2, 0x3ec52fa0, 0x33e64c8c, 0x3ed87efc, + 0x34491311, 0x3eeb3347, 0x34abf67e, 0x3efd4c54, + 0x350ef5de, 0x3f0ec9f5, 0x3572103d, 0x3f1fabff, + 0x35d544a7, 0x3f2ff24a, 0x36389228, 0x3f3f9cab, + 0x369bf7c9, 0x3f4eaafe, 0x36ff7496, 0x3f5d1d1d, + 0x37630799, 0x3f6af2e3, 0x37c6afdc, 0x3f782c30, + 0x382a6c6a, 0x3f84c8e2, 0x388e3c4d, 0x3f90c8da, + 0x38f21e8e, 0x3f9c2bfb, 0x39561237, 0x3fa6f228, + 0x39ba1651, 0x3fb11b48, 0x3a1e29e5, 0x3fbaa740, + 0x3a824bfd, 0x3fc395f9, 0x3ae67ba2, 0x3fcbe75e, + 0x3b4ab7db, 0x3fd39b5a, 0x3baeffb3, 0x3fdab1d9, + 0x3c135231, 0x3fe12acb, 0x3c77ae5e, 0x3fe7061f, + 0x3cdc1342, 0x3fec43c7, 0x3d407fe6, 0x3ff0e3b6, + 0x3da4f351, 0x3ff4e5e0, 0x3e096c8d, 0x3ff84a3c, + 0x3e6deaa1, 0x3ffb10c1, 0x3ed26c94, 0x3ffd3969, + 0x3f36f170, 0x3ffec42d, 0x3f9b783c, 0x3fffb10b +}; + + +/** +* \par +* Generation of realCoefBQ31 array: +* \par +* n = 512 +*
for (i = 0; i < n; i++)   
+* {   
+*    pBTable[2 * i] = 0.5 * (1.0 + sin (2 * PI / (double) (2 * n) * (double) i));   
+*    pBTable[2 * i + 1] = 0.5 * (1.0 * cos (2 * PI / (double) (2 * n) * (double) i));   
+* } 
+* \par +* Convert to fixed point Q31 format +* round(pBTable[i] * pow(2, 31)) +* +*/ + +const q31_t realCoefBQ31[1024] = { + 0x40000000, 0x40000000, 0x406487c4, 0x3fffb10b, + 0x40c90e90, 0x3ffec42d, 0x412d936c, 0x3ffd3969, + 0x4192155f, 0x3ffb10c1, 0x41f69373, 0x3ff84a3c, + 0x425b0caf, 0x3ff4e5e0, 0x42bf801a, 0x3ff0e3b6, + 0x4323ecbe, 0x3fec43c7, 0x438851a2, 0x3fe7061f, + 0x43ecadcf, 0x3fe12acb, 0x4451004d, 0x3fdab1d9, + 0x44b54825, 0x3fd39b5a, 0x4519845e, 0x3fcbe75e, + 0x457db403, 0x3fc395f9, 0x45e1d61b, 0x3fbaa740, + 0x4645e9af, 0x3fb11b48, 0x46a9edc9, 0x3fa6f228, + 0x470de172, 0x3f9c2bfb, 0x4771c3b3, 0x3f90c8da, + 0x47d59396, 0x3f84c8e2, 0x48395024, 0x3f782c30, + 0x489cf867, 0x3f6af2e3, 0x49008b6a, 0x3f5d1d1d, + 0x49640837, 0x3f4eaafe, 0x49c76dd8, 0x3f3f9cab, + 0x4a2abb59, 0x3f2ff24a, 0x4a8defc3, 0x3f1fabff, + 0x4af10a22, 0x3f0ec9f5, 0x4b540982, 0x3efd4c54, + 0x4bb6ecef, 0x3eeb3347, 0x4c19b374, 0x3ed87efc, + 0x4c7c5c1e, 0x3ec52fa0, 0x4cdee5f9, 0x3eb14563, + 0x4d415013, 0x3e9cc076, 0x4da39978, 0x3e87a10c, + 0x4e05c135, 0x3e71e759, 0x4e67c65a, 0x3e5b9392, + 0x4ec9a7f3, 0x3e44a5ef, 0x4f2b650f, 0x3e2d1ea8, + 0x4f8cfcbe, 0x3e14fdf7, 0x4fee6e0d, 0x3dfc4418, + 0x504fb80e, 0x3de2f148, 0x50b0d9d0, 0x3dc905c5, + 0x5111d263, 0x3dae81cf, 0x5172a0d7, 0x3d9365a8, + 0x51d3443f, 0x3d77b192, 0x5233bbac, 0x3d5b65d2, + 0x5294062f, 0x3d3e82ae, 0x52f422db, 0x3d21086c, + 0x535410c3, 0x3d02f757, 0x53b3cefa, 0x3ce44fb7, + 0x54135c94, 0x3cc511d9, 0x5472b8a5, 0x3ca53e09, + 0x54d1e242, 0x3c84d496, 0x5530d881, 0x3c63d5d1, + 0x558f9a76, 0x3c42420a, 0x55ee2738, 0x3c201994, + 0x564c7ddd, 0x3bfd5cc4, 0x56aa9d7e, 0x3bda0bf0, + 0x57088531, 0x3bb6276e, 0x5766340f, 0x3b91af97, + 0x57c3a931, 0x3b6ca4c4, 0x5820e3b0, 0x3b470753, + 0x587de2a7, 0x3b20d79e, 0x58daa52f, 0x3afa1605, + 0x59372a64, 0x3ad2c2e8, 0x59937161, 0x3aaadea6, + 0x59ef7944, 0x3a8269a3, 0x5a4b4128, 0x3a596442, + 0x5aa6c82b, 0x3a2fcee8, 0x5b020d6c, 0x3a05a9fd, + 0x5b5d100a, 0x39daf5e8, 0x5bb7cf23, 0x39afb313, + 0x5c1249d8, 0x3983e1e8, 0x5c6c7f4a, 0x395782d3, + 0x5cc66e99, 0x392a9642, 0x5d2016e9, 0x38fd1ca4, + 0x5d79775c, 0x38cf1669, 0x5dd28f15, 0x38a08402, + 0x5e2b5d38, 0x387165e3, 0x5e83e0eb, 0x3841bc7f, + 0x5edc1953, 0x3811884d, 0x5f340596, 0x37e0c9c3, + 0x5f8ba4dc, 0x37af8159, 0x5fe2f64c, 0x377daf89, + 0x6039f90f, 0x374b54ce, 0x6090ac4d, 0x371871a5, + 0x60e70f32, 0x36e5068a, 0x613d20e8, 0x36b113fd, + 0x6192e09b, 0x367c9a7e, 0x61e84d76, 0x36479a8e, + 0x623d66a8, 0x361214b0, 0x62922b5e, 0x35dc0968, + 0x62e69ac8, 0x35a5793c, 0x633ab414, 0x356e64b2, + 0x638e7673, 0x3536cc52, 0x63e1e117, 0x34feb0a5, + 0x6434f332, 0x34c61236, 0x6487abf7, 0x348cf190, + 0x64da0a9a, 0x34534f41, 0x652c0e4f, 0x34192bd5, + 0x657db64c, 0x33de87de, 0x65cf01c8, 0x33a363ec, + 0x661feffa, 0x3367c090, 0x6670801a, 0x332b9e5e, + 0x66c0b162, 0x32eefdea, 0x6710830c, 0x32b1dfc9, + 0x675ff452, 0x32744493, 0x67af0472, 0x32362ce0, + 0x67fdb2a7, 0x31f79948, 0x684bfe2f, 0x31b88a66, + 0x6899e64a, 0x317900d6, 0x68e76a37, 0x3138fd35, + 0x69348937, 0x30f8801f, 0x6981428c, 0x30b78a36, + 0x69cd9578, 0x30761c18, 0x6a19813f, 0x30343667, + 0x6a650525, 0x2ff1d9c7, 0x6ab02071, 0x2faf06da, + 0x6afad269, 0x2f6bbe45, 0x6b451a55, 0x2f2800af, + 0x6b8ef77d, 0x2ee3cebe, 0x6bd8692b, 0x2e9f291b, + 0x6c216eaa, 0x2e5a1070, 0x6c6a0746, 0x2e148566, + 0x6cb2324c, 0x2dce88aa, 0x6cf9ef09, 0x2d881ae8, + 0x6d413ccd, 0x2d413ccd, 0x6d881ae8, 0x2cf9ef09, + 0x6dce88aa, 0x2cb2324c, 0x6e148566, 0x2c6a0746, + 0x6e5a1070, 0x2c216eaa, 0x6e9f291b, 0x2bd8692b, + 0x6ee3cebe, 0x2b8ef77d, 0x6f2800af, 0x2b451a55, + 0x6f6bbe45, 0x2afad269, 0x6faf06da, 0x2ab02071, + 0x6ff1d9c7, 0x2a650525, 0x70343667, 0x2a19813f, + 0x70761c18, 0x29cd9578, 0x70b78a36, 0x2981428c, + 0x70f8801f, 0x29348937, 0x7138fd35, 0x28e76a37, + 0x717900d6, 0x2899e64a, 0x71b88a66, 0x284bfe2f, + 0x71f79948, 0x27fdb2a7, 0x72362ce0, 0x27af0472, + 0x72744493, 0x275ff452, 0x72b1dfc9, 0x2710830c, + 0x72eefdea, 0x26c0b162, 0x732b9e5e, 0x2670801a, + 0x7367c090, 0x261feffa, 0x73a363ec, 0x25cf01c8, + 0x73de87de, 0x257db64c, 0x74192bd5, 0x252c0e4f, + 0x74534f41, 0x24da0a9a, 0x748cf190, 0x2487abf7, + 0x74c61236, 0x2434f332, 0x74feb0a5, 0x23e1e117, + 0x7536cc52, 0x238e7673, 0x756e64b2, 0x233ab414, + 0x75a5793c, 0x22e69ac8, 0x75dc0968, 0x22922b5e, + 0x761214b0, 0x223d66a8, 0x76479a8e, 0x21e84d76, + 0x767c9a7e, 0x2192e09b, 0x76b113fd, 0x213d20e8, + 0x76e5068a, 0x20e70f32, 0x771871a5, 0x2090ac4d, + 0x774b54ce, 0x2039f90f, 0x777daf89, 0x1fe2f64c, + 0x77af8159, 0x1f8ba4dc, 0x77e0c9c3, 0x1f340596, + 0x7811884d, 0x1edc1953, 0x7841bc7f, 0x1e83e0eb, + 0x787165e3, 0x1e2b5d38, 0x78a08402, 0x1dd28f15, + 0x78cf1669, 0x1d79775c, 0x78fd1ca4, 0x1d2016e9, + 0x792a9642, 0x1cc66e99, 0x795782d3, 0x1c6c7f4a, + 0x7983e1e8, 0x1c1249d8, 0x79afb313, 0x1bb7cf23, + 0x79daf5e8, 0x1b5d100a, 0x7a05a9fd, 0x1b020d6c, + 0x7a2fcee8, 0x1aa6c82b, 0x7a596442, 0x1a4b4128, + 0x7a8269a3, 0x19ef7944, 0x7aaadea6, 0x19937161, + 0x7ad2c2e8, 0x19372a64, 0x7afa1605, 0x18daa52f, + 0x7b20d79e, 0x187de2a7, 0x7b470753, 0x1820e3b0, + 0x7b6ca4c4, 0x17c3a931, 0x7b91af97, 0x1766340f, + 0x7bb6276e, 0x17088531, 0x7bda0bf0, 0x16aa9d7e, + 0x7bfd5cc4, 0x164c7ddd, 0x7c201994, 0x15ee2738, + 0x7c42420a, 0x158f9a76, 0x7c63d5d1, 0x1530d881, + 0x7c84d496, 0x14d1e242, 0x7ca53e09, 0x1472b8a5, + 0x7cc511d9, 0x14135c94, 0x7ce44fb7, 0x13b3cefa, + 0x7d02f757, 0x135410c3, 0x7d21086c, 0x12f422db, + 0x7d3e82ae, 0x1294062f, 0x7d5b65d2, 0x1233bbac, + 0x7d77b192, 0x11d3443f, 0x7d9365a8, 0x1172a0d7, + 0x7dae81cf, 0x1111d263, 0x7dc905c5, 0x10b0d9d0, + 0x7de2f148, 0x104fb80e, 0x7dfc4418, 0xfee6e0d, + 0x7e14fdf7, 0xf8cfcbe, 0x7e2d1ea8, 0xf2b650f, + 0x7e44a5ef, 0xec9a7f3, 0x7e5b9392, 0xe67c65a, + 0x7e71e759, 0xe05c135, 0x7e87a10c, 0xda39978, + 0x7e9cc076, 0xd415013, 0x7eb14563, 0xcdee5f9, + 0x7ec52fa0, 0xc7c5c1e, 0x7ed87efc, 0xc19b374, + 0x7eeb3347, 0xbb6ecef, 0x7efd4c54, 0xb540982, + 0x7f0ec9f5, 0xaf10a22, 0x7f1fabff, 0xa8defc3, + 0x7f2ff24a, 0xa2abb59, 0x7f3f9cab, 0x9c76dd8, + 0x7f4eaafe, 0x9640837, 0x7f5d1d1d, 0x9008b6a, + 0x7f6af2e3, 0x89cf867, 0x7f782c30, 0x8395024, + 0x7f84c8e2, 0x7d59396, 0x7f90c8da, 0x771c3b3, + 0x7f9c2bfb, 0x70de172, 0x7fa6f228, 0x6a9edc9, + 0x7fb11b48, 0x645e9af, 0x7fbaa740, 0x5e1d61b, + 0x7fc395f9, 0x57db403, 0x7fcbe75e, 0x519845e, + 0x7fd39b5a, 0x4b54825, 0x7fdab1d9, 0x451004d, + 0x7fe12acb, 0x3ecadcf, 0x7fe7061f, 0x38851a2, + 0x7fec43c7, 0x323ecbe, 0x7ff0e3b6, 0x2bf801a, + 0x7ff4e5e0, 0x25b0caf, 0x7ff84a3c, 0x1f69373, + 0x7ffb10c1, 0x192155f, 0x7ffd3969, 0x12d936c, + 0x7ffec42d, 0xc90e90, 0x7fffb10b, 0x6487c4, + 0x7fffffff, 0x0, 0x7fffb10b, 0xff9b783c, + 0x7ffec42d, 0xff36f170, 0x7ffd3969, 0xfed26c94, + 0x7ffb10c1, 0xfe6deaa1, 0x7ff84a3c, 0xfe096c8d, + 0x7ff4e5e0, 0xfda4f351, 0x7ff0e3b6, 0xfd407fe6, + 0x7fec43c7, 0xfcdc1342, 0x7fe7061f, 0xfc77ae5e, + 0x7fe12acb, 0xfc135231, 0x7fdab1d9, 0xfbaeffb3, + 0x7fd39b5a, 0xfb4ab7db, 0x7fcbe75e, 0xfae67ba2, + 0x7fc395f9, 0xfa824bfd, 0x7fbaa740, 0xfa1e29e5, + 0x7fb11b48, 0xf9ba1651, 0x7fa6f228, 0xf9561237, + 0x7f9c2bfb, 0xf8f21e8e, 0x7f90c8da, 0xf88e3c4d, + 0x7f84c8e2, 0xf82a6c6a, 0x7f782c30, 0xf7c6afdc, + 0x7f6af2e3, 0xf7630799, 0x7f5d1d1d, 0xf6ff7496, + 0x7f4eaafe, 0xf69bf7c9, 0x7f3f9cab, 0xf6389228, + 0x7f2ff24a, 0xf5d544a7, 0x7f1fabff, 0xf572103d, + 0x7f0ec9f5, 0xf50ef5de, 0x7efd4c54, 0xf4abf67e, + 0x7eeb3347, 0xf4491311, 0x7ed87efc, 0xf3e64c8c, + 0x7ec52fa0, 0xf383a3e2, 0x7eb14563, 0xf3211a07, + 0x7e9cc076, 0xf2beafed, 0x7e87a10c, 0xf25c6688, + 0x7e71e759, 0xf1fa3ecb, 0x7e5b9392, 0xf19839a6, + 0x7e44a5ef, 0xf136580d, 0x7e2d1ea8, 0xf0d49af1, + 0x7e14fdf7, 0xf0730342, 0x7dfc4418, 0xf01191f3, + 0x7de2f148, 0xefb047f2, 0x7dc905c5, 0xef4f2630, + 0x7dae81cf, 0xeeee2d9d, 0x7d9365a8, 0xee8d5f29, + 0x7d77b192, 0xee2cbbc1, 0x7d5b65d2, 0xedcc4454, + 0x7d3e82ae, 0xed6bf9d1, 0x7d21086c, 0xed0bdd25, + 0x7d02f757, 0xecabef3d, 0x7ce44fb7, 0xec4c3106, + 0x7cc511d9, 0xebeca36c, 0x7ca53e09, 0xeb8d475b, + 0x7c84d496, 0xeb2e1dbe, 0x7c63d5d1, 0xeacf277f, + 0x7c42420a, 0xea70658a, 0x7c201994, 0xea11d8c8, + 0x7bfd5cc4, 0xe9b38223, 0x7bda0bf0, 0xe9556282, + 0x7bb6276e, 0xe8f77acf, 0x7b91af97, 0xe899cbf1, + 0x7b6ca4c4, 0xe83c56cf, 0x7b470753, 0xe7df1c50, + 0x7b20d79e, 0xe7821d59, 0x7afa1605, 0xe7255ad1, + 0x7ad2c2e8, 0xe6c8d59c, 0x7aaadea6, 0xe66c8e9f, + 0x7a8269a3, 0xe61086bc, 0x7a596442, 0xe5b4bed8, + 0x7a2fcee8, 0xe55937d5, 0x7a05a9fd, 0xe4fdf294, + 0x79daf5e8, 0xe4a2eff6, 0x79afb313, 0xe44830dd, + 0x7983e1e8, 0xe3edb628, 0x795782d3, 0xe39380b6, + 0x792a9642, 0xe3399167, 0x78fd1ca4, 0xe2dfe917, + 0x78cf1669, 0xe28688a4, 0x78a08402, 0xe22d70eb, + 0x787165e3, 0xe1d4a2c8, 0x7841bc7f, 0xe17c1f15, + 0x7811884d, 0xe123e6ad, 0x77e0c9c3, 0xe0cbfa6a, + 0x77af8159, 0xe0745b24, 0x777daf89, 0xe01d09b4, + 0x774b54ce, 0xdfc606f1, 0x771871a5, 0xdf6f53b3, + 0x76e5068a, 0xdf18f0ce, 0x76b113fd, 0xdec2df18, + 0x767c9a7e, 0xde6d1f65, 0x76479a8e, 0xde17b28a, + 0x761214b0, 0xddc29958, 0x75dc0968, 0xdd6dd4a2, + 0x75a5793c, 0xdd196538, 0x756e64b2, 0xdcc54bec, + 0x7536cc52, 0xdc71898d, 0x74feb0a5, 0xdc1e1ee9, + 0x74c61236, 0xdbcb0cce, 0x748cf190, 0xdb785409, + 0x74534f41, 0xdb25f566, 0x74192bd5, 0xdad3f1b1, + 0x73de87de, 0xda8249b4, 0x73a363ec, 0xda30fe38, + 0x7367c090, 0xd9e01006, 0x732b9e5e, 0xd98f7fe6, + 0x72eefdea, 0xd93f4e9e, 0x72b1dfc9, 0xd8ef7cf4, + 0x72744493, 0xd8a00bae, 0x72362ce0, 0xd850fb8e, + 0x71f79948, 0xd8024d59, 0x71b88a66, 0xd7b401d1, + 0x717900d6, 0xd76619b6, 0x7138fd35, 0xd71895c9, + 0x70f8801f, 0xd6cb76c9, 0x70b78a36, 0xd67ebd74, + 0x70761c18, 0xd6326a88, 0x70343667, 0xd5e67ec1, + 0x6ff1d9c7, 0xd59afadb, 0x6faf06da, 0xd54fdf8f, + 0x6f6bbe45, 0xd5052d97, 0x6f2800af, 0xd4bae5ab, + 0x6ee3cebe, 0xd4710883, 0x6e9f291b, 0xd42796d5, + 0x6e5a1070, 0xd3de9156, 0x6e148566, 0xd395f8ba, + 0x6dce88aa, 0xd34dcdb4, 0x6d881ae8, 0xd30610f7, + 0x6d413ccd, 0xd2bec333, 0x6cf9ef09, 0xd277e518, + 0x6cb2324c, 0xd2317756, 0x6c6a0746, 0xd1eb7a9a, + 0x6c216eaa, 0xd1a5ef90, 0x6bd8692b, 0xd160d6e5, + 0x6b8ef77d, 0xd11c3142, 0x6b451a55, 0xd0d7ff51, + 0x6afad269, 0xd09441bb, 0x6ab02071, 0xd050f926, + 0x6a650525, 0xd00e2639, 0x6a19813f, 0xcfcbc999, + 0x69cd9578, 0xcf89e3e8, 0x6981428c, 0xcf4875ca, + 0x69348937, 0xcf077fe1, 0x68e76a37, 0xcec702cb, + 0x6899e64a, 0xce86ff2a, 0x684bfe2f, 0xce47759a, + 0x67fdb2a7, 0xce0866b8, 0x67af0472, 0xcdc9d320, + 0x675ff452, 0xcd8bbb6d, 0x6710830c, 0xcd4e2037, + 0x66c0b162, 0xcd110216, 0x6670801a, 0xccd461a2, + 0x661feffa, 0xcc983f70, 0x65cf01c8, 0xcc5c9c14, + 0x657db64c, 0xcc217822, 0x652c0e4f, 0xcbe6d42b, + 0x64da0a9a, 0xcbacb0bf, 0x6487abf7, 0xcb730e70, + 0x6434f332, 0xcb39edca, 0x63e1e117, 0xcb014f5b, + 0x638e7673, 0xcac933ae, 0x633ab414, 0xca919b4e, + 0x62e69ac8, 0xca5a86c4, 0x62922b5e, 0xca23f698, + 0x623d66a8, 0xc9edeb50, 0x61e84d76, 0xc9b86572, + 0x6192e09b, 0xc9836582, 0x613d20e8, 0xc94eec03, + 0x60e70f32, 0xc91af976, 0x6090ac4d, 0xc8e78e5b, + 0x6039f90f, 0xc8b4ab32, 0x5fe2f64c, 0xc8825077, + 0x5f8ba4dc, 0xc8507ea7, 0x5f340596, 0xc81f363d, + 0x5edc1953, 0xc7ee77b3, 0x5e83e0eb, 0xc7be4381, + 0x5e2b5d38, 0xc78e9a1d, 0x5dd28f15, 0xc75f7bfe, + 0x5d79775c, 0xc730e997, 0x5d2016e9, 0xc702e35c, + 0x5cc66e99, 0xc6d569be, 0x5c6c7f4a, 0xc6a87d2d, + 0x5c1249d8, 0xc67c1e18, 0x5bb7cf23, 0xc6504ced, + 0x5b5d100a, 0xc6250a18, 0x5b020d6c, 0xc5fa5603, + 0x5aa6c82b, 0xc5d03118, 0x5a4b4128, 0xc5a69bbe, + 0x59ef7944, 0xc57d965d, 0x59937161, 0xc555215a, + 0x59372a64, 0xc52d3d18, 0x58daa52f, 0xc505e9fb, + 0x587de2a7, 0xc4df2862, 0x5820e3b0, 0xc4b8f8ad, + 0x57c3a931, 0xc4935b3c, 0x5766340f, 0xc46e5069, + 0x57088531, 0xc449d892, 0x56aa9d7e, 0xc425f410, + 0x564c7ddd, 0xc402a33c, 0x55ee2738, 0xc3dfe66c, + 0x558f9a76, 0xc3bdbdf6, 0x5530d881, 0xc39c2a2f, + 0x54d1e242, 0xc37b2b6a, 0x5472b8a5, 0xc35ac1f7, + 0x54135c94, 0xc33aee27, 0x53b3cefa, 0xc31bb049, + 0x535410c3, 0xc2fd08a9, 0x52f422db, 0xc2def794, + 0x5294062f, 0xc2c17d52, 0x5233bbac, 0xc2a49a2e, + 0x51d3443f, 0xc2884e6e, 0x5172a0d7, 0xc26c9a58, + 0x5111d263, 0xc2517e31, 0x50b0d9d0, 0xc236fa3b, + 0x504fb80e, 0xc21d0eb8, 0x4fee6e0d, 0xc203bbe8, + 0x4f8cfcbe, 0xc1eb0209, 0x4f2b650f, 0xc1d2e158, + 0x4ec9a7f3, 0xc1bb5a11, 0x4e67c65a, 0xc1a46c6e, + 0x4e05c135, 0xc18e18a7, 0x4da39978, 0xc1785ef4, + 0x4d415013, 0xc1633f8a, 0x4cdee5f9, 0xc14eba9d, + 0x4c7c5c1e, 0xc13ad060, 0x4c19b374, 0xc1278104, + 0x4bb6ecef, 0xc114ccb9, 0x4b540982, 0xc102b3ac, + 0x4af10a22, 0xc0f1360b, 0x4a8defc3, 0xc0e05401, + 0x4a2abb59, 0xc0d00db6, 0x49c76dd8, 0xc0c06355, + 0x49640837, 0xc0b15502, 0x49008b6a, 0xc0a2e2e3, + 0x489cf867, 0xc0950d1d, 0x48395024, 0xc087d3d0, + 0x47d59396, 0xc07b371e, 0x4771c3b3, 0xc06f3726, + 0x470de172, 0xc063d405, 0x46a9edc9, 0xc0590dd8, + 0x4645e9af, 0xc04ee4b8, 0x45e1d61b, 0xc04558c0, + 0x457db403, 0xc03c6a07, 0x4519845e, 0xc03418a2, + 0x44b54825, 0xc02c64a6, 0x4451004d, 0xc0254e27, + 0x43ecadcf, 0xc01ed535, 0x438851a2, 0xc018f9e1, + 0x4323ecbe, 0xc013bc39, 0x42bf801a, 0xc00f1c4a, + 0x425b0caf, 0xc00b1a20, 0x41f69373, 0xc007b5c4, + 0x4192155f, 0xc004ef3f, 0x412d936c, 0xc002c697, + 0x40c90e90, 0xc0013bd3, 0x406487c4, 0xc0004ef5 +}; + +/** +* @brief Initialization function for the Q31 RFFT/RIFFT. +* @param[in, out] *S points to an instance of the Q31 RFFT/RIFFT structure. +* @param[in, out] *S_CFFT points to an instance of the Q31 CFFT/CIFFT structure. +* @param[in] fftLenReal length of the FFT. +* @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. +* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. +* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. +* +* \par Description: +* \par +* The parameter fftLenReal Specifies length of RFFT/RIFFT Process. Supported FFT Lengths are 128, 512, 2048. +* \par +* The parameter ifftFlagR controls whether a forward or inverse transform is computed. +* Set(=1) ifftFlagR to calculate RIFFT, otherwise RFFT is calculated. +* \par +* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. +* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. +* \par +* This function also initializes Twiddle factor table. +*/ + +arm_status arm_rfft_init_q31( + arm_rfft_instance_q31 * S, + arm_cfft_radix4_instance_q31 * S_CFFT, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag) +{ + /* Initialise the default arm status */ + arm_status status = ARM_MATH_SUCCESS; + + /* Initialize the Real FFT length */ + S->fftLenReal = (uint16_t) fftLenReal; + + /* Initialize the Complex FFT length */ + S->fftLenBy2 = (uint16_t) fftLenReal / 2u; + + /* Initialize the Twiddle coefficientA pointer */ + S->pTwiddleAReal = (q31_t *) realCoefAQ31; + + /* Initialize the Twiddle coefficientB pointer */ + S->pTwiddleBReal = (q31_t *) realCoefBQ31; + + /* Initialize the Flag for selection of RFFT or RIFFT */ + S->ifftFlagR = (uint8_t) ifftFlagR; + + /* Initialize the Flag for calculation Bit reversal or not */ + S->bitReverseFlagR = (uint8_t) bitReverseFlag; + + /* Initialization of coef modifier depending on the FFT length */ + switch (S->fftLenReal) + { + case 512u: + S->twidCoefRModifier = 2u; + break; + case 128u: + S->twidCoefRModifier = 8u; + break; + default: + /* Reporting argument error if rfftSize is not valid value */ + status = ARM_MATH_ARGUMENT_ERROR; + break; + } + + /* Init Complex FFT Instance */ + S->pCfft = S_CFFT; + + if(S->ifftFlagR) + { + /* Initializes the CIFFT Module for fftLenreal/2 length */ + arm_cfft_radix4_init_q31(S->pCfft, (uint16_t) S->fftLenBy2, 1u, 1u); + } + else + { + /* Initializes the CFFT Module for fftLenreal/2 length */ + arm_cfft_radix4_init_q31(S->pCfft, (uint16_t) S->fftLenBy2, 0u, 1u); + } + + /* return the status of RFFT Init function */ + return (status); + +} + + /** + * @} end of RFFT_RIFFT group + */ diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_q15.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_q15.c index cf8e09ea5..dabde5993 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_q15.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_q15.c @@ -1,457 +1,457 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_q15.c -* -* Description: RFFT & RIFFT Q15 process function -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/*-------------------------------------------------------------------- -* Internal functions prototypes ---------------------------------------------------------------------*/ - -void arm_split_rfft_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pATable, - q15_t * pBTable, - q15_t * pDst, - uint32_t modifier); - -void arm_split_rifft_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pATable, - q15_t * pBTable, - q15_t * pDst, - uint32_t modifier); - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - -/** - * @brief Processing function for the Q15 RFFT/RIFFT. - * @param[in] *S points to an instance of the Q15 RFFT/RIFFT structure. - * @param[in] *pSrc points to the input buffer. - * @param[out] *pDst points to the output buffer. - * @return none. - * - * \par Input an output formats: - * \par - * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. - * Hence the output format is different for different RFFT sizes. - * The input and output formats for different RFFT sizes and number of bits to upscale are mentioned in the tables below for RFFT and RIFFT: - * \par - * \image html RFFTQ15.gif "Input and Output Formats for Q15 RFFT" - * \par - * \image html RIFFTQ15.gif "Input and Output Formats for Q15 RIFFT" - */ - -void arm_rfft_q15( - const arm_rfft_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst) -{ - const arm_cfft_radix4_instance_q15 *S_CFFT = S->pCfft; - - /* Calculation of RIFFT of input */ - if(S->ifftFlagR == 1u) - { - /* Real IFFT core process */ - arm_split_rifft_q15(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - - /* Complex readix-4 IFFT process */ - arm_radix4_butterfly_inverse_q15(pDst, S_CFFT->fftLen, - S_CFFT->pTwiddle, - S_CFFT->twidCoefModifier); - - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_q15(pDst, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - } - else - { - /* Calculation of RFFT of input */ - - /* Complex readix-4 FFT process */ - arm_radix4_butterfly_q15(pSrc, S_CFFT->fftLen, - S_CFFT->pTwiddle, S_CFFT->twidCoefModifier); - - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_q15(pSrc, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - - arm_split_rfft_q15(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - } - -} - - /** - * @} end of RFFT_RIFFT group - */ - -/** - * @brief Core Real FFT process - * @param *pSrc points to the input buffer. - * @param fftLen length of FFT. - * @param *pATable points to the A twiddle Coef buffer. - * @param *pBTable points to the B twiddle Coef buffer. - * @param *pDst points to the output buffer. - * @param modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - * The function implements a Real FFT - */ - -void arm_split_rfft_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pATable, - q15_t * pBTable, - q15_t * pDst, - uint32_t modifier) -{ - uint32_t i; /* Loop Counter */ - q31_t outR, outI; /* Temporary variables for output */ - q15_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - q15_t *pSrc1, *pSrc2; - - - pSrc[2u * fftLen] = pSrc[0]; - pSrc[(2u * fftLen) + 1u] = pSrc[1]; - - pCoefA = &pATable[modifier * 2u]; - pCoefB = &pBTable[modifier * 2u]; - - pSrc1 = &pSrc[2]; - pSrc2 = &pSrc[(2u * fftLen) - 2u]; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - i = 1u; - - while(i < fftLen) - { - /* - outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] - + pSrc[2 * n - 2 * i] * pBTable[2 * i] + - pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - */ - - /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); */ - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] */ - outR = __SMUSD(*__SIMD32(pSrc1), *__SIMD32(pCoefA)); - -#else - - /* -(pSrc[2 * i + 1] * pATable[2 * i + 1] - pSrc[2 * i] * pATable[2 * i]) */ - outR = -(__SMUSD(*__SIMD32(pSrc1), *__SIMD32(pCoefA))); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* pSrc[2 * n - 2 * i] * pBTable[2 * i] + - pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]) */ - outR = __SMLAD(*__SIMD32(pSrc2), *__SIMD32(pCoefB), outR) >> 15u; - - /* pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ - -#ifndef ARM_MATH_BIG_ENDIAN - - outI = __SMUSDX(*__SIMD32(pSrc2)--, *__SIMD32(pCoefB)); - -#else - - outI = __SMUSDX(*__SIMD32(pCoefB), *__SIMD32(pSrc2)--); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] */ - outI = __SMLADX(*__SIMD32(pSrc1)++, *__SIMD32(pCoefA), outI); - - /* write output */ - pDst[2u * i] = (q15_t) outR; - pDst[(2u * i) + 1u] = outI >> 15u; - - /* write complex conjugate output */ - pDst[(4u * fftLen) - (2u * i)] = (q15_t) outR; - pDst[((4u * fftLen) - (2u * i)) + 1u] = -(outI >> 15u); - - /* update coefficient pointer */ - pCoefB = pCoefB + (2u * modifier); - pCoefA = pCoefA + (2u * modifier); - - i++; - - } - - pDst[2u * fftLen] = pSrc[0] - pSrc[1]; - pDst[(2u * fftLen) + 1u] = 0; - - pDst[0] = pSrc[0] + pSrc[1]; - pDst[1] = 0; - - -#else - - /* Run the below code for Cortex-M0 */ - - i = 1u; - - while(i < fftLen) - { - /* - outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] - + pSrc[2 * n - 2 * i] * pBTable[2 * i] + - pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - */ - - outR = *pSrc1 * *pCoefA; - outR = outR - (*(pSrc1 + 1) * *(pCoefA + 1)); - outR = outR + (*pSrc2 * *pCoefB); - outR = (outR + (*(pSrc2 + 1) * *(pCoefB + 1))) >> 15; - - - /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); - */ - - outI = *pSrc2 * *(pCoefB + 1); - outI = outI - (*(pSrc2 + 1) * *pCoefB); - outI = outI + (*(pSrc1 + 1) * *pCoefA); - outI = outI + (*pSrc1 * *(pCoefA + 1)); - - /* update input pointers */ - pSrc1 += 2u; - pSrc2 -= 2u; - - /* write output */ - pDst[2u * i] = (q15_t) outR; - pDst[(2u * i) + 1u] = outI >> 15u; - - /* write complex conjugate output */ - pDst[(4u * fftLen) - (2u * i)] = (q15_t) outR; - pDst[((4u * fftLen) - (2u * i)) + 1u] = -(outI >> 15u); - - /* update coefficient pointer */ - pCoefB = pCoefB + (2u * modifier); - pCoefA = pCoefA + (2u * modifier); - - i++; - - } - - pDst[2u * fftLen] = pSrc[0] - pSrc[1]; - pDst[(2u * fftLen) + 1u] = 0; - - pDst[0] = pSrc[0] + pSrc[1]; - pDst[1] = 0; - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - -/** - * @brief Core Real IFFT process - * @param[in] *pSrc points to the input buffer. - * @param[in] fftLen length of FFT. - * @param[in] *pATable points to the twiddle Coef A buffer. - * @param[in] *pBTable points to the twiddle Coef B buffer. - * @param[out] *pDst points to the output buffer. - * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - * The function implements a Real IFFT - */ -void arm_split_rifft_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pATable, - q15_t * pBTable, - q15_t * pDst, - uint32_t modifier) -{ - uint32_t i; /* Loop Counter */ - q31_t outR, outI; /* Temporary variables for output */ - q15_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - q15_t *pSrc1, *pSrc2; - q15_t *pDst1 = &pDst[0]; - - pCoefA = &pATable[0]; - pCoefB = &pBTable[0]; - - pSrc1 = &pSrc[0]; - pSrc2 = &pSrc[2u * fftLen]; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - i = fftLen; - - while(i > 0u) - { - - /* - outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - - outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); - - */ - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* pIn[2 * n - 2 * i] * pBTable[2 * i] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]) */ - outR = __SMUSD(*__SIMD32(pSrc2), *__SIMD32(pCoefB)); - -#else - - /* -(-pIn[2 * n - 2 * i] * pBTable[2 * i] + - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1])) */ - outR = -(__SMUSD(*__SIMD32(pSrc2), *__SIMD32(pCoefB))); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i] */ - outR = __SMLAD(*__SIMD32(pSrc1), *__SIMD32(pCoefA), outR) >> 15u; - - /* - -pIn[2 * n - 2 * i] * pBTable[2 * i + 1] + - pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ - outI = __SMUADX(*__SIMD32(pSrc2)--, *__SIMD32(pCoefB)); - - /* pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] */ - -#ifndef ARM_MATH_BIG_ENDIAN - - outI = __SMLSDX(*__SIMD32(pCoefA), *__SIMD32(pSrc1)++, -outI); - -#else - - outI = __SMLSDX(*__SIMD32(pSrc1)++, *__SIMD32(pCoefA), -outI); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - /* write output */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst1)++ = __PKHBT(outR, (outI >> 15u), 16); - -#else - - *__SIMD32(pDst1)++ = __PKHBT((outI >> 15u), outR, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* update coefficient pointer */ - pCoefB = pCoefB + (2u * modifier); - pCoefA = pCoefA + (2u * modifier); - - i--; - - } - - -#else - - /* Run the below code for Cortex-M0 */ - - i = fftLen; - - while(i > 0u) - { - - /* - outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - */ - - outR = *pSrc2 * *pCoefB; - outR = outR - (*(pSrc2 + 1) * *(pCoefB + 1)); - outR = outR + (*pSrc1 * *pCoefA); - outR = (outR + (*(pSrc1 + 1) * *(pCoefA + 1))) >> 15; - - /* - outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); - */ - - outI = *(pSrc1 + 1) * *pCoefA; - outI = outI - (*pSrc1 * *(pCoefA + 1)); - outI = outI - (*pSrc2 * *(pCoefB + 1)); - outI = outI - (*(pSrc2 + 1) * *(pCoefB)); - - /* update input pointers */ - pSrc1 += 2u; - pSrc2 -= 2u; - - /* write output */ - *pDst1++ = (q15_t) outR; - *pDst1++ = (q15_t) (outI >> 15); - - /* update coefficient pointer */ - pCoefB = pCoefB + (2u * modifier); - pCoefA = pCoefA + (2u * modifier); - - i--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_rfft_q15.c +* +* Description: RFFT & RIFFT Q15 process function +* +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + + +#include "arm_math.h" + +/*-------------------------------------------------------------------- +* Internal functions prototypes +--------------------------------------------------------------------*/ + +void arm_split_rfft_q15( + q15_t * pSrc, + uint32_t fftLen, + q15_t * pATable, + q15_t * pBTable, + q15_t * pDst, + uint32_t modifier); + +void arm_split_rifft_q15( + q15_t * pSrc, + uint32_t fftLen, + q15_t * pATable, + q15_t * pBTable, + q15_t * pDst, + uint32_t modifier); + +/** + * @addtogroup RFFT_RIFFT + * @{ + */ + +/** + * @brief Processing function for the Q15 RFFT/RIFFT. + * @param[in] *S points to an instance of the Q15 RFFT/RIFFT structure. + * @param[in] *pSrc points to the input buffer. + * @param[out] *pDst points to the output buffer. + * @return none. + * + * \par Input an output formats: + * \par + * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. + * Hence the output format is different for different RFFT sizes. + * The input and output formats for different RFFT sizes and number of bits to upscale are mentioned in the tables below for RFFT and RIFFT: + * \par + * \image html RFFTQ15.gif "Input and Output Formats for Q15 RFFT" + * \par + * \image html RIFFTQ15.gif "Input and Output Formats for Q15 RIFFT" + */ + +void arm_rfft_q15( + const arm_rfft_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst) +{ + const arm_cfft_radix4_instance_q15 *S_CFFT = S->pCfft; + + /* Calculation of RIFFT of input */ + if(S->ifftFlagR == 1u) + { + /* Real IFFT core process */ + arm_split_rifft_q15(pSrc, S->fftLenBy2, S->pTwiddleAReal, + S->pTwiddleBReal, pDst, S->twidCoefRModifier); + + /* Complex readix-4 IFFT process */ + arm_radix4_butterfly_inverse_q15(pDst, S_CFFT->fftLen, + S_CFFT->pTwiddle, + S_CFFT->twidCoefModifier); + + /* Bit reversal process */ + if(S->bitReverseFlagR == 1u) + { + arm_bitreversal_q15(pDst, S_CFFT->fftLen, + S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); + } + } + else + { + /* Calculation of RFFT of input */ + + /* Complex readix-4 FFT process */ + arm_radix4_butterfly_q15(pSrc, S_CFFT->fftLen, + S_CFFT->pTwiddle, S_CFFT->twidCoefModifier); + + /* Bit reversal process */ + if(S->bitReverseFlagR == 1u) + { + arm_bitreversal_q15(pSrc, S_CFFT->fftLen, + S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); + } + + arm_split_rfft_q15(pSrc, S->fftLenBy2, S->pTwiddleAReal, + S->pTwiddleBReal, pDst, S->twidCoefRModifier); + } + +} + + /** + * @} end of RFFT_RIFFT group + */ + +/** + * @brief Core Real FFT process + * @param *pSrc points to the input buffer. + * @param fftLen length of FFT. + * @param *pATable points to the A twiddle Coef buffer. + * @param *pBTable points to the B twiddle Coef buffer. + * @param *pDst points to the output buffer. + * @param modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + * The function implements a Real FFT + */ + +void arm_split_rfft_q15( + q15_t * pSrc, + uint32_t fftLen, + q15_t * pATable, + q15_t * pBTable, + q15_t * pDst, + uint32_t modifier) +{ + uint32_t i; /* Loop Counter */ + q31_t outR, outI; /* Temporary variables for output */ + q15_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ + q15_t *pSrc1, *pSrc2; + + + pSrc[2u * fftLen] = pSrc[0]; + pSrc[(2u * fftLen) + 1u] = pSrc[1]; + + pCoefA = &pATable[modifier * 2u]; + pCoefB = &pBTable[modifier * 2u]; + + pSrc1 = &pSrc[2]; + pSrc2 = &pSrc[(2u * fftLen) - 2u]; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + i = 1u; + + while(i < fftLen) + { + /* + outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] + + pSrc[2 * n - 2 * i] * pBTable[2 * i] + + pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); + */ + + /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + + pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); */ + + +#ifndef ARM_MATH_BIG_ENDIAN + + /* pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] */ + outR = __SMUSD(*__SIMD32(pSrc1), *__SIMD32(pCoefA)); + +#else + + /* -(pSrc[2 * i + 1] * pATable[2 * i + 1] - pSrc[2 * i] * pATable[2 * i]) */ + outR = -(__SMUSD(*__SIMD32(pSrc1), *__SIMD32(pCoefA))); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* pSrc[2 * n - 2 * i] * pBTable[2 * i] + + pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]) */ + outR = __SMLAD(*__SIMD32(pSrc2), *__SIMD32(pCoefB), outR) >> 15u; + + /* pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ + +#ifndef ARM_MATH_BIG_ENDIAN + + outI = __SMUSDX(*__SIMD32(pSrc2)--, *__SIMD32(pCoefB)); + +#else + + outI = __SMUSDX(*__SIMD32(pCoefB), *__SIMD32(pSrc2)--); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] */ + outI = __SMLADX(*__SIMD32(pSrc1)++, *__SIMD32(pCoefA), outI); + + /* write output */ + pDst[2u * i] = (q15_t) outR; + pDst[(2u * i) + 1u] = outI >> 15u; + + /* write complex conjugate output */ + pDst[(4u * fftLen) - (2u * i)] = (q15_t) outR; + pDst[((4u * fftLen) - (2u * i)) + 1u] = -(outI >> 15u); + + /* update coefficient pointer */ + pCoefB = pCoefB + (2u * modifier); + pCoefA = pCoefA + (2u * modifier); + + i++; + + } + + pDst[2u * fftLen] = pSrc[0] - pSrc[1]; + pDst[(2u * fftLen) + 1u] = 0; + + pDst[0] = pSrc[0] + pSrc[1]; + pDst[1] = 0; + + +#else + + /* Run the below code for Cortex-M0 */ + + i = 1u; + + while(i < fftLen) + { + /* + outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] + + pSrc[2 * n - 2 * i] * pBTable[2 * i] + + pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); + */ + + outR = *pSrc1 * *pCoefA; + outR = outR - (*(pSrc1 + 1) * *(pCoefA + 1)); + outR = outR + (*pSrc2 * *pCoefB); + outR = (outR + (*(pSrc2 + 1) * *(pCoefB + 1))) >> 15; + + + /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + + pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); + */ + + outI = *pSrc2 * *(pCoefB + 1); + outI = outI - (*(pSrc2 + 1) * *pCoefB); + outI = outI + (*(pSrc1 + 1) * *pCoefA); + outI = outI + (*pSrc1 * *(pCoefA + 1)); + + /* update input pointers */ + pSrc1 += 2u; + pSrc2 -= 2u; + + /* write output */ + pDst[2u * i] = (q15_t) outR; + pDst[(2u * i) + 1u] = outI >> 15u; + + /* write complex conjugate output */ + pDst[(4u * fftLen) - (2u * i)] = (q15_t) outR; + pDst[((4u * fftLen) - (2u * i)) + 1u] = -(outI >> 15u); + + /* update coefficient pointer */ + pCoefB = pCoefB + (2u * modifier); + pCoefA = pCoefA + (2u * modifier); + + i++; + + } + + pDst[2u * fftLen] = pSrc[0] - pSrc[1]; + pDst[(2u * fftLen) + 1u] = 0; + + pDst[0] = pSrc[0] + pSrc[1]; + pDst[1] = 0; + +#endif /* #ifndef ARM_MATH_CM0 */ + +} + + +/** + * @brief Core Real IFFT process + * @param[in] *pSrc points to the input buffer. + * @param[in] fftLen length of FFT. + * @param[in] *pATable points to the twiddle Coef A buffer. + * @param[in] *pBTable points to the twiddle Coef B buffer. + * @param[out] *pDst points to the output buffer. + * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + * The function implements a Real IFFT + */ +void arm_split_rifft_q15( + q15_t * pSrc, + uint32_t fftLen, + q15_t * pATable, + q15_t * pBTable, + q15_t * pDst, + uint32_t modifier) +{ + uint32_t i; /* Loop Counter */ + q31_t outR, outI; /* Temporary variables for output */ + q15_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ + q15_t *pSrc1, *pSrc2; + q15_t *pDst1 = &pDst[0]; + + pCoefA = &pATable[0]; + pCoefB = &pBTable[0]; + + pSrc1 = &pSrc[0]; + pSrc2 = &pSrc[2u * fftLen]; + +#ifndef ARM_MATH_CM0 + + /* Run the below code for Cortex-M4 and Cortex-M3 */ + + i = fftLen; + + while(i > 0u) + { + + /* + outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + + pIn[2 * n - 2 * i] * pBTable[2 * i] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); + + outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - + pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); + + */ + + +#ifndef ARM_MATH_BIG_ENDIAN + + /* pIn[2 * n - 2 * i] * pBTable[2 * i] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]) */ + outR = __SMUSD(*__SIMD32(pSrc2), *__SIMD32(pCoefB)); + +#else + + /* -(-pIn[2 * n - 2 * i] * pBTable[2 * i] + + pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1])) */ + outR = -(__SMUSD(*__SIMD32(pSrc2), *__SIMD32(pCoefB))); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + + pIn[2 * n - 2 * i] * pBTable[2 * i] */ + outR = __SMLAD(*__SIMD32(pSrc1), *__SIMD32(pCoefA), outR) >> 15u; + + /* + -pIn[2 * n - 2 * i] * pBTable[2 * i + 1] + + pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ + outI = __SMUADX(*__SIMD32(pSrc2)--, *__SIMD32(pCoefB)); + + /* pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] */ + +#ifndef ARM_MATH_BIG_ENDIAN + + outI = __SMLSDX(*__SIMD32(pCoefA), *__SIMD32(pSrc1)++, -outI); + +#else + + outI = __SMLSDX(*__SIMD32(pSrc1)++, *__SIMD32(pCoefA), -outI); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + /* write output */ + +#ifndef ARM_MATH_BIG_ENDIAN + + *__SIMD32(pDst1)++ = __PKHBT(outR, (outI >> 15u), 16); + +#else + + *__SIMD32(pDst1)++ = __PKHBT((outI >> 15u), outR, 16); + +#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ + + /* update coefficient pointer */ + pCoefB = pCoefB + (2u * modifier); + pCoefA = pCoefA + (2u * modifier); + + i--; + + } + + +#else + + /* Run the below code for Cortex-M0 */ + + i = fftLen; + + while(i > 0u) + { + + /* + outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + + pIn[2 * n - 2 * i] * pBTable[2 * i] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); + */ + + outR = *pSrc2 * *pCoefB; + outR = outR - (*(pSrc2 + 1) * *(pCoefB + 1)); + outR = outR + (*pSrc1 * *pCoefA); + outR = (outR + (*(pSrc1 + 1) * *(pCoefA + 1))) >> 15; + + /* + outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - + pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); + */ + + outI = *(pSrc1 + 1) * *pCoefA; + outI = outI - (*pSrc1 * *(pCoefA + 1)); + outI = outI - (*pSrc2 * *(pCoefB + 1)); + outI = outI - (*(pSrc2 + 1) * *(pCoefB)); + + /* update input pointers */ + pSrc1 += 2u; + pSrc2 -= 2u; + + /* write output */ + *pDst1++ = (q15_t) outR; + *pDst1++ = (q15_t) (outI >> 15); + + /* update coefficient pointer */ + pCoefB = pCoefB + (2u * modifier); + pCoefA = pCoefA + (2u * modifier); + + i--; + + } + +#endif /* #ifndef ARM_MATH_CM0 */ + +} diff --git a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_q31.c b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_q31.c index 49b076883..76c92cdc7 100644 --- a/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_q31.c +++ b/flight/PiOS/Common/Libraries/CMSIS2/DSP_Lib/Source/TransformFunctions/arm_rfft_q31.c @@ -1,326 +1,326 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. July 2011 -* $Revision: V1.0.10 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_q31.c -* -* Description: RFFT & RIFFT Q31 process function -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/*-------------------------------------------------------------------- -* Internal functions prototypes ---------------------------------------------------------------------*/ - -void arm_split_rfft_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pATable, - q31_t * pBTable, - q31_t * pDst, - uint32_t modifier); - -void arm_split_rifft_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pATable, - q31_t * pBTable, - q31_t * pDst, - uint32_t modifier); - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - -/** - * @brief Processing function for the Q31 RFFT/RIFFT. - * @param[in] *S points to an instance of the Q31 RFFT/RIFFT structure. - * @param[in] *pSrc points to the input buffer. - * @param[out] *pDst points to the output buffer. - * @return none. - * - * \par Input an output formats: - * \par - * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. - * Hence the output format is different for different RFFT sizes. - * The input and output formats for different RFFT sizes and number of bits to upscale are mentioned in the tables below for RFFT and RIFFT: - * \par - * \image html RFFTQ31.gif "Input and Output Formats for Q31 RFFT" - * - * \par - * \image html RIFFTQ31.gif "Input and Output Formats for Q31 RIFFT" - */ - -void arm_rfft_q31( - const arm_rfft_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst) -{ - const arm_cfft_radix4_instance_q31 *S_CFFT = S->pCfft; - - /* Calculation of RIFFT of input */ - if(S->ifftFlagR == 1u) - { - /* Real IFFT core process */ - arm_split_rifft_q31(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - - /* Complex readix-4 IFFT process */ - arm_radix4_butterfly_inverse_q31(pDst, S_CFFT->fftLen, - S_CFFT->pTwiddle, - S_CFFT->twidCoefModifier); - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_q31(pDst, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - } - else - { - /* Calculation of RFFT of input */ - - /* Complex readix-4 FFT process */ - arm_radix4_butterfly_q31(pSrc, S_CFFT->fftLen, - S_CFFT->pTwiddle, S_CFFT->twidCoefModifier); - - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_q31(pSrc, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - - /* Real FFT core process */ - arm_split_rfft_q31(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - } - -} - - - /** - * @} end of RFFT_RIFFT group - */ - -/** - * @brief Core Real FFT process - * @param[in] *pSrc points to the input buffer. - * @param[in] fftLen length of FFT. - * @param[in] *pATable points to the twiddle Coef A buffer. - * @param[in] *pBTable points to the twiddle Coef B buffer. - * @param[out] *pDst points to the output buffer. - * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_split_rfft_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pATable, - q31_t * pBTable, - q31_t * pDst, - uint32_t modifier) -{ - uint32_t i; /* Loop Counter */ - q31_t outR, outI; /* Temporary variables for output */ - q31_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - q31_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ - q31_t *pOut1 = &pDst[2], *pOut2 = &pDst[(4u * fftLen) - 1u]; - q31_t *pIn1 = &pSrc[2], *pIn2 = &pSrc[(2u * fftLen) - 1u]; - - pSrc[2u * fftLen] = pSrc[0]; - pSrc[(2u * fftLen) + 1u] = pSrc[1]; - - /* Init coefficient pointers */ - pCoefA = &pATable[modifier * 2u]; - pCoefB = &pBTable[modifier * 2u]; - - i = fftLen - 1u; - - while(i > 0u) - { - /* - outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] - + pSrc[2 * n - 2 * i] * pBTable[2 * i] + - pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - */ - - /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); */ - - CoefA1 = *pCoefA++; - CoefA2 = *pCoefA; - - /* outR = (pSrc[2 * i] * pATable[2 * i] */ - outR = ((int32_t) (((q63_t) * pIn1 * CoefA1) >> 32)); - - /* outI = pIn[2 * i] * pATable[2 * i + 1] */ - outI = ((int32_t) (((q63_t) * pIn1++ * CoefA2) >> 32)); - - /* - pSrc[2 * i + 1] * pATable[2 * i + 1] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn1 * (-CoefA2))) >> 32); - - /* (pIn[2 * i + 1] * pATable[2 * i] */ - outI = - (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn1++ * (CoefA1))) >> 32); - - /* pSrc[2 * n - 2 * i] * pBTable[2 * i] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (-CoefA2))) >> 32); - CoefB1 = *pCoefB; - - /* pIn[2 * n - 2 * i] * pBTable[2 * i + 1] */ - outI = - (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn2-- * (-CoefB1))) >> 32); - - /* pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (CoefB1))) >> 32); - - /* pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ - outI = - (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn2-- * (-CoefA2))) >> 32); - - /* write output */ - *pOut1++ = (outR << 1u); - *pOut1++ = (outI << 1u); - - /* write complex conjugate output */ - *pOut2-- = -(outI << 1u); - *pOut2-- = (outR << 1u); - - /* update coefficient pointer */ - pCoefB = pCoefB + (modifier * 2u); - pCoefA = pCoefA + ((modifier * 2u) - 1u); - - i--; - - } - - pDst[2u * fftLen] = pSrc[0] - pSrc[1]; - pDst[(2u * fftLen) + 1u] = 0; - - pDst[0] = pSrc[0] + pSrc[1]; - pDst[1] = 0; - -} - - -/** - * @brief Core Real IFFT process - * @param[in] *pSrc points to the input buffer. - * @param[in] fftLen length of FFT. - * @param[in] *pATable points to the twiddle Coef A buffer. - * @param[in] *pBTable points to the twiddle Coef B buffer. - * @param[out] *pDst points to the output buffer. - * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_split_rifft_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pATable, - q31_t * pBTable, - q31_t * pDst, - uint32_t modifier) -{ - q31_t outR, outI; /* Temporary variables for output */ - q31_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - q31_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ - q31_t *pIn1 = &pSrc[0], *pIn2 = &pSrc[(2u * fftLen) + 1u]; - - pCoefA = &pATable[0]; - pCoefB = &pBTable[0]; - - while(fftLen > 0u) - { - /* - outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - - outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); - - */ - CoefA1 = *pCoefA++; - CoefA2 = *pCoefA; - - /* outR = (pIn[2 * i] * pATable[2 * i] */ - outR = ((int32_t) (((q63_t) * pIn1 * CoefA1) >> 32)); - - /* - pIn[2 * i] * pATable[2 * i + 1] */ - outI = -((int32_t) (((q63_t) * pIn1++ * CoefA2) >> 32)); - - /* pIn[2 * i + 1] * pATable[2 * i + 1] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn1 * (CoefA2))) >> 32); - - /* pIn[2 * i + 1] * pATable[2 * i] */ - outI = - (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn1++ * (CoefA1))) >> 32); - - /* pIn[2 * n - 2 * i] * pBTable[2 * i] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (CoefA2))) >> 32); - - CoefB1 = *pCoefB; - - /* pIn[2 * n - 2 * i] * pBTable[2 * i + 1] */ - outI = - (q31_t) ((((q63_t) outI << 32) - ((q63_t) * pIn2-- * (CoefB1))) >> 32); - - /* pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (CoefB1))) >> 32); - - /* pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ - outI = - (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn2-- * (CoefA2))) >> 32); - - /* write output */ - *pDst++ = (outR << 1u); - *pDst++ = (outI << 1u); - - /* update coefficient pointer */ - pCoefB = pCoefB + (modifier * 2u); - pCoefA = pCoefA + ((modifier * 2u) - 1u); - - /* Decrement loop count */ - fftLen--; - - } - - -} +/* ---------------------------------------------------------------------- +* Copyright (C) 2010 ARM Limited. All rights reserved. +* +* $Date: 15. July 2011 +* $Revision: V1.0.10 +* +* Project: CMSIS DSP Library +* Title: arm_rfft_q31.c +* +* Description: RFFT & RIFFT Q31 process function +* +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Version 1.0.10 2011/7/15 +* Big Endian support added and Merged M0 and M3/M4 Source code. +* +* Version 1.0.3 2010/11/29 +* Re-organized the CMSIS folders and updated documentation. +* +* Version 1.0.2 2010/11/11 +* Documentation updated. +* +* Version 1.0.1 2010/10/05 +* Production release and review comments incorporated. +* +* Version 1.0.0 2010/09/20 +* Production release and review comments incorporated. +* +* Version 0.0.7 2010/06/10 +* Misra-C changes done +* -------------------------------------------------------------------- */ + +#include "arm_math.h" + +/*-------------------------------------------------------------------- +* Internal functions prototypes +--------------------------------------------------------------------*/ + +void arm_split_rfft_q31( + q31_t * pSrc, + uint32_t fftLen, + q31_t * pATable, + q31_t * pBTable, + q31_t * pDst, + uint32_t modifier); + +void arm_split_rifft_q31( + q31_t * pSrc, + uint32_t fftLen, + q31_t * pATable, + q31_t * pBTable, + q31_t * pDst, + uint32_t modifier); + +/** + * @addtogroup RFFT_RIFFT + * @{ + */ + +/** + * @brief Processing function for the Q31 RFFT/RIFFT. + * @param[in] *S points to an instance of the Q31 RFFT/RIFFT structure. + * @param[in] *pSrc points to the input buffer. + * @param[out] *pDst points to the output buffer. + * @return none. + * + * \par Input an output formats: + * \par + * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. + * Hence the output format is different for different RFFT sizes. + * The input and output formats for different RFFT sizes and number of bits to upscale are mentioned in the tables below for RFFT and RIFFT: + * \par + * \image html RFFTQ31.gif "Input and Output Formats for Q31 RFFT" + * + * \par + * \image html RIFFTQ31.gif "Input and Output Formats for Q31 RIFFT" + */ + +void arm_rfft_q31( + const arm_rfft_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst) +{ + const arm_cfft_radix4_instance_q31 *S_CFFT = S->pCfft; + + /* Calculation of RIFFT of input */ + if(S->ifftFlagR == 1u) + { + /* Real IFFT core process */ + arm_split_rifft_q31(pSrc, S->fftLenBy2, S->pTwiddleAReal, + S->pTwiddleBReal, pDst, S->twidCoefRModifier); + + /* Complex readix-4 IFFT process */ + arm_radix4_butterfly_inverse_q31(pDst, S_CFFT->fftLen, + S_CFFT->pTwiddle, + S_CFFT->twidCoefModifier); + /* Bit reversal process */ + if(S->bitReverseFlagR == 1u) + { + arm_bitreversal_q31(pDst, S_CFFT->fftLen, + S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); + } + } + else + { + /* Calculation of RFFT of input */ + + /* Complex readix-4 FFT process */ + arm_radix4_butterfly_q31(pSrc, S_CFFT->fftLen, + S_CFFT->pTwiddle, S_CFFT->twidCoefModifier); + + /* Bit reversal process */ + if(S->bitReverseFlagR == 1u) + { + arm_bitreversal_q31(pSrc, S_CFFT->fftLen, + S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); + } + + /* Real FFT core process */ + arm_split_rfft_q31(pSrc, S->fftLenBy2, S->pTwiddleAReal, + S->pTwiddleBReal, pDst, S->twidCoefRModifier); + } + +} + + + /** + * @} end of RFFT_RIFFT group + */ + +/** + * @brief Core Real FFT process + * @param[in] *pSrc points to the input buffer. + * @param[in] fftLen length of FFT. + * @param[in] *pATable points to the twiddle Coef A buffer. + * @param[in] *pBTable points to the twiddle Coef B buffer. + * @param[out] *pDst points to the output buffer. + * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + +void arm_split_rfft_q31( + q31_t * pSrc, + uint32_t fftLen, + q31_t * pATable, + q31_t * pBTable, + q31_t * pDst, + uint32_t modifier) +{ + uint32_t i; /* Loop Counter */ + q31_t outR, outI; /* Temporary variables for output */ + q31_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ + q31_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ + q31_t *pOut1 = &pDst[2], *pOut2 = &pDst[(4u * fftLen) - 1u]; + q31_t *pIn1 = &pSrc[2], *pIn2 = &pSrc[(2u * fftLen) - 1u]; + + pSrc[2u * fftLen] = pSrc[0]; + pSrc[(2u * fftLen) + 1u] = pSrc[1]; + + /* Init coefficient pointers */ + pCoefA = &pATable[modifier * 2u]; + pCoefB = &pBTable[modifier * 2u]; + + i = fftLen - 1u; + + while(i > 0u) + { + /* + outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] + + pSrc[2 * n - 2 * i] * pBTable[2 * i] + + pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); + */ + + /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + + pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); */ + + CoefA1 = *pCoefA++; + CoefA2 = *pCoefA; + + /* outR = (pSrc[2 * i] * pATable[2 * i] */ + outR = ((int32_t) (((q63_t) * pIn1 * CoefA1) >> 32)); + + /* outI = pIn[2 * i] * pATable[2 * i + 1] */ + outI = ((int32_t) (((q63_t) * pIn1++ * CoefA2) >> 32)); + + /* - pSrc[2 * i + 1] * pATable[2 * i + 1] */ + outR = + (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn1 * (-CoefA2))) >> 32); + + /* (pIn[2 * i + 1] * pATable[2 * i] */ + outI = + (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn1++ * (CoefA1))) >> 32); + + /* pSrc[2 * n - 2 * i] * pBTable[2 * i] */ + outR = + (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (-CoefA2))) >> 32); + CoefB1 = *pCoefB; + + /* pIn[2 * n - 2 * i] * pBTable[2 * i + 1] */ + outI = + (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn2-- * (-CoefB1))) >> 32); + + /* pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1] */ + outR = + (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (CoefB1))) >> 32); + + /* pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ + outI = + (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn2-- * (-CoefA2))) >> 32); + + /* write output */ + *pOut1++ = (outR << 1u); + *pOut1++ = (outI << 1u); + + /* write complex conjugate output */ + *pOut2-- = -(outI << 1u); + *pOut2-- = (outR << 1u); + + /* update coefficient pointer */ + pCoefB = pCoefB + (modifier * 2u); + pCoefA = pCoefA + ((modifier * 2u) - 1u); + + i--; + + } + + pDst[2u * fftLen] = pSrc[0] - pSrc[1]; + pDst[(2u * fftLen) + 1u] = 0; + + pDst[0] = pSrc[0] + pSrc[1]; + pDst[1] = 0; + +} + + +/** + * @brief Core Real IFFT process + * @param[in] *pSrc points to the input buffer. + * @param[in] fftLen length of FFT. + * @param[in] *pATable points to the twiddle Coef A buffer. + * @param[in] *pBTable points to the twiddle Coef B buffer. + * @param[out] *pDst points to the output buffer. + * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. + * @return none. + */ + +void arm_split_rifft_q31( + q31_t * pSrc, + uint32_t fftLen, + q31_t * pATable, + q31_t * pBTable, + q31_t * pDst, + uint32_t modifier) +{ + q31_t outR, outI; /* Temporary variables for output */ + q31_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ + q31_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ + q31_t *pIn1 = &pSrc[0], *pIn2 = &pSrc[(2u * fftLen) + 1u]; + + pCoefA = &pATable[0]; + pCoefB = &pBTable[0]; + + while(fftLen > 0u) + { + /* + outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + + pIn[2 * n - 2 * i] * pBTable[2 * i] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); + + outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - + pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - + pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); + + */ + CoefA1 = *pCoefA++; + CoefA2 = *pCoefA; + + /* outR = (pIn[2 * i] * pATable[2 * i] */ + outR = ((int32_t) (((q63_t) * pIn1 * CoefA1) >> 32)); + + /* - pIn[2 * i] * pATable[2 * i + 1] */ + outI = -((int32_t) (((q63_t) * pIn1++ * CoefA2) >> 32)); + + /* pIn[2 * i + 1] * pATable[2 * i + 1] */ + outR = + (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn1 * (CoefA2))) >> 32); + + /* pIn[2 * i + 1] * pATable[2 * i] */ + outI = + (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn1++ * (CoefA1))) >> 32); + + /* pIn[2 * n - 2 * i] * pBTable[2 * i] */ + outR = + (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (CoefA2))) >> 32); + + CoefB1 = *pCoefB; + + /* pIn[2 * n - 2 * i] * pBTable[2 * i + 1] */ + outI = + (q31_t) ((((q63_t) outI << 32) - ((q63_t) * pIn2-- * (CoefB1))) >> 32); + + /* pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1] */ + outR = + (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (CoefB1))) >> 32); + + /* pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ + outI = + (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn2-- * (CoefA2))) >> 32); + + /* write output */ + *pDst++ = (outR << 1u); + *pDst++ = (outI << 1u); + + /* update coefficient pointer */ + pCoefB = pCoefB + (modifier * 2u); + pCoefA = pCoefA + ((modifier * 2u) - 1u); + + /* Decrement loop count */ + fftLen--; + + } + + +} diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h index c12f5d76f..c013aa2ec 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/FreeRTOS.h @@ -1,522 +1,522 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef INC_FREERTOS_H -#define INC_FREERTOS_H - - -/* - * Include the generic headers required for the FreeRTOS port being used. - */ -#include - -/* Basic FreeRTOS definitions. */ -#include "projdefs.h" - -/* Application specific configuration options. */ -#include "FreeRTOSConfig.h" - -/* Definitions specific to the port being used. */ -#include "portable.h" - - -/* Defines the prototype to which the application task hook function must -conform. */ -typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); - - - - - -/* - * Check all the required application specific macros have been defined. - * These macros are application specific and (as downloaded) are defined - * within FreeRTOSConfig.h. - */ - -#ifndef configUSE_PREEMPTION - #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_IDLE_HOOK - #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_TICK_HOOK - #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_CO_ROUTINES - #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskPrioritySet - #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_uxTaskPriorityGet - #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelete - #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskSuspend - #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelayUntil - #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelay - #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_16_BIT_TICKS - #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_xTaskGetIdleTaskHandle - #define INCLUDE_xTaskGetIdleTaskHandle 0 -#endif - -#ifndef INCLUDE_xTimerGetTimerDaemonTaskHandle - #define INCLUDE_xTimerGetTimerDaemonTaskHandle 0 -#endif - -#ifndef INCLUDE_xQueueGetMutexHolder - #define INCLUDE_xQueueGetMutexHolder 0 -#endif - -#ifndef INCLUDE_pcTaskGetTaskName - #define INCLUDE_pcTaskGetTaskName 0 -#endif - -#ifndef configUSE_APPLICATION_TASK_TAG - #define configUSE_APPLICATION_TASK_TAG 0 -#endif - -#ifndef INCLUDE_uxTaskGetStackHighWaterMark - #define INCLUDE_uxTaskGetStackHighWaterMark 0 -#endif - -#ifndef configUSE_RECURSIVE_MUTEXES - #define configUSE_RECURSIVE_MUTEXES 0 -#endif - -#ifndef configUSE_MUTEXES - #define configUSE_MUTEXES 0 -#endif - -#ifndef configUSE_TIMERS - #define configUSE_TIMERS 0 -#endif - -#ifndef configUSE_COUNTING_SEMAPHORES - #define configUSE_COUNTING_SEMAPHORES 0 -#endif - -#ifndef configUSE_ALTERNATIVE_API - #define configUSE_ALTERNATIVE_API 0 -#endif - -#ifndef portCRITICAL_NESTING_IN_TCB - #define portCRITICAL_NESTING_IN_TCB 0 -#endif - -#ifndef configMAX_TASK_NAME_LEN - #define configMAX_TASK_NAME_LEN 16 -#endif - -#ifndef configIDLE_SHOULD_YIELD - #define configIDLE_SHOULD_YIELD 1 -#endif - -#if configMAX_TASK_NAME_LEN < 1 - #error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h -#endif - -#ifndef INCLUDE_xTaskResumeFromISR - #define INCLUDE_xTaskResumeFromISR 1 -#endif - -#ifndef configASSERT - #define configASSERT( x ) -#endif - -#ifndef portALIGNMENT_ASSERT_pxCurrentTCB - #define portALIGNMENT_ASSERT_pxCurrentTCB configASSERT -#endif - -/* The timers module relies on xTaskGetSchedulerState(). */ -#if configUSE_TIMERS == 1 - - #ifndef configTIMER_TASK_PRIORITY - #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined. - #endif /* configTIMER_TASK_PRIORITY */ - - #ifndef configTIMER_QUEUE_LENGTH - #error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined. - #endif /* configTIMER_QUEUE_LENGTH */ - - #ifndef configTIMER_TASK_STACK_DEPTH - #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined. - #endif /* configTIMER_TASK_STACK_DEPTH */ - -#endif /* configUSE_TIMERS */ - -#ifndef INCLUDE_xTaskGetSchedulerState - #define INCLUDE_xTaskGetSchedulerState 0 -#endif - -#ifndef INCLUDE_xTaskGetCurrentTaskHandle - #define INCLUDE_xTaskGetCurrentTaskHandle 0 -#endif - - -#ifndef portSET_INTERRUPT_MASK_FROM_ISR - #define portSET_INTERRUPT_MASK_FROM_ISR() 0 -#endif - -#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR - #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue -#endif - -#ifndef portCLEAN_UP_TCB - #define portCLEAN_UP_TCB( pxTCB ) ( void ) pxTCB -#endif - -#ifndef portSETUP_TCB - #define portSETUP_TCB( pxTCB ) ( void ) pxTCB -#endif - -#ifndef configQUEUE_REGISTRY_SIZE - #define configQUEUE_REGISTRY_SIZE 0U -#endif - -#if ( configQUEUE_REGISTRY_SIZE < 1 ) - #define vQueueAddToRegistry( xQueue, pcName ) - #define vQueueUnregisterQueue( xQueue ) -#endif - -#ifndef portPOINTER_SIZE_TYPE - #define portPOINTER_SIZE_TYPE unsigned long -#endif - -/* Remove any unused trace macros. */ -#ifndef traceSTART - /* Used to perform any necessary initialisation - for example, open a file - into which trace is to be written. */ - #define traceSTART() -#endif - -#ifndef traceEND - /* Use to close a trace, for example close a file into which trace has been - written. */ - #define traceEND() -#endif - -#ifndef traceTASK_SWITCHED_IN - /* Called after a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the selected task. */ - #define traceTASK_SWITCHED_IN() -#endif - -#ifndef traceTASK_SWITCHED_OUT - /* Called before a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the task being switched out. */ - #define traceTASK_SWITCHED_OUT() -#endif - -#ifndef traceTASK_PRIORITY_INHERIT - /* Called when a task attempts to take a mutex that is already held by a - lower priority task. pxTCBOfMutexHolder is a pointer to the TCB of the task - that holds the mutex. uxInheritedPriority is the priority the mutex holder - will inherit (the priority of the task that is attempting to obtain the - muted. */ - #define traceTASK_PRIORITY_INHERIT( pxTCBOfMutexHolder, uxInheritedPriority ) -#endif - -#ifndef traceTASK_PRIORITY_DISINHERIT - /* Called when a task releases a mutex, the holding of which had resulted in - the task inheriting the priority of a higher priority task. - pxTCBOfMutexHolder is a pointer to the TCB of the task that is releasing the - mutex. uxOriginalPriority is the task's configured (base) priority. */ - #define traceTASK_PRIORITY_DISINHERIT( pxTCBOfMutexHolder, uxOriginalPriority ) -#endif - -#ifndef traceBLOCKING_ON_QUEUE_RECEIVE - /* Task is about to block because it cannot read from a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the read was attempted. pxCurrentTCB points to the TCB of the - task that attempted the read. */ - #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceBLOCKING_ON_QUEUE_SEND - /* Task is about to block because it cannot write to a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the write was attempted. pxCurrentTCB points to the TCB of the - task that attempted the write. */ - #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) -#endif - -#ifndef configCHECK_FOR_STACK_OVERFLOW - #define configCHECK_FOR_STACK_OVERFLOW 0 -#endif - -/* The following event macros are embedded in the kernel API calls. */ - -#ifndef traceMOVED_TASK_TO_READY_STATE - #define traceMOVED_TASK_TO_READY_STATE( pxTCB ) -#endif - -#ifndef traceQUEUE_CREATE - #define traceQUEUE_CREATE( pxNewQueue ) -#endif - -#ifndef traceQUEUE_CREATE_FAILED - #define traceQUEUE_CREATE_FAILED( ucQueueType ) -#endif - -#ifndef traceCREATE_MUTEX - #define traceCREATE_MUTEX( pxNewQueue ) -#endif - -#ifndef traceCREATE_MUTEX_FAILED - #define traceCREATE_MUTEX_FAILED() -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE - #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED - #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) -#endif - -#ifndef traceTAKE_MUTEX_RECURSIVE - #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED - #define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ) -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE - #define traceCREATE_COUNTING_SEMAPHORE() -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED - #define traceCREATE_COUNTING_SEMAPHORE_FAILED() -#endif - -#ifndef traceQUEUE_SEND - #define traceQUEUE_SEND( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FAILED - #define traceQUEUE_SEND_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE - #define traceQUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceQUEUE_PEEK - #define traceQUEUE_PEEK( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FAILED - #define traceQUEUE_RECEIVE_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR - #define traceQUEUE_SEND_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR_FAILED - #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR - #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED - #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_DELETE - #define traceQUEUE_DELETE( pxQueue ) -#endif - -#ifndef traceTASK_CREATE - #define traceTASK_CREATE( pxNewTCB ) -#endif - -#ifndef traceTASK_CREATE_FAILED - #define traceTASK_CREATE_FAILED() -#endif - -#ifndef traceTASK_DELETE - #define traceTASK_DELETE( pxTaskToDelete ) -#endif - -#ifndef traceTASK_DELAY_UNTIL - #define traceTASK_DELAY_UNTIL() -#endif - -#ifndef traceTASK_DELAY - #define traceTASK_DELAY() -#endif - -#ifndef traceTASK_PRIORITY_SET - #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) -#endif - -#ifndef traceTASK_SUSPEND - #define traceTASK_SUSPEND( pxTaskToSuspend ) -#endif - -#ifndef traceTASK_RESUME - #define traceTASK_RESUME( pxTaskToResume ) -#endif - -#ifndef traceTASK_RESUME_FROM_ISR - #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) -#endif - -#ifndef traceTASK_INCREMENT_TICK - #define traceTASK_INCREMENT_TICK( xTickCount ) -#endif - -#ifndef traceTIMER_CREATE - #define traceTIMER_CREATE( pxNewTimer ) -#endif - -#ifndef traceTIMER_CREATE_FAILED - #define traceTIMER_CREATE_FAILED() -#endif - -#ifndef traceTIMER_COMMAND_SEND - #define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn ) -#endif - -#ifndef traceTIMER_EXPIRED - #define traceTIMER_EXPIRED( pxTimer ) -#endif - -#ifndef traceTIMER_COMMAND_RECEIVED - #define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue ) -#endif - -#ifndef configGENERATE_RUN_TIME_STATS - #define configGENERATE_RUN_TIME_STATS 0 -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. - #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ - - #ifndef portGET_RUN_TIME_COUNTER_VALUE - #ifndef portALT_GET_RUN_TIME_COUNTER_VALUE - #error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined. See the examples provided and the FreeRTOS web site for more information. - #endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */ - #endif /* portGET_RUN_TIME_COUNTER_VALUE */ - -#endif /* configGENERATE_RUN_TIME_STATS */ - -#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() -#endif - -#ifndef configUSE_MALLOC_FAILED_HOOK - #define configUSE_MALLOC_FAILED_HOOK 0 -#endif - -#ifndef portPRIVILEGE_BIT - #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) -#endif - -#ifndef portYIELD_WITHIN_API - #define portYIELD_WITHIN_API portYIELD -#endif - -#ifndef pvPortMallocAligned - #define pvPortMallocAligned( x, puxStackBuffer ) ( ( ( puxStackBuffer ) == NULL ) ? ( pvPortMalloc( ( x ) ) ) : ( puxStackBuffer ) ) -#endif - -#ifndef vPortFreeAligned - #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) -#endif - -#endif /* INC_FREERTOS_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef INC_FREERTOS_H +#define INC_FREERTOS_H + + +/* + * Include the generic headers required for the FreeRTOS port being used. + */ +#include + +/* Basic FreeRTOS definitions. */ +#include "projdefs.h" + +/* Application specific configuration options. */ +#include "FreeRTOSConfig.h" + +/* Definitions specific to the port being used. */ +#include "portable.h" + + +/* Defines the prototype to which the application task hook function must +conform. */ +typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); + + + + + +/* + * Check all the required application specific macros have been defined. + * These macros are application specific and (as downloaded) are defined + * within FreeRTOSConfig.h. + */ + +#ifndef configUSE_PREEMPTION + #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_IDLE_HOOK + #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_TICK_HOOK + #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_CO_ROUTINES + #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskPrioritySet + #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_uxTaskPriorityGet + #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelete + #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskSuspend + #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelayUntil + #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelay + #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_16_BIT_TICKS + #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_xTaskGetIdleTaskHandle + #define INCLUDE_xTaskGetIdleTaskHandle 0 +#endif + +#ifndef INCLUDE_xTimerGetTimerDaemonTaskHandle + #define INCLUDE_xTimerGetTimerDaemonTaskHandle 0 +#endif + +#ifndef INCLUDE_xQueueGetMutexHolder + #define INCLUDE_xQueueGetMutexHolder 0 +#endif + +#ifndef INCLUDE_pcTaskGetTaskName + #define INCLUDE_pcTaskGetTaskName 0 +#endif + +#ifndef configUSE_APPLICATION_TASK_TAG + #define configUSE_APPLICATION_TASK_TAG 0 +#endif + +#ifndef INCLUDE_uxTaskGetStackHighWaterMark + #define INCLUDE_uxTaskGetStackHighWaterMark 0 +#endif + +#ifndef configUSE_RECURSIVE_MUTEXES + #define configUSE_RECURSIVE_MUTEXES 0 +#endif + +#ifndef configUSE_MUTEXES + #define configUSE_MUTEXES 0 +#endif + +#ifndef configUSE_TIMERS + #define configUSE_TIMERS 0 +#endif + +#ifndef configUSE_COUNTING_SEMAPHORES + #define configUSE_COUNTING_SEMAPHORES 0 +#endif + +#ifndef configUSE_ALTERNATIVE_API + #define configUSE_ALTERNATIVE_API 0 +#endif + +#ifndef portCRITICAL_NESTING_IN_TCB + #define portCRITICAL_NESTING_IN_TCB 0 +#endif + +#ifndef configMAX_TASK_NAME_LEN + #define configMAX_TASK_NAME_LEN 16 +#endif + +#ifndef configIDLE_SHOULD_YIELD + #define configIDLE_SHOULD_YIELD 1 +#endif + +#if configMAX_TASK_NAME_LEN < 1 + #error configMAX_TASK_NAME_LEN must be set to a minimum of 1 in FreeRTOSConfig.h +#endif + +#ifndef INCLUDE_xTaskResumeFromISR + #define INCLUDE_xTaskResumeFromISR 1 +#endif + +#ifndef configASSERT + #define configASSERT( x ) +#endif + +#ifndef portALIGNMENT_ASSERT_pxCurrentTCB + #define portALIGNMENT_ASSERT_pxCurrentTCB configASSERT +#endif + +/* The timers module relies on xTaskGetSchedulerState(). */ +#if configUSE_TIMERS == 1 + + #ifndef configTIMER_TASK_PRIORITY + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_PRIORITY must also be defined. + #endif /* configTIMER_TASK_PRIORITY */ + + #ifndef configTIMER_QUEUE_LENGTH + #error If configUSE_TIMERS is set to 1 then configTIMER_QUEUE_LENGTH must also be defined. + #endif /* configTIMER_QUEUE_LENGTH */ + + #ifndef configTIMER_TASK_STACK_DEPTH + #error If configUSE_TIMERS is set to 1 then configTIMER_TASK_STACK_DEPTH must also be defined. + #endif /* configTIMER_TASK_STACK_DEPTH */ + +#endif /* configUSE_TIMERS */ + +#ifndef INCLUDE_xTaskGetSchedulerState + #define INCLUDE_xTaskGetSchedulerState 0 +#endif + +#ifndef INCLUDE_xTaskGetCurrentTaskHandle + #define INCLUDE_xTaskGetCurrentTaskHandle 0 +#endif + + +#ifndef portSET_INTERRUPT_MASK_FROM_ISR + #define portSET_INTERRUPT_MASK_FROM_ISR() 0 +#endif + +#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR + #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue +#endif + +#ifndef portCLEAN_UP_TCB + #define portCLEAN_UP_TCB( pxTCB ) ( void ) pxTCB +#endif + +#ifndef portSETUP_TCB + #define portSETUP_TCB( pxTCB ) ( void ) pxTCB +#endif + +#ifndef configQUEUE_REGISTRY_SIZE + #define configQUEUE_REGISTRY_SIZE 0U +#endif + +#if ( configQUEUE_REGISTRY_SIZE < 1 ) + #define vQueueAddToRegistry( xQueue, pcName ) + #define vQueueUnregisterQueue( xQueue ) +#endif + +#ifndef portPOINTER_SIZE_TYPE + #define portPOINTER_SIZE_TYPE unsigned long +#endif + +/* Remove any unused trace macros. */ +#ifndef traceSTART + /* Used to perform any necessary initialisation - for example, open a file + into which trace is to be written. */ + #define traceSTART() +#endif + +#ifndef traceEND + /* Use to close a trace, for example close a file into which trace has been + written. */ + #define traceEND() +#endif + +#ifndef traceTASK_SWITCHED_IN + /* Called after a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the selected task. */ + #define traceTASK_SWITCHED_IN() +#endif + +#ifndef traceTASK_SWITCHED_OUT + /* Called before a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the task being switched out. */ + #define traceTASK_SWITCHED_OUT() +#endif + +#ifndef traceTASK_PRIORITY_INHERIT + /* Called when a task attempts to take a mutex that is already held by a + lower priority task. pxTCBOfMutexHolder is a pointer to the TCB of the task + that holds the mutex. uxInheritedPriority is the priority the mutex holder + will inherit (the priority of the task that is attempting to obtain the + muted. */ + #define traceTASK_PRIORITY_INHERIT( pxTCBOfMutexHolder, uxInheritedPriority ) +#endif + +#ifndef traceTASK_PRIORITY_DISINHERIT + /* Called when a task releases a mutex, the holding of which had resulted in + the task inheriting the priority of a higher priority task. + pxTCBOfMutexHolder is a pointer to the TCB of the task that is releasing the + mutex. uxOriginalPriority is the task's configured (base) priority. */ + #define traceTASK_PRIORITY_DISINHERIT( pxTCBOfMutexHolder, uxOriginalPriority ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_RECEIVE + /* Task is about to block because it cannot read from a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the read was attempted. pxCurrentTCB points to the TCB of the + task that attempted the read. */ + #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_SEND + /* Task is about to block because it cannot write to a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the write was attempted. pxCurrentTCB points to the TCB of the + task that attempted the write. */ + #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) +#endif + +#ifndef configCHECK_FOR_STACK_OVERFLOW + #define configCHECK_FOR_STACK_OVERFLOW 0 +#endif + +/* The following event macros are embedded in the kernel API calls. */ + +#ifndef traceMOVED_TASK_TO_READY_STATE + #define traceMOVED_TASK_TO_READY_STATE( pxTCB ) +#endif + +#ifndef traceQUEUE_CREATE + #define traceQUEUE_CREATE( pxNewQueue ) +#endif + +#ifndef traceQUEUE_CREATE_FAILED + #define traceQUEUE_CREATE_FAILED( ucQueueType ) +#endif + +#ifndef traceCREATE_MUTEX + #define traceCREATE_MUTEX( pxNewQueue ) +#endif + +#ifndef traceCREATE_MUTEX_FAILED + #define traceCREATE_MUTEX_FAILED() +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE + #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED + #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE + #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE_FAILED + #define traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE + #define traceCREATE_COUNTING_SEMAPHORE() +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED + #define traceCREATE_COUNTING_SEMAPHORE_FAILED() +#endif + +#ifndef traceQUEUE_SEND + #define traceQUEUE_SEND( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FAILED + #define traceQUEUE_SEND_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE + #define traceQUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK + #define traceQUEUE_PEEK( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FAILED + #define traceQUEUE_RECEIVE_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR + #define traceQUEUE_SEND_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR_FAILED + #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR + #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED + #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_DELETE + #define traceQUEUE_DELETE( pxQueue ) +#endif + +#ifndef traceTASK_CREATE + #define traceTASK_CREATE( pxNewTCB ) +#endif + +#ifndef traceTASK_CREATE_FAILED + #define traceTASK_CREATE_FAILED() +#endif + +#ifndef traceTASK_DELETE + #define traceTASK_DELETE( pxTaskToDelete ) +#endif + +#ifndef traceTASK_DELAY_UNTIL + #define traceTASK_DELAY_UNTIL() +#endif + +#ifndef traceTASK_DELAY + #define traceTASK_DELAY() +#endif + +#ifndef traceTASK_PRIORITY_SET + #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) +#endif + +#ifndef traceTASK_SUSPEND + #define traceTASK_SUSPEND( pxTaskToSuspend ) +#endif + +#ifndef traceTASK_RESUME + #define traceTASK_RESUME( pxTaskToResume ) +#endif + +#ifndef traceTASK_RESUME_FROM_ISR + #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) +#endif + +#ifndef traceTASK_INCREMENT_TICK + #define traceTASK_INCREMENT_TICK( xTickCount ) +#endif + +#ifndef traceTIMER_CREATE + #define traceTIMER_CREATE( pxNewTimer ) +#endif + +#ifndef traceTIMER_CREATE_FAILED + #define traceTIMER_CREATE_FAILED() +#endif + +#ifndef traceTIMER_COMMAND_SEND + #define traceTIMER_COMMAND_SEND( xTimer, xMessageID, xMessageValueValue, xReturn ) +#endif + +#ifndef traceTIMER_EXPIRED + #define traceTIMER_EXPIRED( pxTimer ) +#endif + +#ifndef traceTIMER_COMMAND_RECEIVED + #define traceTIMER_COMMAND_RECEIVED( pxTimer, xMessageID, xMessageValue ) +#endif + +#ifndef configGENERATE_RUN_TIME_STATS + #define configGENERATE_RUN_TIME_STATS 0 +#endif + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. + #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ + + #ifndef portGET_RUN_TIME_COUNTER_VALUE + #ifndef portALT_GET_RUN_TIME_COUNTER_VALUE + #error If configGENERATE_RUN_TIME_STATS is defined then either portGET_RUN_TIME_COUNTER_VALUE or portALT_GET_RUN_TIME_COUNTER_VALUE must also be defined. See the examples provided and the FreeRTOS web site for more information. + #endif /* portALT_GET_RUN_TIME_COUNTER_VALUE */ + #endif /* portGET_RUN_TIME_COUNTER_VALUE */ + +#endif /* configGENERATE_RUN_TIME_STATS */ + +#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() +#endif + +#ifndef configUSE_MALLOC_FAILED_HOOK + #define configUSE_MALLOC_FAILED_HOOK 0 +#endif + +#ifndef portPRIVILEGE_BIT + #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) +#endif + +#ifndef portYIELD_WITHIN_API + #define portYIELD_WITHIN_API portYIELD +#endif + +#ifndef pvPortMallocAligned + #define pvPortMallocAligned( x, puxStackBuffer ) ( ( ( puxStackBuffer ) == NULL ) ? ( pvPortMalloc( ( x ) ) ) : ( puxStackBuffer ) ) +#endif + +#ifndef vPortFreeAligned + #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) +#endif + +#endif /* INC_FREERTOS_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h index daf3ce408..13661ea4e 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/StackMacros.h @@ -1,181 +1,181 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef STACK_MACROS_H -#define STACK_MACROS_H - -/* - * Call the stack overflow hook function if the stack of the task being swapped - * out is currently overflowed, or looks like it might have overflowed in the - * past. - * - * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check - * the current stack state only - comparing the current top of stack value to - * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 - * will also cause the last few stack bytes to be checked to ensure the value - * to which the bytes were set when the task was created have not been - * overwritten. Note this second test does not guarantee that an overflowed - * stack will always be recognised. - */ - -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) - - /* FreeRTOSConfig.h is not set to check for stack overflows. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) - - /* FreeRTOSConfig.h is only set to use the first method of - overflow checking. */ - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#endif /* STACK_MACROS_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef STACK_MACROS_H +#define STACK_MACROS_H + +/* + * Call the stack overflow hook function if the stack of the task being swapped + * out is currently overflowed, or looks like it might have overflowed in the + * past. + * + * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check + * the current stack state only - comparing the current top of stack value to + * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 + * will also cause the last few stack bytes to be checked to ensure the value + * to which the bytes were set when the task was created have not been + * overwritten. Note this second test does not guarantee that an overflowed + * stack will always be recognised. + */ + +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) + + /* FreeRTOSConfig.h is not set to check for stack overflows. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) + + /* FreeRTOSConfig.h is only set to use the first method of + overflow checking. */ + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#endif /* STACK_MACROS_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h index f2843cde2..75852dc92 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/croutine.h @@ -1,759 +1,759 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef CO_ROUTINE_H -#define CO_ROUTINE_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include croutine.h" -#endif - -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* Used to hide the implementation of the co-routine control block. The -control block structure however has to be included in the header due to -the macro implementation of the co-routine functionality. */ -typedef void * xCoRoutineHandle; - -/* Defines the prototype to which co-routine functions must conform. */ -typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); - -typedef struct corCoRoutineControlBlock -{ - crCOROUTINE_CODE pxCoRoutineFunction; - xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ - unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ - unsigned short uxState; /*< Used internally by the co-routine implementation. */ -} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ - -/** - * croutine. h - *
- portBASE_TYPE xCoRoutineCreate(
-                                 crCOROUTINE_CODE pxCoRoutineCode,
-                                 unsigned portBASE_TYPE uxPriority,
-                                 unsigned portBASE_TYPE uxIndex
-                               );
- * - * Create a new co-routine and add it to the list of co-routines that are - * ready to run. - * - * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine - * functions require special syntax - see the co-routine section of the WEB - * documentation for more information. - * - * @param uxPriority The priority with respect to other co-routines at which - * the co-routine will run. - * - * @param uxIndex Used to distinguish between different co-routines that - * execute the same function. See the example below and the co-routine section - * of the WEB documentation for further information. - * - * @return pdPASS if the co-routine was successfully created and added to a ready - * list, otherwise an error code defined with ProjDefs.h. - * - * Example usage: -
- // Co-routine to be created.
- void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- static const char cLedToFlash[ 2 ] = { 5, 6 };
- static const portTickType uxFlashRates[ 2 ] = { 200, 400 };
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // This co-routine just delays for a fixed period, then toggles
-         // an LED.  Two co-routines are created using this function, so
-         // the uxIndex parameter is used to tell the co-routine which
-         // LED to flash and how long to delay.  This assumes xQueue has
-         // already been created.
-         vParTestToggleLED( cLedToFlash[ uxIndex ] );
-         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
-
- // Function that creates two co-routines.
- void vOtherFunction( void )
- {
- unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-		
-     // Create two co-routines at priority 0.  The first is given index 0
-     // so (from the code above) toggles LED 5 every 200 ticks.  The second
-     // is given index 1 so toggles LED 6 every 400 ticks.
-     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
-     {
-         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
-     }
- }
-   
- * \defgroup xCoRoutineCreate xCoRoutineCreate - * \ingroup Tasks - */ -signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); - - -/** - * croutine. h - *
- void vCoRoutineSchedule( void );
- * - * Run a co-routine. - * - * vCoRoutineSchedule() executes the highest priority co-routine that is able - * to run. The co-routine will execute until it either blocks, yields or is - * preempted by a task. Co-routines execute cooperatively so one - * co-routine cannot be preempted by another, but can be preempted by a task. - * - * If an application comprises of both tasks and co-routines then - * vCoRoutineSchedule should be called from the idle task (in an idle task - * hook). - * - * Example usage: -
- // This idle task hook will schedule a co-routine each time it is called.
- // The rest of the idle task will execute between co-routine calls.
- void vApplicationIdleHook( void )
- {
-	vCoRoutineSchedule();
- }
-
- // Alternatively, if you do not require any other part of the idle task to
- // execute, the idle task hook can call vCoRoutineScheduler() within an
- // infinite loop.
- void vApplicationIdleHook( void )
- {
-    for( ;; )
-    {
-        vCoRoutineSchedule();
-    }
- }
- 
- * \defgroup vCoRoutineSchedule vCoRoutineSchedule - * \ingroup Tasks - */ -void vCoRoutineSchedule( void ); - -/** - * croutine. h - *
- crSTART( xCoRoutineHandle xHandle );
- * - * This macro MUST always be called at the start of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crSTART( pxCRCB ) switch( ( ( corCRCB * )( pxCRCB ) )->uxState ) { case 0: - -/** - * croutine. h - *
- crEND();
- * - * This macro MUST always be called at the end of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crEND() } - -/* - * These macros are intended for internal use by the co-routine implementation - * only. The macros should not be used directly by application writers. - */ -#define crSET_STATE0( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): -#define crSET_STATE1( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): - -/** - * croutine. h - *
- crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
- * - * Delay a co-routine for a fixed period of time. - * - * crDELAY can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * @param xHandle The handle of the co-routine to delay. This is the xHandle - * parameter of the co-routine function. - * - * @param xTickToDelay The number of ticks that the co-routine should delay - * for. The actual amount of time this equates to is defined by - * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS - * can be used to convert ticks to milliseconds. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- // We are to delay for 200ms.
- static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-        // Delay for 200ms.
-        crDELAY( xHandle, xDelayTime );
-
-        // Do something here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crDELAY crDELAY - * \ingroup Tasks - */ -#define crDELAY( xHandle, xTicksToDelay ) \ - if( ( xTicksToDelay ) > 0 ) \ - { \ - vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL ); \ - } \ - crSET_STATE0( ( xHandle ) ); - -/** - *
- crQUEUE_SEND(
-                  xCoRoutineHandle xHandle,
-                  xQueueHandle pxQueue,
-                  void *pvItemToQueue,
-                  portTickType xTicksToWait,
-                  portBASE_TYPE *pxResult
-             )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_SEND can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue on which the data will be posted. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvItemToQueue A pointer to the data being posted onto the queue. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied from pvItemToQueue into the queue - * itself. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for space to become available on the queue, should space not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example - * below). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully posted onto the queue, otherwise it will be set to an - * error defined within ProjDefs.h. - * - * Example usage: -
- // Co-routine function that blocks for a fixed period then posts a number onto
- // a queue.
- static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xNumberToPost = 0;
- static portBASE_TYPE xResult;
-
-    // Co-routines must begin with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // This assumes the queue has already been created.
-        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
-
-        if( xResult != pdPASS )
-        {
-            // The message was not posted!
-        }
-
-        // Increment the number to be posted onto the queue.
-        xNumberToPost++;
-
-        // Delay for 100 ticks.
-        crDELAY( xHandle, 100 );
-    }
-
-    // Co-routines must end with a call to crEND().
-    crEND();
- }
- * \defgroup crQUEUE_SEND crQUEUE_SEND - * \ingroup Tasks - */ -#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ -{ \ - *( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) ); \ - if( *( pxResult ) == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( ( xHandle ) ); \ - *pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 ); \ - } \ - if( *pxResult == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( ( xHandle ) ); \ - *pxResult = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_RECEIVE(
-                     xCoRoutineHandle xHandle,
-                     xQueueHandle pxQueue,
-                     void *pvBuffer,
-                     portTickType xTicksToWait,
-                     portBASE_TYPE *pxResult
-                 )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_RECEIVE can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue from which the data will be received. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvBuffer The buffer into which the received item is to be copied. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied into pvBuffer. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for data to become available from the queue, should data not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the - * crQUEUE_SEND example). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully retrieved from the queue, otherwise it will be set to - * an error code as defined within ProjDefs.h. - * - * Example usage: -
- // A co-routine receives the number of an LED to flash from a queue.  It
- // blocks on the queue until the number is received.
- static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xResult;
- static unsigned portBASE_TYPE uxLEDToFlash;
-
-    // All co-routines must start with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // Wait for data to become available on the queue.
-        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-        if( xResult == pdPASS )
-        {
-            // We received the LED to flash - flash it!
-            vParTestToggleLED( uxLEDToFlash );
-        }
-    }
-
-    crEND();
- }
- * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ -{ \ - *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) ); \ - if( *( pxResult ) == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( ( xHandle ) ); \ - *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 ); \ - } \ - if( *( pxResult ) == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( ( xHandle ) ); \ - *( pxResult ) = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvItemToQueue,
-                            portBASE_TYPE xCoRoutinePreviouslyWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue - * that is being used from within a co-routine. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto - * the same queue multiple times from a single interrupt. The first call - * should always pass in pdFALSE. Subsequent calls should pass in - * the value returned from the previous call. - * - * @return pdTRUE if a co-routine was woken by posting onto the queue. This is - * used by the ISR to determine if a context switch may be required following - * the ISR. - * - * Example usage: -
- // A co-routine that blocks on a queue waiting for characters to be received.
- static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- char cRxedChar;
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Wait for data to become available on the queue.  This assumes the
-         // queue xCommsRxQueue has already been created!
-         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-         // Was a character received?
-         if( xResult == pdPASS )
-         {
-             // Process the character here.
-         }
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to send characters received on a serial port to
- // a co-routine.
- void vUART_ISR( void )
- {
- char cRxedChar;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     // We loop around reading characters until there are none left in the UART.
-     while( UART_RX_REG_NOT_EMPTY() )
-     {
-         // Obtain the character from the UART.
-         cRxedChar = UART_RX_REG;
-
-         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
-         // the first time around the loop.  If the post causes a co-routine
-         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
-         // In this manner we can ensure that if more than one co-routine is
-         // blocked on the queue only one is woken by this ISR no matter how
-         // many characters are posted to the queue.
-         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
-     }
- }
- * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) ) - - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvBuffer,
-                            portBASE_TYPE * pxCoRoutineWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data - * from a queue that is being used from within a co-routine (a co-routine - * posted to the queue). - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvBuffer A pointer to a buffer into which the received item will be - * placed. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from the queue into - * pvBuffer. - * - * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become - * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a - * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise - * *pxCoRoutineWoken will remain unchanged. - * - * @return pdTRUE an item was successfully received from the queue, otherwise - * pdFALSE. - * - * Example usage: -
- // A co-routine that posts a character to a queue then blocks for a fixed
- // period.  The character is incremented each time.
- static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // cChar holds its value while this co-routine is blocked and must therefore
- // be declared static.
- static char cCharToTx = 'a';
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Send the next character to the queue.
-         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
-
-         if( xResult == pdPASS )
-         {
-             // The character was successfully posted to the queue.
-         }
-		 else
-		 {
-			// Could not post the character to the queue.
-		 }
-
-         // Enable the UART Tx interrupt to cause an interrupt in this
-		 // hypothetical UART.  The interrupt will obtain the character
-		 // from the queue and send it.
-		 ENABLE_RX_INTERRUPT();
-
-		 // Increment to the next character then block for a fixed period.
-		 // cCharToTx will maintain its value across the delay as it is
-		 // declared static.
-		 cCharToTx++;
-		 if( cCharToTx > 'x' )
-		 {
-			cCharToTx = 'a';
-		 }
-		 crDELAY( 100 );
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to receive characters to send on a UART.
- void vUART_ISR( void )
- {
- char cCharToTx;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     while( UART_TX_REG_EMPTY() )
-     {
-         // Are there any characters in the queue waiting to be sent?
-		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
-		 // is woken by the post - ensuring that only a single co-routine is
-		 // woken no matter how many times we go around this loop.
-         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
-		 {
-			 SEND_CHARACTER( cCharToTx );
-		 }
-     }
- }
- * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) ) - -/* - * This function is intended for internal use by the co-routine macros only. - * The macro nature of the co-routine implementation requires that the - * prototype appears here. The function should not be used by application - * writers. - * - * Removes the current co-routine from its ready list and places it in the - * appropriate delayed list. - */ -void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); - -/* - * This function is intended for internal use by the queue implementation only. - * The function should not be used by application writers. - * - * Removes the highest priority co-routine from the event list and places it in - * the pending ready list. - */ -signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); - -#ifdef __cplusplus -} -#endif - -#endif /* CO_ROUTINE_H */ +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef CO_ROUTINE_H +#define CO_ROUTINE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include croutine.h" +#endif + +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Used to hide the implementation of the co-routine control block. The +control block structure however has to be included in the header due to +the macro implementation of the co-routine functionality. */ +typedef void * xCoRoutineHandle; + +/* Defines the prototype to which co-routine functions must conform. */ +typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); + +typedef struct corCoRoutineControlBlock +{ + crCOROUTINE_CODE pxCoRoutineFunction; + xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ + unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ + unsigned short uxState; /*< Used internally by the co-routine implementation. */ +} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ + +/** + * croutine. h + *
+ portBASE_TYPE xCoRoutineCreate(
+                                 crCOROUTINE_CODE pxCoRoutineCode,
+                                 unsigned portBASE_TYPE uxPriority,
+                                 unsigned portBASE_TYPE uxIndex
+                               );
+ * + * Create a new co-routine and add it to the list of co-routines that are + * ready to run. + * + * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine + * functions require special syntax - see the co-routine section of the WEB + * documentation for more information. + * + * @param uxPriority The priority with respect to other co-routines at which + * the co-routine will run. + * + * @param uxIndex Used to distinguish between different co-routines that + * execute the same function. See the example below and the co-routine section + * of the WEB documentation for further information. + * + * @return pdPASS if the co-routine was successfully created and added to a ready + * list, otherwise an error code defined with ProjDefs.h. + * + * Example usage: +
+ // Co-routine to be created.
+ void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ static const char cLedToFlash[ 2 ] = { 5, 6 };
+ static const portTickType uxFlashRates[ 2 ] = { 200, 400 };
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // This co-routine just delays for a fixed period, then toggles
+         // an LED.  Two co-routines are created using this function, so
+         // the uxIndex parameter is used to tell the co-routine which
+         // LED to flash and how long to delay.  This assumes xQueue has
+         // already been created.
+         vParTestToggleLED( cLedToFlash[ uxIndex ] );
+         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+
+ // Function that creates two co-routines.
+ void vOtherFunction( void )
+ {
+ unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+		
+     // Create two co-routines at priority 0.  The first is given index 0
+     // so (from the code above) toggles LED 5 every 200 ticks.  The second
+     // is given index 1 so toggles LED 6 every 400 ticks.
+     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
+     {
+         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
+     }
+ }
+   
+ * \defgroup xCoRoutineCreate xCoRoutineCreate + * \ingroup Tasks + */ +signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); + + +/** + * croutine. h + *
+ void vCoRoutineSchedule( void );
+ * + * Run a co-routine. + * + * vCoRoutineSchedule() executes the highest priority co-routine that is able + * to run. The co-routine will execute until it either blocks, yields or is + * preempted by a task. Co-routines execute cooperatively so one + * co-routine cannot be preempted by another, but can be preempted by a task. + * + * If an application comprises of both tasks and co-routines then + * vCoRoutineSchedule should be called from the idle task (in an idle task + * hook). + * + * Example usage: +
+ // This idle task hook will schedule a co-routine each time it is called.
+ // The rest of the idle task will execute between co-routine calls.
+ void vApplicationIdleHook( void )
+ {
+	vCoRoutineSchedule();
+ }
+
+ // Alternatively, if you do not require any other part of the idle task to
+ // execute, the idle task hook can call vCoRoutineScheduler() within an
+ // infinite loop.
+ void vApplicationIdleHook( void )
+ {
+    for( ;; )
+    {
+        vCoRoutineSchedule();
+    }
+ }
+ 
+ * \defgroup vCoRoutineSchedule vCoRoutineSchedule + * \ingroup Tasks + */ +void vCoRoutineSchedule( void ); + +/** + * croutine. h + *
+ crSTART( xCoRoutineHandle xHandle );
+ * + * This macro MUST always be called at the start of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crSTART( pxCRCB ) switch( ( ( corCRCB * )( pxCRCB ) )->uxState ) { case 0: + +/** + * croutine. h + *
+ crEND();
+ * + * This macro MUST always be called at the end of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crEND() } + +/* + * These macros are intended for internal use by the co-routine implementation + * only. The macros should not be used directly by application writers. + */ +#define crSET_STATE0( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): +#define crSET_STATE1( xHandle ) ( ( corCRCB * )( xHandle ) )->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): + +/** + * croutine. h + *
+ crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
+ * + * Delay a co-routine for a fixed period of time. + * + * crDELAY can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * @param xHandle The handle of the co-routine to delay. This is the xHandle + * parameter of the co-routine function. + * + * @param xTickToDelay The number of ticks that the co-routine should delay + * for. The actual amount of time this equates to is defined by + * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS + * can be used to convert ticks to milliseconds. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ // We are to delay for 200ms.
+ static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+        // Delay for 200ms.
+        crDELAY( xHandle, xDelayTime );
+
+        // Do something here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crDELAY crDELAY + * \ingroup Tasks + */ +#define crDELAY( xHandle, xTicksToDelay ) \ + if( ( xTicksToDelay ) > 0 ) \ + { \ + vCoRoutineAddToDelayedList( ( xTicksToDelay ), NULL ); \ + } \ + crSET_STATE0( ( xHandle ) ); + +/** + *
+ crQUEUE_SEND(
+                  xCoRoutineHandle xHandle,
+                  xQueueHandle pxQueue,
+                  void *pvItemToQueue,
+                  portTickType xTicksToWait,
+                  portBASE_TYPE *pxResult
+             )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_SEND can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue on which the data will be posted. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvItemToQueue A pointer to the data being posted onto the queue. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied from pvItemToQueue into the queue + * itself. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for space to become available on the queue, should space not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example + * below). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully posted onto the queue, otherwise it will be set to an + * error defined within ProjDefs.h. + * + * Example usage: +
+ // Co-routine function that blocks for a fixed period then posts a number onto
+ // a queue.
+ static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xNumberToPost = 0;
+ static portBASE_TYPE xResult;
+
+    // Co-routines must begin with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // This assumes the queue has already been created.
+        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
+
+        if( xResult != pdPASS )
+        {
+            // The message was not posted!
+        }
+
+        // Increment the number to be posted onto the queue.
+        xNumberToPost++;
+
+        // Delay for 100 ticks.
+        crDELAY( xHandle, 100 );
+    }
+
+    // Co-routines must end with a call to crEND().
+    crEND();
+ }
+ * \defgroup crQUEUE_SEND crQUEUE_SEND + * \ingroup Tasks + */ +#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRSend( ( pxQueue) , ( pvItemToQueue) , ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *pxResult = xQueueCRSend( ( pxQueue ), ( pvItemToQueue ), 0 ); \ + } \ + if( *pxResult == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *pxResult = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_RECEIVE(
+                     xCoRoutineHandle xHandle,
+                     xQueueHandle pxQueue,
+                     void *pvBuffer,
+                     portTickType xTicksToWait,
+                     portBASE_TYPE *pxResult
+                 )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_RECEIVE can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue from which the data will be received. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvBuffer The buffer into which the received item is to be copied. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied into pvBuffer. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for data to become available from the queue, should data not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the + * crQUEUE_SEND example). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully retrieved from the queue, otherwise it will be set to + * an error code as defined within ProjDefs.h. + * + * Example usage: +
+ // A co-routine receives the number of an LED to flash from a queue.  It
+ // blocks on the queue until the number is received.
+ static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xResult;
+ static unsigned portBASE_TYPE uxLEDToFlash;
+
+    // All co-routines must start with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // Wait for data to become available on the queue.
+        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+        if( xResult == pdPASS )
+        {
+            // We received the LED to flash - flash it!
+            vParTestToggleLED( uxLEDToFlash );
+        }
+    }
+
+    crEND();
+ }
+ * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ +{ \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), ( xTicksToWait ) ); \ + if( *( pxResult ) == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( ( xHandle ) ); \ + *( pxResult ) = xQueueCRReceive( ( pxQueue) , ( pvBuffer ), 0 ); \ + } \ + if( *( pxResult ) == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( ( xHandle ) ); \ + *( pxResult ) = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvItemToQueue,
+                            portBASE_TYPE xCoRoutinePreviouslyWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue + * that is being used from within a co-routine. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto + * the same queue multiple times from a single interrupt. The first call + * should always pass in pdFALSE. Subsequent calls should pass in + * the value returned from the previous call. + * + * @return pdTRUE if a co-routine was woken by posting onto the queue. This is + * used by the ISR to determine if a context switch may be required following + * the ISR. + * + * Example usage: +
+ // A co-routine that blocks on a queue waiting for characters to be received.
+ static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ char cRxedChar;
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Wait for data to become available on the queue.  This assumes the
+         // queue xCommsRxQueue has already been created!
+         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+         // Was a character received?
+         if( xResult == pdPASS )
+         {
+             // Process the character here.
+         }
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to send characters received on a serial port to
+ // a co-routine.
+ void vUART_ISR( void )
+ {
+ char cRxedChar;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     // We loop around reading characters until there are none left in the UART.
+     while( UART_RX_REG_NOT_EMPTY() )
+     {
+         // Obtain the character from the UART.
+         cRxedChar = UART_RX_REG;
+
+         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
+         // the first time around the loop.  If the post causes a co-routine
+         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
+         // In this manner we can ensure that if more than one co-routine is
+         // blocked on the queue only one is woken by this ISR no matter how
+         // many characters are posted to the queue.
+         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
+     }
+ }
+ * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( xCoRoutinePreviouslyWoken ) ) + + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvBuffer,
+                            portBASE_TYPE * pxCoRoutineWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data + * from a queue that is being used from within a co-routine (a co-routine + * posted to the queue). + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvBuffer A pointer to a buffer into which the received item will be + * placed. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from the queue into + * pvBuffer. + * + * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become + * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a + * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise + * *pxCoRoutineWoken will remain unchanged. + * + * @return pdTRUE an item was successfully received from the queue, otherwise + * pdFALSE. + * + * Example usage: +
+ // A co-routine that posts a character to a queue then blocks for a fixed
+ // period.  The character is incremented each time.
+ static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // cChar holds its value while this co-routine is blocked and must therefore
+ // be declared static.
+ static char cCharToTx = 'a';
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Send the next character to the queue.
+         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
+
+         if( xResult == pdPASS )
+         {
+             // The character was successfully posted to the queue.
+         }
+		 else
+		 {
+			// Could not post the character to the queue.
+		 }
+
+         // Enable the UART Tx interrupt to cause an interrupt in this
+		 // hypothetical UART.  The interrupt will obtain the character
+		 // from the queue and send it.
+		 ENABLE_RX_INTERRUPT();
+
+		 // Increment to the next character then block for a fixed period.
+		 // cCharToTx will maintain its value across the delay as it is
+		 // declared static.
+		 cCharToTx++;
+		 if( cCharToTx > 'x' )
+		 {
+			cCharToTx = 'a';
+		 }
+		 crDELAY( 100 );
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to receive characters to send on a UART.
+ void vUART_ISR( void )
+ {
+ char cCharToTx;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     while( UART_TX_REG_EMPTY() )
+     {
+         // Are there any characters in the queue waiting to be sent?
+		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
+		 // is woken by the post - ensuring that only a single co-routine is
+		 // woken no matter how many times we go around this loop.
+         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
+		 {
+			 SEND_CHARACTER( cCharToTx );
+		 }
+     }
+ }
+ * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( ( pxQueue ), ( pvBuffer ), ( pxCoRoutineWoken ) ) + +/* + * This function is intended for internal use by the co-routine macros only. + * The macro nature of the co-routine implementation requires that the + * prototype appears here. The function should not be used by application + * writers. + * + * Removes the current co-routine from its ready list and places it in the + * appropriate delayed list. + */ +void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); + +/* + * This function is intended for internal use by the queue implementation only. + * The function should not be used by application writers. + * + * Removes the highest priority co-routine from the event list and places it in + * the pending ready list. + */ +signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); + +#ifdef __cplusplus +} +#endif + +#endif /* CO_ROUTINE_H */ diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h index 28d4f248e..9c5fdbe3b 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/list.h @@ -1,337 +1,337 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -/* - * This is the list implementation used by the scheduler. While it is tailored - * heavily for the schedulers needs, it is also available for use by - * application code. - * - * xLists can only store pointers to xListItems. Each xListItem contains a - * numeric value (xItemValue). Most of the time the lists are sorted in - * descending item value order. - * - * Lists are created already containing one list item. The value of this - * item is the maximum possible that can be stored, it is therefore always at - * the end of the list and acts as a marker. The list member pxHead always - * points to this marker - even though it is at the tail of the list. This - * is because the tail contains a wrap back pointer to the true head of - * the list. - * - * In addition to it's value, each list item contains a pointer to the next - * item in the list (pxNext), a pointer to the list it is in (pxContainer) - * and a pointer to back to the object that contains it. These later two - * pointers are included for efficiency of list manipulation. There is - * effectively a two way link between the object containing the list item and - * the list item itself. - * - * - * \page ListIntroduction List Implementation - * \ingroup FreeRTOSIntro - */ - - -#ifndef LIST_H -#define LIST_H - -#ifdef __cplusplus -extern "C" { -#endif -/* - * Definition of the only type of object that a list can contain. - */ -struct xLIST_ITEM -{ - portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ - volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ - volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ - void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ - void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ -}; -typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ - -struct xMINI_LIST_ITEM -{ - portTickType xItemValue; - volatile struct xLIST_ITEM *pxNext; - volatile struct xLIST_ITEM *pxPrevious; -}; -typedef struct xMINI_LIST_ITEM xMiniListItem; - -/* - * Definition of the type of queue used by the scheduler. - */ -typedef struct xLIST -{ - volatile unsigned portBASE_TYPE uxNumberOfItems; - volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ - volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ -} xList; - -/* - * Access macro to set the owner of a list item. The owner of a list item - * is the object (usually a TCB) that contains the list item. - * - * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) - -/* - * Access macro to get the owner of a list item. The owner of a list item - * is the object (usually a TCB) that contains the list item. - * - * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER - * \ingroup LinkedList - */ -#define listGET_LIST_ITEM_OWNER( pxListItem ) ( pxListItem )->pvOwner - -/* - * Access macro to set the value of the list item. In most cases the value is - * used to sort the list in descending order. - * - * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = ( xValue ) - -/* - * Access macro to retrieve the value of the list item. The value can - * represent anything - for example a the priority of a task, or the time at - * which a task should be unblocked. - * - * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) - -/* - * Access macro the retrieve the value of the list item at the head of a given - * list. - * - * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->xItemValue ) - -/* - * Access macro to determine if a list contains any items. The macro will - * only have the value true if the list is empty. - * - * \page listLIST_IS_EMPTY listLIST_IS_EMPTY - * \ingroup LinkedList - */ -#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) - -/* - * Access macro to return the number of items in the list. - */ -#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) - -/* - * Access function to obtain the owner of the next entry in a list. - * - * The list member pxIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list - * and returns that entries pxOwner parameter. Using multiple calls to this - * function it is therefore possible to move through every item contained in - * a list. - * - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the next item owner is to be returned. - * - * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ -{ \ -xList * const pxConstList = ( pxList ); \ - /* Increment the index to the next item and return the item, ensuring */ \ - /* we don't return the marker used at the end of the list. */ \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ - { \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - } \ - ( pxTCB ) = ( pxConstList )->pxIndex->pvOwner; \ -} - - -/* - * Access function to obtain the owner of the first entry in a list. Lists - * are normally sorted in ascending item value order. - * - * This function returns the pxOwner member of the first item in the list. - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the owner of the head item is to be - * returned. - * - * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner ) - -/* - * Check to see if a list item is within a list. The list item maintains a - * "container" pointer that points to the list it is in. All this macro does - * is check to see if the container and the list match. - * - * @param pxList The list we want to know if the list item is within. - * @param pxListItem The list item we want to know if is in the list. - * @return pdTRUE is the list item is in the list, otherwise pdFALSE. - * pointer against - */ -#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) ( pxList ) ) - -/* - * This provides a crude means of knowing if a list has been initialised, as - * pxList->xListEnd.xItemValue is set to portMAX_DELAY by the vListInitialise() - * function. - */ -#define listLIST_IS_INITIALISED( pxList ) ( ( pxList )->xListEnd.xItemValue == portMAX_DELAY ) - -/* - * Must be called before a list is used! This initialises all the members - * of the list structure and inserts the xListEnd item into the list as a - * marker to the back of the list. - * - * @param pxList Pointer to the list being initialised. - * - * \page vListInitialise vListInitialise - * \ingroup LinkedList - */ -void vListInitialise( xList *pxList ); - -/* - * Must be called before a list item is used. This sets the list container to - * null so the item does not think that it is already contained in a list. - * - * @param pxItem Pointer to the list item being initialised. - * - * \page vListInitialiseItem vListInitialiseItem - * \ingroup LinkedList - */ -void vListInitialiseItem( xListItem *pxItem ); - -/* - * Insert a list item into a list. The item will be inserted into the list in - * a position determined by its item value (descending item value order). - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The item to that is to be placed in the list. - * - * \page vListInsert vListInsert - * \ingroup LinkedList - */ -void vListInsert( xList *pxList, xListItem *pxNewListItem ); - -/* - * Insert a list item into a list. The item will be inserted in a position - * such that it will be the last item within the list returned by multiple - * calls to listGET_OWNER_OF_NEXT_ENTRY. - * - * The list member pvIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. - * Placing an item in a list using vListInsertEnd effectively places the item - * in the list position pointed to by pvIndex. This means that every other - * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before - * the pvIndex parameter again points to the item being inserted. - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The list item to be inserted into the list. - * - * \page vListInsertEnd vListInsertEnd - * \ingroup LinkedList - */ -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); - -/* - * Remove an item from a list. The list item has a pointer to the list that - * it is in, so only the list item need be passed into the function. - * - * @param vListRemove The item to be removed. The item will remove itself from - * the list pointed to by it's pxContainer parameter. - * - * \page vListRemove vListRemove - * \ingroup LinkedList - */ -void vListRemove( xListItem *pxItemToRemove ); - -#ifdef __cplusplus -} -#endif - -#endif - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +/* + * This is the list implementation used by the scheduler. While it is tailored + * heavily for the schedulers needs, it is also available for use by + * application code. + * + * xLists can only store pointers to xListItems. Each xListItem contains a + * numeric value (xItemValue). Most of the time the lists are sorted in + * descending item value order. + * + * Lists are created already containing one list item. The value of this + * item is the maximum possible that can be stored, it is therefore always at + * the end of the list and acts as a marker. The list member pxHead always + * points to this marker - even though it is at the tail of the list. This + * is because the tail contains a wrap back pointer to the true head of + * the list. + * + * In addition to it's value, each list item contains a pointer to the next + * item in the list (pxNext), a pointer to the list it is in (pxContainer) + * and a pointer to back to the object that contains it. These later two + * pointers are included for efficiency of list manipulation. There is + * effectively a two way link between the object containing the list item and + * the list item itself. + * + * + * \page ListIntroduction List Implementation + * \ingroup FreeRTOSIntro + */ + + +#ifndef LIST_H +#define LIST_H + +#ifdef __cplusplus +extern "C" { +#endif +/* + * Definition of the only type of object that a list can contain. + */ +struct xLIST_ITEM +{ + portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ + volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ + volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ + void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ + void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ +}; +typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ + +struct xMINI_LIST_ITEM +{ + portTickType xItemValue; + volatile struct xLIST_ITEM *pxNext; + volatile struct xLIST_ITEM *pxPrevious; +}; +typedef struct xMINI_LIST_ITEM xMiniListItem; + +/* + * Definition of the type of queue used by the scheduler. + */ +typedef struct xLIST +{ + volatile unsigned portBASE_TYPE uxNumberOfItems; + volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ + volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ +} xList; + +/* + * Access macro to set the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) ( pxOwner ) + +/* + * Access macro to get the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_OWNER( pxListItem ) ( pxListItem )->pvOwner + +/* + * Access macro to set the value of the list item. In most cases the value is + * used to sort the list in descending order. + * + * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = ( xValue ) + +/* + * Access macro to retrieve the value of the list item. The value can + * represent anything - for example a the priority of a task, or the time at + * which a task should be unblocked. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) + +/* + * Access macro the retrieve the value of the list item at the head of a given + * list. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->xItemValue ) + +/* + * Access macro to determine if a list contains any items. The macro will + * only have the value true if the list is empty. + * + * \page listLIST_IS_EMPTY listLIST_IS_EMPTY + * \ingroup LinkedList + */ +#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) + +/* + * Access macro to return the number of items in the list. + */ +#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) + +/* + * Access function to obtain the owner of the next entry in a list. + * + * The list member pxIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list + * and returns that entries pxOwner parameter. Using multiple calls to this + * function it is therefore possible to move through every item contained in + * a list. + * + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the next item owner is to be returned. + * + * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ +{ \ +xList * const pxConstList = ( pxList ); \ + /* Increment the index to the next item and return the item, ensuring */ \ + /* we don't return the marker used at the end of the list. */ \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ + { \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + } \ + ( pxTCB ) = ( pxConstList )->pxIndex->pvOwner; \ +} + + +/* + * Access function to obtain the owner of the first entry in a list. Lists + * are normally sorted in ascending item value order. + * + * This function returns the pxOwner member of the first item in the list. + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the owner of the head item is to be + * returned. + * + * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( (&( ( pxList )->xListEnd ))->pxNext->pvOwner ) + +/* + * Check to see if a list item is within a list. The list item maintains a + * "container" pointer that points to the list it is in. All this macro does + * is check to see if the container and the list match. + * + * @param pxList The list we want to know if the list item is within. + * @param pxListItem The list item we want to know if is in the list. + * @return pdTRUE is the list item is in the list, otherwise pdFALSE. + * pointer against + */ +#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) ( pxList ) ) + +/* + * This provides a crude means of knowing if a list has been initialised, as + * pxList->xListEnd.xItemValue is set to portMAX_DELAY by the vListInitialise() + * function. + */ +#define listLIST_IS_INITIALISED( pxList ) ( ( pxList )->xListEnd.xItemValue == portMAX_DELAY ) + +/* + * Must be called before a list is used! This initialises all the members + * of the list structure and inserts the xListEnd item into the list as a + * marker to the back of the list. + * + * @param pxList Pointer to the list being initialised. + * + * \page vListInitialise vListInitialise + * \ingroup LinkedList + */ +void vListInitialise( xList *pxList ); + +/* + * Must be called before a list item is used. This sets the list container to + * null so the item does not think that it is already contained in a list. + * + * @param pxItem Pointer to the list item being initialised. + * + * \page vListInitialiseItem vListInitialiseItem + * \ingroup LinkedList + */ +void vListInitialiseItem( xListItem *pxItem ); + +/* + * Insert a list item into a list. The item will be inserted into the list in + * a position determined by its item value (descending item value order). + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The item to that is to be placed in the list. + * + * \page vListInsert vListInsert + * \ingroup LinkedList + */ +void vListInsert( xList *pxList, xListItem *pxNewListItem ); + +/* + * Insert a list item into a list. The item will be inserted in a position + * such that it will be the last item within the list returned by multiple + * calls to listGET_OWNER_OF_NEXT_ENTRY. + * + * The list member pvIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. + * Placing an item in a list using vListInsertEnd effectively places the item + * in the list position pointed to by pvIndex. This means that every other + * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before + * the pvIndex parameter again points to the item being inserted. + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The list item to be inserted into the list. + * + * \page vListInsertEnd vListInsertEnd + * \ingroup LinkedList + */ +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); + +/* + * Remove an item from a list. The list item has a pointer to the list that + * it is in, so only the list item need be passed into the function. + * + * @param vListRemove The item to be removed. The item will remove itself from + * the list pointed to by it's pxContainer parameter. + * + * \page vListRemove vListRemove + * \ingroup LinkedList + */ +void vListRemove( xListItem *pxItemToRemove ); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h index be49c3d88..5ddd22234 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/mpu_wrappers.h @@ -1,146 +1,146 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef MPU_WRAPPERS_H -#define MPU_WRAPPERS_H - -/* This file redefines API functions to be called through a wrapper macro, but -only for ports that are using the MPU. */ -#ifdef portUSING_MPU_WRAPPERS - - /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is - included from queue.c or task.c to prevent it from having an effect within - those files. */ - #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - - #define xTaskGenericCreate MPU_xTaskGenericCreate - #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions - #define vTaskDelete MPU_vTaskDelete - #define vTaskDelayUntil MPU_vTaskDelayUntil - #define vTaskDelay MPU_vTaskDelay - #define uxTaskPriorityGet MPU_uxTaskPriorityGet - #define vTaskPrioritySet MPU_vTaskPrioritySet - #define vTaskSuspend MPU_vTaskSuspend - #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended - #define vTaskResume MPU_vTaskResume - #define vTaskSuspendAll MPU_vTaskSuspendAll - #define xTaskResumeAll MPU_xTaskResumeAll - #define xTaskGetTickCount MPU_xTaskGetTickCount - #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks - #define vTaskList MPU_vTaskList - #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats - #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag - #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag - #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook - #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark - #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle - #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState - - #define xQueueGenericCreate MPU_xQueueGenericCreate - #define xQueueCreateMutex MPU_xQueueCreateMutex - #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive - #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive - #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore - #define xQueueGenericSend MPU_xQueueGenericSend - #define xQueueAltGenericSend MPU_xQueueAltGenericSend - #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive - #define xQueueGenericReceive MPU_xQueueGenericReceive - #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting - #define vQueueDelete MPU_vQueueDelete - - #define pvPortMalloc MPU_pvPortMalloc - #define vPortFree MPU_vPortFree - #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize - #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks - - #if configQUEUE_REGISTRY_SIZE > 0 - #define vQueueAddToRegistry MPU_vQueueAddToRegistry - #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue - #endif - - /* Remove the privileged function macro. */ - #define PRIVILEGED_FUNCTION - - #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - - /* Ensure API functions go in the privileged execution section. */ - #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) - #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) - //#define PRIVILEGED_DATA - - #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - -#else /* portUSING_MPU_WRAPPERS */ - - #define PRIVILEGED_FUNCTION - #define PRIVILEGED_DATA - #define portUSING_MPU_WRAPPERS 0 - -#endif /* portUSING_MPU_WRAPPERS */ - - -#endif /* MPU_WRAPPERS_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef MPU_WRAPPERS_H +#define MPU_WRAPPERS_H + +/* This file redefines API functions to be called through a wrapper macro, but +only for ports that are using the MPU. */ +#ifdef portUSING_MPU_WRAPPERS + + /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is + included from queue.c or task.c to prevent it from having an effect within + those files. */ + #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + + #define xTaskGenericCreate MPU_xTaskGenericCreate + #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions + #define vTaskDelete MPU_vTaskDelete + #define vTaskDelayUntil MPU_vTaskDelayUntil + #define vTaskDelay MPU_vTaskDelay + #define uxTaskPriorityGet MPU_uxTaskPriorityGet + #define vTaskPrioritySet MPU_vTaskPrioritySet + #define vTaskSuspend MPU_vTaskSuspend + #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended + #define vTaskResume MPU_vTaskResume + #define vTaskSuspendAll MPU_vTaskSuspendAll + #define xTaskResumeAll MPU_xTaskResumeAll + #define xTaskGetTickCount MPU_xTaskGetTickCount + #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks + #define vTaskList MPU_vTaskList + #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats + #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag + #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag + #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook + #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark + #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle + #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState + + #define xQueueGenericCreate MPU_xQueueGenericCreate + #define xQueueCreateMutex MPU_xQueueCreateMutex + #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive + #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive + #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore + #define xQueueGenericSend MPU_xQueueGenericSend + #define xQueueAltGenericSend MPU_xQueueAltGenericSend + #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive + #define xQueueGenericReceive MPU_xQueueGenericReceive + #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting + #define vQueueDelete MPU_vQueueDelete + + #define pvPortMalloc MPU_pvPortMalloc + #define vPortFree MPU_vPortFree + #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize + #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks + + #if configQUEUE_REGISTRY_SIZE > 0 + #define vQueueAddToRegistry MPU_vQueueAddToRegistry + #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue + #endif + + /* Remove the privileged function macro. */ + #define PRIVILEGED_FUNCTION + + #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + + /* Ensure API functions go in the privileged execution section. */ + #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) + #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) + //#define PRIVILEGED_DATA + + #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + +#else /* portUSING_MPU_WRAPPERS */ + + #define PRIVILEGED_FUNCTION + #define PRIVILEGED_DATA + #define portUSING_MPU_WRAPPERS 0 + +#endif /* portUSING_MPU_WRAPPERS */ + + +#endif /* MPU_WRAPPERS_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h index 88cfbb2b7..69aa5f813 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/portable.h @@ -1,403 +1,403 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -/*----------------------------------------------------------- - * Portable layer API. Each function must be defined for each port. - *----------------------------------------------------------*/ - -#ifndef PORTABLE_H -#define PORTABLE_H - -/* Include the macro file relevant to the port being used. */ - -#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT - #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT - #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef GCC_MEGA_AVR - #include "../portable/GCC/ATMega323/portmacro.h" -#endif - -#ifdef IAR_MEGA_AVR - #include "../portable/IAR/ATMega323/portmacro.h" -#endif - -#ifdef MPLAB_PIC24_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_DSPIC_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_PIC18F_PORT - #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" -#endif - -#ifdef MPLAB_PIC32MX_PORT - #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" -#endif - -#ifdef _FEDPICC - #include "libFreeRTOS/Include/portmacro.h" -#endif - -#ifdef SDCC_CYGNAL - #include "../../Source/portable/SDCC/Cygnal/portmacro.h" -#endif - -#ifdef GCC_ARM7 - #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" -#endif - -#ifdef GCC_ARM7_ECLIPSE - #include "portmacro.h" -#endif - -#ifdef ROWLEY_LPC23xx - #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" -#endif - -#ifdef IAR_MSP430 - #include "..\..\Source\portable\IAR\MSP430\portmacro.h" -#endif - -#ifdef GCC_MSP430 - #include "../../Source/portable/GCC/MSP430F449/portmacro.h" -#endif - -#ifdef ROWLEY_MSP430 - #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" -#endif - -#ifdef ARM7_LPC21xx_KEIL_RVDS - #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" -#endif - -#ifdef SAM7_GCC - #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" -#endif - -#ifdef SAM7_IAR - #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" -#endif - -#ifdef SAM9XE_IAR - #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" -#endif - -#ifdef LPC2000_IAR - #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" -#endif - -#ifdef STR71X_IAR - #include "..\..\Source\portable\IAR\STR71x\portmacro.h" -#endif - -#ifdef STR75X_IAR - #include "..\..\Source\portable\IAR\STR75x\portmacro.h" -#endif - -#ifdef STR75X_GCC - #include "..\..\Source\portable\GCC\STR75x\portmacro.h" -#endif - -#ifdef STR91X_IAR - #include "..\..\Source\portable\IAR\STR91x\portmacro.h" -#endif - -#ifdef GCC_H8S - #include "../../Source/portable/GCC/H8S2329/portmacro.h" -#endif - -#ifdef GCC_AT91FR40008 - #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" -#endif - -#ifdef RVDS_ARMCM3_LM3S102 - #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3_LM3S102 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARM_CM3 - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARMCM3_LM - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef HCS12_CODE_WARRIOR - #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" -#endif - -#ifdef MICROBLAZE_GCC - #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" -#endif - -#ifdef TERN_EE - #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" -#endif - -#ifdef GCC_HCS12 - #include "../../Source/portable/GCC/HCS12/portmacro.h" -#endif - -#ifdef GCC_MCF5235 - #include "../../Source/portable/GCC/MCF5235/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_GCC - #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_CODEWARRIOR - #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" -#endif - -#ifdef GCC_PPC405 - #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" -#endif - -#ifdef GCC_PPC440 - #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" -#endif - -#ifdef _16FX_SOFTUNE - #include "..\..\Source\portable\Softune\MB96340\portmacro.h" -#endif - -#ifdef BCC_INDUSTRIAL_PC_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef BCC_FLASH_LITE_186_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef __GNUC__ - #ifdef __AVR32_AVR32A__ - #include "portmacro.h" - #endif -#endif - -#ifdef __ICCAVR32__ - #ifdef __CORE__ - #if __CORE__ == __AVR32A__ - #include "portmacro.h" - #endif - #endif -#endif - -#ifdef __91467D - #include "portmacro.h" -#endif - -#ifdef __96340 - #include "portmacro.h" -#endif - - -#ifdef __IAR_V850ES_Fx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3_L__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Hx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3L__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -/* Catch all to ensure portmacro.h is included in the build. Newer demos -have the path as part of the project options, rather than as relative from -the project location. If portENTER_CRITICAL() has not been defined then -portmacro.h has not yet been included - as every portmacro.h provides a -portENTER_CRITICAL() definition. Check the demo application for your demo -to find the path to the correct portmacro.h file. */ -#ifndef portENTER_CRITICAL - #include "portmacro.h" -#endif - -#if portBYTE_ALIGNMENT == 8 - #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) -#endif - -#if portBYTE_ALIGNMENT == 4 - #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) -#endif - -#if portBYTE_ALIGNMENT == 2 - #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) -#endif - -#if portBYTE_ALIGNMENT == 1 - #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) -#endif - -#ifndef portBYTE_ALIGNMENT_MASK - #error "Invalid portBYTE_ALIGNMENT definition" -#endif - -#ifndef portNUM_CONFIGURABLE_REGIONS - #define portNUM_CONFIGURABLE_REGIONS 1 -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -#include "mpu_wrappers.h" - -/* - * Setup the stack of a new task so it is ready to be placed under the - * scheduler control. The registers have to be placed on the stack in - * the order that the port expects to find them. - * - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; -#else - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ); -#endif - -/* - * Map to the memory management routines required for the port. - */ -void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; -void vPortFree( void *pv ) PRIVILEGED_FUNCTION; -void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; -size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; - -/* - * Setup the hardware ready for the scheduler to take control. This generally - * sets up a tick interrupt and sets timers for the correct tick frequency. - */ -portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so - * the hardware is left in its original condition after the scheduler stops - * executing. - */ -void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * The structures and methods of manipulating the MPU are contained within the - * port layer. - * - * Fills the xMPUSettings structure with the memory region information - * contained in xRegions. - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - struct xMEMORY_REGION; - void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* PORTABLE_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +/*----------------------------------------------------------- + * Portable layer API. Each function must be defined for each port. + *----------------------------------------------------------*/ + +#ifndef PORTABLE_H +#define PORTABLE_H + +/* Include the macro file relevant to the port being used. */ + +#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT + #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT + #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef GCC_MEGA_AVR + #include "../portable/GCC/ATMega323/portmacro.h" +#endif + +#ifdef IAR_MEGA_AVR + #include "../portable/IAR/ATMega323/portmacro.h" +#endif + +#ifdef MPLAB_PIC24_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_DSPIC_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_PIC18F_PORT + #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" +#endif + +#ifdef MPLAB_PIC32MX_PORT + #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" +#endif + +#ifdef _FEDPICC + #include "libFreeRTOS/Include/portmacro.h" +#endif + +#ifdef SDCC_CYGNAL + #include "../../Source/portable/SDCC/Cygnal/portmacro.h" +#endif + +#ifdef GCC_ARM7 + #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" +#endif + +#ifdef GCC_ARM7_ECLIPSE + #include "portmacro.h" +#endif + +#ifdef ROWLEY_LPC23xx + #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" +#endif + +#ifdef IAR_MSP430 + #include "..\..\Source\portable\IAR\MSP430\portmacro.h" +#endif + +#ifdef GCC_MSP430 + #include "../../Source/portable/GCC/MSP430F449/portmacro.h" +#endif + +#ifdef ROWLEY_MSP430 + #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" +#endif + +#ifdef ARM7_LPC21xx_KEIL_RVDS + #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" +#endif + +#ifdef SAM7_GCC + #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" +#endif + +#ifdef SAM7_IAR + #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" +#endif + +#ifdef SAM9XE_IAR + #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" +#endif + +#ifdef LPC2000_IAR + #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" +#endif + +#ifdef STR71X_IAR + #include "..\..\Source\portable\IAR\STR71x\portmacro.h" +#endif + +#ifdef STR75X_IAR + #include "..\..\Source\portable\IAR\STR75x\portmacro.h" +#endif + +#ifdef STR75X_GCC + #include "..\..\Source\portable\GCC\STR75x\portmacro.h" +#endif + +#ifdef STR91X_IAR + #include "..\..\Source\portable\IAR\STR91x\portmacro.h" +#endif + +#ifdef GCC_H8S + #include "../../Source/portable/GCC/H8S2329/portmacro.h" +#endif + +#ifdef GCC_AT91FR40008 + #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" +#endif + +#ifdef RVDS_ARMCM3_LM3S102 + #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3_LM3S102 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARM_CM3 + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARMCM3_LM + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef HCS12_CODE_WARRIOR + #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" +#endif + +#ifdef MICROBLAZE_GCC + #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" +#endif + +#ifdef TERN_EE + #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" +#endif + +#ifdef GCC_HCS12 + #include "../../Source/portable/GCC/HCS12/portmacro.h" +#endif + +#ifdef GCC_MCF5235 + #include "../../Source/portable/GCC/MCF5235/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_GCC + #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_CODEWARRIOR + #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" +#endif + +#ifdef GCC_PPC405 + #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" +#endif + +#ifdef GCC_PPC440 + #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" +#endif + +#ifdef _16FX_SOFTUNE + #include "..\..\Source\portable\Softune\MB96340\portmacro.h" +#endif + +#ifdef BCC_INDUSTRIAL_PC_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef BCC_FLASH_LITE_186_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef __GNUC__ + #ifdef __AVR32_AVR32A__ + #include "portmacro.h" + #endif +#endif + +#ifdef __ICCAVR32__ + #ifdef __CORE__ + #if __CORE__ == __AVR32A__ + #include "portmacro.h" + #endif + #endif +#endif + +#ifdef __91467D + #include "portmacro.h" +#endif + +#ifdef __96340 + #include "portmacro.h" +#endif + + +#ifdef __IAR_V850ES_Fx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3_L__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Hx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3L__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +/* Catch all to ensure portmacro.h is included in the build. Newer demos +have the path as part of the project options, rather than as relative from +the project location. If portENTER_CRITICAL() has not been defined then +portmacro.h has not yet been included - as every portmacro.h provides a +portENTER_CRITICAL() definition. Check the demo application for your demo +to find the path to the correct portmacro.h file. */ +#ifndef portENTER_CRITICAL + #include "portmacro.h" +#endif + +#if portBYTE_ALIGNMENT == 8 + #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) +#endif + +#if portBYTE_ALIGNMENT == 4 + #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) +#endif + +#if portBYTE_ALIGNMENT == 2 + #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) +#endif + +#if portBYTE_ALIGNMENT == 1 + #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) +#endif + +#ifndef portBYTE_ALIGNMENT_MASK + #error "Invalid portBYTE_ALIGNMENT definition" +#endif + +#ifndef portNUM_CONFIGURABLE_REGIONS + #define portNUM_CONFIGURABLE_REGIONS 1 +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#include "mpu_wrappers.h" + +/* + * Setup the stack of a new task so it is ready to be placed under the + * scheduler control. The registers have to be placed on the stack in + * the order that the port expects to find them. + * + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; +#else + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ); +#endif + +/* + * Map to the memory management routines required for the port. + */ +void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; +void vPortFree( void *pv ) PRIVILEGED_FUNCTION; +void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; +size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; + +/* + * Setup the hardware ready for the scheduler to take control. This generally + * sets up a tick interrupt and sets timers for the correct tick frequency. + */ +portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so + * the hardware is left in its original condition after the scheduler stops + * executing. + */ +void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * The structures and methods of manipulating the MPU are contained within the + * port layer. + * + * Fills the xMPUSettings structure with the memory region information + * contained in xRegions. + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + struct xMEMORY_REGION; + void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* PORTABLE_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h index c69db9237..37153ee49 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/projdefs.h @@ -1,90 +1,90 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef PROJDEFS_H -#define PROJDEFS_H - -/* Defines the prototype to which task functions must conform. */ -typedef void (*pdTASK_CODE)( void * ); - -#define pdTRUE ( 1 ) -#define pdFALSE ( 0 ) - -#define pdPASS ( 1 ) -#define pdFAIL ( 0 ) -#define errQUEUE_EMPTY ( 0 ) -#define errQUEUE_FULL ( 0 ) - -/* Error definitions. */ -#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) -#define errNO_TASK_TO_RUN ( -2 ) -#define errQUEUE_BLOCKED ( -4 ) -#define errQUEUE_YIELD ( -5 ) - -#endif /* PROJDEFS_H */ - - - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef PROJDEFS_H +#define PROJDEFS_H + +/* Defines the prototype to which task functions must conform. */ +typedef void (*pdTASK_CODE)( void * ); + +#define pdTRUE ( 1 ) +#define pdFALSE ( 0 ) + +#define pdPASS ( 1 ) +#define pdFAIL ( 0 ) +#define errQUEUE_EMPTY ( 0 ) +#define errQUEUE_FULL ( 0 ) + +/* Error definitions. */ +#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) +#define errNO_TASK_TO_RUN ( -2 ) +#define errQUEUE_BLOCKED ( -4 ) +#define errQUEUE_YIELD ( -5 ) + +#endif /* PROJDEFS_H */ + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h index e48cf07a6..88af6ced0 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/queue.h @@ -1,1300 +1,1300 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#ifndef QUEUE_H -#define QUEUE_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h" must appear in source files before "include queue.h" -#endif - -#ifdef __cplusplus -extern "C" { -#endif - - -#include "mpu_wrappers.h" - -/** - * Type by which queues are referenced. For example, a call to xQueueCreate - * returns (via a pointer parameter) an xQueueHandle variable that can then - * be used as a parameter to xQueueSend(), xQueueReceive(), etc. - */ -typedef void * xQueueHandle; - - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - -/* For internal use only. These definitions *must* match those in queue.c. */ -#define queueQUEUE_TYPE_BASE ( 0U ) -#define queueQUEUE_TYPE_MUTEX ( 1U ) -#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( 2U ) -#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( 3U ) -#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( 4U ) - -/** - * queue. h - *
- xQueueHandle xQueueCreate(
-							  unsigned portBASE_TYPE uxQueueLength,
-							  unsigned portBASE_TYPE uxItemSize
-						  );
- * 
- * - * Creates a new queue instance. This allocates the storage required by the - * new queue and returns a handle for the queue. - * - * @param uxQueueLength The maximum number of items that the queue can contain. - * - * @param uxItemSize The number of bytes each item in the queue will require. - * Items are queued by copy, not by reference, so this is the number of bytes - * that will be copied for each posted item. Each item on the queue must be - * the same size. - * - * @return If the queue is successfully create then a handle to the newly - * created queue is returned. If the queue cannot be created then 0 is - * returned. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- };
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-	if( xQueue1 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue2 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueCreate xQueueCreate - * \ingroup QueueManagement - */ -#define xQueueCreate( uxQueueLength, uxItemSize ) xQueueGenericCreate( uxQueueLength, uxItemSize, queueQUEUE_TYPE_BASE ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToToFront(
-								   xQueueHandle	xQueue,
-								   const void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the front of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBack(
-								   xQueueHandle	xQueue,
-								   const	void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the back of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the queue - * is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSend(
-							  xQueueHandle xQueue,
-							  const void * pvItemToQueue,
-							  portTickType xTicksToWait
-						 );
- * 
- * - * This is a macro that calls xQueueGenericSend(). It is included for - * backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToFront() and xQueueSendToBack() macros. It is - * equivalent to xQueueSendToBack(). - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSend(
-									xQueueHandle xQueue,
-									const void * pvItemToQueue,
-									portTickType xTicksToWait
-									portBASE_TYPE xCopyPosition
-								);
- * 
- * - * It is preferred that the macros xQueueSend(), xQueueSendToFront() and - * xQueueSendToBack() are used in place of calling this function directly. - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueuePeek(
-							 xQueueHandle xQueue,
-							 void *pvBuffer,
-							 portTickType xTicksToWait
-						 );
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue without removing the item from the queue. - * The item is received by copy so a buffer of adequate size must be - * provided. The number of bytes copied into the buffer was defined when - * the queue was created. - * - * Successfully received items remain on the queue so will be returned again - * by the next call, or a call to xQueueReceive(). - * - * This macro must not be used in an interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue - * is empty. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to peek the data from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Peek a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask, but the item still remains on the queue.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) - -/** - * queue. h - *
- portBASE_TYPE xQueueReceive(
-								 xQueueHandle xQueue,
-								 void *pvBuffer,
-								 portTickType xTicksToWait
-							);
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * Successfully received items are removed from the queue. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. xQueueReceive() will return immediately if xTicksToWait - * is zero and the queue is empty. The time is defined in tick periods so the - * constant portTICK_RATE_MS should be used to convert to real time if this is - * required. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericReceive(
-									   xQueueHandle	xQueue,
-									   void	*pvBuffer,
-									   portTickType	xTicksToWait
-									   portBASE_TYPE	xJustPeek
-									);
- * - * It is preferred that the macro xQueueReceive() be used rather than calling - * this function directly. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueueGenericReceive() will return immediately if the queue is empty and - * xTicksToWait is 0. - * - * @param xJustPeek When set to true, the item received from the queue is not - * actually removed from the queue - meaning a subsequent call to - * xQueueReceive() will return the same item. When set to false, the item - * being received from the queue is also removed from the queue. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); - -/** - * queue. h - *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
- * - * Return the number of messages stored in a queue. - * - * @param xQueue A handle to the queue being queried. - * - * @return The number of messages available in the queue. - * - * \page uxQueueMessagesWaiting uxQueueMessagesWaiting - * \ingroup QueueManagement - */ -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); - -/** - * queue. h - *
void vQueueDelete( xQueueHandle xQueue );
- * - * Delete a queue - freeing all the memory allocated for storing of items - * placed on the queue. - * - * @param xQueue A handle to the queue to be deleted. - * - * \page vQueueDelete vQueueDelete - * \ingroup QueueManagement - */ -void vQueueDelete( xQueueHandle pxQueue ); - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToFrontFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the front of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPrioritTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBackFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the back of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendFromISR(
-									 xQueueHandle pxQueue,
-									 const void *pvItemToQueue,
-									 portBASE_TYPE *pxHigherPriorityTaskWoken
-								);
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). It is included - * for backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() - * macros. - * - * Post an item to the back of a queue. It is safe to use this function from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		// Actual macro used here is port specific.
-		taskYIELD_FROM_ISR ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSendFromISR(
-										   xQueueHandle	pxQueue,
-										   const	void	*pvItemToQueue,
-										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
-										   portBASE_TYPE	xCopyPosition
-									   );
- 
- * - * It is preferred that the macros xQueueSendFromISR(), - * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place - * of calling this function directly. - * - * Post an item on a queue. It is safe to use this function from within an - * interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWokenByPost;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWokenByPost = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post each byte.
-		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.  Note that the
-	// name of the yield function required is port specific.
-	if( xHigherPriorityTaskWokenByPost )
-	{
-		taskYIELD_YIELD_FROM_ISR();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueueReceiveFromISR(
-									   xQueueHandle	pxQueue,
-									   void	*pvBuffer,
-									   portBASE_TYPE	*pxTaskWoken
-								   );
- * 
- * - * Receive an item from a queue. It is safe to use this function from within an - * interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param pxTaskWoken A task may be blocked waiting for space to become - * available on the queue. If xQueueReceiveFromISR causes such a task to - * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will - * remain unchanged. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
-
- xQueueHandle xQueue;
-
- // Function to create a queue and post some values.
- void vAFunction( void *pvParameters )
- {
- char cValueToPost;
- const portTickType xBlockTime = ( portTickType )0xff;
-
-	// Create a queue capable of containing 10 characters.
-	xQueue = xQueueCreate( 10, sizeof( char ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Post some characters that will be used within an ISR.  If the queue
-	// is full then this task will block for xBlockTime ticks.
-	cValueToPost = 'a';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-	cValueToPost = 'b';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-
-	// ... keep posting characters ... this task may block when the queue
-	// becomes full.
-
-	cValueToPost = 'c';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
- }
-
- // ISR that outputs all the characters received on the queue.
- void vISR_Routine( void )
- {
- portBASE_TYPE xTaskWokenByReceive = pdFALSE;
- char cRxedChar;
-
-	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
-	{
-		// A character was received.  Output the character now.
-		vOutputCharacter( cRxedChar );
-
-		// If removing the character from the queue woke the task that was
-		// posting onto the queue cTaskWokenByReceive will have been set to
-		// pdTRUE.  No matter how many times this loop iterates only one
-		// task will be woken.
-	}
-
-	if( cTaskWokenByPost != ( char ) pdFALSE;
-	{
-		taskYIELD ();
-	}
- }
- 
- * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ); - -/* - * Utilities to query queues that are safe to use from an ISR. These utilities - * should be used only from witin an ISR, or within a critical section. - */ -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); - - -/* - * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). - * Likewise xQueueAltGenericReceive() is an alternative version of - * xQueueGenericReceive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); -#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) -#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) -#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) -#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) - -/* - * The functions defined above are for passing data to and from tasks. The - * functions below are the equivalents for passing data to and from - * co-routines. - * - * These functions are called from the co-routine macro implementation and - * should not be called directly from application code. Instead use the macro - * wrappers defined within croutine.h. - */ -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); - -/* - * For internal use only. Use xSemaphoreCreateMutex(), - * xSemaphoreCreateCounting() or xSemaphoreGetMutexHolder() instead of calling - * these functions directly. - */ -xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ); -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); -void* xQueueGetMutexHolder( xQueueHandle xSemaphore ); - -/* - * For internal use only. Use xSemaphoreTakeMutexRecursive() or - * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. - */ -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ); -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ); - -/* - * Reset a queue back to its original empty state. pdPASS is returned if the - * queue is successfully reset. pdFAIL is returned if the queue could not be - * reset because there are tasks blocked on the queue waiting to either - * receive from the queue or send to the queue. - */ -#define xQueueReset( pxQueue ) xQueueGenericReset( pxQueue, pdFALSE ) - -/* - * The registry is provided as a means for kernel aware debuggers to - * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add - * a queue, semaphore or mutex handle to the registry if you want the handle - * to be available to a kernel aware debugger. If you are not using a kernel - * aware debugger then this function can be ignored. - * - * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the - * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 - * within FreeRTOSConfig.h for the registry to be available. Its value - * does not effect the number of queues, semaphores and mutexes that can be - * created - just the number that the registry can hold. - * - * @param xQueue The handle of the queue being added to the registry. This - * is the handle returned by a call to xQueueCreate(). Semaphore and mutex - * handles can also be passed in here. - * - * @param pcName The name to be associated with the handle. This is the - * name that the kernel aware debugger will display. - */ -#if configQUEUE_REGISTRY_SIZE > 0U - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); -#endif - -/* - * Generic version of the queue creation function, which is in turn called by - * any queue, semaphore or mutex creation function or macro. - */ -xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ); - -/* Not public API functions. */ -void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ); -portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ); - - -#ifdef __cplusplus -} -#endif - -#endif /* QUEUE_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#ifndef QUEUE_H +#define QUEUE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h" must appear in source files before "include queue.h" +#endif + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "mpu_wrappers.h" + +/** + * Type by which queues are referenced. For example, a call to xQueueCreate + * returns (via a pointer parameter) an xQueueHandle variable that can then + * be used as a parameter to xQueueSend(), xQueueReceive(), etc. + */ +typedef void * xQueueHandle; + + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + +/* For internal use only. These definitions *must* match those in queue.c. */ +#define queueQUEUE_TYPE_BASE ( 0U ) +#define queueQUEUE_TYPE_MUTEX ( 1U ) +#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( 2U ) +#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( 3U ) +#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( 4U ) + +/** + * queue. h + *
+ xQueueHandle xQueueCreate(
+							  unsigned portBASE_TYPE uxQueueLength,
+							  unsigned portBASE_TYPE uxItemSize
+						  );
+ * 
+ * + * Creates a new queue instance. This allocates the storage required by the + * new queue and returns a handle for the queue. + * + * @param uxQueueLength The maximum number of items that the queue can contain. + * + * @param uxItemSize The number of bytes each item in the queue will require. + * Items are queued by copy, not by reference, so this is the number of bytes + * that will be copied for each posted item. Each item on the queue must be + * the same size. + * + * @return If the queue is successfully create then a handle to the newly + * created queue is returned. If the queue cannot be created then 0 is + * returned. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+	if( xQueue1 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue2 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueCreate xQueueCreate + * \ingroup QueueManagement + */ +#define xQueueCreate( uxQueueLength, uxItemSize ) xQueueGenericCreate( uxQueueLength, uxItemSize, queueQUEUE_TYPE_BASE ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToToFront(
+								   xQueueHandle	xQueue,
+								   const void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the front of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBack(
+								   xQueueHandle	xQueue,
+								   const	void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the back of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the queue + * is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSend(
+							  xQueueHandle xQueue,
+							  const void * pvItemToQueue,
+							  portTickType xTicksToWait
+						 );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). It is included for + * backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToFront() and xQueueSendToBack() macros. It is + * equivalent to xQueueSendToBack(). + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSend(
+									xQueueHandle xQueue,
+									const void * pvItemToQueue,
+									portTickType xTicksToWait
+									portBASE_TYPE xCopyPosition
+								);
+ * 
+ * + * It is preferred that the macros xQueueSend(), xQueueSendToFront() and + * xQueueSendToBack() are used in place of calling this function directly. + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueuePeek(
+							 xQueueHandle xQueue,
+							 void *pvBuffer,
+							 portTickType xTicksToWait
+						 );
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue without removing the item from the queue. + * The item is received by copy so a buffer of adequate size must be + * provided. The number of bytes copied into the buffer was defined when + * the queue was created. + * + * Successfully received items remain on the queue so will be returned again + * by the next call, or a call to xQueueReceive(). + * + * This macro must not be used in an interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue + * is empty. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to peek the data from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Peek a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask, but the item still remains on the queue.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceive(
+								 xQueueHandle xQueue,
+								 void *pvBuffer,
+								 portTickType xTicksToWait
+							);
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * Successfully received items are removed from the queue. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. xQueueReceive() will return immediately if xTicksToWait + * is zero and the queue is empty. The time is defined in tick periods so the + * constant portTICK_RATE_MS should be used to convert to real time if this is + * required. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericReceive(
+									   xQueueHandle	xQueue,
+									   void	*pvBuffer,
+									   portTickType	xTicksToWait
+									   portBASE_TYPE	xJustPeek
+									);
+ * + * It is preferred that the macro xQueueReceive() be used rather than calling + * this function directly. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueueGenericReceive() will return immediately if the queue is empty and + * xTicksToWait is 0. + * + * @param xJustPeek When set to true, the item received from the queue is not + * actually removed from the queue - meaning a subsequent call to + * xQueueReceive() will return the same item. When set to false, the item + * being received from the queue is also removed from the queue. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); + +/** + * queue. h + *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
+ * + * Return the number of messages stored in a queue. + * + * @param xQueue A handle to the queue being queried. + * + * @return The number of messages available in the queue. + * + * \page uxQueueMessagesWaiting uxQueueMessagesWaiting + * \ingroup QueueManagement + */ +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); + +/** + * queue. h + *
void vQueueDelete( xQueueHandle xQueue );
+ * + * Delete a queue - freeing all the memory allocated for storing of items + * placed on the queue. + * + * @param xQueue A handle to the queue to be deleted. + * + * \page vQueueDelete vQueueDelete + * \ingroup QueueManagement + */ +void vQueueDelete( xQueueHandle pxQueue ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToFrontFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the front of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPrioritTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_FRONT ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBackFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the back of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendFromISR(
+									 xQueueHandle pxQueue,
+									 const void *pvItemToQueue,
+									 portBASE_TYPE *pxHigherPriorityTaskWoken
+								);
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). It is included + * for backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() + * macros. + * + * Post an item to the back of a queue. It is safe to use this function from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		// Actual macro used here is port specific.
+		taskYIELD_FROM_ISR ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( pxQueue ), ( pvItemToQueue ), ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSendFromISR(
+										   xQueueHandle	pxQueue,
+										   const	void	*pvItemToQueue,
+										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
+										   portBASE_TYPE	xCopyPosition
+									   );
+ 
+ * + * It is preferred that the macros xQueueSendFromISR(), + * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place + * of calling this function directly. + * + * Post an item on a queue. It is safe to use this function from within an + * interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWokenByPost;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWokenByPost = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post each byte.
+		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.  Note that the
+	// name of the yield function required is port specific.
+	if( xHigherPriorityTaskWokenByPost )
+	{
+		taskYIELD_YIELD_FROM_ISR();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceiveFromISR(
+									   xQueueHandle	pxQueue,
+									   void	*pvBuffer,
+									   portBASE_TYPE	*pxTaskWoken
+								   );
+ * 
+ * + * Receive an item from a queue. It is safe to use this function from within an + * interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param pxTaskWoken A task may be blocked waiting for space to become + * available on the queue. If xQueueReceiveFromISR causes such a task to + * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will + * remain unchanged. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+
+ xQueueHandle xQueue;
+
+ // Function to create a queue and post some values.
+ void vAFunction( void *pvParameters )
+ {
+ char cValueToPost;
+ const portTickType xBlockTime = ( portTickType )0xff;
+
+	// Create a queue capable of containing 10 characters.
+	xQueue = xQueueCreate( 10, sizeof( char ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Post some characters that will be used within an ISR.  If the queue
+	// is full then this task will block for xBlockTime ticks.
+	cValueToPost = 'a';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+	cValueToPost = 'b';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+
+	// ... keep posting characters ... this task may block when the queue
+	// becomes full.
+
+	cValueToPost = 'c';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+ }
+
+ // ISR that outputs all the characters received on the queue.
+ void vISR_Routine( void )
+ {
+ portBASE_TYPE xTaskWokenByReceive = pdFALSE;
+ char cRxedChar;
+
+	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
+	{
+		// A character was received.  Output the character now.
+		vOutputCharacter( cRxedChar );
+
+		// If removing the character from the queue woke the task that was
+		// posting onto the queue cTaskWokenByReceive will have been set to
+		// pdTRUE.  No matter how many times this loop iterates only one
+		// task will be woken.
+	}
+
+	if( cTaskWokenByPost != ( char ) pdFALSE;
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ); + +/* + * Utilities to query queues that are safe to use from an ISR. These utilities + * should be used only from witin an ISR, or within a critical section. + */ +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); + + +/* + * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). + * Likewise xQueueAltGenericReceive() is an alternative version of + * xQueueGenericReceive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); +#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_FRONT ) +#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( ( xQueue ), ( pvItemToQueue ), ( xTicksToWait ), queueSEND_TO_BACK ) +#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdFALSE ) +#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( ( xQueue ), ( pvBuffer ), ( xTicksToWait ), pdTRUE ) + +/* + * The functions defined above are for passing data to and from tasks. The + * functions below are the equivalents for passing data to and from + * co-routines. + * + * These functions are called from the co-routine macro implementation and + * should not be called directly from application code. Instead use the macro + * wrappers defined within croutine.h. + */ +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); + +/* + * For internal use only. Use xSemaphoreCreateMutex(), + * xSemaphoreCreateCounting() or xSemaphoreGetMutexHolder() instead of calling + * these functions directly. + */ +xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ); +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); +void* xQueueGetMutexHolder( xQueueHandle xSemaphore ); + +/* + * For internal use only. Use xSemaphoreTakeMutexRecursive() or + * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. + */ +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ); +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ); + +/* + * Reset a queue back to its original empty state. pdPASS is returned if the + * queue is successfully reset. pdFAIL is returned if the queue could not be + * reset because there are tasks blocked on the queue waiting to either + * receive from the queue or send to the queue. + */ +#define xQueueReset( pxQueue ) xQueueGenericReset( pxQueue, pdFALSE ) + +/* + * The registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add + * a queue, semaphore or mutex handle to the registry if you want the handle + * to be available to a kernel aware debugger. If you are not using a kernel + * aware debugger then this function can be ignored. + * + * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the + * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 + * within FreeRTOSConfig.h for the registry to be available. Its value + * does not effect the number of queues, semaphores and mutexes that can be + * created - just the number that the registry can hold. + * + * @param xQueue The handle of the queue being added to the registry. This + * is the handle returned by a call to xQueueCreate(). Semaphore and mutex + * handles can also be passed in here. + * + * @param pcName The name to be associated with the handle. This is the + * name that the kernel aware debugger will display. + */ +#if configQUEUE_REGISTRY_SIZE > 0U + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); +#endif + +/* + * Generic version of the queue creation function, which is in turn called by + * any queue, semaphore or mutex creation function or macro. + */ +xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ); + +/* Not public API functions. */ +void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ); +portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ); + + +#ifdef __cplusplus +} +#endif + +#endif /* QUEUE_H */ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h index 65c77c7c9..1097d7f68 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/semphr.h @@ -1,787 +1,787 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#ifndef SEMAPHORE_H -#define SEMAPHORE_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h" must appear in source files before "include semphr.h" -#endif - -#include "queue.h" - -typedef xQueueHandle xSemaphoreHandle; - -#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1U ) -#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0U ) -#define semGIVE_BLOCK_TIME ( ( portTickType ) 0U ) - - -/** - * semphr. h - *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
- * - * Macro that implements a semaphore by using the existing queue mechanism. - * The queue length is 1 as this is a binary semaphore. The data size is 0 - * as we don't want to actually store any data - we just want to know if the - * queue is empty or full. - * - * This type of semaphore can be used for pure synchronisation between tasks or - * between an interrupt and a task. The semaphore need not be given back once - * obtained, so one task/interrupt can continuously 'give' the semaphore while - * another continuously 'takes' the semaphore. For this reason this type of - * semaphore does not use a priority inheritance mechanism. For an alternative - * that does use priority inheritance see xSemaphoreCreateMutex(). - * - * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
-    // This is a macro so pass the variable in directly.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary - * \ingroup Semaphores - */ -#define vSemaphoreCreateBinary( xSemaphore ) \ - { \ - ( xSemaphore ) = xQueueGenericCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE ); \ - if( ( xSemaphore ) != NULL ) \ - { \ - xSemaphoreGive( ( xSemaphore ) ); \ - } \ - } - -/** - * semphr. h - *
xSemaphoreTake( 
- *                   xSemaphoreHandle xSemaphore, 
- *                   portTickType xBlockTime 
- *               )
- * - * Macro to obtain a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). - * - * @param xSemaphore A handle to the semaphore being taken - obtained when - * the semaphore was created. - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. A block - * time of portMAX_DELAY can be used to block indefinitely (provided - * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). - * - * @return pdTRUE if the semaphore was obtained. pdFALSE - * if xBlockTime expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- // A task that creates a semaphore.
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
- }
-
- // A task that uses the semaphore.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xSemaphore != NULL )
-    {
-        // See if we can obtain the semaphore.  If the semaphore is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the semaphore and can now access the
-            // shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource.  Release the 
-            // semaphore.
-            xSemaphoreGive( xSemaphore );
-        }
-        else
-        {
-            // We could not obtain the semaphore and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTake xSemaphoreTake - * \ingroup Semaphores - */ -#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) - -/** - * semphr. h - * xSemaphoreTakeRecursive( - * xSemaphoreHandle xMutex, - * portTickType xBlockTime - * ) - * - * Macro to recursively obtain, or 'take', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being obtained. This is the - * handle returned by xSemaphoreCreateRecursiveMutex(); - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. If - * the task already owns the semaphore then xSemaphoreTakeRecursive() will - * return immediately no matter what the value of xBlockTime. - * - * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime - * expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, but instead buried in a more complex
-			// call structure.  This is just for illustrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive - * \ingroup Semaphores - */ -#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) ) - - -/* - * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) - -/** - * semphr. h - *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). - * - * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for - * an alternative which can be used from an ISR. - * - * This macro must also not be used on semaphores created using - * xSemaphoreCreateRecursiveMutex(). - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. - * Semaphores are implemented using queues. An error can occur if there is - * no space on the queue to post a message - indicating that the - * semaphore was not first obtained correctly. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-        {
-            // We would expect this call to fail because we cannot give
-            // a semaphore without first "taking" it!
-        }
-
-        // Obtain the semaphore - don't block if the semaphore is not
-        // immediately available.
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
-        {
-            // We now have the semaphore and can access the shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource so can free the
-            // semaphore.
-            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-            {
-                // We would not expect this call to fail because we must have
-                // obtained the semaphore to get here.
-            }
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGive xSemaphoreGive - * \ingroup Semaphores - */ -#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
- * - * Macro to recursively release, or 'give', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being released, or 'given'. This is the - * handle returned by xSemaphoreCreateMutex(); - * - * @return pdTRUE if the semaphore was given. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, it would be more likely that the calls
-			// to xSemaphoreGiveRecursive() would be called as a call stack
-			// unwound.  This is just for demonstrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive - * \ingroup Semaphores - */ -#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) ) - -/* - * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
- xSemaphoreGiveFromISR( 
-                          xSemaphoreHandle xSemaphore, 
-                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
-                      )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). - * - * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) - * must not be used with this macro. - * - * This macro can be used from an ISR. - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. - * - * Example usage: -
- \#define LONG_TIME 0xffff
- \#define TICKS_TO_WAIT	10
- xSemaphoreHandle xSemaphore = NULL;
-
- // Repetitive task.
- void vATask( void * pvParameters )
- {
-    for( ;; )
-    {
-        // We want this task to run every 10 ticks of a timer.  The semaphore 
-        // was created before this task was started.
-
-        // Block waiting for the semaphore to become available.
-        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
-        {
-            // It is time to execute.
-
-            // ...
-
-            // We have finished our task.  Return to the top of the loop where
-            // we will block on the semaphore until it is time to execute 
-            // again.  Note when using the semaphore for synchronisation with an
-			// ISR in this manner there is no need to 'give' the semaphore back.
-        }
-    }
- }
-
- // Timer ISR
- void vTimerISR( void * pvParameters )
- {
- static unsigned char ucLocalTickCount = 0;
- static signed portBASE_TYPE xHigherPriorityTaskWoken;
-
-    // A timer tick has occurred.
-
-    // ... Do other time functions.
-
-    // Is it time for vATask () to run?
-	xHigherPriorityTaskWoken = pdFALSE;
-    ucLocalTickCount++;
-    if( ucLocalTickCount >= TICKS_TO_WAIT )
-    {
-        // Unblock the task by releasing the semaphore.
-        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
-
-        // Reset the count so we release the semaphore again in 10 ticks time.
-        ucLocalTickCount = 0;
-    }
-
-    if( xHigherPriorityTaskWoken != pdFALSE )
-    {
-        // We can force a context switch here.  Context switching from an
-        // ISR uses port specific syntax.  Check the demo task for your port
-        // to find the syntax required.
-    }
- }
- 
- * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR - * \ingroup Semaphores - */ -#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) - -/** - * semphr. h - *
- xSemaphoreTakeFromISR( 
-                          xSemaphoreHandle xSemaphore, 
-                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
-                      )
- * - * Macro to take a semaphore from an ISR. The semaphore must have - * previously been created with a call to vSemaphoreCreateBinary() or - * xSemaphoreCreateCounting(). - * - * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) - * must not be used with this macro. - * - * This macro can be used from an ISR, however taking a semaphore from an ISR - * is not a common operation. It is likely to only be useful when taking a - * counting semaphore when an interrupt is obtaining an object from a resource - * pool (when the semaphore count indicates the number of resources available). - * - * @param xSemaphore A handle to the semaphore being taken. This is the - * handle returned when the semaphore was created. - * - * @param pxHigherPriorityTaskWoken xSemaphoreTakeFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if taking the semaphore caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xSemaphoreTakeFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the semaphore was successfully taken, otherwise - * pdFALSE - */ -#define xSemaphoreTakeFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueReceiveFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ) ) - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateMutex( void )
- * - * Macro that implements a mutex semaphore by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the xSemaphoreTake() - * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and - * xSemaphoreGiveRecursive() macros should not be used. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateMutex() xQueueCreateMutex( queueQUEUE_TYPE_MUTEX ) - - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
- * - * Macro that implements a recursive mutex by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the - * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The - * xSemaphoreTake() and xSemaphoreGive() macros should not be used. - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateRecursiveMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex( queueQUEUE_TYPE_RECURSIVE_MUTEX ) - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
- * - * Macro that creates a counting semaphore by using the existing - * queue mechanism. - * - * Counting semaphores are typically used for two things: - * - * 1) Counting events. - * - * In this usage scenario an event handler will 'give' a semaphore each time - * an event occurs (incrementing the semaphore count value), and a handler - * task will 'take' a semaphore each time it processes an event - * (decrementing the semaphore count value). The count value is therefore - * the difference between the number of events that have occurred and the - * number that have been processed. In this case it is desirable for the - * initial count value to be zero. - * - * 2) Resource management. - * - * In this usage scenario the count value indicates the number of resources - * available. To obtain control of a resource a task must first obtain a - * semaphore - decrementing the semaphore count value. When the count value - * reaches zero there are no free resources. When a task finishes with the - * resource it 'gives' the semaphore back - incrementing the semaphore count - * value. In this case it is desirable for the initial count value to be - * equal to the maximum count value, indicating that all resources are free. - * - * @param uxMaxCount The maximum count value that can be reached. When the - * semaphore reaches this value it can no longer be 'given'. - * - * @param uxInitialCount The count value assigned to the semaphore when it is - * created. - * - * @return Handle to the created semaphore. Null if the semaphore could not be - * created. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
- xSemaphoreHandle xSemaphore = NULL;
-
-    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
-    // The max value to which the semaphore can count should be 10, and the
-    // initial value assigned to the count should be 0.
-    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting - * \ingroup Semaphores - */ -#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) - -/** - * semphr. h - *
void vSemaphoreDelete( xSemaphoreHandle xSemaphore );
- * - * Delete a semaphore. This function must be used with care. For example, - * do not delete a mutex type semaphore if the mutex is held by a task. - * - * @param xSemaphore A handle to the semaphore to be deleted. - * - * \page vSemaphoreDelete vSemaphoreDelete - * \ingroup Semaphores - */ -#define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( xQueueHandle ) ( xSemaphore ) ) - -/** - * semphr.h - *
xTaskHandle xSemaphoreGetMutexHolder( xSemaphoreHandle xMutex );
- * - * If xMutex is indeed a mutex type semaphore, return the current mutex holder. - * If xMutex is not a mutex type semaphore, or the mutex is available (not held - * by a task), return NULL. - * - * Note: This Is is a good way of determining if the calling task is the mutex - * holder, but not a good way of determining the identity of the mutex holder as - * the holder may change between the function exiting and the returned value - * being tested. - */ -#define xSemaphoreGetMutexHolder( xSemaphore ) xQueueGetMutexHolder( ( xSemaphore ) ) - -#endif /* SEMAPHORE_H */ - - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#ifndef SEMAPHORE_H +#define SEMAPHORE_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h" must appear in source files before "include semphr.h" +#endif + +#include "queue.h" + +typedef xQueueHandle xSemaphoreHandle; + +#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1U ) +#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0U ) +#define semGIVE_BLOCK_TIME ( ( portTickType ) 0U ) + + +/** + * semphr. h + *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
+ * + * Macro that implements a semaphore by using the existing queue mechanism. + * The queue length is 1 as this is a binary semaphore. The data size is 0 + * as we don't want to actually store any data - we just want to know if the + * queue is empty or full. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
+    // This is a macro so pass the variable in directly.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary + * \ingroup Semaphores + */ +#define vSemaphoreCreateBinary( xSemaphore ) \ + { \ + ( xSemaphore ) = xQueueGenericCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_BINARY_SEMAPHORE ); \ + if( ( xSemaphore ) != NULL ) \ + { \ + xSemaphoreGive( ( xSemaphore ) ); \ + } \ + } + +/** + * semphr. h + *
xSemaphoreTake( 
+ *                   xSemaphoreHandle xSemaphore, 
+ *                   portTickType xBlockTime 
+ *               )
+ * + * Macro to obtain a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). + * + * @param xSemaphore A handle to the semaphore being taken - obtained when + * the semaphore was created. + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. A block + * time of portMAX_DELAY can be used to block indefinitely (provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). + * + * @return pdTRUE if the semaphore was obtained. pdFALSE + * if xBlockTime expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // A task that creates a semaphore.
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+ }
+
+ // A task that uses the semaphore.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xSemaphore != NULL )
+    {
+        // See if we can obtain the semaphore.  If the semaphore is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the semaphore and can now access the
+            // shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource.  Release the 
+            // semaphore.
+            xSemaphoreGive( xSemaphore );
+        }
+        else
+        {
+            // We could not obtain the semaphore and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTake xSemaphoreTake + * \ingroup Semaphores + */ +#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) + +/** + * semphr. h + * xSemaphoreTakeRecursive( + * xSemaphoreHandle xMutex, + * portTickType xBlockTime + * ) + * + * Macro to recursively obtain, or 'take', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being obtained. This is the + * handle returned by xSemaphoreCreateRecursiveMutex(); + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. If + * the task already owns the semaphore then xSemaphoreTakeRecursive() will + * return immediately no matter what the value of xBlockTime. + * + * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime + * expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, but instead buried in a more complex
+			// call structure.  This is just for illustrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive + * \ingroup Semaphores + */ +#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) ) + + +/* + * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) ( xSemaphore ), NULL, ( xBlockTime ), pdFALSE ) + +/** + * semphr. h + *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). + * + * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for + * an alternative which can be used from an ISR. + * + * This macro must also not be used on semaphores created using + * xSemaphoreCreateRecursiveMutex(). + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. + * Semaphores are implemented using queues. An error can occur if there is + * no space on the queue to post a message - indicating that the + * semaphore was not first obtained correctly. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+        {
+            // We would expect this call to fail because we cannot give
+            // a semaphore without first "taking" it!
+        }
+
+        // Obtain the semaphore - don't block if the semaphore is not
+        // immediately available.
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
+        {
+            // We now have the semaphore and can access the shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource so can free the
+            // semaphore.
+            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+            {
+                // We would not expect this call to fail because we must have
+                // obtained the semaphore to get here.
+            }
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGive xSemaphoreGive + * \ingroup Semaphores + */ +#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
+ * + * Macro to recursively release, or 'give', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being released, or 'given'. This is the + * handle returned by xSemaphoreCreateMutex(); + * + * @return pdTRUE if the semaphore was given. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, it would be more likely that the calls
+			// to xSemaphoreGiveRecursive() would be called as a call stack
+			// unwound.  This is just for demonstrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive + * \ingroup Semaphores + */ +#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) ) + +/* + * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) ( xSemaphore ), NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
+ xSemaphoreGiveFromISR( 
+                          xSemaphoreHandle xSemaphore, 
+                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR. + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. + * + * Example usage: +
+ \#define LONG_TIME 0xffff
+ \#define TICKS_TO_WAIT	10
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // Repetitive task.
+ void vATask( void * pvParameters )
+ {
+    for( ;; )
+    {
+        // We want this task to run every 10 ticks of a timer.  The semaphore 
+        // was created before this task was started.
+
+        // Block waiting for the semaphore to become available.
+        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
+        {
+            // It is time to execute.
+
+            // ...
+
+            // We have finished our task.  Return to the top of the loop where
+            // we will block on the semaphore until it is time to execute 
+            // again.  Note when using the semaphore for synchronisation with an
+			// ISR in this manner there is no need to 'give' the semaphore back.
+        }
+    }
+ }
+
+ // Timer ISR
+ void vTimerISR( void * pvParameters )
+ {
+ static unsigned char ucLocalTickCount = 0;
+ static signed portBASE_TYPE xHigherPriorityTaskWoken;
+
+    // A timer tick has occurred.
+
+    // ... Do other time functions.
+
+    // Is it time for vATask () to run?
+	xHigherPriorityTaskWoken = pdFALSE;
+    ucLocalTickCount++;
+    if( ucLocalTickCount >= TICKS_TO_WAIT )
+    {
+        // Unblock the task by releasing the semaphore.
+        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
+
+        // Reset the count so we release the semaphore again in 10 ticks time.
+        ucLocalTickCount = 0;
+    }
+
+    if( xHigherPriorityTaskWoken != pdFALSE )
+    {
+        // We can force a context switch here.  Context switching from an
+        // ISR uses port specific syntax.  Check the demo task for your port
+        // to find the syntax required.
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR + * \ingroup Semaphores + */ +#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ), queueSEND_TO_BACK ) + +/** + * semphr. h + *
+ xSemaphoreTakeFromISR( 
+                          xSemaphoreHandle xSemaphore, 
+                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to take a semaphore from an ISR. The semaphore must have + * previously been created with a call to vSemaphoreCreateBinary() or + * xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR, however taking a semaphore from an ISR + * is not a common operation. It is likely to only be useful when taking a + * counting semaphore when an interrupt is obtaining an object from a resource + * pool (when the semaphore count indicates the number of resources available). + * + * @param xSemaphore A handle to the semaphore being taken. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreTakeFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if taking the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreTakeFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully taken, otherwise + * pdFALSE + */ +#define xSemaphoreTakeFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueReceiveFromISR( ( xQueueHandle ) ( xSemaphore ), NULL, ( pxHigherPriorityTaskWoken ) ) + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateMutex( void )
+ * + * Macro that implements a mutex semaphore by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the xSemaphoreTake() + * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and + * xSemaphoreGiveRecursive() macros should not be used. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateMutex() xQueueCreateMutex( queueQUEUE_TYPE_MUTEX ) + + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
+ * + * Macro that implements a recursive mutex by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the + * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The + * xSemaphoreTake() and xSemaphoreGive() macros should not be used. + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateRecursiveMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex( queueQUEUE_TYPE_RECURSIVE_MUTEX ) + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
+ * + * Macro that creates a counting semaphore by using the existing + * queue mechanism. + * + * Counting semaphores are typically used for two things: + * + * 1) Counting events. + * + * In this usage scenario an event handler will 'give' a semaphore each time + * an event occurs (incrementing the semaphore count value), and a handler + * task will 'take' a semaphore each time it processes an event + * (decrementing the semaphore count value). The count value is therefore + * the difference between the number of events that have occurred and the + * number that have been processed. In this case it is desirable for the + * initial count value to be zero. + * + * 2) Resource management. + * + * In this usage scenario the count value indicates the number of resources + * available. To obtain control of a resource a task must first obtain a + * semaphore - decrementing the semaphore count value. When the count value + * reaches zero there are no free resources. When a task finishes with the + * resource it 'gives' the semaphore back - incrementing the semaphore count + * value. In this case it is desirable for the initial count value to be + * equal to the maximum count value, indicating that all resources are free. + * + * @param uxMaxCount The maximum count value that can be reached. When the + * semaphore reaches this value it can no longer be 'given'. + * + * @param uxInitialCount The count value assigned to the semaphore when it is + * created. + * + * @return Handle to the created semaphore. Null if the semaphore could not be + * created. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+ xSemaphoreHandle xSemaphore = NULL;
+
+    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
+    // The max value to which the semaphore can count should be 10, and the
+    // initial value assigned to the count should be 0.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting + * \ingroup Semaphores + */ +#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( ( uxMaxCount ), ( uxInitialCount ) ) + +/** + * semphr. h + *
void vSemaphoreDelete( xSemaphoreHandle xSemaphore );
+ * + * Delete a semaphore. This function must be used with care. For example, + * do not delete a mutex type semaphore if the mutex is held by a task. + * + * @param xSemaphore A handle to the semaphore to be deleted. + * + * \page vSemaphoreDelete vSemaphoreDelete + * \ingroup Semaphores + */ +#define vSemaphoreDelete( xSemaphore ) vQueueDelete( ( xQueueHandle ) ( xSemaphore ) ) + +/** + * semphr.h + *
xTaskHandle xSemaphoreGetMutexHolder( xSemaphoreHandle xMutex );
+ * + * If xMutex is indeed a mutex type semaphore, return the current mutex holder. + * If xMutex is not a mutex type semaphore, or the mutex is available (not held + * by a task), return NULL. + * + * Note: This Is is a good way of determining if the calling task is the mutex + * holder, but not a good way of determining the identity of the mutex holder as + * the holder may change between the function exiting and the returned value + * being tested. + */ +#define xSemaphoreGetMutexHolder( xSemaphore ) xQueueGetMutexHolder( ( xSemaphore ) ) + +#endif /* SEMAPHORE_H */ + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h index aa1733b86..5b6e6eb95 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/task.h @@ -1,1315 +1,1315 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - Selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#ifndef TASK_H -#define TASK_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include task.h" -#endif - -#include "portable.h" -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * MACROS AND DEFINITIONS - *----------------------------------------------------------*/ - -#define tskKERNEL_VERSION_NUMBER "V7.2.0" - -/** - * task. h - * - * Type by which tasks are referenced. For example, a call to xTaskCreate - * returns (via a pointer parameter) an xTaskHandle variable that can then - * be used as a parameter to vTaskDelete to delete the task. - * - * \page xTaskHandle xTaskHandle - * \ingroup Tasks - */ -typedef void * xTaskHandle; - -/* - * Used internally only. - */ -typedef struct xTIME_OUT -{ - portBASE_TYPE xOverflowCount; - portTickType xTimeOnEntering; -} xTimeOutType; - -/* - * Defines the memory ranges allocated to the task when an MPU is used. - */ -typedef struct xMEMORY_REGION -{ - void *pvBaseAddress; - unsigned long ulLengthInBytes; - unsigned long ulParameters; -} xMemoryRegion; - -/* - * Parameters required to create an MPU protected task. - */ -typedef struct xTASK_PARAMTERS -{ - pdTASK_CODE pvTaskCode; - const signed char * const pcName; - unsigned short usStackDepth; - void *pvParameters; - unsigned portBASE_TYPE uxPriority; - portSTACK_TYPE *puxStackBuffer; - xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; -} xTaskParameters; - -/* - * Defines the priority used by the idle task. This must not be modified. - * - * \ingroup TaskUtils - */ -#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0U ) - -/** - * task. h - * - * Macro for forcing a context switch. - * - * \page taskYIELD taskYIELD - * \ingroup SchedulerControl - */ -#define taskYIELD() portYIELD() - -/** - * task. h - * - * Macro to mark the start of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskENTER_CRITICAL taskENTER_CRITICAL - * \ingroup SchedulerControl - */ -#define taskENTER_CRITICAL() portENTER_CRITICAL() - -/** - * task. h - * - * Macro to mark the end of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskEXIT_CRITICAL taskEXIT_CRITICAL - * \ingroup SchedulerControl - */ -#define taskEXIT_CRITICAL() portEXIT_CRITICAL() - -/** - * task. h - * - * Macro to disable all maskable interrupts. - * - * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() - -/** - * task. h - * - * Macro to enable microcontroller interrupts. - * - * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() - -/* Definitions returned by xTaskGetSchedulerState(). */ -#define taskSCHEDULER_NOT_STARTED 0 -#define taskSCHEDULER_RUNNING 1 -#define taskSCHEDULER_SUSPENDED 2 - -/*----------------------------------------------------------- - * TASK CREATION API - *----------------------------------------------------------*/ - -/** - * task. h - *
- portBASE_TYPE xTaskCreate(
-							  pdTASK_CODE pvTaskCode,
-							  const char * const pcName,
-							  unsigned short usStackDepth,
-							  void *pvParameters,
-							  unsigned portBASE_TYPE uxPriority,
-							  xTaskHandle *pvCreatedTask
-						  );
- * - * Create a new task and add it to the list of tasks that are ready to run. - * - * xTaskCreate() can only be used to create a task that has unrestricted - * access to the entire microcontroller memory map. Systems that include MPU - * support can alternatively create an MPU constrained task using - * xTaskCreateRestricted(). - * - * @param pvTaskCode Pointer to the task entry function. Tasks - * must be implemented to never return (i.e. continuous loop). - * - * @param pcName A descriptive name for the task. This is mainly used to - * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default - * is 16. - * - * @param usStackDepth The size of the task stack specified as the number of - * variables the stack can hold - not the number of bytes. For example, if - * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes - * will be allocated for stack storage. - * - * @param pvParameters Pointer that will be used as the parameter for the task - * being created. - * - * @param uxPriority The priority at which the task should run. Systems that - * include MPU support can optionally create tasks in a privileged (system) - * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For - * example, to create a privileged task at priority 2 the uxPriority parameter - * should be set to ( 2 | portPRIVILEGE_BIT ). - * - * @param pvCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
- // Task to be created.
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-	 }
- }
-
- // Function that creates a task.
- void vOtherFunction( void )
- {
- static unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
-	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
-	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
-	 // the new task attempts to access it.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup xTaskCreate xTaskCreate - * \ingroup Tasks - */ -#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) - -/** - * task. h - *
- portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
- * - * xTaskCreateRestricted() should only be used in systems that include an MPU - * implementation. - * - * Create a new task and add it to the list of tasks that are ready to run. - * The function parameters define the memory regions and associated access - * permissions allocated to the task. - * - * @param pxTaskDefinition Pointer to a structure that contains a member - * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API - * documentation) plus an optional stack buffer and the memory region - * definitions. - * - * @param pxCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
-// Create an xTaskParameters structure that defines the task to be created.
-static const xTaskParameters xCheckTaskParameters =
-{
-	vATask,		// pvTaskCode - the function that implements the task.
-	"ATask",	// pcName - just a text name for the task to assist debugging.
-	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
-	NULL,		// pvParameters - passed into the task function as the function parameters.
-	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
-	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
-
-	// xRegions - Allocate up to three separate memory regions for access by
-	// the task, with appropriate access permissions.  Different processors have
-	// different memory alignment requirements - refer to the FreeRTOS documentation
-	// for full information.
-	{											
-		// Base address					Length	Parameters
-        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
-        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
-        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
-	}
-};
-
-int main( void )
-{
-xTaskHandle xHandle;
-
-	// Create a task from the const structure defined above.  The task handle
-	// is requested (the second parameter is not NULL) but in this case just for
-	// demonstration purposes as its not actually used.
-	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
-
-	// Start the scheduler.
-	vTaskStartScheduler();
-
-	// Will only get here if there was insufficient memory to create the idle
-	// task.
-	for( ;; );
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) - -/** - * task. h - *
- void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
- * - * Memory regions are assigned to a restricted task when the task is created by - * a call to xTaskCreateRestricted(). These regions can be redefined using - * vTaskAllocateMPURegions(). - * - * @param xTask The handle of the task being updated. - * - * @param xRegions A pointer to an xMemoryRegion structure that contains the - * new memory region definitions. - * - * Example usage: -
-// Define an array of xMemoryRegion structures that configures an MPU region
-// allowing read/write access for 1024 bytes starting at the beginning of the
-// ucOneKByte array.  The other two of the maximum 3 definable regions are
-// unused so set to zero.
-static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
-{											
-	// Base address		Length		Parameters
-	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
-	{ 0,				0,			0 },
-	{ 0,				0,			0 }
-};
-
-void vATask( void *pvParameters )
-{
-	// This task was created such that it has access to certain regions of
-	// memory as defined by the MPU configuration.  At some point it is
-	// desired that these MPU regions are replaced with that defined in the
-	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
-	// for this purpose.  NULL is used as the task handle to indicate that this
-	// function should modify the MPU regions of the calling task.
-	vTaskAllocateMPURegions( NULL, xAltRegions );
-	
-	// Now the task can continue its function, but from this point on can only
-	// access its stack and the ucOneKByte array (unless any other statically
-	// defined or shared regions have been declared elsewhere).
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelete( xTaskHandle pxTask );
- * - * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Remove a task from the RTOS real time kernels management. The task being - * deleted will be removed from all ready, blocked, suspended and event lists. - * - * NOTE: The idle task is responsible for freeing the kernel allocated - * memory from tasks that have been deleted. It is therefore important that - * the idle task is not starved of microcontroller processing time if your - * application makes any calls to vTaskDelete (). Memory allocated by the - * task code is not automatically freed, and should be freed before the task - * is deleted. - * - * See the demo application file death.c for sample code that utilises - * vTaskDelete (). - * - * @param pxTask The handle of the task to be deleted. Passing NULL will - * cause the calling task to be deleted. - * - * Example usage: -
- void vOtherFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup vTaskDelete vTaskDelete - * \ingroup Tasks - */ -void vTaskDelete( xTaskHandle pxTaskToDelete ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * TASK CONTROL API - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskDelay( portTickType xTicksToDelay );
- * - * Delay a task for a given number of ticks. The actual time that the - * task remains blocked depends on the tick rate. The constant - * portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * - * vTaskDelay() specifies a time at which the task wishes to unblock relative to - * the time at which vTaskDelay() is called. For example, specifying a block - * period of 100 ticks will cause the task to unblock 100 ticks after - * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method - * of controlling the frequency of a cyclical task as the path taken through the - * code, as well as other task and interrupt activity, will effect the frequency - * at which vTaskDelay() gets called and therefore the time at which the task - * next executes. See vTaskDelayUntil() for an alternative API function designed - * to facilitate fixed frequency execution. It does this by specifying an - * absolute time (rather than a relative time) at which the calling task should - * unblock. - * - * @param xTicksToDelay The amount of time, in tick periods, that - * the calling task should block. - * - * Example usage: - - void vTaskFunction( void * pvParameters ) - { - void vTaskFunction( void * pvParameters ) - { - // Block for 500ms. - const portTickType xDelay = 500 / portTICK_RATE_MS; - - for( ;; ) - { - // Simply toggle the LED every 500ms, blocking between each toggle. - vToggleLED(); - vTaskDelay( xDelay ); - } - } - - * \defgroup vTaskDelay vTaskDelay - * \ingroup TaskCtrl - */ -void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
- * - * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Delay a task until a specified time. This function can be used by cyclical - * tasks to ensure a constant execution frequency. - * - * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will - * cause a task to block for the specified number of ticks from the time vTaskDelay () is - * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed - * execution frequency as the time between a task starting to execute and that task - * calling vTaskDelay () may not be fixed [the task may take a different path though the - * code between calls, or may get interrupted or preempted a different number of times - * each time it executes]. - * - * Whereas vTaskDelay () specifies a wake time relative to the time at which the function - * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to - * unblock. - * - * The constant portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the - * task was last unblocked. The variable must be initialised with the current time - * prior to its first use (see the example below). Following this the variable is - * automatically updated within vTaskDelayUntil (). - * - * @param xTimeIncrement The cycle time period. The task will be unblocked at - * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the - * same xTimeIncrement parameter value will cause the task to execute with - * a fixed interface period. - * - * Example usage: -
- // Perform an action every 10 ticks.
- void vTaskFunction( void * pvParameters )
- {
- portTickType xLastWakeTime;
- const portTickType xFrequency = 10;
-
-	 // Initialise the xLastWakeTime variable with the current time.
-	 xLastWakeTime = xTaskGetTickCount ();
-	 for( ;; )
-	 {
-		 // Wait for the next cycle.
-		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
-
-		 // Perform action here.
-	 }
- }
-   
- * \defgroup vTaskDelayUntil vTaskDelayUntil - * \ingroup TaskCtrl - */ -void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
- * - * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Obtain the priority of any task. - * - * @param pxTask Handle of the task to be queried. Passing a NULL - * handle results in the priority of the calling task being returned. - * - * @return The priority of pxTask. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to obtain the priority of the created task.
-	 // It was created with tskIDLE_PRIORITY, but may have changed
-	 // it itself.
-	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
-	 {
-		 // The task has changed it's priority.
-	 }
-
-	 // ...
-
-	 // Is our priority higher than the created task?
-	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
-	 {
-		 // Our priority (obtained using NULL handle) is higher.
-	 }
- }
-   
- * \defgroup uxTaskPriorityGet uxTaskPriorityGet - * \ingroup TaskCtrl - */ -unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
- * - * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Set the priority of any task. - * - * A context switch will occur before the function returns if the priority - * being set is higher than the currently executing task. - * - * @param pxTask Handle to the task for which the priority is being set. - * Passing a NULL handle results in the priority of the calling task being set. - * - * @param uxNewPriority The priority to which the task will be set. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to raise the priority of the created task.
-	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
-
-	 // ...
-
-	 // Use a NULL handle to raise our priority to the same value.
-	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
- }
-   
- * \defgroup vTaskPrioritySet vTaskPrioritySet - * \ingroup TaskCtrl - */ -void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Suspend any task. When suspended a task will never get any microcontroller - * processing time, no matter what its priority. - * - * Calls to vTaskSuspend are not accumulative - - * i.e. calling vTaskSuspend () twice on the same task still only requires one - * call to vTaskResume () to ready the suspended task. - * - * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL - * handle will cause the calling task to be suspended. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Suspend ourselves.
-	 vTaskSuspend( NULL );
-
-	 // We cannot get here unless another task calls vTaskResume
-	 // with our handle as the parameter.
- }
-   
- * \defgroup vTaskSuspend vTaskSuspend - * \ingroup TaskCtrl - */ -void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskResume( xTaskHandle pxTaskToResume );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Resumes a suspended task. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * vTaskResume (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Resume the suspended task ourselves.
-	 vTaskResume( xHandle );
-
-	 // The created task will once again get microcontroller processing
-	 // time in accordance with it priority within the system.
- }
-   
- * \defgroup vTaskResume vTaskResume - * \ingroup TaskCtrl - */ -void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
- * - * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * An implementation of vTaskResume() that can be called from within an ISR. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * xTaskResumeFromISR (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * \defgroup vTaskResumeFromISR vTaskResumeFromISR - * \ingroup TaskCtrl - */ -portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * SCHEDULER CONTROL - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskStartScheduler( void );
- * - * Starts the real time kernel tick processing. After calling the kernel - * has control over which tasks are executed and when. This function - * does not return until an executing task calls vTaskEndScheduler (). - * - * At least one task should be created via a call to xTaskCreate () - * before calling vTaskStartScheduler (). The idle task is created - * automatically when the first application task is created. - * - * See the demo application file main.c for an example of creating - * tasks and starting the kernel. - * - * Example usage: -
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will not get here unless a task calls vTaskEndScheduler ()
- }
-   
- * - * \defgroup vTaskStartScheduler vTaskStartScheduler - * \ingroup SchedulerControl - */ -void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskEndScheduler( void );
- * - * Stops the real time kernel tick. All created tasks will be automatically - * deleted and multitasking (either preemptive or cooperative) will - * stop. Execution then resumes from the point where vTaskStartScheduler () - * was called, as if vTaskStartScheduler () had just returned. - * - * See the demo application file main. c in the demo/PC directory for an - * example that uses vTaskEndScheduler (). - * - * vTaskEndScheduler () requires an exit function to be defined within the - * portable layer (see vPortEndScheduler () in port. c for the PC port). This - * performs hardware specific operations such as stopping the kernel tick. - * - * vTaskEndScheduler () will cause all of the resources allocated by the - * kernel to be freed - but will not free resources allocated by application - * tasks. - * - * Example usage: -
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // At some point we want to end the real time kernel processing
-		 // so call ...
-		 vTaskEndScheduler ();
-	 }
- }
-
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will only get here when the vTaskCode () task has called
-	 // vTaskEndScheduler ().  When we get here we are back to single task
-	 // execution.
- }
-   
- * - * \defgroup vTaskEndScheduler vTaskEndScheduler - * \ingroup SchedulerControl - */ -void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspendAll( void );
- * - * Suspends all real time kernel activity while keeping interrupts (including the - * kernel tick) enabled. - * - * After calling vTaskSuspendAll () the calling task will continue to execute - * without risk of being swapped out until a call to xTaskResumeAll () has been - * made. - * - * API functions that have the potential to cause a context switch (for example, - * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler - * is suspended. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the kernel
-		 // tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.
-		 xTaskResumeAll ();
-	 }
- }
-   
- * \defgroup vTaskSuspendAll vTaskSuspendAll - * \ingroup SchedulerControl - */ -void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
char xTaskResumeAll( void );
- * - * Resumes real time kernel activity following a call to vTaskSuspendAll (). - * After a call to vTaskSuspendAll () the kernel will take control of which - * task is executing at any time. - * - * @return If resuming the scheduler caused a context switch then pdTRUE is - * returned, otherwise pdFALSE is returned. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the real
-		 // time kernel tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.  We want to force
-		 // a context switch - but there is no point if resuming the scheduler
-		 // caused a context switch already.
-		 if( !xTaskResumeAll () )
-		 {
-			  taskYIELD ();
-		 }
-	 }
- }
-   
- * \defgroup xTaskResumeAll xTaskResumeAll - * \ingroup SchedulerControl - */ -signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
- * - * Utility task that simply returns pdTRUE if the task referenced by xTask is - * currently in the Suspended state, or pdFALSE if the task referenced by xTask - * is in any other state. - * - */ -signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * TASK UTILITIES - *----------------------------------------------------------*/ - -/** - * task. h - *
portTickType xTaskGetTickCount( void );
- * - * @return The count of ticks since vTaskStartScheduler was called. - * - * \page xTaskGetTickCount xTaskGetTickCount - * \ingroup TaskUtils - */ -portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
portTickType xTaskGetTickCountFromISR( void );
- * - * @return The count of ticks since vTaskStartScheduler was called. - * - * This is a version of xTaskGetTickCount() that is safe to be called from an - * ISR - provided that portTickType is the natural word size of the - * microcontroller being used or interrupt nesting is either not supported or - * not being used. - * - * \page xTaskGetTickCount xTaskGetTickCount - * \ingroup TaskUtils - */ -portTickType xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned short uxTaskGetNumberOfTasks( void );
- * - * @return The number of tasks that the real time kernel is currently managing. - * This includes all ready, blocked and suspended tasks. A task that - * has been deleted but not yet freed by the idle task will also be - * included in the count. - * - * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks - * \ingroup TaskUtils - */ -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery );
- * - * @return The text (human readable) name of the task referenced by the handle - * xTaskToQueury. A task can query its own name by either passing in its own - * handle, or by setting xTaskToQuery to NULL. INCLUDE_pcTaskGetTaskName must be - * set to 1 in FreeRTOSConfig.h for pcTaskGetTaskName() to be available. - * - * \page pcTaskGetTaskName pcTaskGetTaskName - * \ingroup TaskUtils - */ -signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ); - -/** - * task. h - *
void vTaskList( char *pcWriteBuffer );
- * - * configUSE_TRACE_FACILITY must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Lists all the current tasks, along with their current state and stack - * usage high water mark. - * - * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or - * suspended ('S'). - * - * @param pcWriteBuffer A buffer into which the above mentioned details - * will be written, in ascii form. This buffer is assumed to be large - * enough to contain the generated report. Approximately 40 bytes per - * task should be sufficient. - * - * \page vTaskList vTaskList - * \ingroup TaskUtils - */ -void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
- * - * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function - * to be available. The application must also then provide definitions - * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and - * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter - * and return the timers current count value respectively. The counter - * should be at least 10 times the frequency of the tick count. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total - * accumulated execution time being stored for each task. The resolution - * of the accumulated time value depends on the frequency of the timer - * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. - * Calling vTaskGetRunTimeStats() writes the total execution time of each - * task into a buffer, both as an absolute count value and as a percentage - * of the total system execution time. - * - * @param pcWriteBuffer A buffer into which the execution times will be - * written, in ascii form. This buffer is assumed to be large enough to - * contain the generated report. Approximately 40 bytes per task should - * be sufficient. - * - * \page vTaskGetRunTimeStats vTaskGetRunTimeStats - * \ingroup TaskUtils - */ -void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
- * - * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for - * this function to be available. - * - * Returns the high water mark of the stack associated with xTask. That is, - * the minimum free stack space there has been (in words, so on a 32 bit machine - * a value of 1 means 4 bytes) since the task started. The smaller the returned - * number the closer the task has come to overflowing its stack. - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The smallest amount of free stack space there has been (in bytes) - * since the task referenced by xTask was created. - */ -unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask );
- * - * Returns the run time of selected task - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The run time of selected task - */ -unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ); - -/* When using trace macros it is sometimes necessary to include tasks.h before -FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, -so the following two prototypes will cause a compilation error. This can be -fixed by simply guarding against the inclusion of these two prototypes unless -they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration -constant. */ -#ifdef configUSE_APPLICATION_TASK_TAG - #if configUSE_APPLICATION_TASK_TAG == 1 - /** - * task.h - *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Sets pxHookFunction to be the task hook function used by the task xTask. - * Passing xTask as NULL has the effect of setting the calling tasks hook - * function. - */ - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; - - /** - * task.h - *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
- * - * Returns the pxHookFunction value assigned to the task xTask. - */ - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - #endif /* configUSE_APPLICATION_TASK_TAG ==1 */ -#endif /* ifdef configUSE_APPLICATION_TASK_TAG */ - -/** - * task.h - *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Calls the hook function associated with xTask. Passing xTask as NULL has - * the effect of calling the Running tasks (the calling task) hook function. - * - * pvParameter is passed to the hook function for the task to interpret as it - * wants. - */ -portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; - -/** - * xTaskGetIdleTaskHandle() is only available if - * INCLUDE_xTaskGetIdleTaskHandle is set to 1 in FreeRTOSConfig.h. - * - * Simply returns the handle of the idle task. It is not valid to call - * xTaskGetIdleTaskHandle() before the scheduler has been started. - */ -xTaskHandle xTaskGetIdleTaskHandle( void ); - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - *----------------------------------------------------------*/ - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Called from the real time kernel tick (either preemptive or cooperative), - * this increments the tick count and checks if any tasks that are blocked - * for a finite period required removing from a blocked list and placing on - * a ready list. - */ -void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes the calling task from the ready list and places it both - * on the list of tasks waiting for a particular event, and the - * list of delayed tasks. The task will be removed from both lists - * and replaced on the ready list should either the event occur (and - * there be no higher priority tasks waiting on the same event) or - * the delay period expires. - * - * @param pxEventList The list containing tasks that are blocked waiting - * for the event to occur. - * - * @param xTicksToWait The maximum amount of time that the task should wait - * for the event to occur. This is specified in kernel ticks,the constant - * portTICK_RATE_MS can be used to convert kernel ticks into a real time - * period. - */ -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * This function performs nearly the same function as vTaskPlaceOnEventList(). - * The difference being that this function does not permit tasks to block - * indefinitely, whereas vTaskPlaceOnEventList() does. - * - * @return pdTRUE if the task being removed has a higher priority than the task - * making the call, otherwise pdFALSE. - */ -void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes a task from both the specified event list and the list of blocked - * tasks, and places it on a ready queue. - * - * xTaskRemoveFromEventList () will be called if either an event occurs to - * unblock a task, or the block timeout period expires. - * - * @return pdTRUE if the task being removed has a higher priority than the task - * making the call, otherwise pdFALSE. - */ -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Sets the pointer to the current TCB to the TCB of the highest priority task - * that is ready to run. - */ -void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; - -/* - * Return the handle of the calling task. - */ -xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; - -/* - * Capture the current time status for future reference. - */ -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; - -/* - * Compare the time status now with that previously captured to see if the - * timeout has expired. - */ -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * Shortcut used by the queue implementation to prevent unnecessary call to - * taskYIELD(); - */ -void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; - -/* - * Returns the scheduler state as taskSCHEDULER_RUNNING, - * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. - */ -portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; - -/* - * Raises the priority of the mutex holder to that of the calling task should - * the mutex holder have a priority less than the calling task. - */ -void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Set the priority of a task back to its proper priority in the case that it - * inherited a higher priority while it was holding a semaphore. - */ -void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Generic version of the task creation function which is in turn called by the - * xTaskCreate() and xTaskCreateRestricted() macros. - */ -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; - -/* - * Get the uxTCBNumber assigned to the task referenced by the xTask parameter. - */ -unsigned portBASE_TYPE uxTaskGetTaskNumber( xTaskHandle xTask ); - -/* - * Set the uxTCBNumber of the task referenced by the xTask parameter to - * ucHandle. - */ -void vTaskSetTaskNumber( xTaskHandle xTask, unsigned portBASE_TYPE uxHandle ); - - -#ifdef __cplusplus -} -#endif -#endif /* TASK_H */ - - - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - Selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#ifndef TASK_H +#define TASK_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include task.h" +#endif + +#include "portable.h" +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + +#define tskKERNEL_VERSION_NUMBER "V7.2.0" + +/** + * task. h + * + * Type by which tasks are referenced. For example, a call to xTaskCreate + * returns (via a pointer parameter) an xTaskHandle variable that can then + * be used as a parameter to vTaskDelete to delete the task. + * + * \page xTaskHandle xTaskHandle + * \ingroup Tasks + */ +typedef void * xTaskHandle; + +/* + * Used internally only. + */ +typedef struct xTIME_OUT +{ + portBASE_TYPE xOverflowCount; + portTickType xTimeOnEntering; +} xTimeOutType; + +/* + * Defines the memory ranges allocated to the task when an MPU is used. + */ +typedef struct xMEMORY_REGION +{ + void *pvBaseAddress; + unsigned long ulLengthInBytes; + unsigned long ulParameters; +} xMemoryRegion; + +/* + * Parameters required to create an MPU protected task. + */ +typedef struct xTASK_PARAMTERS +{ + pdTASK_CODE pvTaskCode; + const signed char * const pcName; + unsigned short usStackDepth; + void *pvParameters; + unsigned portBASE_TYPE uxPriority; + portSTACK_TYPE *puxStackBuffer; + xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; +} xTaskParameters; + +/* + * Defines the priority used by the idle task. This must not be modified. + * + * \ingroup TaskUtils + */ +#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0U ) + +/** + * task. h + * + * Macro for forcing a context switch. + * + * \page taskYIELD taskYIELD + * \ingroup SchedulerControl + */ +#define taskYIELD() portYIELD() + +/** + * task. h + * + * Macro to mark the start of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskENTER_CRITICAL taskENTER_CRITICAL + * \ingroup SchedulerControl + */ +#define taskENTER_CRITICAL() portENTER_CRITICAL() + +/** + * task. h + * + * Macro to mark the end of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskEXIT_CRITICAL taskEXIT_CRITICAL + * \ingroup SchedulerControl + */ +#define taskEXIT_CRITICAL() portEXIT_CRITICAL() + +/** + * task. h + * + * Macro to disable all maskable interrupts. + * + * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() + +/** + * task. h + * + * Macro to enable microcontroller interrupts. + * + * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() + +/* Definitions returned by xTaskGetSchedulerState(). */ +#define taskSCHEDULER_NOT_STARTED 0 +#define taskSCHEDULER_RUNNING 1 +#define taskSCHEDULER_SUSPENDED 2 + +/*----------------------------------------------------------- + * TASK CREATION API + *----------------------------------------------------------*/ + +/** + * task. h + *
+ portBASE_TYPE xTaskCreate(
+							  pdTASK_CODE pvTaskCode,
+							  const char * const pcName,
+							  unsigned short usStackDepth,
+							  void *pvParameters,
+							  unsigned portBASE_TYPE uxPriority,
+							  xTaskHandle *pvCreatedTask
+						  );
+ * + * Create a new task and add it to the list of tasks that are ready to run. + * + * xTaskCreate() can only be used to create a task that has unrestricted + * access to the entire microcontroller memory map. Systems that include MPU + * support can alternatively create an MPU constrained task using + * xTaskCreateRestricted(). + * + * @param pvTaskCode Pointer to the task entry function. Tasks + * must be implemented to never return (i.e. continuous loop). + * + * @param pcName A descriptive name for the task. This is mainly used to + * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default + * is 16. + * + * @param usStackDepth The size of the task stack specified as the number of + * variables the stack can hold - not the number of bytes. For example, if + * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes + * will be allocated for stack storage. + * + * @param pvParameters Pointer that will be used as the parameter for the task + * being created. + * + * @param uxPriority The priority at which the task should run. Systems that + * include MPU support can optionally create tasks in a privileged (system) + * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For + * example, to create a privileged task at priority 2 the uxPriority parameter + * should be set to ( 2 | portPRIVILEGE_BIT ). + * + * @param pvCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+ // Task to be created.
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+	 }
+ }
+
+ // Function that creates a task.
+ void vOtherFunction( void )
+ {
+ static unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
+	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
+	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
+	 // the new task attempts to access it.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup xTaskCreate xTaskCreate + * \ingroup Tasks + */ +#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) + +/** + * task. h + *
+ portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
+ * + * xTaskCreateRestricted() should only be used in systems that include an MPU + * implementation. + * + * Create a new task and add it to the list of tasks that are ready to run. + * The function parameters define the memory regions and associated access + * permissions allocated to the task. + * + * @param pxTaskDefinition Pointer to a structure that contains a member + * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API + * documentation) plus an optional stack buffer and the memory region + * definitions. + * + * @param pxCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+// Create an xTaskParameters structure that defines the task to be created.
+static const xTaskParameters xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{											
+		// Base address					Length	Parameters
+        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+};
+
+int main( void )
+{
+xTaskHandle xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// task.
+	for( ;; );
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) + +/** + * task. h + *
+ void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
+ * + * Memory regions are assigned to a restricted task when the task is created by + * a call to xTaskCreateRestricted(). These regions can be redefined using + * vTaskAllocateMPURegions(). + * + * @param xTask The handle of the task being updated. + * + * @param xRegions A pointer to an xMemoryRegion structure that contains the + * new memory region definitions. + * + * Example usage: +
+// Define an array of xMemoryRegion structures that configures an MPU region
+// allowing read/write access for 1024 bytes starting at the beginning of the
+// ucOneKByte array.  The other two of the maximum 3 definable regions are
+// unused so set to zero.
+static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
+{											
+	// Base address		Length		Parameters
+	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
+	{ 0,				0,			0 },
+	{ 0,				0,			0 }
+};
+
+void vATask( void *pvParameters )
+{
+	// This task was created such that it has access to certain regions of
+	// memory as defined by the MPU configuration.  At some point it is
+	// desired that these MPU regions are replaced with that defined in the
+	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
+	// for this purpose.  NULL is used as the task handle to indicate that this
+	// function should modify the MPU regions of the calling task.
+	vTaskAllocateMPURegions( NULL, xAltRegions );
+	
+	// Now the task can continue its function, but from this point on can only
+	// access its stack and the ucOneKByte array (unless any other statically
+	// defined or shared regions have been declared elsewhere).
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelete( xTaskHandle pxTask );
+ * + * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Remove a task from the RTOS real time kernels management. The task being + * deleted will be removed from all ready, blocked, suspended and event lists. + * + * NOTE: The idle task is responsible for freeing the kernel allocated + * memory from tasks that have been deleted. It is therefore important that + * the idle task is not starved of microcontroller processing time if your + * application makes any calls to vTaskDelete (). Memory allocated by the + * task code is not automatically freed, and should be freed before the task + * is deleted. + * + * See the demo application file death.c for sample code that utilises + * vTaskDelete (). + * + * @param pxTask The handle of the task to be deleted. Passing NULL will + * cause the calling task to be deleted. + * + * Example usage: +
+ void vOtherFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup vTaskDelete vTaskDelete + * \ingroup Tasks + */ +void vTaskDelete( xTaskHandle pxTaskToDelete ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK CONTROL API + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskDelay( portTickType xTicksToDelay );
+ * + * Delay a task for a given number of ticks. The actual time that the + * task remains blocked depends on the tick rate. The constant + * portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * + * vTaskDelay() specifies a time at which the task wishes to unblock relative to + * the time at which vTaskDelay() is called. For example, specifying a block + * period of 100 ticks will cause the task to unblock 100 ticks after + * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method + * of controlling the frequency of a cyclical task as the path taken through the + * code, as well as other task and interrupt activity, will effect the frequency + * at which vTaskDelay() gets called and therefore the time at which the task + * next executes. See vTaskDelayUntil() for an alternative API function designed + * to facilitate fixed frequency execution. It does this by specifying an + * absolute time (rather than a relative time) at which the calling task should + * unblock. + * + * @param xTicksToDelay The amount of time, in tick periods, that + * the calling task should block. + * + * Example usage: + + void vTaskFunction( void * pvParameters ) + { + void vTaskFunction( void * pvParameters ) + { + // Block for 500ms. + const portTickType xDelay = 500 / portTICK_RATE_MS; + + for( ;; ) + { + // Simply toggle the LED every 500ms, blocking between each toggle. + vToggleLED(); + vTaskDelay( xDelay ); + } + } + + * \defgroup vTaskDelay vTaskDelay + * \ingroup TaskCtrl + */ +void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
+ * + * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Delay a task until a specified time. This function can be used by cyclical + * tasks to ensure a constant execution frequency. + * + * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will + * cause a task to block for the specified number of ticks from the time vTaskDelay () is + * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed + * execution frequency as the time between a task starting to execute and that task + * calling vTaskDelay () may not be fixed [the task may take a different path though the + * code between calls, or may get interrupted or preempted a different number of times + * each time it executes]. + * + * Whereas vTaskDelay () specifies a wake time relative to the time at which the function + * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to + * unblock. + * + * The constant portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the + * task was last unblocked. The variable must be initialised with the current time + * prior to its first use (see the example below). Following this the variable is + * automatically updated within vTaskDelayUntil (). + * + * @param xTimeIncrement The cycle time period. The task will be unblocked at + * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the + * same xTimeIncrement parameter value will cause the task to execute with + * a fixed interface period. + * + * Example usage: +
+ // Perform an action every 10 ticks.
+ void vTaskFunction( void * pvParameters )
+ {
+ portTickType xLastWakeTime;
+ const portTickType xFrequency = 10;
+
+	 // Initialise the xLastWakeTime variable with the current time.
+	 xLastWakeTime = xTaskGetTickCount ();
+	 for( ;; )
+	 {
+		 // Wait for the next cycle.
+		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
+
+		 // Perform action here.
+	 }
+ }
+   
+ * \defgroup vTaskDelayUntil vTaskDelayUntil + * \ingroup TaskCtrl + */ +void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
+ * + * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Obtain the priority of any task. + * + * @param pxTask Handle of the task to be queried. Passing a NULL + * handle results in the priority of the calling task being returned. + * + * @return The priority of pxTask. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to obtain the priority of the created task.
+	 // It was created with tskIDLE_PRIORITY, but may have changed
+	 // it itself.
+	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
+	 {
+		 // The task has changed it's priority.
+	 }
+
+	 // ...
+
+	 // Is our priority higher than the created task?
+	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
+	 {
+		 // Our priority (obtained using NULL handle) is higher.
+	 }
+ }
+   
+ * \defgroup uxTaskPriorityGet uxTaskPriorityGet + * \ingroup TaskCtrl + */ +unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
+ * + * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Set the priority of any task. + * + * A context switch will occur before the function returns if the priority + * being set is higher than the currently executing task. + * + * @param pxTask Handle to the task for which the priority is being set. + * Passing a NULL handle results in the priority of the calling task being set. + * + * @param uxNewPriority The priority to which the task will be set. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to raise the priority of the created task.
+	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
+
+	 // ...
+
+	 // Use a NULL handle to raise our priority to the same value.
+	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
+ }
+   
+ * \defgroup vTaskPrioritySet vTaskPrioritySet + * \ingroup TaskCtrl + */ +void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Suspend any task. When suspended a task will never get any microcontroller + * processing time, no matter what its priority. + * + * Calls to vTaskSuspend are not accumulative - + * i.e. calling vTaskSuspend () twice on the same task still only requires one + * call to vTaskResume () to ready the suspended task. + * + * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL + * handle will cause the calling task to be suspended. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Suspend ourselves.
+	 vTaskSuspend( NULL );
+
+	 // We cannot get here unless another task calls vTaskResume
+	 // with our handle as the parameter.
+ }
+   
+ * \defgroup vTaskSuspend vTaskSuspend + * \ingroup TaskCtrl + */ +void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskResume( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Resumes a suspended task. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * vTaskResume (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Resume the suspended task ourselves.
+	 vTaskResume( xHandle );
+
+	 // The created task will once again get microcontroller processing
+	 // time in accordance with it priority within the system.
+ }
+   
+ * \defgroup vTaskResume vTaskResume + * \ingroup TaskCtrl + */ +void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * An implementation of vTaskResume() that can be called from within an ISR. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * xTaskResumeFromISR (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * \defgroup vTaskResumeFromISR vTaskResumeFromISR + * \ingroup TaskCtrl + */ +portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * SCHEDULER CONTROL + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskStartScheduler( void );
+ * + * Starts the real time kernel tick processing. After calling the kernel + * has control over which tasks are executed and when. This function + * does not return until an executing task calls vTaskEndScheduler (). + * + * At least one task should be created via a call to xTaskCreate () + * before calling vTaskStartScheduler (). The idle task is created + * automatically when the first application task is created. + * + * See the demo application file main.c for an example of creating + * tasks and starting the kernel. + * + * Example usage: +
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will not get here unless a task calls vTaskEndScheduler ()
+ }
+   
+ * + * \defgroup vTaskStartScheduler vTaskStartScheduler + * \ingroup SchedulerControl + */ +void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskEndScheduler( void );
+ * + * Stops the real time kernel tick. All created tasks will be automatically + * deleted and multitasking (either preemptive or cooperative) will + * stop. Execution then resumes from the point where vTaskStartScheduler () + * was called, as if vTaskStartScheduler () had just returned. + * + * See the demo application file main. c in the demo/PC directory for an + * example that uses vTaskEndScheduler (). + * + * vTaskEndScheduler () requires an exit function to be defined within the + * portable layer (see vPortEndScheduler () in port. c for the PC port). This + * performs hardware specific operations such as stopping the kernel tick. + * + * vTaskEndScheduler () will cause all of the resources allocated by the + * kernel to be freed - but will not free resources allocated by application + * tasks. + * + * Example usage: +
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // At some point we want to end the real time kernel processing
+		 // so call ...
+		 vTaskEndScheduler ();
+	 }
+ }
+
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will only get here when the vTaskCode () task has called
+	 // vTaskEndScheduler ().  When we get here we are back to single task
+	 // execution.
+ }
+   
+ * + * \defgroup vTaskEndScheduler vTaskEndScheduler + * \ingroup SchedulerControl + */ +void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspendAll( void );
+ * + * Suspends all real time kernel activity while keeping interrupts (including the + * kernel tick) enabled. + * + * After calling vTaskSuspendAll () the calling task will continue to execute + * without risk of being swapped out until a call to xTaskResumeAll () has been + * made. + * + * API functions that have the potential to cause a context switch (for example, + * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler + * is suspended. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the kernel
+		 // tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.
+		 xTaskResumeAll ();
+	 }
+ }
+   
+ * \defgroup vTaskSuspendAll vTaskSuspendAll + * \ingroup SchedulerControl + */ +void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
char xTaskResumeAll( void );
+ * + * Resumes real time kernel activity following a call to vTaskSuspendAll (). + * After a call to vTaskSuspendAll () the kernel will take control of which + * task is executing at any time. + * + * @return If resuming the scheduler caused a context switch then pdTRUE is + * returned, otherwise pdFALSE is returned. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the real
+		 // time kernel tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.  We want to force
+		 // a context switch - but there is no point if resuming the scheduler
+		 // caused a context switch already.
+		 if( !xTaskResumeAll () )
+		 {
+			  taskYIELD ();
+		 }
+	 }
+ }
+   
+ * \defgroup xTaskResumeAll xTaskResumeAll + * \ingroup SchedulerControl + */ +signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
+ * + * Utility task that simply returns pdTRUE if the task referenced by xTask is + * currently in the Suspended state, or pdFALSE if the task referenced by xTask + * is in any other state. + * + */ +signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK UTILITIES + *----------------------------------------------------------*/ + +/** + * task. h + *
portTickType xTaskGetTickCount( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * \page xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
portTickType xTaskGetTickCountFromISR( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * This is a version of xTaskGetTickCount() that is safe to be called from an + * ISR - provided that portTickType is the natural word size of the + * microcontroller being used or interrupt nesting is either not supported or + * not being used. + * + * \page xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +portTickType xTaskGetTickCountFromISR( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned short uxTaskGetNumberOfTasks( void );
+ * + * @return The number of tasks that the real time kernel is currently managing. + * This includes all ready, blocked and suspended tasks. A task that + * has been deleted but not yet freed by the idle task will also be + * included in the count. + * + * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks + * \ingroup TaskUtils + */ +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery );
+ * + * @return The text (human readable) name of the task referenced by the handle + * xTaskToQueury. A task can query its own name by either passing in its own + * handle, or by setting xTaskToQuery to NULL. INCLUDE_pcTaskGetTaskName must be + * set to 1 in FreeRTOSConfig.h for pcTaskGetTaskName() to be available. + * + * \page pcTaskGetTaskName pcTaskGetTaskName + * \ingroup TaskUtils + */ +signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ); + +/** + * task. h + *
void vTaskList( char *pcWriteBuffer );
+ * + * configUSE_TRACE_FACILITY must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Lists all the current tasks, along with their current state and stack + * usage high water mark. + * + * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or + * suspended ('S'). + * + * @param pcWriteBuffer A buffer into which the above mentioned details + * will be written, in ascii form. This buffer is assumed to be large + * enough to contain the generated report. Approximately 40 bytes per + * task should be sufficient. + * + * \page vTaskList vTaskList + * \ingroup TaskUtils + */ +void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
+ * + * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function + * to be available. The application must also then provide definitions + * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and + * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter + * and return the timers current count value respectively. The counter + * should be at least 10 times the frequency of the tick count. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total + * accumulated execution time being stored for each task. The resolution + * of the accumulated time value depends on the frequency of the timer + * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. + * Calling vTaskGetRunTimeStats() writes the total execution time of each + * task into a buffer, both as an absolute count value and as a percentage + * of the total system execution time. + * + * @param pcWriteBuffer A buffer into which the execution times will be + * written, in ascii form. This buffer is assumed to be large enough to + * contain the generated report. Approximately 40 bytes per task should + * be sufficient. + * + * \page vTaskGetRunTimeStats vTaskGetRunTimeStats + * \ingroup TaskUtils + */ +void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
+ * + * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for + * this function to be available. + * + * Returns the high water mark of the stack associated with xTask. That is, + * the minimum free stack space there has been (in words, so on a 32 bit machine + * a value of 1 means 4 bytes) since the task started. The smaller the returned + * number the closer the task has come to overflowing its stack. + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The smallest amount of free stack space there has been (in bytes) + * since the task referenced by xTask was created. + */ +unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask );
+ * + * Returns the run time of selected task + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The run time of selected task + */ +unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ); + +/* When using trace macros it is sometimes necessary to include tasks.h before +FreeRTOS.h. When this is done pdTASK_HOOK_CODE will not yet have been defined, +so the following two prototypes will cause a compilation error. This can be +fixed by simply guarding against the inclusion of these two prototypes unless +they are explicitly required by the configUSE_APPLICATION_TASK_TAG configuration +constant. */ +#ifdef configUSE_APPLICATION_TASK_TAG + #if configUSE_APPLICATION_TASK_TAG == 1 + /** + * task.h + *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Sets pxHookFunction to be the task hook function used by the task xTask. + * Passing xTask as NULL has the effect of setting the calling tasks hook + * function. + */ + void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; + + /** + * task.h + *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
+ * + * Returns the pxHookFunction value assigned to the task xTask. + */ + pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + #endif /* configUSE_APPLICATION_TASK_TAG ==1 */ +#endif /* ifdef configUSE_APPLICATION_TASK_TAG */ + +/** + * task.h + *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Calls the hook function associated with xTask. Passing xTask as NULL has + * the effect of calling the Running tasks (the calling task) hook function. + * + * pvParameter is passed to the hook function for the task to interpret as it + * wants. + */ +portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; + +/** + * xTaskGetIdleTaskHandle() is only available if + * INCLUDE_xTaskGetIdleTaskHandle is set to 1 in FreeRTOSConfig.h. + * + * Simply returns the handle of the idle task. It is not valid to call + * xTaskGetIdleTaskHandle() before the scheduler has been started. + */ +xTaskHandle xTaskGetIdleTaskHandle( void ); + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + *----------------------------------------------------------*/ + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Called from the real time kernel tick (either preemptive or cooperative), + * this increments the tick count and checks if any tasks that are blocked + * for a finite period required removing from a blocked list and placing on + * a ready list. + */ +void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes the calling task from the ready list and places it both + * on the list of tasks waiting for a particular event, and the + * list of delayed tasks. The task will be removed from both lists + * and replaced on the ready list should either the event occur (and + * there be no higher priority tasks waiting on the same event) or + * the delay period expires. + * + * @param pxEventList The list containing tasks that are blocked waiting + * for the event to occur. + * + * @param xTicksToWait The maximum amount of time that the task should wait + * for the event to occur. This is specified in kernel ticks,the constant + * portTICK_RATE_MS can be used to convert kernel ticks into a real time + * period. + */ +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * This function performs nearly the same function as vTaskPlaceOnEventList(). + * The difference being that this function does not permit tasks to block + * indefinitely, whereas vTaskPlaceOnEventList() does. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes a task from both the specified event list and the list of blocked + * tasks, and places it on a ready queue. + * + * xTaskRemoveFromEventList () will be called if either an event occurs to + * unblock a task, or the block timeout period expires. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Sets the pointer to the current TCB to the TCB of the highest priority task + * that is ready to run. + */ +void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; + +/* + * Return the handle of the calling task. + */ +xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; + +/* + * Capture the current time status for future reference. + */ +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; + +/* + * Compare the time status now with that previously captured to see if the + * timeout has expired. + */ +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * Shortcut used by the queue implementation to prevent unnecessary call to + * taskYIELD(); + */ +void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; + +/* + * Returns the scheduler state as taskSCHEDULER_RUNNING, + * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. + */ +portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; + +/* + * Raises the priority of the mutex holder to that of the calling task should + * the mutex holder have a priority less than the calling task. + */ +void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Set the priority of a task back to its proper priority in the case that it + * inherited a higher priority while it was holding a semaphore. + */ +void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Generic version of the task creation function which is in turn called by the + * xTaskCreate() and xTaskCreateRestricted() macros. + */ +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; + +/* + * Get the uxTCBNumber assigned to the task referenced by the xTask parameter. + */ +unsigned portBASE_TYPE uxTaskGetTaskNumber( xTaskHandle xTask ); + +/* + * Set the uxTCBNumber of the task referenced by the xTask parameter to + * ucHandle. + */ +void vTaskSetTaskNumber( xTaskHandle xTask, unsigned portBASE_TYPE uxHandle ); + + +#ifdef __cplusplus +} +#endif +#endif /* TASK_H */ + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h index 5f62368f5..f02c189a4 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/include/timers.h @@ -1,952 +1,952 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#ifndef TIMERS_H -#define TIMERS_H - -#ifndef INC_FREERTOS_H - #error "include FreeRTOS.h must appear in source files before include timers.h" -#endif - -#include "portable.h" -#include "list.h" -#include "task.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* IDs for commands that can be sent/received on the timer queue. These are to -be used solely through the macros that make up the public software timer API, -as defined below. */ -#define tmrCOMMAND_START 0 -#define tmrCOMMAND_STOP 1 -#define tmrCOMMAND_CHANGE_PERIOD 2 -#define tmrCOMMAND_DELETE 3 - -/*----------------------------------------------------------- - * MACROS AND DEFINITIONS - *----------------------------------------------------------*/ - - /** - * Type by which software timers are referenced. For example, a call to - * xTimerCreate() returns an xTimerHandle variable that can then be used to - * reference the subject timer in calls to other software timer API functions - * (for example, xTimerStart(), xTimerReset(), etc.). - */ -typedef void * xTimerHandle; - -/* Define the prototype to which timer callback functions must conform. */ -typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); - -/** - * xTimerHandle xTimerCreate( const signed char *pcTimerName, - * portTickType xTimerPeriodInTicks, - * unsigned portBASE_TYPE uxAutoReload, - * void * pvTimerID, - * tmrTIMER_CALLBACK pxCallbackFunction ); - * - * Creates a new software timer instance. This allocates the storage required - * by the new timer, initialises the new timers internal state, and returns a - * handle by which the new timer can be referenced. - * - * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), - * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and - * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the - * active state. - * - * @param pcTimerName A text name that is assigned to the timer. This is done - * purely to assist debugging. The kernel itself only ever references a timer by - * its handle, and never by its name. - * - * @param xTimerPeriodInTicks The timer period. The time is defined in tick periods so - * the constant portTICK_RATE_MS can be used to convert a time that has been - * specified in milliseconds. For example, if the timer must expire after 100 - * ticks, then xTimerPeriodInTicks should be set to 100. Alternatively, if the timer - * must expire after 500ms, then xPeriod can be set to ( 500 / portTICK_RATE_MS ) - * provided configTICK_RATE_HZ is less than or equal to 1000. - * - * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will - * expire repeatedly with a frequency set by the xTimerPeriodInTicks parameter. If - * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and - * enter the dormant state after it expires. - * - * @param pvTimerID An identifier that is assigned to the timer being created. - * Typically this would be used in the timer callback function to identify which - * timer expired when the same callback function is assigned to more than one - * timer. - * - * @param pxCallbackFunction The function to call when the timer expires. - * Callback functions must have the prototype defined by tmrTIMER_CALLBACK, - * which is "void vCallbackFunction( xTimerHandle xTimer );". - * - * @return If the timer is successfully create then a handle to the newly - * created timer is returned. If the timer cannot be created (because either - * there is insufficient FreeRTOS heap remaining to allocate the timer - * structures, or the timer period was set to 0) then 0 is returned. - * - * Example usage: - * - * #define NUM_TIMERS 5 - * - * // An array to hold handles to the created timers. - * xTimerHandle xTimers[ NUM_TIMERS ]; - * - * // An array to hold a count of the number of times each timer expires. - * long lExpireCounters[ NUM_TIMERS ] = { 0 }; - * - * // Define a callback function that will be used by multiple timer instances. - * // The callback function does nothing but count the number of times the - * // associated timer expires, and stop the timer once the timer has expired - * // 10 times. - * void vTimerCallback( xTimerHandle pxTimer ) - * { - * long lArrayIndex; - * const long xMaxExpiryCountBeforeStopping = 10; - * - * // Optionally do something if the pxTimer parameter is NULL. - * configASSERT( pxTimer ); - * - * // Which timer expired? - * lArrayIndex = ( long ) pvTimerGetTimerID( pxTimer ); - * - * // Increment the number of times that pxTimer has expired. - * lExpireCounters[ lArrayIndex ] += 1; - * - * // If the timer has expired 10 times then stop it from running. - * if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping ) - * { - * // Do not use a block time if calling a timer API function from a - * // timer callback function, as doing so could cause a deadlock! - * xTimerStop( pxTimer, 0 ); - * } - * } - * - * void main( void ) - * { - * long x; - * - * // Create then start some timers. Starting the timers before the scheduler - * // has been started means the timers will start running immediately that - * // the scheduler starts. - * for( x = 0; x < NUM_TIMERS; x++ ) - * { - * xTimers[ x ] = xTimerCreate( "Timer", // Just a text name, not used by the kernel. - * ( 100 * x ), // The timer period in ticks. - * pdTRUE, // The timers will auto-reload themselves when they expire. - * ( void * ) x, // Assign each timer a unique id equal to its array index. - * vTimerCallback // Each timer calls the same callback when it expires. - * ); - * - * if( xTimers[ x ] == NULL ) - * { - * // The timer was not created. - * } - * else - * { - * // Start the timer. No block time is specified, and even if one was - * // it would be ignored because the scheduler has not yet been - * // started. - * if( xTimerStart( xTimers[ x ], 0 ) != pdPASS ) - * { - * // The timer could not be set into the Active state. - * } - * } - * } - * - * // ... - * // Create tasks here. - * // ... - * - * // Starting the scheduler will start the timers running as they have already - * // been set into the active state. - * xTaskStartScheduler(); - * - * // Should not reach here. - * for( ;; ); - * } - */ -xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void * pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) PRIVILEGED_FUNCTION; - -/** - * void *pvTimerGetTimerID( xTimerHandle xTimer ); - * - * Returns the ID assigned to the timer. - * - * IDs are assigned to timers using the pvTimerID parameter of the call to - * xTimerCreated() that was used to create the timer. - * - * If the same callback function is assigned to multiple timers then the timer - * ID can be used within the callback function to identify which timer actually - * expired. - * - * @param xTimer The timer being queried. - * - * @return The ID assigned to the timer being queried. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - */ -void *pvTimerGetTimerID( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; - -/** - * portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ); - * - * Queries a timer to see if it is active or dormant. - * - * A timer will be dormant if: - * 1) It has been created but not started, or - * 2) It is an expired on-shot timer that has not been restarted. - * - * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), - * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and - * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the - * active state. - * - * @param xTimer The timer being queried. - * - * @return pdFALSE will be returned if the timer is dormant. A value other than - * pdFALSE will be returned if the timer is active. - * - * Example usage: - * - * // This function assumes xTimer has already been created. - * void vAFunction( xTimerHandle xTimer ) - * { - * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" - * { - * // xTimer is active, do something. - * } - * else - * { - * // xTimer is not active, do something else. - * } - * } - */ -portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; - -/** - * xTimerGetTimerDaemonTaskHandle() is only available if - * INCLUDE_xTimerGetTimerDaemonTaskHandle is set to 1 in FreeRTOSConfig.h. - * - * Simply returns the handle of the timer service/daemon task. It it not valid - * to call xTimerGetTimerDaemonTaskHandle() before the scheduler has been started. - */ -xTaskHandle xTimerGetTimerDaemonTaskHandle( void ); - -/** - * portBASE_TYPE xTimerStart( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerStart() starts a timer that was previously created using the - * xTimerCreate() API function. If the timer had already been started and was - * already in the active state, then xTimerStart() has equivalent functionality - * to the xTimerReset() API function. - * - * Starting a timer ensures the timer is in the active state. If the timer - * is not stopped, deleted, or reset in the mean time, the callback function - * associated with the timer will get called 'n' ticks after xTimerStart() was - * called, where 'n' is the timers defined period. - * - * It is valid to call xTimerStart() before the scheduler has been started, but - * when this is done the timer will not actually start until the scheduler is - * started, and the timers expiry time will be relative to when the scheduler is - * started, not relative to when xTimerStart() was called. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart() - * to be available. - * - * @param xTimer The handle of the timer being started/restarted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the start command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerStart() was called. xBlockTime is ignored if xTimerStart() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the start command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system, although the - * timers expiry time is relative to when xTimerStart() is actually called. The - * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - * - */ -#define xTimerStart( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerStop( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerStop() stops a timer that was previously started using either of the - * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(), - * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions. - * - * Stopping a timer ensures the timer is not in the active state. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop() - * to be available. - * - * @param xTimer The handle of the timer being stopped. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the stop command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerStop() was called. xBlockTime is ignored if xTimerStop() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the stop command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system. The timer - * service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerCreate() API function example usage scenario. - * - */ -#define xTimerStop( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerChangePeriod( xTimerHandle xTimer, - * portTickType xNewPeriod, - * portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerChangePeriod() changes the period of a timer that was previously - * created using the xTimerCreate() API function. - * - * xTimerChangePeriod() can be called to change the period of an active or - * dormant state timer. - * - * The configUSE_TIMERS configuration constant must be set to 1 for - * xTimerChangePeriod() to be available. - * - * @param xTimer The handle of the timer that is having its period changed. - * - * @param xNewPeriod The new period for xTimer. Timer periods are specified in - * tick periods, so the constant portTICK_RATE_MS can be used to convert a time - * that has been specified in milliseconds. For example, if the timer must - * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, - * if the timer must expire after 500ms, then xNewPeriod can be set to - * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than - * or equal to 1000. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the change period command to be - * successfully sent to the timer command queue, should the queue already be - * full when xTimerChangePeriod() was called. xBlockTime is ignored if - * xTimerChangePeriod() is called before the scheduler is started. - * - * @return pdFAIL will be returned if the change period command could not be - * sent to the timer command queue even after xBlockTime ticks had passed. - * pdPASS will be returned if the command was successfully sent to the timer - * command queue. When the command is actually processed will depend on the - * priority of the timer service/daemon task relative to other tasks in the - * system. The timer service/daemon task priority is set by the - * configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This function assumes xTimer has already been created. If the timer - * // referenced by xTimer is already active when it is called, then the timer - * // is deleted. If the timer referenced by xTimer is not active when it is - * // called, then the period of the timer is set to 500ms and the timer is - * // started. - * void vAFunction( xTimerHandle xTimer ) - * { - * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" - * { - * // xTimer is already active - delete it. - * xTimerDelete( xTimer ); - * } - * else - * { - * // xTimer is not active, change its period to 500ms. This will also - * // cause the timer to start. Block for a maximum of 100 ticks if the - * // change period command cannot immediately be sent to the timer - * // command queue. - * if( xTimerChangePeriod( xTimer, 500 / portTICK_RATE_MS, 100 ) == pdPASS ) - * { - * // The command was successfully sent. - * } - * else - * { - * // The command could not be sent, even after waiting for 100 ticks - * // to pass. Take appropriate action here. - * } - * } - * } - */ - #define xTimerChangePeriod( xTimer, xNewPeriod, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerDelete( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerDelete() deletes a timer that was previously created using the - * xTimerCreate() API function. - * - * The configUSE_TIMERS configuration constant must be set to 1 for - * xTimerDelete() to be available. - * - * @param xTimer The handle of the timer being deleted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the delete command to be - * successfully sent to the timer command queue, should the queue already be - * full when xTimerDelete() was called. xBlockTime is ignored if xTimerDelete() - * is called before the scheduler is started. - * - * @return pdFAIL will be returned if the delete command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system. The timer - * service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * See the xTimerChangePeriod() API function example usage scenario. - */ -#define xTimerDelete( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerReset( xTimerHandle xTimer, portTickType xBlockTime ); - * - * Timer functionality is provided by a timer service/daemon task. Many of the - * public FreeRTOS timer API functions send commands to the timer service task - * though a queue called the timer command queue. The timer command queue is - * private to the kernel itself and is not directly accessible to application - * code. The length of the timer command queue is set by the - * configTIMER_QUEUE_LENGTH configuration constant. - * - * xTimerReset() re-starts a timer that was previously created using the - * xTimerCreate() API function. If the timer had already been started and was - * already in the active state, then xTimerReset() will cause the timer to - * re-evaluate its expiry time so that it is relative to when xTimerReset() was - * called. If the timer was in the dormant state then xTimerReset() has - * equivalent functionality to the xTimerStart() API function. - * - * Resetting a timer ensures the timer is in the active state. If the timer - * is not stopped, deleted, or reset in the mean time, the callback function - * associated with the timer will get called 'n' ticks after xTimerReset() was - * called, where 'n' is the timers defined period. - * - * It is valid to call xTimerReset() before the scheduler has been started, but - * when this is done the timer will not actually start until the scheduler is - * started, and the timers expiry time will be relative to when the scheduler is - * started, not relative to when xTimerReset() was called. - * - * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset() - * to be available. - * - * @param xTimer The handle of the timer being reset/started/restarted. - * - * @param xBlockTime Specifies the time, in ticks, that the calling task should - * be held in the Blocked state to wait for the reset command to be successfully - * sent to the timer command queue, should the queue already be full when - * xTimerReset() was called. xBlockTime is ignored if xTimerReset() is called - * before the scheduler is started. - * - * @return pdFAIL will be returned if the reset command could not be sent to - * the timer command queue even after xBlockTime ticks had passed. pdPASS will - * be returned if the command was successfully sent to the timer command queue. - * When the command is actually processed will depend on the priority of the - * timer service/daemon task relative to other tasks in the system, although the - * timers expiry time is relative to when xTimerStart() is actually called. The - * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY - * configuration constant. - * - * Example usage: - * - * // When a key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer. - * - * xTimerHandle xBacklightTimer = NULL; - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTimerHandle pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press event handler. - * void vKeyPressEventHandler( char cKey ) - * { - * // Ensure the LCD back-light is on, then reset the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. Wait 10 ticks for the command to be successfully sent - * // if it cannot be sent immediately. - * vSetBacklightState( BACKLIGHT_ON ); - * if( xTimerReset( xBacklightTimer, 100 ) != pdPASS ) - * { - * // The reset command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * } - * - * void main( void ) - * { - * long x; - * - * // Create then start the one-shot timer that is responsible for turning - * // the back-light off if no keys are pressed within a 5 second period. - * xBacklightTimer = xTimerCreate( "BacklightTimer", // Just a text name, not used by the kernel. - * ( 5000 / portTICK_RATE_MS), // The timer period in ticks. - * pdFALSE, // The timer is a one-shot timer. - * 0, // The id is not used by the callback so can take any value. - * vBacklightTimerCallback // The callback function that switches the LCD back-light off. - * ); - * - * if( xBacklightTimer == NULL ) - * { - * // The timer was not created. - * } - * else - * { - * // Start the timer. No block time is specified, and even if one was - * // it would be ignored because the scheduler has not yet been - * // started. - * if( xTimerStart( xBacklightTimer, 0 ) != pdPASS ) - * { - * // The timer could not be set into the Active state. - * } - * } - * - * // ... - * // Create tasks here. - * // ... - * - * // Starting the scheduler will start the timer running as it has already - * // been set into the active state. - * xTaskStartScheduler(); - * - * // Should not reach here. - * for( ;; ); - * } - */ -#define xTimerReset( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) - -/** - * portBASE_TYPE xTimerStartFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerStart() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer being started/restarted. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerStartFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerStartFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerStartFromISR() function. If - * xTimerStartFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the start command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system, although the timers expiry time is - * relative to when xTimerStartFromISR() is actually called. The timer service/daemon - * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xBacklightTimer has already been created. When a - * // key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer, and unlike the example given for - * // the xTimerReset() function, the key press event handler is an interrupt - * // service routine. - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTimerHandle pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press interrupt service routine. - * void vKeyPressEventInterruptHandler( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // Ensure the LCD back-light is on, then restart the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. This is an interrupt service routine so can only - * // call FreeRTOS API functions that end in "FromISR". - * vSetBacklightState( BACKLIGHT_ON ); - * - * // xTimerStartFromISR() or xTimerResetFromISR() could be called here - * // as both cause the timer to re-calculate its expiry time. - * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was - * // declared (in this function). - * if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The start command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerStopFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerStop() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer being stopped. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerStopFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerStopFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerStopFromISR() function. If - * xTimerStopFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the stop command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system. The timer service/daemon task - * priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xTimer has already been created and started. When - * // an interrupt occurs, the timer should be simply stopped. - * - * // The interrupt service routine that stops the timer. - * void vAnExampleInterruptServiceRoutine( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // The interrupt has occurred - simply stop the timer. - * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined - * // (within this function). As this is an interrupt service routine, only - * // FreeRTOS API functions that end in "FromISR" can be used. - * if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The stop command was not executed successfully. Take appropriate - * // action here. - * } - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0, ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerChangePeriodFromISR( xTimerHandle xTimer, - * portTickType xNewPeriod, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerChangePeriod() that can be called from an interrupt - * service routine. - * - * @param xTimer The handle of the timer that is having its period changed. - * - * @param xNewPeriod The new period for xTimer. Timer periods are specified in - * tick periods, so the constant portTICK_RATE_MS can be used to convert a time - * that has been specified in milliseconds. For example, if the timer must - * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, - * if the timer must expire after 500ms, then xNewPeriod can be set to - * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than - * or equal to 1000. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerChangePeriodFromISR() writes a message to the - * timer command queue, so has the potential to transition the timer service/ - * daemon task out of the Blocked state. If calling xTimerChangePeriodFromISR() - * causes the timer service/daemon task to leave the Blocked state, and the - * timer service/daemon task has a priority equal to or greater than the - * currently executing task (the task that was interrupted), then - * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the - * xTimerChangePeriodFromISR() function. If xTimerChangePeriodFromISR() sets - * this value to pdTRUE then a context switch should be performed before the - * interrupt exits. - * - * @return pdFAIL will be returned if the command to change the timers period - * could not be sent to the timer command queue. pdPASS will be returned if the - * command was successfully sent to the timer command queue. When the command - * is actually processed will depend on the priority of the timer service/daemon - * task relative to other tasks in the system. The timer service/daemon task - * priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xTimer has already been created and started. When - * // an interrupt occurs, the period of xTimer should be changed to 500ms. - * - * // The interrupt service routine that changes the period of xTimer. - * void vAnExampleInterruptServiceRoutine( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // The interrupt has occurred - change the period of xTimer to 500ms. - * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined - * // (within this function). As this is an interrupt service routine, only - * // FreeRTOS API functions that end in "FromISR" can be used. - * if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The command to change the timers period was not executed - * // successfully. Take appropriate action here. - * } - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U ) - -/** - * portBASE_TYPE xTimerResetFromISR( xTimerHandle xTimer, - * portBASE_TYPE *pxHigherPriorityTaskWoken ); - * - * A version of xTimerReset() that can be called from an interrupt service - * routine. - * - * @param xTimer The handle of the timer that is to be started, reset, or - * restarted. - * - * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most - * of its time in the Blocked state, waiting for messages to arrive on the timer - * command queue. Calling xTimerResetFromISR() writes a message to the timer - * command queue, so has the potential to transition the timer service/daemon - * task out of the Blocked state. If calling xTimerResetFromISR() causes the - * timer service/daemon task to leave the Blocked state, and the timer service/ - * daemon task has a priority equal to or greater than the currently executing - * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will - * get set to pdTRUE internally within the xTimerResetFromISR() function. If - * xTimerResetFromISR() sets this value to pdTRUE then a context switch should - * be performed before the interrupt exits. - * - * @return pdFAIL will be returned if the reset command could not be sent to - * the timer command queue. pdPASS will be returned if the command was - * successfully sent to the timer command queue. When the command is actually - * processed will depend on the priority of the timer service/daemon task - * relative to other tasks in the system, although the timers expiry time is - * relative to when xTimerResetFromISR() is actually called. The timer service/daemon - * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. - * - * Example usage: - * - * // This scenario assumes xBacklightTimer has already been created. When a - * // key is pressed, an LCD back-light is switched on. If 5 seconds pass - * // without a key being pressed, then the LCD back-light is switched off. In - * // this case, the timer is a one-shot timer, and unlike the example given for - * // the xTimerReset() function, the key press event handler is an interrupt - * // service routine. - * - * // The callback function assigned to the one-shot timer. In this case the - * // parameter is not used. - * void vBacklightTimerCallback( xTimerHandle pxTimer ) - * { - * // The timer expired, therefore 5 seconds must have passed since a key - * // was pressed. Switch off the LCD back-light. - * vSetBacklightState( BACKLIGHT_OFF ); - * } - * - * // The key press interrupt service routine. - * void vKeyPressEventInterruptHandler( void ) - * { - * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; - * - * // Ensure the LCD back-light is on, then reset the timer that is - * // responsible for turning the back-light off after 5 seconds of - * // key inactivity. This is an interrupt service routine so can only - * // call FreeRTOS API functions that end in "FromISR". - * vSetBacklightState( BACKLIGHT_ON ); - * - * // xTimerStartFromISR() or xTimerResetFromISR() could be called here - * // as both cause the timer to re-calculate its expiry time. - * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was - * // declared (in this function). - * if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) - * { - * // The reset command was not executed successfully. Take appropriate - * // action here. - * } - * - * // Perform the rest of the key processing here. - * - * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch - * // should be performed. The syntax required to perform a context switch - * // from inside an ISR varies from port to port, and from compiler to - * // compiler. Inspect the demos for the port you are using to find the - * // actual syntax required. - * if( xHigherPriorityTaskWoken != pdFALSE ) - * { - * // Call the interrupt safe yield function here (actual function - * // depends on the FreeRTOS port being used. - * } - * } - */ -#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) - -/* - * Functions beyond this part are not part of the public API and are intended - * for use by the kernel only. - */ -portBASE_TYPE xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; -portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) PRIVILEGED_FUNCTION; - -#ifdef __cplusplus -} -#endif -#endif /* TIMERS_H */ - - - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#ifndef TIMERS_H +#define TIMERS_H + +#ifndef INC_FREERTOS_H + #error "include FreeRTOS.h must appear in source files before include timers.h" +#endif + +#include "portable.h" +#include "list.h" +#include "task.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* IDs for commands that can be sent/received on the timer queue. These are to +be used solely through the macros that make up the public software timer API, +as defined below. */ +#define tmrCOMMAND_START 0 +#define tmrCOMMAND_STOP 1 +#define tmrCOMMAND_CHANGE_PERIOD 2 +#define tmrCOMMAND_DELETE 3 + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + + /** + * Type by which software timers are referenced. For example, a call to + * xTimerCreate() returns an xTimerHandle variable that can then be used to + * reference the subject timer in calls to other software timer API functions + * (for example, xTimerStart(), xTimerReset(), etc.). + */ +typedef void * xTimerHandle; + +/* Define the prototype to which timer callback functions must conform. */ +typedef void (*tmrTIMER_CALLBACK)( xTimerHandle xTimer ); + +/** + * xTimerHandle xTimerCreate( const signed char *pcTimerName, + * portTickType xTimerPeriodInTicks, + * unsigned portBASE_TYPE uxAutoReload, + * void * pvTimerID, + * tmrTIMER_CALLBACK pxCallbackFunction ); + * + * Creates a new software timer instance. This allocates the storage required + * by the new timer, initialises the new timers internal state, and returns a + * handle by which the new timer can be referenced. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the + * active state. + * + * @param pcTimerName A text name that is assigned to the timer. This is done + * purely to assist debugging. The kernel itself only ever references a timer by + * its handle, and never by its name. + * + * @param xTimerPeriodInTicks The timer period. The time is defined in tick periods so + * the constant portTICK_RATE_MS can be used to convert a time that has been + * specified in milliseconds. For example, if the timer must expire after 100 + * ticks, then xTimerPeriodInTicks should be set to 100. Alternatively, if the timer + * must expire after 500ms, then xPeriod can be set to ( 500 / portTICK_RATE_MS ) + * provided configTICK_RATE_HZ is less than or equal to 1000. + * + * @param uxAutoReload If uxAutoReload is set to pdTRUE then the timer will + * expire repeatedly with a frequency set by the xTimerPeriodInTicks parameter. If + * uxAutoReload is set to pdFALSE then the timer will be a one-shot timer and + * enter the dormant state after it expires. + * + * @param pvTimerID An identifier that is assigned to the timer being created. + * Typically this would be used in the timer callback function to identify which + * timer expired when the same callback function is assigned to more than one + * timer. + * + * @param pxCallbackFunction The function to call when the timer expires. + * Callback functions must have the prototype defined by tmrTIMER_CALLBACK, + * which is "void vCallbackFunction( xTimerHandle xTimer );". + * + * @return If the timer is successfully create then a handle to the newly + * created timer is returned. If the timer cannot be created (because either + * there is insufficient FreeRTOS heap remaining to allocate the timer + * structures, or the timer period was set to 0) then 0 is returned. + * + * Example usage: + * + * #define NUM_TIMERS 5 + * + * // An array to hold handles to the created timers. + * xTimerHandle xTimers[ NUM_TIMERS ]; + * + * // An array to hold a count of the number of times each timer expires. + * long lExpireCounters[ NUM_TIMERS ] = { 0 }; + * + * // Define a callback function that will be used by multiple timer instances. + * // The callback function does nothing but count the number of times the + * // associated timer expires, and stop the timer once the timer has expired + * // 10 times. + * void vTimerCallback( xTimerHandle pxTimer ) + * { + * long lArrayIndex; + * const long xMaxExpiryCountBeforeStopping = 10; + * + * // Optionally do something if the pxTimer parameter is NULL. + * configASSERT( pxTimer ); + * + * // Which timer expired? + * lArrayIndex = ( long ) pvTimerGetTimerID( pxTimer ); + * + * // Increment the number of times that pxTimer has expired. + * lExpireCounters[ lArrayIndex ] += 1; + * + * // If the timer has expired 10 times then stop it from running. + * if( lExpireCounters[ lArrayIndex ] == xMaxExpiryCountBeforeStopping ) + * { + * // Do not use a block time if calling a timer API function from a + * // timer callback function, as doing so could cause a deadlock! + * xTimerStop( pxTimer, 0 ); + * } + * } + * + * void main( void ) + * { + * long x; + * + * // Create then start some timers. Starting the timers before the scheduler + * // has been started means the timers will start running immediately that + * // the scheduler starts. + * for( x = 0; x < NUM_TIMERS; x++ ) + * { + * xTimers[ x ] = xTimerCreate( "Timer", // Just a text name, not used by the kernel. + * ( 100 * x ), // The timer period in ticks. + * pdTRUE, // The timers will auto-reload themselves when they expire. + * ( void * ) x, // Assign each timer a unique id equal to its array index. + * vTimerCallback // Each timer calls the same callback when it expires. + * ); + * + * if( xTimers[ x ] == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xTimers[ x ], 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timers running as they have already + * // been set into the active state. + * xTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + */ +xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void * pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) PRIVILEGED_FUNCTION; + +/** + * void *pvTimerGetTimerID( xTimerHandle xTimer ); + * + * Returns the ID assigned to the timer. + * + * IDs are assigned to timers using the pvTimerID parameter of the call to + * xTimerCreated() that was used to create the timer. + * + * If the same callback function is assigned to multiple timers then the timer + * ID can be used within the callback function to identify which timer actually + * expired. + * + * @param xTimer The timer being queried. + * + * @return The ID assigned to the timer being queried. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + */ +void *pvTimerGetTimerID( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; + +/** + * portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ); + * + * Queries a timer to see if it is active or dormant. + * + * A timer will be dormant if: + * 1) It has been created but not started, or + * 2) It is an expired on-shot timer that has not been restarted. + * + * Timers are created in the dormant state. The xTimerStart(), xTimerReset(), + * xTimerStartFromISR(), xTimerResetFromISR(), xTimerChangePeriod() and + * xTimerChangePeriodFromISR() API functions can all be used to transition a timer into the + * active state. + * + * @param xTimer The timer being queried. + * + * @return pdFALSE will be returned if the timer is dormant. A value other than + * pdFALSE will be returned if the timer is active. + * + * Example usage: + * + * // This function assumes xTimer has already been created. + * void vAFunction( xTimerHandle xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is active, do something. + * } + * else + * { + * // xTimer is not active, do something else. + * } + * } + */ +portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) PRIVILEGED_FUNCTION; + +/** + * xTimerGetTimerDaemonTaskHandle() is only available if + * INCLUDE_xTimerGetTimerDaemonTaskHandle is set to 1 in FreeRTOSConfig.h. + * + * Simply returns the handle of the timer service/daemon task. It it not valid + * to call xTimerGetTimerDaemonTaskHandle() before the scheduler has been started. + */ +xTaskHandle xTimerGetTimerDaemonTaskHandle( void ); + +/** + * portBASE_TYPE xTimerStart( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStart() starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerStart() has equivalent functionality + * to the xTimerReset() API function. + * + * Starting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerStart() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerStart() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerStart() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStart() + * to be available. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the start command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStart() was called. xBlockTime is ignored if xTimerStart() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStart( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerStop( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerStop() stops a timer that was previously started using either of the + * The xTimerStart(), xTimerReset(), xTimerStartFromISR(), xTimerResetFromISR(), + * xTimerChangePeriod() or xTimerChangePeriodFromISR() API functions. + * + * Stopping a timer ensures the timer is not in the active state. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerStop() + * to be available. + * + * @param xTimer The handle of the timer being stopped. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the stop command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerStop() was called. xBlockTime is ignored if xTimerStop() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerCreate() API function example usage scenario. + * + */ +#define xTimerStop( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0U, NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerChangePeriod( xTimerHandle xTimer, + * portTickType xNewPeriod, + * portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerChangePeriod() changes the period of a timer that was previously + * created using the xTimerCreate() API function. + * + * xTimerChangePeriod() can be called to change the period of an active or + * dormant state timer. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerChangePeriod() to be available. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_RATE_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the change period command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerChangePeriod() was called. xBlockTime is ignored if + * xTimerChangePeriod() is called before the scheduler is started. + * + * @return pdFAIL will be returned if the change period command could not be + * sent to the timer command queue even after xBlockTime ticks had passed. + * pdPASS will be returned if the command was successfully sent to the timer + * command queue. When the command is actually processed will depend on the + * priority of the timer service/daemon task relative to other tasks in the + * system. The timer service/daemon task priority is set by the + * configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This function assumes xTimer has already been created. If the timer + * // referenced by xTimer is already active when it is called, then the timer + * // is deleted. If the timer referenced by xTimer is not active when it is + * // called, then the period of the timer is set to 500ms and the timer is + * // started. + * void vAFunction( xTimerHandle xTimer ) + * { + * if( xTimerIsTimerActive( xTimer ) != pdFALSE ) // or more simply and equivalently "if( xTimerIsTimerActive( xTimer ) )" + * { + * // xTimer is already active - delete it. + * xTimerDelete( xTimer ); + * } + * else + * { + * // xTimer is not active, change its period to 500ms. This will also + * // cause the timer to start. Block for a maximum of 100 ticks if the + * // change period command cannot immediately be sent to the timer + * // command queue. + * if( xTimerChangePeriod( xTimer, 500 / portTICK_RATE_MS, 100 ) == pdPASS ) + * { + * // The command was successfully sent. + * } + * else + * { + * // The command could not be sent, even after waiting for 100 ticks + * // to pass. Take appropriate action here. + * } + * } + * } + */ + #define xTimerChangePeriod( xTimer, xNewPeriod, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerDelete( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerDelete() deletes a timer that was previously created using the + * xTimerCreate() API function. + * + * The configUSE_TIMERS configuration constant must be set to 1 for + * xTimerDelete() to be available. + * + * @param xTimer The handle of the timer being deleted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the delete command to be + * successfully sent to the timer command queue, should the queue already be + * full when xTimerDelete() was called. xBlockTime is ignored if xTimerDelete() + * is called before the scheduler is started. + * + * @return pdFAIL will be returned if the delete command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system. The timer + * service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * See the xTimerChangePeriod() API function example usage scenario. + */ +#define xTimerDelete( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_DELETE, 0U, NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerReset( xTimerHandle xTimer, portTickType xBlockTime ); + * + * Timer functionality is provided by a timer service/daemon task. Many of the + * public FreeRTOS timer API functions send commands to the timer service task + * though a queue called the timer command queue. The timer command queue is + * private to the kernel itself and is not directly accessible to application + * code. The length of the timer command queue is set by the + * configTIMER_QUEUE_LENGTH configuration constant. + * + * xTimerReset() re-starts a timer that was previously created using the + * xTimerCreate() API function. If the timer had already been started and was + * already in the active state, then xTimerReset() will cause the timer to + * re-evaluate its expiry time so that it is relative to when xTimerReset() was + * called. If the timer was in the dormant state then xTimerReset() has + * equivalent functionality to the xTimerStart() API function. + * + * Resetting a timer ensures the timer is in the active state. If the timer + * is not stopped, deleted, or reset in the mean time, the callback function + * associated with the timer will get called 'n' ticks after xTimerReset() was + * called, where 'n' is the timers defined period. + * + * It is valid to call xTimerReset() before the scheduler has been started, but + * when this is done the timer will not actually start until the scheduler is + * started, and the timers expiry time will be relative to when the scheduler is + * started, not relative to when xTimerReset() was called. + * + * The configUSE_TIMERS configuration constant must be set to 1 for xTimerReset() + * to be available. + * + * @param xTimer The handle of the timer being reset/started/restarted. + * + * @param xBlockTime Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the reset command to be successfully + * sent to the timer command queue, should the queue already be full when + * xTimerReset() was called. xBlockTime is ignored if xTimerReset() is called + * before the scheduler is started. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue even after xBlockTime ticks had passed. pdPASS will + * be returned if the command was successfully sent to the timer command queue. + * When the command is actually processed will depend on the priority of the + * timer service/daemon task relative to other tasks in the system, although the + * timers expiry time is relative to when xTimerStart() is actually called. The + * timer service/daemon task priority is set by the configTIMER_TASK_PRIORITY + * configuration constant. + * + * Example usage: + * + * // When a key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer. + * + * xTimerHandle xBacklightTimer = NULL; + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTimerHandle pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press event handler. + * void vKeyPressEventHandler( char cKey ) + * { + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. Wait 10 ticks for the command to be successfully sent + * // if it cannot be sent immediately. + * vSetBacklightState( BACKLIGHT_ON ); + * if( xTimerReset( xBacklightTimer, 100 ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * } + * + * void main( void ) + * { + * long x; + * + * // Create then start the one-shot timer that is responsible for turning + * // the back-light off if no keys are pressed within a 5 second period. + * xBacklightTimer = xTimerCreate( "BacklightTimer", // Just a text name, not used by the kernel. + * ( 5000 / portTICK_RATE_MS), // The timer period in ticks. + * pdFALSE, // The timer is a one-shot timer. + * 0, // The id is not used by the callback so can take any value. + * vBacklightTimerCallback // The callback function that switches the LCD back-light off. + * ); + * + * if( xBacklightTimer == NULL ) + * { + * // The timer was not created. + * } + * else + * { + * // Start the timer. No block time is specified, and even if one was + * // it would be ignored because the scheduler has not yet been + * // started. + * if( xTimerStart( xBacklightTimer, 0 ) != pdPASS ) + * { + * // The timer could not be set into the Active state. + * } + * } + * + * // ... + * // Create tasks here. + * // ... + * + * // Starting the scheduler will start the timer running as it has already + * // been set into the active state. + * xTaskStartScheduler(); + * + * // Should not reach here. + * for( ;; ); + * } + */ +#define xTimerReset( xTimer, xBlockTime ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCount() ), NULL, ( xBlockTime ) ) + +/** + * portBASE_TYPE xTimerStartFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStart() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being started/restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStartFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStartFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStartFromISR() function. If + * xTimerStartFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the start command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerStartFromISR() is actually called. The timer service/daemon + * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTimerHandle pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then restart the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerStartFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The start command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerStartFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerStopFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerStop() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer being stopped. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerStopFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerStopFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerStopFromISR() function. If + * xTimerStopFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the stop command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the timer should be simply stopped. + * + * // The interrupt service routine that stops the timer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - simply stop the timer. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerStopFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The stop command was not executed successfully. Take appropriate + * // action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerStopFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_STOP, 0, ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerChangePeriodFromISR( xTimerHandle xTimer, + * portTickType xNewPeriod, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerChangePeriod() that can be called from an interrupt + * service routine. + * + * @param xTimer The handle of the timer that is having its period changed. + * + * @param xNewPeriod The new period for xTimer. Timer periods are specified in + * tick periods, so the constant portTICK_RATE_MS can be used to convert a time + * that has been specified in milliseconds. For example, if the timer must + * expire after 100 ticks, then xNewPeriod should be set to 100. Alternatively, + * if the timer must expire after 500ms, then xNewPeriod can be set to + * ( 500 / portTICK_RATE_MS ) provided configTICK_RATE_HZ is less than + * or equal to 1000. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerChangePeriodFromISR() writes a message to the + * timer command queue, so has the potential to transition the timer service/ + * daemon task out of the Blocked state. If calling xTimerChangePeriodFromISR() + * causes the timer service/daemon task to leave the Blocked state, and the + * timer service/daemon task has a priority equal to or greater than the + * currently executing task (the task that was interrupted), then + * *pxHigherPriorityTaskWoken will get set to pdTRUE internally within the + * xTimerChangePeriodFromISR() function. If xTimerChangePeriodFromISR() sets + * this value to pdTRUE then a context switch should be performed before the + * interrupt exits. + * + * @return pdFAIL will be returned if the command to change the timers period + * could not be sent to the timer command queue. pdPASS will be returned if the + * command was successfully sent to the timer command queue. When the command + * is actually processed will depend on the priority of the timer service/daemon + * task relative to other tasks in the system. The timer service/daemon task + * priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xTimer has already been created and started. When + * // an interrupt occurs, the period of xTimer should be changed to 500ms. + * + * // The interrupt service routine that changes the period of xTimer. + * void vAnExampleInterruptServiceRoutine( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // The interrupt has occurred - change the period of xTimer to 500ms. + * // xHigherPriorityTaskWoken was set to pdFALSE where it was defined + * // (within this function). As this is an interrupt service routine, only + * // FreeRTOS API functions that end in "FromISR" can be used. + * if( xTimerChangePeriodFromISR( xTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The command to change the timers period was not executed + * // successfully. Take appropriate action here. + * } + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerChangePeriodFromISR( xTimer, xNewPeriod, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_CHANGE_PERIOD, ( xNewPeriod ), ( pxHigherPriorityTaskWoken ), 0U ) + +/** + * portBASE_TYPE xTimerResetFromISR( xTimerHandle xTimer, + * portBASE_TYPE *pxHigherPriorityTaskWoken ); + * + * A version of xTimerReset() that can be called from an interrupt service + * routine. + * + * @param xTimer The handle of the timer that is to be started, reset, or + * restarted. + * + * @param pxHigherPriorityTaskWoken The timer service/daemon task spends most + * of its time in the Blocked state, waiting for messages to arrive on the timer + * command queue. Calling xTimerResetFromISR() writes a message to the timer + * command queue, so has the potential to transition the timer service/daemon + * task out of the Blocked state. If calling xTimerResetFromISR() causes the + * timer service/daemon task to leave the Blocked state, and the timer service/ + * daemon task has a priority equal to or greater than the currently executing + * task (the task that was interrupted), then *pxHigherPriorityTaskWoken will + * get set to pdTRUE internally within the xTimerResetFromISR() function. If + * xTimerResetFromISR() sets this value to pdTRUE then a context switch should + * be performed before the interrupt exits. + * + * @return pdFAIL will be returned if the reset command could not be sent to + * the timer command queue. pdPASS will be returned if the command was + * successfully sent to the timer command queue. When the command is actually + * processed will depend on the priority of the timer service/daemon task + * relative to other tasks in the system, although the timers expiry time is + * relative to when xTimerResetFromISR() is actually called. The timer service/daemon + * task priority is set by the configTIMER_TASK_PRIORITY configuration constant. + * + * Example usage: + * + * // This scenario assumes xBacklightTimer has already been created. When a + * // key is pressed, an LCD back-light is switched on. If 5 seconds pass + * // without a key being pressed, then the LCD back-light is switched off. In + * // this case, the timer is a one-shot timer, and unlike the example given for + * // the xTimerReset() function, the key press event handler is an interrupt + * // service routine. + * + * // The callback function assigned to the one-shot timer. In this case the + * // parameter is not used. + * void vBacklightTimerCallback( xTimerHandle pxTimer ) + * { + * // The timer expired, therefore 5 seconds must have passed since a key + * // was pressed. Switch off the LCD back-light. + * vSetBacklightState( BACKLIGHT_OFF ); + * } + * + * // The key press interrupt service routine. + * void vKeyPressEventInterruptHandler( void ) + * { + * portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; + * + * // Ensure the LCD back-light is on, then reset the timer that is + * // responsible for turning the back-light off after 5 seconds of + * // key inactivity. This is an interrupt service routine so can only + * // call FreeRTOS API functions that end in "FromISR". + * vSetBacklightState( BACKLIGHT_ON ); + * + * // xTimerStartFromISR() or xTimerResetFromISR() could be called here + * // as both cause the timer to re-calculate its expiry time. + * // xHigherPriorityTaskWoken was initialised to pdFALSE when it was + * // declared (in this function). + * if( xTimerResetFromISR( xBacklightTimer, &xHigherPriorityTaskWoken ) != pdPASS ) + * { + * // The reset command was not executed successfully. Take appropriate + * // action here. + * } + * + * // Perform the rest of the key processing here. + * + * // If xHigherPriorityTaskWoken equals pdTRUE, then a context switch + * // should be performed. The syntax required to perform a context switch + * // from inside an ISR varies from port to port, and from compiler to + * // compiler. Inspect the demos for the port you are using to find the + * // actual syntax required. + * if( xHigherPriorityTaskWoken != pdFALSE ) + * { + * // Call the interrupt safe yield function here (actual function + * // depends on the FreeRTOS port being used. + * } + * } + */ +#define xTimerResetFromISR( xTimer, pxHigherPriorityTaskWoken ) xTimerGenericCommand( ( xTimer ), tmrCOMMAND_START, ( xTaskGetTickCountFromISR() ), ( pxHigherPriorityTaskWoken ), 0U ) + +/* + * Functions beyond this part are not part of the public API and are intended + * for use by the kernel only. + */ +portBASE_TYPE xTimerCreateTimerTask( void ) PRIVILEGED_FUNCTION; +portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) PRIVILEGED_FUNCTION; + +#ifdef __cplusplus +} +#endif +#endif /* TIMERS_H */ + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c index 9ae5d86e4..418a0f7c8 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/list.c @@ -1,204 +1,204 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#include -#include "FreeRTOS.h" -#include "list.h" - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -void vListInitialise( xList *pxList ) -{ - /* The list structure contains a list item which is used to mark the - end of the list. To initialise the list the list end is inserted - as the only list entry. */ - pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); - - /* The list end value is the highest possible value in the list to - ensure it remains at the end of the list. */ - pxList->xListEnd.xItemValue = portMAX_DELAY; - - /* The list end next and previous pointers point to itself so we know - when the list is empty. */ - pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); - pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); - - pxList->uxNumberOfItems = ( unsigned portBASE_TYPE ) 0U; -} -/*-----------------------------------------------------------*/ - -void vListInitialiseItem( xListItem *pxItem ) -{ - /* Make sure the list item is not recorded as being on a list. */ - pxItem->pvContainer = NULL; -} -/*-----------------------------------------------------------*/ - -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) -{ -volatile xListItem * pxIndex; - - /* Insert a new list item into pxList, but rather than sort the list, - makes the new list item the last item to be removed by a call to - pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by - the pxIndex member. */ - pxIndex = pxList->pxIndex; - - pxNewListItem->pxNext = pxIndex->pxNext; - pxNewListItem->pxPrevious = pxList->pxIndex; - pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; - pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListInsert( xList *pxList, xListItem *pxNewListItem ) -{ -volatile xListItem *pxIterator; -portTickType xValueOfInsertion; - - /* Insert the new list item into the list, sorted in ulListItem order. */ - xValueOfInsertion = pxNewListItem->xItemValue; - - /* If the list already contains a list item with the same item value then - the new list item should be placed after it. This ensures that TCB's which - are stored in ready lists (all of which have the same ulListItem value) - get an equal share of the CPU. However, if the xItemValue is the same as - the back marker the iteration loop below will not end. This means we need - to guard against this by checking the value first and modifying the - algorithm slightly if necessary. */ - if( xValueOfInsertion == portMAX_DELAY ) - { - pxIterator = pxList->xListEnd.pxPrevious; - } - else - { - /* *** NOTE *********************************************************** - If you find your application is crashing here then likely causes are: - 1) Stack overflow - - see http://www.freertos.org/Stacks-and-stack-overflow-checking.html - 2) Incorrect interrupt priority assignment, especially on Cortex-M3 - parts where numerically high priority values denote low actual - interrupt priories, which can seem counter intuitive. See - configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html - 3) Calling an API function from within a critical section or when - the scheduler is suspended. - 4) Using a queue or semaphore before it has been initialised or - before the scheduler has been started (are interrupts firing - before vTaskStartScheduler() has been called?). - See http://www.freertos.org/FAQHelp.html for more tips. - **********************************************************************/ - - for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) - { - /* There is nothing to do here, we are just iterating to the - wanted insertion position. */ - } - } - - pxNewListItem->pxNext = pxIterator->pxNext; - pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxNewListItem->pxPrevious = pxIterator; - pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. This allows fast removal of the - item later. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListRemove( xListItem *pxItemToRemove ) -{ -xList * pxList; - - pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; - pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; - - /* The list item knows which list it is in. Obtain the list from the list - item. */ - pxList = ( xList * ) pxItemToRemove->pvContainer; - - /* Make sure the index is left pointing to a valid item. */ - if( pxList->pxIndex == pxItemToRemove ) - { - pxList->pxIndex = pxItemToRemove->pxPrevious; - } - - pxItemToRemove->pvContainer = NULL; - ( pxList->uxNumberOfItems )--; -} -/*-----------------------------------------------------------*/ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#include +#include "FreeRTOS.h" +#include "list.h" + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +void vListInitialise( xList *pxList ) +{ + /* The list structure contains a list item which is used to mark the + end of the list. To initialise the list the list end is inserted + as the only list entry. */ + pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); + + /* The list end value is the highest possible value in the list to + ensure it remains at the end of the list. */ + pxList->xListEnd.xItemValue = portMAX_DELAY; + + /* The list end next and previous pointers point to itself so we know + when the list is empty. */ + pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); + pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); + + pxList->uxNumberOfItems = ( unsigned portBASE_TYPE ) 0U; +} +/*-----------------------------------------------------------*/ + +void vListInitialiseItem( xListItem *pxItem ) +{ + /* Make sure the list item is not recorded as being on a list. */ + pxItem->pvContainer = NULL; +} +/*-----------------------------------------------------------*/ + +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) +{ +volatile xListItem * pxIndex; + + /* Insert a new list item into pxList, but rather than sort the list, + makes the new list item the last item to be removed by a call to + pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by + the pxIndex member. */ + pxIndex = pxList->pxIndex; + + pxNewListItem->pxNext = pxIndex->pxNext; + pxNewListItem->pxPrevious = pxList->pxIndex; + pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; + pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListInsert( xList *pxList, xListItem *pxNewListItem ) +{ +volatile xListItem *pxIterator; +portTickType xValueOfInsertion; + + /* Insert the new list item into the list, sorted in ulListItem order. */ + xValueOfInsertion = pxNewListItem->xItemValue; + + /* If the list already contains a list item with the same item value then + the new list item should be placed after it. This ensures that TCB's which + are stored in ready lists (all of which have the same ulListItem value) + get an equal share of the CPU. However, if the xItemValue is the same as + the back marker the iteration loop below will not end. This means we need + to guard against this by checking the value first and modifying the + algorithm slightly if necessary. */ + if( xValueOfInsertion == portMAX_DELAY ) + { + pxIterator = pxList->xListEnd.pxPrevious; + } + else + { + /* *** NOTE *********************************************************** + If you find your application is crashing here then likely causes are: + 1) Stack overflow - + see http://www.freertos.org/Stacks-and-stack-overflow-checking.html + 2) Incorrect interrupt priority assignment, especially on Cortex-M3 + parts where numerically high priority values denote low actual + interrupt priories, which can seem counter intuitive. See + configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html + 3) Calling an API function from within a critical section or when + the scheduler is suspended. + 4) Using a queue or semaphore before it has been initialised or + before the scheduler has been started (are interrupts firing + before vTaskStartScheduler() has been called?). + See http://www.freertos.org/FAQHelp.html for more tips. + **********************************************************************/ + + for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) + { + /* There is nothing to do here, we are just iterating to the + wanted insertion position. */ + } + } + + pxNewListItem->pxNext = pxIterator->pxNext; + pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxNewListItem->pxPrevious = pxIterator; + pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. This allows fast removal of the + item later. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListRemove( xListItem *pxItemToRemove ) +{ +xList * pxList; + + pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; + pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; + + /* The list item knows which list it is in. Obtain the list from the list + item. */ + pxList = ( xList * ) pxItemToRemove->pvContainer; + + /* Make sure the index is left pointing to a valid item. */ + if( pxList->pxIndex == pxItemToRemove ) + { + pxList->pxIndex = pxItemToRemove->pxPrevious; + } + + pxItemToRemove->pvContainer = NULL; + ( pxList->uxNumberOfItems )--; +} +/*-----------------------------------------------------------*/ + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c index 4748860db..8abfaf95e 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/queue.c @@ -1,1682 +1,1682 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" - -#if ( configUSE_CO_ROUTINES == 1 ) - #include "croutine.h" -#endif - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -/* Constants used with the cRxLock and xTxLock structure members. */ -#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) -#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) - -#define queueERRONEOUS_UNBLOCK ( -1 ) - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - -/* Effectively make a union out of the xQUEUE structure. */ -#define pxMutexHolder pcTail -#define uxQueueType pcHead -#define uxRecursiveCallCount pcReadFrom -#define queueQUEUE_IS_MUTEX NULL - -/* Semaphores do not actually store or copy data, so have an items size of -zero. */ -#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned portBASE_TYPE ) 0 ) -#define queueDONT_BLOCK ( ( portTickType ) 0U ) -#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0U ) - -/* These definitions *must* match those in queue.h. */ -#define queueQUEUE_TYPE_BASE ( 0U ) -#define queueQUEUE_TYPE_MUTEX ( 1U ) -#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( 2U ) -#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( 3U ) -#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( 4U ) - -/* - * Definition of the queue used by the scheduler. - * Items are queued by copy, not reference. - */ -typedef struct QueueDefinition -{ - signed char *pcHead; /*< Points to the beginning of the queue storage area. */ - signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ - - signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ - signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ - - xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ - xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ - - volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ - unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ - unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ - - volatile signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - volatile signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned char ucQueueNumber; - unsigned char ucQueueType; - #endif - -} xQUEUE; -/*-----------------------------------------------------------*/ - -/* - * Inside this file xQueueHandle is a pointer to a xQUEUE structure. - * To keep the definition private the API header file defines it as a - * pointer to void. - */ -typedef xQUEUE * xQueueHandle; - -/* - * Prototypes for public functions are included here so we don't have to - * include the API header file (as it defines xQueueHandle differently). These - * functions are documented in the API header file. - */ -xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; -unsigned char ucQueueGetQueueNumber( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueSetQueueNumber( xQueueHandle pxQueue, unsigned char ucQueueNumber ) PRIVILEGED_FUNCTION; -unsigned char ucQueueGetQueueType( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ) PRIVILEGED_FUNCTION; -xTaskHandle xQueueGetMutexHolder( xQueueHandle xSemaphore ) PRIVILEGED_FUNCTION; - -/* - * Co-routine queue functions differ from task queue functions. Co-routines are - * an optional component. - */ -#if configUSE_CO_ROUTINES == 1 - signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; -#endif - -/* - * The queue registry is just a means for kernel aware debuggers to locate - * queue structures. It has no other purpose so is an optional component. - */ -#if configQUEUE_REGISTRY_SIZE > 0 - - /* The type stored within the queue registry array. This allows a name - to be assigned to each queue making kernel aware debugging a little - more user friendly. */ - typedef struct QUEUE_REGISTRY_ITEM - { - signed char *pcQueueName; - xQueueHandle xHandle; - } xQueueRegistryItem; - - /* The queue registry is simply an array of xQueueRegistryItem structures. - The pcQueueName member of a structure being NULL is indicative of the - array position being vacant. */ - xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; - - /* Removes a queue from the registry by simply setting the pcQueueName - member to NULL. */ - static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; -#endif - -/* - * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not - * prevent an ISR from adding or removing items to the queue, but does prevent - * an ISR from removing tasks from the queue event lists. If an ISR finds a - * queue is locked it will instead increment the appropriate queue lock count - * to indicate that a task may require unblocking. When the queue in unlocked - * these lock counts are inspected, and the appropriate action taken. - */ -static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any data in a queue. - * - * @return pdTRUE if the queue contains no items, otherwise pdFALSE. - */ -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any space in a queue. - * - * @return pdTRUE if there is no space, otherwise pdFALSE; - */ -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Copies an item into the queue, either at the front of the queue or the - * back of the queue. - */ -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; - -/* - * Copies an item out of a queue. - */ -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; -/*-----------------------------------------------------------*/ - -/* - * Macro to mark a queue as locked. Locking a queue prevents an ISR from - * accessing the queue event lists. - */ -#define prvLockQueue( pxQueue ) \ - taskENTER_CRITICAL(); \ - { \ - if( ( pxQueue )->xRxLock == queueUNLOCKED ) \ - { \ - ( pxQueue )->xRxLock = queueLOCKED_UNMODIFIED; \ - } \ - if( ( pxQueue )->xTxLock == queueUNLOCKED ) \ - { \ - ( pxQueue )->xTxLock = queueLOCKED_UNMODIFIED; \ - } \ - } \ - taskEXIT_CRITICAL() -/*-----------------------------------------------------------*/ - - -/*----------------------------------------------------------- - * PUBLIC QUEUE MANAGEMENT API documented in queue.h - *----------------------------------------------------------*/ - -portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ) -{ - configASSERT( pxQueue ); - - taskENTER_CRITICAL(); - { - pxQueue->pcTail = pxQueue->pcHead + ( pxQueue->uxLength * pxQueue->uxItemSize ); - pxQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; - pxQueue->pcWriteTo = pxQueue->pcHead; - pxQueue->pcReadFrom = pxQueue->pcHead + ( ( pxQueue->uxLength - ( unsigned portBASE_TYPE ) 1U ) * pxQueue->uxItemSize ); - pxQueue->xRxLock = queueUNLOCKED; - pxQueue->xTxLock = queueUNLOCKED; - - if( xNewQueue == pdFALSE ) - { - /* If there are tasks blocked waiting to read from the queue, then - the tasks will remain blocked as after this function exits the queue - will still be empty. If there are tasks blocked waiting to write to - the queue, then one should be unblocked as after this function exits - it will be possible to write to it. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - /* Ensure the event queues start in the correct state. */ - vListInitialise( &( pxQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxQueue->xTasksWaitingToReceive ) ); - } - } - taskEXIT_CRITICAL(); - - /* A value is returned for calling semantic consistency with previous - versions. */ - return pdPASS; -} -/*-----------------------------------------------------------*/ - -xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ) -{ -xQUEUE *pxNewQueue; -size_t xQueueSizeInBytes; -xQueueHandle xReturn = NULL; - - /* Remove compiler warnings about unused parameters should - configUSE_TRACE_FACILITY not be set to 1. */ - ( void ) ucQueueType; - - /* Allocate the new queue structure. */ - if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) - { - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Create the list of pointers to queue items. The queue is one byte - longer than asked for to make wrap checking easier/faster. */ - xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; - - pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); - if( pxNewQueue->pcHead != NULL ) - { - /* Initialise the queue members as described above where the - queue type is defined. */ - pxNewQueue->uxLength = uxQueueLength; - pxNewQueue->uxItemSize = uxItemSize; - xQueueGenericReset( pxNewQueue, pdTRUE ); - #if ( configUSE_TRACE_FACILITY == 1 ) - { - pxNewQueue->ucQueueType = ucQueueType; - } - #endif /* configUSE_TRACE_FACILITY */ - - traceQUEUE_CREATE( pxNewQueue ); - xReturn = pxNewQueue; - } - else - { - traceQUEUE_CREATE_FAILED( ucQueueType ); - vPortFree( pxNewQueue ); - } - } - } - - configASSERT( xReturn ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ) - { - xQUEUE *pxNewQueue; - - /* Prevent compiler warnings about unused parameters if - configUSE_TRACE_FACILITY does not equal 1. */ - ( void ) ucQueueType; - - /* Allocate the new queue structure. */ - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Information required for priority inheritance. */ - pxNewQueue->pxMutexHolder = NULL; - pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; - - /* Queues used as a mutex no data is actually copied into or out - of the queue. */ - pxNewQueue->pcWriteTo = NULL; - pxNewQueue->pcReadFrom = NULL; - - /* Each mutex has a length of 1 (like a binary semaphore) and - an item size of 0 as nothing is actually copied into or out - of the mutex. */ - pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->uxLength = ( unsigned portBASE_TYPE ) 1U; - pxNewQueue->uxItemSize = ( unsigned portBASE_TYPE ) 0U; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - #if ( configUSE_TRACE_FACILITY == 1 ) - { - pxNewQueue->ucQueueType = ucQueueType; - } - #endif - - /* Ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); - - traceCREATE_MUTEX( pxNewQueue ); - - /* Start with the semaphore in the expected state. */ - xQueueGenericSend( pxNewQueue, NULL, ( portTickType ) 0U, queueSEND_TO_BACK ); - } - else - { - traceCREATE_MUTEX_FAILED(); - } - - configASSERT( pxNewQueue ); - return pxNewQueue; - } - -#endif /* configUSE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xQueueGetMutexHolder == 1 ) ) - - void* xQueueGetMutexHolder( xQueueHandle xSemaphore ) - { - void *pxReturn; - - /* This function is called by xSemaphoreGetMutexHolder(), and should not - be called directly. Note: This is is a good way of determining if the - calling task is the mutex holder, but not a good way of determining the - identity of the mutex holder, as the holder may change between the - following critical section exiting and the function returning. */ - taskENTER_CRITICAL(); - { - if( xSemaphore->uxQueueType == queueQUEUE_IS_MUTEX ) - { - pxReturn = ( void * ) xSemaphore->pxMutexHolder; - } - else - { - pxReturn = NULL; - } - } - taskEXIT_CRITICAL(); - - return pxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_RECURSIVE_MUTEXES == 1 ) - - portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) - { - portBASE_TYPE xReturn; - - configASSERT( pxMutex ); - - /* If this is the task that holds the mutex then pxMutexHolder will not - change outside of this task. If this task does not hold the mutex then - pxMutexHolder can never coincidentally equal the tasks handle, and as - this is the only condition we are interested in it does not matter if - pxMutexHolder is accessed simultaneously by another task. Therefore no - mutual exclusion is required to test the pxMutexHolder variable. */ - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - traceGIVE_MUTEX_RECURSIVE( pxMutex ); - - /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to - the task handle, therefore no underflow check is required. Also, - uxRecursiveCallCount is only modified by the mutex holder, and as - there can only be one, no mutual exclusion is required to modify the - uxRecursiveCallCount member. */ - ( pxMutex->uxRecursiveCallCount )--; - - /* Have we unwound the call count? */ - if( pxMutex->uxRecursiveCallCount == 0 ) - { - /* Return the mutex. This will automatically unblock any other - task that might be waiting to access the mutex. */ - xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); - } - - xReturn = pdPASS; - } - else - { - /* We cannot give the mutex because we are not the holder. */ - xReturn = pdFAIL; - - traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_RECURSIVE_MUTEXES == 1 - - portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) - { - portBASE_TYPE xReturn; - - configASSERT( pxMutex ); - - /* Comments regarding mutual exclusion as per those within - xQueueGiveMutexRecursive(). */ - - traceTAKE_MUTEX_RECURSIVE( pxMutex ); - - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - ( pxMutex->uxRecursiveCallCount )++; - xReturn = pdPASS; - } - else - { - xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); - - /* pdPASS will only be returned if we successfully obtained the mutex, - we may have blocked to reach here. */ - if( xReturn == pdPASS ) - { - ( pxMutex->uxRecursiveCallCount )++; - } - else - { - traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ); - } - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_COUNTING_SEMAPHORES == 1 - - xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) - { - xQueueHandle pxHandle; - - pxHandle = xQueueGenericCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_COUNTING_SEMAPHORE ); - - if( pxHandle != NULL ) - { - pxHandle->uxMessagesWaiting = uxInitialCount; - - traceCREATE_COUNTING_SEMAPHORE(); - } - else - { - traceCREATE_COUNTING_SEMAPHORE_FAILED(); - } - - configASSERT( pxHandle ); - return pxHandle; - } - -#endif /* configUSE_COUNTING_SEMAPHORES */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; - - configASSERT( pxQueue ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. Yes it is ok to do - this from within the critical section - the kernel - takes care of that. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting the - function. */ - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was full and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting - the function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was full and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - - /* Unlocking the queue means queue events can effect the - event list. It is possible that interrupts occurring now - remove this task from the event list again - but as the - scheduler is suspended the task will go onto the pending - ready last instead of the actual ready list. */ - prvUnlockQueue( pxQueue ); - - /* Resuming the scheduler will move tasks from the pending - ready list into the ready list - so it is feasible that this - task is already in a ready list before it yields - in which - case the yield will not cause a context switch unless there - is also a higher priority task in the pending ready list. */ - if( xTaskResumeAll() == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - /* The timeout has expired. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - - /* Return to the original privilege level before exiting the - function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } -} -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - - configASSERT( pxQueue ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } - taskEXIT_CRITICAL(); - } - } - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - signed char *pcOriginalReadPosition; - - configASSERT( pxQueue ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - for( ;; ) - { - taskENTER_CRITICAL(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } - taskEXIT_CRITICAL(); - } - } - - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - configASSERT( pxQueue ); - configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* Similar to xQueueGenericSend, except we don't block if there is no room - in the queue. Also we don't directly wake a task that was blocked on a - queue read, instead we return a flag to say whether a context switch is - required or not (i.e. has a task with a higher priority than us been woken - by this post). */ - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND_FROM_ISR( pxQueue ); - - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If the queue is locked we do not alter the event list. This will - be done when the queue is unlocked later. */ - if( pxQueue->xTxLock == queueUNLOCKED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - if( pxHigherPriorityTaskWoken != NULL ) - { - *pxHigherPriorityTaskWoken = pdTRUE; - } - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was posted while it was locked. */ - ++( pxQueue->xTxLock ); - } - - xReturn = pdPASS; - } - else - { - traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); - xReturn = errQUEUE_FULL; - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; -signed char *pcOriginalReadPosition; - - configASSERT( pxQueue ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there data in the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was empty and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was empty and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - { - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - } - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - prvUnlockQueue( pxQueue ); - if( xTaskResumeAll() == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - configASSERT( pxQueue ); - configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - /* We cannot block from an ISR, so check there is data available. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - --( pxQueue->uxMessagesWaiting ); - - /* If the queue is locked we will not modify the event list. Instead - we update the lock count so the task that unlocks the queue will know - that an ISR has removed data while the queue was locked. */ - if( pxQueue->xRxLock == queueUNLOCKED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than us so - force a context switch. */ - if( pxHigherPriorityTaskWoken != NULL ) - { - *pxHigherPriorityTaskWoken = pdTRUE; - } - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was removed while it was locked. */ - ++( pxQueue->xRxLock ); - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - configASSERT( pxQueue ); - - taskENTER_CRITICAL(); - uxReturn = pxQueue->uxMessagesWaiting; - taskEXIT_CRITICAL(); - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - configASSERT( pxQueue ); - - uxReturn = pxQueue->uxMessagesWaiting; - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -void vQueueDelete( xQueueHandle pxQueue ) -{ - configASSERT( pxQueue ); - - traceQUEUE_DELETE( pxQueue ); - vQueueUnregisterQueue( pxQueue ); - vPortFree( pxQueue->pcHead ); - vPortFree( pxQueue ); -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned char ucQueueGetQueueNumber( xQueueHandle pxQueue ) - { - return pxQueue->ucQueueNumber; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vQueueSetQueueNumber( xQueueHandle pxQueue, unsigned char ucQueueNumber ) - { - pxQueue->ucQueueNumber = ucQueueNumber; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - unsigned char ucQueueGetQueueType( xQueueHandle pxQueue ) - { - return pxQueue->ucQueueType; - } - -#endif -/*-----------------------------------------------------------*/ - -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) -{ - if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) - { - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* The mutex is no longer being held. */ - vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); - pxQueue->pxMutexHolder = NULL; - } - } - #endif - } - else if( xPosition == queueSEND_TO_BACK ) - { - memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcWriteTo += pxQueue->uxItemSize; - if( pxQueue->pcWriteTo >= pxQueue->pcTail ) - { - pxQueue->pcWriteTo = pxQueue->pcHead; - } - } - else - { - memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcReadFrom -= pxQueue->uxItemSize; - if( pxQueue->pcReadFrom < pxQueue->pcHead ) - { - pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); - } - } - - ++( pxQueue->uxMessagesWaiting ); -} -/*-----------------------------------------------------------*/ - -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) -{ - if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) - { - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - } -} -/*-----------------------------------------------------------*/ - -static void prvUnlockQueue( xQueueHandle pxQueue ) -{ - /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ - - /* The lock counts contains the number of extra data items placed or - removed from the queue while the queue was locked. When a queue is - locked items can be added or removed, but the event lists cannot be - updated. */ - taskENTER_CRITICAL(); - { - /* See if data was added to the queue while it was locked. */ - while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) - { - /* Data was posted while the queue was locked. Are any tasks - blocked waiting for data to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - vTaskMissedYield(); - } - - --( pxQueue->xTxLock ); - } - else - { - break; - } - } - - pxQueue->xTxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); - - /* Do the same for the Rx lock. */ - taskENTER_CRITICAL(); - { - while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - vTaskMissedYield(); - } - - --( pxQueue->xRxLock ); - } - else - { - break; - } - } - - pxQueue->xRxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - configASSERT( pxQueue ); - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - configASSERT( pxQueue ); - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already full we may have to block. A critical section - is required to prevent an interrupt removing something from the queue - between the check to see if the queue is full and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( prvIsQueueFull( pxQueue ) != pdFALSE ) - { - /* The queue is full - do we want to block or just leave without - posting? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is called from a coroutine we cannot block directly, but - return indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - /* There is room in the queue, copy the data into the queue. */ - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - xReturn = pdPASS; - - /* Were any co-routines waiting for data to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The co-routine waiting has a higher priority so record - that a yield might be appropriate. */ - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = errQUEUE_FULL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already empty we may have to block. A critical section - is required to prevent an interrupt adding something to the queue - between the check to see if the queue is empty and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) - { - /* There are no messages in the queue, do we want to block or just - leave with nothing? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is a co-routine we cannot block directly, but return - indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Data is available from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - xReturn = pdPASS; - - /* Were any co-routines waiting for space to become available? */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = pdFAIL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - - - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) -{ - /* Cannot block within an ISR so if there is no space on the queue then - exit without doing anything. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - - /* We only want to wake one co-routine per ISR, so check that a - co-routine has not already been woken. */ - if( xCoRoutinePreviouslyWoken == pdFALSE ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - return pdTRUE; - } - } - } - } - - return xCoRoutinePreviouslyWoken; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) -{ -signed portBASE_TYPE xReturn; - - /* We cannot block from an ISR, so check there is data available. If - not then just leave without doing anything. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Copy the data from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - if( ( *pxCoRoutineWoken ) == pdFALSE ) - { - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - *pxCoRoutineWoken = pdTRUE; - } - } - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - } - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) - { - unsigned portBASE_TYPE ux; - - /* See if there is an empty space in the registry. A NULL name denotes - a free slot. */ - for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].pcQueueName == NULL ) - { - /* Store the information on this queue. */ - xQueueRegistry[ ux ].pcQueueName = pcQueueName; - xQueueRegistry[ ux ].xHandle = xQueue; - break; - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - static void vQueueUnregisterQueue( xQueueHandle xQueue ) - { - unsigned portBASE_TYPE ux; - - /* See if the handle of the queue being unregistered in actually in the - registry. */ - for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].xHandle == xQueue ) - { - /* Set the name to NULL to show that this slot if free again. */ - xQueueRegistry[ ux ].pcQueueName = NULL; - break; - } - } - - } - -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_TIMERS == 1 - - void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) - { - /* This function should not be called by application code hence the - 'Restricted' in its name. It is not part of the public API. It is - designed for use by kernel code, and has special calling requirements. - It can result in vListInsert() being called on a list that can only - possibly ever have one item in it, so the list will be fast, but even - so it should be called with the scheduler locked and not from a critical - section. */ - - /* Only do anything if there are no messages in the queue. This function - will not actually cause the task to block, just place it on a blocked - list. It will not block until the scheduler is unlocked - at which - time a yield will be performed. If an item is added to the queue while - the queue is locked, and the calling task blocks on the queue, then the - calling task will be immediately unblocked when the queue is unlocked. */ - prvLockQueue( pxQueue ); - if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0U ) - { - /* There is nothing in the queue, block for the specified period. */ - vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - } - prvUnlockQueue( pxQueue ); - } - -#endif - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#if ( configUSE_CO_ROUTINES == 1 ) + #include "croutine.h" +#endif + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +/* Constants used with the cRxLock and xTxLock structure members. */ +#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) +#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) + +#define queueERRONEOUS_UNBLOCK ( -1 ) + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + +/* Effectively make a union out of the xQUEUE structure. */ +#define pxMutexHolder pcTail +#define uxQueueType pcHead +#define uxRecursiveCallCount pcReadFrom +#define queueQUEUE_IS_MUTEX NULL + +/* Semaphores do not actually store or copy data, so have an items size of +zero. */ +#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned portBASE_TYPE ) 0 ) +#define queueDONT_BLOCK ( ( portTickType ) 0U ) +#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0U ) + +/* These definitions *must* match those in queue.h. */ +#define queueQUEUE_TYPE_BASE ( 0U ) +#define queueQUEUE_TYPE_MUTEX ( 1U ) +#define queueQUEUE_TYPE_COUNTING_SEMAPHORE ( 2U ) +#define queueQUEUE_TYPE_BINARY_SEMAPHORE ( 3U ) +#define queueQUEUE_TYPE_RECURSIVE_MUTEX ( 4U ) + +/* + * Definition of the queue used by the scheduler. + * Items are queued by copy, not reference. + */ +typedef struct QueueDefinition +{ + signed char *pcHead; /*< Points to the beginning of the queue storage area. */ + signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ + + signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ + signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ + + xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ + xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ + + volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ + unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ + unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ + + volatile signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + volatile signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + + #if ( configUSE_TRACE_FACILITY == 1 ) + unsigned char ucQueueNumber; + unsigned char ucQueueType; + #endif + +} xQUEUE; +/*-----------------------------------------------------------*/ + +/* + * Inside this file xQueueHandle is a pointer to a xQUEUE structure. + * To keep the definition private the API header file defines it as a + * pointer to void. + */ +typedef xQUEUE * xQueueHandle; + +/* + * Prototypes for public functions are included here so we don't have to + * include the API header file (as it defines xQueueHandle differently). These + * functions are documented in the API header file. + */ +xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; +unsigned char ucQueueGetQueueNumber( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueSetQueueNumber( xQueueHandle pxQueue, unsigned char ucQueueNumber ) PRIVILEGED_FUNCTION; +unsigned char ucQueueGetQueueType( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ) PRIVILEGED_FUNCTION; +xTaskHandle xQueueGetMutexHolder( xQueueHandle xSemaphore ) PRIVILEGED_FUNCTION; + +/* + * Co-routine queue functions differ from task queue functions. Co-routines are + * an optional component. + */ +#if configUSE_CO_ROUTINES == 1 + signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; +#endif + +/* + * The queue registry is just a means for kernel aware debuggers to locate + * queue structures. It has no other purpose so is an optional component. + */ +#if configQUEUE_REGISTRY_SIZE > 0 + + /* The type stored within the queue registry array. This allows a name + to be assigned to each queue making kernel aware debugging a little + more user friendly. */ + typedef struct QUEUE_REGISTRY_ITEM + { + signed char *pcQueueName; + xQueueHandle xHandle; + } xQueueRegistryItem; + + /* The queue registry is simply an array of xQueueRegistryItem structures. + The pcQueueName member of a structure being NULL is indicative of the + array position being vacant. */ + xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; + + /* Removes a queue from the registry by simply setting the pcQueueName + member to NULL. */ + static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; +#endif + +/* + * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not + * prevent an ISR from adding or removing items to the queue, but does prevent + * an ISR from removing tasks from the queue event lists. If an ISR finds a + * queue is locked it will instead increment the appropriate queue lock count + * to indicate that a task may require unblocking. When the queue in unlocked + * these lock counts are inspected, and the appropriate action taken. + */ +static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any data in a queue. + * + * @return pdTRUE if the queue contains no items, otherwise pdFALSE. + */ +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any space in a queue. + * + * @return pdTRUE if there is no space, otherwise pdFALSE; + */ +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Copies an item into the queue, either at the front of the queue or the + * back of the queue. + */ +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; + +/* + * Copies an item out of a queue. + */ +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; +/*-----------------------------------------------------------*/ + +/* + * Macro to mark a queue as locked. Locking a queue prevents an ISR from + * accessing the queue event lists. + */ +#define prvLockQueue( pxQueue ) \ + taskENTER_CRITICAL(); \ + { \ + if( ( pxQueue )->xRxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->xRxLock = queueLOCKED_UNMODIFIED; \ + } \ + if( ( pxQueue )->xTxLock == queueUNLOCKED ) \ + { \ + ( pxQueue )->xTxLock = queueLOCKED_UNMODIFIED; \ + } \ + } \ + taskEXIT_CRITICAL() +/*-----------------------------------------------------------*/ + + +/*----------------------------------------------------------- + * PUBLIC QUEUE MANAGEMENT API documented in queue.h + *----------------------------------------------------------*/ + +portBASE_TYPE xQueueGenericReset( xQueueHandle pxQueue, portBASE_TYPE xNewQueue ) +{ + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + { + pxQueue->pcTail = pxQueue->pcHead + ( pxQueue->uxLength * pxQueue->uxItemSize ); + pxQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; + pxQueue->pcWriteTo = pxQueue->pcHead; + pxQueue->pcReadFrom = pxQueue->pcHead + ( ( pxQueue->uxLength - ( unsigned portBASE_TYPE ) 1U ) * pxQueue->uxItemSize ); + pxQueue->xRxLock = queueUNLOCKED; + pxQueue->xTxLock = queueUNLOCKED; + + if( xNewQueue == pdFALSE ) + { + /* If there are tasks blocked waiting to read from the queue, then + the tasks will remain blocked as after this function exits the queue + will still be empty. If there are tasks blocked waiting to write to + the queue, then one should be unblocked as after this function exits + it will be possible to write to it. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + /* Ensure the event queues start in the correct state. */ + vListInitialise( &( pxQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxQueue->xTasksWaitingToReceive ) ); + } + } + taskEXIT_CRITICAL(); + + /* A value is returned for calling semantic consistency with previous + versions. */ + return pdPASS; +} +/*-----------------------------------------------------------*/ + +xQueueHandle xQueueGenericCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize, unsigned char ucQueueType ) +{ +xQUEUE *pxNewQueue; +size_t xQueueSizeInBytes; +xQueueHandle xReturn = NULL; + + /* Remove compiler warnings about unused parameters should + configUSE_TRACE_FACILITY not be set to 1. */ + ( void ) ucQueueType; + + /* Allocate the new queue structure. */ + if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) + { + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Create the list of pointers to queue items. The queue is one byte + longer than asked for to make wrap checking easier/faster. */ + xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; + + pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); + if( pxNewQueue->pcHead != NULL ) + { + /* Initialise the queue members as described above where the + queue type is defined. */ + pxNewQueue->uxLength = uxQueueLength; + pxNewQueue->uxItemSize = uxItemSize; + xQueueGenericReset( pxNewQueue, pdTRUE ); + #if ( configUSE_TRACE_FACILITY == 1 ) + { + pxNewQueue->ucQueueType = ucQueueType; + } + #endif /* configUSE_TRACE_FACILITY */ + + traceQUEUE_CREATE( pxNewQueue ); + xReturn = pxNewQueue; + } + else + { + traceQUEUE_CREATE_FAILED( ucQueueType ); + vPortFree( pxNewQueue ); + } + } + } + + configASSERT( xReturn ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + xQueueHandle xQueueCreateMutex( unsigned char ucQueueType ) + { + xQUEUE *pxNewQueue; + + /* Prevent compiler warnings about unused parameters if + configUSE_TRACE_FACILITY does not equal 1. */ + ( void ) ucQueueType; + + /* Allocate the new queue structure. */ + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Information required for priority inheritance. */ + pxNewQueue->pxMutexHolder = NULL; + pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; + + /* Queues used as a mutex no data is actually copied into or out + of the queue. */ + pxNewQueue->pcWriteTo = NULL; + pxNewQueue->pcReadFrom = NULL; + + /* Each mutex has a length of 1 (like a binary semaphore) and + an item size of 0 as nothing is actually copied into or out + of the mutex. */ + pxNewQueue->uxMessagesWaiting = ( unsigned portBASE_TYPE ) 0U; + pxNewQueue->uxLength = ( unsigned portBASE_TYPE ) 1U; + pxNewQueue->uxItemSize = ( unsigned portBASE_TYPE ) 0U; + pxNewQueue->xRxLock = queueUNLOCKED; + pxNewQueue->xTxLock = queueUNLOCKED; + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + pxNewQueue->ucQueueType = ucQueueType; + } + #endif + + /* Ensure the event queues start with the correct state. */ + vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + + traceCREATE_MUTEX( pxNewQueue ); + + /* Start with the semaphore in the expected state. */ + xQueueGenericSend( pxNewQueue, NULL, ( portTickType ) 0U, queueSEND_TO_BACK ); + } + else + { + traceCREATE_MUTEX_FAILED(); + } + + configASSERT( pxNewQueue ); + return pxNewQueue; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_MUTEXES == 1 ) && ( INCLUDE_xQueueGetMutexHolder == 1 ) ) + + void* xQueueGetMutexHolder( xQueueHandle xSemaphore ) + { + void *pxReturn; + + /* This function is called by xSemaphoreGetMutexHolder(), and should not + be called directly. Note: This is is a good way of determining if the + calling task is the mutex holder, but not a good way of determining the + identity of the mutex holder, as the holder may change between the + following critical section exiting and the function returning. */ + taskENTER_CRITICAL(); + { + if( xSemaphore->uxQueueType == queueQUEUE_IS_MUTEX ) + { + pxReturn = ( void * ) xSemaphore->pxMutexHolder; + } + else + { + pxReturn = NULL; + } + } + taskEXIT_CRITICAL(); + + return pxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_RECURSIVE_MUTEXES == 1 ) + + portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) + { + portBASE_TYPE xReturn; + + configASSERT( pxMutex ); + + /* If this is the task that holds the mutex then pxMutexHolder will not + change outside of this task. If this task does not hold the mutex then + pxMutexHolder can never coincidentally equal the tasks handle, and as + this is the only condition we are interested in it does not matter if + pxMutexHolder is accessed simultaneously by another task. Therefore no + mutual exclusion is required to test the pxMutexHolder variable. */ + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + traceGIVE_MUTEX_RECURSIVE( pxMutex ); + + /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to + the task handle, therefore no underflow check is required. Also, + uxRecursiveCallCount is only modified by the mutex holder, and as + there can only be one, no mutual exclusion is required to modify the + uxRecursiveCallCount member. */ + ( pxMutex->uxRecursiveCallCount )--; + + /* Have we unwound the call count? */ + if( pxMutex->uxRecursiveCallCount == 0 ) + { + /* Return the mutex. This will automatically unblock any other + task that might be waiting to access the mutex. */ + xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); + } + + xReturn = pdPASS; + } + else + { + /* We cannot give the mutex because we are not the holder. */ + xReturn = pdFAIL; + + traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_RECURSIVE_MUTEXES == 1 + + portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) + { + portBASE_TYPE xReturn; + + configASSERT( pxMutex ); + + /* Comments regarding mutual exclusion as per those within + xQueueGiveMutexRecursive(). */ + + traceTAKE_MUTEX_RECURSIVE( pxMutex ); + + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + ( pxMutex->uxRecursiveCallCount )++; + xReturn = pdPASS; + } + else + { + xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); + + /* pdPASS will only be returned if we successfully obtained the mutex, + we may have blocked to reach here. */ + if( xReturn == pdPASS ) + { + ( pxMutex->uxRecursiveCallCount )++; + } + else + { + traceTAKE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_COUNTING_SEMAPHORES == 1 + + xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) + { + xQueueHandle pxHandle; + + pxHandle = xQueueGenericCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH, queueQUEUE_TYPE_COUNTING_SEMAPHORE ); + + if( pxHandle != NULL ) + { + pxHandle->uxMessagesWaiting = uxInitialCount; + + traceCREATE_COUNTING_SEMAPHORE(); + } + else + { + traceCREATE_COUNTING_SEMAPHORE_FAILED(); + } + + configASSERT( pxHandle ); + return pxHandle; + } + +#endif /* configUSE_COUNTING_SEMAPHORES */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. Yes it is ok to do + this from within the critical section - the kernel + takes care of that. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting the + function. */ + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was full and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting + the function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was full and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + + /* Unlocking the queue means queue events can effect the + event list. It is possible that interrupts occurring now + remove this task from the event list again - but as the + scheduler is suspended the task will go onto the pending + ready last instead of the actual ready list. */ + prvUnlockQueue( pxQueue ); + + /* Resuming the scheduler will move tasks from the pending + ready list into the ready list - so it is feasible that this + task is already in a ready list before it yields - in which + case the yield will not cause a context switch unless there + is also a higher priority task in the pending ready list. */ + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* The timeout has expired. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + /* Return to the original privilege level before exiting the + function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } +} +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } + taskEXIT_CRITICAL(); + } + } + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + signed char *pcOriginalReadPosition; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + for( ;; ) + { + taskENTER_CRITICAL(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } + taskEXIT_CRITICAL(); + } + } + + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + configASSERT( pxQueue ); + configASSERT( !( ( pvItemToQueue == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* Similar to xQueueGenericSend, except we don't block if there is no room + in the queue. Also we don't directly wake a task that was blocked on a + queue read, instead we return a flag to say whether a context switch is + required or not (i.e. has a task with a higher priority than us been woken + by this post). */ + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND_FROM_ISR( pxQueue ); + + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If the queue is locked we do not alter the event list. This will + be done when the queue is unlocked later. */ + if( pxQueue->xTxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was posted while it was locked. */ + ++( pxQueue->xTxLock ); + } + + xReturn = pdPASS; + } + else + { + traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); + xReturn = errQUEUE_FULL; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; +signed char *pcOriginalReadPosition; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there data in the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was empty and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was empty and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) != pdFALSE ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + { + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + } + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( xTaskResumeAll() == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxHigherPriorityTaskWoken ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + configASSERT( pxQueue ); + configASSERT( !( ( pvBuffer == NULL ) && ( pxQueue->uxItemSize != ( unsigned portBASE_TYPE ) 0U ) ) ); + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* We cannot block from an ISR, so check there is data available. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + --( pxQueue->uxMessagesWaiting ); + + /* If the queue is locked we will not modify the event list. Instead + we update the lock count so the task that unlocks the queue will know + that an ISR has removed data while the queue was locked. */ + if( pxQueue->xRxLock == queueUNLOCKED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than us so + force a context switch. */ + if( pxHigherPriorityTaskWoken != NULL ) + { + *pxHigherPriorityTaskWoken = pdTRUE; + } + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was removed while it was locked. */ + ++( pxQueue->xRxLock ); + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + configASSERT( pxQueue ); + + taskENTER_CRITICAL(); + uxReturn = pxQueue->uxMessagesWaiting; + taskEXIT_CRITICAL(); + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + configASSERT( pxQueue ); + + uxReturn = pxQueue->uxMessagesWaiting; + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +void vQueueDelete( xQueueHandle pxQueue ) +{ + configASSERT( pxQueue ); + + traceQUEUE_DELETE( pxQueue ); + vQueueUnregisterQueue( pxQueue ); + vPortFree( pxQueue->pcHead ); + vPortFree( pxQueue ); +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + unsigned char ucQueueGetQueueNumber( xQueueHandle pxQueue ) + { + return pxQueue->ucQueueNumber; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vQueueSetQueueNumber( xQueueHandle pxQueue, unsigned char ucQueueNumber ) + { + pxQueue->ucQueueNumber = ucQueueNumber; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + unsigned char ucQueueGetQueueType( xQueueHandle pxQueue ) + { + return pxQueue->ucQueueType; + } + +#endif +/*-----------------------------------------------------------*/ + +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) +{ + if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) + { + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* The mutex is no longer being held. */ + vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); + pxQueue->pxMutexHolder = NULL; + } + } + #endif + } + else if( xPosition == queueSEND_TO_BACK ) + { + memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcWriteTo += pxQueue->uxItemSize; + if( pxQueue->pcWriteTo >= pxQueue->pcTail ) + { + pxQueue->pcWriteTo = pxQueue->pcHead; + } + } + else + { + memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcReadFrom -= pxQueue->uxItemSize; + if( pxQueue->pcReadFrom < pxQueue->pcHead ) + { + pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); + } + } + + ++( pxQueue->uxMessagesWaiting ); +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) +{ + if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) + { + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + } +} +/*-----------------------------------------------------------*/ + +static void prvUnlockQueue( xQueueHandle pxQueue ) +{ + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ + + /* The lock counts contains the number of extra data items placed or + removed from the queue while the queue was locked. When a queue is + locked items can be added or removed, but the event lists cannot be + updated. */ + taskENTER_CRITICAL(); + { + /* See if data was added to the queue while it was locked. */ + while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) + { + /* Data was posted while the queue was locked. Are any tasks + blocked waiting for data to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + vTaskMissedYield(); + } + + --( pxQueue->xTxLock ); + } + else + { + break; + } + } + + pxQueue->xTxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); + + /* Do the same for the Rx lock. */ + taskENTER_CRITICAL(); + { + while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + vTaskMissedYield(); + } + + --( pxQueue->xRxLock ); + } + else + { + break; + } + } + + pxQueue->xRxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + configASSERT( pxQueue ); + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + configASSERT( pxQueue ); + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already full we may have to block. A critical section + is required to prevent an interrupt removing something from the queue + between the check to see if the queue is full and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( prvIsQueueFull( pxQueue ) != pdFALSE ) + { + /* The queue is full - do we want to block or just leave without + posting? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is called from a coroutine we cannot block directly, but + return indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + /* There is room in the queue, copy the data into the queue. */ + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + xReturn = pdPASS; + + /* Were any co-routines waiting for data to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The co-routine waiting has a higher priority so record + that a yield might be appropriate. */ + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = errQUEUE_FULL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already empty we may have to block. A critical section + is required to prevent an interrupt adding something to the queue + between the check to see if the queue is empty and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) + { + /* There are no messages in the queue, do we want to block or just + leave with nothing? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is a co-routine we cannot block directly, but return + indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Data is available from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + xReturn = pdPASS; + + /* Were any co-routines waiting for space to become available? */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = pdFAIL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + + + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) +{ + /* Cannot block within an ISR so if there is no space on the queue then + exit without doing anything. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + + /* We only want to wake one co-routine per ISR, so check that a + co-routine has not already been woken. */ + if( xCoRoutinePreviouslyWoken == pdFALSE ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + return pdTRUE; + } + } + } + } + + return xCoRoutinePreviouslyWoken; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) +{ +signed portBASE_TYPE xReturn; + + /* We cannot block from an ISR, so check there is data available. If + not then just leave without doing anything. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Copy the data from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + if( ( *pxCoRoutineWoken ) == pdFALSE ) + { + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + *pxCoRoutineWoken = pdTRUE; + } + } + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) + { + unsigned portBASE_TYPE ux; + + /* See if there is an empty space in the registry. A NULL name denotes + a free slot. */ + for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].pcQueueName == NULL ) + { + /* Store the information on this queue. */ + xQueueRegistry[ ux ].pcQueueName = pcQueueName; + xQueueRegistry[ ux ].xHandle = xQueue; + break; + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + static void vQueueUnregisterQueue( xQueueHandle xQueue ) + { + unsigned portBASE_TYPE ux; + + /* See if the handle of the queue being unregistered in actually in the + registry. */ + for( ux = ( unsigned portBASE_TYPE ) 0U; ux < ( unsigned portBASE_TYPE ) configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].xHandle == xQueue ) + { + /* Set the name to NULL to show that this slot if free again. */ + xQueueRegistry[ ux ].pcQueueName = NULL; + break; + } + } + + } + +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_TIMERS == 1 + + void vQueueWaitForMessageRestricted( xQueueHandle pxQueue, portTickType xTicksToWait ) + { + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements. + It can result in vListInsert() being called on a list that can only + possibly ever have one item in it, so the list will be fast, but even + so it should be called with the scheduler locked and not from a critical + section. */ + + /* Only do anything if there are no messages in the queue. This function + will not actually cause the task to block, just place it on a blocked + list. It will not block until the scheduler is unlocked - at which + time a yield will be performed. If an item is added to the queue while + the queue is locked, and the calling task blocks on the queue, then the + calling task will be immediately unblocked when the queue is unlocked. */ + prvLockQueue( pxQueue ); + if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0U ) + { + /* There is nothing in the queue, block for the specified period. */ + vTaskPlaceOnEventListRestricted( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + } + prvUnlockQueue( pxQueue ); + } + +#endif + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c index 8bc546e0d..265c893cd 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/tasks.c @@ -1,2496 +1,2496 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#include -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "timers.h" -#include "StackMacros.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* - * Macro to define the amount of stack available to the idle task. - */ -#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE - -/* - * Task control block. A task control block (TCB) is allocated to each task, - * and stores the context of the task. - */ -typedef struct tskTaskControlBlock -{ - volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ - - #if ( portUSING_MPU_WRAPPERS == 1 ) - xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ - #endif - - xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ - portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ - signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ - - #if ( portSTACK_GROWTH > 0 ) - portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ - #endif - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - unsigned portBASE_TYPE uxCriticalNesting; - #endif - - #if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTCBNumber; /*< This stores a number that increments each time a TCB is created. It allows debuggers to determine when a task has been deleted and then recreated. */ - unsigned portBASE_TYPE uxTaskNumber; /*< This stores a number specifically for use by third party trace code. */ - #endif - - #if ( configUSE_MUTEXES == 1 ) - unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - pdTASK_HOOK_CODE pxTaskTag; - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ - #endif - -} tskTCB; - - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - -/*lint -e956 */ -PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; - -/* Lists for ready and blocked tasks. --------------------*/ - -PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ -PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ -PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ -PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ - -#if ( INCLUDE_vTaskDelete == 1 ) - - PRIVILEGED_DATA static xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ - PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0U; - -#endif - -#if ( INCLUDE_vTaskSuspend == 1 ) - - PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ - -#endif - -#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) - - PRIVILEGED_DATA static xTaskHandle xIdleTaskHandle = NULL; - -#endif - -/* File private variables. --------------------------------*/ -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0U; -PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0U; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; -PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0U; -PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; -PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; -PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0U; -PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) portMAX_DELAY; - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - PRIVILEGED_DATA static char pcStatsString[ 50 ] ; - PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; - -#endif - -/* Debugging and trace facilities private variables and macros. ------------*/ - -/* - * The value used to fill the stack of a task when the task is created. This - * is used purely for checking the high water mark for tasks. - */ -#define tskSTACK_FILL_BYTE ( 0xa5U ) - -/* - * Macros used by vListTask to indicate which state a task is in. - */ -#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) -#define tskREADY_CHAR ( ( signed char ) 'R' ) -#define tskDELETED_CHAR ( ( signed char ) 'D' ) -#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) - -/*-----------------------------------------------------------*/ - -/* - * Place the task represented by pxTCB into the appropriate ready queue for - * the task. It is inserted at the end of the list. One quirk of this is - * that if the task being inserted is at the same priority as the currently - * executing task, then it will only be rescheduled after the currently - * executing task has been rescheduled. - */ -#define prvAddTaskToReadyQueue( pxTCB ) \ - traceMOVED_TASK_TO_READY_STATE( pxTCB ) \ - if( ( pxTCB )->uxPriority > uxTopReadyPriority ) \ - { \ - uxTopReadyPriority = ( pxTCB )->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xGenericListItem ) ) -/*-----------------------------------------------------------*/ - -/* - * Macro that looks at the list of tasks that are currently delayed to see if - * any require waking. - * - * Tasks are stored in the queue in the order of their wake time - meaning - * once one tasks has been found whose timer has not expired we need not look - * any further down the list. - */ -#define prvCheckDelayedTasks() \ -{ \ -portTickType xItemValue; \ - \ - /* Is the tick count greater than or equal to the wake time of the first \ - task referenced from the delayed tasks list? */ \ - if( xTickCount >= xNextTaskUnblockTime ) \ - { \ - for( ;; ) \ - { \ - if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) \ - { \ - /* The delayed list is empty. Set xNextTaskUnblockTime to the \ - maximum possible value so it is extremely unlikely that the \ - if( xTickCount >= xNextTaskUnblockTime ) test will pass next \ - time through. */ \ - xNextTaskUnblockTime = portMAX_DELAY; \ - break; \ - } \ - else \ - { \ - /* The delayed list is not empty, get the value of the item at \ - the head of the delayed list. This is the time at which the \ - task at the head of the delayed list should be removed from \ - the Blocked state. */ \ - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); \ - xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); \ - \ - if( xTickCount < xItemValue ) \ - { \ - /* It is not time to unblock this item yet, but the item \ - value is the time at which the task at the head of the \ - blocked list should be removed from the Blocked state - \ - so record the item value in xNextTaskUnblockTime. */ \ - xNextTaskUnblockTime = xItemValue; \ - break; \ - } \ - \ - /* It is time to remove the item from the Blocked state. */ \ - vListRemove( &( pxTCB->xGenericListItem ) ); \ - \ - /* Is the task waiting on an event also? */ \ - if( pxTCB->xEventListItem.pvContainer != NULL ) \ - { \ - vListRemove( &( pxTCB->xEventListItem ) ); \ - } \ - prvAddTaskToReadyQueue( pxTCB ); \ - } \ - } \ - } \ -} -/*-----------------------------------------------------------*/ - -/* - * Several functions take an xTaskHandle parameter that can optionally be NULL, - * where NULL is used to indicate that the handle of the currently executing - * task should be used in place of the parameter. This macro simply checks to - * see if the parameter is NULL and returns a pointer to the appropriate TCB. - */ -#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) ( pxHandle ) ) - -/* Callback function prototypes. --------------------------*/ -extern void vApplicationStackOverflowHook( xTaskHandle pxTask, signed char *pcTaskName ); -extern void vApplicationTickHook( void ); - -/* File private functions. --------------------------------*/ - -/* - * Utility to ready a TCB for a given task. Mainly just copies the parameters - * into the TCB structure. - */ -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first task. - */ -static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; - -/* - * The idle task, which as all tasks is implemented as a never ending loop. - * The idle task is automatically created and added to the ready lists upon - * creation of the first user task. - * - * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); - -/* - * Utility to free all memory allocated by the scheduler to hold a TCB, - * including the stack pointed to by the TCB. - * - * This does not free memory allocated by the task itself (i.e. memory - * allocated by calls to pvPortMalloc from within the tasks application code). - */ -#if ( INCLUDE_vTaskDelete == 1 ) - - static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; - -#endif - -/* - * Used only by the idle task. This checks to see if anything has been placed - * in the list of tasks waiting to be deleted. If so the task is cleaned up - * and its TCB deleted. - */ -static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; - -/* - * The currently executing task is entering the Blocked state. Add the task to - * either the current or the overflow delayed task list. - */ -static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) PRIVILEGED_FUNCTION; - -/* - * Allocates memory from the heap for a TCB and associated stack. Checks the - * allocation was successful. - */ -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; - -/* - * Called from vTaskList. vListTasks details all the tasks currently under - * control of the scheduler. The tasks may be in one of a number of lists. - * prvListTaskWithinSingleList accepts a list and details the tasks from - * within just that list. - * - * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM - * NORMAL APPLICATION CODE. - */ -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; - -#endif - -/* - * When a task is created, the stack of the task is filled with a known value. - * This function determines the 'high water mark' of the task stack by - * determining how much of the stack remains at the original preset value. - */ -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; - -#endif - - -/*lint +e956 */ - - - -/*----------------------------------------------------------- - * TASK CREATION API documented in task.h - *----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) -{ -signed portBASE_TYPE xReturn; -tskTCB * pxNewTCB; - - configASSERT( pxTaskCode ); - configASSERT( ( ( uxPriority & ( ~portPRIVILEGE_BIT ) ) < configMAX_PRIORITIES ) ); - - /* Allocate the memory required by the TCB and stack for the new task, - checking that the allocation was successful. */ - pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); - - if( pxNewTCB != NULL ) - { - portSTACK_TYPE *pxTopOfStack; - - #if( portUSING_MPU_WRAPPERS == 1 ) - /* Should the task be created in privileged mode? */ - portBASE_TYPE xRunPrivileged; - if( ( uxPriority & portPRIVILEGE_BIT ) != 0U ) - { - xRunPrivileged = pdTRUE; - } - else - { - xRunPrivileged = pdFALSE; - } - uxPriority &= ~portPRIVILEGE_BIT; - #endif /* portUSING_MPU_WRAPPERS == 1 */ - - /* Calculate the top of stack address. This depends on whether the - stack grows from high memory to low (as per the 80x86) or visa versa. - portSTACK_GROWTH is used to make the result positive or negative as - required by the port. */ - #if( portSTACK_GROWTH < 0 ) - { - pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - ( unsigned short ) 1 ); - pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack ) & ( ( portPOINTER_SIZE_TYPE ) ~portBYTE_ALIGNMENT_MASK ) ); - - /* Check the alignment of the calculated top of stack is correct. */ - configASSERT( ( ( ( unsigned long ) pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - } - #else - { - pxTopOfStack = pxNewTCB->pxStack; - - /* Check the alignment of the stack buffer is correct. */ - configASSERT( ( ( ( unsigned long ) pxNewTCB->pxStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - - /* If we want to use stack checking on architectures that use - a positive stack growth direction then we also need to store the - other extreme of the stack space. */ - pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); - } - #endif - - /* Setup the newly allocated TCB with the initial state of the task. */ - prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); - - /* Initialize the TCB stack to look as if the task was already running, - but had been interrupted by the scheduler. The return address is set - to the start of the task function. Once the stack has been initialised - the top of stack variable is updated. */ - #if( portUSING_MPU_WRAPPERS == 1 ) - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); - } - #else - { - pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); - } - #endif - - /* Check the alignment of the initialised stack. */ - portALIGNMENT_ASSERT_pxCurrentTCB( ( ( ( unsigned long ) pxNewTCB->pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); - - if( ( void * ) pxCreatedTask != NULL ) - { - /* Pass the TCB out - in an anonymous way. The calling function/ - task can use this as a handle to delete the task later if - required.*/ - *pxCreatedTask = ( xTaskHandle ) pxNewTCB; - } - - /* We are going to manipulate the task queues to add this task to a - ready list, so must make sure no interrupts occur. */ - taskENTER_CRITICAL(); - { - uxCurrentNumberOfTasks++; - if( pxCurrentTCB == NULL ) - { - /* There are no other tasks, or all the other tasks are in - the suspended state - make this the current task. */ - pxCurrentTCB = pxNewTCB; - - if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) - { - /* This is the first task to be created so do the preliminary - initialisation required. We will not recover if this call - fails, but we will report the failure. */ - prvInitialiseTaskLists(); - } - } - else - { - /* If the scheduler is not already running, make this task the - current task if it is the highest priority task to be created - so far. */ - if( xSchedulerRunning == pdFALSE ) - { - if( pxCurrentTCB->uxPriority <= uxPriority ) - { - pxCurrentTCB = pxNewTCB; - } - } - } - - /* Remember the top priority to make context switching faster. Use - the priority in pxNewTCB as this has been capped to a valid value. */ - if( pxNewTCB->uxPriority > uxTopUsedPriority ) - { - uxTopUsedPriority = pxNewTCB->uxPriority; - } - - #if ( configUSE_TRACE_FACILITY == 1 ) - { - /* Add a counter into the TCB for tracing only. */ - pxNewTCB->uxTCBNumber = uxTaskNumber; - } - #endif - uxTaskNumber++; - - prvAddTaskToReadyQueue( pxNewTCB ); - - xReturn = pdPASS; - portSETUP_TCB( pxNewTCB ); - traceTASK_CREATE( pxNewTCB ); - } - taskEXIT_CRITICAL(); - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - traceTASK_CREATE_FAILED(); - } - - if( xReturn == pdPASS ) - { - if( xSchedulerRunning != pdFALSE ) - { - /* If the created task is of a higher priority than the current task - then it should run now. */ - if( pxCurrentTCB->uxPriority < uxPriority ) - { - portYIELD_WITHIN_API(); - } - } - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - void vTaskDelete( xTaskHandle pxTaskToDelete ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - deleted. */ - if( pxTaskToDelete == pxCurrentTCB ) - { - pxTaskToDelete = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); - - /* Remove task from the ready list and place in the termination list. - This will stop the task from be scheduled. The idle task will check - the termination list and free up any memory allocated by the - scheduler for the TCB and stack. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer != NULL ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); - - /* Increment the ucTasksDeleted variable so the idle task knows - there is a task that has been deleted and that it should therefore - check the xTasksWaitingTermination list. */ - ++uxTasksDeleted; - - /* Increment the uxTaskNumberVariable also so kernel aware debuggers - can detect that the task lists need re-generating. */ - uxTaskNumber++; - - traceTASK_DELETE( pxTCB ); - } - taskEXIT_CRITICAL(); - - /* Force a reschedule if we have just deleted the current task. */ - if( xSchedulerRunning != pdFALSE ) - { - if( ( void * ) pxTaskToDelete == NULL ) - { - portYIELD_WITHIN_API(); - } - } - } - -#endif - - - - - - -/*----------------------------------------------------------- - * TASK CONTROL API documented in task.h - *----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelayUntil == 1 ) - - void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) - { - portTickType xTimeToWake; - portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; - - configASSERT( pxPreviousWakeTime ); - configASSERT( ( xTimeIncrement > 0U ) ); - - vTaskSuspendAll(); - { - /* Generate the tick time at which the task wants to wake. */ - xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; - - if( xTickCount < *pxPreviousWakeTime ) - { - /* The tick count has overflowed since this function was - lasted called. In this case the only time we should ever - actually delay is if the wake time has also overflowed, - and the wake time is greater than the tick time. When this - is the case it is as if neither time had overflowed. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - else - { - /* The tick time has not overflowed. In this case we will - delay if either the wake time has overflowed, and/or the - tick time is less than the wake time. */ - if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) - { - xShouldDelay = pdTRUE; - } - } - - /* Update the wake time ready for the next call. */ - *pxPreviousWakeTime = xTimeToWake; - - if( xShouldDelay != pdFALSE ) - { - traceTASK_DELAY_UNTIL(); - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - } - xAlreadyYielded = xTaskResumeAll(); - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( xAlreadyYielded == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelay == 1 ) - - void vTaskDelay( portTickType xTicksToDelay ) - { - portTickType xTimeToWake; - signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* A delay time of zero just forces a reschedule. */ - if( xTicksToDelay > ( portTickType ) 0U ) - { - vTaskSuspendAll(); - { - traceTASK_DELAY(); - - /* A task that is removed from the event list while the - scheduler is suspended will not get placed in the ready - list or removed from the blocked list until the scheduler - is resumed. - - This task cannot be in an event list as it is the currently - executing task. */ - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - xAlreadyYielded = xTaskResumeAll(); - } - - /* Force a reschedule if xTaskResumeAll has not already done so, we may - have put ourselves to sleep. */ - if( xAlreadyYielded == pdFALSE ) - { - portYIELD_WITHIN_API(); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskPriorityGet == 1 ) - - unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxReturn; - - taskENTER_CRITICAL(); - { - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - uxReturn = pxTCB->uxPriority; - } - taskEXIT_CRITICAL(); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskPrioritySet == 1 ) - - void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) - { - tskTCB *pxTCB; - unsigned portBASE_TYPE uxCurrentPriority; - portBASE_TYPE xYieldRequired = pdFALSE; - - configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) ); - - /* Ensure the new priority is valid. */ - if( uxNewPriority >= configMAX_PRIORITIES ) - { - uxNewPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; - } - - taskENTER_CRITICAL(); - { - if( pxTask == pxCurrentTCB ) - { - pxTask = NULL; - } - - /* If null is passed in here then we are changing the - priority of the calling function. */ - pxTCB = prvGetTCBFromHandle( pxTask ); - - traceTASK_PRIORITY_SET( pxTCB, uxNewPriority ); - - #if ( configUSE_MUTEXES == 1 ) - { - uxCurrentPriority = pxTCB->uxBasePriority; - } - #else - { - uxCurrentPriority = pxTCB->uxPriority; - } - #endif - - if( uxCurrentPriority != uxNewPriority ) - { - /* The priority change may have readied a task of higher - priority than the calling task. */ - if( uxNewPriority > uxCurrentPriority ) - { - if( pxTask != NULL ) - { - /* The priority of another task is being raised. If we - were raising the priority of the currently running task - there would be no need to switch as it must have already - been the highest priority task. */ - xYieldRequired = pdTRUE; - } - } - else if( pxTask == NULL ) - { - /* Setting our own priority down means there may now be another - task of higher priority that is ready to execute. */ - xYieldRequired = pdTRUE; - } - - - - #if ( configUSE_MUTEXES == 1 ) - { - /* Only change the priority being used if the task is not - currently using an inherited priority. */ - if( pxTCB->uxBasePriority == pxTCB->uxPriority ) - { - pxTCB->uxPriority = uxNewPriority; - } - - /* The base priority gets set whatever. */ - pxTCB->uxBasePriority = uxNewPriority; - } - #else - { - pxTCB->uxPriority = uxNewPriority; - } - #endif - - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); - - /* If the task is in the blocked or suspended list we need do - nothing more than change it's priority variable. However, if - the task is in a ready list it needs to be removed and placed - in the queue appropriate to its new priority. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) - { - /* The task is currently in its ready list - remove before adding - it to it's new ready list. As we are in a critical section we - can do this even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - - if( xYieldRequired == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - taskEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskSuspend( xTaskHandle pxTaskToSuspend ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - /* Ensure a yield is performed if the current task is being - suspended. */ - if( pxTaskToSuspend == pxCurrentTCB ) - { - pxTaskToSuspend = NULL; - } - - /* If null is passed in here then we are suspending ourselves. */ - pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); - - traceTASK_SUSPEND( pxTCB ); - - /* Remove task from the ready/delayed list and place in the suspended list. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Is the task waiting on an event also? */ - if( pxTCB->xEventListItem.pvContainer != NULL ) - { - vListRemove( &( pxTCB->xEventListItem ) ); - } - - vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); - } - taskEXIT_CRITICAL(); - - if( ( void * ) pxTaskToSuspend == NULL ) - { - if( xSchedulerRunning != pdFALSE ) - { - /* We have just suspended the current task. */ - portYIELD_WITHIN_API(); - } - else - { - /* The scheduler is not running, but the task that was pointed - to by pxCurrentTCB has just been suspended and pxCurrentTCB - must be adjusted to point to a different task. */ - if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) - { - /* No other tasks are ready, so set pxCurrentTCB back to - NULL so when the next task is created pxCurrentTCB will - be set to point to it no matter what its relative priority - is. */ - pxCurrentTCB = NULL; - } - else - { - vTaskSwitchContext(); - } - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) - { - portBASE_TYPE xReturn = pdFALSE; - const tskTCB * const pxTCB = ( tskTCB * ) xTask; - - /* It does not make sense to check if the calling task is suspended. */ - configASSERT( xTask ); - - /* Is the task we are attempting to resume actually in the - suspended list? */ - if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - /* Has the task already been resumed from within an ISR? */ - if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) - { - /* Is it in the suspended list because it is in the - Suspended state? It is possible to be in the suspended - list because it is blocked on a task with no timeout - specified. */ - if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) - { - xReturn = pdTRUE; - } - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskSuspend == 1 ) - - void vTaskResume( xTaskHandle pxTaskToResume ) - { - tskTCB *pxTCB; - - /* It does not make sense to resume the calling task. */ - configASSERT( pxTaskToResume ); - - /* Remove the task from whichever list it is currently in, and place - it in the ready list. */ - pxTCB = ( tskTCB * ) pxTaskToResume; - - /* The parameter cannot be NULL as it is impossible to resume the - currently executing task. */ - if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) - { - taskENTER_CRITICAL(); - { - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME( pxTCB ); - - /* As we are in a critical section we can access the ready - lists even if the scheduler is suspended. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* We may have just resumed a higher priority task. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* This yield may not cause the task just resumed to run, but - will leave the lists in the correct state for the next yield. */ - portYIELD_WITHIN_API(); - } - } - } - taskEXIT_CRITICAL(); - } - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) - - portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - tskTCB *pxTCB; - unsigned portBASE_TYPE uxSavedInterruptStatus; - - configASSERT( pxTaskToResume ); - - pxTCB = ( tskTCB * ) pxTaskToResume; - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) - { - traceTASK_RESUME_FROM_ISR( pxTCB ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed, at which point a - yield will be performed if necessary. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); - } - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xYieldRequired; - } - -#endif - - - - -/*----------------------------------------------------------- - * PUBLIC SCHEDULER CONTROL documented in task.h - *----------------------------------------------------------*/ - - -void vTaskStartScheduler( void ) -{ -portBASE_TYPE xReturn; - - /* Add the idle task at the lowest priority. */ - #if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) - { - /* Create the idle task, storing its handle in xIdleTaskHandle so it can - be returned by the xTaskGetIdleTaskHandle() function. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), &xIdleTaskHandle ); - } - #else - { - /* Create the idle task without storing its handle. */ - xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), NULL ); - } - #endif - - #if ( configUSE_TIMERS == 1 ) - { - if( xReturn == pdPASS ) - { - xReturn = xTimerCreateTimerTask(); - } - } - #endif - - if( xReturn == pdPASS ) - { - /* Interrupts are turned off here, to ensure a tick does not occur - before or during the call to xPortStartScheduler(). The stacks of - the created tasks contain a status word with interrupts switched on - so interrupts will automatically get re-enabled when the first task - starts to run. - - STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE - DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ - portDISABLE_INTERRUPTS(); - - xSchedulerRunning = pdTRUE; - xTickCount = ( portTickType ) 0U; - - /* If configGENERATE_RUN_TIME_STATS is defined then the following - macro must be defined to configure the timer/counter used to generate - the run time counter time base. */ - portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); - - /* Setting up the timer tick is hardware specific and thus in the - portable interface. */ - if( xPortStartScheduler() != pdFALSE ) - { - /* Should not reach here as if the scheduler is running the - function will not return. */ - } - else - { - /* Should only reach here if a task calls xTaskEndScheduler(). */ - } - } - - /* This line will only be reached if the kernel could not be started. */ - configASSERT( xReturn ); -} -/*-----------------------------------------------------------*/ - -void vTaskEndScheduler( void ) -{ - /* Stop the scheduler interrupts and call the portable scheduler end - routine so the original ISRs can be restored if necessary. The port - layer must ensure interrupts enable bit is left in the correct state. */ - portDISABLE_INTERRUPTS(); - xSchedulerRunning = pdFALSE; - vPortEndScheduler(); -} -/*----------------------------------------------------------*/ - -void vTaskSuspendAll( void ) -{ - /* A critical section is not required as the variable is of type - portBASE_TYPE. */ - ++uxSchedulerSuspended; -} -/*----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskResumeAll( void ) -{ -register tskTCB *pxTCB; -signed portBASE_TYPE xAlreadyYielded = pdFALSE; - - /* If uxSchedulerSuspended is zero then this function does not match a - previous call to vTaskSuspendAll(). */ - configASSERT( uxSchedulerSuspended ); - - /* It is possible that an ISR caused a task to be removed from an event - list while the scheduler was suspended. If this was the case then the - removed task will have been added to the xPendingReadyList. Once the - scheduler has been resumed it is safe to move all the pending ready - tasks from this list into their appropriate ready list. */ - taskENTER_CRITICAL(); - { - --uxSchedulerSuspended; - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0U ) - { - portBASE_TYPE xYieldRequired = pdFALSE; - - /* Move any readied tasks from the pending list into the - appropriate ready list. */ - while( listLIST_IS_EMPTY( ( xList * ) &xPendingReadyList ) == pdFALSE ) - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ); - vListRemove( &( pxTCB->xEventListItem ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxTCB ); - - /* If we have moved a task that has a priority higher than - the current task then we should yield. */ - if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - xYieldRequired = pdTRUE; - } - } - - /* If any ticks occurred while the scheduler was suspended then - they should be processed now. This ensures the tick count does not - slip, and that any delayed tasks are resumed at the correct time. */ - if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) - { - while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) - { - vTaskIncrementTick(); - --uxMissedTicks; - } - - /* As we have processed some ticks it is appropriate to yield - to ensure the highest priority task that is ready to run is - the task actually running. */ - #if configUSE_PREEMPTION == 1 - { - xYieldRequired = pdTRUE; - } - #endif - } - - if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) - { - xAlreadyYielded = pdTRUE; - xMissedYield = pdFALSE; - portYIELD_WITHIN_API(); - } - } - } - } - taskEXIT_CRITICAL(); - - return xAlreadyYielded; -} - - - - - - -/*----------------------------------------------------------- - * PUBLIC TASK UTILITIES documented in task.h - *----------------------------------------------------------*/ - - - -portTickType xTaskGetTickCount( void ) -{ -portTickType xTicks; - - /* Critical section required if running on a 16 bit processor. */ - taskENTER_CRITICAL(); - { - xTicks = xTickCount; - } - taskEXIT_CRITICAL(); - - return xTicks; -} -/*-----------------------------------------------------------*/ - -portTickType xTaskGetTickCountFromISR( void ) -{ -portTickType xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - xReturn = xTickCount; - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) -{ - /* A critical section is not required because the variables are of type - portBASE_TYPE. */ - return uxCurrentNumberOfTasks; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_pcTaskGetTaskName == 1 ) - - signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ) - { - tskTCB *pxTCB; - - /* If null is passed in here then the name of the calling task is being queried. */ - pxTCB = prvGetTCBFromHandle( xTaskToQuery ); - configASSERT( pxTCB ); - return &( pxTCB->pcTaskName[ 0 ] ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - void vTaskList( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - /* Run through all the lists that could potentially contain a TCB and - report the task name, state and stack high water mark. */ - - *pcWriteBuffer = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; - - do - { - uxQueue--; - - if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); - } - - if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); - } - - #if( INCLUDE_vTaskDelete == 1 ) - { - if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, &xTasksWaitingTermination, tskDELETED_CHAR ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) - { - prvListTaskWithinSingleList( pcWriteBuffer, &xSuspendedTaskList, tskSUSPENDED_CHAR ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) - { - unsigned portBASE_TYPE uxQueue; - unsigned long ulTotalRunTime; - - /* This is a VERY costly function that should be used for debug only. - It leaves interrupts disabled for a LONG time. */ - - vTaskSuspendAll(); - { - #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE - portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime ); - #else - ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); - #endif - - /* Divide ulTotalRunTime by 100 to make the percentage caluclations - simpler in the prvGenerateRunTimeStatsForTasksInList() function. */ - ulTotalRunTime /= 100UL; - - /* Run through all the lists that could potentially contain a TCB, - generating a table of run timer percentages in the provided - buffer. */ - - *pcWriteBuffer = ( signed char ) 0x00; - strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); - - uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; - - do - { - uxQueue--; - - if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); - } - }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); - } - - if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); - } - - #if ( INCLUDE_vTaskDelete == 1 ) - { - if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xTasksWaitingTermination, ulTotalRunTime ); - } - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) - { - prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xSuspendedTaskList, ulTotalRunTime ); - } - } - #endif - } - xTaskResumeAll(); - } - -#endif -/*----------------------------------------------------------*/ - -#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) - - xTaskHandle xTaskGetIdleTaskHandle( void ) - { - /* If xTaskGetIdleTaskHandle() is called before the scheduler has been - started, then xIdleTaskHandle will be NULL. */ - configASSERT( ( xIdleTaskHandle != NULL ) ); - return xIdleTaskHandle; - } - -#endif - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - * documented in task.h - *----------------------------------------------------------*/ - -void vTaskIncrementTick( void ) -{ -tskTCB * pxTCB; - - /* Called by the portable layer each time a tick interrupt occurs. - Increments the tick then checks to see if the new tick value will cause any - tasks to be unblocked. */ - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - ++xTickCount; - if( xTickCount == ( portTickType ) 0U ) - { - xList *pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. - If there are any items in pxDelayedTaskList here then there is - an error! */ - configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) ); - - pxTemp = pxDelayedTaskList; - pxDelayedTaskList = pxOverflowDelayedTaskList; - pxOverflowDelayedTaskList = pxTemp; - xNumOfOverflows++; - - if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) - { - /* The new current delayed list is empty. Set - xNextTaskUnblockTime to the maximum possible value so it is - extremely unlikely that the - if( xTickCount >= xNextTaskUnblockTime ) test will pass until - there is an item in the delayed list. */ - xNextTaskUnblockTime = portMAX_DELAY; - } - else - { - /* The new current delayed list is not empty, get the value of - the item at the head of the delayed list. This is the time at - which the task at the head of the delayed list should be removed - from the Blocked state. */ - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); - xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); - } - } - - /* See if this tick has made a timeout expire. */ - prvCheckDelayedTasks(); - } - else - { - ++uxMissedTicks; - - /* The tick hook gets called at regular intervals, even if the - scheduler is locked. */ - #if ( configUSE_TICK_HOOK == 1 ) - { - vApplicationTickHook(); - } - #endif - } - - #if ( configUSE_TICK_HOOK == 1 ) - { - /* Guard against the tick hook being called when the missed tick - count is being unwound (when the scheduler is being unlocked. */ - if( uxMissedTicks == ( unsigned portBASE_TYPE ) 0U ) - { - vApplicationTickHook(); - } - } - #endif - - traceTASK_INCREMENT_TICK( xTickCount ); -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) - { - tskTCB *xTCB; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - taskENTER_CRITICAL(); - xTCB->pxTaskTag = pxHookFunction; - taskEXIT_CRITICAL(); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) - { - tskTCB *xTCB; - pdTASK_HOOK_CODE xReturn; - - /* If xTask is NULL then we are setting our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - /* Save the hook function in the TCB. A critical section is required as - the value can be accessed from an interrupt. */ - taskENTER_CRITICAL(); - xReturn = xTCB->pxTaskTag; - taskEXIT_CRITICAL(); - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_APPLICATION_TASK_TAG == 1 ) - - portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) - { - tskTCB *xTCB; - portBASE_TYPE xReturn; - - /* If xTask is NULL then we are calling our own task hook. */ - if( xTask == NULL ) - { - xTCB = ( tskTCB * ) pxCurrentTCB; - } - else - { - xTCB = ( tskTCB * ) xTask; - } - - if( xTCB->pxTaskTag != NULL ) - { - xReturn = xTCB->pxTaskTag( pvParameter ); - } - else - { - xReturn = pdFAIL; - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -void vTaskSwitchContext( void ) -{ - if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) - { - /* The scheduler is currently suspended - do not allow a context - switch. */ - xMissedYield = pdTRUE; - } - else - { - traceTASK_SWITCHED_OUT(); - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - unsigned long ulTempCounter; - - #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE - portALT_GET_RUN_TIME_COUNTER_VALUE( ulTempCounter ); - #else - ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); - #endif - - /* Add the amount of time the task has been running to the accumulated - time so far. The time the task started running was stored in - ulTaskSwitchedInTime. Note that there is no overflow protection here - so count values are only valid until the timer overflows. Generally - this will be about 1 hour assuming a 1uS timer increment. */ - pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); - ulTaskSwitchedInTime = ulTempCounter; - } - #endif - - taskFIRST_CHECK_FOR_STACK_OVERFLOW(); - taskSECOND_CHECK_FOR_STACK_OVERFLOW(); - - /* Find the highest priority queue that contains ready tasks. */ - while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) - { - configASSERT( uxTopReadyPriority ); - --uxTopReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the - same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); - - traceTASK_SWITCHED_IN(); - } -} -/*-----------------------------------------------------------*/ - -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) -{ -portTickType xTimeToWake; - - configASSERT( pxEventList ); - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. */ - - /* Place the event list item of the TCB in the appropriate event list. - This is placed in the list in priority order so the highest priority task - is the first to be woken by the event. */ - vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove ourselves from the ready list before adding ourselves - to the blocked list as the same list item is used for both lists. We have - exclusive access to the ready lists as the scheduler is locked. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - if( xTicksToWait == portMAX_DELAY ) - { - /* Add ourselves to the suspended task list instead of a delayed task - list to ensure we are not woken by a timing event. We will block - indefinitely. */ - vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - } - #else - { - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - #endif -} -/*-----------------------------------------------------------*/ - -#if configUSE_TIMERS == 1 - - void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) - { - portTickType xTimeToWake; - - configASSERT( pxEventList ); - - /* This function should not be called by application code hence the - 'Restricted' in its name. It is not part of the public API. It is - designed for use by kernel code, and has special calling requirements - - it should be called from a critical section. */ - - - /* Place the event list item of the TCB in the appropriate event list. - In this case it is assume that this is the only task that is going to - be waiting on this event list, so the faster vListInsertEnd() function - can be used in place of vListInsert. */ - vListInsertEnd( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); - - /* We must remove this task from the ready list before adding it to the - blocked list as the same list item is used for both lists. This - function is called form a critical section. */ - vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* Calculate the time at which the task should be woken if the event does - not occur. This may overflow but this doesn't matter. */ - xTimeToWake = xTickCount + xTicksToWait; - prvAddCurrentTaskToDelayedList( xTimeToWake ); - } - -#endif /* configUSE_TIMERS */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) -{ -tskTCB *pxUnblockedTCB; -portBASE_TYPE xReturn; - - /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE - SCHEDULER SUSPENDED. It can also be called from within an ISR. */ - - /* The event list is sorted in priority order, so we can remove the - first in the list, remove the TCB from the delayed list, and add - it to the ready list. - - If an event is for a queue that is locked then this function will never - get called - the lock count on the queue will get modified instead. This - means we can always expect exclusive access to the event list here. - - This function assumes that a check has already been made to ensure that - pxEventList is not empty. */ - pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - configASSERT( pxUnblockedTCB ); - vListRemove( &( pxUnblockedTCB->xEventListItem ) ); - - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); - prvAddTaskToReadyQueue( pxUnblockedTCB ); - } - else - { - /* We cannot access the delayed or ready lists, so will hold this - task pending until the scheduler is resumed. */ - vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); - } - - if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) - { - /* Return true if the task removed from the event list has - a higher priority than the calling task. This allows - the calling task to know if it should force a context - switch now. */ - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) -{ - configASSERT( pxTimeOut ); - pxTimeOut->xOverflowCount = xNumOfOverflows; - pxTimeOut->xTimeOnEntering = xTickCount; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) -{ -portBASE_TYPE xReturn; - - configASSERT( pxTimeOut ); - configASSERT( pxTicksToWait ); - - taskENTER_CRITICAL(); - { - #if ( INCLUDE_vTaskSuspend == 1 ) - /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is - the maximum block time then the task should block indefinitely, and - therefore never time out. */ - if( *pxTicksToWait == portMAX_DELAY ) - { - xReturn = pdFALSE; - } - else /* We are not blocking indefinitely, perform the checks below. */ - #endif - - if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) - { - /* The tick count is greater than the time at which vTaskSetTimeout() - was called, but has also overflowed since vTaskSetTimeOut() was called. - It must have wrapped all the way around and gone past us again. This - passed since vTaskSetTimeout() was called. */ - xReturn = pdTRUE; - } - else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) - { - /* Not a genuine timeout. Adjust parameters for time remaining. */ - *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); - vTaskSetTimeOutState( pxTimeOut ); - xReturn = pdFALSE; - } - else - { - xReturn = pdTRUE; - } - } - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vTaskMissedYield( void ) -{ - xMissedYield = pdTRUE; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - unsigned portBASE_TYPE uxTaskGetTaskNumber( xTaskHandle xTask ) - { - unsigned portBASE_TYPE uxReturn; - tskTCB *pxTCB; - - if( xTask != NULL ) - { - pxTCB = ( tskTCB * ) xTask; - uxReturn = pxTCB->uxTaskNumber; - } - else - { - uxReturn = 0U; - } - - return uxReturn; - } -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - void vTaskSetTaskNumber( xTaskHandle xTask, unsigned portBASE_TYPE uxHandle ) - { - tskTCB *pxTCB; - - if( xTask != NULL ) - { - pxTCB = ( tskTCB * ) xTask; - pxTCB->uxTaskNumber = uxHandle; - } - } -#endif - - -/* - * ----------------------------------------------------------- - * The Idle task. - * ---------------------------------------------------------- - * - * The portTASK_FUNCTION() macro is used to allow port/compiler specific - * language extensions. The equivalent prototype for this function is: - * - * void prvIdleTask( void *pvParameters ); - * - */ -static portTASK_FUNCTION( prvIdleTask, pvParameters ) -{ - /* Stop warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* See if any tasks have been deleted. */ - prvCheckTasksWaitingTermination(); - - #if ( configUSE_PREEMPTION == 0 ) - { - /* If we are not using preemption we keep forcing a task switch to - see if any other task has become available. If we are using - preemption we don't need to do this as any task becoming available - will automatically get the processor anyway. */ - taskYIELD(); - } - #endif - - #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) - { - /* When using preemption tasks of equal priority will be - timesliced. If a task that is sharing the idle priority is ready - to run then the idle task should yield before the end of the - timeslice. - - A critical region is not required here as we are just reading from - the list, and an occasional incorrect value will not matter. If - the ready list at the idle priority contains more than one task - then a task other than the idle task is ready to execute. */ - if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) - { - taskYIELD(); - } - } - #endif - - #if ( configUSE_IDLE_HOOK == 1 ) - { - extern void vApplicationIdleHook( void ); - - /* Call the user defined function from within the idle task. This - allows the application designer to add background functionality - without the overhead of a separate task. - NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, - CALL A FUNCTION THAT MIGHT BLOCK. */ - vApplicationIdleHook(); - } - #endif - } -} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ - - - - - - - -/*----------------------------------------------------------- - * File private functions documented at the top of the file. - *----------------------------------------------------------*/ - - - -static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) -{ - /* Store the function name in the TCB. */ - #if configMAX_TASK_NAME_LEN > 1 - { - /* Don't bring strncpy into the build unnecessarily. */ - strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); - } - #endif - pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = ( signed char ) '\0'; - - /* This is used as an array index so must ensure it's not too large. First - remove the privilege bit if one is present. */ - if( uxPriority >= configMAX_PRIORITIES ) - { - uxPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; - } - - pxTCB->uxPriority = uxPriority; - #if ( configUSE_MUTEXES == 1 ) - { - pxTCB->uxBasePriority = uxPriority; - } - #endif - - vListInitialiseItem( &( pxTCB->xGenericListItem ) ); - vListInitialiseItem( &( pxTCB->xEventListItem ) ); - - /* Set the pxTCB as a link back from the xListItem. This is so we can get - back to the containing TCB from a generic item in a list. */ - listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); - - #if ( portCRITICAL_NESTING_IN_TCB == 1 ) - { - pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0U; - } - #endif - - #if ( configUSE_APPLICATION_TASK_TAG == 1 ) - { - pxTCB->pxTaskTag = NULL; - } - #endif - - #if ( configGENERATE_RUN_TIME_STATS == 1 ) - { - pxTCB->ulRunTimeCounter = 0UL; - } - #endif - - #if ( portUSING_MPU_WRAPPERS == 1 ) - { - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); - } - #else - { - ( void ) xRegions; - ( void ) usStackDepth; - } - #endif -} -/*-----------------------------------------------------------*/ - -#if ( portUSING_MPU_WRAPPERS == 1 ) - - void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) - { - tskTCB *pxTCB; - - if( xTaskToModify == pxCurrentTCB ) - { - xTaskToModify = NULL; - } - - /* If null is passed in here then we are deleting ourselves. */ - pxTCB = prvGetTCBFromHandle( xTaskToModify ); - - vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); - } - /*-----------------------------------------------------------*/ -#endif - -static void prvInitialiseTaskLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = ( unsigned portBASE_TYPE ) 0U; uxPriority < configMAX_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedTaskList1 ); - vListInitialise( ( xList * ) &xDelayedTaskList2 ); - vListInitialise( ( xList * ) &xPendingReadyList ); - - #if ( INCLUDE_vTaskDelete == 1 ) - { - vListInitialise( ( xList * ) &xTasksWaitingTermination ); - } - #endif - - #if ( INCLUDE_vTaskSuspend == 1 ) - { - vListInitialise( ( xList * ) &xSuspendedTaskList ); - } - #endif - - /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList - using list2. */ - pxDelayedTaskList = &xDelayedTaskList1; - pxOverflowDelayedTaskList = &xDelayedTaskList2; -} -/*-----------------------------------------------------------*/ - -static void prvCheckTasksWaitingTermination( void ) -{ - #if ( INCLUDE_vTaskDelete == 1 ) - { - portBASE_TYPE xListIsEmpty; - - /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called - too often in the idle task. */ - if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0U ) - { - vTaskSuspendAll(); - xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); - xTaskResumeAll(); - - if( xListIsEmpty == pdFALSE ) - { - tskTCB *pxTCB; - - taskENTER_CRITICAL(); - { - pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); - vListRemove( &( pxTCB->xGenericListItem ) ); - --uxCurrentNumberOfTasks; - --uxTasksDeleted; - } - taskEXIT_CRITICAL(); - - prvDeleteTCB( pxTCB ); - } - } - } - #endif -} -/*-----------------------------------------------------------*/ - -static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) -{ - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xTickCount ) - { - /* Wake time has overflowed. Place this item in the overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the current block list. */ - vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); - - /* If the task entering the blocked state was placed at the head of the - list of blocked tasks then xNextTaskUnblockTime needs to be updated - too. */ - if( xTimeToWake < xNextTaskUnblockTime ) - { - xNextTaskUnblockTime = xTimeToWake; - } - } -} -/*-----------------------------------------------------------*/ - -static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) -{ -tskTCB *pxNewTCB; - - /* Allocate space for the TCB. Where the memory comes from depends on - the implementation of the port malloc function. */ - pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); - - if( pxNewTCB != NULL ) - { - /* Allocate space for the stack used by the task being created. - The base of the stack memory stored in the TCB so the task can - be deleted later if required. */ - pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); - - if( pxNewTCB->pxStack == NULL ) - { - /* Could not allocate the stack. Delete the allocated TCB. */ - vPortFree( pxNewTCB ); - pxNewTCB = NULL; - } - else - { - /* Just to help debugging. */ - memset( pxNewTCB->pxStack, ( int ) tskSTACK_FILL_BYTE, ( size_t ) usStackDepth * sizeof( portSTACK_TYPE ) ); - } - } - - return pxNewTCB; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_TRACE_FACILITY == 1 ) - - static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned short usStackRemaining; - PRIVILEGED_DATA static char pcStatusString[ configMAX_TASK_NAME_LEN + 30 ]; - - /* Write the details of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - #if ( portSTACK_GROWTH > 0 ) - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); - } - #else - { - usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); - } - #endif - - sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) - { - volatile tskTCB *pxNextTCB, *pxFirstTCB; - unsigned long ulStatsAsPercentage; - - /* Write the run time stats of all the TCB's in pxList into the buffer. */ - listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); - do - { - /* Get next TCB in from the list. */ - listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); - - /* Divide by zero check. */ - if( ulTotalRunTime > 0UL ) - { - /* Has the task run at all? */ - if( pxNextTCB->ulRunTimeCounter == 0UL ) - { - /* The task has used no CPU time at all. */ - sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); - } - else - { - /* What percentage of the total run time has the task used? - This will always be rounded down to the nearest integer. - ulTotalRunTime has already been divided by 100. */ - ulStatsAsPercentage = pxNextTCB->ulRunTimeCounter / ulTotalRunTime; - - if( ulStatsAsPercentage > 0UL ) - { - #ifdef portLU_PRINTF_SPECIFIER_REQUIRED - { - sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t%lu%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter, ulStatsAsPercentage ); - } - #else - { - /* sizeof( int ) == sizeof( long ) so a smaller - printf() library can be used. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); - } - #endif - } - else - { - /* If the percentage is zero here then the task has - consumed less than 1% of the total run time. */ - #ifdef portLU_PRINTF_SPECIFIER_REQUIRED - { - sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t<1%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter ); - } - #else - { - /* sizeof( int ) == sizeof( long ) so a smaller - printf() library can be used. */ - sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); - } - #endif - } - } - - strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); - } - - } while( pxNextTCB != pxFirstTCB ); - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) - - static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) - { - register unsigned short usCount = 0U; - - while( *pucStackByte == tskSTACK_FILL_BYTE ) - { - pucStackByte -= portSTACK_GROWTH; - usCount++; - } - - usCount /= sizeof( portSTACK_TYPE ); - - return usCount; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetRunTime == 1 ) - - unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) - { - unsigned long runTime; - - tskTCB *pxTCB; - pxTCB = prvGetTCBFromHandle( xTask ); - runTime = pxTCB->ulRunTimeCounter; - pxTCB->ulRunTimeCounter = 0; - return runTime; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) - - unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) - { - tskTCB *pxTCB; - unsigned char *pcEndOfStack; - unsigned portBASE_TYPE uxReturn; - - pxTCB = prvGetTCBFromHandle( xTask ); - - #if portSTACK_GROWTH < 0 - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; - } - #else - { - pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; - } - #endif - - uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); - - return uxReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_vTaskDelete == 1 ) - - static void prvDeleteTCB( tskTCB *pxTCB ) - { - /* This call is required specifically for the TriCore port. It must be - above the vPortFree() calls. The call is also used by ports/demos that - want to allocate and clean RAM statically. */ - portCLEAN_UP_TCB( pxTCB ); - - /* Free up the memory allocated by the scheduler for the task. It is up to - the task to free any memory allocated at the application level. */ - vPortFreeAligned( pxTCB->pxStack ); - vPortFree( pxTCB ); - } - -#endif - - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) - - xTaskHandle xTaskGetCurrentTaskHandle( void ) - { - xTaskHandle xReturn; - - /* A critical section is not required as this is not called from - an interrupt and the current TCB will always be the same for any - individual execution thread. */ - xReturn = pxCurrentTCB; - - return xReturn; - } - -#endif - -/*-----------------------------------------------------------*/ - -#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) - - portBASE_TYPE xTaskGetSchedulerState( void ) - { - portBASE_TYPE xReturn; - - if( xSchedulerRunning == pdFALSE ) - { - xReturn = taskSCHEDULER_NOT_STARTED; - } - else - { - if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) - { - xReturn = taskSCHEDULER_RUNNING; - } - else - { - xReturn = taskSCHEDULER_SUSPENDED; - } - } - - return xReturn; - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - configASSERT( pxMutexHolder ); - - if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) - { - /* Adjust the mutex holder state to account for its new priority. */ - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); - - /* If the task being modified is in the ready state it will need to - be moved in to a new list. */ - if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) != pdFALSE ) - { - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Inherit the priority before being moved into the new list. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - prvAddTaskToReadyQueue( pxTCB ); - } - else - { - /* Just inherit the priority. */ - pxTCB->uxPriority = pxCurrentTCB->uxPriority; - } - - traceTASK_PRIORITY_INHERIT( pxTCB, pxCurrentTCB->uxPriority ); - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) - { - tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; - - if( pxMutexHolder != NULL ) - { - if( pxTCB->uxPriority != pxTCB->uxBasePriority ) - { - /* We must be the running task to be able to give the mutex back. - Remove ourselves from the ready list we currently appear in. */ - vListRemove( &( pxTCB->xGenericListItem ) ); - - /* Disinherit the priority before adding the task into the new - ready list. */ - traceTASK_PRIORITY_DISINHERIT( pxTCB, pxTCB->uxBasePriority ); - pxTCB->uxPriority = pxTCB->uxBasePriority; - listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); - prvAddTaskToReadyQueue( pxTCB ); - } - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - - void vTaskEnterCritical( void ) - { - portDISABLE_INTERRUPTS(); - - if( xSchedulerRunning != pdFALSE ) - { - ( pxCurrentTCB->uxCriticalNesting )++; - } - } - -#endif -/*-----------------------------------------------------------*/ - -#if ( portCRITICAL_NESTING_IN_TCB == 1 ) - -void vTaskExitCritical( void ) -{ - if( xSchedulerRunning != pdFALSE ) - { - if( pxCurrentTCB->uxCriticalNesting > 0U ) - { - ( pxCurrentTCB->uxCriticalNesting )--; - - if( pxCurrentTCB->uxCriticalNesting == 0U ) - { - portENABLE_INTERRUPTS(); - } - } - } -} - -#endif -/*-----------------------------------------------------------*/ - - - - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#include +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "timers.h" +#include "StackMacros.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* + * Macro to define the amount of stack available to the idle task. + */ +#define tskIDLE_STACK_SIZE configMINIMAL_STACK_SIZE + +/* + * Task control block. A task control block (TCB) is allocated to each task, + * and stores the context of the task. + */ +typedef struct tskTaskControlBlock +{ + volatile portSTACK_TYPE *pxTopOfStack; /*< Points to the location of the last item placed on the tasks stack. THIS MUST BE THE FIRST MEMBER OF THE STRUCT. */ + + #if ( portUSING_MPU_WRAPPERS == 1 ) + xMPU_SETTINGS xMPUSettings; /*< The MPU settings are defined as part of the port layer. THIS MUST BE THE SECOND MEMBER OF THE STRUCT. */ + #endif + + xListItem xGenericListItem; /*< List item used to place the TCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the TCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the task where 0 is the lowest priority. */ + portSTACK_TYPE *pxStack; /*< Points to the start of the stack. */ + signed char pcTaskName[ configMAX_TASK_NAME_LEN ];/*< Descriptive name given to the task when created. Facilitates debugging only. */ + + #if ( portSTACK_GROWTH > 0 ) + portSTACK_TYPE *pxEndOfStack; /*< Used for stack overflow checking on architectures where the stack grows up from low memory. */ + #endif + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + unsigned portBASE_TYPE uxCriticalNesting; + #endif + + #if ( configUSE_TRACE_FACILITY == 1 ) + unsigned portBASE_TYPE uxTCBNumber; /*< This stores a number that increments each time a TCB is created. It allows debuggers to determine when a task has been deleted and then recreated. */ + unsigned portBASE_TYPE uxTaskNumber; /*< This stores a number specifically for use by third party trace code. */ + #endif + + #if ( configUSE_MUTEXES == 1 ) + unsigned portBASE_TYPE uxBasePriority; /*< The priority last assigned to the task - used by the priority inheritance mechanism. */ + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + pdTASK_HOOK_CODE pxTaskTag; + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + unsigned long ulRunTimeCounter; /*< Used for calculating how much CPU time each task is utilising. */ + #endif + +} tskTCB; + + +/* + * Some kernel aware debuggers require data to be viewed to be global, rather + * than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + +/*lint -e956 */ +PRIVILEGED_DATA tskTCB * volatile pxCurrentTCB = NULL; + +/* Lists for ready and blocked tasks. --------------------*/ + +PRIVILEGED_DATA static xList pxReadyTasksLists[ configMAX_PRIORITIES ]; /*< Prioritised ready tasks. */ +PRIVILEGED_DATA static xList xDelayedTaskList1; /*< Delayed tasks. */ +PRIVILEGED_DATA static xList xDelayedTaskList2; /*< Delayed tasks (two lists are used - one for delays that have overflowed the current tick count. */ +PRIVILEGED_DATA static xList * volatile pxDelayedTaskList ; /*< Points to the delayed task list currently being used. */ +PRIVILEGED_DATA static xList * volatile pxOverflowDelayedTaskList; /*< Points to the delayed task list currently being used to hold tasks that have overflowed the current tick count. */ +PRIVILEGED_DATA static xList xPendingReadyList; /*< Tasks that have been readied while the scheduler was suspended. They will be moved to the ready queue when the scheduler is resumed. */ + +#if ( INCLUDE_vTaskDelete == 1 ) + + PRIVILEGED_DATA static xList xTasksWaitingTermination; /*< Tasks that have been deleted - but the their memory not yet freed. */ + PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTasksDeleted = ( unsigned portBASE_TYPE ) 0U; + +#endif + +#if ( INCLUDE_vTaskSuspend == 1 ) + + PRIVILEGED_DATA static xList xSuspendedTaskList; /*< Tasks that are currently suspended. */ + +#endif + +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + + PRIVILEGED_DATA static xTaskHandle xIdleTaskHandle = NULL; + +#endif + +/* File private variables. --------------------------------*/ +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxCurrentNumberOfTasks = ( unsigned portBASE_TYPE ) 0U; +PRIVILEGED_DATA static volatile portTickType xTickCount = ( portTickType ) 0U; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTopUsedPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxTopReadyPriority = tskIDLE_PRIORITY; +PRIVILEGED_DATA static volatile signed portBASE_TYPE xSchedulerRunning = pdFALSE; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxSchedulerSuspended = ( unsigned portBASE_TYPE ) pdFALSE; +PRIVILEGED_DATA static volatile unsigned portBASE_TYPE uxMissedTicks = ( unsigned portBASE_TYPE ) 0U; +PRIVILEGED_DATA static volatile portBASE_TYPE xMissedYield = ( portBASE_TYPE ) pdFALSE; +PRIVILEGED_DATA static volatile portBASE_TYPE xNumOfOverflows = ( portBASE_TYPE ) 0; +PRIVILEGED_DATA static unsigned portBASE_TYPE uxTaskNumber = ( unsigned portBASE_TYPE ) 0U; +PRIVILEGED_DATA static portTickType xNextTaskUnblockTime = ( portTickType ) portMAX_DELAY; + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + PRIVILEGED_DATA static char pcStatsString[ 50 ] ; + PRIVILEGED_DATA static unsigned long ulTaskSwitchedInTime = 0UL; /*< Holds the value of a timer/counter the last time a task was switched in. */ + static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) PRIVILEGED_FUNCTION; + +#endif + +/* Debugging and trace facilities private variables and macros. ------------*/ + +/* + * The value used to fill the stack of a task when the task is created. This + * is used purely for checking the high water mark for tasks. + */ +#define tskSTACK_FILL_BYTE ( 0xa5U ) + +/* + * Macros used by vListTask to indicate which state a task is in. + */ +#define tskBLOCKED_CHAR ( ( signed char ) 'B' ) +#define tskREADY_CHAR ( ( signed char ) 'R' ) +#define tskDELETED_CHAR ( ( signed char ) 'D' ) +#define tskSUSPENDED_CHAR ( ( signed char ) 'S' ) + +/*-----------------------------------------------------------*/ + +/* + * Place the task represented by pxTCB into the appropriate ready queue for + * the task. It is inserted at the end of the list. One quirk of this is + * that if the task being inserted is at the same priority as the currently + * executing task, then it will only be rescheduled after the currently + * executing task has been rescheduled. + */ +#define prvAddTaskToReadyQueue( pxTCB ) \ + traceMOVED_TASK_TO_READY_STATE( pxTCB ) \ + if( ( pxTCB )->uxPriority > uxTopReadyPriority ) \ + { \ + uxTopReadyPriority = ( pxTCB )->uxPriority; \ + } \ + vListInsertEnd( ( xList * ) &( pxReadyTasksLists[ ( pxTCB )->uxPriority ] ), &( ( pxTCB )->xGenericListItem ) ) +/*-----------------------------------------------------------*/ + +/* + * Macro that looks at the list of tasks that are currently delayed to see if + * any require waking. + * + * Tasks are stored in the queue in the order of their wake time - meaning + * once one tasks has been found whose timer has not expired we need not look + * any further down the list. + */ +#define prvCheckDelayedTasks() \ +{ \ +portTickType xItemValue; \ + \ + /* Is the tick count greater than or equal to the wake time of the first \ + task referenced from the delayed tasks list? */ \ + if( xTickCount >= xNextTaskUnblockTime ) \ + { \ + for( ;; ) \ + { \ + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) \ + { \ + /* The delayed list is empty. Set xNextTaskUnblockTime to the \ + maximum possible value so it is extremely unlikely that the \ + if( xTickCount >= xNextTaskUnblockTime ) test will pass next \ + time through. */ \ + xNextTaskUnblockTime = portMAX_DELAY; \ + break; \ + } \ + else \ + { \ + /* The delayed list is not empty, get the value of the item at \ + the head of the delayed list. This is the time at which the \ + task at the head of the delayed list should be removed from \ + the Blocked state. */ \ + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); \ + xItemValue = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); \ + \ + if( xTickCount < xItemValue ) \ + { \ + /* It is not time to unblock this item yet, but the item \ + value is the time at which the task at the head of the \ + blocked list should be removed from the Blocked state - \ + so record the item value in xNextTaskUnblockTime. */ \ + xNextTaskUnblockTime = xItemValue; \ + break; \ + } \ + \ + /* It is time to remove the item from the Blocked state. */ \ + vListRemove( &( pxTCB->xGenericListItem ) ); \ + \ + /* Is the task waiting on an event also? */ \ + if( pxTCB->xEventListItem.pvContainer != NULL ) \ + { \ + vListRemove( &( pxTCB->xEventListItem ) ); \ + } \ + prvAddTaskToReadyQueue( pxTCB ); \ + } \ + } \ + } \ +} +/*-----------------------------------------------------------*/ + +/* + * Several functions take an xTaskHandle parameter that can optionally be NULL, + * where NULL is used to indicate that the handle of the currently executing + * task should be used in place of the parameter. This macro simply checks to + * see if the parameter is NULL and returns a pointer to the appropriate TCB. + */ +#define prvGetTCBFromHandle( pxHandle ) ( ( ( pxHandle ) == NULL ) ? ( tskTCB * ) pxCurrentTCB : ( tskTCB * ) ( pxHandle ) ) + +/* Callback function prototypes. --------------------------*/ +extern void vApplicationStackOverflowHook( xTaskHandle pxTask, signed char *pcTaskName ); +extern void vApplicationTickHook( void ); + +/* File private functions. --------------------------------*/ + +/* + * Utility to ready a TCB for a given task. Mainly just copies the parameters + * into the TCB structure. + */ +static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first task. + */ +static void prvInitialiseTaskLists( void ) PRIVILEGED_FUNCTION; + +/* + * The idle task, which as all tasks is implemented as a never ending loop. + * The idle task is automatically created and added to the ready lists upon + * creation of the first user task. + * + * The portTASK_FUNCTION_PROTO() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION_PROTO( prvIdleTask, pvParameters ); + +/* + * Utility to free all memory allocated by the scheduler to hold a TCB, + * including the stack pointed to by the TCB. + * + * This does not free memory allocated by the task itself (i.e. memory + * allocated by calls to pvPortMalloc from within the tasks application code). + */ +#if ( INCLUDE_vTaskDelete == 1 ) + + static void prvDeleteTCB( tskTCB *pxTCB ) PRIVILEGED_FUNCTION; + +#endif + +/* + * Used only by the idle task. This checks to see if anything has been placed + * in the list of tasks waiting to be deleted. If so the task is cleaned up + * and its TCB deleted. + */ +static void prvCheckTasksWaitingTermination( void ) PRIVILEGED_FUNCTION; + +/* + * The currently executing task is entering the Blocked state. Add the task to + * either the current or the overflow delayed task list. + */ +static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) PRIVILEGED_FUNCTION; + +/* + * Allocates memory from the heap for a TCB and associated stack. Checks the + * allocation was successful. + */ +static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) PRIVILEGED_FUNCTION; + +/* + * Called from vTaskList. vListTasks details all the tasks currently under + * control of the scheduler. The tasks may be in one of a number of lists. + * prvListTaskWithinSingleList accepts a list and details the tasks from + * within just that list. + * + * THIS FUNCTION IS INTENDED FOR DEBUGGING ONLY, AND SHOULD NOT BE CALLED FROM + * NORMAL APPLICATION CODE. + */ +#if ( configUSE_TRACE_FACILITY == 1 ) + + static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) PRIVILEGED_FUNCTION; + +#endif + +/* + * When a task is created, the stack of the task is filled with a known value. + * This function determines the 'high water mark' of the task stack by + * determining how much of the stack remains at the original preset value. + */ +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) + + static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) PRIVILEGED_FUNCTION; + +#endif + + +/*lint +e956 */ + + + +/*----------------------------------------------------------- + * TASK CREATION API documented in task.h + *----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pxTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) +{ +signed portBASE_TYPE xReturn; +tskTCB * pxNewTCB; + + configASSERT( pxTaskCode ); + configASSERT( ( ( uxPriority & ( ~portPRIVILEGE_BIT ) ) < configMAX_PRIORITIES ) ); + + /* Allocate the memory required by the TCB and stack for the new task, + checking that the allocation was successful. */ + pxNewTCB = prvAllocateTCBAndStack( usStackDepth, puxStackBuffer ); + + if( pxNewTCB != NULL ) + { + portSTACK_TYPE *pxTopOfStack; + + #if( portUSING_MPU_WRAPPERS == 1 ) + /* Should the task be created in privileged mode? */ + portBASE_TYPE xRunPrivileged; + if( ( uxPriority & portPRIVILEGE_BIT ) != 0U ) + { + xRunPrivileged = pdTRUE; + } + else + { + xRunPrivileged = pdFALSE; + } + uxPriority &= ~portPRIVILEGE_BIT; + #endif /* portUSING_MPU_WRAPPERS == 1 */ + + /* Calculate the top of stack address. This depends on whether the + stack grows from high memory to low (as per the 80x86) or visa versa. + portSTACK_GROWTH is used to make the result positive or negative as + required by the port. */ + #if( portSTACK_GROWTH < 0 ) + { + pxTopOfStack = pxNewTCB->pxStack + ( usStackDepth - ( unsigned short ) 1 ); + pxTopOfStack = ( portSTACK_TYPE * ) ( ( ( portPOINTER_SIZE_TYPE ) pxTopOfStack ) & ( ( portPOINTER_SIZE_TYPE ) ~portBYTE_ALIGNMENT_MASK ) ); + + /* Check the alignment of the calculated top of stack is correct. */ + configASSERT( ( ( ( unsigned long ) pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + } + #else + { + pxTopOfStack = pxNewTCB->pxStack; + + /* Check the alignment of the stack buffer is correct. */ + configASSERT( ( ( ( unsigned long ) pxNewTCB->pxStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + /* If we want to use stack checking on architectures that use + a positive stack growth direction then we also need to store the + other extreme of the stack space. */ + pxNewTCB->pxEndOfStack = pxNewTCB->pxStack + ( usStackDepth - 1 ); + } + #endif + + /* Setup the newly allocated TCB with the initial state of the task. */ + prvInitialiseTCBVariables( pxNewTCB, pcName, uxPriority, xRegions, usStackDepth ); + + /* Initialize the TCB stack to look as if the task was already running, + but had been interrupted by the scheduler. The return address is set + to the start of the task function. Once the stack has been initialised + the top of stack variable is updated. */ + #if( portUSING_MPU_WRAPPERS == 1 ) + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters, xRunPrivileged ); + } + #else + { + pxNewTCB->pxTopOfStack = pxPortInitialiseStack( pxTopOfStack, pxTaskCode, pvParameters ); + } + #endif + + /* Check the alignment of the initialised stack. */ + portALIGNMENT_ASSERT_pxCurrentTCB( ( ( ( unsigned long ) pxNewTCB->pxTopOfStack & ( unsigned long ) portBYTE_ALIGNMENT_MASK ) == 0UL ) ); + + if( ( void * ) pxCreatedTask != NULL ) + { + /* Pass the TCB out - in an anonymous way. The calling function/ + task can use this as a handle to delete the task later if + required.*/ + *pxCreatedTask = ( xTaskHandle ) pxNewTCB; + } + + /* We are going to manipulate the task queues to add this task to a + ready list, so must make sure no interrupts occur. */ + taskENTER_CRITICAL(); + { + uxCurrentNumberOfTasks++; + if( pxCurrentTCB == NULL ) + { + /* There are no other tasks, or all the other tasks are in + the suspended state - make this the current task. */ + pxCurrentTCB = pxNewTCB; + + if( uxCurrentNumberOfTasks == ( unsigned portBASE_TYPE ) 1 ) + { + /* This is the first task to be created so do the preliminary + initialisation required. We will not recover if this call + fails, but we will report the failure. */ + prvInitialiseTaskLists(); + } + } + else + { + /* If the scheduler is not already running, make this task the + current task if it is the highest priority task to be created + so far. */ + if( xSchedulerRunning == pdFALSE ) + { + if( pxCurrentTCB->uxPriority <= uxPriority ) + { + pxCurrentTCB = pxNewTCB; + } + } + } + + /* Remember the top priority to make context switching faster. Use + the priority in pxNewTCB as this has been capped to a valid value. */ + if( pxNewTCB->uxPriority > uxTopUsedPriority ) + { + uxTopUsedPriority = pxNewTCB->uxPriority; + } + + #if ( configUSE_TRACE_FACILITY == 1 ) + { + /* Add a counter into the TCB for tracing only. */ + pxNewTCB->uxTCBNumber = uxTaskNumber; + } + #endif + uxTaskNumber++; + + prvAddTaskToReadyQueue( pxNewTCB ); + + xReturn = pdPASS; + portSETUP_TCB( pxNewTCB ); + traceTASK_CREATE( pxNewTCB ); + } + taskEXIT_CRITICAL(); + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + traceTASK_CREATE_FAILED(); + } + + if( xReturn == pdPASS ) + { + if( xSchedulerRunning != pdFALSE ) + { + /* If the created task is of a higher priority than the current task + then it should run now. */ + if( pxCurrentTCB->uxPriority < uxPriority ) + { + portYIELD_WITHIN_API(); + } + } + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + void vTaskDelete( xTaskHandle pxTaskToDelete ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + /* Ensure a yield is performed if the current task is being + deleted. */ + if( pxTaskToDelete == pxCurrentTCB ) + { + pxTaskToDelete = NULL; + } + + /* If null is passed in here then we are deleting ourselves. */ + pxTCB = prvGetTCBFromHandle( pxTaskToDelete ); + + /* Remove task from the ready list and place in the termination list. + This will stop the task from be scheduled. The idle task will check + the termination list and free up any memory allocated by the + scheduler for the TCB and stack. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Is the task waiting on an event also? */ + if( pxTCB->xEventListItem.pvContainer != NULL ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + } + + vListInsertEnd( ( xList * ) &xTasksWaitingTermination, &( pxTCB->xGenericListItem ) ); + + /* Increment the ucTasksDeleted variable so the idle task knows + there is a task that has been deleted and that it should therefore + check the xTasksWaitingTermination list. */ + ++uxTasksDeleted; + + /* Increment the uxTaskNumberVariable also so kernel aware debuggers + can detect that the task lists need re-generating. */ + uxTaskNumber++; + + traceTASK_DELETE( pxTCB ); + } + taskEXIT_CRITICAL(); + + /* Force a reschedule if we have just deleted the current task. */ + if( xSchedulerRunning != pdFALSE ) + { + if( ( void * ) pxTaskToDelete == NULL ) + { + portYIELD_WITHIN_API(); + } + } + } + +#endif + + + + + + +/*----------------------------------------------------------- + * TASK CONTROL API documented in task.h + *----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelayUntil == 1 ) + + void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) + { + portTickType xTimeToWake; + portBASE_TYPE xAlreadyYielded, xShouldDelay = pdFALSE; + + configASSERT( pxPreviousWakeTime ); + configASSERT( ( xTimeIncrement > 0U ) ); + + vTaskSuspendAll(); + { + /* Generate the tick time at which the task wants to wake. */ + xTimeToWake = *pxPreviousWakeTime + xTimeIncrement; + + if( xTickCount < *pxPreviousWakeTime ) + { + /* The tick count has overflowed since this function was + lasted called. In this case the only time we should ever + actually delay is if the wake time has also overflowed, + and the wake time is greater than the tick time. When this + is the case it is as if neither time had overflowed. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) && ( xTimeToWake > xTickCount ) ) + { + xShouldDelay = pdTRUE; + } + } + else + { + /* The tick time has not overflowed. In this case we will + delay if either the wake time has overflowed, and/or the + tick time is less than the wake time. */ + if( ( xTimeToWake < *pxPreviousWakeTime ) || ( xTimeToWake > xTickCount ) ) + { + xShouldDelay = pdTRUE; + } + } + + /* Update the wake time ready for the next call. */ + *pxPreviousWakeTime = xTimeToWake; + + if( xShouldDelay != pdFALSE ) + { + traceTASK_DELAY_UNTIL(); + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + } + xAlreadyYielded = xTaskResumeAll(); + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelay == 1 ) + + void vTaskDelay( portTickType xTicksToDelay ) + { + portTickType xTimeToWake; + signed portBASE_TYPE xAlreadyYielded = pdFALSE; + + /* A delay time of zero just forces a reschedule. */ + if( xTicksToDelay > ( portTickType ) 0U ) + { + vTaskSuspendAll(); + { + traceTASK_DELAY(); + + /* A task that is removed from the event list while the + scheduler is suspended will not get placed in the ready + list or removed from the blocked list until the scheduler + is resumed. + + This task cannot be in an event list as it is the currently + executing task. */ + + /* Calculate the time to wake - this may overflow but this is + not a problem. */ + xTimeToWake = xTickCount + xTicksToDelay; + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + xAlreadyYielded = xTaskResumeAll(); + } + + /* Force a reschedule if xTaskResumeAll has not already done so, we may + have put ourselves to sleep. */ + if( xAlreadyYielded == pdFALSE ) + { + portYIELD_WITHIN_API(); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskPriorityGet == 1 ) + + unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) + { + tskTCB *pxTCB; + unsigned portBASE_TYPE uxReturn; + + taskENTER_CRITICAL(); + { + /* If null is passed in here then we are changing the + priority of the calling function. */ + pxTCB = prvGetTCBFromHandle( pxTask ); + uxReturn = pxTCB->uxPriority; + } + taskEXIT_CRITICAL(); + + return uxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskPrioritySet == 1 ) + + void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) + { + tskTCB *pxTCB; + unsigned portBASE_TYPE uxCurrentPriority; + portBASE_TYPE xYieldRequired = pdFALSE; + + configASSERT( ( uxNewPriority < configMAX_PRIORITIES ) ); + + /* Ensure the new priority is valid. */ + if( uxNewPriority >= configMAX_PRIORITIES ) + { + uxNewPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; + } + + taskENTER_CRITICAL(); + { + if( pxTask == pxCurrentTCB ) + { + pxTask = NULL; + } + + /* If null is passed in here then we are changing the + priority of the calling function. */ + pxTCB = prvGetTCBFromHandle( pxTask ); + + traceTASK_PRIORITY_SET( pxTCB, uxNewPriority ); + + #if ( configUSE_MUTEXES == 1 ) + { + uxCurrentPriority = pxTCB->uxBasePriority; + } + #else + { + uxCurrentPriority = pxTCB->uxPriority; + } + #endif + + if( uxCurrentPriority != uxNewPriority ) + { + /* The priority change may have readied a task of higher + priority than the calling task. */ + if( uxNewPriority > uxCurrentPriority ) + { + if( pxTask != NULL ) + { + /* The priority of another task is being raised. If we + were raising the priority of the currently running task + there would be no need to switch as it must have already + been the highest priority task. */ + xYieldRequired = pdTRUE; + } + } + else if( pxTask == NULL ) + { + /* Setting our own priority down means there may now be another + task of higher priority that is ready to execute. */ + xYieldRequired = pdTRUE; + } + + + + #if ( configUSE_MUTEXES == 1 ) + { + /* Only change the priority being used if the task is not + currently using an inherited priority. */ + if( pxTCB->uxBasePriority == pxTCB->uxPriority ) + { + pxTCB->uxPriority = uxNewPriority; + } + + /* The base priority gets set whatever. */ + pxTCB->uxBasePriority = uxNewPriority; + } + #else + { + pxTCB->uxPriority = uxNewPriority; + } + #endif + + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), ( configMAX_PRIORITIES - ( portTickType ) uxNewPriority ) ); + + /* If the task is in the blocked or suspended list we need do + nothing more than change it's priority variable. However, if + the task is in a ready list it needs to be removed and placed + in the queue appropriate to its new priority. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ uxCurrentPriority ] ), &( pxTCB->xGenericListItem ) ) ) + { + /* The task is currently in its ready list - remove before adding + it to it's new ready list. As we are in a critical section we + can do this even if the scheduler is suspended. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + + if( xYieldRequired == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + taskEXIT_CRITICAL(); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskSuspend( xTaskHandle pxTaskToSuspend ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + /* Ensure a yield is performed if the current task is being + suspended. */ + if( pxTaskToSuspend == pxCurrentTCB ) + { + pxTaskToSuspend = NULL; + } + + /* If null is passed in here then we are suspending ourselves. */ + pxTCB = prvGetTCBFromHandle( pxTaskToSuspend ); + + traceTASK_SUSPEND( pxTCB ); + + /* Remove task from the ready/delayed list and place in the suspended list. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Is the task waiting on an event also? */ + if( pxTCB->xEventListItem.pvContainer != NULL ) + { + vListRemove( &( pxTCB->xEventListItem ) ); + } + + vListInsertEnd( ( xList * ) &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ); + } + taskEXIT_CRITICAL(); + + if( ( void * ) pxTaskToSuspend == NULL ) + { + if( xSchedulerRunning != pdFALSE ) + { + /* We have just suspended the current task. */ + portYIELD_WITHIN_API(); + } + else + { + /* The scheduler is not running, but the task that was pointed + to by pxCurrentTCB has just been suspended and pxCurrentTCB + must be adjusted to point to a different task. */ + if( listCURRENT_LIST_LENGTH( &xSuspendedTaskList ) == uxCurrentNumberOfTasks ) + { + /* No other tasks are ready, so set pxCurrentTCB back to + NULL so when the next task is created pxCurrentTCB will + be set to point to it no matter what its relative priority + is. */ + pxCurrentTCB = NULL; + } + else + { + vTaskSwitchContext(); + } + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) + { + portBASE_TYPE xReturn = pdFALSE; + const tskTCB * const pxTCB = ( tskTCB * ) xTask; + + /* It does not make sense to check if the calling task is suspended. */ + configASSERT( xTask ); + + /* Is the task we are attempting to resume actually in the + suspended list? */ + if( listIS_CONTAINED_WITHIN( &xSuspendedTaskList, &( pxTCB->xGenericListItem ) ) != pdFALSE ) + { + /* Has the task already been resumed from within an ISR? */ + if( listIS_CONTAINED_WITHIN( &xPendingReadyList, &( pxTCB->xEventListItem ) ) != pdTRUE ) + { + /* Is it in the suspended list because it is in the + Suspended state? It is possible to be in the suspended + list because it is blocked on a task with no timeout + specified. */ + if( listIS_CONTAINED_WITHIN( NULL, &( pxTCB->xEventListItem ) ) == pdTRUE ) + { + xReturn = pdTRUE; + } + } + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskSuspend == 1 ) + + void vTaskResume( xTaskHandle pxTaskToResume ) + { + tskTCB *pxTCB; + + /* It does not make sense to resume the calling task. */ + configASSERT( pxTaskToResume ); + + /* Remove the task from whichever list it is currently in, and place + it in the ready list. */ + pxTCB = ( tskTCB * ) pxTaskToResume; + + /* The parameter cannot be NULL as it is impossible to resume the + currently executing task. */ + if( ( pxTCB != NULL ) && ( pxTCB != pxCurrentTCB ) ) + { + taskENTER_CRITICAL(); + { + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME( pxTCB ); + + /* As we are in a critical section we can access the ready + lists even if the scheduler is suspended. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + + /* We may have just resumed a higher priority task. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* This yield may not cause the task just resumed to run, but + will leave the lists in the correct state for the next yield. */ + portYIELD_WITHIN_API(); + } + } + } + taskEXIT_CRITICAL(); + } + } + +#endif + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskResumeFromISR == 1 ) && ( INCLUDE_vTaskSuspend == 1 ) ) + + portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) + { + portBASE_TYPE xYieldRequired = pdFALSE; + tskTCB *pxTCB; + unsigned portBASE_TYPE uxSavedInterruptStatus; + + configASSERT( pxTaskToResume ); + + pxTCB = ( tskTCB * ) pxTaskToResume; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( xTaskIsTaskSuspended( pxTCB ) == pdTRUE ) + { + traceTASK_RESUME_FROM_ISR( pxTCB ); + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xYieldRequired = ( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed, at which point a + yield will be performed if necessary. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxTCB->xEventListItem ) ); + } + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xYieldRequired; + } + +#endif + + + + +/*----------------------------------------------------------- + * PUBLIC SCHEDULER CONTROL documented in task.h + *----------------------------------------------------------*/ + + +void vTaskStartScheduler( void ) +{ +portBASE_TYPE xReturn; + + /* Add the idle task at the lowest priority. */ + #if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + { + /* Create the idle task, storing its handle in xIdleTaskHandle so it can + be returned by the xTaskGetIdleTaskHandle() function. */ + xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), &xIdleTaskHandle ); + } + #else + { + /* Create the idle task without storing its handle. */ + xReturn = xTaskCreate( prvIdleTask, ( signed char * ) "IDLE", tskIDLE_STACK_SIZE, ( void * ) NULL, ( tskIDLE_PRIORITY | portPRIVILEGE_BIT ), NULL ); + } + #endif + + #if ( configUSE_TIMERS == 1 ) + { + if( xReturn == pdPASS ) + { + xReturn = xTimerCreateTimerTask(); + } + } + #endif + + if( xReturn == pdPASS ) + { + /* Interrupts are turned off here, to ensure a tick does not occur + before or during the call to xPortStartScheduler(). The stacks of + the created tasks contain a status word with interrupts switched on + so interrupts will automatically get re-enabled when the first task + starts to run. + + STEPPING THROUGH HERE USING A DEBUGGER CAN CAUSE BIG PROBLEMS IF THE + DEBUGGER ALLOWS INTERRUPTS TO BE PROCESSED. */ + portDISABLE_INTERRUPTS(); + + xSchedulerRunning = pdTRUE; + xTickCount = ( portTickType ) 0U; + + /* If configGENERATE_RUN_TIME_STATS is defined then the following + macro must be defined to configure the timer/counter used to generate + the run time counter time base. */ + portCONFIGURE_TIMER_FOR_RUN_TIME_STATS(); + + /* Setting up the timer tick is hardware specific and thus in the + portable interface. */ + if( xPortStartScheduler() != pdFALSE ) + { + /* Should not reach here as if the scheduler is running the + function will not return. */ + } + else + { + /* Should only reach here if a task calls xTaskEndScheduler(). */ + } + } + + /* This line will only be reached if the kernel could not be started. */ + configASSERT( xReturn ); +} +/*-----------------------------------------------------------*/ + +void vTaskEndScheduler( void ) +{ + /* Stop the scheduler interrupts and call the portable scheduler end + routine so the original ISRs can be restored if necessary. The port + layer must ensure interrupts enable bit is left in the correct state. */ + portDISABLE_INTERRUPTS(); + xSchedulerRunning = pdFALSE; + vPortEndScheduler(); +} +/*----------------------------------------------------------*/ + +void vTaskSuspendAll( void ) +{ + /* A critical section is not required as the variable is of type + portBASE_TYPE. */ + ++uxSchedulerSuspended; +} +/*----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskResumeAll( void ) +{ +register tskTCB *pxTCB; +signed portBASE_TYPE xAlreadyYielded = pdFALSE; + + /* If uxSchedulerSuspended is zero then this function does not match a + previous call to vTaskSuspendAll(). */ + configASSERT( uxSchedulerSuspended ); + + /* It is possible that an ISR caused a task to be removed from an event + list while the scheduler was suspended. If this was the case then the + removed task will have been added to the xPendingReadyList. Once the + scheduler has been resumed it is safe to move all the pending ready + tasks from this list into their appropriate ready list. */ + taskENTER_CRITICAL(); + { + --uxSchedulerSuspended; + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + if( uxCurrentNumberOfTasks > ( unsigned portBASE_TYPE ) 0U ) + { + portBASE_TYPE xYieldRequired = pdFALSE; + + /* Move any readied tasks from the pending list into the + appropriate ready list. */ + while( listLIST_IS_EMPTY( ( xList * ) &xPendingReadyList ) == pdFALSE ) + { + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xPendingReadyList ) ); + vListRemove( &( pxTCB->xEventListItem ) ); + vListRemove( &( pxTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxTCB ); + + /* If we have moved a task that has a priority higher than + the current task then we should yield. */ + if( pxTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + xYieldRequired = pdTRUE; + } + } + + /* If any ticks occurred while the scheduler was suspended then + they should be processed now. This ensures the tick count does not + slip, and that any delayed tasks are resumed at the correct time. */ + if( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) + { + while( uxMissedTicks > ( unsigned portBASE_TYPE ) 0U ) + { + vTaskIncrementTick(); + --uxMissedTicks; + } + + /* As we have processed some ticks it is appropriate to yield + to ensure the highest priority task that is ready to run is + the task actually running. */ + #if configUSE_PREEMPTION == 1 + { + xYieldRequired = pdTRUE; + } + #endif + } + + if( ( xYieldRequired == pdTRUE ) || ( xMissedYield == pdTRUE ) ) + { + xAlreadyYielded = pdTRUE; + xMissedYield = pdFALSE; + portYIELD_WITHIN_API(); + } + } + } + } + taskEXIT_CRITICAL(); + + return xAlreadyYielded; +} + + + + + + +/*----------------------------------------------------------- + * PUBLIC TASK UTILITIES documented in task.h + *----------------------------------------------------------*/ + + + +portTickType xTaskGetTickCount( void ) +{ +portTickType xTicks; + + /* Critical section required if running on a 16 bit processor. */ + taskENTER_CRITICAL(); + { + xTicks = xTickCount; + } + taskEXIT_CRITICAL(); + + return xTicks; +} +/*-----------------------------------------------------------*/ + +portTickType xTaskGetTickCountFromISR( void ) +{ +portTickType xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + xReturn = xTickCount; + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) +{ + /* A critical section is not required because the variables are of type + portBASE_TYPE. */ + return uxCurrentNumberOfTasks; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_pcTaskGetTaskName == 1 ) + + signed char *pcTaskGetTaskName( xTaskHandle xTaskToQuery ) + { + tskTCB *pxTCB; + + /* If null is passed in here then the name of the calling task is being queried. */ + pxTCB = prvGetTCBFromHandle( xTaskToQuery ); + configASSERT( pxTCB ); + return &( pxTCB->pcTaskName[ 0 ] ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + void vTaskList( signed char *pcWriteBuffer ) + { + unsigned portBASE_TYPE uxQueue; + + /* This is a VERY costly function that should be used for debug only. + It leaves interrupts disabled for a LONG time. */ + + vTaskSuspendAll(); + { + /* Run through all the lists that could potentially contain a TCB and + report the task name, state and stack high water mark. */ + + *pcWriteBuffer = ( signed char ) 0x00; + strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); + + uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; + + do + { + uxQueue--; + + if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), tskREADY_CHAR ); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, tskBLOCKED_CHAR ); + } + + if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, tskBLOCKED_CHAR ); + } + + #if( INCLUDE_vTaskDelete == 1 ) + { + if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, &xTasksWaitingTermination, tskDELETED_CHAR ); + } + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) + { + prvListTaskWithinSingleList( pcWriteBuffer, &xSuspendedTaskList, tskSUSPENDED_CHAR ); + } + } + #endif + } + xTaskResumeAll(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) + { + unsigned portBASE_TYPE uxQueue; + unsigned long ulTotalRunTime; + + /* This is a VERY costly function that should be used for debug only. + It leaves interrupts disabled for a LONG time. */ + + vTaskSuspendAll(); + { + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ulTotalRunTime ); + #else + ulTotalRunTime = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + + /* Divide ulTotalRunTime by 100 to make the percentage caluclations + simpler in the prvGenerateRunTimeStatsForTasksInList() function. */ + ulTotalRunTime /= 100UL; + + /* Run through all the lists that could potentially contain a TCB, + generating a table of run timer percentages in the provided + buffer. */ + + *pcWriteBuffer = ( signed char ) 0x00; + strcat( ( char * ) pcWriteBuffer, ( const char * ) "\r\n" ); + + uxQueue = uxTopUsedPriority + ( unsigned portBASE_TYPE ) 1U; + + do + { + uxQueue--; + + if( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxQueue ] ) ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) &( pxReadyTasksLists[ uxQueue ] ), ulTotalRunTime ); + } + }while( uxQueue > ( unsigned short ) tskIDLE_PRIORITY ); + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxDelayedTaskList, ulTotalRunTime ); + } + + if( listLIST_IS_EMPTY( pxOverflowDelayedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, ( xList * ) pxOverflowDelayedTaskList, ulTotalRunTime ); + } + + #if ( INCLUDE_vTaskDelete == 1 ) + { + if( listLIST_IS_EMPTY( &xTasksWaitingTermination ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xTasksWaitingTermination, ulTotalRunTime ); + } + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( listLIST_IS_EMPTY( &xSuspendedTaskList ) == pdFALSE ) + { + prvGenerateRunTimeStatsForTasksInList( pcWriteBuffer, &xSuspendedTaskList, ulTotalRunTime ); + } + } + #endif + } + xTaskResumeAll(); + } + +#endif +/*----------------------------------------------------------*/ + +#if ( INCLUDE_xTaskGetIdleTaskHandle == 1 ) + + xTaskHandle xTaskGetIdleTaskHandle( void ) + { + /* If xTaskGetIdleTaskHandle() is called before the scheduler has been + started, then xIdleTaskHandle will be NULL. */ + configASSERT( ( xIdleTaskHandle != NULL ) ); + return xIdleTaskHandle; + } + +#endif + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + * documented in task.h + *----------------------------------------------------------*/ + +void vTaskIncrementTick( void ) +{ +tskTCB * pxTCB; + + /* Called by the portable layer each time a tick interrupt occurs. + Increments the tick then checks to see if the new tick value will cause any + tasks to be unblocked. */ + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + ++xTickCount; + if( xTickCount == ( portTickType ) 0U ) + { + xList *pxTemp; + + /* Tick count has overflowed so we need to swap the delay lists. + If there are any items in pxDelayedTaskList here then there is + an error! */ + configASSERT( ( listLIST_IS_EMPTY( pxDelayedTaskList ) ) ); + + pxTemp = pxDelayedTaskList; + pxDelayedTaskList = pxOverflowDelayedTaskList; + pxOverflowDelayedTaskList = pxTemp; + xNumOfOverflows++; + + if( listLIST_IS_EMPTY( pxDelayedTaskList ) != pdFALSE ) + { + /* The new current delayed list is empty. Set + xNextTaskUnblockTime to the maximum possible value so it is + extremely unlikely that the + if( xTickCount >= xNextTaskUnblockTime ) test will pass until + there is an item in the delayed list. */ + xNextTaskUnblockTime = portMAX_DELAY; + } + else + { + /* The new current delayed list is not empty, get the value of + the item at the head of the delayed list. This is the time at + which the task at the head of the delayed list should be removed + from the Blocked state. */ + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedTaskList ); + xNextTaskUnblockTime = listGET_LIST_ITEM_VALUE( &( pxTCB->xGenericListItem ) ); + } + } + + /* See if this tick has made a timeout expire. */ + prvCheckDelayedTasks(); + } + else + { + ++uxMissedTicks; + + /* The tick hook gets called at regular intervals, even if the + scheduler is locked. */ + #if ( configUSE_TICK_HOOK == 1 ) + { + vApplicationTickHook(); + } + #endif + } + + #if ( configUSE_TICK_HOOK == 1 ) + { + /* Guard against the tick hook being called when the missed tick + count is being unwound (when the scheduler is being unlocked. */ + if( uxMissedTicks == ( unsigned portBASE_TYPE ) 0U ) + { + vApplicationTickHook(); + } + } + #endif + + traceTASK_INCREMENT_TICK( xTickCount ); +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) + { + tskTCB *xTCB; + + /* If xTask is NULL then we are setting our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + xTCB->pxTaskTag = pxHookFunction; + taskEXIT_CRITICAL(); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) + { + tskTCB *xTCB; + pdTASK_HOOK_CODE xReturn; + + /* If xTask is NULL then we are setting our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + /* Save the hook function in the TCB. A critical section is required as + the value can be accessed from an interrupt. */ + taskENTER_CRITICAL(); + xReturn = xTCB->pxTaskTag; + taskEXIT_CRITICAL(); + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_APPLICATION_TASK_TAG == 1 ) + + portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) + { + tskTCB *xTCB; + portBASE_TYPE xReturn; + + /* If xTask is NULL then we are calling our own task hook. */ + if( xTask == NULL ) + { + xTCB = ( tskTCB * ) pxCurrentTCB; + } + else + { + xTCB = ( tskTCB * ) xTask; + } + + if( xTCB->pxTaskTag != NULL ) + { + xReturn = xTCB->pxTaskTag( pvParameter ); + } + else + { + xReturn = pdFAIL; + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +void vTaskSwitchContext( void ) +{ + if( uxSchedulerSuspended != ( unsigned portBASE_TYPE ) pdFALSE ) + { + /* The scheduler is currently suspended - do not allow a context + switch. */ + xMissedYield = pdTRUE; + } + else + { + traceTASK_SWITCHED_OUT(); + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + unsigned long ulTempCounter; + + #ifdef portALT_GET_RUN_TIME_COUNTER_VALUE + portALT_GET_RUN_TIME_COUNTER_VALUE( ulTempCounter ); + #else + ulTempCounter = portGET_RUN_TIME_COUNTER_VALUE(); + #endif + + /* Add the amount of time the task has been running to the accumulated + time so far. The time the task started running was stored in + ulTaskSwitchedInTime. Note that there is no overflow protection here + so count values are only valid until the timer overflows. Generally + this will be about 1 hour assuming a 1uS timer increment. */ + pxCurrentTCB->ulRunTimeCounter += ( ulTempCounter - ulTaskSwitchedInTime ); + ulTaskSwitchedInTime = ulTempCounter; + } + #endif + + taskFIRST_CHECK_FOR_STACK_OVERFLOW(); + taskSECOND_CHECK_FOR_STACK_OVERFLOW(); + + /* Find the highest priority queue that contains ready tasks. */ + while( listLIST_IS_EMPTY( &( pxReadyTasksLists[ uxTopReadyPriority ] ) ) ) + { + configASSERT( uxTopReadyPriority ); + --uxTopReadyPriority; + } + + /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the tasks of the + same priority get an equal share of the processor time. */ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentTCB, &( pxReadyTasksLists[ uxTopReadyPriority ] ) ); + + traceTASK_SWITCHED_IN(); + } +} +/*-----------------------------------------------------------*/ + +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) +{ +portTickType xTimeToWake; + + configASSERT( pxEventList ); + + /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED. */ + + /* Place the event list item of the TCB in the appropriate event list. + This is placed in the list in priority order so the highest priority task + is the first to be woken by the event. */ + vListInsert( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); + + /* We must remove ourselves from the ready list before adding ourselves + to the blocked list as the same list item is used for both lists. We have + exclusive access to the ready lists as the scheduler is locked. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + if( xTicksToWait == portMAX_DELAY ) + { + /* Add ourselves to the suspended task list instead of a delayed task + list to ensure we are not woken by a timing event. We will block + indefinitely. */ + vListInsertEnd( ( xList * ) &xSuspendedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + } + #else + { + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + #endif +} +/*-----------------------------------------------------------*/ + +#if configUSE_TIMERS == 1 + + void vTaskPlaceOnEventListRestricted( const xList * const pxEventList, portTickType xTicksToWait ) + { + portTickType xTimeToWake; + + configASSERT( pxEventList ); + + /* This function should not be called by application code hence the + 'Restricted' in its name. It is not part of the public API. It is + designed for use by kernel code, and has special calling requirements - + it should be called from a critical section. */ + + + /* Place the event list item of the TCB in the appropriate event list. + In this case it is assume that this is the only task that is going to + be waiting on this event list, so the faster vListInsertEnd() function + can be used in place of vListInsert. */ + vListInsertEnd( ( xList * ) pxEventList, ( xListItem * ) &( pxCurrentTCB->xEventListItem ) ); + + /* We must remove this task from the ready list before adding it to the + blocked list as the same list item is used for both lists. This + function is called form a critical section. */ + vListRemove( ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + /* Calculate the time at which the task should be woken if the event does + not occur. This may overflow but this doesn't matter. */ + xTimeToWake = xTickCount + xTicksToWait; + prvAddCurrentTaskToDelayedList( xTimeToWake ); + } + +#endif /* configUSE_TIMERS */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) +{ +tskTCB *pxUnblockedTCB; +portBASE_TYPE xReturn; + + /* THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED OR THE + SCHEDULER SUSPENDED. It can also be called from within an ISR. */ + + /* The event list is sorted in priority order, so we can remove the + first in the list, remove the TCB from the delayed list, and add + it to the ready list. + + If an event is for a queue that is locked then this function will never + get called - the lock count on the queue will get modified instead. This + means we can always expect exclusive access to the event list here. + + This function assumes that a check has already been made to ensure that + pxEventList is not empty. */ + pxUnblockedTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); + configASSERT( pxUnblockedTCB ); + vListRemove( &( pxUnblockedTCB->xEventListItem ) ); + + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + vListRemove( &( pxUnblockedTCB->xGenericListItem ) ); + prvAddTaskToReadyQueue( pxUnblockedTCB ); + } + else + { + /* We cannot access the delayed or ready lists, so will hold this + task pending until the scheduler is resumed. */ + vListInsertEnd( ( xList * ) &( xPendingReadyList ), &( pxUnblockedTCB->xEventListItem ) ); + } + + if( pxUnblockedTCB->uxPriority >= pxCurrentTCB->uxPriority ) + { + /* Return true if the task removed from the event list has + a higher priority than the calling task. This allows + the calling task to know if it should force a context + switch now. */ + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) +{ + configASSERT( pxTimeOut ); + pxTimeOut->xOverflowCount = xNumOfOverflows; + pxTimeOut->xTimeOnEntering = xTickCount; +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) +{ +portBASE_TYPE xReturn; + + configASSERT( pxTimeOut ); + configASSERT( pxTicksToWait ); + + taskENTER_CRITICAL(); + { + #if ( INCLUDE_vTaskSuspend == 1 ) + /* If INCLUDE_vTaskSuspend is set to 1 and the block time specified is + the maximum block time then the task should block indefinitely, and + therefore never time out. */ + if( *pxTicksToWait == portMAX_DELAY ) + { + xReturn = pdFALSE; + } + else /* We are not blocking indefinitely, perform the checks below. */ + #endif + + if( ( xNumOfOverflows != pxTimeOut->xOverflowCount ) && ( ( portTickType ) xTickCount >= ( portTickType ) pxTimeOut->xTimeOnEntering ) ) + { + /* The tick count is greater than the time at which vTaskSetTimeout() + was called, but has also overflowed since vTaskSetTimeOut() was called. + It must have wrapped all the way around and gone past us again. This + passed since vTaskSetTimeout() was called. */ + xReturn = pdTRUE; + } + else if( ( ( portTickType ) ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ) ) < ( portTickType ) *pxTicksToWait ) + { + /* Not a genuine timeout. Adjust parameters for time remaining. */ + *pxTicksToWait -= ( ( portTickType ) xTickCount - ( portTickType ) pxTimeOut->xTimeOnEntering ); + vTaskSetTimeOutState( pxTimeOut ); + xReturn = pdFALSE; + } + else + { + xReturn = pdTRUE; + } + } + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vTaskMissedYield( void ) +{ + xMissedYield = pdTRUE; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + unsigned portBASE_TYPE uxTaskGetTaskNumber( xTaskHandle xTask ) + { + unsigned portBASE_TYPE uxReturn; + tskTCB *pxTCB; + + if( xTask != NULL ) + { + pxTCB = ( tskTCB * ) xTask; + uxReturn = pxTCB->uxTaskNumber; + } + else + { + uxReturn = 0U; + } + + return uxReturn; + } +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + void vTaskSetTaskNumber( xTaskHandle xTask, unsigned portBASE_TYPE uxHandle ) + { + tskTCB *pxTCB; + + if( xTask != NULL ) + { + pxTCB = ( tskTCB * ) xTask; + pxTCB->uxTaskNumber = uxHandle; + } + } +#endif + + +/* + * ----------------------------------------------------------- + * The Idle task. + * ---------------------------------------------------------- + * + * The portTASK_FUNCTION() macro is used to allow port/compiler specific + * language extensions. The equivalent prototype for this function is: + * + * void prvIdleTask( void *pvParameters ); + * + */ +static portTASK_FUNCTION( prvIdleTask, pvParameters ) +{ + /* Stop warnings. */ + ( void ) pvParameters; + + for( ;; ) + { + /* See if any tasks have been deleted. */ + prvCheckTasksWaitingTermination(); + + #if ( configUSE_PREEMPTION == 0 ) + { + /* If we are not using preemption we keep forcing a task switch to + see if any other task has become available. If we are using + preemption we don't need to do this as any task becoming available + will automatically get the processor anyway. */ + taskYIELD(); + } + #endif + + #if ( ( configUSE_PREEMPTION == 1 ) && ( configIDLE_SHOULD_YIELD == 1 ) ) + { + /* When using preemption tasks of equal priority will be + timesliced. If a task that is sharing the idle priority is ready + to run then the idle task should yield before the end of the + timeslice. + + A critical region is not required here as we are just reading from + the list, and an occasional incorrect value will not matter. If + the ready list at the idle priority contains more than one task + then a task other than the idle task is ready to execute. */ + if( listCURRENT_LIST_LENGTH( &( pxReadyTasksLists[ tskIDLE_PRIORITY ] ) ) > ( unsigned portBASE_TYPE ) 1 ) + { + taskYIELD(); + } + } + #endif + + #if ( configUSE_IDLE_HOOK == 1 ) + { + extern void vApplicationIdleHook( void ); + + /* Call the user defined function from within the idle task. This + allows the application designer to add background functionality + without the overhead of a separate task. + NOTE: vApplicationIdleHook() MUST NOT, UNDER ANY CIRCUMSTANCES, + CALL A FUNCTION THAT MIGHT BLOCK. */ + vApplicationIdleHook(); + } + #endif + } +} /*lint !e715 pvParameters is not accessed but all task functions require the same prototype. */ + + + + + + + +/*----------------------------------------------------------- + * File private functions documented at the top of the file. + *----------------------------------------------------------*/ + + + +static void prvInitialiseTCBVariables( tskTCB *pxTCB, const signed char * const pcName, unsigned portBASE_TYPE uxPriority, const xMemoryRegion * const xRegions, unsigned short usStackDepth ) +{ + /* Store the function name in the TCB. */ + #if configMAX_TASK_NAME_LEN > 1 + { + /* Don't bring strncpy into the build unnecessarily. */ + strncpy( ( char * ) pxTCB->pcTaskName, ( const char * ) pcName, ( unsigned short ) configMAX_TASK_NAME_LEN ); + } + #endif + pxTCB->pcTaskName[ ( unsigned short ) configMAX_TASK_NAME_LEN - ( unsigned short ) 1 ] = ( signed char ) '\0'; + + /* This is used as an array index so must ensure it's not too large. First + remove the privilege bit if one is present. */ + if( uxPriority >= configMAX_PRIORITIES ) + { + uxPriority = configMAX_PRIORITIES - ( unsigned portBASE_TYPE ) 1U; + } + + pxTCB->uxPriority = uxPriority; + #if ( configUSE_MUTEXES == 1 ) + { + pxTCB->uxBasePriority = uxPriority; + } + #endif + + vListInitialiseItem( &( pxTCB->xGenericListItem ) ); + vListInitialiseItem( &( pxTCB->xEventListItem ) ); + + /* Set the pxTCB as a link back from the xListItem. This is so we can get + back to the containing TCB from a generic item in a list. */ + listSET_LIST_ITEM_OWNER( &( pxTCB->xGenericListItem ), pxTCB ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); + listSET_LIST_ITEM_OWNER( &( pxTCB->xEventListItem ), pxTCB ); + + #if ( portCRITICAL_NESTING_IN_TCB == 1 ) + { + pxTCB->uxCriticalNesting = ( unsigned portBASE_TYPE ) 0U; + } + #endif + + #if ( configUSE_APPLICATION_TASK_TAG == 1 ) + { + pxTCB->pxTaskTag = NULL; + } + #endif + + #if ( configGENERATE_RUN_TIME_STATS == 1 ) + { + pxTCB->ulRunTimeCounter = 0UL; + } + #endif + + #if ( portUSING_MPU_WRAPPERS == 1 ) + { + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, pxTCB->pxStack, usStackDepth ); + } + #else + { + ( void ) xRegions; + ( void ) usStackDepth; + } + #endif +} +/*-----------------------------------------------------------*/ + +#if ( portUSING_MPU_WRAPPERS == 1 ) + + void vTaskAllocateMPURegions( xTaskHandle xTaskToModify, const xMemoryRegion * const xRegions ) + { + tskTCB *pxTCB; + + if( xTaskToModify == pxCurrentTCB ) + { + xTaskToModify = NULL; + } + + /* If null is passed in here then we are deleting ourselves. */ + pxTCB = prvGetTCBFromHandle( xTaskToModify ); + + vPortStoreTaskMPUSettings( &( pxTCB->xMPUSettings ), xRegions, NULL, 0 ); + } + /*-----------------------------------------------------------*/ +#endif + +static void prvInitialiseTaskLists( void ) +{ +unsigned portBASE_TYPE uxPriority; + + for( uxPriority = ( unsigned portBASE_TYPE ) 0U; uxPriority < configMAX_PRIORITIES; uxPriority++ ) + { + vListInitialise( ( xList * ) &( pxReadyTasksLists[ uxPriority ] ) ); + } + + vListInitialise( ( xList * ) &xDelayedTaskList1 ); + vListInitialise( ( xList * ) &xDelayedTaskList2 ); + vListInitialise( ( xList * ) &xPendingReadyList ); + + #if ( INCLUDE_vTaskDelete == 1 ) + { + vListInitialise( ( xList * ) &xTasksWaitingTermination ); + } + #endif + + #if ( INCLUDE_vTaskSuspend == 1 ) + { + vListInitialise( ( xList * ) &xSuspendedTaskList ); + } + #endif + + /* Start with pxDelayedTaskList using list1 and the pxOverflowDelayedTaskList + using list2. */ + pxDelayedTaskList = &xDelayedTaskList1; + pxOverflowDelayedTaskList = &xDelayedTaskList2; +} +/*-----------------------------------------------------------*/ + +static void prvCheckTasksWaitingTermination( void ) +{ + #if ( INCLUDE_vTaskDelete == 1 ) + { + portBASE_TYPE xListIsEmpty; + + /* ucTasksDeleted is used to prevent vTaskSuspendAll() being called + too often in the idle task. */ + if( uxTasksDeleted > ( unsigned portBASE_TYPE ) 0U ) + { + vTaskSuspendAll(); + xListIsEmpty = listLIST_IS_EMPTY( &xTasksWaitingTermination ); + xTaskResumeAll(); + + if( xListIsEmpty == pdFALSE ) + { + tskTCB *pxTCB; + + taskENTER_CRITICAL(); + { + pxTCB = ( tskTCB * ) listGET_OWNER_OF_HEAD_ENTRY( ( ( xList * ) &xTasksWaitingTermination ) ); + vListRemove( &( pxTCB->xGenericListItem ) ); + --uxCurrentNumberOfTasks; + --uxTasksDeleted; + } + taskEXIT_CRITICAL(); + + prvDeleteTCB( pxTCB ); + } + } + } + #endif +} +/*-----------------------------------------------------------*/ + +static void prvAddCurrentTaskToDelayedList( portTickType xTimeToWake ) +{ + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentTCB->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xTickCount ) + { + /* Wake time has overflowed. Place this item in the overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the current block list. */ + vListInsert( ( xList * ) pxDelayedTaskList, ( xListItem * ) &( pxCurrentTCB->xGenericListItem ) ); + + /* If the task entering the blocked state was placed at the head of the + list of blocked tasks then xNextTaskUnblockTime needs to be updated + too. */ + if( xTimeToWake < xNextTaskUnblockTime ) + { + xNextTaskUnblockTime = xTimeToWake; + } + } +} +/*-----------------------------------------------------------*/ + +static tskTCB *prvAllocateTCBAndStack( unsigned short usStackDepth, portSTACK_TYPE *puxStackBuffer ) +{ +tskTCB *pxNewTCB; + + /* Allocate space for the TCB. Where the memory comes from depends on + the implementation of the port malloc function. */ + pxNewTCB = ( tskTCB * ) pvPortMalloc( sizeof( tskTCB ) ); + + if( pxNewTCB != NULL ) + { + /* Allocate space for the stack used by the task being created. + The base of the stack memory stored in the TCB so the task can + be deleted later if required. */ + pxNewTCB->pxStack = ( portSTACK_TYPE * ) pvPortMallocAligned( ( ( ( size_t )usStackDepth ) * sizeof( portSTACK_TYPE ) ), puxStackBuffer ); + + if( pxNewTCB->pxStack == NULL ) + { + /* Could not allocate the stack. Delete the allocated TCB. */ + vPortFree( pxNewTCB ); + pxNewTCB = NULL; + } + else + { + /* Just to help debugging. */ + memset( pxNewTCB->pxStack, ( int ) tskSTACK_FILL_BYTE, ( size_t ) usStackDepth * sizeof( portSTACK_TYPE ) ); + } + } + + return pxNewTCB; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_TRACE_FACILITY == 1 ) + + static void prvListTaskWithinSingleList( const signed char *pcWriteBuffer, xList *pxList, signed char cStatus ) + { + volatile tskTCB *pxNextTCB, *pxFirstTCB; + unsigned short usStackRemaining; + PRIVILEGED_DATA static char pcStatusString[ configMAX_TASK_NAME_LEN + 30 ]; + + /* Write the details of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + #if ( portSTACK_GROWTH > 0 ) + { + usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxEndOfStack ); + } + #else + { + usStackRemaining = usTaskCheckFreeStackSpace( ( unsigned char * ) pxNextTCB->pxStack ); + } + #endif + + sprintf( pcStatusString, ( char * ) "%s\t\t%c\t%u\t%u\t%u\r\n", pxNextTCB->pcTaskName, cStatus, ( unsigned int ) pxNextTCB->uxPriority, usStackRemaining, ( unsigned int ) pxNextTCB->uxTCBNumber ); + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatusString ); + + } while( pxNextTCB != pxFirstTCB ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + static void prvGenerateRunTimeStatsForTasksInList( const signed char *pcWriteBuffer, xList *pxList, unsigned long ulTotalRunTime ) + { + volatile tskTCB *pxNextTCB, *pxFirstTCB; + unsigned long ulStatsAsPercentage; + + /* Write the run time stats of all the TCB's in pxList into the buffer. */ + listGET_OWNER_OF_NEXT_ENTRY( pxFirstTCB, pxList ); + do + { + /* Get next TCB in from the list. */ + listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList ); + + /* Divide by zero check. */ + if( ulTotalRunTime > 0UL ) + { + /* Has the task run at all? */ + if( pxNextTCB->ulRunTimeCounter == 0UL ) + { + /* The task has used no CPU time at all. */ + sprintf( pcStatsString, ( char * ) "%s\t\t0\t\t0%%\r\n", pxNextTCB->pcTaskName ); + } + else + { + /* What percentage of the total run time has the task used? + This will always be rounded down to the nearest integer. + ulTotalRunTime has already been divided by 100. */ + ulStatsAsPercentage = pxNextTCB->ulRunTimeCounter / ulTotalRunTime; + + if( ulStatsAsPercentage > 0UL ) + { + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t%lu%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter, ulStatsAsPercentage ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t%u%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter, ( unsigned int ) ulStatsAsPercentage ); + } + #endif + } + else + { + /* If the percentage is zero here then the task has + consumed less than 1% of the total run time. */ + #ifdef portLU_PRINTF_SPECIFIER_REQUIRED + { + sprintf( pcStatsString, ( char * ) "%s\t\t%lu\t\t<1%%\r\n", pxNextTCB->pcTaskName, pxNextTCB->ulRunTimeCounter ); + } + #else + { + /* sizeof( int ) == sizeof( long ) so a smaller + printf() library can be used. */ + sprintf( pcStatsString, ( char * ) "%s\t\t%u\t\t<1%%\r\n", pxNextTCB->pcTaskName, ( unsigned int ) pxNextTCB->ulRunTimeCounter ); + } + #endif + } + } + + strcat( ( char * ) pcWriteBuffer, ( char * ) pcStatsString ); + } + + } while( pxNextTCB != pxFirstTCB ); + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( ( configUSE_TRACE_FACILITY == 1 ) || ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) ) + + static unsigned short usTaskCheckFreeStackSpace( const unsigned char * pucStackByte ) + { + register unsigned short usCount = 0U; + + while( *pucStackByte == tskSTACK_FILL_BYTE ) + { + pucStackByte -= portSTACK_GROWTH; + usCount++; + } + + usCount /= sizeof( portSTACK_TYPE ); + + return usCount; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetRunTime == 1 ) + + unsigned portBASE_TYPE uxTaskGetRunTime( xTaskHandle xTask ) + { + unsigned long runTime; + + tskTCB *pxTCB; + pxTCB = prvGetTCBFromHandle( xTask ); + runTime = pxTCB->ulRunTimeCounter; + pxTCB->ulRunTimeCounter = 0; + return runTime; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_uxTaskGetStackHighWaterMark == 1 ) + + unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) + { + tskTCB *pxTCB; + unsigned char *pcEndOfStack; + unsigned portBASE_TYPE uxReturn; + + pxTCB = prvGetTCBFromHandle( xTask ); + + #if portSTACK_GROWTH < 0 + { + pcEndOfStack = ( unsigned char * ) pxTCB->pxStack; + } + #else + { + pcEndOfStack = ( unsigned char * ) pxTCB->pxEndOfStack; + } + #endif + + uxReturn = ( unsigned portBASE_TYPE ) usTaskCheckFreeStackSpace( pcEndOfStack ); + + return uxReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_vTaskDelete == 1 ) + + static void prvDeleteTCB( tskTCB *pxTCB ) + { + /* This call is required specifically for the TriCore port. It must be + above the vPortFree() calls. The call is also used by ports/demos that + want to allocate and clean RAM statically. */ + portCLEAN_UP_TCB( pxTCB ); + + /* Free up the memory allocated by the scheduler for the task. It is up to + the task to free any memory allocated at the application level. */ + vPortFreeAligned( pxTCB->pxStack ); + vPortFree( pxTCB ); + } + +#endif + + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetCurrentTaskHandle == 1 ) || ( configUSE_MUTEXES == 1 ) ) + + xTaskHandle xTaskGetCurrentTaskHandle( void ) + { + xTaskHandle xReturn; + + /* A critical section is not required as this is not called from + an interrupt and the current TCB will always be the same for any + individual execution thread. */ + xReturn = pxCurrentTCB; + + return xReturn; + } + +#endif + +/*-----------------------------------------------------------*/ + +#if ( ( INCLUDE_xTaskGetSchedulerState == 1 ) || ( configUSE_TIMERS == 1 ) ) + + portBASE_TYPE xTaskGetSchedulerState( void ) + { + portBASE_TYPE xReturn; + + if( xSchedulerRunning == pdFALSE ) + { + xReturn = taskSCHEDULER_NOT_STARTED; + } + else + { + if( uxSchedulerSuspended == ( unsigned portBASE_TYPE ) pdFALSE ) + { + xReturn = taskSCHEDULER_RUNNING; + } + else + { + xReturn = taskSCHEDULER_SUSPENDED; + } + } + + return xReturn; + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) + { + tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; + + configASSERT( pxMutexHolder ); + + if( pxTCB->uxPriority < pxCurrentTCB->uxPriority ) + { + /* Adjust the mutex holder state to account for its new priority. */ + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxCurrentTCB->uxPriority ); + + /* If the task being modified is in the ready state it will need to + be moved in to a new list. */ + if( listIS_CONTAINED_WITHIN( &( pxReadyTasksLists[ pxTCB->uxPriority ] ), &( pxTCB->xGenericListItem ) ) != pdFALSE ) + { + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Inherit the priority before being moved into the new list. */ + pxTCB->uxPriority = pxCurrentTCB->uxPriority; + prvAddTaskToReadyQueue( pxTCB ); + } + else + { + /* Just inherit the priority. */ + pxTCB->uxPriority = pxCurrentTCB->uxPriority; + } + + traceTASK_PRIORITY_INHERIT( pxTCB, pxCurrentTCB->uxPriority ); + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) + { + tskTCB * const pxTCB = ( tskTCB * ) pxMutexHolder; + + if( pxMutexHolder != NULL ) + { + if( pxTCB->uxPriority != pxTCB->uxBasePriority ) + { + /* We must be the running task to be able to give the mutex back. + Remove ourselves from the ready list we currently appear in. */ + vListRemove( &( pxTCB->xGenericListItem ) ); + + /* Disinherit the priority before adding the task into the new + ready list. */ + traceTASK_PRIORITY_DISINHERIT( pxTCB, pxTCB->uxBasePriority ); + pxTCB->uxPriority = pxTCB->uxBasePriority; + listSET_LIST_ITEM_VALUE( &( pxTCB->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) pxTCB->uxPriority ); + prvAddTaskToReadyQueue( pxTCB ); + } + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + + void vTaskEnterCritical( void ) + { + portDISABLE_INTERRUPTS(); + + if( xSchedulerRunning != pdFALSE ) + { + ( pxCurrentTCB->uxCriticalNesting )++; + } + } + +#endif +/*-----------------------------------------------------------*/ + +#if ( portCRITICAL_NESTING_IN_TCB == 1 ) + +void vTaskExitCritical( void ) +{ + if( xSchedulerRunning != pdFALSE ) + { + if( pxCurrentTCB->uxCriticalNesting > 0U ) + { + ( pxCurrentTCB->uxCriticalNesting )--; + + if( pxCurrentTCB->uxCriticalNesting == 0U ) + { + portENABLE_INTERRUPTS(); + } + } + } +} + +#endif +/*-----------------------------------------------------------*/ + + + + diff --git a/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c b/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c index 0be294277..9a7579f39 100755 --- a/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c +++ b/flight/PiOS/Common/Libraries/FreeRTOS/Source/timers.c @@ -1,686 +1,686 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "queue.h" -#include "timers.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* This entire source file will be skipped if the application is not configured -to include software timer functionality. This #if is closed at the very bottom -of this file. If you want to include software timer functionality then ensure -configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ -#if ( configUSE_TIMERS == 1 ) - -/* Misc definitions. */ -#define tmrNO_DELAY ( portTickType ) 0U - -/* The definition of the timers themselves. */ -typedef struct tmrTimerControl -{ - const signed char *pcTimerName; /*<< Text name. This is not used by the kernel, it is included simply to make debugging easier. */ - xListItem xTimerListItem; /*<< Standard linked list item as used by all kernel features for event management. */ - portTickType xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */ - unsigned portBASE_TYPE uxAutoReload; /*<< Set to pdTRUE if the timer should be automatically restarted once expired. Set to pdFALSE if the timer is, in effect, a one shot timer. */ - void *pvTimerID; /*<< An ID to identify the timer. This allows the timer to be identified when the same callback is used for multiple timers. */ - tmrTIMER_CALLBACK pxCallbackFunction; /*<< The function that will be called when the timer expires. */ -} xTIMER; - -/* The definition of messages that can be sent and received on the timer -queue. */ -typedef struct tmrTimerQueueMessage -{ - portBASE_TYPE xMessageID; /*<< The command being sent to the timer service task. */ - portTickType xMessageValue; /*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */ - xTIMER * pxTimer; /*<< The timer to which the command will be applied. */ -} xTIMER_MESSAGE; - - -/* The list in which active timers are stored. Timers are referenced in expire -time order, with the nearest expiry time at the front of the list. Only the -timer service task is allowed to access xActiveTimerList. */ -PRIVILEGED_DATA static xList xActiveTimerList1; -PRIVILEGED_DATA static xList xActiveTimerList2; -PRIVILEGED_DATA static xList *pxCurrentTimerList; -PRIVILEGED_DATA static xList *pxOverflowTimerList; - -/* A queue that is used to send commands to the timer service task. */ -PRIVILEGED_DATA static xQueueHandle xTimerQueue = NULL; - -#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) - - PRIVILEGED_DATA static xTaskHandle xTimerTaskHandle = NULL; - -#endif - -/*-----------------------------------------------------------*/ - -/* - * Initialise the infrastructure used by the timer service task if it has not - * been initialised already. - */ -static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION; - -/* - * The timer service task (daemon). Timer functionality is controlled by this - * task. Other tasks communicate with the timer service task using the - * xTimerQueue queue. - */ -static void prvTimerTask( void *pvParameters ) PRIVILEGED_FUNCTION; - -/* - * Called by the timer service task to interpret and process a command it - * received on the timer queue. - */ -static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION; - -/* - * Insert the timer into either xActiveTimerList1, or xActiveTimerList2, - * depending on if the expire time causes a timer counter overflow. - */ -static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) PRIVILEGED_FUNCTION; - -/* - * An active timer has reached its expire time. Reload the timer if it is an - * auto reload timer, then call its callback. - */ -static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) PRIVILEGED_FUNCTION; - -/* - * The tick count has overflowed. Switch the timer lists after ensuring the - * current timer list does not still reference some timers. - */ -static void prvSwitchTimerLists( portTickType xLastTime ) PRIVILEGED_FUNCTION; - -/* - * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE - * if a tick count overflow occurred since prvSampleTimeNow() was last called. - */ -static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION; - -/* - * If the timer list contains any active timers then return the expire time of - * the timer that will expire first and set *pxListWasEmpty to false. If the - * timer list does not contain any timers then return 0 and set *pxListWasEmpty - * to pdTRUE. - */ -static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) PRIVILEGED_FUNCTION; - -/* - * If a timer has expired, process it. Otherwise, block the timer service task - * until either a timer does expire or a command is received. - */ -static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) PRIVILEGED_FUNCTION; - -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerCreateTimerTask( void ) -{ -portBASE_TYPE xReturn = pdFAIL; - - /* This function is called when the scheduler is started if - configUSE_TIMERS is set to 1. Check that the infrastructure used by the - timer service task has been created/initialised. If timers have already - been created then the initialisation will already have been performed. */ - prvCheckForValidListAndQueue(); - - if( xTimerQueue != NULL ) - { - #if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) - { - /* Create the timer task, storing its handle in xTimerTaskHandle so - it can be returned by the xTimerGetTimerDaemonTaskHandle() function. */ - xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, &xTimerTaskHandle ); - } - #else - { - /* Create the timer task without storing its handle. */ - xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, NULL); - } - #endif - } - - configASSERT( xReturn ); - return xReturn; -} -/*-----------------------------------------------------------*/ - -xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void *pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) -{ -xTIMER *pxNewTimer; - - /* Allocate the timer structure. */ - if( xTimerPeriodInTicks == ( portTickType ) 0U ) - { - pxNewTimer = NULL; - configASSERT( ( xTimerPeriodInTicks > 0 ) ); - } - else - { - pxNewTimer = ( xTIMER * ) pvPortMalloc( sizeof( xTIMER ) ); - if( pxNewTimer != NULL ) - { - /* Ensure the infrastructure used by the timer service task has been - created/initialised. */ - prvCheckForValidListAndQueue(); - - /* Initialise the timer structure members using the function parameters. */ - pxNewTimer->pcTimerName = pcTimerName; - pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks; - pxNewTimer->uxAutoReload = uxAutoReload; - pxNewTimer->pvTimerID = pvTimerID; - pxNewTimer->pxCallbackFunction = pxCallbackFunction; - vListInitialiseItem( &( pxNewTimer->xTimerListItem ) ); - - traceTIMER_CREATE( pxNewTimer ); - } - else - { - traceTIMER_CREATE_FAILED(); - } - } - - return ( xTimerHandle ) pxNewTimer; -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) -{ -portBASE_TYPE xReturn = pdFAIL; -xTIMER_MESSAGE xMessage; - - /* Send a message to the timer service task to perform a particular action - on a particular timer definition. */ - if( xTimerQueue != NULL ) - { - /* Send a command to the timer service task to start the xTimer timer. */ - xMessage.xMessageID = xCommandID; - xMessage.xMessageValue = xOptionalValue; - xMessage.pxTimer = ( xTIMER * ) xTimer; - - if( pxHigherPriorityTaskWoken == NULL ) - { - if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING ) - { - xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xBlockTime ); - } - else - { - xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY ); - } - } - else - { - xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); - } - - traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn ); - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) - - xTaskHandle xTimerGetTimerDaemonTaskHandle( void ) - { - /* If xTimerGetTimerDaemonTaskHandle() is called before the scheduler has been - started, then xTimerTaskHandle will be NULL. */ - configASSERT( ( xTimerTaskHandle != NULL ) ); - return xTimerTaskHandle; - } - -#endif -/*-----------------------------------------------------------*/ - -static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) -{ -xTIMER *pxTimer; -portBASE_TYPE xResult; - - /* Remove the timer from the list of active timers. A check has already - been performed to ensure the list is not empty. */ - pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); - vListRemove( &( pxTimer->xTimerListItem ) ); - traceTIMER_EXPIRED( pxTimer ); - - /* If the timer is an auto reload timer then calculate the next - expiry time and re-insert the timer in the list of active timers. */ - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - /* This is the only time a timer is inserted into a list using - a time relative to anything other than the current time. It - will therefore be inserted into the correct list relative to - the time this task thinks it is now, even if a command to - switch lists due to a tick count overflow is already waiting in - the timer queue. */ - if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) == pdTRUE ) - { - /* The timer expired before it was added to the active timer - list. Reload it now. */ - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - - /* Call the timer callback. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); -} -/*-----------------------------------------------------------*/ - -static void prvTimerTask( void *pvParameters ) -{ -portTickType xNextExpireTime; -portBASE_TYPE xListWasEmpty; - - /* Just to avoid compiler warnings. */ - ( void ) pvParameters; - - for( ;; ) - { - /* Query the timers list to see if it contains any timers, and if so, - obtain the time at which the next timer will expire. */ - xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty ); - - /* If a timer has expired, process it. Otherwise, block this task - until either a timer does expire, or a command is received. */ - prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty ); - - /* Empty the command queue. */ - prvProcessReceivedCommands(); - } -} -/*-----------------------------------------------------------*/ - -static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) -{ -portTickType xTimeNow; -portBASE_TYPE xTimerListsWereSwitched; - - vTaskSuspendAll(); - { - /* Obtain the time now to make an assessment as to whether the timer - has expired or not. If obtaining the time causes the lists to switch - then don't process this timer as any timers that remained in the list - when the lists were switched will have been processed within the - prvSampelTimeNow() function. */ - xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); - if( xTimerListsWereSwitched == pdFALSE ) - { - /* The tick count has not overflowed, has the timer expired? */ - if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) ) - { - xTaskResumeAll(); - prvProcessExpiredTimer( xNextExpireTime, xTimeNow ); - } - else - { - /* The tick count has not overflowed, and the next expire - time has not been reached yet. This task should therefore - block to wait for the next expire time or a command to be - received - whichever comes first. The following line cannot - be reached unless xNextExpireTime > xTimeNow, except in the - case when the current timer list is empty. */ - vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ) ); - - if( xTaskResumeAll() == pdFALSE ) - { - /* Yield to wait for either a command to arrive, or the block time - to expire. If a command arrived between the critical section being - exited and this yield then the yield will not cause the task - to block. */ - portYIELD_WITHIN_API(); - } - } - } - else - { - xTaskResumeAll(); - } - } -} -/*-----------------------------------------------------------*/ - -static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) -{ -portTickType xNextExpireTime; - - /* Timers are listed in expiry time order, with the head of the list - referencing the task that will expire first. Obtain the time at which - the timer with the nearest expiry time will expire. If there are no - active timers then just set the next expire time to 0. That will cause - this task to unblock when the tick count overflows, at which point the - timer lists will be switched and the next expiry time can be - re-assessed. */ - *pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList ); - if( *pxListWasEmpty == pdFALSE ) - { - xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); - } - else - { - /* Ensure the task unblocks when the tick count rolls over. */ - xNextExpireTime = ( portTickType ) 0U; - } - - return xNextExpireTime; -} -/*-----------------------------------------------------------*/ - -static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) -{ -portTickType xTimeNow; -PRIVILEGED_DATA static portTickType xLastTime = ( portTickType ) 0U; - - xTimeNow = xTaskGetTickCount(); - - if( xTimeNow < xLastTime ) - { - prvSwitchTimerLists( xLastTime ); - *pxTimerListsWereSwitched = pdTRUE; - } - else - { - *pxTimerListsWereSwitched = pdFALSE; - } - - xLastTime = xTimeNow; - - return xTimeNow; -} -/*-----------------------------------------------------------*/ - -static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) -{ -portBASE_TYPE xProcessTimerNow = pdFALSE; - - listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime ); - listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); - - if( xNextExpiryTime <= xTimeNow ) - { - /* Has the expiry time elapsed between the command to start/reset a - timer was issued, and the time the command was processed? */ - if( ( ( portTickType ) ( xTimeNow - xCommandTime ) ) >= pxTimer->xTimerPeriodInTicks ) - { - /* The time between a command being issued and the command being - processed actually exceeds the timers period. */ - xProcessTimerNow = pdTRUE; - } - else - { - vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) ); - } - } - else - { - if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) ) - { - /* If, since the command was issued, the tick count has overflowed - but the expiry time has not, then the timer must have already passed - its expiry time and should be processed immediately. */ - xProcessTimerNow = pdTRUE; - } - else - { - vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); - } - } - - return xProcessTimerNow; -} -/*-----------------------------------------------------------*/ - -static void prvProcessReceivedCommands( void ) -{ -xTIMER_MESSAGE xMessage; -xTIMER *pxTimer; -portBASE_TYPE xTimerListsWereSwitched, xResult; -portTickType xTimeNow; - - /* In this case the xTimerListsWereSwitched parameter is not used, but it - must be present in the function call. */ - xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); - - while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) - { - pxTimer = xMessage.pxTimer; - - /* Is the timer already in a list of active timers? When the command - is trmCOMMAND_PROCESS_TIMER_OVERFLOW, the timer will be NULL as the - command is to the task rather than to an individual timer. */ - if( pxTimer != NULL ) - { - if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE ) - { - /* The timer is in a list, remove it. */ - vListRemove( &( pxTimer->xTimerListItem ) ); - } - } - - traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.xMessageValue ); - - switch( xMessage.xMessageID ) - { - case tmrCOMMAND_START : - /* Start or restart a timer. */ - if( prvInsertTimerInActiveList( pxTimer, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.xMessageValue ) == pdTRUE ) - { - /* The timer expired before it was added to the active timer - list. Process it now. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); - - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - break; - - case tmrCOMMAND_STOP : - /* The timer has already been removed from the active list. - There is nothing to do here. */ - break; - - case tmrCOMMAND_CHANGE_PERIOD : - pxTimer->xTimerPeriodInTicks = xMessage.xMessageValue; - configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) ); - prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow ); - break; - - case tmrCOMMAND_DELETE : - /* The timer has already been removed from the active list, - just free up the memory. */ - vPortFree( pxTimer ); - break; - - default : - /* Don't expect to get here. */ - break; - } - } -} -/*-----------------------------------------------------------*/ - -static void prvSwitchTimerLists( portTickType xLastTime ) -{ -portTickType xNextExpireTime, xReloadTime; -xList *pxTemp; -xTIMER *pxTimer; -portBASE_TYPE xResult; - - /* Remove compiler warnings if configASSERT() is not defined. */ - ( void ) xLastTime; - - /* The tick count has overflowed. The timer lists must be switched. - If there are any timers still referenced from the current timer list - then they must have expired and should be processed before the lists - are switched. */ - while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE ) - { - xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); - - /* Remove the timer from the list. */ - pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); - vListRemove( &( pxTimer->xTimerListItem ) ); - - /* Execute its callback, then send a command to restart the timer if - it is an auto-reload timer. It cannot be restarted here as the lists - have not yet been switched. */ - pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); - - if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) - { - /* Calculate the reload value, and if the reload value results in - the timer going into the same timer list then it has already expired - and the timer should be re-inserted into the current list so it is - processed again within this loop. Otherwise a command should be sent - to restart the timer to ensure it is only inserted into a list after - the lists have been swapped. */ - xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ); - if( xReloadTime > xNextExpireTime ) - { - listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime ); - listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); - vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); - } - else - { - xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); - configASSERT( xResult ); - ( void ) xResult; - } - } - } - - pxTemp = pxCurrentTimerList; - pxCurrentTimerList = pxOverflowTimerList; - pxOverflowTimerList = pxTemp; -} -/*-----------------------------------------------------------*/ - -static void prvCheckForValidListAndQueue( void ) -{ - /* Check that the list from which active timers are referenced, and the - queue used to communicate with the timer service, have been - initialised. */ - taskENTER_CRITICAL(); - { - if( xTimerQueue == NULL ) - { - vListInitialise( &xActiveTimerList1 ); - vListInitialise( &xActiveTimerList2 ); - pxCurrentTimerList = &xActiveTimerList1; - pxOverflowTimerList = &xActiveTimerList2; - xTimerQueue = xQueueCreate( ( unsigned portBASE_TYPE ) configTIMER_QUEUE_LENGTH, sizeof( xTIMER_MESSAGE ) ); - } - } - taskEXIT_CRITICAL(); -} -/*-----------------------------------------------------------*/ - -portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) -{ -portBASE_TYPE xTimerIsInActiveList; -xTIMER *pxTimer = ( xTIMER * ) xTimer; - - /* Is the timer in the list of active timers? */ - taskENTER_CRITICAL(); - { - /* Checking to see if it is in the NULL list in effect checks to see if - it is referenced from either the current or the overflow timer lists in - one go, but the logic has to be reversed, hence the '!'. */ - xTimerIsInActiveList = !( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) ); - } - taskEXIT_CRITICAL(); - - return xTimerIsInActiveList; -} -/*-----------------------------------------------------------*/ - -void *pvTimerGetTimerID( xTimerHandle xTimer ) -{ -xTIMER *pxTimer = ( xTIMER * ) xTimer; - - return pxTimer->pvTimerID; -} -/*-----------------------------------------------------------*/ - -/* This entire source file will be skipped if the application is not configured -to include software timer functionality. If you want to include software timer -functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ -#endif /* configUSE_TIMERS == 1 */ +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "timers.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. This #if is closed at the very bottom +of this file. If you want to include software timer functionality then ensure +configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#if ( configUSE_TIMERS == 1 ) + +/* Misc definitions. */ +#define tmrNO_DELAY ( portTickType ) 0U + +/* The definition of the timers themselves. */ +typedef struct tmrTimerControl +{ + const signed char *pcTimerName; /*<< Text name. This is not used by the kernel, it is included simply to make debugging easier. */ + xListItem xTimerListItem; /*<< Standard linked list item as used by all kernel features for event management. */ + portTickType xTimerPeriodInTicks;/*<< How quickly and often the timer expires. */ + unsigned portBASE_TYPE uxAutoReload; /*<< Set to pdTRUE if the timer should be automatically restarted once expired. Set to pdFALSE if the timer is, in effect, a one shot timer. */ + void *pvTimerID; /*<< An ID to identify the timer. This allows the timer to be identified when the same callback is used for multiple timers. */ + tmrTIMER_CALLBACK pxCallbackFunction; /*<< The function that will be called when the timer expires. */ +} xTIMER; + +/* The definition of messages that can be sent and received on the timer +queue. */ +typedef struct tmrTimerQueueMessage +{ + portBASE_TYPE xMessageID; /*<< The command being sent to the timer service task. */ + portTickType xMessageValue; /*<< An optional value used by a subset of commands, for example, when changing the period of a timer. */ + xTIMER * pxTimer; /*<< The timer to which the command will be applied. */ +} xTIMER_MESSAGE; + + +/* The list in which active timers are stored. Timers are referenced in expire +time order, with the nearest expiry time at the front of the list. Only the +timer service task is allowed to access xActiveTimerList. */ +PRIVILEGED_DATA static xList xActiveTimerList1; +PRIVILEGED_DATA static xList xActiveTimerList2; +PRIVILEGED_DATA static xList *pxCurrentTimerList; +PRIVILEGED_DATA static xList *pxOverflowTimerList; + +/* A queue that is used to send commands to the timer service task. */ +PRIVILEGED_DATA static xQueueHandle xTimerQueue = NULL; + +#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + + PRIVILEGED_DATA static xTaskHandle xTimerTaskHandle = NULL; + +#endif + +/*-----------------------------------------------------------*/ + +/* + * Initialise the infrastructure used by the timer service task if it has not + * been initialised already. + */ +static void prvCheckForValidListAndQueue( void ) PRIVILEGED_FUNCTION; + +/* + * The timer service task (daemon). Timer functionality is controlled by this + * task. Other tasks communicate with the timer service task using the + * xTimerQueue queue. + */ +static void prvTimerTask( void *pvParameters ) PRIVILEGED_FUNCTION; + +/* + * Called by the timer service task to interpret and process a command it + * received on the timer queue. + */ +static void prvProcessReceivedCommands( void ) PRIVILEGED_FUNCTION; + +/* + * Insert the timer into either xActiveTimerList1, or xActiveTimerList2, + * depending on if the expire time causes a timer counter overflow. + */ +static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) PRIVILEGED_FUNCTION; + +/* + * An active timer has reached its expire time. Reload the timer if it is an + * auto reload timer, then call its callback. + */ +static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) PRIVILEGED_FUNCTION; + +/* + * The tick count has overflowed. Switch the timer lists after ensuring the + * current timer list does not still reference some timers. + */ +static void prvSwitchTimerLists( portTickType xLastTime ) PRIVILEGED_FUNCTION; + +/* + * Obtain the current tick count, setting *pxTimerListsWereSwitched to pdTRUE + * if a tick count overflow occurred since prvSampleTimeNow() was last called. + */ +static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) PRIVILEGED_FUNCTION; + +/* + * If the timer list contains any active timers then return the expire time of + * the timer that will expire first and set *pxListWasEmpty to false. If the + * timer list does not contain any timers then return 0 and set *pxListWasEmpty + * to pdTRUE. + */ +static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) PRIVILEGED_FUNCTION; + +/* + * If a timer has expired, process it. Otherwise, block the timer service task + * until either a timer does expire or a command is received. + */ +static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) PRIVILEGED_FUNCTION; + +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerCreateTimerTask( void ) +{ +portBASE_TYPE xReturn = pdFAIL; + + /* This function is called when the scheduler is started if + configUSE_TIMERS is set to 1. Check that the infrastructure used by the + timer service task has been created/initialised. If timers have already + been created then the initialisation will already have been performed. */ + prvCheckForValidListAndQueue(); + + if( xTimerQueue != NULL ) + { + #if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + { + /* Create the timer task, storing its handle in xTimerTaskHandle so + it can be returned by the xTimerGetTimerDaemonTaskHandle() function. */ + xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, &xTimerTaskHandle ); + } + #else + { + /* Create the timer task without storing its handle. */ + xReturn = xTaskCreate( prvTimerTask, ( const signed char * ) "Tmr Svc", ( unsigned short ) configTIMER_TASK_STACK_DEPTH, NULL, ( ( unsigned portBASE_TYPE ) configTIMER_TASK_PRIORITY ) | portPRIVILEGE_BIT, NULL); + } + #endif + } + + configASSERT( xReturn ); + return xReturn; +} +/*-----------------------------------------------------------*/ + +xTimerHandle xTimerCreate( const signed char *pcTimerName, portTickType xTimerPeriodInTicks, unsigned portBASE_TYPE uxAutoReload, void *pvTimerID, tmrTIMER_CALLBACK pxCallbackFunction ) +{ +xTIMER *pxNewTimer; + + /* Allocate the timer structure. */ + if( xTimerPeriodInTicks == ( portTickType ) 0U ) + { + pxNewTimer = NULL; + configASSERT( ( xTimerPeriodInTicks > 0 ) ); + } + else + { + pxNewTimer = ( xTIMER * ) pvPortMalloc( sizeof( xTIMER ) ); + if( pxNewTimer != NULL ) + { + /* Ensure the infrastructure used by the timer service task has been + created/initialised. */ + prvCheckForValidListAndQueue(); + + /* Initialise the timer structure members using the function parameters. */ + pxNewTimer->pcTimerName = pcTimerName; + pxNewTimer->xTimerPeriodInTicks = xTimerPeriodInTicks; + pxNewTimer->uxAutoReload = uxAutoReload; + pxNewTimer->pvTimerID = pvTimerID; + pxNewTimer->pxCallbackFunction = pxCallbackFunction; + vListInitialiseItem( &( pxNewTimer->xTimerListItem ) ); + + traceTIMER_CREATE( pxNewTimer ); + } + else + { + traceTIMER_CREATE_FAILED(); + } + } + + return ( xTimerHandle ) pxNewTimer; +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerGenericCommand( xTimerHandle xTimer, portBASE_TYPE xCommandID, portTickType xOptionalValue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portTickType xBlockTime ) +{ +portBASE_TYPE xReturn = pdFAIL; +xTIMER_MESSAGE xMessage; + + /* Send a message to the timer service task to perform a particular action + on a particular timer definition. */ + if( xTimerQueue != NULL ) + { + /* Send a command to the timer service task to start the xTimer timer. */ + xMessage.xMessageID = xCommandID; + xMessage.xMessageValue = xOptionalValue; + xMessage.pxTimer = ( xTIMER * ) xTimer; + + if( pxHigherPriorityTaskWoken == NULL ) + { + if( xTaskGetSchedulerState() == taskSCHEDULER_RUNNING ) + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, xBlockTime ); + } + else + { + xReturn = xQueueSendToBack( xTimerQueue, &xMessage, tmrNO_DELAY ); + } + } + else + { + xReturn = xQueueSendToBackFromISR( xTimerQueue, &xMessage, pxHigherPriorityTaskWoken ); + } + + traceTIMER_COMMAND_SEND( xTimer, xCommandID, xOptionalValue, xReturn ); + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if ( INCLUDE_xTimerGetTimerDaemonTaskHandle == 1 ) + + xTaskHandle xTimerGetTimerDaemonTaskHandle( void ) + { + /* If xTimerGetTimerDaemonTaskHandle() is called before the scheduler has been + started, then xTimerTaskHandle will be NULL. */ + configASSERT( ( xTimerTaskHandle != NULL ) ); + return xTimerTaskHandle; + } + +#endif +/*-----------------------------------------------------------*/ + +static void prvProcessExpiredTimer( portTickType xNextExpireTime, portTickType xTimeNow ) +{ +xTIMER *pxTimer; +portBASE_TYPE xResult; + + /* Remove the timer from the list of active timers. A check has already + been performed to ensure the list is not empty. */ + pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); + vListRemove( &( pxTimer->xTimerListItem ) ); + traceTIMER_EXPIRED( pxTimer ); + + /* If the timer is an auto reload timer then calculate the next + expiry time and re-insert the timer in the list of active timers. */ + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + /* This is the only time a timer is inserted into a list using + a time relative to anything other than the current time. It + will therefore be inserted into the correct list relative to + the time this task thinks it is now, even if a command to + switch lists due to a tick count overflow is already waiting in + the timer queue. */ + if( prvInsertTimerInActiveList( pxTimer, ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ), xTimeNow, xNextExpireTime ) == pdTRUE ) + { + /* The timer expired before it was added to the active timer + list. Reload it now. */ + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + + /* Call the timer callback. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); +} +/*-----------------------------------------------------------*/ + +static void prvTimerTask( void *pvParameters ) +{ +portTickType xNextExpireTime; +portBASE_TYPE xListWasEmpty; + + /* Just to avoid compiler warnings. */ + ( void ) pvParameters; + + for( ;; ) + { + /* Query the timers list to see if it contains any timers, and if so, + obtain the time at which the next timer will expire. */ + xNextExpireTime = prvGetNextExpireTime( &xListWasEmpty ); + + /* If a timer has expired, process it. Otherwise, block this task + until either a timer does expire, or a command is received. */ + prvProcessTimerOrBlockTask( xNextExpireTime, xListWasEmpty ); + + /* Empty the command queue. */ + prvProcessReceivedCommands(); + } +} +/*-----------------------------------------------------------*/ + +static void prvProcessTimerOrBlockTask( portTickType xNextExpireTime, portBASE_TYPE xListWasEmpty ) +{ +portTickType xTimeNow; +portBASE_TYPE xTimerListsWereSwitched; + + vTaskSuspendAll(); + { + /* Obtain the time now to make an assessment as to whether the timer + has expired or not. If obtaining the time causes the lists to switch + then don't process this timer as any timers that remained in the list + when the lists were switched will have been processed within the + prvSampelTimeNow() function. */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + if( xTimerListsWereSwitched == pdFALSE ) + { + /* The tick count has not overflowed, has the timer expired? */ + if( ( xListWasEmpty == pdFALSE ) && ( xNextExpireTime <= xTimeNow ) ) + { + xTaskResumeAll(); + prvProcessExpiredTimer( xNextExpireTime, xTimeNow ); + } + else + { + /* The tick count has not overflowed, and the next expire + time has not been reached yet. This task should therefore + block to wait for the next expire time or a command to be + received - whichever comes first. The following line cannot + be reached unless xNextExpireTime > xTimeNow, except in the + case when the current timer list is empty. */ + vQueueWaitForMessageRestricted( xTimerQueue, ( xNextExpireTime - xTimeNow ) ); + + if( xTaskResumeAll() == pdFALSE ) + { + /* Yield to wait for either a command to arrive, or the block time + to expire. If a command arrived between the critical section being + exited and this yield then the yield will not cause the task + to block. */ + portYIELD_WITHIN_API(); + } + } + } + else + { + xTaskResumeAll(); + } + } +} +/*-----------------------------------------------------------*/ + +static portTickType prvGetNextExpireTime( portBASE_TYPE *pxListWasEmpty ) +{ +portTickType xNextExpireTime; + + /* Timers are listed in expiry time order, with the head of the list + referencing the task that will expire first. Obtain the time at which + the timer with the nearest expiry time will expire. If there are no + active timers then just set the next expire time to 0. That will cause + this task to unblock when the tick count overflows, at which point the + timer lists will be switched and the next expiry time can be + re-assessed. */ + *pxListWasEmpty = listLIST_IS_EMPTY( pxCurrentTimerList ); + if( *pxListWasEmpty == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + } + else + { + /* Ensure the task unblocks when the tick count rolls over. */ + xNextExpireTime = ( portTickType ) 0U; + } + + return xNextExpireTime; +} +/*-----------------------------------------------------------*/ + +static portTickType prvSampleTimeNow( portBASE_TYPE *pxTimerListsWereSwitched ) +{ +portTickType xTimeNow; +PRIVILEGED_DATA static portTickType xLastTime = ( portTickType ) 0U; + + xTimeNow = xTaskGetTickCount(); + + if( xTimeNow < xLastTime ) + { + prvSwitchTimerLists( xLastTime ); + *pxTimerListsWereSwitched = pdTRUE; + } + else + { + *pxTimerListsWereSwitched = pdFALSE; + } + + xLastTime = xTimeNow; + + return xTimeNow; +} +/*-----------------------------------------------------------*/ + +static portBASE_TYPE prvInsertTimerInActiveList( xTIMER *pxTimer, portTickType xNextExpiryTime, portTickType xTimeNow, portTickType xCommandTime ) +{ +portBASE_TYPE xProcessTimerNow = pdFALSE; + + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xNextExpiryTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + + if( xNextExpiryTime <= xTimeNow ) + { + /* Has the expiry time elapsed between the command to start/reset a + timer was issued, and the time the command was processed? */ + if( ( ( portTickType ) ( xTimeNow - xCommandTime ) ) >= pxTimer->xTimerPeriodInTicks ) + { + /* The time between a command being issued and the command being + processed actually exceeds the timers period. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxOverflowTimerList, &( pxTimer->xTimerListItem ) ); + } + } + else + { + if( ( xTimeNow < xCommandTime ) && ( xNextExpiryTime >= xCommandTime ) ) + { + /* If, since the command was issued, the tick count has overflowed + but the expiry time has not, then the timer must have already passed + its expiry time and should be processed immediately. */ + xProcessTimerNow = pdTRUE; + } + else + { + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + } + + return xProcessTimerNow; +} +/*-----------------------------------------------------------*/ + +static void prvProcessReceivedCommands( void ) +{ +xTIMER_MESSAGE xMessage; +xTIMER *pxTimer; +portBASE_TYPE xTimerListsWereSwitched, xResult; +portTickType xTimeNow; + + /* In this case the xTimerListsWereSwitched parameter is not used, but it + must be present in the function call. */ + xTimeNow = prvSampleTimeNow( &xTimerListsWereSwitched ); + + while( xQueueReceive( xTimerQueue, &xMessage, tmrNO_DELAY ) != pdFAIL ) + { + pxTimer = xMessage.pxTimer; + + /* Is the timer already in a list of active timers? When the command + is trmCOMMAND_PROCESS_TIMER_OVERFLOW, the timer will be NULL as the + command is to the task rather than to an individual timer. */ + if( pxTimer != NULL ) + { + if( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) == pdFALSE ) + { + /* The timer is in a list, remove it. */ + vListRemove( &( pxTimer->xTimerListItem ) ); + } + } + + traceTIMER_COMMAND_RECEIVED( pxTimer, xMessage.xMessageID, xMessage.xMessageValue ); + + switch( xMessage.xMessageID ) + { + case tmrCOMMAND_START : + /* Start or restart a timer. */ + if( prvInsertTimerInActiveList( pxTimer, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, xTimeNow, xMessage.xMessageValue ) == pdTRUE ) + { + /* The timer expired before it was added to the active timer + list. Process it now. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); + + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xMessage.xMessageValue + pxTimer->xTimerPeriodInTicks, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + break; + + case tmrCOMMAND_STOP : + /* The timer has already been removed from the active list. + There is nothing to do here. */ + break; + + case tmrCOMMAND_CHANGE_PERIOD : + pxTimer->xTimerPeriodInTicks = xMessage.xMessageValue; + configASSERT( ( pxTimer->xTimerPeriodInTicks > 0 ) ); + prvInsertTimerInActiveList( pxTimer, ( xTimeNow + pxTimer->xTimerPeriodInTicks ), xTimeNow, xTimeNow ); + break; + + case tmrCOMMAND_DELETE : + /* The timer has already been removed from the active list, + just free up the memory. */ + vPortFree( pxTimer ); + break; + + default : + /* Don't expect to get here. */ + break; + } + } +} +/*-----------------------------------------------------------*/ + +static void prvSwitchTimerLists( portTickType xLastTime ) +{ +portTickType xNextExpireTime, xReloadTime; +xList *pxTemp; +xTIMER *pxTimer; +portBASE_TYPE xResult; + + /* Remove compiler warnings if configASSERT() is not defined. */ + ( void ) xLastTime; + + /* The tick count has overflowed. The timer lists must be switched. + If there are any timers still referenced from the current timer list + then they must have expired and should be processed before the lists + are switched. */ + while( listLIST_IS_EMPTY( pxCurrentTimerList ) == pdFALSE ) + { + xNextExpireTime = listGET_ITEM_VALUE_OF_HEAD_ENTRY( pxCurrentTimerList ); + + /* Remove the timer from the list. */ + pxTimer = ( xTIMER * ) listGET_OWNER_OF_HEAD_ENTRY( pxCurrentTimerList ); + vListRemove( &( pxTimer->xTimerListItem ) ); + + /* Execute its callback, then send a command to restart the timer if + it is an auto-reload timer. It cannot be restarted here as the lists + have not yet been switched. */ + pxTimer->pxCallbackFunction( ( xTimerHandle ) pxTimer ); + + if( pxTimer->uxAutoReload == ( unsigned portBASE_TYPE ) pdTRUE ) + { + /* Calculate the reload value, and if the reload value results in + the timer going into the same timer list then it has already expired + and the timer should be re-inserted into the current list so it is + processed again within this loop. Otherwise a command should be sent + to restart the timer to ensure it is only inserted into a list after + the lists have been swapped. */ + xReloadTime = ( xNextExpireTime + pxTimer->xTimerPeriodInTicks ); + if( xReloadTime > xNextExpireTime ) + { + listSET_LIST_ITEM_VALUE( &( pxTimer->xTimerListItem ), xReloadTime ); + listSET_LIST_ITEM_OWNER( &( pxTimer->xTimerListItem ), pxTimer ); + vListInsert( pxCurrentTimerList, &( pxTimer->xTimerListItem ) ); + } + else + { + xResult = xTimerGenericCommand( pxTimer, tmrCOMMAND_START, xNextExpireTime, NULL, tmrNO_DELAY ); + configASSERT( xResult ); + ( void ) xResult; + } + } + } + + pxTemp = pxCurrentTimerList; + pxCurrentTimerList = pxOverflowTimerList; + pxOverflowTimerList = pxTemp; +} +/*-----------------------------------------------------------*/ + +static void prvCheckForValidListAndQueue( void ) +{ + /* Check that the list from which active timers are referenced, and the + queue used to communicate with the timer service, have been + initialised. */ + taskENTER_CRITICAL(); + { + if( xTimerQueue == NULL ) + { + vListInitialise( &xActiveTimerList1 ); + vListInitialise( &xActiveTimerList2 ); + pxCurrentTimerList = &xActiveTimerList1; + pxOverflowTimerList = &xActiveTimerList2; + xTimerQueue = xQueueCreate( ( unsigned portBASE_TYPE ) configTIMER_QUEUE_LENGTH, sizeof( xTIMER_MESSAGE ) ); + } + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +portBASE_TYPE xTimerIsTimerActive( xTimerHandle xTimer ) +{ +portBASE_TYPE xTimerIsInActiveList; +xTIMER *pxTimer = ( xTIMER * ) xTimer; + + /* Is the timer in the list of active timers? */ + taskENTER_CRITICAL(); + { + /* Checking to see if it is in the NULL list in effect checks to see if + it is referenced from either the current or the overflow timer lists in + one go, but the logic has to be reversed, hence the '!'. */ + xTimerIsInActiveList = !( listIS_CONTAINED_WITHIN( NULL, &( pxTimer->xTimerListItem ) ) ); + } + taskEXIT_CRITICAL(); + + return xTimerIsInActiveList; +} +/*-----------------------------------------------------------*/ + +void *pvTimerGetTimerID( xTimerHandle xTimer ) +{ +xTIMER *pxTimer = ( xTIMER * ) xTimer; + + return pxTimer->pvTimerID; +} +/*-----------------------------------------------------------*/ + +/* This entire source file will be skipped if the application is not configured +to include software timer functionality. If you want to include software timer +functionality then ensure configUSE_TIMERS is set to 1 in FreeRTOSConfig.h. */ +#endif /* configUSE_TIMERS == 1 */ diff --git a/flight/PiOS/Common/pios_video.c b/flight/PiOS/Common/pios_video.c index eaf4d6cb7..679da1084 100644 --- a/flight/PiOS/Common/pios_video.c +++ b/flight/PiOS/Common/pios_video.c @@ -1,482 +1,482 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_VIDEO Code for OSD video generator - * @brief OSD generator, Parts from CL-OSD and SUPEROSD project - * @{ - * - * @file pios_video.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief OSD generator, Parts from CL-OSD and SUPEROSD projects - * @see The GNU Public License (GPL) Version 3 - * - ****************************************************************************** - */ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pios.h" - -#ifdef PIOS_INCLUDE_VIDEO - -// Private methods -static void configure_hsync_timers(); -static void stop_hsync_timers(); -static void reset_hsync_timers(); -static void prepare_line(uint32_t line_num); -static void flush_spi(); - -// Private variables -extern xSemaphoreHandle osdSemaphore; -static const struct pios_video_cfg * dev_cfg; - - -// Define the buffers. -// For 256x192 pixel mode: -// buffer0_level/buffer0_mask becomes buffer_level; and -// buffer1_level/buffer1_mask becomes buffer_mask; -// For 192x128 pixel mode, allocations are as the names are written. -// divide by 8 because two bytes to a word. -// Must be allocated in one block, so it is in a struct. -struct _buffers -{ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_VIDEO Code for OSD video generator + * @brief OSD generator, Parts from CL-OSD and SUPEROSD project + * @{ + * + * @file pios_video.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief OSD generator, Parts from CL-OSD and SUPEROSD projects + * @see The GNU Public License (GPL) Version 3 + * + ****************************************************************************** + */ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios.h" + +#ifdef PIOS_INCLUDE_VIDEO + +// Private methods +static void configure_hsync_timers(); +static void stop_hsync_timers(); +static void reset_hsync_timers(); +static void prepare_line(uint32_t line_num); +static void flush_spi(); + +// Private variables +extern xSemaphoreHandle osdSemaphore; +static const struct pios_video_cfg * dev_cfg; + + +// Define the buffers. +// For 256x192 pixel mode: +// buffer0_level/buffer0_mask becomes buffer_level; and +// buffer1_level/buffer1_mask becomes buffer_mask; +// For 192x128 pixel mode, allocations are as the names are written. +// divide by 8 because two bytes to a word. +// Must be allocated in one block, so it is in a struct. +struct _buffers +{ uint8_t buffer0_level[GRAPHICS_HEIGHT*GRAPHICS_WIDTH]; uint8_t buffer0_mask[GRAPHICS_HEIGHT*GRAPHICS_WIDTH]; uint8_t buffer1_level[GRAPHICS_HEIGHT*GRAPHICS_WIDTH]; uint8_t buffer1_mask[GRAPHICS_HEIGHT*GRAPHICS_WIDTH]; -} buffers; - -// Remove the struct definition (makes it easier to write for.) -#define buffer0_level (buffers.buffer0_level) -#define buffer0_mask (buffers.buffer0_mask) -#define buffer1_level (buffers.buffer1_level) -#define buffer1_mask (buffers.buffer1_mask) - -// We define pointers to each of these buffers. +} buffers; + +// Remove the struct definition (makes it easier to write for.) +#define buffer0_level (buffers.buffer0_level) +#define buffer0_mask (buffers.buffer0_mask) +#define buffer1_level (buffers.buffer1_level) +#define buffer1_mask (buffers.buffer1_mask) + +// We define pointers to each of these buffers. uint8_t *draw_buffer_level; uint8_t *draw_buffer_mask; uint8_t *disp_buffer_level; uint8_t *disp_buffer_mask; - -volatile uint8_t gLineType = LINE_TYPE_UNKNOWN; -volatile uint16_t gActiveLine = 0; -volatile uint16_t gActivePixmapLine = 0; -volatile uint16_t line=0; -volatile uint16_t Vsync_update=0; -volatile uint16_t Hsync_update=0; -static int16_t m_osdLines=0; - -/** - * swap_buffers: Swaps the two buffers. Contents in the display - * buffer is seen on the output and the display buffer becomes - * the new draw buffer. - */ -void swap_buffers() -{ - // While we could use XOR swap this is more reliable and - // dependable and it's only called a few times per second. - // Many compliers should optimise these to EXCH instructions. - uint8_t *tmp; - SWAP_BUFFS(tmp, disp_buffer_mask, draw_buffer_mask); - SWAP_BUFFS(tmp, disp_buffer_level, draw_buffer_level); -} - -bool PIOS_Hsync_ISR() -{ - // On tenth line prepare data which will start clocking out on GRAPHICS_LINE+1 - if(Hsync_update==GRAPHICS_LINE) - { - prepare_line(0); - gActiveLine = 1; - } - Hsync_update++; -} - -bool PIOS_Vsync_ISR() { - static portBASE_TYPE xHigherPriorityTaskWoken; - - xHigherPriorityTaskWoken = pdFALSE; - m_osdLines = gActiveLine; - - stop_hsync_timers(); - - // Wait for previous word to clock out of each - TIM_Cmd(dev_cfg->pixel_timer.timer, ENABLE); - flush_spi(); - TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); - - gActiveLine = 0; - Hsync_update = 0; - Vsync_update++; - if(Vsync_update>=2) - { - // load second image buffer - swap_buffers(); - Vsync_update=0; - - // trigger redraw every second field - xHigherPriorityTaskWoken = xSemaphoreGiveFromISR(osdSemaphore, &xHigherPriorityTaskWoken); - } - - portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); //portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); + +volatile uint8_t gLineType = LINE_TYPE_UNKNOWN; +volatile uint16_t gActiveLine = 0; +volatile uint16_t gActivePixmapLine = 0; +volatile uint16_t line=0; +volatile uint16_t Vsync_update=0; +volatile uint16_t Hsync_update=0; +static int16_t m_osdLines=0; + +/** + * swap_buffers: Swaps the two buffers. Contents in the display + * buffer is seen on the output and the display buffer becomes + * the new draw buffer. + */ +void swap_buffers() +{ + // While we could use XOR swap this is more reliable and + // dependable and it's only called a few times per second. + // Many compliers should optimise these to EXCH instructions. + uint8_t *tmp; + SWAP_BUFFS(tmp, disp_buffer_mask, draw_buffer_mask); + SWAP_BUFFS(tmp, disp_buffer_level, draw_buffer_level); +} + +bool PIOS_Hsync_ISR() +{ + // On tenth line prepare data which will start clocking out on GRAPHICS_LINE+1 + if(Hsync_update==GRAPHICS_LINE) + { + prepare_line(0); + gActiveLine = 1; + } + Hsync_update++; +} + +bool PIOS_Vsync_ISR() { + static portBASE_TYPE xHigherPriorityTaskWoken; + + xHigherPriorityTaskWoken = pdFALSE; + m_osdLines = gActiveLine; + + stop_hsync_timers(); + + // Wait for previous word to clock out of each + TIM_Cmd(dev_cfg->pixel_timer.timer, ENABLE); + flush_spi(); + TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); + + gActiveLine = 0; + Hsync_update = 0; + Vsync_update++; + if(Vsync_update>=2) + { + // load second image buffer + swap_buffers(); + Vsync_update=0; + + // trigger redraw every second field + xHigherPriorityTaskWoken = xSemaphoreGiveFromISR(osdSemaphore, &xHigherPriorityTaskWoken); + } + + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); //portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); return xHigherPriorityTaskWoken == pdTRUE; -} - -uint16_t PIOS_Video_GetOSDLines(void) { - return m_osdLines; -} - -/** - * Stops the pixel clock and ensures it ignores the rising edge. To be used after a - * vsync until the first line is to be displayed - */ -static void stop_hsync_timers() -{ - // This removes the slave mode configuration - TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); - TIM_InternalClockConfig(dev_cfg->pixel_timer.timer); -} - -const struct pios_tim_callbacks px_callback = { - .overflow = NULL, - .edge = NULL, -}; - -#ifdef PAL -const uint32_t period = 10; -const uint32_t dc = (10 / 2); -#else -const uint32_t period = 11; -const uint32_t dc = (11 / 2); -#endif -/** - * Reset the timer and configure for next call. Keeps them synced. Ideally this won't even be needed - * since I don't think the slave mode gets lost, and this can simply be disable timer - */ -uint32_t failcount = 0; -static void reset_hsync_timers() -{ - // Stop both timers - TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); - - uint32_t tim_id; - const struct pios_tim_channel *channels = &dev_cfg->hsync_capture; - - //BUG: This is nuts this line is needed. It simply results in allocating - //all the memory but somehow leaving it out breaks the timer functionality. - // I do not see how these can be related - if (failcount == 0) { - if(PIOS_TIM_InitChannels(&tim_id, channels, 1, &px_callback, 0) < 0) - failcount++; - } - - dev_cfg->pixel_timer.timer->CNT = 0xFFFF - 100; //dc; - - // Listen to Channel1 (HSYNC) - switch(dev_cfg->hsync_capture.timer_chan) { - case TIM_Channel_1: - TIM_SelectInputTrigger(dev_cfg->pixel_timer.timer, TIM_TS_TI1FP1); - break; - case TIM_Channel_2: - TIM_SelectInputTrigger(dev_cfg->pixel_timer.timer, TIM_TS_TI2FP2); - break; - default: - PIOS_Assert(0); - } - TIM_SelectSlaveMode(dev_cfg->pixel_timer.timer, TIM_SlaveMode_Trigger); -} - - -static void configure_hsync_timers() -{ - // Stop both timers - TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); - - // This is overkill but used for consistency. No interrupts used for pixel clock - // but this function calls the GPIO_Remap - uint32_t tim_id; - const struct pios_tim_channel *channels; - - // Init the channel to output the pixel clock - channels = &dev_cfg->pixel_timer; - PIOS_TIM_InitChannels(&tim_id, channels, 1, &px_callback, 0); - - // Init the channel to capture the pulse - channels = &dev_cfg->hsync_capture; - PIOS_TIM_InitChannels(&tim_id, channels, 1, &px_callback, 0); - - // Configure the input capture channel - TIM_ICInitTypeDef TIM_ICInitStructure; - switch(dev_cfg->hsync_capture.timer_chan) { - case TIM_Channel_1: - TIM_ICInitStructure.TIM_Channel = TIM_Channel_1; - break; - case TIM_Channel_2: - TIM_ICInitStructure.TIM_Channel = TIM_Channel_2; - break; - default: - PIOS_Assert(0); - } - TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; - //TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; - TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; - TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; - TIM_ICInitStructure.TIM_ICFilter = 0; - TIM_ICInit(dev_cfg->pixel_timer.timer, &TIM_ICInitStructure); - - // Set up the channel to output the pixel clock - switch(dev_cfg->pixel_timer.timer_chan) { - case TIM_Channel_1: - TIM_OC1Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); - TIM_OC1PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); - TIM_SetCompare1(dev_cfg->pixel_timer.timer, dc); - break; - case TIM_Channel_2: - TIM_OC2Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); - TIM_OC2PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); - TIM_SetCompare2(dev_cfg->pixel_timer.timer, dc); - break; - case TIM_Channel_3: - TIM_OC3Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); - TIM_OC3PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); - TIM_SetCompare3(dev_cfg->pixel_timer.timer, dc); - break; - case TIM_Channel_4: - TIM_OC4Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); - TIM_OC4PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); - TIM_SetCompare4(dev_cfg->pixel_timer.timer, dc); - break; - } - TIM_ARRPreloadConfig(dev_cfg->pixel_timer.timer, ENABLE); - TIM_CtrlPWMOutputs(dev_cfg->pixel_timer.timer, ENABLE); - - // This shouldn't be needed as it should come from the config struture. Something - // is clobbering that - TIM_PrescalerConfig(dev_cfg->pixel_timer.timer, 0, TIM_PSCReloadMode_Immediate); - TIM_SetAutoreload(dev_cfg->pixel_timer.timer, period); -} - -DMA_TypeDef * main_dma; -DMA_TypeDef * mask_dma; -DMA_Stream_TypeDef * main_stream; -DMA_Stream_TypeDef * mask_stream; -void PIOS_Video_Init(const struct pios_video_cfg * cfg) -{ - dev_cfg = cfg; // store config before enabling interrupt - - configure_hsync_timers(); - - /* needed for HW hack */ - const GPIO_InitTypeDef initStruct = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN , - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }; - GPIO_Init(GPIOC, &initStruct); - - /* SPI3 - MASKBUFFER */ - GPIO_Init(cfg->mask.sclk.gpio, (GPIO_InitTypeDef*)&(cfg->mask.sclk.init)); - GPIO_Init(cfg->mask.miso.gpio, (GPIO_InitTypeDef*)&(cfg->mask.miso.init)); - - /* SPI1 SLAVE FRAMEBUFFER */ - GPIO_Init(cfg->level.sclk.gpio, (GPIO_InitTypeDef*)&(cfg->level.sclk.init)); - GPIO_Init(cfg->level.miso.gpio, (GPIO_InitTypeDef*)&(cfg->level.miso.init)); - - if (cfg->mask.remap) { - GPIO_PinAFConfig(cfg->mask.sclk.gpio, - __builtin_ctz(cfg->mask.sclk.init.GPIO_Pin), - cfg->mask.remap); - GPIO_PinAFConfig(cfg->mask.miso.gpio, - __builtin_ctz(cfg->mask.miso.init.GPIO_Pin), - cfg->mask.remap); - } - if (cfg->level.remap) - { - GPIO_PinAFConfig(cfg->level.sclk.gpio, - __builtin_ctz(cfg->level.sclk.init.GPIO_Pin), - cfg->level.remap); - GPIO_PinAFConfig(cfg->level.miso.gpio, - __builtin_ctz(cfg->level.miso.init.GPIO_Pin), - cfg->level.remap); - } - - /* Initialize the SPI block */ - SPI_Init(cfg->level.regs, (SPI_InitTypeDef*)&(cfg->level.init)); - SPI_Init(cfg->mask.regs, (SPI_InitTypeDef*)&(cfg->mask.init)); - - /* Enable SPI */ - SPI_Cmd(cfg->level.regs, ENABLE); - SPI_Cmd(cfg->mask.regs, ENABLE); - - /* Configure DMA for SPI Tx SLAVE Maskbuffer */ - DMA_Cmd(cfg->mask.dma.tx.channel, DISABLE); - DMA_Init(cfg->mask.dma.tx.channel, (DMA_InitTypeDef*)&(cfg->mask.dma.tx.init)); - - /* Configure DMA for SPI Tx SLAVE Framebuffer*/ - DMA_Cmd(cfg->level.dma.tx.channel, DISABLE); - DMA_Init(cfg->level.dma.tx.channel, (DMA_InitTypeDef*)&(cfg->level.dma.tx.init)); - - /* Trigger interrupt when for half conversions too to indicate double buffer */ - DMA_ITConfig(cfg->level.dma.tx.channel, DMA_IT_TC, ENABLE); - - /* Configure and clear buffers */ - draw_buffer_level = buffer0_level; - draw_buffer_mask = buffer0_mask; - disp_buffer_level = buffer1_level; - disp_buffer_mask = buffer1_mask; - memset(disp_buffer_mask, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); - memset(disp_buffer_level, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); - memset(draw_buffer_mask, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); - memset(draw_buffer_level, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); - - /* Configure DMA interrupt */ - - NVIC_Init(&cfg->level.dma.irq.init); - - /* Enable SPI interrupts to DMA */ - SPI_I2S_DMACmd(cfg->mask.regs, SPI_I2S_DMAReq_Tx, ENABLE); - SPI_I2S_DMACmd(cfg->level.regs, SPI_I2S_DMAReq_Tx, ENABLE); - - mask_dma = DMA1; - main_dma = DMA2; - main_stream = cfg->level.dma.tx.channel; - mask_stream = cfg->mask.dma.tx.channel; - /* Configure the Video Line interrupt */ - PIOS_EXTI_Init(cfg->hsync); - PIOS_EXTI_Init(cfg->vsync); - - //set levels to zero - PIOS_Servo_Set(0,0); - PIOS_Servo_Set(1,0); -} - -/** - * Prepare the system to watch for a HSYNC pulse to trigger the pixel - * clock and clock out the next line - */ -static void prepare_line(uint32_t line_num) -{ - if(line_numpixel_timer.timer->CNT = dc; - - DMA_ClearFlag(dev_cfg->mask.dma.tx.channel, DMA_FLAG_TCIF7 | DMA_FLAG_HTIF7 | DMA_FLAG_FEIF7 | DMA_FLAG_TEIF7); - DMA_ClearFlag(dev_cfg->level.dma.tx.channel, DMA_FLAG_FEIF5 | DMA_FLAG_TEIF5); - - // Load new line - DMA_MemoryTargetConfig(dev_cfg->level.dma.tx.channel,(uint32_t)&disp_buffer_level[buf_offset],DMA_Memory_0); - DMA_MemoryTargetConfig(dev_cfg->mask.dma.tx.channel,(uint32_t)&disp_buffer_mask[buf_offset],DMA_Memory_0); - - // Enable DMA, Slave first - DMA_SetCurrDataCounter(dev_cfg->level.dma.tx.channel, BUFFER_LINE_LENGTH); - DMA_SetCurrDataCounter(dev_cfg->mask.dma.tx.channel, BUFFER_LINE_LENGTH); - - SPI_Cmd(dev_cfg->level.regs, ENABLE); - SPI_Cmd(dev_cfg->mask.regs, ENABLE); - - /* Enable SPI interrupts to DMA */ - SPI_I2S_DMACmd(dev_cfg->mask.regs, SPI_I2S_DMAReq_Tx, ENABLE); - SPI_I2S_DMACmd(dev_cfg->level.regs, SPI_I2S_DMAReq_Tx, ENABLE); - - DMA_Cmd(dev_cfg->level.dma.tx.channel, ENABLE); - DMA_Cmd(dev_cfg->mask.dma.tx.channel, ENABLE); - } - reset_hsync_timers(); -} - -void PIOS_VIDEO_DMA_Handler(void); -void DMA1_Stream7_IRQHandler(void) __attribute__ ((alias("PIOS_VIDEO_DMA_Handler"))); -void DMA2_Stream5_IRQHandler(void) __attribute__ ((alias("PIOS_VIDEO_DMA_Handler"))); - -/** - * Check both SPI for the stop sequence before disabling them - */ -static void flush_spi() -{ - bool level_empty = false; - bool mask_empty = false; - bool level_stopped = false; - bool mask_stopped = false; - - // Can't flush if clock not running - while((dev_cfg->pixel_timer.timer->CR1 & 0x0001) && ( !level_stopped | !mask_stopped )) { - - level_empty |= SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_TXE) == SET; - mask_empty |= SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_TXE) == SET; - - if (level_empty && !level_stopped) { // && SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_BSY) == RESET) { - SPI_Cmd(dev_cfg->level.regs, DISABLE); - level_stopped = true; - } - - if (mask_empty && !mask_stopped) { // && SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_BSY) == RESET) { - SPI_Cmd(dev_cfg->mask.regs, DISABLE); - mask_stopped = true; - } - } - /* - uint32_t i = 0; - while(SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_TXE) == RESET && i < 30000) i++; - while(SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_TXE) == RESET && i < 30000) i++; - while(SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_BSY) == SET && i < 30000) i++; - while(SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_BSY) == SET && i < 30000) i++;*/ - SPI_Cmd(dev_cfg->mask.regs, DISABLE); - SPI_Cmd(dev_cfg->level.regs, DISABLE); -} - -/** - * @brief Interrupt for half and full buffer transfer - */ -void PIOS_VIDEO_DMA_Handler(void) -{ - // Handle flags from stream channel - if (DMA_GetFlagStatus(dev_cfg->level.dma.tx.channel,DMA_FLAG_TCIF5)) { // whole double buffer filled - DMA_ClearFlag(dev_cfg->level.dma.tx.channel,DMA_FLAG_TCIF5); - if(gActiveLine < GRAPHICS_HEIGHT) - { - flush_spi(); - stop_hsync_timers(); - - dev_cfg->pixel_timer.timer->CNT = dc; - - prepare_line(gActiveLine); - } - else if(gActiveLine >= GRAPHICS_HEIGHT) - { - //last line completed - flush_spi(); - stop_hsync_timers(); - - // STOP DMA, master first - DMA_Cmd(dev_cfg->mask.dma.tx.channel, DISABLE); - DMA_Cmd(dev_cfg->level.dma.tx.channel, DISABLE); - } - gActiveLine++; - } - else if (DMA_GetFlagStatus(dev_cfg->level.dma.tx.channel,DMA_FLAG_HTIF5)) { - DMA_ClearFlag(dev_cfg->level.dma.tx.channel,DMA_FLAG_HTIF5); - } - else { - } -} - -#endif /* PIOS_INCLUDE_VIDEO */ +} + +uint16_t PIOS_Video_GetOSDLines(void) { + return m_osdLines; +} + +/** + * Stops the pixel clock and ensures it ignores the rising edge. To be used after a + * vsync until the first line is to be displayed + */ +static void stop_hsync_timers() +{ + // This removes the slave mode configuration + TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); + TIM_InternalClockConfig(dev_cfg->pixel_timer.timer); +} + +const struct pios_tim_callbacks px_callback = { + .overflow = NULL, + .edge = NULL, +}; + +#ifdef PAL +const uint32_t period = 10; +const uint32_t dc = (10 / 2); +#else +const uint32_t period = 11; +const uint32_t dc = (11 / 2); +#endif +/** + * Reset the timer and configure for next call. Keeps them synced. Ideally this won't even be needed + * since I don't think the slave mode gets lost, and this can simply be disable timer + */ +uint32_t failcount = 0; +static void reset_hsync_timers() +{ + // Stop both timers + TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); + + uint32_t tim_id; + const struct pios_tim_channel *channels = &dev_cfg->hsync_capture; + + //BUG: This is nuts this line is needed. It simply results in allocating + //all the memory but somehow leaving it out breaks the timer functionality. + // I do not see how these can be related + if (failcount == 0) { + if(PIOS_TIM_InitChannels(&tim_id, channels, 1, &px_callback, 0) < 0) + failcount++; + } + + dev_cfg->pixel_timer.timer->CNT = 0xFFFF - 100; //dc; + + // Listen to Channel1 (HSYNC) + switch(dev_cfg->hsync_capture.timer_chan) { + case TIM_Channel_1: + TIM_SelectInputTrigger(dev_cfg->pixel_timer.timer, TIM_TS_TI1FP1); + break; + case TIM_Channel_2: + TIM_SelectInputTrigger(dev_cfg->pixel_timer.timer, TIM_TS_TI2FP2); + break; + default: + PIOS_Assert(0); + } + TIM_SelectSlaveMode(dev_cfg->pixel_timer.timer, TIM_SlaveMode_Trigger); +} + + +static void configure_hsync_timers() +{ + // Stop both timers + TIM_Cmd(dev_cfg->pixel_timer.timer, DISABLE); + + // This is overkill but used for consistency. No interrupts used for pixel clock + // but this function calls the GPIO_Remap + uint32_t tim_id; + const struct pios_tim_channel *channels; + + // Init the channel to output the pixel clock + channels = &dev_cfg->pixel_timer; + PIOS_TIM_InitChannels(&tim_id, channels, 1, &px_callback, 0); + + // Init the channel to capture the pulse + channels = &dev_cfg->hsync_capture; + PIOS_TIM_InitChannels(&tim_id, channels, 1, &px_callback, 0); + + // Configure the input capture channel + TIM_ICInitTypeDef TIM_ICInitStructure; + switch(dev_cfg->hsync_capture.timer_chan) { + case TIM_Channel_1: + TIM_ICInitStructure.TIM_Channel = TIM_Channel_1; + break; + case TIM_Channel_2: + TIM_ICInitStructure.TIM_Channel = TIM_Channel_2; + break; + default: + PIOS_Assert(0); + } + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; + //TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStructure.TIM_ICFilter = 0; + TIM_ICInit(dev_cfg->pixel_timer.timer, &TIM_ICInitStructure); + + // Set up the channel to output the pixel clock + switch(dev_cfg->pixel_timer.timer_chan) { + case TIM_Channel_1: + TIM_OC1Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); + TIM_OC1PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); + TIM_SetCompare1(dev_cfg->pixel_timer.timer, dc); + break; + case TIM_Channel_2: + TIM_OC2Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); + TIM_OC2PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); + TIM_SetCompare2(dev_cfg->pixel_timer.timer, dc); + break; + case TIM_Channel_3: + TIM_OC3Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); + TIM_OC3PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); + TIM_SetCompare3(dev_cfg->pixel_timer.timer, dc); + break; + case TIM_Channel_4: + TIM_OC4Init(dev_cfg->pixel_timer.timer, &dev_cfg->tim_oc_init); + TIM_OC4PreloadConfig(dev_cfg->pixel_timer.timer, TIM_OCPreload_Enable); + TIM_SetCompare4(dev_cfg->pixel_timer.timer, dc); + break; + } + TIM_ARRPreloadConfig(dev_cfg->pixel_timer.timer, ENABLE); + TIM_CtrlPWMOutputs(dev_cfg->pixel_timer.timer, ENABLE); + + // This shouldn't be needed as it should come from the config struture. Something + // is clobbering that + TIM_PrescalerConfig(dev_cfg->pixel_timer.timer, 0, TIM_PSCReloadMode_Immediate); + TIM_SetAutoreload(dev_cfg->pixel_timer.timer, period); +} + +DMA_TypeDef * main_dma; +DMA_TypeDef * mask_dma; +DMA_Stream_TypeDef * main_stream; +DMA_Stream_TypeDef * mask_stream; +void PIOS_Video_Init(const struct pios_video_cfg * cfg) +{ + dev_cfg = cfg; // store config before enabling interrupt + + configure_hsync_timers(); + + /* needed for HW hack */ + const GPIO_InitTypeDef initStruct = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN , + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }; + GPIO_Init(GPIOC, &initStruct); + + /* SPI3 - MASKBUFFER */ + GPIO_Init(cfg->mask.sclk.gpio, (GPIO_InitTypeDef*)&(cfg->mask.sclk.init)); + GPIO_Init(cfg->mask.miso.gpio, (GPIO_InitTypeDef*)&(cfg->mask.miso.init)); + + /* SPI1 SLAVE FRAMEBUFFER */ + GPIO_Init(cfg->level.sclk.gpio, (GPIO_InitTypeDef*)&(cfg->level.sclk.init)); + GPIO_Init(cfg->level.miso.gpio, (GPIO_InitTypeDef*)&(cfg->level.miso.init)); + + if (cfg->mask.remap) { + GPIO_PinAFConfig(cfg->mask.sclk.gpio, + __builtin_ctz(cfg->mask.sclk.init.GPIO_Pin), + cfg->mask.remap); + GPIO_PinAFConfig(cfg->mask.miso.gpio, + __builtin_ctz(cfg->mask.miso.init.GPIO_Pin), + cfg->mask.remap); + } + if (cfg->level.remap) + { + GPIO_PinAFConfig(cfg->level.sclk.gpio, + __builtin_ctz(cfg->level.sclk.init.GPIO_Pin), + cfg->level.remap); + GPIO_PinAFConfig(cfg->level.miso.gpio, + __builtin_ctz(cfg->level.miso.init.GPIO_Pin), + cfg->level.remap); + } + + /* Initialize the SPI block */ + SPI_Init(cfg->level.regs, (SPI_InitTypeDef*)&(cfg->level.init)); + SPI_Init(cfg->mask.regs, (SPI_InitTypeDef*)&(cfg->mask.init)); + + /* Enable SPI */ + SPI_Cmd(cfg->level.regs, ENABLE); + SPI_Cmd(cfg->mask.regs, ENABLE); + + /* Configure DMA for SPI Tx SLAVE Maskbuffer */ + DMA_Cmd(cfg->mask.dma.tx.channel, DISABLE); + DMA_Init(cfg->mask.dma.tx.channel, (DMA_InitTypeDef*)&(cfg->mask.dma.tx.init)); + + /* Configure DMA for SPI Tx SLAVE Framebuffer*/ + DMA_Cmd(cfg->level.dma.tx.channel, DISABLE); + DMA_Init(cfg->level.dma.tx.channel, (DMA_InitTypeDef*)&(cfg->level.dma.tx.init)); + + /* Trigger interrupt when for half conversions too to indicate double buffer */ + DMA_ITConfig(cfg->level.dma.tx.channel, DMA_IT_TC, ENABLE); + + /* Configure and clear buffers */ + draw_buffer_level = buffer0_level; + draw_buffer_mask = buffer0_mask; + disp_buffer_level = buffer1_level; + disp_buffer_mask = buffer1_mask; + memset(disp_buffer_mask, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); + memset(disp_buffer_level, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); + memset(draw_buffer_mask, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); + memset(draw_buffer_level, 0, GRAPHICS_WIDTH*GRAPHICS_HEIGHT); + + /* Configure DMA interrupt */ + + NVIC_Init(&cfg->level.dma.irq.init); + + /* Enable SPI interrupts to DMA */ + SPI_I2S_DMACmd(cfg->mask.regs, SPI_I2S_DMAReq_Tx, ENABLE); + SPI_I2S_DMACmd(cfg->level.regs, SPI_I2S_DMAReq_Tx, ENABLE); + + mask_dma = DMA1; + main_dma = DMA2; + main_stream = cfg->level.dma.tx.channel; + mask_stream = cfg->mask.dma.tx.channel; + /* Configure the Video Line interrupt */ + PIOS_EXTI_Init(cfg->hsync); + PIOS_EXTI_Init(cfg->vsync); + + //set levels to zero + PIOS_Servo_Set(0,0); + PIOS_Servo_Set(1,0); +} + +/** + * Prepare the system to watch for a HSYNC pulse to trigger the pixel + * clock and clock out the next line + */ +static void prepare_line(uint32_t line_num) +{ + if(line_numpixel_timer.timer->CNT = dc; + + DMA_ClearFlag(dev_cfg->mask.dma.tx.channel, DMA_FLAG_TCIF7 | DMA_FLAG_HTIF7 | DMA_FLAG_FEIF7 | DMA_FLAG_TEIF7); + DMA_ClearFlag(dev_cfg->level.dma.tx.channel, DMA_FLAG_FEIF5 | DMA_FLAG_TEIF5); + + // Load new line + DMA_MemoryTargetConfig(dev_cfg->level.dma.tx.channel,(uint32_t)&disp_buffer_level[buf_offset],DMA_Memory_0); + DMA_MemoryTargetConfig(dev_cfg->mask.dma.tx.channel,(uint32_t)&disp_buffer_mask[buf_offset],DMA_Memory_0); + + // Enable DMA, Slave first + DMA_SetCurrDataCounter(dev_cfg->level.dma.tx.channel, BUFFER_LINE_LENGTH); + DMA_SetCurrDataCounter(dev_cfg->mask.dma.tx.channel, BUFFER_LINE_LENGTH); + + SPI_Cmd(dev_cfg->level.regs, ENABLE); + SPI_Cmd(dev_cfg->mask.regs, ENABLE); + + /* Enable SPI interrupts to DMA */ + SPI_I2S_DMACmd(dev_cfg->mask.regs, SPI_I2S_DMAReq_Tx, ENABLE); + SPI_I2S_DMACmd(dev_cfg->level.regs, SPI_I2S_DMAReq_Tx, ENABLE); + + DMA_Cmd(dev_cfg->level.dma.tx.channel, ENABLE); + DMA_Cmd(dev_cfg->mask.dma.tx.channel, ENABLE); + } + reset_hsync_timers(); +} + +void PIOS_VIDEO_DMA_Handler(void); +void DMA1_Stream7_IRQHandler(void) __attribute__ ((alias("PIOS_VIDEO_DMA_Handler"))); +void DMA2_Stream5_IRQHandler(void) __attribute__ ((alias("PIOS_VIDEO_DMA_Handler"))); + +/** + * Check both SPI for the stop sequence before disabling them + */ +static void flush_spi() +{ + bool level_empty = false; + bool mask_empty = false; + bool level_stopped = false; + bool mask_stopped = false; + + // Can't flush if clock not running + while((dev_cfg->pixel_timer.timer->CR1 & 0x0001) && ( !level_stopped | !mask_stopped )) { + + level_empty |= SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_TXE) == SET; + mask_empty |= SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_TXE) == SET; + + if (level_empty && !level_stopped) { // && SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_BSY) == RESET) { + SPI_Cmd(dev_cfg->level.regs, DISABLE); + level_stopped = true; + } + + if (mask_empty && !mask_stopped) { // && SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_BSY) == RESET) { + SPI_Cmd(dev_cfg->mask.regs, DISABLE); + mask_stopped = true; + } + } + /* + uint32_t i = 0; + while(SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_TXE) == RESET && i < 30000) i++; + while(SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_TXE) == RESET && i < 30000) i++; + while(SPI_I2S_GetFlagStatus(dev_cfg->level.regs ,SPI_I2S_FLAG_BSY) == SET && i < 30000) i++; + while(SPI_I2S_GetFlagStatus(dev_cfg->mask.regs ,SPI_I2S_FLAG_BSY) == SET && i < 30000) i++;*/ + SPI_Cmd(dev_cfg->mask.regs, DISABLE); + SPI_Cmd(dev_cfg->level.regs, DISABLE); +} + +/** + * @brief Interrupt for half and full buffer transfer + */ +void PIOS_VIDEO_DMA_Handler(void) +{ + // Handle flags from stream channel + if (DMA_GetFlagStatus(dev_cfg->level.dma.tx.channel,DMA_FLAG_TCIF5)) { // whole double buffer filled + DMA_ClearFlag(dev_cfg->level.dma.tx.channel,DMA_FLAG_TCIF5); + if(gActiveLine < GRAPHICS_HEIGHT) + { + flush_spi(); + stop_hsync_timers(); + + dev_cfg->pixel_timer.timer->CNT = dc; + + prepare_line(gActiveLine); + } + else if(gActiveLine >= GRAPHICS_HEIGHT) + { + //last line completed + flush_spi(); + stop_hsync_timers(); + + // STOP DMA, master first + DMA_Cmd(dev_cfg->mask.dma.tx.channel, DISABLE); + DMA_Cmd(dev_cfg->level.dma.tx.channel, DISABLE); + } + gActiveLine++; + } + else if (DMA_GetFlagStatus(dev_cfg->level.dma.tx.channel,DMA_FLAG_HTIF5)) { + DMA_ClearFlag(dev_cfg->level.dma.tx.channel,DMA_FLAG_HTIF5); + } + else { + } +} + +#endif /* PIOS_INCLUDE_VIDEO */ diff --git a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/core_cm3.c b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/core_cm3.c index d202e369b..e1c414f98 100755 --- a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/core_cm3.c +++ b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/core_cm3.c @@ -1,784 +1,784 @@ -/**************************************************************************//** - * @file core_cm3.c - * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Source File - * @version V1.30 - * @date 30. October 2009 - * - * @note - * Copyright (C) 2009 ARM Limited. All rights reserved. - * - * @par - * ARM Limited (ARM) is supplying this software for use with Cortex-M - * processor based microcontrollers. This file can be freely distributed - * within development tools that are supporting such ARM based processors. - * - * @par - * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED - * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. - * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR - * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. - * - ******************************************************************************/ - -#include - -/* define compiler specific symbols */ -#if defined ( __CC_ARM ) - #define __ASM __asm /*!< asm keyword for ARM Compiler */ - #define __INLINE __inline /*!< inline keyword for ARM Compiler */ - -#elif defined ( __ICCARM__ ) - #define __ASM __asm /*!< asm keyword for IAR Compiler */ - #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */ - -#elif defined ( __GNUC__ ) - #define __ASM __asm /*!< asm keyword for GNU Compiler */ - #define __INLINE inline /*!< inline keyword for GNU Compiler */ - -#elif defined ( __TASKING__ ) - #define __ASM __asm /*!< asm keyword for TASKING Compiler */ - #define __INLINE inline /*!< inline keyword for TASKING Compiler */ - -#endif - - -/* ################### Compiler specific Intrinsics ########################### */ - -#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ -/* ARM armcc specific functions */ - -/** - * @brief Return the Process Stack Pointer - * - * @return ProcessStackPointer - * - * Return the actual process stack pointer - */ -__ASM uint32_t __get_PSP(void) -{ - mrs r0, psp - bx lr -} - -/** - * @brief Set the Process Stack Pointer - * - * @param topOfProcStack Process Stack Pointer - * - * Assign the value ProcessStackPointer to the MSP - * (process stack pointer) Cortex processor register - */ -__ASM void __set_PSP(uint32_t topOfProcStack) -{ - msr psp, r0 - bx lr -} - -/** - * @brief Return the Main Stack Pointer - * - * @return Main Stack Pointer - * - * Return the current value of the MSP (main stack pointer) - * Cortex processor register - */ -__ASM uint32_t __get_MSP(void) -{ - mrs r0, msp - bx lr -} - -/** - * @brief Set the Main Stack Pointer - * - * @param topOfMainStack Main Stack Pointer - * - * Assign the value mainStackPointer to the MSP - * (main stack pointer) Cortex processor register - */ -__ASM void __set_MSP(uint32_t mainStackPointer) -{ - msr msp, r0 - bx lr -} - -/** - * @brief Reverse byte order in unsigned short value - * - * @param value value to reverse - * @return reversed value - * - * Reverse byte order in unsigned short value - */ -__ASM uint32_t __REV16(uint16_t value) -{ - rev16 r0, r0 - bx lr -} - -/** - * @brief Reverse byte order in signed short value with sign extension to integer - * - * @param value value to reverse - * @return reversed value - * - * Reverse byte order in signed short value with sign extension to integer - */ -__ASM int32_t __REVSH(int16_t value) -{ - revsh r0, r0 - bx lr -} - - -#if (__ARMCC_VERSION < 400000) - -/** - * @brief Remove the exclusive lock created by ldrex - * - * Removes the exclusive lock which is created by ldrex. - */ -__ASM void __CLREX(void) -{ - clrex -} - -/** - * @brief Return the Base Priority value - * - * @return BasePriority - * - * Return the content of the base priority register - */ -__ASM uint32_t __get_BASEPRI(void) -{ - mrs r0, basepri - bx lr -} - -/** - * @brief Set the Base Priority value - * - * @param basePri BasePriority - * - * Set the base priority register - */ -__ASM void __set_BASEPRI(uint32_t basePri) -{ - msr basepri, r0 - bx lr -} - -/** - * @brief Return the Priority Mask value - * - * @return PriMask - * - * Return state of the priority mask bit from the priority mask register - */ -__ASM uint32_t __get_PRIMASK(void) -{ - mrs r0, primask - bx lr -} - -/** - * @brief Set the Priority Mask value - * - * @param priMask PriMask - * - * Set the priority mask bit in the priority mask register - */ -__ASM void __set_PRIMASK(uint32_t priMask) -{ - msr primask, r0 - bx lr -} - -/** - * @brief Return the Fault Mask value - * - * @return FaultMask - * - * Return the content of the fault mask register - */ -__ASM uint32_t __get_FAULTMASK(void) -{ - mrs r0, faultmask - bx lr -} - -/** - * @brief Set the Fault Mask value - * - * @param faultMask faultMask value - * - * Set the fault mask register - */ -__ASM void __set_FAULTMASK(uint32_t faultMask) -{ - msr faultmask, r0 - bx lr -} - -/** - * @brief Return the Control Register value - * - * @return Control value - * - * Return the content of the control register - */ -__ASM uint32_t __get_CONTROL(void) -{ - mrs r0, control - bx lr -} - -/** - * @brief Set the Control Register value - * - * @param control Control value - * - * Set the control register - */ -__ASM void __set_CONTROL(uint32_t control) -{ - msr control, r0 - bx lr -} - -#endif /* __ARMCC_VERSION */ - - - -#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/ -/* IAR iccarm specific functions */ -#pragma diag_suppress=Pe940 - -/** - * @brief Return the Process Stack Pointer - * - * @return ProcessStackPointer - * - * Return the actual process stack pointer - */ -uint32_t __get_PSP(void) -{ - __ASM("mrs r0, psp"); - __ASM("bx lr"); -} - -/** - * @brief Set the Process Stack Pointer - * - * @param topOfProcStack Process Stack Pointer - * - * Assign the value ProcessStackPointer to the MSP - * (process stack pointer) Cortex processor register - */ -void __set_PSP(uint32_t topOfProcStack) -{ - __ASM("msr psp, r0"); - __ASM("bx lr"); -} - -/** - * @brief Return the Main Stack Pointer - * - * @return Main Stack Pointer - * - * Return the current value of the MSP (main stack pointer) - * Cortex processor register - */ -uint32_t __get_MSP(void) -{ - __ASM("mrs r0, msp"); - __ASM("bx lr"); -} - -/** - * @brief Set the Main Stack Pointer - * - * @param topOfMainStack Main Stack Pointer - * - * Assign the value mainStackPointer to the MSP - * (main stack pointer) Cortex processor register - */ -void __set_MSP(uint32_t topOfMainStack) -{ - __ASM("msr msp, r0"); - __ASM("bx lr"); -} - -/** - * @brief Reverse byte order in unsigned short value - * - * @param value value to reverse - * @return reversed value - * - * Reverse byte order in unsigned short value - */ -uint32_t __REV16(uint16_t value) -{ - __ASM("rev16 r0, r0"); - __ASM("bx lr"); -} - -/** - * @brief Reverse bit order of value - * - * @param value value to reverse - * @return reversed value - * - * Reverse bit order of value - */ -uint32_t __RBIT(uint32_t value) -{ - __ASM("rbit r0, r0"); - __ASM("bx lr"); -} - -/** - * @brief LDR Exclusive (8 bit) - * - * @param *addr address pointer - * @return value of (*address) - * - * Exclusive LDR command for 8 bit values) - */ -uint8_t __LDREXB(uint8_t *addr) -{ - __ASM("ldrexb r0, [r0]"); - __ASM("bx lr"); -} - -/** - * @brief LDR Exclusive (16 bit) - * - * @param *addr address pointer - * @return value of (*address) - * - * Exclusive LDR command for 16 bit values - */ -uint16_t __LDREXH(uint16_t *addr) -{ - __ASM("ldrexh r0, [r0]"); - __ASM("bx lr"); -} - -/** - * @brief LDR Exclusive (32 bit) - * - * @param *addr address pointer - * @return value of (*address) - * - * Exclusive LDR command for 32 bit values - */ -uint32_t __LDREXW(uint32_t *addr) -{ - __ASM("ldrex r0, [r0]"); - __ASM("bx lr"); -} - -/** - * @brief STR Exclusive (8 bit) - * - * @param value value to store - * @param *addr address pointer - * @return successful / failed - * - * Exclusive STR command for 8 bit values - */ -uint32_t __STREXB(uint8_t value, uint8_t *addr) -{ - __ASM("strexb r0, r0, [r1]"); - __ASM("bx lr"); -} - -/** - * @brief STR Exclusive (16 bit) - * - * @param value value to store - * @param *addr address pointer - * @return successful / failed - * - * Exclusive STR command for 16 bit values - */ -uint32_t __STREXH(uint16_t value, uint16_t *addr) -{ - __ASM("strexh r0, r0, [r1]"); - __ASM("bx lr"); -} - -/** - * @brief STR Exclusive (32 bit) - * - * @param value value to store - * @param *addr address pointer - * @return successful / failed - * - * Exclusive STR command for 32 bit values - */ -uint32_t __STREXW(uint32_t value, uint32_t *addr) -{ - __ASM("strex r0, r0, [r1]"); - __ASM("bx lr"); -} - -#pragma diag_default=Pe940 - - -#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/ -/* GNU gcc specific functions */ - -/** - * @brief Return the Process Stack Pointer - * - * @return ProcessStackPointer - * - * Return the actual process stack pointer - */ -uint32_t __get_PSP(void) __attribute__( ( naked ) ); -uint32_t __get_PSP(void) -{ - uint32_t result=0; - - __ASM volatile ("MRS %0, psp\n\t" - "MOV r0, %0 \n\t" - "BX lr \n\t" : "=r" (result) ); - return(result); -} - -/** - * @brief Set the Process Stack Pointer - * - * @param topOfProcStack Process Stack Pointer - * - * Assign the value ProcessStackPointer to the MSP - * (process stack pointer) Cortex processor register - */ -void __set_PSP(uint32_t topOfProcStack) __attribute__( ( naked ) ); -void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0\n\t" - "BX lr \n\t" : : "r" (topOfProcStack) ); -} - -/** - * @brief Return the Main Stack Pointer - * - * @return Main Stack Pointer - * - * Return the current value of the MSP (main stack pointer) - * Cortex processor register - */ -uint32_t __get_MSP(void) __attribute__( ( naked ) ); -uint32_t __get_MSP(void) -{ - uint32_t result=0; - - __ASM volatile ("MRS %0, msp\n\t" - "MOV r0, %0 \n\t" - "BX lr \n\t" : "=r" (result) ); - return(result); -} - -/** - * @brief Set the Main Stack Pointer - * - * @param topOfMainStack Main Stack Pointer - * - * Assign the value mainStackPointer to the MSP - * (main stack pointer) Cortex processor register - */ -void __set_MSP(uint32_t topOfMainStack) __attribute__( ( naked ) ); -void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0\n\t" - "BX lr \n\t" : : "r" (topOfMainStack) ); -} - -/** - * @brief Return the Base Priority value - * - * @return BasePriority - * - * Return the content of the base priority register - */ -uint32_t __get_BASEPRI(void) -{ - uint32_t result=0; - - __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); - return(result); -} - -/** - * @brief Set the Base Priority value - * - * @param basePri BasePriority - * - * Set the base priority register - */ -void __set_BASEPRI(uint32_t value) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (value) ); -} - -/** - * @brief Return the Priority Mask value - * - * @return PriMask - * - * Return state of the priority mask bit from the priority mask register - */ -uint32_t __get_PRIMASK(void) -{ - uint32_t result=0; - - __ASM volatile ("MRS %0, primask" : "=r" (result) ); - return(result); -} - -/** - * @brief Set the Priority Mask value - * - * @param priMask PriMask - * - * Set the priority mask bit in the priority mask register - */ -void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) ); -} - -/** - * @brief Return the Fault Mask value - * - * @return FaultMask - * - * Return the content of the fault mask register - */ -uint32_t __get_FAULTMASK(void) -{ - uint32_t result=0; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - -/** - * @brief Set the Fault Mask value - * - * @param faultMask faultMask value - * - * Set the fault mask register - */ -void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) ); -} - -/** - * @brief Return the Control Register value -* -* @return Control value - * - * Return the content of the control register - */ -uint32_t __get_CONTROL(void) -{ - uint32_t result=0; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - -/** - * @brief Set the Control Register value - * - * @param control Control value - * - * Set the control register - */ -void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) ); -} - - -/** - * @brief Reverse byte order in integer value - * - * @param value value to reverse - * @return reversed value - * - * Reverse byte order in integer value - */ -uint32_t __REV(uint32_t value) -{ - uint32_t result=0; - - __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) ); - return(result); -} - -/** - * @brief Reverse byte order in unsigned short value - * - * @param value value to reverse - * @return reversed value - * - * Reverse byte order in unsigned short value - */ -uint32_t __REV16(uint16_t value) -{ - uint32_t result=0; - - __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) ); - return(result); -} - -/** - * @brief Reverse byte order in signed short value with sign extension to integer - * - * @param value value to reverse - * @return reversed value - * - * Reverse byte order in signed short value with sign extension to integer - */ -int32_t __REVSH(int16_t value) -{ - uint32_t result=0; - - __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) ); - return(result); -} - -/** - * @brief Reverse bit order of value - * - * @param value value to reverse - * @return reversed value - * - * Reverse bit order of value - */ -uint32_t __RBIT(uint32_t value) -{ - uint32_t result=0; - - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); - return(result); -} - -/** - * @brief LDR Exclusive (8 bit) - * - * @param *addr address pointer - * @return value of (*address) - * - * Exclusive LDR command for 8 bit value - */ -uint8_t __LDREXB(uint8_t *addr) -{ - uint8_t result=0; - - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) ); - return(result); -} - -/** - * @brief LDR Exclusive (16 bit) - * - * @param *addr address pointer - * @return value of (*address) - * - * Exclusive LDR command for 16 bit values - */ -uint16_t __LDREXH(uint16_t *addr) -{ - uint16_t result=0; - - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) ); - return(result); -} - -/** - * @brief LDR Exclusive (32 bit) - * - * @param *addr address pointer - * @return value of (*address) - * - * Exclusive LDR command for 32 bit values - */ -uint32_t __LDREXW(uint32_t *addr) -{ - uint32_t result=0; - - __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) ); - return(result); -} - -/** - * @brief STR Exclusive (8 bit) - * - * @param value value to store - * @param *addr address pointer - * @return successful / failed - * - * Exclusive STR command for 8 bit values - */ -uint32_t __STREXB(uint8_t value, uint8_t *addr) -{ - uint32_t result=0; - - __ASM volatile ("strexb %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); - return(result); -} - -/** - * @brief STR Exclusive (16 bit) - * - * @param value value to store - * @param *addr address pointer - * @return successful / failed - * - * Exclusive STR command for 16 bit values - */ -uint32_t __STREXH(uint16_t value, uint16_t *addr) -{ - uint32_t result=0; - - __ASM volatile ("strexh %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); - return(result); -} - -/** - * @brief STR Exclusive (32 bit) - * - * @param value value to store - * @param *addr address pointer - * @return successful / failed - * - * Exclusive STR command for 32 bit values - */ -uint32_t __STREXW(uint32_t value, uint32_t *addr) -{ - uint32_t result=0; - - __ASM volatile ("strex %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); - return(result); -} - - -#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/ -/* TASKING carm specific functions */ - -/* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all instrinsics, - * Including the CMSIS ones. - */ - -#endif +/**************************************************************************//** + * @file core_cm3.c + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Source File + * @version V1.30 + * @date 30. October 2009 + * + * @note + * Copyright (C) 2009 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#include + +/* define compiler specific symbols */ +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */ + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + +#endif + + +/* ################### Compiler specific Intrinsics ########################### */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +__ASM uint32_t __get_PSP(void) +{ + mrs r0, psp + bx lr +} + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +__ASM void __set_PSP(uint32_t topOfProcStack) +{ + msr psp, r0 + bx lr +} + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +__ASM uint32_t __get_MSP(void) +{ + mrs r0, msp + bx lr +} + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +__ASM void __set_MSP(uint32_t mainStackPointer) +{ + msr msp, r0 + bx lr +} + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +__ASM uint32_t __REV16(uint16_t value) +{ + rev16 r0, r0 + bx lr +} + +/** + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +__ASM int32_t __REVSH(int16_t value) +{ + revsh r0, r0 + bx lr +} + + +#if (__ARMCC_VERSION < 400000) + +/** + * @brief Remove the exclusive lock created by ldrex + * + * Removes the exclusive lock which is created by ldrex. + */ +__ASM void __CLREX(void) +{ + clrex +} + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +__ASM uint32_t __get_BASEPRI(void) +{ + mrs r0, basepri + bx lr +} + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +__ASM void __set_BASEPRI(uint32_t basePri) +{ + msr basepri, r0 + bx lr +} + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +__ASM uint32_t __get_PRIMASK(void) +{ + mrs r0, primask + bx lr +} + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +__ASM void __set_PRIMASK(uint32_t priMask) +{ + msr primask, r0 + bx lr +} + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +__ASM uint32_t __get_FAULTMASK(void) +{ + mrs r0, faultmask + bx lr +} + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +__ASM void __set_FAULTMASK(uint32_t faultMask) +{ + msr faultmask, r0 + bx lr +} + +/** + * @brief Return the Control Register value + * + * @return Control value + * + * Return the content of the control register + */ +__ASM uint32_t __get_CONTROL(void) +{ + mrs r0, control + bx lr +} + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +__ASM void __set_CONTROL(uint32_t control) +{ + msr control, r0 + bx lr +} + +#endif /* __ARMCC_VERSION */ + + + +#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ +#pragma diag_suppress=Pe940 + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +uint32_t __get_PSP(void) +{ + __ASM("mrs r0, psp"); + __ASM("bx lr"); +} + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +void __set_PSP(uint32_t topOfProcStack) +{ + __ASM("msr psp, r0"); + __ASM("bx lr"); +} + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +uint32_t __get_MSP(void) +{ + __ASM("mrs r0, msp"); + __ASM("bx lr"); +} + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +void __set_MSP(uint32_t topOfMainStack) +{ + __ASM("msr msp, r0"); + __ASM("bx lr"); +} + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +uint32_t __REV16(uint16_t value) +{ + __ASM("rev16 r0, r0"); + __ASM("bx lr"); +} + +/** + * @brief Reverse bit order of value + * + * @param value value to reverse + * @return reversed value + * + * Reverse bit order of value + */ +uint32_t __RBIT(uint32_t value) +{ + __ASM("rbit r0, r0"); + __ASM("bx lr"); +} + +/** + * @brief LDR Exclusive (8 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 8 bit values) + */ +uint8_t __LDREXB(uint8_t *addr) +{ + __ASM("ldrexb r0, [r0]"); + __ASM("bx lr"); +} + +/** + * @brief LDR Exclusive (16 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 16 bit values + */ +uint16_t __LDREXH(uint16_t *addr) +{ + __ASM("ldrexh r0, [r0]"); + __ASM("bx lr"); +} + +/** + * @brief LDR Exclusive (32 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 32 bit values + */ +uint32_t __LDREXW(uint32_t *addr) +{ + __ASM("ldrex r0, [r0]"); + __ASM("bx lr"); +} + +/** + * @brief STR Exclusive (8 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 8 bit values + */ +uint32_t __STREXB(uint8_t value, uint8_t *addr) +{ + __ASM("strexb r0, r0, [r1]"); + __ASM("bx lr"); +} + +/** + * @brief STR Exclusive (16 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 16 bit values + */ +uint32_t __STREXH(uint16_t value, uint16_t *addr) +{ + __ASM("strexh r0, r0, [r1]"); + __ASM("bx lr"); +} + +/** + * @brief STR Exclusive (32 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 32 bit values + */ +uint32_t __STREXW(uint32_t value, uint32_t *addr) +{ + __ASM("strex r0, r0, [r1]"); + __ASM("bx lr"); +} + +#pragma diag_default=Pe940 + + +#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +uint32_t __get_PSP(void) __attribute__( ( naked ) ); +uint32_t __get_PSP(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, psp\n\t" + "MOV r0, %0 \n\t" + "BX lr \n\t" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +void __set_PSP(uint32_t topOfProcStack) __attribute__( ( naked ) ); +void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0\n\t" + "BX lr \n\t" : : "r" (topOfProcStack) ); +} + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +uint32_t __get_MSP(void) __attribute__( ( naked ) ); +uint32_t __get_MSP(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, msp\n\t" + "MOV r0, %0 \n\t" + "BX lr \n\t" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +void __set_MSP(uint32_t topOfMainStack) __attribute__( ( naked ) ); +void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0\n\t" + "BX lr \n\t" : : "r" (topOfMainStack) ); +} + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +uint32_t __get_BASEPRI(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +void __set_BASEPRI(uint32_t value) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (value) ); +} + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +uint32_t __get_PRIMASK(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) ); +} + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +uint32_t __get_FAULTMASK(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) ); +} + +/** + * @brief Return the Control Register value +* +* @return Control value + * + * Return the content of the control register + */ +uint32_t __get_CONTROL(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) ); +} + + +/** + * @brief Reverse byte order in integer value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in integer value + */ +uint32_t __REV(uint32_t value) +{ + uint32_t result=0; + + __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +uint32_t __REV16(uint16_t value) +{ + uint32_t result=0; + + __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +int32_t __REVSH(int16_t value) +{ + uint32_t result=0; + + __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief Reverse bit order of value + * + * @param value value to reverse + * @return reversed value + * + * Reverse bit order of value + */ +uint32_t __RBIT(uint32_t value) +{ + uint32_t result=0; + + __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief LDR Exclusive (8 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 8 bit value + */ +uint8_t __LDREXB(uint8_t *addr) +{ + uint8_t result=0; + + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + +/** + * @brief LDR Exclusive (16 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 16 bit values + */ +uint16_t __LDREXH(uint16_t *addr) +{ + uint16_t result=0; + + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + +/** + * @brief LDR Exclusive (32 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 32 bit values + */ +uint32_t __LDREXW(uint32_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + +/** + * @brief STR Exclusive (8 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 8 bit values + */ +uint32_t __STREXB(uint8_t value, uint8_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("strexb %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + +/** + * @brief STR Exclusive (16 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 16 bit values + */ +uint32_t __STREXH(uint16_t value, uint16_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("strexh %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + +/** + * @brief STR Exclusive (32 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 32 bit values + */ +uint32_t __STREXW(uint32_t value, uint32_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("strex %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all instrinsics, + * Including the CMSIS ones. + */ + +#endif diff --git a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_cl.s b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_cl.s index b017eb811..55dd60366 100755 --- a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_cl.s +++ b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_cl.s @@ -1,467 +1,467 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_cl.s - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief STM32F10x Connectivity line Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR - * address. - * - Configure the clock system - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ******************************************************************************* - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss - -.equ BootRAM, 0xF1E0F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss - -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler - -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word CAN1_TX_IRQHandler - .word CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word OTG_FS_WKUP_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word TIM5_IRQHandler - .word SPI3_IRQHandler - .word UART4_IRQHandler - .word UART5_IRQHandler - .word TIM6_IRQHandler - .word TIM7_IRQHandler - .word DMA2_Channel1_IRQHandler - .word DMA2_Channel2_IRQHandler - .word DMA2_Channel3_IRQHandler - .word DMA2_Channel4_IRQHandler - .word DMA2_Channel5_IRQHandler - .word ETH_IRQHandler - .word ETH_WKUP_IRQHandler - .word CAN2_TX_IRQHandler - .word CAN2_RX0_IRQHandler - .word CAN2_RX1_IRQHandler - .word CAN2_SCE_IRQHandler - .word OTG_FS_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x1E0. This is for boot in RAM mode for - STM32F10x Connectivity line Devices. */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak CAN1_TX_IRQHandler - .thumb_set CAN1_TX_IRQHandler,Default_Handler - - .weak CAN1_RX0_IRQHandler - .thumb_set CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak OTG_FS_WKUP_IRQHandler - .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_IRQHandler - .thumb_set TIM6_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Channel1_IRQHandler - .thumb_set DMA2_Channel1_IRQHandler,Default_Handler - - .weak DMA2_Channel2_IRQHandler - .thumb_set DMA2_Channel2_IRQHandler,Default_Handler - - .weak DMA2_Channel3_IRQHandler - .thumb_set DMA2_Channel3_IRQHandler,Default_Handler - - .weak DMA2_Channel4_IRQHandler - .thumb_set DMA2_Channel4_IRQHandler,Default_Handler - - .weak DMA2_Channel5_IRQHandler - .thumb_set DMA2_Channel5_IRQHandler,Default_Handler - - .weak ETH_IRQHandler - .thumb_set ETH_IRQHandler,Default_Handler - - .weak ETH_WKUP_IRQHandler - .thumb_set ETH_WKUP_IRQHandler,Default_Handler - - .weak CAN2_TX_IRQHandler - .thumb_set CAN2_TX_IRQHandler,Default_Handler - - .weak CAN2_RX0_IRQHandler - .thumb_set CAN2_RX0_IRQHandler,Default_Handler - - .weak CAN2_RX1_IRQHandler - .thumb_set CAN2_RX1_IRQHandler,Default_Handler - - .weak CAN2_SCE_IRQHandler - .thumb_set CAN2_SCE_IRQHandler,Default_Handler - - .weak OTG_FS_IRQHandler - .thumb_set OTG_FS_IRQHandler ,Default_Handler - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file startup_stm32f10x_cl.s + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief STM32F10x Connectivity line Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR + * address. + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ******************************************************************************* + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss + +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler + +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word CAN1_TX_IRQHandler + .word CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word OTG_FS_WKUP_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_IRQHandler + .word DMA2_Channel5_IRQHandler + .word ETH_IRQHandler + .word ETH_WKUP_IRQHandler + .word CAN2_TX_IRQHandler + .word CAN2_RX0_IRQHandler + .word CAN2_RX1_IRQHandler + .word CAN2_SCE_IRQHandler + .word OTG_FS_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x Connectivity line Devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_IRQHandler + .thumb_set DMA2_Channel4_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + + .weak ETH_IRQHandler + .thumb_set ETH_IRQHandler,Default_Handler + + .weak ETH_WKUP_IRQHandler + .thumb_set ETH_WKUP_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler ,Default_Handler + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_hd.s b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_hd.s index a1b1f9397..0b392adcd 100755 --- a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_hd.s +++ b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_hd.s @@ -1,464 +1,464 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_hd.s - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief STM32F10x High Density Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system and the external SRAM mounted on - * STM3210E-EVAL board to be used as data memory (optional, - * to be enabled by user) - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ******************************************************************************* - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -.equ BootRAM, 0xF1E0F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -*******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word USBWakeUp_IRQHandler - .word TIM8_BRK_IRQHandler - .word TIM8_UP_IRQHandler - .word TIM8_TRG_COM_IRQHandler - .word TIM8_CC_IRQHandler - .word ADC3_IRQHandler - .word FSMC_IRQHandler - .word SDIO_IRQHandler - .word TIM5_IRQHandler - .word SPI3_IRQHandler - .word UART4_IRQHandler - .word UART5_IRQHandler - .word TIM6_IRQHandler - .word TIM7_IRQHandler - .word DMA2_Channel1_IRQHandler - .word DMA2_Channel2_IRQHandler - .word DMA2_Channel3_IRQHandler - .word DMA2_Channel4_5_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x1E0. This is for boot in RAM mode for - STM32F10x High Density devices. */ -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - - .weak TIM8_BRK_IRQHandler - .thumb_set TIM8_BRK_IRQHandler,Default_Handler - - .weak TIM8_UP_IRQHandler - .thumb_set TIM8_UP_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_IRQHandler - .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak ADC3_IRQHandler - .thumb_set ADC3_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_IRQHandler - .thumb_set TIM6_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Channel1_IRQHandler - .thumb_set DMA2_Channel1_IRQHandler,Default_Handler - - .weak DMA2_Channel2_IRQHandler - .thumb_set DMA2_Channel2_IRQHandler,Default_Handler - - .weak DMA2_Channel3_IRQHandler - .thumb_set DMA2_Channel3_IRQHandler,Default_Handler - - .weak DMA2_Channel4_5_IRQHandler - .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file startup_stm32f10x_hd.s + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief STM32F10x High Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM3210E-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ******************************************************************************* + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_IRQHandler + .word TIM8_UP_IRQHandler + .word TIM8_TRG_COM_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density devices. */ +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_IRQHandler + .thumb_set TIM8_BRK_IRQHandler,Default_Handler + + .weak TIM8_UP_IRQHandler + .thumb_set TIM8_UP_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_IRQHandler + .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_ld.s b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_ld.s index c3dbf4147..a5e0e12c7 100755 --- a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_ld.s +++ b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_ld.s @@ -1,342 +1,342 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_ld.s - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief STM32F10x Low Density Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ******************************************************************************* - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss - -.equ BootRAM, 0xF108F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word 0 - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word 0 - .word 0 - .word SPI1_IRQHandler - .word 0 - .word USART1_IRQHandler - .word USART2_IRQHandler - .word 0 - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word USBWakeUp_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x108. This is for boot in RAM mode for - STM32F10x Low Density devices.*/ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file startup_stm32f10x_ld.s + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief STM32F10x Low Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ******************************************************************************* + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word 0 + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word 0 + .word 0 + .word SPI1_IRQHandler + .word 0 + .word USART1_IRQHandler + .word USART2_IRQHandler + .word 0 + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Low Density devices.*/ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_md.s b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_md.s index b91fbd7db..ea1ec0522 100755 --- a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_md.s +++ b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/startup/gcc/startup_stm32f10x_md.s @@ -1,357 +1,357 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_md.s - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Configure the clock system - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ******************************************************************************* - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss - -.equ BootRAM, 0xF108F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss -/* Call the clock system intitialization function.*/ - bl SystemInit -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * @param None - * @retval None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word USBWakeUp_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x108. This is for boot in RAM mode for - STM32F10x Medium Density devices. */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ******************************************************************************* + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/stm32f10x.h b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/stm32f10x.h index 2951de4ad..18f43bcc4 100755 --- a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/stm32f10x.h +++ b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/stm32f10x.h @@ -1,8323 +1,8323 @@ -/** - ****************************************************************************** - * @file stm32f10x.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief CMSIS Cortex-M3 Device Peripheral Access Layer Header File. - * This file contains all the peripheral register's definitions, bits - * definitions and memory mapping for STM32F10x Connectivity line, - * High density, High density value line, Medium density, - * Medium density Value line, Low density, Low density Value line - * and XL-density devices. - ****************************************************************************** - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f10x - * @{ - */ - -#ifndef __STM32F10x_H -#define __STM32F10x_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup Library_configuration_section - * @{ - */ - -/* Uncomment the line below according to the target STM32 device used in your - application - */ - -#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_XL) && !defined (STM32F10X_CL) - /* #define STM32F10X_LD */ /*!< STM32F10X_LD: STM32 Low density devices */ - /* #define STM32F10X_LD_VL */ /*!< STM32F10X_LD_VL: STM32 Low density Value Line devices */ - /* #define STM32F10X_MD */ /*!< STM32F10X_MD: STM32 Medium density devices */ - /* #define STM32F10X_MD_VL */ /*!< STM32F10X_MD_VL: STM32 Medium density Value Line devices */ - /* #define STM32F10X_HD */ /*!< STM32F10X_HD: STM32 High density devices */ - /* #define STM32F10X_HD_VL */ /*!< STM32F10X_HD_VL: STM32 High density value line devices */ - /* #define STM32F10X_XL */ /*!< STM32F10X_XL: STM32 XL-density devices */ - /* #define STM32F10X_CL */ /*!< STM32F10X_CL: STM32 Connectivity line devices */ -#endif -/* Tip: To avoid modifying this file each time you need to switch between these - devices, you can define the device in your toolchain compiler preprocessor. - - - Low-density devices are STM32F101xx, STM32F102xx and STM32F103xx microcontrollers - where the Flash memory density ranges between 16 and 32 Kbytes. - - Low-density value line devices are STM32F100xx microcontrollers where the Flash - memory density ranges between 16 and 32 Kbytes. - - Medium-density devices are STM32F101xx, STM32F102xx and STM32F103xx microcontrollers - where the Flash memory density ranges between 64 and 128 Kbytes. - - Medium-density value line devices are STM32F100xx microcontrollers where the - Flash memory density ranges between 64 and 128 Kbytes. - - High-density devices are STM32F101xx and STM32F103xx microcontrollers where - the Flash memory density ranges between 256 and 512 Kbytes. - - High-density value line devices are STM32F100xx microcontrollers where the - Flash memory density ranges between 256 and 512 Kbytes. - - XL-density devices are STM32F101xx and STM32F103xx microcontrollers where - the Flash memory density ranges between 512 and 1024 Kbytes. - - Connectivity line devices are STM32F105xx and STM32F107xx microcontrollers. - */ - -#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_XL) && !defined (STM32F10X_CL) - #error "Please select first the target STM32F10x device used in your application (in stm32f10x.h file)" -#endif - -#if !defined USE_STDPERIPH_DRIVER -/** - * @brief Comment the line below if you will not use the peripherals drivers. - In this case, these drivers will not be included and the application code will - be based on direct access to peripherals registers - */ - /*#define USE_STDPERIPH_DRIVER*/ -#endif - -/** - * @brief In the following line adjust the value of External High Speed oscillator (HSE) - used in your application - - Tip: To avoid modifying this file each time you need to use different HSE, you - can define the HSE value in your toolchain compiler preprocessor. - */ -#if !defined HSE_VALUE - #ifdef STM32F10X_CL - #define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ - #else - #define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */ - #endif /* STM32F10X_CL */ -#endif /* HSE_VALUE */ - - -/** - * @brief In the following line adjust the External High Speed oscillator (HSE) Startup - Timeout value - */ -#define HSE_STARTUP_TIMEOUT ((uint16_t)0x0500) /*!< Time out for HSE start up */ - -#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/ - -/** - * @brief STM32F10x Standard Peripheral Library version number - */ -#define __STM32F10X_STDPERIPH_VERSION_MAIN (0x03) /*!< [31:16] STM32F10x Standard Peripheral Library main version */ -#define __STM32F10X_STDPERIPH_VERSION_SUB1 (0x04) /*!< [15:8] STM32F10x Standard Peripheral Library sub1 version */ -#define __STM32F10X_STDPERIPH_VERSION_SUB2 (0x00) /*!< [7:0] STM32F10x Standard Peripheral Library sub2 version */ -#define __STM32F10X_STDPERIPH_VERSION ((__STM32F10X_STDPERIPH_VERSION_MAIN << 16)\ - | (__STM32F10X_STDPERIPH_VERSION_SUB1 << 8)\ - | __STM32F10X_STDPERIPH_VERSION_SUB2) - -/** - * @} - */ - -/** @addtogroup Configuration_section_for_CMSIS - * @{ - */ - -/** - * @brief Configuration of the Cortex-M3 Processor and Core Peripherals - */ -#ifdef STM32F10X_XL - #define __MPU_PRESENT 1 /*!< STM32 XL-density devices provide an MPU */ -#else - #define __MPU_PRESENT 0 /*!< Other STM32 devices does not provide an MPU */ -#endif /* STM32F10X_XL */ -#define __NVIC_PRIO_BITS 4 /*!< STM32 uses 4 Bits for the Priority Levels */ -#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ - -/** - * @brief STM32F10x Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum IRQn -{ -/****** Cortex-M3 Processor Exceptions Numbers ***************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */ - -/****** STM32 specific Interrupt Numbers *********************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ - PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ - TAMPER_IRQn = 2, /*!< Tamper Interrupt */ - RTC_IRQn = 3, /*!< RTC global Interrupt */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Channel1_IRQn = 11, /*!< DMA1 Channel 1 global Interrupt */ - DMA1_Channel2_IRQn = 12, /*!< DMA1 Channel 2 global Interrupt */ - DMA1_Channel3_IRQn = 13, /*!< DMA1 Channel 3 global Interrupt */ - DMA1_Channel4_IRQn = 14, /*!< DMA1 Channel 4 global Interrupt */ - DMA1_Channel5_IRQn = 15, /*!< DMA1 Channel 5 global Interrupt */ - DMA1_Channel6_IRQn = 16, /*!< DMA1 Channel 6 global Interrupt */ - DMA1_Channel7_IRQn = 17, /*!< DMA1 Channel 7 global Interrupt */ - -#ifdef STM32F10X_LD - ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ - USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ - USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ - TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ - TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ - USBWakeUp_IRQn = 42 /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ -#endif /* STM32F10X_LD */ - -#ifdef STM32F10X_LD_VL - ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ - TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ - TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ - CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ - TIM7_IRQn = 55 /*!< TIM7 Interrupt */ -#endif /* STM32F10X_LD_VL */ - -#ifdef STM32F10X_MD - ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ - USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ - USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ - TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ - TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ - USBWakeUp_IRQn = 42 /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ -#endif /* STM32F10X_MD */ - -#ifdef STM32F10X_MD_VL - ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ - TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ - TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ - CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ - TIM7_IRQn = 55 /*!< TIM7 Interrupt */ -#endif /* STM32F10X_MD_VL */ - -#ifdef STM32F10X_HD - ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ - USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ - USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ - TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ - TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ - USBWakeUp_IRQn = 42, /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ - TIM8_BRK_IRQn = 43, /*!< TIM8 Break Interrupt */ - TIM8_UP_IRQn = 44, /*!< TIM8 Update Interrupt */ - TIM8_TRG_COM_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ - ADC3_IRQn = 47, /*!< ADC3 global Interrupt */ - FSMC_IRQn = 48, /*!< FSMC global Interrupt */ - SDIO_IRQn = 49, /*!< SDIO global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ - TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ - DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ - DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ - DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ - DMA2_Channel4_5_IRQn = 59 /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ -#endif /* STM32F10X_HD */ - -#ifdef STM32F10X_HD_VL - ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ - TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ - TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ - CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ - TIM12_IRQn = 43, /*!< TIM12 global Interrupt */ - TIM13_IRQn = 44, /*!< TIM13 global Interrupt */ - TIM14_IRQn = 45, /*!< TIM14 global Interrupt */ - FSMC_IRQn = 48, /*!< FSMC global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ - TIM7_IRQn = 55, /*!< TIM7 Interrupt */ - DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ - DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ - DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ - DMA2_Channel4_5_IRQn = 59, /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ - DMA2_Channel5_IRQn = 60 /*!< DMA2 Channel 5 global Interrupt (DMA2 Channel 5 is - mapped at postion 60 only if the MISC_REMAP bit in - the AFIO_MAPR2 register is set) */ -#endif /* STM32F10X_HD_VL */ - -#ifdef STM32F10X_XL - ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ - USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ - USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break Interrupt and TIM9 global Interrupt */ - TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global Interrupt */ - TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ - USBWakeUp_IRQn = 42, /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global Interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global Interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ - ADC3_IRQn = 47, /*!< ADC3 global Interrupt */ - FSMC_IRQn = 48, /*!< FSMC global Interrupt */ - SDIO_IRQn = 49, /*!< SDIO global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ - TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ - DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ - DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ - DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ - DMA2_Channel4_5_IRQn = 59 /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ -#endif /* STM32F10X_XL */ - -#ifdef STM32F10X_CL - ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ - CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ - CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ - TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ - TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ - OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS WakeUp from suspend through EXTI Line Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ - TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ - DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ - DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ - DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ - DMA2_Channel4_IRQn = 59, /*!< DMA2 Channel 4 global Interrupt */ - DMA2_Channel5_IRQn = 60, /*!< DMA2 Channel 5 global Interrupt */ - ETH_IRQn = 61, /*!< Ethernet global Interrupt */ - ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ - CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ - CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ - CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ - CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ - OTG_FS_IRQn = 67 /*!< USB OTG FS global Interrupt */ -#endif /* STM32F10X_CL */ -} IRQn_Type; - -/** - * @} - */ - -#include "core_cm3.h" -#include "system_stm32f10x.h" -#include - -/** @addtogroup Exported_types - * @{ - */ - -/*!< STM32F10x Standard Peripheral Library old types (maintained for legacy purpose) */ -typedef int32_t s32; -typedef int16_t s16; -typedef int8_t s8; - -typedef const int32_t sc32; /*!< Read Only */ -typedef const int16_t sc16; /*!< Read Only */ -typedef const int8_t sc8; /*!< Read Only */ - -typedef __IO int32_t vs32; -typedef __IO int16_t vs16; -typedef __IO int8_t vs8; - -typedef __I int32_t vsc32; /*!< Read Only */ -typedef __I int16_t vsc16; /*!< Read Only */ -typedef __I int8_t vsc8; /*!< Read Only */ - -typedef uint32_t u32; -typedef uint16_t u16; -typedef uint8_t u8; - -typedef const uint32_t uc32; /*!< Read Only */ -typedef const uint16_t uc16; /*!< Read Only */ -typedef const uint8_t uc8; /*!< Read Only */ - -typedef __IO uint32_t vu32; -typedef __IO uint16_t vu16; -typedef __IO uint8_t vu8; - -typedef __I uint32_t vuc32; /*!< Read Only */ -typedef __I uint16_t vuc16; /*!< Read Only */ -typedef __I uint8_t vuc8; /*!< Read Only */ - -#ifndef __cplusplus - typedef enum {FALSE = 0, TRUE = !FALSE} bool; -#endif - -typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus; - -typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; -#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) - -typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus; - -/*!< STM32F10x Standard Peripheral Library old definitions (maintained for legacy purpose) */ -#define HSEStartUp_TimeOut HSE_STARTUP_TIMEOUT -#define HSE_Value HSE_VALUE -#define HSI_Value HSI_VALUE -/** - * @} - */ - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t SR; - __IO uint32_t CR1; - __IO uint32_t CR2; - __IO uint32_t SMPR1; - __IO uint32_t SMPR2; - __IO uint32_t JOFR1; - __IO uint32_t JOFR2; - __IO uint32_t JOFR3; - __IO uint32_t JOFR4; - __IO uint32_t HTR; - __IO uint32_t LTR; - __IO uint32_t SQR1; - __IO uint32_t SQR2; - __IO uint32_t SQR3; - __IO uint32_t JSQR; - __IO uint32_t JDR1; - __IO uint32_t JDR2; - __IO uint32_t JDR3; - __IO uint32_t JDR4; - __IO uint32_t DR; -} ADC_TypeDef; - -/** - * @brief Backup Registers - */ - -typedef struct -{ - uint32_t RESERVED0; - __IO uint16_t DR1; - uint16_t RESERVED1; - __IO uint16_t DR2; - uint16_t RESERVED2; - __IO uint16_t DR3; - uint16_t RESERVED3; - __IO uint16_t DR4; - uint16_t RESERVED4; - __IO uint16_t DR5; - uint16_t RESERVED5; - __IO uint16_t DR6; - uint16_t RESERVED6; - __IO uint16_t DR7; - uint16_t RESERVED7; - __IO uint16_t DR8; - uint16_t RESERVED8; - __IO uint16_t DR9; - uint16_t RESERVED9; - __IO uint16_t DR10; - uint16_t RESERVED10; - __IO uint16_t RTCCR; - uint16_t RESERVED11; - __IO uint16_t CR; - uint16_t RESERVED12; - __IO uint16_t CSR; - uint16_t RESERVED13[5]; - __IO uint16_t DR11; - uint16_t RESERVED14; - __IO uint16_t DR12; - uint16_t RESERVED15; - __IO uint16_t DR13; - uint16_t RESERVED16; - __IO uint16_t DR14; - uint16_t RESERVED17; - __IO uint16_t DR15; - uint16_t RESERVED18; - __IO uint16_t DR16; - uint16_t RESERVED19; - __IO uint16_t DR17; - uint16_t RESERVED20; - __IO uint16_t DR18; - uint16_t RESERVED21; - __IO uint16_t DR19; - uint16_t RESERVED22; - __IO uint16_t DR20; - uint16_t RESERVED23; - __IO uint16_t DR21; - uint16_t RESERVED24; - __IO uint16_t DR22; - uint16_t RESERVED25; - __IO uint16_t DR23; - uint16_t RESERVED26; - __IO uint16_t DR24; - uint16_t RESERVED27; - __IO uint16_t DR25; - uint16_t RESERVED28; - __IO uint16_t DR26; - uint16_t RESERVED29; - __IO uint16_t DR27; - uint16_t RESERVED30; - __IO uint16_t DR28; - uint16_t RESERVED31; - __IO uint16_t DR29; - uint16_t RESERVED32; - __IO uint16_t DR30; - uint16_t RESERVED33; - __IO uint16_t DR31; - uint16_t RESERVED34; - __IO uint16_t DR32; - uint16_t RESERVED35; - __IO uint16_t DR33; - uint16_t RESERVED36; - __IO uint16_t DR34; - uint16_t RESERVED37; - __IO uint16_t DR35; - uint16_t RESERVED38; - __IO uint16_t DR36; - uint16_t RESERVED39; - __IO uint16_t DR37; - uint16_t RESERVED40; - __IO uint16_t DR38; - uint16_t RESERVED41; - __IO uint16_t DR39; - uint16_t RESERVED42; - __IO uint16_t DR40; - uint16_t RESERVED43; - __IO uint16_t DR41; - uint16_t RESERVED44; - __IO uint16_t DR42; - uint16_t RESERVED45; -} BKP_TypeDef; - -/** - * @brief Controller Area Network TxMailBox - */ - -typedef struct -{ - __IO uint32_t TIR; - __IO uint32_t TDTR; - __IO uint32_t TDLR; - __IO uint32_t TDHR; -} CAN_TxMailBox_TypeDef; - -/** - * @brief Controller Area Network FIFOMailBox - */ - -typedef struct -{ - __IO uint32_t RIR; - __IO uint32_t RDTR; - __IO uint32_t RDLR; - __IO uint32_t RDHR; -} CAN_FIFOMailBox_TypeDef; - -/** - * @brief Controller Area Network FilterRegister - */ - -typedef struct -{ - __IO uint32_t FR1; - __IO uint32_t FR2; -} CAN_FilterRegister_TypeDef; - -/** - * @brief Controller Area Network - */ - -typedef struct -{ - __IO uint32_t MCR; - __IO uint32_t MSR; - __IO uint32_t TSR; - __IO uint32_t RF0R; - __IO uint32_t RF1R; - __IO uint32_t IER; - __IO uint32_t ESR; - __IO uint32_t BTR; - uint32_t RESERVED0[88]; - CAN_TxMailBox_TypeDef sTxMailBox[3]; - CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; - uint32_t RESERVED1[12]; - __IO uint32_t FMR; - __IO uint32_t FM1R; - uint32_t RESERVED2; - __IO uint32_t FS1R; - uint32_t RESERVED3; - __IO uint32_t FFA1R; - uint32_t RESERVED4; - __IO uint32_t FA1R; - uint32_t RESERVED5[8]; -#ifndef STM32F10X_CL - CAN_FilterRegister_TypeDef sFilterRegister[14]; -#else - CAN_FilterRegister_TypeDef sFilterRegister[28]; -#endif /* STM32F10X_CL */ -} CAN_TypeDef; - -/** - * @brief Consumer Electronics Control (CEC) - */ -typedef struct -{ - __IO uint32_t CFGR; - __IO uint32_t OAR; - __IO uint32_t PRES; - __IO uint32_t ESR; - __IO uint32_t CSR; - __IO uint32_t TXD; - __IO uint32_t RXD; -} CEC_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; - __IO uint8_t IDR; - uint8_t RESERVED0; - uint16_t RESERVED1; - __IO uint32_t CR; -} CRC_TypeDef; - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; - __IO uint32_t SWTRIGR; - __IO uint32_t DHR12R1; - __IO uint32_t DHR12L1; - __IO uint32_t DHR8R1; - __IO uint32_t DHR12R2; - __IO uint32_t DHR12L2; - __IO uint32_t DHR8R2; - __IO uint32_t DHR12RD; - __IO uint32_t DHR12LD; - __IO uint32_t DHR8RD; - __IO uint32_t DOR1; - __IO uint32_t DOR2; -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) - __IO uint32_t SR; -#endif -} DAC_TypeDef; - -/** - * @brief Debug MCU - */ - -typedef struct -{ - __IO uint32_t IDCODE; - __IO uint32_t CR; -}DBGMCU_TypeDef; - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CCR; - __IO uint32_t CNDTR; - __IO uint32_t CPAR; - __IO uint32_t CMAR; -} DMA_Channel_TypeDef; - -typedef struct -{ - __IO uint32_t ISR; - __IO uint32_t IFCR; -} DMA_TypeDef; - -/** - * @brief Ethernet MAC - */ - -typedef struct -{ - __IO uint32_t MACCR; - __IO uint32_t MACFFR; - __IO uint32_t MACHTHR; - __IO uint32_t MACHTLR; - __IO uint32_t MACMIIAR; - __IO uint32_t MACMIIDR; - __IO uint32_t MACFCR; - __IO uint32_t MACVLANTR; /* 8 */ - uint32_t RESERVED0[2]; - __IO uint32_t MACRWUFFR; /* 11 */ - __IO uint32_t MACPMTCSR; - uint32_t RESERVED1[2]; - __IO uint32_t MACSR; /* 15 */ - __IO uint32_t MACIMR; - __IO uint32_t MACA0HR; - __IO uint32_t MACA0LR; - __IO uint32_t MACA1HR; - __IO uint32_t MACA1LR; - __IO uint32_t MACA2HR; - __IO uint32_t MACA2LR; - __IO uint32_t MACA3HR; - __IO uint32_t MACA3LR; /* 24 */ - uint32_t RESERVED2[40]; - __IO uint32_t MMCCR; /* 65 */ - __IO uint32_t MMCRIR; - __IO uint32_t MMCTIR; - __IO uint32_t MMCRIMR; - __IO uint32_t MMCTIMR; /* 69 */ - uint32_t RESERVED3[14]; - __IO uint32_t MMCTGFSCCR; /* 84 */ - __IO uint32_t MMCTGFMSCCR; - uint32_t RESERVED4[5]; - __IO uint32_t MMCTGFCR; - uint32_t RESERVED5[10]; - __IO uint32_t MMCRFCECR; - __IO uint32_t MMCRFAECR; - uint32_t RESERVED6[10]; - __IO uint32_t MMCRGUFCR; - uint32_t RESERVED7[334]; - __IO uint32_t PTPTSCR; - __IO uint32_t PTPSSIR; - __IO uint32_t PTPTSHR; - __IO uint32_t PTPTSLR; - __IO uint32_t PTPTSHUR; - __IO uint32_t PTPTSLUR; - __IO uint32_t PTPTSAR; - __IO uint32_t PTPTTHR; - __IO uint32_t PTPTTLR; - uint32_t RESERVED8[567]; - __IO uint32_t DMABMR; - __IO uint32_t DMATPDR; - __IO uint32_t DMARPDR; - __IO uint32_t DMARDLAR; - __IO uint32_t DMATDLAR; - __IO uint32_t DMASR; - __IO uint32_t DMAOMR; - __IO uint32_t DMAIER; - __IO uint32_t DMAMFBOCR; - uint32_t RESERVED9[9]; - __IO uint32_t DMACHTDR; - __IO uint32_t DMACHRDR; - __IO uint32_t DMACHTBAR; - __IO uint32_t DMACHRBAR; -} ETH_TypeDef; - -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ - __IO uint32_t IMR; - __IO uint32_t EMR; - __IO uint32_t RTSR; - __IO uint32_t FTSR; - __IO uint32_t SWIER; - __IO uint32_t PR; -} EXTI_TypeDef; - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; - __IO uint32_t KEYR; - __IO uint32_t OPTKEYR; - __IO uint32_t SR; - __IO uint32_t CR; - __IO uint32_t AR; - __IO uint32_t RESERVED; - __IO uint32_t OBR; - __IO uint32_t WRPR; -#ifdef STM32F10X_XL - uint32_t RESERVED1[8]; - __IO uint32_t KEYR2; - uint32_t RESERVED2; - __IO uint32_t SR2; - __IO uint32_t CR2; - __IO uint32_t AR2; -#endif /* STM32F10X_XL */ -} FLASH_TypeDef; - -/** - * @brief Option Bytes Registers - */ - -typedef struct -{ - __IO uint16_t RDP; - __IO uint16_t USER; - __IO uint16_t Data0; - __IO uint16_t Data1; - __IO uint16_t WRP0; - __IO uint16_t WRP1; - __IO uint16_t WRP2; - __IO uint16_t WRP3; -} OB_TypeDef; - -/** - * @brief Flexible Static Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; -} FSMC_Bank1_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; -} FSMC_Bank1E_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank2 - */ - -typedef struct -{ - __IO uint32_t PCR2; - __IO uint32_t SR2; - __IO uint32_t PMEM2; - __IO uint32_t PATT2; - uint32_t RESERVED0; - __IO uint32_t ECCR2; -} FSMC_Bank2_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank3 - */ - -typedef struct -{ - __IO uint32_t PCR3; - __IO uint32_t SR3; - __IO uint32_t PMEM3; - __IO uint32_t PATT3; - uint32_t RESERVED0; - __IO uint32_t ECCR3; -} FSMC_Bank3_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank4 - */ - -typedef struct -{ - __IO uint32_t PCR4; - __IO uint32_t SR4; - __IO uint32_t PMEM4; - __IO uint32_t PATT4; - __IO uint32_t PIO4; -} FSMC_Bank4_TypeDef; - -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t CRL; - __IO uint32_t CRH; - __IO uint32_t IDR; - __IO uint32_t ODR; - __IO uint32_t BSRR; - __IO uint32_t BRR; - __IO uint32_t LCKR; -} GPIO_TypeDef; - -/** - * @brief Alternate Function I/O - */ - -typedef struct -{ - __IO uint32_t EVCR; - __IO uint32_t MAPR; - __IO uint32_t EXTICR[4]; - uint32_t RESERVED0; - __IO uint32_t MAPR2; -} AFIO_TypeDef; -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint16_t CR1; - uint16_t RESERVED0; - __IO uint16_t CR2; - uint16_t RESERVED1; - __IO uint16_t OAR1; - uint16_t RESERVED2; - __IO uint16_t OAR2; - uint16_t RESERVED3; - __IO uint16_t DR; - uint16_t RESERVED4; - __IO uint16_t SR1; - uint16_t RESERVED5; - __IO uint16_t SR2; - uint16_t RESERVED6; - __IO uint16_t CCR; - uint16_t RESERVED7; - __IO uint16_t TRISE; - uint16_t RESERVED8; -} I2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; - __IO uint32_t PR; - __IO uint32_t RLR; - __IO uint32_t SR; -} IWDG_TypeDef; - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR; - __IO uint32_t CSR; -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; - __IO uint32_t CFGR; - __IO uint32_t CIR; - __IO uint32_t APB2RSTR; - __IO uint32_t APB1RSTR; - __IO uint32_t AHBENR; - __IO uint32_t APB2ENR; - __IO uint32_t APB1ENR; - __IO uint32_t BDCR; - __IO uint32_t CSR; - -#ifdef STM32F10X_CL - __IO uint32_t AHBRSTR; - __IO uint32_t CFGR2; -#endif /* STM32F10X_CL */ - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) - uint32_t RESERVED0; - __IO uint32_t CFGR2; -#endif /* STM32F10X_LD_VL || STM32F10X_MD_VL || STM32F10X_HD_VL */ -} RCC_TypeDef; - -/** - * @brief Real-Time Clock - */ - -typedef struct -{ - __IO uint16_t CRH; - uint16_t RESERVED0; - __IO uint16_t CRL; - uint16_t RESERVED1; - __IO uint16_t PRLH; - uint16_t RESERVED2; - __IO uint16_t PRLL; - uint16_t RESERVED3; - __IO uint16_t DIVH; - uint16_t RESERVED4; - __IO uint16_t DIVL; - uint16_t RESERVED5; - __IO uint16_t CNTH; - uint16_t RESERVED6; - __IO uint16_t CNTL; - uint16_t RESERVED7; - __IO uint16_t ALRH; - uint16_t RESERVED8; - __IO uint16_t ALRL; - uint16_t RESERVED9; -} RTC_TypeDef; - -/** - * @brief SD host Interface - */ - -typedef struct -{ - __IO uint32_t POWER; - __IO uint32_t CLKCR; - __IO uint32_t ARG; - __IO uint32_t CMD; - __I uint32_t RESPCMD; - __I uint32_t RESP1; - __I uint32_t RESP2; - __I uint32_t RESP3; - __I uint32_t RESP4; - __IO uint32_t DTIMER; - __IO uint32_t DLEN; - __IO uint32_t DCTRL; - __I uint32_t DCOUNT; - __I uint32_t STA; - __IO uint32_t ICR; - __IO uint32_t MASK; - uint32_t RESERVED0[2]; - __I uint32_t FIFOCNT; - uint32_t RESERVED1[13]; - __IO uint32_t FIFO; -} SDIO_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint16_t CR1; - uint16_t RESERVED0; - __IO uint16_t CR2; - uint16_t RESERVED1; - __IO uint16_t SR; - uint16_t RESERVED2; - __IO uint16_t DR; - uint16_t RESERVED3; - __IO uint16_t CRCPR; - uint16_t RESERVED4; - __IO uint16_t RXCRCR; - uint16_t RESERVED5; - __IO uint16_t TXCRCR; - uint16_t RESERVED6; - __IO uint16_t I2SCFGR; - uint16_t RESERVED7; - __IO uint16_t I2SPR; - uint16_t RESERVED8; -} SPI_TypeDef; - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint16_t CR1; - uint16_t RESERVED0; - __IO uint16_t CR2; - uint16_t RESERVED1; - __IO uint16_t SMCR; - uint16_t RESERVED2; - __IO uint16_t DIER; - uint16_t RESERVED3; - __IO uint16_t SR; - uint16_t RESERVED4; - __IO uint16_t EGR; - uint16_t RESERVED5; - __IO uint16_t CCMR1; - uint16_t RESERVED6; - __IO uint16_t CCMR2; - uint16_t RESERVED7; - __IO uint16_t CCER; - uint16_t RESERVED8; - __IO uint16_t CNT; - uint16_t RESERVED9; - __IO uint16_t PSC; - uint16_t RESERVED10; - __IO uint16_t ARR; - uint16_t RESERVED11; - __IO uint16_t RCR; - uint16_t RESERVED12; - __IO uint16_t CCR1; - uint16_t RESERVED13; - __IO uint16_t CCR2; - uint16_t RESERVED14; - __IO uint16_t CCR3; - uint16_t RESERVED15; - __IO uint16_t CCR4; - uint16_t RESERVED16; - __IO uint16_t BDTR; - uint16_t RESERVED17; - __IO uint16_t DCR; - uint16_t RESERVED18; - __IO uint16_t DMAR; - uint16_t RESERVED19; -} TIM_TypeDef; - -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint16_t SR; - uint16_t RESERVED0; - __IO uint16_t DR; - uint16_t RESERVED1; - __IO uint16_t BRR; - uint16_t RESERVED2; - __IO uint16_t CR1; - uint16_t RESERVED3; - __IO uint16_t CR2; - uint16_t RESERVED4; - __IO uint16_t CR3; - uint16_t RESERVED5; - __IO uint16_t GTPR; - uint16_t RESERVED6; -} USART_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; - __IO uint32_t CFR; - __IO uint32_t SR; -} WWDG_TypeDef; - -/** - * @} - */ - -/** @addtogroup Peripheral_memory_map - * @{ - */ - - -#define FLASH_BASE ((uint32_t)0x08000000) /*!< FLASH base address in the alias region */ -#define SRAM_BASE ((uint32_t)0x20000000) /*!< SRAM base address in the alias region */ -#define PERIPH_BASE ((uint32_t)0x40000000) /*!< Peripheral base address in the alias region */ - -#define SRAM_BB_BASE ((uint32_t)0x22000000) /*!< SRAM base address in the bit-band region */ -#define PERIPH_BB_BASE ((uint32_t)0x42000000) /*!< Peripheral base address in the bit-band region */ - -#define FSMC_R_BASE ((uint32_t)0xA0000000) /*!< FSMC registers base address */ - -/*!< Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x10000) -#define AHBPERIPH_BASE (PERIPH_BASE + 0x20000) - -#define TIM2_BASE (APB1PERIPH_BASE + 0x0000) -#define TIM3_BASE (APB1PERIPH_BASE + 0x0400) -#define TIM4_BASE (APB1PERIPH_BASE + 0x0800) -#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00) -#define TIM6_BASE (APB1PERIPH_BASE + 0x1000) -#define TIM7_BASE (APB1PERIPH_BASE + 0x1400) -#define TIM12_BASE (APB1PERIPH_BASE + 0x1800) -#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00) -#define TIM14_BASE (APB1PERIPH_BASE + 0x2000) -#define RTC_BASE (APB1PERIPH_BASE + 0x2800) -#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00) -#define IWDG_BASE (APB1PERIPH_BASE + 0x3000) -#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) -#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) -#define USART2_BASE (APB1PERIPH_BASE + 0x4400) -#define USART3_BASE (APB1PERIPH_BASE + 0x4800) -#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) -#define UART5_BASE (APB1PERIPH_BASE + 0x5000) -#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) -#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) -#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) -#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) -#define BKP_BASE (APB1PERIPH_BASE + 0x6C00) -#define PWR_BASE (APB1PERIPH_BASE + 0x7000) -#define DAC_BASE (APB1PERIPH_BASE + 0x7400) -#define CEC_BASE (APB1PERIPH_BASE + 0x7800) - -#define AFIO_BASE (APB2PERIPH_BASE + 0x0000) -#define EXTI_BASE (APB2PERIPH_BASE + 0x0400) -#define GPIOA_BASE (APB2PERIPH_BASE + 0x0800) -#define GPIOB_BASE (APB2PERIPH_BASE + 0x0C00) -#define GPIOC_BASE (APB2PERIPH_BASE + 0x1000) -#define GPIOD_BASE (APB2PERIPH_BASE + 0x1400) -#define GPIOE_BASE (APB2PERIPH_BASE + 0x1800) -#define GPIOF_BASE (APB2PERIPH_BASE + 0x1C00) -#define GPIOG_BASE (APB2PERIPH_BASE + 0x2000) -#define ADC1_BASE (APB2PERIPH_BASE + 0x2400) -#define ADC2_BASE (APB2PERIPH_BASE + 0x2800) -#define TIM1_BASE (APB2PERIPH_BASE + 0x2C00) -#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) -#define TIM8_BASE (APB2PERIPH_BASE + 0x3400) -#define USART1_BASE (APB2PERIPH_BASE + 0x3800) -#define ADC3_BASE (APB2PERIPH_BASE + 0x3C00) -#define TIM15_BASE (APB2PERIPH_BASE + 0x4000) -#define TIM16_BASE (APB2PERIPH_BASE + 0x4400) -#define TIM17_BASE (APB2PERIPH_BASE + 0x4800) -#define TIM9_BASE (APB2PERIPH_BASE + 0x4C00) -#define TIM10_BASE (APB2PERIPH_BASE + 0x5000) -#define TIM11_BASE (APB2PERIPH_BASE + 0x5400) - -#define SDIO_BASE (PERIPH_BASE + 0x18000) - -#define DMA1_BASE (AHBPERIPH_BASE + 0x0000) -#define DMA1_Channel1_BASE (AHBPERIPH_BASE + 0x0008) -#define DMA1_Channel2_BASE (AHBPERIPH_BASE + 0x001C) -#define DMA1_Channel3_BASE (AHBPERIPH_BASE + 0x0030) -#define DMA1_Channel4_BASE (AHBPERIPH_BASE + 0x0044) -#define DMA1_Channel5_BASE (AHBPERIPH_BASE + 0x0058) -#define DMA1_Channel6_BASE (AHBPERIPH_BASE + 0x006C) -#define DMA1_Channel7_BASE (AHBPERIPH_BASE + 0x0080) -#define DMA2_BASE (AHBPERIPH_BASE + 0x0400) -#define DMA2_Channel1_BASE (AHBPERIPH_BASE + 0x0408) -#define DMA2_Channel2_BASE (AHBPERIPH_BASE + 0x041C) -#define DMA2_Channel3_BASE (AHBPERIPH_BASE + 0x0430) -#define DMA2_Channel4_BASE (AHBPERIPH_BASE + 0x0444) -#define DMA2_Channel5_BASE (AHBPERIPH_BASE + 0x0458) -#define RCC_BASE (AHBPERIPH_BASE + 0x1000) -#define CRC_BASE (AHBPERIPH_BASE + 0x3000) - -#define FLASH_R_BASE (AHBPERIPH_BASE + 0x2000) /*!< Flash registers base address */ -#define OB_BASE ((uint32_t)0x1FFFF800) /*!< Flash Option Bytes base address */ - -#define ETH_BASE (AHBPERIPH_BASE + 0x8000) -#define ETH_MAC_BASE (ETH_BASE) -#define ETH_MMC_BASE (ETH_BASE + 0x0100) -#define ETH_PTP_BASE (ETH_BASE + 0x0700) -#define ETH_DMA_BASE (ETH_BASE + 0x1000) - -#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000) /*!< FSMC Bank1 registers base address */ -#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104) /*!< FSMC Bank1E registers base address */ -#define FSMC_Bank2_R_BASE (FSMC_R_BASE + 0x0060) /*!< FSMC Bank2 registers base address */ -#define FSMC_Bank3_R_BASE (FSMC_R_BASE + 0x0080) /*!< FSMC Bank3 registers base address */ -#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0) /*!< FSMC Bank4 registers base address */ - -#define DBGMCU_BASE ((uint32_t)0xE0042000) /*!< Debug MCU registers base address */ - -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ - -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG ((WWDG_TypeDef *) WWDG_BASE) -#define IWDG ((IWDG_TypeDef *) IWDG_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define CAN1 ((CAN_TypeDef *) CAN1_BASE) -#define CAN2 ((CAN_TypeDef *) CAN2_BASE) -#define BKP ((BKP_TypeDef *) BKP_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC ((DAC_TypeDef *) DAC_BASE) -#define CEC ((CEC_TypeDef *) CEC_BASE) -#define AFIO ((AFIO_TypeDef *) AFIO_BASE) -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define ADC2 ((ADC_TypeDef *) ADC2_BASE) -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define ADC3 ((ADC_TypeDef *) ADC3_BASE) -#define TIM15 ((TIM_TypeDef *) TIM15_BASE) -#define TIM16 ((TIM_TypeDef *) TIM16_BASE) -#define TIM17 ((TIM_TypeDef *) TIM17_BASE) -#define TIM9 ((TIM_TypeDef *) TIM9_BASE) -#define TIM10 ((TIM_TypeDef *) TIM10_BASE) -#define TIM11 ((TIM_TypeDef *) TIM11_BASE) -#define SDIO ((SDIO_TypeDef *) SDIO_BASE) -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA1_Channel1 ((DMA_Channel_TypeDef *) DMA1_Channel1_BASE) -#define DMA1_Channel2 ((DMA_Channel_TypeDef *) DMA1_Channel2_BASE) -#define DMA1_Channel3 ((DMA_Channel_TypeDef *) DMA1_Channel3_BASE) -#define DMA1_Channel4 ((DMA_Channel_TypeDef *) DMA1_Channel4_BASE) -#define DMA1_Channel5 ((DMA_Channel_TypeDef *) DMA1_Channel5_BASE) -#define DMA1_Channel6 ((DMA_Channel_TypeDef *) DMA1_Channel6_BASE) -#define DMA1_Channel7 ((DMA_Channel_TypeDef *) DMA1_Channel7_BASE) -#define DMA2_Channel1 ((DMA_Channel_TypeDef *) DMA2_Channel1_BASE) -#define DMA2_Channel2 ((DMA_Channel_TypeDef *) DMA2_Channel2_BASE) -#define DMA2_Channel3 ((DMA_Channel_TypeDef *) DMA2_Channel3_BASE) -#define DMA2_Channel4 ((DMA_Channel_TypeDef *) DMA2_Channel4_BASE) -#define DMA2_Channel5 ((DMA_Channel_TypeDef *) DMA2_Channel5_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define OB ((OB_TypeDef *) OB_BASE) -#define ETH ((ETH_TypeDef *) ETH_BASE) -#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) -#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) -#define FSMC_Bank2 ((FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE) -#define FSMC_Bank3 ((FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE) -#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* CRC calculation unit */ -/* */ -/******************************************************************************/ - -/******************* Bit definition for CRC_DR register *********************/ -#define CRC_DR_DR ((uint32_t)0xFFFFFFFF) /*!< Data register bits */ - - -/******************* Bit definition for CRC_IDR register ********************/ -#define CRC_IDR_IDR ((uint8_t)0xFF) /*!< General-purpose 8-bit data register bits */ - - -/******************** Bit definition for CRC_CR register ********************/ -#define CRC_CR_RESET ((uint8_t)0x01) /*!< RESET bit */ - -/******************************************************************************/ -/* */ -/* Power Control */ -/* */ -/******************************************************************************/ - -/******************** Bit definition for PWR_CR register ********************/ -#define PWR_CR_LPDS ((uint16_t)0x0001) /*!< Low-Power Deepsleep */ -#define PWR_CR_PDDS ((uint16_t)0x0002) /*!< Power Down Deepsleep */ -#define PWR_CR_CWUF ((uint16_t)0x0004) /*!< Clear Wakeup Flag */ -#define PWR_CR_CSBF ((uint16_t)0x0008) /*!< Clear Standby Flag */ -#define PWR_CR_PVDE ((uint16_t)0x0010) /*!< Power Voltage Detector Enable */ - -#define PWR_CR_PLS ((uint16_t)0x00E0) /*!< PLS[2:0] bits (PVD Level Selection) */ -#define PWR_CR_PLS_0 ((uint16_t)0x0020) /*!< Bit 0 */ -#define PWR_CR_PLS_1 ((uint16_t)0x0040) /*!< Bit 1 */ -#define PWR_CR_PLS_2 ((uint16_t)0x0080) /*!< Bit 2 */ - -/*!< PVD level configuration */ -#define PWR_CR_PLS_2V2 ((uint16_t)0x0000) /*!< PVD level 2.2V */ -#define PWR_CR_PLS_2V3 ((uint16_t)0x0020) /*!< PVD level 2.3V */ -#define PWR_CR_PLS_2V4 ((uint16_t)0x0040) /*!< PVD level 2.4V */ -#define PWR_CR_PLS_2V5 ((uint16_t)0x0060) /*!< PVD level 2.5V */ -#define PWR_CR_PLS_2V6 ((uint16_t)0x0080) /*!< PVD level 2.6V */ -#define PWR_CR_PLS_2V7 ((uint16_t)0x00A0) /*!< PVD level 2.7V */ -#define PWR_CR_PLS_2V8 ((uint16_t)0x00C0) /*!< PVD level 2.8V */ -#define PWR_CR_PLS_2V9 ((uint16_t)0x00E0) /*!< PVD level 2.9V */ - -#define PWR_CR_DBP ((uint16_t)0x0100) /*!< Disable Backup Domain write protection */ - - -/******************* Bit definition for PWR_CSR register ********************/ -#define PWR_CSR_WUF ((uint16_t)0x0001) /*!< Wakeup Flag */ -#define PWR_CSR_SBF ((uint16_t)0x0002) /*!< Standby Flag */ -#define PWR_CSR_PVDO ((uint16_t)0x0004) /*!< PVD Output */ -#define PWR_CSR_EWUP ((uint16_t)0x0100) /*!< Enable WKUP pin */ - -/******************************************************************************/ -/* */ -/* Backup registers */ -/* */ -/******************************************************************************/ - -/******************* Bit definition for BKP_DR1 register ********************/ -#define BKP_DR1_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR2 register ********************/ -#define BKP_DR2_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR3 register ********************/ -#define BKP_DR3_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR4 register ********************/ -#define BKP_DR4_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR5 register ********************/ -#define BKP_DR5_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR6 register ********************/ -#define BKP_DR6_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR7 register ********************/ -#define BKP_DR7_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR8 register ********************/ -#define BKP_DR8_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR9 register ********************/ -#define BKP_DR9_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR10 register *******************/ -#define BKP_DR10_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR11 register *******************/ -#define BKP_DR11_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR12 register *******************/ -#define BKP_DR12_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR13 register *******************/ -#define BKP_DR13_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR14 register *******************/ -#define BKP_DR14_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR15 register *******************/ -#define BKP_DR15_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR16 register *******************/ -#define BKP_DR16_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR17 register *******************/ -#define BKP_DR17_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/****************** Bit definition for BKP_DR18 register ********************/ -#define BKP_DR18_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR19 register *******************/ -#define BKP_DR19_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR20 register *******************/ -#define BKP_DR20_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR21 register *******************/ -#define BKP_DR21_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR22 register *******************/ -#define BKP_DR22_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR23 register *******************/ -#define BKP_DR23_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR24 register *******************/ -#define BKP_DR24_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR25 register *******************/ -#define BKP_DR25_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR26 register *******************/ -#define BKP_DR26_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR27 register *******************/ -#define BKP_DR27_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR28 register *******************/ -#define BKP_DR28_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR29 register *******************/ -#define BKP_DR29_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR30 register *******************/ -#define BKP_DR30_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR31 register *******************/ -#define BKP_DR31_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR32 register *******************/ -#define BKP_DR32_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR33 register *******************/ -#define BKP_DR33_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR34 register *******************/ -#define BKP_DR34_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR35 register *******************/ -#define BKP_DR35_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR36 register *******************/ -#define BKP_DR36_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR37 register *******************/ -#define BKP_DR37_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR38 register *******************/ -#define BKP_DR38_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR39 register *******************/ -#define BKP_DR39_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR40 register *******************/ -#define BKP_DR40_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR41 register *******************/ -#define BKP_DR41_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/******************* Bit definition for BKP_DR42 register *******************/ -#define BKP_DR42_D ((uint16_t)0xFFFF) /*!< Backup data */ - -/****************** Bit definition for BKP_RTCCR register *******************/ -#define BKP_RTCCR_CAL ((uint16_t)0x007F) /*!< Calibration value */ -#define BKP_RTCCR_CCO ((uint16_t)0x0080) /*!< Calibration Clock Output */ -#define BKP_RTCCR_ASOE ((uint16_t)0x0100) /*!< Alarm or Second Output Enable */ -#define BKP_RTCCR_ASOS ((uint16_t)0x0200) /*!< Alarm or Second Output Selection */ - -/******************** Bit definition for BKP_CR register ********************/ -#define BKP_CR_TPE ((uint8_t)0x01) /*!< TAMPER pin enable */ -#define BKP_CR_TPAL ((uint8_t)0x02) /*!< TAMPER pin active level */ - -/******************* Bit definition for BKP_CSR register ********************/ -#define BKP_CSR_CTE ((uint16_t)0x0001) /*!< Clear Tamper event */ -#define BKP_CSR_CTI ((uint16_t)0x0002) /*!< Clear Tamper Interrupt */ -#define BKP_CSR_TPIE ((uint16_t)0x0004) /*!< TAMPER Pin interrupt enable */ -#define BKP_CSR_TEF ((uint16_t)0x0100) /*!< Tamper Event Flag */ -#define BKP_CSR_TIF ((uint16_t)0x0200) /*!< Tamper Interrupt Flag */ - -/******************************************************************************/ -/* */ -/* Reset and Clock Control */ -/* */ -/******************************************************************************/ - -/******************** Bit definition for RCC_CR register ********************/ -#define RCC_CR_HSION ((uint32_t)0x00000001) /*!< Internal High Speed clock enable */ -#define RCC_CR_HSIRDY ((uint32_t)0x00000002) /*!< Internal High Speed clock ready flag */ -#define RCC_CR_HSITRIM ((uint32_t)0x000000F8) /*!< Internal High Speed clock trimming */ -#define RCC_CR_HSICAL ((uint32_t)0x0000FF00) /*!< Internal High Speed clock Calibration */ -#define RCC_CR_HSEON ((uint32_t)0x00010000) /*!< External High Speed clock enable */ -#define RCC_CR_HSERDY ((uint32_t)0x00020000) /*!< External High Speed clock ready flag */ -#define RCC_CR_HSEBYP ((uint32_t)0x00040000) /*!< External High Speed clock Bypass */ -#define RCC_CR_CSSON ((uint32_t)0x00080000) /*!< Clock Security System enable */ -#define RCC_CR_PLLON ((uint32_t)0x01000000) /*!< PLL enable */ -#define RCC_CR_PLLRDY ((uint32_t)0x02000000) /*!< PLL clock ready flag */ - -#ifdef STM32F10X_CL - #define RCC_CR_PLL2ON ((uint32_t)0x04000000) /*!< PLL2 enable */ - #define RCC_CR_PLL2RDY ((uint32_t)0x08000000) /*!< PLL2 clock ready flag */ - #define RCC_CR_PLL3ON ((uint32_t)0x10000000) /*!< PLL3 enable */ - #define RCC_CR_PLL3RDY ((uint32_t)0x20000000) /*!< PLL3 clock ready flag */ -#endif /* STM32F10X_CL */ - -/******************* Bit definition for RCC_CFGR register *******************/ -/*!< SW configuration */ -#define RCC_CFGR_SW ((uint32_t)0x00000003) /*!< SW[1:0] bits (System clock Switch) */ -#define RCC_CFGR_SW_0 ((uint32_t)0x00000001) /*!< Bit 0 */ -#define RCC_CFGR_SW_1 ((uint32_t)0x00000002) /*!< Bit 1 */ - -#define RCC_CFGR_SW_HSI ((uint32_t)0x00000000) /*!< HSI selected as system clock */ -#define RCC_CFGR_SW_HSE ((uint32_t)0x00000001) /*!< HSE selected as system clock */ -#define RCC_CFGR_SW_PLL ((uint32_t)0x00000002) /*!< PLL selected as system clock */ - -/*!< SWS configuration */ -#define RCC_CFGR_SWS ((uint32_t)0x0000000C) /*!< SWS[1:0] bits (System Clock Switch Status) */ -#define RCC_CFGR_SWS_0 ((uint32_t)0x00000004) /*!< Bit 0 */ -#define RCC_CFGR_SWS_1 ((uint32_t)0x00000008) /*!< Bit 1 */ - -#define RCC_CFGR_SWS_HSI ((uint32_t)0x00000000) /*!< HSI oscillator used as system clock */ -#define RCC_CFGR_SWS_HSE ((uint32_t)0x00000004) /*!< HSE oscillator used as system clock */ -#define RCC_CFGR_SWS_PLL ((uint32_t)0x00000008) /*!< PLL used as system clock */ - -/*!< HPRE configuration */ -#define RCC_CFGR_HPRE ((uint32_t)0x000000F0) /*!< HPRE[3:0] bits (AHB prescaler) */ -#define RCC_CFGR_HPRE_0 ((uint32_t)0x00000010) /*!< Bit 0 */ -#define RCC_CFGR_HPRE_1 ((uint32_t)0x00000020) /*!< Bit 1 */ -#define RCC_CFGR_HPRE_2 ((uint32_t)0x00000040) /*!< Bit 2 */ -#define RCC_CFGR_HPRE_3 ((uint32_t)0x00000080) /*!< Bit 3 */ - -#define RCC_CFGR_HPRE_DIV1 ((uint32_t)0x00000000) /*!< SYSCLK not divided */ -#define RCC_CFGR_HPRE_DIV2 ((uint32_t)0x00000080) /*!< SYSCLK divided by 2 */ -#define RCC_CFGR_HPRE_DIV4 ((uint32_t)0x00000090) /*!< SYSCLK divided by 4 */ -#define RCC_CFGR_HPRE_DIV8 ((uint32_t)0x000000A0) /*!< SYSCLK divided by 8 */ -#define RCC_CFGR_HPRE_DIV16 ((uint32_t)0x000000B0) /*!< SYSCLK divided by 16 */ -#define RCC_CFGR_HPRE_DIV64 ((uint32_t)0x000000C0) /*!< SYSCLK divided by 64 */ -#define RCC_CFGR_HPRE_DIV128 ((uint32_t)0x000000D0) /*!< SYSCLK divided by 128 */ -#define RCC_CFGR_HPRE_DIV256 ((uint32_t)0x000000E0) /*!< SYSCLK divided by 256 */ -#define RCC_CFGR_HPRE_DIV512 ((uint32_t)0x000000F0) /*!< SYSCLK divided by 512 */ - -/*!< PPRE1 configuration */ -#define RCC_CFGR_PPRE1 ((uint32_t)0x00000700) /*!< PRE1[2:0] bits (APB1 prescaler) */ -#define RCC_CFGR_PPRE1_0 ((uint32_t)0x00000100) /*!< Bit 0 */ -#define RCC_CFGR_PPRE1_1 ((uint32_t)0x00000200) /*!< Bit 1 */ -#define RCC_CFGR_PPRE1_2 ((uint32_t)0x00000400) /*!< Bit 2 */ - -#define RCC_CFGR_PPRE1_DIV1 ((uint32_t)0x00000000) /*!< HCLK not divided */ -#define RCC_CFGR_PPRE1_DIV2 ((uint32_t)0x00000400) /*!< HCLK divided by 2 */ -#define RCC_CFGR_PPRE1_DIV4 ((uint32_t)0x00000500) /*!< HCLK divided by 4 */ -#define RCC_CFGR_PPRE1_DIV8 ((uint32_t)0x00000600) /*!< HCLK divided by 8 */ -#define RCC_CFGR_PPRE1_DIV16 ((uint32_t)0x00000700) /*!< HCLK divided by 16 */ - -/*!< PPRE2 configuration */ -#define RCC_CFGR_PPRE2 ((uint32_t)0x00003800) /*!< PRE2[2:0] bits (APB2 prescaler) */ -#define RCC_CFGR_PPRE2_0 ((uint32_t)0x00000800) /*!< Bit 0 */ -#define RCC_CFGR_PPRE2_1 ((uint32_t)0x00001000) /*!< Bit 1 */ -#define RCC_CFGR_PPRE2_2 ((uint32_t)0x00002000) /*!< Bit 2 */ - -#define RCC_CFGR_PPRE2_DIV1 ((uint32_t)0x00000000) /*!< HCLK not divided */ -#define RCC_CFGR_PPRE2_DIV2 ((uint32_t)0x00002000) /*!< HCLK divided by 2 */ -#define RCC_CFGR_PPRE2_DIV4 ((uint32_t)0x00002800) /*!< HCLK divided by 4 */ -#define RCC_CFGR_PPRE2_DIV8 ((uint32_t)0x00003000) /*!< HCLK divided by 8 */ -#define RCC_CFGR_PPRE2_DIV16 ((uint32_t)0x00003800) /*!< HCLK divided by 16 */ - -/*!< ADCPPRE configuration */ -#define RCC_CFGR_ADCPRE ((uint32_t)0x0000C000) /*!< ADCPRE[1:0] bits (ADC prescaler) */ -#define RCC_CFGR_ADCPRE_0 ((uint32_t)0x00004000) /*!< Bit 0 */ -#define RCC_CFGR_ADCPRE_1 ((uint32_t)0x00008000) /*!< Bit 1 */ - -#define RCC_CFGR_ADCPRE_DIV2 ((uint32_t)0x00000000) /*!< PCLK2 divided by 2 */ -#define RCC_CFGR_ADCPRE_DIV4 ((uint32_t)0x00004000) /*!< PCLK2 divided by 4 */ -#define RCC_CFGR_ADCPRE_DIV6 ((uint32_t)0x00008000) /*!< PCLK2 divided by 6 */ -#define RCC_CFGR_ADCPRE_DIV8 ((uint32_t)0x0000C000) /*!< PCLK2 divided by 8 */ - -#define RCC_CFGR_PLLSRC ((uint32_t)0x00010000) /*!< PLL entry clock source */ - -#define RCC_CFGR_PLLXTPRE ((uint32_t)0x00020000) /*!< HSE divider for PLL entry */ - -/*!< PLLMUL configuration */ -#define RCC_CFGR_PLLMULL ((uint32_t)0x003C0000) /*!< PLLMUL[3:0] bits (PLL multiplication factor) */ -#define RCC_CFGR_PLLMULL_0 ((uint32_t)0x00040000) /*!< Bit 0 */ -#define RCC_CFGR_PLLMULL_1 ((uint32_t)0x00080000) /*!< Bit 1 */ -#define RCC_CFGR_PLLMULL_2 ((uint32_t)0x00100000) /*!< Bit 2 */ -#define RCC_CFGR_PLLMULL_3 ((uint32_t)0x00200000) /*!< Bit 3 */ - -#ifdef STM32F10X_CL - #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ - #define RCC_CFGR_PLLSRC_PREDIV1 ((uint32_t)0x00010000) /*!< PREDIV1 clock selected as PLL entry clock source */ - - #define RCC_CFGR_PLLXTPRE_PREDIV1 ((uint32_t)0x00000000) /*!< PREDIV1 clock not divided for PLL entry */ - #define RCC_CFGR_PLLXTPRE_PREDIV1_Div2 ((uint32_t)0x00020000) /*!< PREDIV1 clock divided by 2 for PLL entry */ - - #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock * 4 */ - #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock * 5 */ - #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock * 6 */ - #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock * 7 */ - #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock * 8 */ - #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock * 9 */ - #define RCC_CFGR_PLLMULL6_5 ((uint32_t)0x00340000) /*!< PLL input clock * 6.5 */ - - #define RCC_CFGR_OTGFSPRE ((uint32_t)0x00400000) /*!< USB OTG FS prescaler */ - -/*!< MCO configuration */ - #define RCC_CFGR_MCO ((uint32_t)0x0F000000) /*!< MCO[3:0] bits (Microcontroller Clock Output) */ - #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ - #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ - #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ - #define RCC_CFGR_MCO_3 ((uint32_t)0x08000000) /*!< Bit 3 */ - - #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ - #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ - #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ - #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ - #define RCC_CFGR_MCO_PLLCLK_Div2 ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ - #define RCC_CFGR_MCO_PLL2CLK ((uint32_t)0x08000000) /*!< PLL2 clock selected as MCO source*/ - #define RCC_CFGR_MCO_PLL3CLK_Div2 ((uint32_t)0x09000000) /*!< PLL3 clock divided by 2 selected as MCO source*/ - #define RCC_CFGR_MCO_Ext_HSE ((uint32_t)0x0A000000) /*!< XT1 external 3-25 MHz oscillator clock selected as MCO source */ - #define RCC_CFGR_MCO_PLL3CLK ((uint32_t)0x0B000000) /*!< PLL3 clock selected as MCO source */ -#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) - #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ - #define RCC_CFGR_PLLSRC_PREDIV1 ((uint32_t)0x00010000) /*!< PREDIV1 clock selected as PLL entry clock source */ - - #define RCC_CFGR_PLLXTPRE_PREDIV1 ((uint32_t)0x00000000) /*!< PREDIV1 clock not divided for PLL entry */ - #define RCC_CFGR_PLLXTPRE_PREDIV1_Div2 ((uint32_t)0x00020000) /*!< PREDIV1 clock divided by 2 for PLL entry */ - - #define RCC_CFGR_PLLMULL2 ((uint32_t)0x00000000) /*!< PLL input clock*2 */ - #define RCC_CFGR_PLLMULL3 ((uint32_t)0x00040000) /*!< PLL input clock*3 */ - #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock*4 */ - #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock*5 */ - #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock*6 */ - #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock*7 */ - #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock*8 */ - #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock*9 */ - #define RCC_CFGR_PLLMULL10 ((uint32_t)0x00200000) /*!< PLL input clock10 */ - #define RCC_CFGR_PLLMULL11 ((uint32_t)0x00240000) /*!< PLL input clock*11 */ - #define RCC_CFGR_PLLMULL12 ((uint32_t)0x00280000) /*!< PLL input clock*12 */ - #define RCC_CFGR_PLLMULL13 ((uint32_t)0x002C0000) /*!< PLL input clock*13 */ - #define RCC_CFGR_PLLMULL14 ((uint32_t)0x00300000) /*!< PLL input clock*14 */ - #define RCC_CFGR_PLLMULL15 ((uint32_t)0x00340000) /*!< PLL input clock*15 */ - #define RCC_CFGR_PLLMULL16 ((uint32_t)0x00380000) /*!< PLL input clock*16 */ - -/*!< MCO configuration */ - #define RCC_CFGR_MCO ((uint32_t)0x07000000) /*!< MCO[2:0] bits (Microcontroller Clock Output) */ - #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ - #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ - #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ - - #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ - #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ - #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ - #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ - #define RCC_CFGR_MCO_PLL ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ -#else - #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ - #define RCC_CFGR_PLLSRC_HSE ((uint32_t)0x00010000) /*!< HSE clock selected as PLL entry clock source */ - - #define RCC_CFGR_PLLXTPRE_HSE ((uint32_t)0x00000000) /*!< HSE clock not divided for PLL entry */ - #define RCC_CFGR_PLLXTPRE_HSE_Div2 ((uint32_t)0x00020000) /*!< HSE clock divided by 2 for PLL entry */ - - #define RCC_CFGR_PLLMULL2 ((uint32_t)0x00000000) /*!< PLL input clock*2 */ - #define RCC_CFGR_PLLMULL3 ((uint32_t)0x00040000) /*!< PLL input clock*3 */ - #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock*4 */ - #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock*5 */ - #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock*6 */ - #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock*7 */ - #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock*8 */ - #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock*9 */ - #define RCC_CFGR_PLLMULL10 ((uint32_t)0x00200000) /*!< PLL input clock10 */ - #define RCC_CFGR_PLLMULL11 ((uint32_t)0x00240000) /*!< PLL input clock*11 */ - #define RCC_CFGR_PLLMULL12 ((uint32_t)0x00280000) /*!< PLL input clock*12 */ - #define RCC_CFGR_PLLMULL13 ((uint32_t)0x002C0000) /*!< PLL input clock*13 */ - #define RCC_CFGR_PLLMULL14 ((uint32_t)0x00300000) /*!< PLL input clock*14 */ - #define RCC_CFGR_PLLMULL15 ((uint32_t)0x00340000) /*!< PLL input clock*15 */ - #define RCC_CFGR_PLLMULL16 ((uint32_t)0x00380000) /*!< PLL input clock*16 */ - #define RCC_CFGR_USBPRE ((uint32_t)0x00400000) /*!< USB Device prescaler */ - -/*!< MCO configuration */ - #define RCC_CFGR_MCO ((uint32_t)0x07000000) /*!< MCO[2:0] bits (Microcontroller Clock Output) */ - #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ - #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ - #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ - - #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ - #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ - #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ - #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ - #define RCC_CFGR_MCO_PLL ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ -#endif /* STM32F10X_CL */ - -/*!<****************** Bit definition for RCC_CIR register ********************/ -#define RCC_CIR_LSIRDYF ((uint32_t)0x00000001) /*!< LSI Ready Interrupt flag */ -#define RCC_CIR_LSERDYF ((uint32_t)0x00000002) /*!< LSE Ready Interrupt flag */ -#define RCC_CIR_HSIRDYF ((uint32_t)0x00000004) /*!< HSI Ready Interrupt flag */ -#define RCC_CIR_HSERDYF ((uint32_t)0x00000008) /*!< HSE Ready Interrupt flag */ -#define RCC_CIR_PLLRDYF ((uint32_t)0x00000010) /*!< PLL Ready Interrupt flag */ -#define RCC_CIR_CSSF ((uint32_t)0x00000080) /*!< Clock Security System Interrupt flag */ -#define RCC_CIR_LSIRDYIE ((uint32_t)0x00000100) /*!< LSI Ready Interrupt Enable */ -#define RCC_CIR_LSERDYIE ((uint32_t)0x00000200) /*!< LSE Ready Interrupt Enable */ -#define RCC_CIR_HSIRDYIE ((uint32_t)0x00000400) /*!< HSI Ready Interrupt Enable */ -#define RCC_CIR_HSERDYIE ((uint32_t)0x00000800) /*!< HSE Ready Interrupt Enable */ -#define RCC_CIR_PLLRDYIE ((uint32_t)0x00001000) /*!< PLL Ready Interrupt Enable */ -#define RCC_CIR_LSIRDYC ((uint32_t)0x00010000) /*!< LSI Ready Interrupt Clear */ -#define RCC_CIR_LSERDYC ((uint32_t)0x00020000) /*!< LSE Ready Interrupt Clear */ -#define RCC_CIR_HSIRDYC ((uint32_t)0x00040000) /*!< HSI Ready Interrupt Clear */ -#define RCC_CIR_HSERDYC ((uint32_t)0x00080000) /*!< HSE Ready Interrupt Clear */ -#define RCC_CIR_PLLRDYC ((uint32_t)0x00100000) /*!< PLL Ready Interrupt Clear */ -#define RCC_CIR_CSSC ((uint32_t)0x00800000) /*!< Clock Security System Interrupt Clear */ - -#ifdef STM32F10X_CL - #define RCC_CIR_PLL2RDYF ((uint32_t)0x00000020) /*!< PLL2 Ready Interrupt flag */ - #define RCC_CIR_PLL3RDYF ((uint32_t)0x00000040) /*!< PLL3 Ready Interrupt flag */ - #define RCC_CIR_PLL2RDYIE ((uint32_t)0x00002000) /*!< PLL2 Ready Interrupt Enable */ - #define RCC_CIR_PLL3RDYIE ((uint32_t)0x00004000) /*!< PLL3 Ready Interrupt Enable */ - #define RCC_CIR_PLL2RDYC ((uint32_t)0x00200000) /*!< PLL2 Ready Interrupt Clear */ - #define RCC_CIR_PLL3RDYC ((uint32_t)0x00400000) /*!< PLL3 Ready Interrupt Clear */ -#endif /* STM32F10X_CL */ - -/***************** Bit definition for RCC_APB2RSTR register *****************/ -#define RCC_APB2RSTR_AFIORST ((uint32_t)0x00000001) /*!< Alternate Function I/O reset */ -#define RCC_APB2RSTR_IOPARST ((uint32_t)0x00000004) /*!< I/O port A reset */ -#define RCC_APB2RSTR_IOPBRST ((uint32_t)0x00000008) /*!< I/O port B reset */ -#define RCC_APB2RSTR_IOPCRST ((uint32_t)0x00000010) /*!< I/O port C reset */ -#define RCC_APB2RSTR_IOPDRST ((uint32_t)0x00000020) /*!< I/O port D reset */ -#define RCC_APB2RSTR_ADC1RST ((uint32_t)0x00000200) /*!< ADC 1 interface reset */ - -#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) -#define RCC_APB2RSTR_ADC2RST ((uint32_t)0x00000400) /*!< ADC 2 interface reset */ -#endif - -#define RCC_APB2RSTR_TIM1RST ((uint32_t)0x00000800) /*!< TIM1 Timer reset */ -#define RCC_APB2RSTR_SPI1RST ((uint32_t)0x00001000) /*!< SPI 1 reset */ -#define RCC_APB2RSTR_USART1RST ((uint32_t)0x00004000) /*!< USART1 reset */ - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) -#define RCC_APB2RSTR_TIM15RST ((uint32_t)0x00010000) /*!< TIM15 Timer reset */ -#define RCC_APB2RSTR_TIM16RST ((uint32_t)0x00020000) /*!< TIM16 Timer reset */ -#define RCC_APB2RSTR_TIM17RST ((uint32_t)0x00040000) /*!< TIM17 Timer reset */ -#endif - -#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) - #define RCC_APB2RSTR_IOPERST ((uint32_t)0x00000040) /*!< I/O port E reset */ -#endif /* STM32F10X_LD && STM32F10X_LD_VL */ - -#if defined (STM32F10X_HD) || defined (STM32F10X_XL) - #define RCC_APB2RSTR_IOPFRST ((uint32_t)0x00000080) /*!< I/O port F reset */ - #define RCC_APB2RSTR_IOPGRST ((uint32_t)0x00000100) /*!< I/O port G reset */ - #define RCC_APB2RSTR_TIM8RST ((uint32_t)0x00002000) /*!< TIM8 Timer reset */ - #define RCC_APB2RSTR_ADC3RST ((uint32_t)0x00008000) /*!< ADC3 interface reset */ -#endif - -#if defined (STM32F10X_HD_VL) - #define RCC_APB2RSTR_IOPFRST ((uint32_t)0x00000080) /*!< I/O port F reset */ - #define RCC_APB2RSTR_IOPGRST ((uint32_t)0x00000100) /*!< I/O port G reset */ -#endif - -#ifdef STM32F10X_XL - #define RCC_APB2RSTR_TIM9RST ((uint32_t)0x00080000) /*!< TIM9 Timer reset */ - #define RCC_APB2RSTR_TIM10RST ((uint32_t)0x00100000) /*!< TIM10 Timer reset */ - #define RCC_APB2RSTR_TIM11RST ((uint32_t)0x00200000) /*!< TIM11 Timer reset */ -#endif /* STM32F10X_XL */ - -/***************** Bit definition for RCC_APB1RSTR register *****************/ -#define RCC_APB1RSTR_TIM2RST ((uint32_t)0x00000001) /*!< Timer 2 reset */ -#define RCC_APB1RSTR_TIM3RST ((uint32_t)0x00000002) /*!< Timer 3 reset */ -#define RCC_APB1RSTR_WWDGRST ((uint32_t)0x00000800) /*!< Window Watchdog reset */ -#define RCC_APB1RSTR_USART2RST ((uint32_t)0x00020000) /*!< USART 2 reset */ -#define RCC_APB1RSTR_I2C1RST ((uint32_t)0x00200000) /*!< I2C 1 reset */ - -#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) -#define RCC_APB1RSTR_CAN1RST ((uint32_t)0x02000000) /*!< CAN1 reset */ -#endif - -#define RCC_APB1RSTR_BKPRST ((uint32_t)0x08000000) /*!< Backup interface reset */ -#define RCC_APB1RSTR_PWRRST ((uint32_t)0x10000000) /*!< Power interface reset */ - -#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) - #define RCC_APB1RSTR_TIM4RST ((uint32_t)0x00000004) /*!< Timer 4 reset */ - #define RCC_APB1RSTR_SPI2RST ((uint32_t)0x00004000) /*!< SPI 2 reset */ - #define RCC_APB1RSTR_USART3RST ((uint32_t)0x00040000) /*!< RUSART 3 reset */ - #define RCC_APB1RSTR_I2C2RST ((uint32_t)0x00400000) /*!< I2C 2 reset */ -#endif /* STM32F10X_LD && STM32F10X_LD_VL */ - -#if defined (STM32F10X_HD) || defined (STM32F10X_MD) || defined (STM32F10X_LD) || defined (STM32F10X_XL) - #define RCC_APB1RSTR_USBRST ((uint32_t)0x00800000) /*!< USB Device reset */ -#endif - -#if defined (STM32F10X_HD) || defined (STM32F10X_CL) || defined (STM32F10X_XL) - #define RCC_APB1RSTR_TIM5RST ((uint32_t)0x00000008) /*!< Timer 5 reset */ - #define RCC_APB1RSTR_TIM6RST ((uint32_t)0x00000010) /*!< Timer 6 reset */ - #define RCC_APB1RSTR_TIM7RST ((uint32_t)0x00000020) /*!< Timer 7 reset */ - #define RCC_APB1RSTR_SPI3RST ((uint32_t)0x00008000) /*!< SPI 3 reset */ - #define RCC_APB1RSTR_UART4RST ((uint32_t)0x00080000) /*!< UART 4 reset */ - #define RCC_APB1RSTR_UART5RST ((uint32_t)0x00100000) /*!< UART 5 reset */ - #define RCC_APB1RSTR_DACRST ((uint32_t)0x20000000) /*!< DAC interface reset */ -#endif - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) - #define RCC_APB1RSTR_TIM6RST ((uint32_t)0x00000010) /*!< Timer 6 reset */ - #define RCC_APB1RSTR_TIM7RST ((uint32_t)0x00000020) /*!< Timer 7 reset */ - #define RCC_APB1RSTR_DACRST ((uint32_t)0x20000000) /*!< DAC interface reset */ - #define RCC_APB1RSTR_CECRST ((uint32_t)0x40000000) /*!< CEC interface reset */ -#endif - -#if defined (STM32F10X_HD_VL) - #define RCC_APB1RSTR_TIM5RST ((uint32_t)0x00000008) /*!< Timer 5 reset */ - #define RCC_APB1RSTR_TIM12RST ((uint32_t)0x00000040) /*!< TIM12 Timer reset */ - #define RCC_APB1RSTR_TIM13RST ((uint32_t)0x00000080) /*!< TIM13 Timer reset */ - #define RCC_APB1RSTR_TIM14RST ((uint32_t)0x00000100) /*!< TIM14 Timer reset */ - #define RCC_APB1RSTR_SPI3RST ((uint32_t)0x00008000) /*!< SPI 3 reset */ - #define RCC_APB1RSTR_UART4RST ((uint32_t)0x00080000) /*!< UART 4 reset */ - #define RCC_APB1RSTR_UART5RST ((uint32_t)0x00100000) /*!< UART 5 reset */ -#endif - -#ifdef STM32F10X_CL - #define RCC_APB1RSTR_CAN2RST ((uint32_t)0x04000000) /*!< CAN2 reset */ -#endif /* STM32F10X_CL */ - -#ifdef STM32F10X_XL - #define RCC_APB1RSTR_TIM12RST ((uint32_t)0x00000040) /*!< TIM12 Timer reset */ - #define RCC_APB1RSTR_TIM13RST ((uint32_t)0x00000080) /*!< TIM13 Timer reset */ - #define RCC_APB1RSTR_TIM14RST ((uint32_t)0x00000100) /*!< TIM14 Timer reset */ -#endif /* STM32F10X_XL */ - -/****************** Bit definition for RCC_AHBENR register ******************/ -#define RCC_AHBENR_DMA1EN ((uint16_t)0x0001) /*!< DMA1 clock enable */ -#define RCC_AHBENR_SRAMEN ((uint16_t)0x0004) /*!< SRAM interface clock enable */ -#define RCC_AHBENR_FLITFEN ((uint16_t)0x0010) /*!< FLITF clock enable */ -#define RCC_AHBENR_CRCEN ((uint16_t)0x0040) /*!< CRC clock enable */ - -#if defined (STM32F10X_HD) || defined (STM32F10X_CL) || defined (STM32F10X_HD_VL) - #define RCC_AHBENR_DMA2EN ((uint16_t)0x0002) /*!< DMA2 clock enable */ -#endif - -#if defined (STM32F10X_HD) || defined (STM32F10X_XL) - #define RCC_AHBENR_FSMCEN ((uint16_t)0x0100) /*!< FSMC clock enable */ - #define RCC_AHBENR_SDIOEN ((uint16_t)0x0400) /*!< SDIO clock enable */ -#endif - -#if defined (STM32F10X_HD_VL) - #define RCC_AHBENR_FSMCEN ((uint16_t)0x0100) /*!< FSMC clock enable */ -#endif - -#ifdef STM32F10X_CL - #define RCC_AHBENR_OTGFSEN ((uint32_t)0x00001000) /*!< USB OTG FS clock enable */ - #define RCC_AHBENR_ETHMACEN ((uint32_t)0x00004000) /*!< ETHERNET MAC clock enable */ - #define RCC_AHBENR_ETHMACTXEN ((uint32_t)0x00008000) /*!< ETHERNET MAC Tx clock enable */ - #define RCC_AHBENR_ETHMACRXEN ((uint32_t)0x00010000) /*!< ETHERNET MAC Rx clock enable */ -#endif /* STM32F10X_CL */ - -/****************** Bit definition for RCC_APB2ENR register *****************/ -#define RCC_APB2ENR_AFIOEN ((uint32_t)0x00000001) /*!< Alternate Function I/O clock enable */ -#define RCC_APB2ENR_IOPAEN ((uint32_t)0x00000004) /*!< I/O port A clock enable */ -#define RCC_APB2ENR_IOPBEN ((uint32_t)0x00000008) /*!< I/O port B clock enable */ -#define RCC_APB2ENR_IOPCEN ((uint32_t)0x00000010) /*!< I/O port C clock enable */ -#define RCC_APB2ENR_IOPDEN ((uint32_t)0x00000020) /*!< I/O port D clock enable */ -#define RCC_APB2ENR_ADC1EN ((uint32_t)0x00000200) /*!< ADC 1 interface clock enable */ - -#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) -#define RCC_APB2ENR_ADC2EN ((uint32_t)0x00000400) /*!< ADC 2 interface clock enable */ -#endif - -#define RCC_APB2ENR_TIM1EN ((uint32_t)0x00000800) /*!< TIM1 Timer clock enable */ -#define RCC_APB2ENR_SPI1EN ((uint32_t)0x00001000) /*!< SPI 1 clock enable */ -#define RCC_APB2ENR_USART1EN ((uint32_t)0x00004000) /*!< USART1 clock enable */ - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) -#define RCC_APB2ENR_TIM15EN ((uint32_t)0x00010000) /*!< TIM15 Timer clock enable */ -#define RCC_APB2ENR_TIM16EN ((uint32_t)0x00020000) /*!< TIM16 Timer clock enable */ -#define RCC_APB2ENR_TIM17EN ((uint32_t)0x00040000) /*!< TIM17 Timer clock enable */ -#endif - -#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) - #define RCC_APB2ENR_IOPEEN ((uint32_t)0x00000040) /*!< I/O port E clock enable */ -#endif /* STM32F10X_LD && STM32F10X_LD_VL */ - -#if defined (STM32F10X_HD) || defined (STM32F10X_XL) - #define RCC_APB2ENR_IOPFEN ((uint32_t)0x00000080) /*!< I/O port F clock enable */ - #define RCC_APB2ENR_IOPGEN ((uint32_t)0x00000100) /*!< I/O port G clock enable */ - #define RCC_APB2ENR_TIM8EN ((uint32_t)0x00002000) /*!< TIM8 Timer clock enable */ - #define RCC_APB2ENR_ADC3EN ((uint32_t)0x00008000) /*!< DMA1 clock enable */ -#endif - -#if defined (STM32F10X_HD_VL) - #define RCC_APB2ENR_IOPFEN ((uint32_t)0x00000080) /*!< I/O port F clock enable */ - #define RCC_APB2ENR_IOPGEN ((uint32_t)0x00000100) /*!< I/O port G clock enable */ -#endif - -#ifdef STM32F10X_XL - #define RCC_APB2ENR_TIM9EN ((uint32_t)0x00080000) /*!< TIM9 Timer clock enable */ - #define RCC_APB2ENR_TIM10EN ((uint32_t)0x00100000) /*!< TIM10 Timer clock enable */ - #define RCC_APB2ENR_TIM11EN ((uint32_t)0x00200000) /*!< TIM11 Timer clock enable */ -#endif - -/***************** Bit definition for RCC_APB1ENR register ******************/ -#define RCC_APB1ENR_TIM2EN ((uint32_t)0x00000001) /*!< Timer 2 clock enabled*/ -#define RCC_APB1ENR_TIM3EN ((uint32_t)0x00000002) /*!< Timer 3 clock enable */ -#define RCC_APB1ENR_WWDGEN ((uint32_t)0x00000800) /*!< Window Watchdog clock enable */ -#define RCC_APB1ENR_USART2EN ((uint32_t)0x00020000) /*!< USART 2 clock enable */ -#define RCC_APB1ENR_I2C1EN ((uint32_t)0x00200000) /*!< I2C 1 clock enable */ - -#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) -#define RCC_APB1ENR_CAN1EN ((uint32_t)0x02000000) /*!< CAN1 clock enable */ -#endif - -#define RCC_APB1ENR_BKPEN ((uint32_t)0x08000000) /*!< Backup interface clock enable */ -#define RCC_APB1ENR_PWREN ((uint32_t)0x10000000) /*!< Power interface clock enable */ - -#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) - #define RCC_APB1ENR_TIM4EN ((uint32_t)0x00000004) /*!< Timer 4 clock enable */ - #define RCC_APB1ENR_SPI2EN ((uint32_t)0x00004000) /*!< SPI 2 clock enable */ - #define RCC_APB1ENR_USART3EN ((uint32_t)0x00040000) /*!< USART 3 clock enable */ - #define RCC_APB1ENR_I2C2EN ((uint32_t)0x00400000) /*!< I2C 2 clock enable */ -#endif /* STM32F10X_LD && STM32F10X_LD_VL */ - -#if defined (STM32F10X_HD) || defined (STM32F10X_MD) || defined (STM32F10X_LD) - #define RCC_APB1ENR_USBEN ((uint32_t)0x00800000) /*!< USB Device clock enable */ -#endif - -#if defined (STM32F10X_HD) || defined (STM32F10X_CL) - #define RCC_APB1ENR_TIM5EN ((uint32_t)0x00000008) /*!< Timer 5 clock enable */ - #define RCC_APB1ENR_TIM6EN ((uint32_t)0x00000010) /*!< Timer 6 clock enable */ - #define RCC_APB1ENR_TIM7EN ((uint32_t)0x00000020) /*!< Timer 7 clock enable */ - #define RCC_APB1ENR_SPI3EN ((uint32_t)0x00008000) /*!< SPI 3 clock enable */ - #define RCC_APB1ENR_UART4EN ((uint32_t)0x00080000) /*!< UART 4 clock enable */ - #define RCC_APB1ENR_UART5EN ((uint32_t)0x00100000) /*!< UART 5 clock enable */ - #define RCC_APB1ENR_DACEN ((uint32_t)0x20000000) /*!< DAC interface clock enable */ -#endif - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) - #define RCC_APB1ENR_TIM6EN ((uint32_t)0x00000010) /*!< Timer 6 clock enable */ - #define RCC_APB1ENR_TIM7EN ((uint32_t)0x00000020) /*!< Timer 7 clock enable */ - #define RCC_APB1ENR_DACEN ((uint32_t)0x20000000) /*!< DAC interface clock enable */ - #define RCC_APB1ENR_CECEN ((uint32_t)0x40000000) /*!< CEC interface clock enable */ -#endif - -#ifdef STM32F10X_HD_VL - #define RCC_APB1ENR_TIM5EN ((uint32_t)0x00000008) /*!< Timer 5 clock enable */ - #define RCC_APB1ENR_TIM12EN ((uint32_t)0x00000040) /*!< TIM12 Timer clock enable */ - #define RCC_APB1ENR_TIM13EN ((uint32_t)0x00000080) /*!< TIM13 Timer clock enable */ - #define RCC_APB1ENR_TIM14EN ((uint32_t)0x00000100) /*!< TIM14 Timer clock enable */ - #define RCC_APB1ENR_SPI3EN ((uint32_t)0x00008000) /*!< SPI 3 clock enable */ - #define RCC_APB1ENR_UART4EN ((uint32_t)0x00080000) /*!< UART 4 clock enable */ - #define RCC_APB1ENR_UART5EN ((uint32_t)0x00100000) /*!< UART 5 clock enable */ -#endif /* STM32F10X_HD_VL */ - -#ifdef STM32F10X_CL - #define RCC_APB1ENR_CAN2EN ((uint32_t)0x04000000) /*!< CAN2 clock enable */ -#endif /* STM32F10X_CL */ - -#ifdef STM32F10X_XL - #define RCC_APB1ENR_TIM12EN ((uint32_t)0x00000040) /*!< TIM12 Timer clock enable */ - #define RCC_APB1ENR_TIM13EN ((uint32_t)0x00000080) /*!< TIM13 Timer clock enable */ - #define RCC_APB1ENR_TIM14EN ((uint32_t)0x00000100) /*!< TIM14 Timer clock enable */ -#endif /* STM32F10X_XL */ - -/******************* Bit definition for RCC_BDCR register *******************/ -#define RCC_BDCR_LSEON ((uint32_t)0x00000001) /*!< External Low Speed oscillator enable */ -#define RCC_BDCR_LSERDY ((uint32_t)0x00000002) /*!< External Low Speed oscillator Ready */ -#define RCC_BDCR_LSEBYP ((uint32_t)0x00000004) /*!< External Low Speed oscillator Bypass */ - -#define RCC_BDCR_RTCSEL ((uint32_t)0x00000300) /*!< RTCSEL[1:0] bits (RTC clock source selection) */ -#define RCC_BDCR_RTCSEL_0 ((uint32_t)0x00000100) /*!< Bit 0 */ -#define RCC_BDCR_RTCSEL_1 ((uint32_t)0x00000200) /*!< Bit 1 */ - -/*!< RTC congiguration */ -#define RCC_BDCR_RTCSEL_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ -#define RCC_BDCR_RTCSEL_LSE ((uint32_t)0x00000100) /*!< LSE oscillator clock used as RTC clock */ -#define RCC_BDCR_RTCSEL_LSI ((uint32_t)0x00000200) /*!< LSI oscillator clock used as RTC clock */ -#define RCC_BDCR_RTCSEL_HSE ((uint32_t)0x00000300) /*!< HSE oscillator clock divided by 128 used as RTC clock */ - -#define RCC_BDCR_RTCEN ((uint32_t)0x00008000) /*!< RTC clock enable */ -#define RCC_BDCR_BDRST ((uint32_t)0x00010000) /*!< Backup domain software reset */ - -/******************* Bit definition for RCC_CSR register ********************/ -#define RCC_CSR_LSION ((uint32_t)0x00000001) /*!< Internal Low Speed oscillator enable */ -#define RCC_CSR_LSIRDY ((uint32_t)0x00000002) /*!< Internal Low Speed oscillator Ready */ -#define RCC_CSR_RMVF ((uint32_t)0x01000000) /*!< Remove reset flag */ -#define RCC_CSR_PINRSTF ((uint32_t)0x04000000) /*!< PIN reset flag */ -#define RCC_CSR_PORRSTF ((uint32_t)0x08000000) /*!< POR/PDR reset flag */ -#define RCC_CSR_SFTRSTF ((uint32_t)0x10000000) /*!< Software Reset flag */ -#define RCC_CSR_IWDGRSTF ((uint32_t)0x20000000) /*!< Independent Watchdog reset flag */ -#define RCC_CSR_WWDGRSTF ((uint32_t)0x40000000) /*!< Window watchdog reset flag */ -#define RCC_CSR_LPWRRSTF ((uint32_t)0x80000000) /*!< Low-Power reset flag */ - -#ifdef STM32F10X_CL -/******************* Bit definition for RCC_AHBRSTR register ****************/ - #define RCC_AHBRSTR_OTGFSRST ((uint32_t)0x00001000) /*!< USB OTG FS reset */ - #define RCC_AHBRSTR_ETHMACRST ((uint32_t)0x00004000) /*!< ETHERNET MAC reset */ - -/******************* Bit definition for RCC_CFGR2 register ******************/ -/*!< PREDIV1 configuration */ - #define RCC_CFGR2_PREDIV1 ((uint32_t)0x0000000F) /*!< PREDIV1[3:0] bits */ - #define RCC_CFGR2_PREDIV1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ - #define RCC_CFGR2_PREDIV1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ - #define RCC_CFGR2_PREDIV1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ - #define RCC_CFGR2_PREDIV1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ - - #define RCC_CFGR2_PREDIV1_DIV1 ((uint32_t)0x00000000) /*!< PREDIV1 input clock not divided */ - #define RCC_CFGR2_PREDIV1_DIV2 ((uint32_t)0x00000001) /*!< PREDIV1 input clock divided by 2 */ - #define RCC_CFGR2_PREDIV1_DIV3 ((uint32_t)0x00000002) /*!< PREDIV1 input clock divided by 3 */ - #define RCC_CFGR2_PREDIV1_DIV4 ((uint32_t)0x00000003) /*!< PREDIV1 input clock divided by 4 */ - #define RCC_CFGR2_PREDIV1_DIV5 ((uint32_t)0x00000004) /*!< PREDIV1 input clock divided by 5 */ - #define RCC_CFGR2_PREDIV1_DIV6 ((uint32_t)0x00000005) /*!< PREDIV1 input clock divided by 6 */ - #define RCC_CFGR2_PREDIV1_DIV7 ((uint32_t)0x00000006) /*!< PREDIV1 input clock divided by 7 */ - #define RCC_CFGR2_PREDIV1_DIV8 ((uint32_t)0x00000007) /*!< PREDIV1 input clock divided by 8 */ - #define RCC_CFGR2_PREDIV1_DIV9 ((uint32_t)0x00000008) /*!< PREDIV1 input clock divided by 9 */ - #define RCC_CFGR2_PREDIV1_DIV10 ((uint32_t)0x00000009) /*!< PREDIV1 input clock divided by 10 */ - #define RCC_CFGR2_PREDIV1_DIV11 ((uint32_t)0x0000000A) /*!< PREDIV1 input clock divided by 11 */ - #define RCC_CFGR2_PREDIV1_DIV12 ((uint32_t)0x0000000B) /*!< PREDIV1 input clock divided by 12 */ - #define RCC_CFGR2_PREDIV1_DIV13 ((uint32_t)0x0000000C) /*!< PREDIV1 input clock divided by 13 */ - #define RCC_CFGR2_PREDIV1_DIV14 ((uint32_t)0x0000000D) /*!< PREDIV1 input clock divided by 14 */ - #define RCC_CFGR2_PREDIV1_DIV15 ((uint32_t)0x0000000E) /*!< PREDIV1 input clock divided by 15 */ - #define RCC_CFGR2_PREDIV1_DIV16 ((uint32_t)0x0000000F) /*!< PREDIV1 input clock divided by 16 */ - -/*!< PREDIV2 configuration */ - #define RCC_CFGR2_PREDIV2 ((uint32_t)0x000000F0) /*!< PREDIV2[3:0] bits */ - #define RCC_CFGR2_PREDIV2_0 ((uint32_t)0x00000010) /*!< Bit 0 */ - #define RCC_CFGR2_PREDIV2_1 ((uint32_t)0x00000020) /*!< Bit 1 */ - #define RCC_CFGR2_PREDIV2_2 ((uint32_t)0x00000040) /*!< Bit 2 */ - #define RCC_CFGR2_PREDIV2_3 ((uint32_t)0x00000080) /*!< Bit 3 */ - - #define RCC_CFGR2_PREDIV2_DIV1 ((uint32_t)0x00000000) /*!< PREDIV2 input clock not divided */ - #define RCC_CFGR2_PREDIV2_DIV2 ((uint32_t)0x00000010) /*!< PREDIV2 input clock divided by 2 */ - #define RCC_CFGR2_PREDIV2_DIV3 ((uint32_t)0x00000020) /*!< PREDIV2 input clock divided by 3 */ - #define RCC_CFGR2_PREDIV2_DIV4 ((uint32_t)0x00000030) /*!< PREDIV2 input clock divided by 4 */ - #define RCC_CFGR2_PREDIV2_DIV5 ((uint32_t)0x00000040) /*!< PREDIV2 input clock divided by 5 */ - #define RCC_CFGR2_PREDIV2_DIV6 ((uint32_t)0x00000050) /*!< PREDIV2 input clock divided by 6 */ - #define RCC_CFGR2_PREDIV2_DIV7 ((uint32_t)0x00000060) /*!< PREDIV2 input clock divided by 7 */ - #define RCC_CFGR2_PREDIV2_DIV8 ((uint32_t)0x00000070) /*!< PREDIV2 input clock divided by 8 */ - #define RCC_CFGR2_PREDIV2_DIV9 ((uint32_t)0x00000080) /*!< PREDIV2 input clock divided by 9 */ - #define RCC_CFGR2_PREDIV2_DIV10 ((uint32_t)0x00000090) /*!< PREDIV2 input clock divided by 10 */ - #define RCC_CFGR2_PREDIV2_DIV11 ((uint32_t)0x000000A0) /*!< PREDIV2 input clock divided by 11 */ - #define RCC_CFGR2_PREDIV2_DIV12 ((uint32_t)0x000000B0) /*!< PREDIV2 input clock divided by 12 */ - #define RCC_CFGR2_PREDIV2_DIV13 ((uint32_t)0x000000C0) /*!< PREDIV2 input clock divided by 13 */ - #define RCC_CFGR2_PREDIV2_DIV14 ((uint32_t)0x000000D0) /*!< PREDIV2 input clock divided by 14 */ - #define RCC_CFGR2_PREDIV2_DIV15 ((uint32_t)0x000000E0) /*!< PREDIV2 input clock divided by 15 */ - #define RCC_CFGR2_PREDIV2_DIV16 ((uint32_t)0x000000F0) /*!< PREDIV2 input clock divided by 16 */ - -/*!< PLL2MUL configuration */ - #define RCC_CFGR2_PLL2MUL ((uint32_t)0x00000F00) /*!< PLL2MUL[3:0] bits */ - #define RCC_CFGR2_PLL2MUL_0 ((uint32_t)0x00000100) /*!< Bit 0 */ - #define RCC_CFGR2_PLL2MUL_1 ((uint32_t)0x00000200) /*!< Bit 1 */ - #define RCC_CFGR2_PLL2MUL_2 ((uint32_t)0x00000400) /*!< Bit 2 */ - #define RCC_CFGR2_PLL2MUL_3 ((uint32_t)0x00000800) /*!< Bit 3 */ - - #define RCC_CFGR2_PLL2MUL8 ((uint32_t)0x00000600) /*!< PLL2 input clock * 8 */ - #define RCC_CFGR2_PLL2MUL9 ((uint32_t)0x00000700) /*!< PLL2 input clock * 9 */ - #define RCC_CFGR2_PLL2MUL10 ((uint32_t)0x00000800) /*!< PLL2 input clock * 10 */ - #define RCC_CFGR2_PLL2MUL11 ((uint32_t)0x00000900) /*!< PLL2 input clock * 11 */ - #define RCC_CFGR2_PLL2MUL12 ((uint32_t)0x00000A00) /*!< PLL2 input clock * 12 */ - #define RCC_CFGR2_PLL2MUL13 ((uint32_t)0x00000B00) /*!< PLL2 input clock * 13 */ - #define RCC_CFGR2_PLL2MUL14 ((uint32_t)0x00000C00) /*!< PLL2 input clock * 14 */ - #define RCC_CFGR2_PLL2MUL16 ((uint32_t)0x00000E00) /*!< PLL2 input clock * 16 */ - #define RCC_CFGR2_PLL2MUL20 ((uint32_t)0x00000F00) /*!< PLL2 input clock * 20 */ - -/*!< PLL3MUL configuration */ - #define RCC_CFGR2_PLL3MUL ((uint32_t)0x0000F000) /*!< PLL3MUL[3:0] bits */ - #define RCC_CFGR2_PLL3MUL_0 ((uint32_t)0x00001000) /*!< Bit 0 */ - #define RCC_CFGR2_PLL3MUL_1 ((uint32_t)0x00002000) /*!< Bit 1 */ - #define RCC_CFGR2_PLL3MUL_2 ((uint32_t)0x00004000) /*!< Bit 2 */ - #define RCC_CFGR2_PLL3MUL_3 ((uint32_t)0x00008000) /*!< Bit 3 */ - - #define RCC_CFGR2_PLL3MUL8 ((uint32_t)0x00006000) /*!< PLL3 input clock * 8 */ - #define RCC_CFGR2_PLL3MUL9 ((uint32_t)0x00007000) /*!< PLL3 input clock * 9 */ - #define RCC_CFGR2_PLL3MUL10 ((uint32_t)0x00008000) /*!< PLL3 input clock * 10 */ - #define RCC_CFGR2_PLL3MUL11 ((uint32_t)0x00009000) /*!< PLL3 input clock * 11 */ - #define RCC_CFGR2_PLL3MUL12 ((uint32_t)0x0000A000) /*!< PLL3 input clock * 12 */ - #define RCC_CFGR2_PLL3MUL13 ((uint32_t)0x0000B000) /*!< PLL3 input clock * 13 */ - #define RCC_CFGR2_PLL3MUL14 ((uint32_t)0x0000C000) /*!< PLL3 input clock * 14 */ - #define RCC_CFGR2_PLL3MUL16 ((uint32_t)0x0000E000) /*!< PLL3 input clock * 16 */ - #define RCC_CFGR2_PLL3MUL20 ((uint32_t)0x0000F000) /*!< PLL3 input clock * 20 */ - - #define RCC_CFGR2_PREDIV1SRC ((uint32_t)0x00010000) /*!< PREDIV1 entry clock source */ - #define RCC_CFGR2_PREDIV1SRC_PLL2 ((uint32_t)0x00010000) /*!< PLL2 selected as PREDIV1 entry clock source */ - #define RCC_CFGR2_PREDIV1SRC_HSE ((uint32_t)0x00000000) /*!< HSE selected as PREDIV1 entry clock source */ - #define RCC_CFGR2_I2S2SRC ((uint32_t)0x00020000) /*!< I2S2 entry clock source */ - #define RCC_CFGR2_I2S3SRC ((uint32_t)0x00040000) /*!< I2S3 clock source */ -#endif /* STM32F10X_CL */ - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) -/******************* Bit definition for RCC_CFGR2 register ******************/ -/*!< PREDIV1 configuration */ - #define RCC_CFGR2_PREDIV1 ((uint32_t)0x0000000F) /*!< PREDIV1[3:0] bits */ - #define RCC_CFGR2_PREDIV1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ - #define RCC_CFGR2_PREDIV1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ - #define RCC_CFGR2_PREDIV1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ - #define RCC_CFGR2_PREDIV1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ - - #define RCC_CFGR2_PREDIV1_DIV1 ((uint32_t)0x00000000) /*!< PREDIV1 input clock not divided */ - #define RCC_CFGR2_PREDIV1_DIV2 ((uint32_t)0x00000001) /*!< PREDIV1 input clock divided by 2 */ - #define RCC_CFGR2_PREDIV1_DIV3 ((uint32_t)0x00000002) /*!< PREDIV1 input clock divided by 3 */ - #define RCC_CFGR2_PREDIV1_DIV4 ((uint32_t)0x00000003) /*!< PREDIV1 input clock divided by 4 */ - #define RCC_CFGR2_PREDIV1_DIV5 ((uint32_t)0x00000004) /*!< PREDIV1 input clock divided by 5 */ - #define RCC_CFGR2_PREDIV1_DIV6 ((uint32_t)0x00000005) /*!< PREDIV1 input clock divided by 6 */ - #define RCC_CFGR2_PREDIV1_DIV7 ((uint32_t)0x00000006) /*!< PREDIV1 input clock divided by 7 */ - #define RCC_CFGR2_PREDIV1_DIV8 ((uint32_t)0x00000007) /*!< PREDIV1 input clock divided by 8 */ - #define RCC_CFGR2_PREDIV1_DIV9 ((uint32_t)0x00000008) /*!< PREDIV1 input clock divided by 9 */ - #define RCC_CFGR2_PREDIV1_DIV10 ((uint32_t)0x00000009) /*!< PREDIV1 input clock divided by 10 */ - #define RCC_CFGR2_PREDIV1_DIV11 ((uint32_t)0x0000000A) /*!< PREDIV1 input clock divided by 11 */ - #define RCC_CFGR2_PREDIV1_DIV12 ((uint32_t)0x0000000B) /*!< PREDIV1 input clock divided by 12 */ - #define RCC_CFGR2_PREDIV1_DIV13 ((uint32_t)0x0000000C) /*!< PREDIV1 input clock divided by 13 */ - #define RCC_CFGR2_PREDIV1_DIV14 ((uint32_t)0x0000000D) /*!< PREDIV1 input clock divided by 14 */ - #define RCC_CFGR2_PREDIV1_DIV15 ((uint32_t)0x0000000E) /*!< PREDIV1 input clock divided by 15 */ - #define RCC_CFGR2_PREDIV1_DIV16 ((uint32_t)0x0000000F) /*!< PREDIV1 input clock divided by 16 */ -#endif - -/******************************************************************************/ -/* */ -/* General Purpose and Alternate Function I/O */ -/* */ -/******************************************************************************/ - -/******************* Bit definition for GPIO_CRL register *******************/ -#define GPIO_CRL_MODE ((uint32_t)0x33333333) /*!< Port x mode bits */ - -#define GPIO_CRL_MODE0 ((uint32_t)0x00000003) /*!< MODE0[1:0] bits (Port x mode bits, pin 0) */ -#define GPIO_CRL_MODE0_0 ((uint32_t)0x00000001) /*!< Bit 0 */ -#define GPIO_CRL_MODE0_1 ((uint32_t)0x00000002) /*!< Bit 1 */ - -#define GPIO_CRL_MODE1 ((uint32_t)0x00000030) /*!< MODE1[1:0] bits (Port x mode bits, pin 1) */ -#define GPIO_CRL_MODE1_0 ((uint32_t)0x00000010) /*!< Bit 0 */ -#define GPIO_CRL_MODE1_1 ((uint32_t)0x00000020) /*!< Bit 1 */ - -#define GPIO_CRL_MODE2 ((uint32_t)0x00000300) /*!< MODE2[1:0] bits (Port x mode bits, pin 2) */ -#define GPIO_CRL_MODE2_0 ((uint32_t)0x00000100) /*!< Bit 0 */ -#define GPIO_CRL_MODE2_1 ((uint32_t)0x00000200) /*!< Bit 1 */ - -#define GPIO_CRL_MODE3 ((uint32_t)0x00003000) /*!< MODE3[1:0] bits (Port x mode bits, pin 3) */ -#define GPIO_CRL_MODE3_0 ((uint32_t)0x00001000) /*!< Bit 0 */ -#define GPIO_CRL_MODE3_1 ((uint32_t)0x00002000) /*!< Bit 1 */ - -#define GPIO_CRL_MODE4 ((uint32_t)0x00030000) /*!< MODE4[1:0] bits (Port x mode bits, pin 4) */ -#define GPIO_CRL_MODE4_0 ((uint32_t)0x00010000) /*!< Bit 0 */ -#define GPIO_CRL_MODE4_1 ((uint32_t)0x00020000) /*!< Bit 1 */ - -#define GPIO_CRL_MODE5 ((uint32_t)0x00300000) /*!< MODE5[1:0] bits (Port x mode bits, pin 5) */ -#define GPIO_CRL_MODE5_0 ((uint32_t)0x00100000) /*!< Bit 0 */ -#define GPIO_CRL_MODE5_1 ((uint32_t)0x00200000) /*!< Bit 1 */ - -#define GPIO_CRL_MODE6 ((uint32_t)0x03000000) /*!< MODE6[1:0] bits (Port x mode bits, pin 6) */ -#define GPIO_CRL_MODE6_0 ((uint32_t)0x01000000) /*!< Bit 0 */ -#define GPIO_CRL_MODE6_1 ((uint32_t)0x02000000) /*!< Bit 1 */ - -#define GPIO_CRL_MODE7 ((uint32_t)0x30000000) /*!< MODE7[1:0] bits (Port x mode bits, pin 7) */ -#define GPIO_CRL_MODE7_0 ((uint32_t)0x10000000) /*!< Bit 0 */ -#define GPIO_CRL_MODE7_1 ((uint32_t)0x20000000) /*!< Bit 1 */ - -#define GPIO_CRL_CNF ((uint32_t)0xCCCCCCCC) /*!< Port x configuration bits */ - -#define GPIO_CRL_CNF0 ((uint32_t)0x0000000C) /*!< CNF0[1:0] bits (Port x configuration bits, pin 0) */ -#define GPIO_CRL_CNF0_0 ((uint32_t)0x00000004) /*!< Bit 0 */ -#define GPIO_CRL_CNF0_1 ((uint32_t)0x00000008) /*!< Bit 1 */ - -#define GPIO_CRL_CNF1 ((uint32_t)0x000000C0) /*!< CNF1[1:0] bits (Port x configuration bits, pin 1) */ -#define GPIO_CRL_CNF1_0 ((uint32_t)0x00000040) /*!< Bit 0 */ -#define GPIO_CRL_CNF1_1 ((uint32_t)0x00000080) /*!< Bit 1 */ - -#define GPIO_CRL_CNF2 ((uint32_t)0x00000C00) /*!< CNF2[1:0] bits (Port x configuration bits, pin 2) */ -#define GPIO_CRL_CNF2_0 ((uint32_t)0x00000400) /*!< Bit 0 */ -#define GPIO_CRL_CNF2_1 ((uint32_t)0x00000800) /*!< Bit 1 */ - -#define GPIO_CRL_CNF3 ((uint32_t)0x0000C000) /*!< CNF3[1:0] bits (Port x configuration bits, pin 3) */ -#define GPIO_CRL_CNF3_0 ((uint32_t)0x00004000) /*!< Bit 0 */ -#define GPIO_CRL_CNF3_1 ((uint32_t)0x00008000) /*!< Bit 1 */ - -#define GPIO_CRL_CNF4 ((uint32_t)0x000C0000) /*!< CNF4[1:0] bits (Port x configuration bits, pin 4) */ -#define GPIO_CRL_CNF4_0 ((uint32_t)0x00040000) /*!< Bit 0 */ -#define GPIO_CRL_CNF4_1 ((uint32_t)0x00080000) /*!< Bit 1 */ - -#define GPIO_CRL_CNF5 ((uint32_t)0x00C00000) /*!< CNF5[1:0] bits (Port x configuration bits, pin 5) */ -#define GPIO_CRL_CNF5_0 ((uint32_t)0x00400000) /*!< Bit 0 */ -#define GPIO_CRL_CNF5_1 ((uint32_t)0x00800000) /*!< Bit 1 */ - -#define GPIO_CRL_CNF6 ((uint32_t)0x0C000000) /*!< CNF6[1:0] bits (Port x configuration bits, pin 6) */ -#define GPIO_CRL_CNF6_0 ((uint32_t)0x04000000) /*!< Bit 0 */ -#define GPIO_CRL_CNF6_1 ((uint32_t)0x08000000) /*!< Bit 1 */ - -#define GPIO_CRL_CNF7 ((uint32_t)0xC0000000) /*!< CNF7[1:0] bits (Port x configuration bits, pin 7) */ -#define GPIO_CRL_CNF7_0 ((uint32_t)0x40000000) /*!< Bit 0 */ -#define GPIO_CRL_CNF7_1 ((uint32_t)0x80000000) /*!< Bit 1 */ - -/******************* Bit definition for GPIO_CRH register *******************/ -#define GPIO_CRH_MODE ((uint32_t)0x33333333) /*!< Port x mode bits */ - -#define GPIO_CRH_MODE8 ((uint32_t)0x00000003) /*!< MODE8[1:0] bits (Port x mode bits, pin 8) */ -#define GPIO_CRH_MODE8_0 ((uint32_t)0x00000001) /*!< Bit 0 */ -#define GPIO_CRH_MODE8_1 ((uint32_t)0x00000002) /*!< Bit 1 */ - -#define GPIO_CRH_MODE9 ((uint32_t)0x00000030) /*!< MODE9[1:0] bits (Port x mode bits, pin 9) */ -#define GPIO_CRH_MODE9_0 ((uint32_t)0x00000010) /*!< Bit 0 */ -#define GPIO_CRH_MODE9_1 ((uint32_t)0x00000020) /*!< Bit 1 */ - -#define GPIO_CRH_MODE10 ((uint32_t)0x00000300) /*!< MODE10[1:0] bits (Port x mode bits, pin 10) */ -#define GPIO_CRH_MODE10_0 ((uint32_t)0x00000100) /*!< Bit 0 */ -#define GPIO_CRH_MODE10_1 ((uint32_t)0x00000200) /*!< Bit 1 */ - -#define GPIO_CRH_MODE11 ((uint32_t)0x00003000) /*!< MODE11[1:0] bits (Port x mode bits, pin 11) */ -#define GPIO_CRH_MODE11_0 ((uint32_t)0x00001000) /*!< Bit 0 */ -#define GPIO_CRH_MODE11_1 ((uint32_t)0x00002000) /*!< Bit 1 */ - -#define GPIO_CRH_MODE12 ((uint32_t)0x00030000) /*!< MODE12[1:0] bits (Port x mode bits, pin 12) */ -#define GPIO_CRH_MODE12_0 ((uint32_t)0x00010000) /*!< Bit 0 */ -#define GPIO_CRH_MODE12_1 ((uint32_t)0x00020000) /*!< Bit 1 */ - -#define GPIO_CRH_MODE13 ((uint32_t)0x00300000) /*!< MODE13[1:0] bits (Port x mode bits, pin 13) */ -#define GPIO_CRH_MODE13_0 ((uint32_t)0x00100000) /*!< Bit 0 */ -#define GPIO_CRH_MODE13_1 ((uint32_t)0x00200000) /*!< Bit 1 */ - -#define GPIO_CRH_MODE14 ((uint32_t)0x03000000) /*!< MODE14[1:0] bits (Port x mode bits, pin 14) */ -#define GPIO_CRH_MODE14_0 ((uint32_t)0x01000000) /*!< Bit 0 */ -#define GPIO_CRH_MODE14_1 ((uint32_t)0x02000000) /*!< Bit 1 */ - -#define GPIO_CRH_MODE15 ((uint32_t)0x30000000) /*!< MODE15[1:0] bits (Port x mode bits, pin 15) */ -#define GPIO_CRH_MODE15_0 ((uint32_t)0x10000000) /*!< Bit 0 */ -#define GPIO_CRH_MODE15_1 ((uint32_t)0x20000000) /*!< Bit 1 */ - -#define GPIO_CRH_CNF ((uint32_t)0xCCCCCCCC) /*!< Port x configuration bits */ - -#define GPIO_CRH_CNF8 ((uint32_t)0x0000000C) /*!< CNF8[1:0] bits (Port x configuration bits, pin 8) */ -#define GPIO_CRH_CNF8_0 ((uint32_t)0x00000004) /*!< Bit 0 */ -#define GPIO_CRH_CNF8_1 ((uint32_t)0x00000008) /*!< Bit 1 */ - -#define GPIO_CRH_CNF9 ((uint32_t)0x000000C0) /*!< CNF9[1:0] bits (Port x configuration bits, pin 9) */ -#define GPIO_CRH_CNF9_0 ((uint32_t)0x00000040) /*!< Bit 0 */ -#define GPIO_CRH_CNF9_1 ((uint32_t)0x00000080) /*!< Bit 1 */ - -#define GPIO_CRH_CNF10 ((uint32_t)0x00000C00) /*!< CNF10[1:0] bits (Port x configuration bits, pin 10) */ -#define GPIO_CRH_CNF10_0 ((uint32_t)0x00000400) /*!< Bit 0 */ -#define GPIO_CRH_CNF10_1 ((uint32_t)0x00000800) /*!< Bit 1 */ - -#define GPIO_CRH_CNF11 ((uint32_t)0x0000C000) /*!< CNF11[1:0] bits (Port x configuration bits, pin 11) */ -#define GPIO_CRH_CNF11_0 ((uint32_t)0x00004000) /*!< Bit 0 */ -#define GPIO_CRH_CNF11_1 ((uint32_t)0x00008000) /*!< Bit 1 */ - -#define GPIO_CRH_CNF12 ((uint32_t)0x000C0000) /*!< CNF12[1:0] bits (Port x configuration bits, pin 12) */ -#define GPIO_CRH_CNF12_0 ((uint32_t)0x00040000) /*!< Bit 0 */ -#define GPIO_CRH_CNF12_1 ((uint32_t)0x00080000) /*!< Bit 1 */ - -#define GPIO_CRH_CNF13 ((uint32_t)0x00C00000) /*!< CNF13[1:0] bits (Port x configuration bits, pin 13) */ -#define GPIO_CRH_CNF13_0 ((uint32_t)0x00400000) /*!< Bit 0 */ -#define GPIO_CRH_CNF13_1 ((uint32_t)0x00800000) /*!< Bit 1 */ - -#define GPIO_CRH_CNF14 ((uint32_t)0x0C000000) /*!< CNF14[1:0] bits (Port x configuration bits, pin 14) */ -#define GPIO_CRH_CNF14_0 ((uint32_t)0x04000000) /*!< Bit 0 */ -#define GPIO_CRH_CNF14_1 ((uint32_t)0x08000000) /*!< Bit 1 */ - -#define GPIO_CRH_CNF15 ((uint32_t)0xC0000000) /*!< CNF15[1:0] bits (Port x configuration bits, pin 15) */ -#define GPIO_CRH_CNF15_0 ((uint32_t)0x40000000) /*!< Bit 0 */ -#define GPIO_CRH_CNF15_1 ((uint32_t)0x80000000) /*!< Bit 1 */ - -/*!<****************** Bit definition for GPIO_IDR register *******************/ -#define GPIO_IDR_IDR0 ((uint16_t)0x0001) /*!< Port input data, bit 0 */ -#define GPIO_IDR_IDR1 ((uint16_t)0x0002) /*!< Port input data, bit 1 */ -#define GPIO_IDR_IDR2 ((uint16_t)0x0004) /*!< Port input data, bit 2 */ -#define GPIO_IDR_IDR3 ((uint16_t)0x0008) /*!< Port input data, bit 3 */ -#define GPIO_IDR_IDR4 ((uint16_t)0x0010) /*!< Port input data, bit 4 */ -#define GPIO_IDR_IDR5 ((uint16_t)0x0020) /*!< Port input data, bit 5 */ -#define GPIO_IDR_IDR6 ((uint16_t)0x0040) /*!< Port input data, bit 6 */ -#define GPIO_IDR_IDR7 ((uint16_t)0x0080) /*!< Port input data, bit 7 */ -#define GPIO_IDR_IDR8 ((uint16_t)0x0100) /*!< Port input data, bit 8 */ -#define GPIO_IDR_IDR9 ((uint16_t)0x0200) /*!< Port input data, bit 9 */ -#define GPIO_IDR_IDR10 ((uint16_t)0x0400) /*!< Port input data, bit 10 */ -#define GPIO_IDR_IDR11 ((uint16_t)0x0800) /*!< Port input data, bit 11 */ -#define GPIO_IDR_IDR12 ((uint16_t)0x1000) /*!< Port input data, bit 12 */ -#define GPIO_IDR_IDR13 ((uint16_t)0x2000) /*!< Port input data, bit 13 */ -#define GPIO_IDR_IDR14 ((uint16_t)0x4000) /*!< Port input data, bit 14 */ -#define GPIO_IDR_IDR15 ((uint16_t)0x8000) /*!< Port input data, bit 15 */ - -/******************* Bit definition for GPIO_ODR register *******************/ -#define GPIO_ODR_ODR0 ((uint16_t)0x0001) /*!< Port output data, bit 0 */ -#define GPIO_ODR_ODR1 ((uint16_t)0x0002) /*!< Port output data, bit 1 */ -#define GPIO_ODR_ODR2 ((uint16_t)0x0004) /*!< Port output data, bit 2 */ -#define GPIO_ODR_ODR3 ((uint16_t)0x0008) /*!< Port output data, bit 3 */ -#define GPIO_ODR_ODR4 ((uint16_t)0x0010) /*!< Port output data, bit 4 */ -#define GPIO_ODR_ODR5 ((uint16_t)0x0020) /*!< Port output data, bit 5 */ -#define GPIO_ODR_ODR6 ((uint16_t)0x0040) /*!< Port output data, bit 6 */ -#define GPIO_ODR_ODR7 ((uint16_t)0x0080) /*!< Port output data, bit 7 */ -#define GPIO_ODR_ODR8 ((uint16_t)0x0100) /*!< Port output data, bit 8 */ -#define GPIO_ODR_ODR9 ((uint16_t)0x0200) /*!< Port output data, bit 9 */ -#define GPIO_ODR_ODR10 ((uint16_t)0x0400) /*!< Port output data, bit 10 */ -#define GPIO_ODR_ODR11 ((uint16_t)0x0800) /*!< Port output data, bit 11 */ -#define GPIO_ODR_ODR12 ((uint16_t)0x1000) /*!< Port output data, bit 12 */ -#define GPIO_ODR_ODR13 ((uint16_t)0x2000) /*!< Port output data, bit 13 */ -#define GPIO_ODR_ODR14 ((uint16_t)0x4000) /*!< Port output data, bit 14 */ -#define GPIO_ODR_ODR15 ((uint16_t)0x8000) /*!< Port output data, bit 15 */ - -/****************** Bit definition for GPIO_BSRR register *******************/ -#define GPIO_BSRR_BS0 ((uint32_t)0x00000001) /*!< Port x Set bit 0 */ -#define GPIO_BSRR_BS1 ((uint32_t)0x00000002) /*!< Port x Set bit 1 */ -#define GPIO_BSRR_BS2 ((uint32_t)0x00000004) /*!< Port x Set bit 2 */ -#define GPIO_BSRR_BS3 ((uint32_t)0x00000008) /*!< Port x Set bit 3 */ -#define GPIO_BSRR_BS4 ((uint32_t)0x00000010) /*!< Port x Set bit 4 */ -#define GPIO_BSRR_BS5 ((uint32_t)0x00000020) /*!< Port x Set bit 5 */ -#define GPIO_BSRR_BS6 ((uint32_t)0x00000040) /*!< Port x Set bit 6 */ -#define GPIO_BSRR_BS7 ((uint32_t)0x00000080) /*!< Port x Set bit 7 */ -#define GPIO_BSRR_BS8 ((uint32_t)0x00000100) /*!< Port x Set bit 8 */ -#define GPIO_BSRR_BS9 ((uint32_t)0x00000200) /*!< Port x Set bit 9 */ -#define GPIO_BSRR_BS10 ((uint32_t)0x00000400) /*!< Port x Set bit 10 */ -#define GPIO_BSRR_BS11 ((uint32_t)0x00000800) /*!< Port x Set bit 11 */ -#define GPIO_BSRR_BS12 ((uint32_t)0x00001000) /*!< Port x Set bit 12 */ -#define GPIO_BSRR_BS13 ((uint32_t)0x00002000) /*!< Port x Set bit 13 */ -#define GPIO_BSRR_BS14 ((uint32_t)0x00004000) /*!< Port x Set bit 14 */ -#define GPIO_BSRR_BS15 ((uint32_t)0x00008000) /*!< Port x Set bit 15 */ - -#define GPIO_BSRR_BR0 ((uint32_t)0x00010000) /*!< Port x Reset bit 0 */ -#define GPIO_BSRR_BR1 ((uint32_t)0x00020000) /*!< Port x Reset bit 1 */ -#define GPIO_BSRR_BR2 ((uint32_t)0x00040000) /*!< Port x Reset bit 2 */ -#define GPIO_BSRR_BR3 ((uint32_t)0x00080000) /*!< Port x Reset bit 3 */ -#define GPIO_BSRR_BR4 ((uint32_t)0x00100000) /*!< Port x Reset bit 4 */ -#define GPIO_BSRR_BR5 ((uint32_t)0x00200000) /*!< Port x Reset bit 5 */ -#define GPIO_BSRR_BR6 ((uint32_t)0x00400000) /*!< Port x Reset bit 6 */ -#define GPIO_BSRR_BR7 ((uint32_t)0x00800000) /*!< Port x Reset bit 7 */ -#define GPIO_BSRR_BR8 ((uint32_t)0x01000000) /*!< Port x Reset bit 8 */ -#define GPIO_BSRR_BR9 ((uint32_t)0x02000000) /*!< Port x Reset bit 9 */ -#define GPIO_BSRR_BR10 ((uint32_t)0x04000000) /*!< Port x Reset bit 10 */ -#define GPIO_BSRR_BR11 ((uint32_t)0x08000000) /*!< Port x Reset bit 11 */ -#define GPIO_BSRR_BR12 ((uint32_t)0x10000000) /*!< Port x Reset bit 12 */ -#define GPIO_BSRR_BR13 ((uint32_t)0x20000000) /*!< Port x Reset bit 13 */ -#define GPIO_BSRR_BR14 ((uint32_t)0x40000000) /*!< Port x Reset bit 14 */ -#define GPIO_BSRR_BR15 ((uint32_t)0x80000000) /*!< Port x Reset bit 15 */ - -/******************* Bit definition for GPIO_BRR register *******************/ -#define GPIO_BRR_BR0 ((uint16_t)0x0001) /*!< Port x Reset bit 0 */ -#define GPIO_BRR_BR1 ((uint16_t)0x0002) /*!< Port x Reset bit 1 */ -#define GPIO_BRR_BR2 ((uint16_t)0x0004) /*!< Port x Reset bit 2 */ -#define GPIO_BRR_BR3 ((uint16_t)0x0008) /*!< Port x Reset bit 3 */ -#define GPIO_BRR_BR4 ((uint16_t)0x0010) /*!< Port x Reset bit 4 */ -#define GPIO_BRR_BR5 ((uint16_t)0x0020) /*!< Port x Reset bit 5 */ -#define GPIO_BRR_BR6 ((uint16_t)0x0040) /*!< Port x Reset bit 6 */ -#define GPIO_BRR_BR7 ((uint16_t)0x0080) /*!< Port x Reset bit 7 */ -#define GPIO_BRR_BR8 ((uint16_t)0x0100) /*!< Port x Reset bit 8 */ -#define GPIO_BRR_BR9 ((uint16_t)0x0200) /*!< Port x Reset bit 9 */ -#define GPIO_BRR_BR10 ((uint16_t)0x0400) /*!< Port x Reset bit 10 */ -#define GPIO_BRR_BR11 ((uint16_t)0x0800) /*!< Port x Reset bit 11 */ -#define GPIO_BRR_BR12 ((uint16_t)0x1000) /*!< Port x Reset bit 12 */ -#define GPIO_BRR_BR13 ((uint16_t)0x2000) /*!< Port x Reset bit 13 */ -#define GPIO_BRR_BR14 ((uint16_t)0x4000) /*!< Port x Reset bit 14 */ -#define GPIO_BRR_BR15 ((uint16_t)0x8000) /*!< Port x Reset bit 15 */ - -/****************** Bit definition for GPIO_LCKR register *******************/ -#define GPIO_LCKR_LCK0 ((uint32_t)0x00000001) /*!< Port x Lock bit 0 */ -#define GPIO_LCKR_LCK1 ((uint32_t)0x00000002) /*!< Port x Lock bit 1 */ -#define GPIO_LCKR_LCK2 ((uint32_t)0x00000004) /*!< Port x Lock bit 2 */ -#define GPIO_LCKR_LCK3 ((uint32_t)0x00000008) /*!< Port x Lock bit 3 */ -#define GPIO_LCKR_LCK4 ((uint32_t)0x00000010) /*!< Port x Lock bit 4 */ -#define GPIO_LCKR_LCK5 ((uint32_t)0x00000020) /*!< Port x Lock bit 5 */ -#define GPIO_LCKR_LCK6 ((uint32_t)0x00000040) /*!< Port x Lock bit 6 */ -#define GPIO_LCKR_LCK7 ((uint32_t)0x00000080) /*!< Port x Lock bit 7 */ -#define GPIO_LCKR_LCK8 ((uint32_t)0x00000100) /*!< Port x Lock bit 8 */ -#define GPIO_LCKR_LCK9 ((uint32_t)0x00000200) /*!< Port x Lock bit 9 */ -#define GPIO_LCKR_LCK10 ((uint32_t)0x00000400) /*!< Port x Lock bit 10 */ -#define GPIO_LCKR_LCK11 ((uint32_t)0x00000800) /*!< Port x Lock bit 11 */ -#define GPIO_LCKR_LCK12 ((uint32_t)0x00001000) /*!< Port x Lock bit 12 */ -#define GPIO_LCKR_LCK13 ((uint32_t)0x00002000) /*!< Port x Lock bit 13 */ -#define GPIO_LCKR_LCK14 ((uint32_t)0x00004000) /*!< Port x Lock bit 14 */ -#define GPIO_LCKR_LCK15 ((uint32_t)0x00008000) /*!< Port x Lock bit 15 */ -#define GPIO_LCKR_LCKK ((uint32_t)0x00010000) /*!< Lock key */ - -/*----------------------------------------------------------------------------*/ - -/****************** Bit definition for AFIO_EVCR register *******************/ -#define AFIO_EVCR_PIN ((uint8_t)0x0F) /*!< PIN[3:0] bits (Pin selection) */ -#define AFIO_EVCR_PIN_0 ((uint8_t)0x01) /*!< Bit 0 */ -#define AFIO_EVCR_PIN_1 ((uint8_t)0x02) /*!< Bit 1 */ -#define AFIO_EVCR_PIN_2 ((uint8_t)0x04) /*!< Bit 2 */ -#define AFIO_EVCR_PIN_3 ((uint8_t)0x08) /*!< Bit 3 */ - -/*!< PIN configuration */ -#define AFIO_EVCR_PIN_PX0 ((uint8_t)0x00) /*!< Pin 0 selected */ -#define AFIO_EVCR_PIN_PX1 ((uint8_t)0x01) /*!< Pin 1 selected */ -#define AFIO_EVCR_PIN_PX2 ((uint8_t)0x02) /*!< Pin 2 selected */ -#define AFIO_EVCR_PIN_PX3 ((uint8_t)0x03) /*!< Pin 3 selected */ -#define AFIO_EVCR_PIN_PX4 ((uint8_t)0x04) /*!< Pin 4 selected */ -#define AFIO_EVCR_PIN_PX5 ((uint8_t)0x05) /*!< Pin 5 selected */ -#define AFIO_EVCR_PIN_PX6 ((uint8_t)0x06) /*!< Pin 6 selected */ -#define AFIO_EVCR_PIN_PX7 ((uint8_t)0x07) /*!< Pin 7 selected */ -#define AFIO_EVCR_PIN_PX8 ((uint8_t)0x08) /*!< Pin 8 selected */ -#define AFIO_EVCR_PIN_PX9 ((uint8_t)0x09) /*!< Pin 9 selected */ -#define AFIO_EVCR_PIN_PX10 ((uint8_t)0x0A) /*!< Pin 10 selected */ -#define AFIO_EVCR_PIN_PX11 ((uint8_t)0x0B) /*!< Pin 11 selected */ -#define AFIO_EVCR_PIN_PX12 ((uint8_t)0x0C) /*!< Pin 12 selected */ -#define AFIO_EVCR_PIN_PX13 ((uint8_t)0x0D) /*!< Pin 13 selected */ -#define AFIO_EVCR_PIN_PX14 ((uint8_t)0x0E) /*!< Pin 14 selected */ -#define AFIO_EVCR_PIN_PX15 ((uint8_t)0x0F) /*!< Pin 15 selected */ - -#define AFIO_EVCR_PORT ((uint8_t)0x70) /*!< PORT[2:0] bits (Port selection) */ -#define AFIO_EVCR_PORT_0 ((uint8_t)0x10) /*!< Bit 0 */ -#define AFIO_EVCR_PORT_1 ((uint8_t)0x20) /*!< Bit 1 */ -#define AFIO_EVCR_PORT_2 ((uint8_t)0x40) /*!< Bit 2 */ - -/*!< PORT configuration */ -#define AFIO_EVCR_PORT_PA ((uint8_t)0x00) /*!< Port A selected */ -#define AFIO_EVCR_PORT_PB ((uint8_t)0x10) /*!< Port B selected */ -#define AFIO_EVCR_PORT_PC ((uint8_t)0x20) /*!< Port C selected */ -#define AFIO_EVCR_PORT_PD ((uint8_t)0x30) /*!< Port D selected */ -#define AFIO_EVCR_PORT_PE ((uint8_t)0x40) /*!< Port E selected */ - -#define AFIO_EVCR_EVOE ((uint8_t)0x80) /*!< Event Output Enable */ - -/****************** Bit definition for AFIO_MAPR register *******************/ -#define AFIO_MAPR_SPI1_REMAP ((uint32_t)0x00000001) /*!< SPI1 remapping */ -#define AFIO_MAPR_I2C1_REMAP ((uint32_t)0x00000002) /*!< I2C1 remapping */ -#define AFIO_MAPR_USART1_REMAP ((uint32_t)0x00000004) /*!< USART1 remapping */ -#define AFIO_MAPR_USART2_REMAP ((uint32_t)0x00000008) /*!< USART2 remapping */ - -#define AFIO_MAPR_USART3_REMAP ((uint32_t)0x00000030) /*!< USART3_REMAP[1:0] bits (USART3 remapping) */ -#define AFIO_MAPR_USART3_REMAP_0 ((uint32_t)0x00000010) /*!< Bit 0 */ -#define AFIO_MAPR_USART3_REMAP_1 ((uint32_t)0x00000020) /*!< Bit 1 */ - -/* USART3_REMAP configuration */ -#define AFIO_MAPR_USART3_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (TX/PB10, RX/PB11, CK/PB12, CTS/PB13, RTS/PB14) */ -#define AFIO_MAPR_USART3_REMAP_PARTIALREMAP ((uint32_t)0x00000010) /*!< Partial remap (TX/PC10, RX/PC11, CK/PC12, CTS/PB13, RTS/PB14) */ -#define AFIO_MAPR_USART3_REMAP_FULLREMAP ((uint32_t)0x00000030) /*!< Full remap (TX/PD8, RX/PD9, CK/PD10, CTS/PD11, RTS/PD12) */ - -#define AFIO_MAPR_TIM1_REMAP ((uint32_t)0x000000C0) /*!< TIM1_REMAP[1:0] bits (TIM1 remapping) */ -#define AFIO_MAPR_TIM1_REMAP_0 ((uint32_t)0x00000040) /*!< Bit 0 */ -#define AFIO_MAPR_TIM1_REMAP_1 ((uint32_t)0x00000080) /*!< Bit 1 */ - -/*!< TIM1_REMAP configuration */ -#define AFIO_MAPR_TIM1_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PB12, CH1N/PB13, CH2N/PB14, CH3N/PB15) */ -#define AFIO_MAPR_TIM1_REMAP_PARTIALREMAP ((uint32_t)0x00000040) /*!< Partial remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PA6, CH1N/PA7, CH2N/PB0, CH3N/PB1) */ -#define AFIO_MAPR_TIM1_REMAP_FULLREMAP ((uint32_t)0x000000C0) /*!< Full remap (ETR/PE7, CH1/PE9, CH2/PE11, CH3/PE13, CH4/PE14, BKIN/PE15, CH1N/PE8, CH2N/PE10, CH3N/PE12) */ - -#define AFIO_MAPR_TIM2_REMAP ((uint32_t)0x00000300) /*!< TIM2_REMAP[1:0] bits (TIM2 remapping) */ -#define AFIO_MAPR_TIM2_REMAP_0 ((uint32_t)0x00000100) /*!< Bit 0 */ -#define AFIO_MAPR_TIM2_REMAP_1 ((uint32_t)0x00000200) /*!< Bit 1 */ - -/*!< TIM2_REMAP configuration */ -#define AFIO_MAPR_TIM2_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (CH1/ETR/PA0, CH2/PA1, CH3/PA2, CH4/PA3) */ -#define AFIO_MAPR_TIM2_REMAP_PARTIALREMAP1 ((uint32_t)0x00000100) /*!< Partial remap (CH1/ETR/PA15, CH2/PB3, CH3/PA2, CH4/PA3) */ -#define AFIO_MAPR_TIM2_REMAP_PARTIALREMAP2 ((uint32_t)0x00000200) /*!< Partial remap (CH1/ETR/PA0, CH2/PA1, CH3/PB10, CH4/PB11) */ -#define AFIO_MAPR_TIM2_REMAP_FULLREMAP ((uint32_t)0x00000300) /*!< Full remap (CH1/ETR/PA15, CH2/PB3, CH3/PB10, CH4/PB11) */ - -#define AFIO_MAPR_TIM3_REMAP ((uint32_t)0x00000C00) /*!< TIM3_REMAP[1:0] bits (TIM3 remapping) */ -#define AFIO_MAPR_TIM3_REMAP_0 ((uint32_t)0x00000400) /*!< Bit 0 */ -#define AFIO_MAPR_TIM3_REMAP_1 ((uint32_t)0x00000800) /*!< Bit 1 */ - -/*!< TIM3_REMAP configuration */ -#define AFIO_MAPR_TIM3_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (CH1/PA6, CH2/PA7, CH3/PB0, CH4/PB1) */ -#define AFIO_MAPR_TIM3_REMAP_PARTIALREMAP ((uint32_t)0x00000800) /*!< Partial remap (CH1/PB4, CH2/PB5, CH3/PB0, CH4/PB1) */ -#define AFIO_MAPR_TIM3_REMAP_FULLREMAP ((uint32_t)0x00000C00) /*!< Full remap (CH1/PC6, CH2/PC7, CH3/PC8, CH4/PC9) */ - -#define AFIO_MAPR_TIM4_REMAP ((uint32_t)0x00001000) /*!< TIM4_REMAP bit (TIM4 remapping) */ - -#define AFIO_MAPR_CAN_REMAP ((uint32_t)0x00006000) /*!< CAN_REMAP[1:0] bits (CAN Alternate function remapping) */ -#define AFIO_MAPR_CAN_REMAP_0 ((uint32_t)0x00002000) /*!< Bit 0 */ -#define AFIO_MAPR_CAN_REMAP_1 ((uint32_t)0x00004000) /*!< Bit 1 */ - -/*!< CAN_REMAP configuration */ -#define AFIO_MAPR_CAN_REMAP_REMAP1 ((uint32_t)0x00000000) /*!< CANRX mapped to PA11, CANTX mapped to PA12 */ -#define AFIO_MAPR_CAN_REMAP_REMAP2 ((uint32_t)0x00004000) /*!< CANRX mapped to PB8, CANTX mapped to PB9 */ -#define AFIO_MAPR_CAN_REMAP_REMAP3 ((uint32_t)0x00006000) /*!< CANRX mapped to PD0, CANTX mapped to PD1 */ - -#define AFIO_MAPR_PD01_REMAP ((uint32_t)0x00008000) /*!< Port D0/Port D1 mapping on OSC_IN/OSC_OUT */ -#define AFIO_MAPR_TIM5CH4_IREMAP ((uint32_t)0x00010000) /*!< TIM5 Channel4 Internal Remap */ -#define AFIO_MAPR_ADC1_ETRGINJ_REMAP ((uint32_t)0x00020000) /*!< ADC 1 External Trigger Injected Conversion remapping */ -#define AFIO_MAPR_ADC1_ETRGREG_REMAP ((uint32_t)0x00040000) /*!< ADC 1 External Trigger Regular Conversion remapping */ -#define AFIO_MAPR_ADC2_ETRGINJ_REMAP ((uint32_t)0x00080000) /*!< ADC 2 External Trigger Injected Conversion remapping */ -#define AFIO_MAPR_ADC2_ETRGREG_REMAP ((uint32_t)0x00100000) /*!< ADC 2 External Trigger Regular Conversion remapping */ - -/*!< SWJ_CFG configuration */ -#define AFIO_MAPR_SWJ_CFG ((uint32_t)0x07000000) /*!< SWJ_CFG[2:0] bits (Serial Wire JTAG configuration) */ -#define AFIO_MAPR_SWJ_CFG_0 ((uint32_t)0x01000000) /*!< Bit 0 */ -#define AFIO_MAPR_SWJ_CFG_1 ((uint32_t)0x02000000) /*!< Bit 1 */ -#define AFIO_MAPR_SWJ_CFG_2 ((uint32_t)0x04000000) /*!< Bit 2 */ - -#define AFIO_MAPR_SWJ_CFG_RESET ((uint32_t)0x00000000) /*!< Full SWJ (JTAG-DP + SW-DP) : Reset State */ -#define AFIO_MAPR_SWJ_CFG_NOJNTRST ((uint32_t)0x01000000) /*!< Full SWJ (JTAG-DP + SW-DP) but without JNTRST */ -#define AFIO_MAPR_SWJ_CFG_JTAGDISABLE ((uint32_t)0x02000000) /*!< JTAG-DP Disabled and SW-DP Enabled */ -#define AFIO_MAPR_SWJ_CFG_DISABLE ((uint32_t)0x04000000) /*!< JTAG-DP Disabled and SW-DP Disabled */ - -#ifdef STM32F10X_CL -/*!< ETH_REMAP configuration */ - #define AFIO_MAPR_ETH_REMAP ((uint32_t)0x00200000) /*!< SPI3_REMAP bit (Ethernet MAC I/O remapping) */ - -/*!< CAN2_REMAP configuration */ - #define AFIO_MAPR_CAN2_REMAP ((uint32_t)0x00400000) /*!< CAN2_REMAP bit (CAN2 I/O remapping) */ - -/*!< MII_RMII_SEL configuration */ - #define AFIO_MAPR_MII_RMII_SEL ((uint32_t)0x00800000) /*!< MII_RMII_SEL bit (Ethernet MII or RMII selection) */ - -/*!< SPI3_REMAP configuration */ - #define AFIO_MAPR_SPI3_REMAP ((uint32_t)0x10000000) /*!< SPI3_REMAP bit (SPI3 remapping) */ - -/*!< TIM2ITR1_IREMAP configuration */ - #define AFIO_MAPR_TIM2ITR1_IREMAP ((uint32_t)0x20000000) /*!< TIM2ITR1_IREMAP bit (TIM2 internal trigger 1 remapping) */ - -/*!< PTP_PPS_REMAP configuration */ - #define AFIO_MAPR_PTP_PPS_REMAP ((uint32_t)0x20000000) /*!< PTP_PPS_REMAP bit (Ethernet PTP PPS remapping) */ -#endif - -/***************** Bit definition for AFIO_EXTICR1 register *****************/ -#define AFIO_EXTICR1_EXTI0 ((uint16_t)0x000F) /*!< EXTI 0 configuration */ -#define AFIO_EXTICR1_EXTI1 ((uint16_t)0x00F0) /*!< EXTI 1 configuration */ -#define AFIO_EXTICR1_EXTI2 ((uint16_t)0x0F00) /*!< EXTI 2 configuration */ -#define AFIO_EXTICR1_EXTI3 ((uint16_t)0xF000) /*!< EXTI 3 configuration */ - -/*!< EXTI0 configuration */ -#define AFIO_EXTICR1_EXTI0_PA ((uint16_t)0x0000) /*!< PA[0] pin */ -#define AFIO_EXTICR1_EXTI0_PB ((uint16_t)0x0001) /*!< PB[0] pin */ -#define AFIO_EXTICR1_EXTI0_PC ((uint16_t)0x0002) /*!< PC[0] pin */ -#define AFIO_EXTICR1_EXTI0_PD ((uint16_t)0x0003) /*!< PD[0] pin */ -#define AFIO_EXTICR1_EXTI0_PE ((uint16_t)0x0004) /*!< PE[0] pin */ -#define AFIO_EXTICR1_EXTI0_PF ((uint16_t)0x0005) /*!< PF[0] pin */ -#define AFIO_EXTICR1_EXTI0_PG ((uint16_t)0x0006) /*!< PG[0] pin */ - -/*!< EXTI1 configuration */ -#define AFIO_EXTICR1_EXTI1_PA ((uint16_t)0x0000) /*!< PA[1] pin */ -#define AFIO_EXTICR1_EXTI1_PB ((uint16_t)0x0010) /*!< PB[1] pin */ -#define AFIO_EXTICR1_EXTI1_PC ((uint16_t)0x0020) /*!< PC[1] pin */ -#define AFIO_EXTICR1_EXTI1_PD ((uint16_t)0x0030) /*!< PD[1] pin */ -#define AFIO_EXTICR1_EXTI1_PE ((uint16_t)0x0040) /*!< PE[1] pin */ -#define AFIO_EXTICR1_EXTI1_PF ((uint16_t)0x0050) /*!< PF[1] pin */ -#define AFIO_EXTICR1_EXTI1_PG ((uint16_t)0x0060) /*!< PG[1] pin */ - -/*!< EXTI2 configuration */ -#define AFIO_EXTICR1_EXTI2_PA ((uint16_t)0x0000) /*!< PA[2] pin */ -#define AFIO_EXTICR1_EXTI2_PB ((uint16_t)0x0100) /*!< PB[2] pin */ -#define AFIO_EXTICR1_EXTI2_PC ((uint16_t)0x0200) /*!< PC[2] pin */ -#define AFIO_EXTICR1_EXTI2_PD ((uint16_t)0x0300) /*!< PD[2] pin */ -#define AFIO_EXTICR1_EXTI2_PE ((uint16_t)0x0400) /*!< PE[2] pin */ -#define AFIO_EXTICR1_EXTI2_PF ((uint16_t)0x0500) /*!< PF[2] pin */ -#define AFIO_EXTICR1_EXTI2_PG ((uint16_t)0x0600) /*!< PG[2] pin */ - -/*!< EXTI3 configuration */ -#define AFIO_EXTICR1_EXTI3_PA ((uint16_t)0x0000) /*!< PA[3] pin */ -#define AFIO_EXTICR1_EXTI3_PB ((uint16_t)0x1000) /*!< PB[3] pin */ -#define AFIO_EXTICR1_EXTI3_PC ((uint16_t)0x2000) /*!< PC[3] pin */ -#define AFIO_EXTICR1_EXTI3_PD ((uint16_t)0x3000) /*!< PD[3] pin */ -#define AFIO_EXTICR1_EXTI3_PE ((uint16_t)0x4000) /*!< PE[3] pin */ -#define AFIO_EXTICR1_EXTI3_PF ((uint16_t)0x5000) /*!< PF[3] pin */ -#define AFIO_EXTICR1_EXTI3_PG ((uint16_t)0x6000) /*!< PG[3] pin */ - -/***************** Bit definition for AFIO_EXTICR2 register *****************/ -#define AFIO_EXTICR2_EXTI4 ((uint16_t)0x000F) /*!< EXTI 4 configuration */ -#define AFIO_EXTICR2_EXTI5 ((uint16_t)0x00F0) /*!< EXTI 5 configuration */ -#define AFIO_EXTICR2_EXTI6 ((uint16_t)0x0F00) /*!< EXTI 6 configuration */ -#define AFIO_EXTICR2_EXTI7 ((uint16_t)0xF000) /*!< EXTI 7 configuration */ - -/*!< EXTI4 configuration */ -#define AFIO_EXTICR2_EXTI4_PA ((uint16_t)0x0000) /*!< PA[4] pin */ -#define AFIO_EXTICR2_EXTI4_PB ((uint16_t)0x0001) /*!< PB[4] pin */ -#define AFIO_EXTICR2_EXTI4_PC ((uint16_t)0x0002) /*!< PC[4] pin */ -#define AFIO_EXTICR2_EXTI4_PD ((uint16_t)0x0003) /*!< PD[4] pin */ -#define AFIO_EXTICR2_EXTI4_PE ((uint16_t)0x0004) /*!< PE[4] pin */ -#define AFIO_EXTICR2_EXTI4_PF ((uint16_t)0x0005) /*!< PF[4] pin */ -#define AFIO_EXTICR2_EXTI4_PG ((uint16_t)0x0006) /*!< PG[4] pin */ - -/* EXTI5 configuration */ -#define AFIO_EXTICR2_EXTI5_PA ((uint16_t)0x0000) /*!< PA[5] pin */ -#define AFIO_EXTICR2_EXTI5_PB ((uint16_t)0x0010) /*!< PB[5] pin */ -#define AFIO_EXTICR2_EXTI5_PC ((uint16_t)0x0020) /*!< PC[5] pin */ -#define AFIO_EXTICR2_EXTI5_PD ((uint16_t)0x0030) /*!< PD[5] pin */ -#define AFIO_EXTICR2_EXTI5_PE ((uint16_t)0x0040) /*!< PE[5] pin */ -#define AFIO_EXTICR2_EXTI5_PF ((uint16_t)0x0050) /*!< PF[5] pin */ -#define AFIO_EXTICR2_EXTI5_PG ((uint16_t)0x0060) /*!< PG[5] pin */ - -/*!< EXTI6 configuration */ -#define AFIO_EXTICR2_EXTI6_PA ((uint16_t)0x0000) /*!< PA[6] pin */ -#define AFIO_EXTICR2_EXTI6_PB ((uint16_t)0x0100) /*!< PB[6] pin */ -#define AFIO_EXTICR2_EXTI6_PC ((uint16_t)0x0200) /*!< PC[6] pin */ -#define AFIO_EXTICR2_EXTI6_PD ((uint16_t)0x0300) /*!< PD[6] pin */ -#define AFIO_EXTICR2_EXTI6_PE ((uint16_t)0x0400) /*!< PE[6] pin */ -#define AFIO_EXTICR2_EXTI6_PF ((uint16_t)0x0500) /*!< PF[6] pin */ -#define AFIO_EXTICR2_EXTI6_PG ((uint16_t)0x0600) /*!< PG[6] pin */ - -/*!< EXTI7 configuration */ -#define AFIO_EXTICR2_EXTI7_PA ((uint16_t)0x0000) /*!< PA[7] pin */ -#define AFIO_EXTICR2_EXTI7_PB ((uint16_t)0x1000) /*!< PB[7] pin */ -#define AFIO_EXTICR2_EXTI7_PC ((uint16_t)0x2000) /*!< PC[7] pin */ -#define AFIO_EXTICR2_EXTI7_PD ((uint16_t)0x3000) /*!< PD[7] pin */ -#define AFIO_EXTICR2_EXTI7_PE ((uint16_t)0x4000) /*!< PE[7] pin */ -#define AFIO_EXTICR2_EXTI7_PF ((uint16_t)0x5000) /*!< PF[7] pin */ -#define AFIO_EXTICR2_EXTI7_PG ((uint16_t)0x6000) /*!< PG[7] pin */ - -/***************** Bit definition for AFIO_EXTICR3 register *****************/ -#define AFIO_EXTICR3_EXTI8 ((uint16_t)0x000F) /*!< EXTI 8 configuration */ -#define AFIO_EXTICR3_EXTI9 ((uint16_t)0x00F0) /*!< EXTI 9 configuration */ -#define AFIO_EXTICR3_EXTI10 ((uint16_t)0x0F00) /*!< EXTI 10 configuration */ -#define AFIO_EXTICR3_EXTI11 ((uint16_t)0xF000) /*!< EXTI 11 configuration */ - -/*!< EXTI8 configuration */ -#define AFIO_EXTICR3_EXTI8_PA ((uint16_t)0x0000) /*!< PA[8] pin */ -#define AFIO_EXTICR3_EXTI8_PB ((uint16_t)0x0001) /*!< PB[8] pin */ -#define AFIO_EXTICR3_EXTI8_PC ((uint16_t)0x0002) /*!< PC[8] pin */ -#define AFIO_EXTICR3_EXTI8_PD ((uint16_t)0x0003) /*!< PD[8] pin */ -#define AFIO_EXTICR3_EXTI8_PE ((uint16_t)0x0004) /*!< PE[8] pin */ -#define AFIO_EXTICR3_EXTI8_PF ((uint16_t)0x0005) /*!< PF[8] pin */ -#define AFIO_EXTICR3_EXTI8_PG ((uint16_t)0x0006) /*!< PG[8] pin */ - -/*!< EXTI9 configuration */ -#define AFIO_EXTICR3_EXTI9_PA ((uint16_t)0x0000) /*!< PA[9] pin */ -#define AFIO_EXTICR3_EXTI9_PB ((uint16_t)0x0010) /*!< PB[9] pin */ -#define AFIO_EXTICR3_EXTI9_PC ((uint16_t)0x0020) /*!< PC[9] pin */ -#define AFIO_EXTICR3_EXTI9_PD ((uint16_t)0x0030) /*!< PD[9] pin */ -#define AFIO_EXTICR3_EXTI9_PE ((uint16_t)0x0040) /*!< PE[9] pin */ -#define AFIO_EXTICR3_EXTI9_PF ((uint16_t)0x0050) /*!< PF[9] pin */ -#define AFIO_EXTICR3_EXTI9_PG ((uint16_t)0x0060) /*!< PG[9] pin */ - -/*!< EXTI10 configuration */ -#define AFIO_EXTICR3_EXTI10_PA ((uint16_t)0x0000) /*!< PA[10] pin */ -#define AFIO_EXTICR3_EXTI10_PB ((uint16_t)0x0100) /*!< PB[10] pin */ -#define AFIO_EXTICR3_EXTI10_PC ((uint16_t)0x0200) /*!< PC[10] pin */ -#define AFIO_EXTICR3_EXTI10_PD ((uint16_t)0x0300) /*!< PD[10] pin */ -#define AFIO_EXTICR3_EXTI10_PE ((uint16_t)0x0400) /*!< PE[10] pin */ -#define AFIO_EXTICR3_EXTI10_PF ((uint16_t)0x0500) /*!< PF[10] pin */ -#define AFIO_EXTICR3_EXTI10_PG ((uint16_t)0x0600) /*!< PG[10] pin */ - -/*!< EXTI11 configuration */ -#define AFIO_EXTICR3_EXTI11_PA ((uint16_t)0x0000) /*!< PA[11] pin */ -#define AFIO_EXTICR3_EXTI11_PB ((uint16_t)0x1000) /*!< PB[11] pin */ -#define AFIO_EXTICR3_EXTI11_PC ((uint16_t)0x2000) /*!< PC[11] pin */ -#define AFIO_EXTICR3_EXTI11_PD ((uint16_t)0x3000) /*!< PD[11] pin */ -#define AFIO_EXTICR3_EXTI11_PE ((uint16_t)0x4000) /*!< PE[11] pin */ -#define AFIO_EXTICR3_EXTI11_PF ((uint16_t)0x5000) /*!< PF[11] pin */ -#define AFIO_EXTICR3_EXTI11_PG ((uint16_t)0x6000) /*!< PG[11] pin */ - -/***************** Bit definition for AFIO_EXTICR4 register *****************/ -#define AFIO_EXTICR4_EXTI12 ((uint16_t)0x000F) /*!< EXTI 12 configuration */ -#define AFIO_EXTICR4_EXTI13 ((uint16_t)0x00F0) /*!< EXTI 13 configuration */ -#define AFIO_EXTICR4_EXTI14 ((uint16_t)0x0F00) /*!< EXTI 14 configuration */ -#define AFIO_EXTICR4_EXTI15 ((uint16_t)0xF000) /*!< EXTI 15 configuration */ - -/* EXTI12 configuration */ -#define AFIO_EXTICR4_EXTI12_PA ((uint16_t)0x0000) /*!< PA[12] pin */ -#define AFIO_EXTICR4_EXTI12_PB ((uint16_t)0x0001) /*!< PB[12] pin */ -#define AFIO_EXTICR4_EXTI12_PC ((uint16_t)0x0002) /*!< PC[12] pin */ -#define AFIO_EXTICR4_EXTI12_PD ((uint16_t)0x0003) /*!< PD[12] pin */ -#define AFIO_EXTICR4_EXTI12_PE ((uint16_t)0x0004) /*!< PE[12] pin */ -#define AFIO_EXTICR4_EXTI12_PF ((uint16_t)0x0005) /*!< PF[12] pin */ -#define AFIO_EXTICR4_EXTI12_PG ((uint16_t)0x0006) /*!< PG[12] pin */ - -/* EXTI13 configuration */ -#define AFIO_EXTICR4_EXTI13_PA ((uint16_t)0x0000) /*!< PA[13] pin */ -#define AFIO_EXTICR4_EXTI13_PB ((uint16_t)0x0010) /*!< PB[13] pin */ -#define AFIO_EXTICR4_EXTI13_PC ((uint16_t)0x0020) /*!< PC[13] pin */ -#define AFIO_EXTICR4_EXTI13_PD ((uint16_t)0x0030) /*!< PD[13] pin */ -#define AFIO_EXTICR4_EXTI13_PE ((uint16_t)0x0040) /*!< PE[13] pin */ -#define AFIO_EXTICR4_EXTI13_PF ((uint16_t)0x0050) /*!< PF[13] pin */ -#define AFIO_EXTICR4_EXTI13_PG ((uint16_t)0x0060) /*!< PG[13] pin */ - -/*!< EXTI14 configuration */ -#define AFIO_EXTICR4_EXTI14_PA ((uint16_t)0x0000) /*!< PA[14] pin */ -#define AFIO_EXTICR4_EXTI14_PB ((uint16_t)0x0100) /*!< PB[14] pin */ -#define AFIO_EXTICR4_EXTI14_PC ((uint16_t)0x0200) /*!< PC[14] pin */ -#define AFIO_EXTICR4_EXTI14_PD ((uint16_t)0x0300) /*!< PD[14] pin */ -#define AFIO_EXTICR4_EXTI14_PE ((uint16_t)0x0400) /*!< PE[14] pin */ -#define AFIO_EXTICR4_EXTI14_PF ((uint16_t)0x0500) /*!< PF[14] pin */ -#define AFIO_EXTICR4_EXTI14_PG ((uint16_t)0x0600) /*!< PG[14] pin */ - -/*!< EXTI15 configuration */ -#define AFIO_EXTICR4_EXTI15_PA ((uint16_t)0x0000) /*!< PA[15] pin */ -#define AFIO_EXTICR4_EXTI15_PB ((uint16_t)0x1000) /*!< PB[15] pin */ -#define AFIO_EXTICR4_EXTI15_PC ((uint16_t)0x2000) /*!< PC[15] pin */ -#define AFIO_EXTICR4_EXTI15_PD ((uint16_t)0x3000) /*!< PD[15] pin */ -#define AFIO_EXTICR4_EXTI15_PE ((uint16_t)0x4000) /*!< PE[15] pin */ -#define AFIO_EXTICR4_EXTI15_PF ((uint16_t)0x5000) /*!< PF[15] pin */ -#define AFIO_EXTICR4_EXTI15_PG ((uint16_t)0x6000) /*!< PG[15] pin */ - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) -/****************** Bit definition for AFIO_MAPR2 register ******************/ -#define AFIO_MAPR2_TIM15_REMAP ((uint32_t)0x00000001) /*!< TIM15 remapping */ -#define AFIO_MAPR2_TIM16_REMAP ((uint32_t)0x00000002) /*!< TIM16 remapping */ -#define AFIO_MAPR2_TIM17_REMAP ((uint32_t)0x00000004) /*!< TIM17 remapping */ -#define AFIO_MAPR2_CEC_REMAP ((uint32_t)0x00000008) /*!< CEC remapping */ -#define AFIO_MAPR2_TIM1_DMA_REMAP ((uint32_t)0x00000010) /*!< TIM1_DMA remapping */ -#endif - -#ifdef STM32F10X_HD_VL -#define AFIO_MAPR2_TIM13_REMAP ((uint32_t)0x00000100) /*!< TIM13 remapping */ -#define AFIO_MAPR2_TIM14_REMAP ((uint32_t)0x00000200) /*!< TIM14 remapping */ -#define AFIO_MAPR2_FSMC_NADV_REMAP ((uint32_t)0x00000400) /*!< FSMC NADV remapping */ -#define AFIO_MAPR2_TIM67_DAC_DMA_REMAP ((uint32_t)0x00000800) /*!< TIM6/TIM7 and DAC DMA remapping */ -#define AFIO_MAPR2_TIM12_REMAP ((uint32_t)0x00001000) /*!< TIM12 remapping */ -#define AFIO_MAPR2_MISC_REMAP ((uint32_t)0x00002000) /*!< Miscellaneous remapping */ -#endif - -#ifdef STM32F10X_XL -/****************** Bit definition for AFIO_MAPR2 register ******************/ -#define AFIO_MAPR2_TIM9_REMAP ((uint32_t)0x00000020) /*!< TIM9 remapping */ -#define AFIO_MAPR2_TIM10_REMAP ((uint32_t)0x00000040) /*!< TIM10 remapping */ -#define AFIO_MAPR2_TIM11_REMAP ((uint32_t)0x00000080) /*!< TIM11 remapping */ -#define AFIO_MAPR2_TIM13_REMAP ((uint32_t)0x00000100) /*!< TIM13 remapping */ -#define AFIO_MAPR2_TIM14_REMAP ((uint32_t)0x00000200) /*!< TIM14 remapping */ -#define AFIO_MAPR2_FSMC_NADV_REMAP ((uint32_t)0x00000400) /*!< FSMC NADV remapping */ -#endif - -/******************************************************************************/ -/* */ -/* SystemTick */ -/* */ -/******************************************************************************/ - -/***************** Bit definition for SysTick_CTRL register *****************/ -#define SysTick_CTRL_ENABLE ((uint32_t)0x00000001) /*!< Counter enable */ -#define SysTick_CTRL_TICKINT ((uint32_t)0x00000002) /*!< Counting down to 0 pends the SysTick handler */ -#define SysTick_CTRL_CLKSOURCE ((uint32_t)0x00000004) /*!< Clock source */ -#define SysTick_CTRL_COUNTFLAG ((uint32_t)0x00010000) /*!< Count Flag */ - -/***************** Bit definition for SysTick_LOAD register *****************/ -#define SysTick_LOAD_RELOAD ((uint32_t)0x00FFFFFF) /*!< Value to load into the SysTick Current Value Register when the counter reaches 0 */ - -/***************** Bit definition for SysTick_VAL register ******************/ -#define SysTick_VAL_CURRENT ((uint32_t)0x00FFFFFF) /*!< Current value at the time the register is accessed */ - -/***************** Bit definition for SysTick_CALIB register ****************/ -#define SysTick_CALIB_TENMS ((uint32_t)0x00FFFFFF) /*!< Reload value to use for 10ms timing */ -#define SysTick_CALIB_SKEW ((uint32_t)0x40000000) /*!< Calibration value is not exactly 10 ms */ -#define SysTick_CALIB_NOREF ((uint32_t)0x80000000) /*!< The reference clock is not provided */ - -/******************************************************************************/ -/* */ -/* Nested Vectored Interrupt Controller */ -/* */ -/******************************************************************************/ - -/****************** Bit definition for NVIC_ISER register *******************/ -#define NVIC_ISER_SETENA ((uint32_t)0xFFFFFFFF) /*!< Interrupt set enable bits */ -#define NVIC_ISER_SETENA_0 ((uint32_t)0x00000001) /*!< bit 0 */ -#define NVIC_ISER_SETENA_1 ((uint32_t)0x00000002) /*!< bit 1 */ -#define NVIC_ISER_SETENA_2 ((uint32_t)0x00000004) /*!< bit 2 */ -#define NVIC_ISER_SETENA_3 ((uint32_t)0x00000008) /*!< bit 3 */ -#define NVIC_ISER_SETENA_4 ((uint32_t)0x00000010) /*!< bit 4 */ -#define NVIC_ISER_SETENA_5 ((uint32_t)0x00000020) /*!< bit 5 */ -#define NVIC_ISER_SETENA_6 ((uint32_t)0x00000040) /*!< bit 6 */ -#define NVIC_ISER_SETENA_7 ((uint32_t)0x00000080) /*!< bit 7 */ -#define NVIC_ISER_SETENA_8 ((uint32_t)0x00000100) /*!< bit 8 */ -#define NVIC_ISER_SETENA_9 ((uint32_t)0x00000200) /*!< bit 9 */ -#define NVIC_ISER_SETENA_10 ((uint32_t)0x00000400) /*!< bit 10 */ -#define NVIC_ISER_SETENA_11 ((uint32_t)0x00000800) /*!< bit 11 */ -#define NVIC_ISER_SETENA_12 ((uint32_t)0x00001000) /*!< bit 12 */ -#define NVIC_ISER_SETENA_13 ((uint32_t)0x00002000) /*!< bit 13 */ -#define NVIC_ISER_SETENA_14 ((uint32_t)0x00004000) /*!< bit 14 */ -#define NVIC_ISER_SETENA_15 ((uint32_t)0x00008000) /*!< bit 15 */ -#define NVIC_ISER_SETENA_16 ((uint32_t)0x00010000) /*!< bit 16 */ -#define NVIC_ISER_SETENA_17 ((uint32_t)0x00020000) /*!< bit 17 */ -#define NVIC_ISER_SETENA_18 ((uint32_t)0x00040000) /*!< bit 18 */ -#define NVIC_ISER_SETENA_19 ((uint32_t)0x00080000) /*!< bit 19 */ -#define NVIC_ISER_SETENA_20 ((uint32_t)0x00100000) /*!< bit 20 */ -#define NVIC_ISER_SETENA_21 ((uint32_t)0x00200000) /*!< bit 21 */ -#define NVIC_ISER_SETENA_22 ((uint32_t)0x00400000) /*!< bit 22 */ -#define NVIC_ISER_SETENA_23 ((uint32_t)0x00800000) /*!< bit 23 */ -#define NVIC_ISER_SETENA_24 ((uint32_t)0x01000000) /*!< bit 24 */ -#define NVIC_ISER_SETENA_25 ((uint32_t)0x02000000) /*!< bit 25 */ -#define NVIC_ISER_SETENA_26 ((uint32_t)0x04000000) /*!< bit 26 */ -#define NVIC_ISER_SETENA_27 ((uint32_t)0x08000000) /*!< bit 27 */ -#define NVIC_ISER_SETENA_28 ((uint32_t)0x10000000) /*!< bit 28 */ -#define NVIC_ISER_SETENA_29 ((uint32_t)0x20000000) /*!< bit 29 */ -#define NVIC_ISER_SETENA_30 ((uint32_t)0x40000000) /*!< bit 30 */ -#define NVIC_ISER_SETENA_31 ((uint32_t)0x80000000) /*!< bit 31 */ - -/****************** Bit definition for NVIC_ICER register *******************/ -#define NVIC_ICER_CLRENA ((uint32_t)0xFFFFFFFF) /*!< Interrupt clear-enable bits */ -#define NVIC_ICER_CLRENA_0 ((uint32_t)0x00000001) /*!< bit 0 */ -#define NVIC_ICER_CLRENA_1 ((uint32_t)0x00000002) /*!< bit 1 */ -#define NVIC_ICER_CLRENA_2 ((uint32_t)0x00000004) /*!< bit 2 */ -#define NVIC_ICER_CLRENA_3 ((uint32_t)0x00000008) /*!< bit 3 */ -#define NVIC_ICER_CLRENA_4 ((uint32_t)0x00000010) /*!< bit 4 */ -#define NVIC_ICER_CLRENA_5 ((uint32_t)0x00000020) /*!< bit 5 */ -#define NVIC_ICER_CLRENA_6 ((uint32_t)0x00000040) /*!< bit 6 */ -#define NVIC_ICER_CLRENA_7 ((uint32_t)0x00000080) /*!< bit 7 */ -#define NVIC_ICER_CLRENA_8 ((uint32_t)0x00000100) /*!< bit 8 */ -#define NVIC_ICER_CLRENA_9 ((uint32_t)0x00000200) /*!< bit 9 */ -#define NVIC_ICER_CLRENA_10 ((uint32_t)0x00000400) /*!< bit 10 */ -#define NVIC_ICER_CLRENA_11 ((uint32_t)0x00000800) /*!< bit 11 */ -#define NVIC_ICER_CLRENA_12 ((uint32_t)0x00001000) /*!< bit 12 */ -#define NVIC_ICER_CLRENA_13 ((uint32_t)0x00002000) /*!< bit 13 */ -#define NVIC_ICER_CLRENA_14 ((uint32_t)0x00004000) /*!< bit 14 */ -#define NVIC_ICER_CLRENA_15 ((uint32_t)0x00008000) /*!< bit 15 */ -#define NVIC_ICER_CLRENA_16 ((uint32_t)0x00010000) /*!< bit 16 */ -#define NVIC_ICER_CLRENA_17 ((uint32_t)0x00020000) /*!< bit 17 */ -#define NVIC_ICER_CLRENA_18 ((uint32_t)0x00040000) /*!< bit 18 */ -#define NVIC_ICER_CLRENA_19 ((uint32_t)0x00080000) /*!< bit 19 */ -#define NVIC_ICER_CLRENA_20 ((uint32_t)0x00100000) /*!< bit 20 */ -#define NVIC_ICER_CLRENA_21 ((uint32_t)0x00200000) /*!< bit 21 */ -#define NVIC_ICER_CLRENA_22 ((uint32_t)0x00400000) /*!< bit 22 */ -#define NVIC_ICER_CLRENA_23 ((uint32_t)0x00800000) /*!< bit 23 */ -#define NVIC_ICER_CLRENA_24 ((uint32_t)0x01000000) /*!< bit 24 */ -#define NVIC_ICER_CLRENA_25 ((uint32_t)0x02000000) /*!< bit 25 */ -#define NVIC_ICER_CLRENA_26 ((uint32_t)0x04000000) /*!< bit 26 */ -#define NVIC_ICER_CLRENA_27 ((uint32_t)0x08000000) /*!< bit 27 */ -#define NVIC_ICER_CLRENA_28 ((uint32_t)0x10000000) /*!< bit 28 */ -#define NVIC_ICER_CLRENA_29 ((uint32_t)0x20000000) /*!< bit 29 */ -#define NVIC_ICER_CLRENA_30 ((uint32_t)0x40000000) /*!< bit 30 */ -#define NVIC_ICER_CLRENA_31 ((uint32_t)0x80000000) /*!< bit 31 */ - -/****************** Bit definition for NVIC_ISPR register *******************/ -#define NVIC_ISPR_SETPEND ((uint32_t)0xFFFFFFFF) /*!< Interrupt set-pending bits */ -#define NVIC_ISPR_SETPEND_0 ((uint32_t)0x00000001) /*!< bit 0 */ -#define NVIC_ISPR_SETPEND_1 ((uint32_t)0x00000002) /*!< bit 1 */ -#define NVIC_ISPR_SETPEND_2 ((uint32_t)0x00000004) /*!< bit 2 */ -#define NVIC_ISPR_SETPEND_3 ((uint32_t)0x00000008) /*!< bit 3 */ -#define NVIC_ISPR_SETPEND_4 ((uint32_t)0x00000010) /*!< bit 4 */ -#define NVIC_ISPR_SETPEND_5 ((uint32_t)0x00000020) /*!< bit 5 */ -#define NVIC_ISPR_SETPEND_6 ((uint32_t)0x00000040) /*!< bit 6 */ -#define NVIC_ISPR_SETPEND_7 ((uint32_t)0x00000080) /*!< bit 7 */ -#define NVIC_ISPR_SETPEND_8 ((uint32_t)0x00000100) /*!< bit 8 */ -#define NVIC_ISPR_SETPEND_9 ((uint32_t)0x00000200) /*!< bit 9 */ -#define NVIC_ISPR_SETPEND_10 ((uint32_t)0x00000400) /*!< bit 10 */ -#define NVIC_ISPR_SETPEND_11 ((uint32_t)0x00000800) /*!< bit 11 */ -#define NVIC_ISPR_SETPEND_12 ((uint32_t)0x00001000) /*!< bit 12 */ -#define NVIC_ISPR_SETPEND_13 ((uint32_t)0x00002000) /*!< bit 13 */ -#define NVIC_ISPR_SETPEND_14 ((uint32_t)0x00004000) /*!< bit 14 */ -#define NVIC_ISPR_SETPEND_15 ((uint32_t)0x00008000) /*!< bit 15 */ -#define NVIC_ISPR_SETPEND_16 ((uint32_t)0x00010000) /*!< bit 16 */ -#define NVIC_ISPR_SETPEND_17 ((uint32_t)0x00020000) /*!< bit 17 */ -#define NVIC_ISPR_SETPEND_18 ((uint32_t)0x00040000) /*!< bit 18 */ -#define NVIC_ISPR_SETPEND_19 ((uint32_t)0x00080000) /*!< bit 19 */ -#define NVIC_ISPR_SETPEND_20 ((uint32_t)0x00100000) /*!< bit 20 */ -#define NVIC_ISPR_SETPEND_21 ((uint32_t)0x00200000) /*!< bit 21 */ -#define NVIC_ISPR_SETPEND_22 ((uint32_t)0x00400000) /*!< bit 22 */ -#define NVIC_ISPR_SETPEND_23 ((uint32_t)0x00800000) /*!< bit 23 */ -#define NVIC_ISPR_SETPEND_24 ((uint32_t)0x01000000) /*!< bit 24 */ -#define NVIC_ISPR_SETPEND_25 ((uint32_t)0x02000000) /*!< bit 25 */ -#define NVIC_ISPR_SETPEND_26 ((uint32_t)0x04000000) /*!< bit 26 */ -#define NVIC_ISPR_SETPEND_27 ((uint32_t)0x08000000) /*!< bit 27 */ -#define NVIC_ISPR_SETPEND_28 ((uint32_t)0x10000000) /*!< bit 28 */ -#define NVIC_ISPR_SETPEND_29 ((uint32_t)0x20000000) /*!< bit 29 */ -#define NVIC_ISPR_SETPEND_30 ((uint32_t)0x40000000) /*!< bit 30 */ -#define NVIC_ISPR_SETPEND_31 ((uint32_t)0x80000000) /*!< bit 31 */ - -/****************** Bit definition for NVIC_ICPR register *******************/ -#define NVIC_ICPR_CLRPEND ((uint32_t)0xFFFFFFFF) /*!< Interrupt clear-pending bits */ -#define NVIC_ICPR_CLRPEND_0 ((uint32_t)0x00000001) /*!< bit 0 */ -#define NVIC_ICPR_CLRPEND_1 ((uint32_t)0x00000002) /*!< bit 1 */ -#define NVIC_ICPR_CLRPEND_2 ((uint32_t)0x00000004) /*!< bit 2 */ -#define NVIC_ICPR_CLRPEND_3 ((uint32_t)0x00000008) /*!< bit 3 */ -#define NVIC_ICPR_CLRPEND_4 ((uint32_t)0x00000010) /*!< bit 4 */ -#define NVIC_ICPR_CLRPEND_5 ((uint32_t)0x00000020) /*!< bit 5 */ -#define NVIC_ICPR_CLRPEND_6 ((uint32_t)0x00000040) /*!< bit 6 */ -#define NVIC_ICPR_CLRPEND_7 ((uint32_t)0x00000080) /*!< bit 7 */ -#define NVIC_ICPR_CLRPEND_8 ((uint32_t)0x00000100) /*!< bit 8 */ -#define NVIC_ICPR_CLRPEND_9 ((uint32_t)0x00000200) /*!< bit 9 */ -#define NVIC_ICPR_CLRPEND_10 ((uint32_t)0x00000400) /*!< bit 10 */ -#define NVIC_ICPR_CLRPEND_11 ((uint32_t)0x00000800) /*!< bit 11 */ -#define NVIC_ICPR_CLRPEND_12 ((uint32_t)0x00001000) /*!< bit 12 */ -#define NVIC_ICPR_CLRPEND_13 ((uint32_t)0x00002000) /*!< bit 13 */ -#define NVIC_ICPR_CLRPEND_14 ((uint32_t)0x00004000) /*!< bit 14 */ -#define NVIC_ICPR_CLRPEND_15 ((uint32_t)0x00008000) /*!< bit 15 */ -#define NVIC_ICPR_CLRPEND_16 ((uint32_t)0x00010000) /*!< bit 16 */ -#define NVIC_ICPR_CLRPEND_17 ((uint32_t)0x00020000) /*!< bit 17 */ -#define NVIC_ICPR_CLRPEND_18 ((uint32_t)0x00040000) /*!< bit 18 */ -#define NVIC_ICPR_CLRPEND_19 ((uint32_t)0x00080000) /*!< bit 19 */ -#define NVIC_ICPR_CLRPEND_20 ((uint32_t)0x00100000) /*!< bit 20 */ -#define NVIC_ICPR_CLRPEND_21 ((uint32_t)0x00200000) /*!< bit 21 */ -#define NVIC_ICPR_CLRPEND_22 ((uint32_t)0x00400000) /*!< bit 22 */ -#define NVIC_ICPR_CLRPEND_23 ((uint32_t)0x00800000) /*!< bit 23 */ -#define NVIC_ICPR_CLRPEND_24 ((uint32_t)0x01000000) /*!< bit 24 */ -#define NVIC_ICPR_CLRPEND_25 ((uint32_t)0x02000000) /*!< bit 25 */ -#define NVIC_ICPR_CLRPEND_26 ((uint32_t)0x04000000) /*!< bit 26 */ -#define NVIC_ICPR_CLRPEND_27 ((uint32_t)0x08000000) /*!< bit 27 */ -#define NVIC_ICPR_CLRPEND_28 ((uint32_t)0x10000000) /*!< bit 28 */ -#define NVIC_ICPR_CLRPEND_29 ((uint32_t)0x20000000) /*!< bit 29 */ -#define NVIC_ICPR_CLRPEND_30 ((uint32_t)0x40000000) /*!< bit 30 */ -#define NVIC_ICPR_CLRPEND_31 ((uint32_t)0x80000000) /*!< bit 31 */ - -/****************** Bit definition for NVIC_IABR register *******************/ -#define NVIC_IABR_ACTIVE ((uint32_t)0xFFFFFFFF) /*!< Interrupt active flags */ -#define NVIC_IABR_ACTIVE_0 ((uint32_t)0x00000001) /*!< bit 0 */ -#define NVIC_IABR_ACTIVE_1 ((uint32_t)0x00000002) /*!< bit 1 */ -#define NVIC_IABR_ACTIVE_2 ((uint32_t)0x00000004) /*!< bit 2 */ -#define NVIC_IABR_ACTIVE_3 ((uint32_t)0x00000008) /*!< bit 3 */ -#define NVIC_IABR_ACTIVE_4 ((uint32_t)0x00000010) /*!< bit 4 */ -#define NVIC_IABR_ACTIVE_5 ((uint32_t)0x00000020) /*!< bit 5 */ -#define NVIC_IABR_ACTIVE_6 ((uint32_t)0x00000040) /*!< bit 6 */ -#define NVIC_IABR_ACTIVE_7 ((uint32_t)0x00000080) /*!< bit 7 */ -#define NVIC_IABR_ACTIVE_8 ((uint32_t)0x00000100) /*!< bit 8 */ -#define NVIC_IABR_ACTIVE_9 ((uint32_t)0x00000200) /*!< bit 9 */ -#define NVIC_IABR_ACTIVE_10 ((uint32_t)0x00000400) /*!< bit 10 */ -#define NVIC_IABR_ACTIVE_11 ((uint32_t)0x00000800) /*!< bit 11 */ -#define NVIC_IABR_ACTIVE_12 ((uint32_t)0x00001000) /*!< bit 12 */ -#define NVIC_IABR_ACTIVE_13 ((uint32_t)0x00002000) /*!< bit 13 */ -#define NVIC_IABR_ACTIVE_14 ((uint32_t)0x00004000) /*!< bit 14 */ -#define NVIC_IABR_ACTIVE_15 ((uint32_t)0x00008000) /*!< bit 15 */ -#define NVIC_IABR_ACTIVE_16 ((uint32_t)0x00010000) /*!< bit 16 */ -#define NVIC_IABR_ACTIVE_17 ((uint32_t)0x00020000) /*!< bit 17 */ -#define NVIC_IABR_ACTIVE_18 ((uint32_t)0x00040000) /*!< bit 18 */ -#define NVIC_IABR_ACTIVE_19 ((uint32_t)0x00080000) /*!< bit 19 */ -#define NVIC_IABR_ACTIVE_20 ((uint32_t)0x00100000) /*!< bit 20 */ -#define NVIC_IABR_ACTIVE_21 ((uint32_t)0x00200000) /*!< bit 21 */ -#define NVIC_IABR_ACTIVE_22 ((uint32_t)0x00400000) /*!< bit 22 */ -#define NVIC_IABR_ACTIVE_23 ((uint32_t)0x00800000) /*!< bit 23 */ -#define NVIC_IABR_ACTIVE_24 ((uint32_t)0x01000000) /*!< bit 24 */ -#define NVIC_IABR_ACTIVE_25 ((uint32_t)0x02000000) /*!< bit 25 */ -#define NVIC_IABR_ACTIVE_26 ((uint32_t)0x04000000) /*!< bit 26 */ -#define NVIC_IABR_ACTIVE_27 ((uint32_t)0x08000000) /*!< bit 27 */ -#define NVIC_IABR_ACTIVE_28 ((uint32_t)0x10000000) /*!< bit 28 */ -#define NVIC_IABR_ACTIVE_29 ((uint32_t)0x20000000) /*!< bit 29 */ -#define NVIC_IABR_ACTIVE_30 ((uint32_t)0x40000000) /*!< bit 30 */ -#define NVIC_IABR_ACTIVE_31 ((uint32_t)0x80000000) /*!< bit 31 */ - -/****************** Bit definition for NVIC_PRI0 register *******************/ -#define NVIC_IPR0_PRI_0 ((uint32_t)0x000000FF) /*!< Priority of interrupt 0 */ -#define NVIC_IPR0_PRI_1 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 1 */ -#define NVIC_IPR0_PRI_2 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 2 */ -#define NVIC_IPR0_PRI_3 ((uint32_t)0xFF000000) /*!< Priority of interrupt 3 */ - -/****************** Bit definition for NVIC_PRI1 register *******************/ -#define NVIC_IPR1_PRI_4 ((uint32_t)0x000000FF) /*!< Priority of interrupt 4 */ -#define NVIC_IPR1_PRI_5 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 5 */ -#define NVIC_IPR1_PRI_6 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 6 */ -#define NVIC_IPR1_PRI_7 ((uint32_t)0xFF000000) /*!< Priority of interrupt 7 */ - -/****************** Bit definition for NVIC_PRI2 register *******************/ -#define NVIC_IPR2_PRI_8 ((uint32_t)0x000000FF) /*!< Priority of interrupt 8 */ -#define NVIC_IPR2_PRI_9 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 9 */ -#define NVIC_IPR2_PRI_10 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 10 */ -#define NVIC_IPR2_PRI_11 ((uint32_t)0xFF000000) /*!< Priority of interrupt 11 */ - -/****************** Bit definition for NVIC_PRI3 register *******************/ -#define NVIC_IPR3_PRI_12 ((uint32_t)0x000000FF) /*!< Priority of interrupt 12 */ -#define NVIC_IPR3_PRI_13 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 13 */ -#define NVIC_IPR3_PRI_14 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 14 */ -#define NVIC_IPR3_PRI_15 ((uint32_t)0xFF000000) /*!< Priority of interrupt 15 */ - -/****************** Bit definition for NVIC_PRI4 register *******************/ -#define NVIC_IPR4_PRI_16 ((uint32_t)0x000000FF) /*!< Priority of interrupt 16 */ -#define NVIC_IPR4_PRI_17 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 17 */ -#define NVIC_IPR4_PRI_18 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 18 */ -#define NVIC_IPR4_PRI_19 ((uint32_t)0xFF000000) /*!< Priority of interrupt 19 */ - -/****************** Bit definition for NVIC_PRI5 register *******************/ -#define NVIC_IPR5_PRI_20 ((uint32_t)0x000000FF) /*!< Priority of interrupt 20 */ -#define NVIC_IPR5_PRI_21 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 21 */ -#define NVIC_IPR5_PRI_22 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 22 */ -#define NVIC_IPR5_PRI_23 ((uint32_t)0xFF000000) /*!< Priority of interrupt 23 */ - -/****************** Bit definition for NVIC_PRI6 register *******************/ -#define NVIC_IPR6_PRI_24 ((uint32_t)0x000000FF) /*!< Priority of interrupt 24 */ -#define NVIC_IPR6_PRI_25 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 25 */ -#define NVIC_IPR6_PRI_26 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 26 */ -#define NVIC_IPR6_PRI_27 ((uint32_t)0xFF000000) /*!< Priority of interrupt 27 */ - -/****************** Bit definition for NVIC_PRI7 register *******************/ -#define NVIC_IPR7_PRI_28 ((uint32_t)0x000000FF) /*!< Priority of interrupt 28 */ -#define NVIC_IPR7_PRI_29 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 29 */ -#define NVIC_IPR7_PRI_30 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 30 */ -#define NVIC_IPR7_PRI_31 ((uint32_t)0xFF000000) /*!< Priority of interrupt 31 */ - -/****************** Bit definition for SCB_CPUID register *******************/ -#define SCB_CPUID_REVISION ((uint32_t)0x0000000F) /*!< Implementation defined revision number */ -#define SCB_CPUID_PARTNO ((uint32_t)0x0000FFF0) /*!< Number of processor within family */ -#define SCB_CPUID_Constant ((uint32_t)0x000F0000) /*!< Reads as 0x0F */ -#define SCB_CPUID_VARIANT ((uint32_t)0x00F00000) /*!< Implementation defined variant number */ -#define SCB_CPUID_IMPLEMENTER ((uint32_t)0xFF000000) /*!< Implementer code. ARM is 0x41 */ - -/******************* Bit definition for SCB_ICSR register *******************/ -#define SCB_ICSR_VECTACTIVE ((uint32_t)0x000001FF) /*!< Active ISR number field */ -#define SCB_ICSR_RETTOBASE ((uint32_t)0x00000800) /*!< All active exceptions minus the IPSR_current_exception yields the empty set */ -#define SCB_ICSR_VECTPENDING ((uint32_t)0x003FF000) /*!< Pending ISR number field */ -#define SCB_ICSR_ISRPENDING ((uint32_t)0x00400000) /*!< Interrupt pending flag */ -#define SCB_ICSR_ISRPREEMPT ((uint32_t)0x00800000) /*!< It indicates that a pending interrupt becomes active in the next running cycle */ -#define SCB_ICSR_PENDSTCLR ((uint32_t)0x02000000) /*!< Clear pending SysTick bit */ -#define SCB_ICSR_PENDSTSET ((uint32_t)0x04000000) /*!< Set pending SysTick bit */ -#define SCB_ICSR_PENDSVCLR ((uint32_t)0x08000000) /*!< Clear pending pendSV bit */ -#define SCB_ICSR_PENDSVSET ((uint32_t)0x10000000) /*!< Set pending pendSV bit */ -#define SCB_ICSR_NMIPENDSET ((uint32_t)0x80000000) /*!< Set pending NMI bit */ - -/******************* Bit definition for SCB_VTOR register *******************/ -#define SCB_VTOR_TBLOFF ((uint32_t)0x1FFFFF80) /*!< Vector table base offset field */ -#define SCB_VTOR_TBLBASE ((uint32_t)0x20000000) /*!< Table base in code(0) or RAM(1) */ - -/*!<***************** Bit definition for SCB_AIRCR register *******************/ -#define SCB_AIRCR_VECTRESET ((uint32_t)0x00000001) /*!< System Reset bit */ -#define SCB_AIRCR_VECTCLRACTIVE ((uint32_t)0x00000002) /*!< Clear active vector bit */ -#define SCB_AIRCR_SYSRESETREQ ((uint32_t)0x00000004) /*!< Requests chip control logic to generate a reset */ - -#define SCB_AIRCR_PRIGROUP ((uint32_t)0x00000700) /*!< PRIGROUP[2:0] bits (Priority group) */ -#define SCB_AIRCR_PRIGROUP_0 ((uint32_t)0x00000100) /*!< Bit 0 */ -#define SCB_AIRCR_PRIGROUP_1 ((uint32_t)0x00000200) /*!< Bit 1 */ -#define SCB_AIRCR_PRIGROUP_2 ((uint32_t)0x00000400) /*!< Bit 2 */ - -/* prority group configuration */ -#define SCB_AIRCR_PRIGROUP0 ((uint32_t)0x00000000) /*!< Priority group=0 (7 bits of pre-emption priority, 1 bit of subpriority) */ -#define SCB_AIRCR_PRIGROUP1 ((uint32_t)0x00000100) /*!< Priority group=1 (6 bits of pre-emption priority, 2 bits of subpriority) */ -#define SCB_AIRCR_PRIGROUP2 ((uint32_t)0x00000200) /*!< Priority group=2 (5 bits of pre-emption priority, 3 bits of subpriority) */ -#define SCB_AIRCR_PRIGROUP3 ((uint32_t)0x00000300) /*!< Priority group=3 (4 bits of pre-emption priority, 4 bits of subpriority) */ -#define SCB_AIRCR_PRIGROUP4 ((uint32_t)0x00000400) /*!< Priority group=4 (3 bits of pre-emption priority, 5 bits of subpriority) */ -#define SCB_AIRCR_PRIGROUP5 ((uint32_t)0x00000500) /*!< Priority group=5 (2 bits of pre-emption priority, 6 bits of subpriority) */ -#define SCB_AIRCR_PRIGROUP6 ((uint32_t)0x00000600) /*!< Priority group=6 (1 bit of pre-emption priority, 7 bits of subpriority) */ -#define SCB_AIRCR_PRIGROUP7 ((uint32_t)0x00000700) /*!< Priority group=7 (no pre-emption priority, 8 bits of subpriority) */ - -#define SCB_AIRCR_ENDIANESS ((uint32_t)0x00008000) /*!< Data endianness bit */ -#define SCB_AIRCR_VECTKEY ((uint32_t)0xFFFF0000) /*!< Register key (VECTKEY) - Reads as 0xFA05 (VECTKEYSTAT) */ - -/******************* Bit definition for SCB_SCR register ********************/ -#define SCB_SCR_SLEEPONEXIT ((uint8_t)0x02) /*!< Sleep on exit bit */ -#define SCB_SCR_SLEEPDEEP ((uint8_t)0x04) /*!< Sleep deep bit */ -#define SCB_SCR_SEVONPEND ((uint8_t)0x10) /*!< Wake up from WFE */ - -/******************** Bit definition for SCB_CCR register *******************/ -#define SCB_CCR_NONBASETHRDENA ((uint16_t)0x0001) /*!< Thread mode can be entered from any level in Handler mode by controlled return value */ -#define SCB_CCR_USERSETMPEND ((uint16_t)0x0002) /*!< Enables user code to write the Software Trigger Interrupt register to trigger (pend) a Main exception */ -#define SCB_CCR_UNALIGN_TRP ((uint16_t)0x0008) /*!< Trap for unaligned access */ -#define SCB_CCR_DIV_0_TRP ((uint16_t)0x0010) /*!< Trap on Divide by 0 */ -#define SCB_CCR_BFHFNMIGN ((uint16_t)0x0100) /*!< Handlers running at priority -1 and -2 */ -#define SCB_CCR_STKALIGN ((uint16_t)0x0200) /*!< On exception entry, the SP used prior to the exception is adjusted to be 8-byte aligned */ - -/******************* Bit definition for SCB_SHPR register ********************/ -#define SCB_SHPR_PRI_N ((uint32_t)0x000000FF) /*!< Priority of system handler 4,8, and 12. Mem Manage, reserved and Debug Monitor */ -#define SCB_SHPR_PRI_N1 ((uint32_t)0x0000FF00) /*!< Priority of system handler 5,9, and 13. Bus Fault, reserved and reserved */ -#define SCB_SHPR_PRI_N2 ((uint32_t)0x00FF0000) /*!< Priority of system handler 6,10, and 14. Usage Fault, reserved and PendSV */ -#define SCB_SHPR_PRI_N3 ((uint32_t)0xFF000000) /*!< Priority of system handler 7,11, and 15. Reserved, SVCall and SysTick */ - -/****************** Bit definition for SCB_SHCSR register *******************/ -#define SCB_SHCSR_MEMFAULTACT ((uint32_t)0x00000001) /*!< MemManage is active */ -#define SCB_SHCSR_BUSFAULTACT ((uint32_t)0x00000002) /*!< BusFault is active */ -#define SCB_SHCSR_USGFAULTACT ((uint32_t)0x00000008) /*!< UsageFault is active */ -#define SCB_SHCSR_SVCALLACT ((uint32_t)0x00000080) /*!< SVCall is active */ -#define SCB_SHCSR_MONITORACT ((uint32_t)0x00000100) /*!< Monitor is active */ -#define SCB_SHCSR_PENDSVACT ((uint32_t)0x00000400) /*!< PendSV is active */ -#define SCB_SHCSR_SYSTICKACT ((uint32_t)0x00000800) /*!< SysTick is active */ -#define SCB_SHCSR_USGFAULTPENDED ((uint32_t)0x00001000) /*!< Usage Fault is pended */ -#define SCB_SHCSR_MEMFAULTPENDED ((uint32_t)0x00002000) /*!< MemManage is pended */ -#define SCB_SHCSR_BUSFAULTPENDED ((uint32_t)0x00004000) /*!< Bus Fault is pended */ -#define SCB_SHCSR_SVCALLPENDED ((uint32_t)0x00008000) /*!< SVCall is pended */ -#define SCB_SHCSR_MEMFAULTENA ((uint32_t)0x00010000) /*!< MemManage enable */ -#define SCB_SHCSR_BUSFAULTENA ((uint32_t)0x00020000) /*!< Bus Fault enable */ -#define SCB_SHCSR_USGFAULTENA ((uint32_t)0x00040000) /*!< UsageFault enable */ - -/******************* Bit definition for SCB_CFSR register *******************/ -/*!< MFSR */ -#define SCB_CFSR_IACCVIOL ((uint32_t)0x00000001) /*!< Instruction access violation */ -#define SCB_CFSR_DACCVIOL ((uint32_t)0x00000002) /*!< Data access violation */ -#define SCB_CFSR_MUNSTKERR ((uint32_t)0x00000008) /*!< Unstacking error */ -#define SCB_CFSR_MSTKERR ((uint32_t)0x00000010) /*!< Stacking error */ -#define SCB_CFSR_MMARVALID ((uint32_t)0x00000080) /*!< Memory Manage Address Register address valid flag */ -/*!< BFSR */ -#define SCB_CFSR_IBUSERR ((uint32_t)0x00000100) /*!< Instruction bus error flag */ -#define SCB_CFSR_PRECISERR ((uint32_t)0x00000200) /*!< Precise data bus error */ -#define SCB_CFSR_IMPRECISERR ((uint32_t)0x00000400) /*!< Imprecise data bus error */ -#define SCB_CFSR_UNSTKERR ((uint32_t)0x00000800) /*!< Unstacking error */ -#define SCB_CFSR_STKERR ((uint32_t)0x00001000) /*!< Stacking error */ -#define SCB_CFSR_BFARVALID ((uint32_t)0x00008000) /*!< Bus Fault Address Register address valid flag */ -/*!< UFSR */ -#define SCB_CFSR_UNDEFINSTR ((uint32_t)0x00010000) /*!< The processor attempt to excecute an undefined instruction */ -#define SCB_CFSR_INVSTATE ((uint32_t)0x00020000) /*!< Invalid combination of EPSR and instruction */ -#define SCB_CFSR_INVPC ((uint32_t)0x00040000) /*!< Attempt to load EXC_RETURN into pc illegally */ -#define SCB_CFSR_NOCP ((uint32_t)0x00080000) /*!< Attempt to use a coprocessor instruction */ -#define SCB_CFSR_UNALIGNED ((uint32_t)0x01000000) /*!< Fault occurs when there is an attempt to make an unaligned memory access */ -#define SCB_CFSR_DIVBYZERO ((uint32_t)0x02000000) /*!< Fault occurs when SDIV or DIV instruction is used with a divisor of 0 */ - -/******************* Bit definition for SCB_HFSR register *******************/ -#define SCB_HFSR_VECTTBL ((uint32_t)0x00000002) /*!< Fault occures because of vector table read on exception processing */ -#define SCB_HFSR_FORCED ((uint32_t)0x40000000) /*!< Hard Fault activated when a configurable Fault was received and cannot activate */ -#define SCB_HFSR_DEBUGEVT ((uint32_t)0x80000000) /*!< Fault related to debug */ - -/******************* Bit definition for SCB_DFSR register *******************/ -#define SCB_DFSR_HALTED ((uint8_t)0x01) /*!< Halt request flag */ -#define SCB_DFSR_BKPT ((uint8_t)0x02) /*!< BKPT flag */ -#define SCB_DFSR_DWTTRAP ((uint8_t)0x04) /*!< Data Watchpoint and Trace (DWT) flag */ -#define SCB_DFSR_VCATCH ((uint8_t)0x08) /*!< Vector catch flag */ -#define SCB_DFSR_EXTERNAL ((uint8_t)0x10) /*!< External debug request flag */ - -/******************* Bit definition for SCB_MMFAR register ******************/ -#define SCB_MMFAR_ADDRESS ((uint32_t)0xFFFFFFFF) /*!< Mem Manage fault address field */ - -/******************* Bit definition for SCB_BFAR register *******************/ -#define SCB_BFAR_ADDRESS ((uint32_t)0xFFFFFFFF) /*!< Bus fault address field */ - -/******************* Bit definition for SCB_afsr register *******************/ -#define SCB_AFSR_IMPDEF ((uint32_t)0xFFFFFFFF) /*!< Implementation defined */ - -/******************************************************************************/ -/* */ -/* External Interrupt/Event Controller */ -/* */ -/******************************************************************************/ - -/******************* Bit definition for EXTI_IMR register *******************/ -#define EXTI_IMR_MR0 ((uint32_t)0x00000001) /*!< Interrupt Mask on line 0 */ -#define EXTI_IMR_MR1 ((uint32_t)0x00000002) /*!< Interrupt Mask on line 1 */ -#define EXTI_IMR_MR2 ((uint32_t)0x00000004) /*!< Interrupt Mask on line 2 */ -#define EXTI_IMR_MR3 ((uint32_t)0x00000008) /*!< Interrupt Mask on line 3 */ -#define EXTI_IMR_MR4 ((uint32_t)0x00000010) /*!< Interrupt Mask on line 4 */ -#define EXTI_IMR_MR5 ((uint32_t)0x00000020) /*!< Interrupt Mask on line 5 */ -#define EXTI_IMR_MR6 ((uint32_t)0x00000040) /*!< Interrupt Mask on line 6 */ -#define EXTI_IMR_MR7 ((uint32_t)0x00000080) /*!< Interrupt Mask on line 7 */ -#define EXTI_IMR_MR8 ((uint32_t)0x00000100) /*!< Interrupt Mask on line 8 */ -#define EXTI_IMR_MR9 ((uint32_t)0x00000200) /*!< Interrupt Mask on line 9 */ -#define EXTI_IMR_MR10 ((uint32_t)0x00000400) /*!< Interrupt Mask on line 10 */ -#define EXTI_IMR_MR11 ((uint32_t)0x00000800) /*!< Interrupt Mask on line 11 */ -#define EXTI_IMR_MR12 ((uint32_t)0x00001000) /*!< Interrupt Mask on line 12 */ -#define EXTI_IMR_MR13 ((uint32_t)0x00002000) /*!< Interrupt Mask on line 13 */ -#define EXTI_IMR_MR14 ((uint32_t)0x00004000) /*!< Interrupt Mask on line 14 */ -#define EXTI_IMR_MR15 ((uint32_t)0x00008000) /*!< Interrupt Mask on line 15 */ -#define EXTI_IMR_MR16 ((uint32_t)0x00010000) /*!< Interrupt Mask on line 16 */ -#define EXTI_IMR_MR17 ((uint32_t)0x00020000) /*!< Interrupt Mask on line 17 */ -#define EXTI_IMR_MR18 ((uint32_t)0x00040000) /*!< Interrupt Mask on line 18 */ -#define EXTI_IMR_MR19 ((uint32_t)0x00080000) /*!< Interrupt Mask on line 19 */ - -/******************* Bit definition for EXTI_EMR register *******************/ -#define EXTI_EMR_MR0 ((uint32_t)0x00000001) /*!< Event Mask on line 0 */ -#define EXTI_EMR_MR1 ((uint32_t)0x00000002) /*!< Event Mask on line 1 */ -#define EXTI_EMR_MR2 ((uint32_t)0x00000004) /*!< Event Mask on line 2 */ -#define EXTI_EMR_MR3 ((uint32_t)0x00000008) /*!< Event Mask on line 3 */ -#define EXTI_EMR_MR4 ((uint32_t)0x00000010) /*!< Event Mask on line 4 */ -#define EXTI_EMR_MR5 ((uint32_t)0x00000020) /*!< Event Mask on line 5 */ -#define EXTI_EMR_MR6 ((uint32_t)0x00000040) /*!< Event Mask on line 6 */ -#define EXTI_EMR_MR7 ((uint32_t)0x00000080) /*!< Event Mask on line 7 */ -#define EXTI_EMR_MR8 ((uint32_t)0x00000100) /*!< Event Mask on line 8 */ -#define EXTI_EMR_MR9 ((uint32_t)0x00000200) /*!< Event Mask on line 9 */ -#define EXTI_EMR_MR10 ((uint32_t)0x00000400) /*!< Event Mask on line 10 */ -#define EXTI_EMR_MR11 ((uint32_t)0x00000800) /*!< Event Mask on line 11 */ -#define EXTI_EMR_MR12 ((uint32_t)0x00001000) /*!< Event Mask on line 12 */ -#define EXTI_EMR_MR13 ((uint32_t)0x00002000) /*!< Event Mask on line 13 */ -#define EXTI_EMR_MR14 ((uint32_t)0x00004000) /*!< Event Mask on line 14 */ -#define EXTI_EMR_MR15 ((uint32_t)0x00008000) /*!< Event Mask on line 15 */ -#define EXTI_EMR_MR16 ((uint32_t)0x00010000) /*!< Event Mask on line 16 */ -#define EXTI_EMR_MR17 ((uint32_t)0x00020000) /*!< Event Mask on line 17 */ -#define EXTI_EMR_MR18 ((uint32_t)0x00040000) /*!< Event Mask on line 18 */ -#define EXTI_EMR_MR19 ((uint32_t)0x00080000) /*!< Event Mask on line 19 */ - -/****************** Bit definition for EXTI_RTSR register *******************/ -#define EXTI_RTSR_TR0 ((uint32_t)0x00000001) /*!< Rising trigger event configuration bit of line 0 */ -#define EXTI_RTSR_TR1 ((uint32_t)0x00000002) /*!< Rising trigger event configuration bit of line 1 */ -#define EXTI_RTSR_TR2 ((uint32_t)0x00000004) /*!< Rising trigger event configuration bit of line 2 */ -#define EXTI_RTSR_TR3 ((uint32_t)0x00000008) /*!< Rising trigger event configuration bit of line 3 */ -#define EXTI_RTSR_TR4 ((uint32_t)0x00000010) /*!< Rising trigger event configuration bit of line 4 */ -#define EXTI_RTSR_TR5 ((uint32_t)0x00000020) /*!< Rising trigger event configuration bit of line 5 */ -#define EXTI_RTSR_TR6 ((uint32_t)0x00000040) /*!< Rising trigger event configuration bit of line 6 */ -#define EXTI_RTSR_TR7 ((uint32_t)0x00000080) /*!< Rising trigger event configuration bit of line 7 */ -#define EXTI_RTSR_TR8 ((uint32_t)0x00000100) /*!< Rising trigger event configuration bit of line 8 */ -#define EXTI_RTSR_TR9 ((uint32_t)0x00000200) /*!< Rising trigger event configuration bit of line 9 */ -#define EXTI_RTSR_TR10 ((uint32_t)0x00000400) /*!< Rising trigger event configuration bit of line 10 */ -#define EXTI_RTSR_TR11 ((uint32_t)0x00000800) /*!< Rising trigger event configuration bit of line 11 */ -#define EXTI_RTSR_TR12 ((uint32_t)0x00001000) /*!< Rising trigger event configuration bit of line 12 */ -#define EXTI_RTSR_TR13 ((uint32_t)0x00002000) /*!< Rising trigger event configuration bit of line 13 */ -#define EXTI_RTSR_TR14 ((uint32_t)0x00004000) /*!< Rising trigger event configuration bit of line 14 */ -#define EXTI_RTSR_TR15 ((uint32_t)0x00008000) /*!< Rising trigger event configuration bit of line 15 */ -#define EXTI_RTSR_TR16 ((uint32_t)0x00010000) /*!< Rising trigger event configuration bit of line 16 */ -#define EXTI_RTSR_TR17 ((uint32_t)0x00020000) /*!< Rising trigger event configuration bit of line 17 */ -#define EXTI_RTSR_TR18 ((uint32_t)0x00040000) /*!< Rising trigger event configuration bit of line 18 */ -#define EXTI_RTSR_TR19 ((uint32_t)0x00080000) /*!< Rising trigger event configuration bit of line 19 */ - -/****************** Bit definition for EXTI_FTSR register *******************/ -#define EXTI_FTSR_TR0 ((uint32_t)0x00000001) /*!< Falling trigger event configuration bit of line 0 */ -#define EXTI_FTSR_TR1 ((uint32_t)0x00000002) /*!< Falling trigger event configuration bit of line 1 */ -#define EXTI_FTSR_TR2 ((uint32_t)0x00000004) /*!< Falling trigger event configuration bit of line 2 */ -#define EXTI_FTSR_TR3 ((uint32_t)0x00000008) /*!< Falling trigger event configuration bit of line 3 */ -#define EXTI_FTSR_TR4 ((uint32_t)0x00000010) /*!< Falling trigger event configuration bit of line 4 */ -#define EXTI_FTSR_TR5 ((uint32_t)0x00000020) /*!< Falling trigger event configuration bit of line 5 */ -#define EXTI_FTSR_TR6 ((uint32_t)0x00000040) /*!< Falling trigger event configuration bit of line 6 */ -#define EXTI_FTSR_TR7 ((uint32_t)0x00000080) /*!< Falling trigger event configuration bit of line 7 */ -#define EXTI_FTSR_TR8 ((uint32_t)0x00000100) /*!< Falling trigger event configuration bit of line 8 */ -#define EXTI_FTSR_TR9 ((uint32_t)0x00000200) /*!< Falling trigger event configuration bit of line 9 */ -#define EXTI_FTSR_TR10 ((uint32_t)0x00000400) /*!< Falling trigger event configuration bit of line 10 */ -#define EXTI_FTSR_TR11 ((uint32_t)0x00000800) /*!< Falling trigger event configuration bit of line 11 */ -#define EXTI_FTSR_TR12 ((uint32_t)0x00001000) /*!< Falling trigger event configuration bit of line 12 */ -#define EXTI_FTSR_TR13 ((uint32_t)0x00002000) /*!< Falling trigger event configuration bit of line 13 */ -#define EXTI_FTSR_TR14 ((uint32_t)0x00004000) /*!< Falling trigger event configuration bit of line 14 */ -#define EXTI_FTSR_TR15 ((uint32_t)0x00008000) /*!< Falling trigger event configuration bit of line 15 */ -#define EXTI_FTSR_TR16 ((uint32_t)0x00010000) /*!< Falling trigger event configuration bit of line 16 */ -#define EXTI_FTSR_TR17 ((uint32_t)0x00020000) /*!< Falling trigger event configuration bit of line 17 */ -#define EXTI_FTSR_TR18 ((uint32_t)0x00040000) /*!< Falling trigger event configuration bit of line 18 */ -#define EXTI_FTSR_TR19 ((uint32_t)0x00080000) /*!< Falling trigger event configuration bit of line 19 */ - -/****************** Bit definition for EXTI_SWIER register ******************/ -#define EXTI_SWIER_SWIER0 ((uint32_t)0x00000001) /*!< Software Interrupt on line 0 */ -#define EXTI_SWIER_SWIER1 ((uint32_t)0x00000002) /*!< Software Interrupt on line 1 */ -#define EXTI_SWIER_SWIER2 ((uint32_t)0x00000004) /*!< Software Interrupt on line 2 */ -#define EXTI_SWIER_SWIER3 ((uint32_t)0x00000008) /*!< Software Interrupt on line 3 */ -#define EXTI_SWIER_SWIER4 ((uint32_t)0x00000010) /*!< Software Interrupt on line 4 */ -#define EXTI_SWIER_SWIER5 ((uint32_t)0x00000020) /*!< Software Interrupt on line 5 */ -#define EXTI_SWIER_SWIER6 ((uint32_t)0x00000040) /*!< Software Interrupt on line 6 */ -#define EXTI_SWIER_SWIER7 ((uint32_t)0x00000080) /*!< Software Interrupt on line 7 */ -#define EXTI_SWIER_SWIER8 ((uint32_t)0x00000100) /*!< Software Interrupt on line 8 */ -#define EXTI_SWIER_SWIER9 ((uint32_t)0x00000200) /*!< Software Interrupt on line 9 */ -#define EXTI_SWIER_SWIER10 ((uint32_t)0x00000400) /*!< Software Interrupt on line 10 */ -#define EXTI_SWIER_SWIER11 ((uint32_t)0x00000800) /*!< Software Interrupt on line 11 */ -#define EXTI_SWIER_SWIER12 ((uint32_t)0x00001000) /*!< Software Interrupt on line 12 */ -#define EXTI_SWIER_SWIER13 ((uint32_t)0x00002000) /*!< Software Interrupt on line 13 */ -#define EXTI_SWIER_SWIER14 ((uint32_t)0x00004000) /*!< Software Interrupt on line 14 */ -#define EXTI_SWIER_SWIER15 ((uint32_t)0x00008000) /*!< Software Interrupt on line 15 */ -#define EXTI_SWIER_SWIER16 ((uint32_t)0x00010000) /*!< Software Interrupt on line 16 */ -#define EXTI_SWIER_SWIER17 ((uint32_t)0x00020000) /*!< Software Interrupt on line 17 */ -#define EXTI_SWIER_SWIER18 ((uint32_t)0x00040000) /*!< Software Interrupt on line 18 */ -#define EXTI_SWIER_SWIER19 ((uint32_t)0x00080000) /*!< Software Interrupt on line 19 */ - -/******************* Bit definition for EXTI_PR register ********************/ -#define EXTI_PR_PR0 ((uint32_t)0x00000001) /*!< Pending bit for line 0 */ -#define EXTI_PR_PR1 ((uint32_t)0x00000002) /*!< Pending bit for line 1 */ -#define EXTI_PR_PR2 ((uint32_t)0x00000004) /*!< Pending bit for line 2 */ -#define EXTI_PR_PR3 ((uint32_t)0x00000008) /*!< Pending bit for line 3 */ -#define EXTI_PR_PR4 ((uint32_t)0x00000010) /*!< Pending bit for line 4 */ -#define EXTI_PR_PR5 ((uint32_t)0x00000020) /*!< Pending bit for line 5 */ -#define EXTI_PR_PR6 ((uint32_t)0x00000040) /*!< Pending bit for line 6 */ -#define EXTI_PR_PR7 ((uint32_t)0x00000080) /*!< Pending bit for line 7 */ -#define EXTI_PR_PR8 ((uint32_t)0x00000100) /*!< Pending bit for line 8 */ -#define EXTI_PR_PR9 ((uint32_t)0x00000200) /*!< Pending bit for line 9 */ -#define EXTI_PR_PR10 ((uint32_t)0x00000400) /*!< Pending bit for line 10 */ -#define EXTI_PR_PR11 ((uint32_t)0x00000800) /*!< Pending bit for line 11 */ -#define EXTI_PR_PR12 ((uint32_t)0x00001000) /*!< Pending bit for line 12 */ -#define EXTI_PR_PR13 ((uint32_t)0x00002000) /*!< Pending bit for line 13 */ -#define EXTI_PR_PR14 ((uint32_t)0x00004000) /*!< Pending bit for line 14 */ -#define EXTI_PR_PR15 ((uint32_t)0x00008000) /*!< Pending bit for line 15 */ -#define EXTI_PR_PR16 ((uint32_t)0x00010000) /*!< Pending bit for line 16 */ -#define EXTI_PR_PR17 ((uint32_t)0x00020000) /*!< Pending bit for line 17 */ -#define EXTI_PR_PR18 ((uint32_t)0x00040000) /*!< Pending bit for line 18 */ -#define EXTI_PR_PR19 ((uint32_t)0x00080000) /*!< Pending bit for line 19 */ - -/******************************************************************************/ -/* */ -/* DMA Controller */ -/* */ -/******************************************************************************/ - -/******************* Bit definition for DMA_ISR register ********************/ -#define DMA_ISR_GIF1 ((uint32_t)0x00000001) /*!< Channel 1 Global interrupt flag */ -#define DMA_ISR_TCIF1 ((uint32_t)0x00000002) /*!< Channel 1 Transfer Complete flag */ -#define DMA_ISR_HTIF1 ((uint32_t)0x00000004) /*!< Channel 1 Half Transfer flag */ -#define DMA_ISR_TEIF1 ((uint32_t)0x00000008) /*!< Channel 1 Transfer Error flag */ -#define DMA_ISR_GIF2 ((uint32_t)0x00000010) /*!< Channel 2 Global interrupt flag */ -#define DMA_ISR_TCIF2 ((uint32_t)0x00000020) /*!< Channel 2 Transfer Complete flag */ -#define DMA_ISR_HTIF2 ((uint32_t)0x00000040) /*!< Channel 2 Half Transfer flag */ -#define DMA_ISR_TEIF2 ((uint32_t)0x00000080) /*!< Channel 2 Transfer Error flag */ -#define DMA_ISR_GIF3 ((uint32_t)0x00000100) /*!< Channel 3 Global interrupt flag */ -#define DMA_ISR_TCIF3 ((uint32_t)0x00000200) /*!< Channel 3 Transfer Complete flag */ -#define DMA_ISR_HTIF3 ((uint32_t)0x00000400) /*!< Channel 3 Half Transfer flag */ -#define DMA_ISR_TEIF3 ((uint32_t)0x00000800) /*!< Channel 3 Transfer Error flag */ -#define DMA_ISR_GIF4 ((uint32_t)0x00001000) /*!< Channel 4 Global interrupt flag */ -#define DMA_ISR_TCIF4 ((uint32_t)0x00002000) /*!< Channel 4 Transfer Complete flag */ -#define DMA_ISR_HTIF4 ((uint32_t)0x00004000) /*!< Channel 4 Half Transfer flag */ -#define DMA_ISR_TEIF4 ((uint32_t)0x00008000) /*!< Channel 4 Transfer Error flag */ -#define DMA_ISR_GIF5 ((uint32_t)0x00010000) /*!< Channel 5 Global interrupt flag */ -#define DMA_ISR_TCIF5 ((uint32_t)0x00020000) /*!< Channel 5 Transfer Complete flag */ -#define DMA_ISR_HTIF5 ((uint32_t)0x00040000) /*!< Channel 5 Half Transfer flag */ -#define DMA_ISR_TEIF5 ((uint32_t)0x00080000) /*!< Channel 5 Transfer Error flag */ -#define DMA_ISR_GIF6 ((uint32_t)0x00100000) /*!< Channel 6 Global interrupt flag */ -#define DMA_ISR_TCIF6 ((uint32_t)0x00200000) /*!< Channel 6 Transfer Complete flag */ -#define DMA_ISR_HTIF6 ((uint32_t)0x00400000) /*!< Channel 6 Half Transfer flag */ -#define DMA_ISR_TEIF6 ((uint32_t)0x00800000) /*!< Channel 6 Transfer Error flag */ -#define DMA_ISR_GIF7 ((uint32_t)0x01000000) /*!< Channel 7 Global interrupt flag */ -#define DMA_ISR_TCIF7 ((uint32_t)0x02000000) /*!< Channel 7 Transfer Complete flag */ -#define DMA_ISR_HTIF7 ((uint32_t)0x04000000) /*!< Channel 7 Half Transfer flag */ -#define DMA_ISR_TEIF7 ((uint32_t)0x08000000) /*!< Channel 7 Transfer Error flag */ - -/******************* Bit definition for DMA_IFCR register *******************/ -#define DMA_IFCR_CGIF1 ((uint32_t)0x00000001) /*!< Channel 1 Global interrupt clearr */ -#define DMA_IFCR_CTCIF1 ((uint32_t)0x00000002) /*!< Channel 1 Transfer Complete clear */ -#define DMA_IFCR_CHTIF1 ((uint32_t)0x00000004) /*!< Channel 1 Half Transfer clear */ -#define DMA_IFCR_CTEIF1 ((uint32_t)0x00000008) /*!< Channel 1 Transfer Error clear */ -#define DMA_IFCR_CGIF2 ((uint32_t)0x00000010) /*!< Channel 2 Global interrupt clear */ -#define DMA_IFCR_CTCIF2 ((uint32_t)0x00000020) /*!< Channel 2 Transfer Complete clear */ -#define DMA_IFCR_CHTIF2 ((uint32_t)0x00000040) /*!< Channel 2 Half Transfer clear */ -#define DMA_IFCR_CTEIF2 ((uint32_t)0x00000080) /*!< Channel 2 Transfer Error clear */ -#define DMA_IFCR_CGIF3 ((uint32_t)0x00000100) /*!< Channel 3 Global interrupt clear */ -#define DMA_IFCR_CTCIF3 ((uint32_t)0x00000200) /*!< Channel 3 Transfer Complete clear */ -#define DMA_IFCR_CHTIF3 ((uint32_t)0x00000400) /*!< Channel 3 Half Transfer clear */ -#define DMA_IFCR_CTEIF3 ((uint32_t)0x00000800) /*!< Channel 3 Transfer Error clear */ -#define DMA_IFCR_CGIF4 ((uint32_t)0x00001000) /*!< Channel 4 Global interrupt clear */ -#define DMA_IFCR_CTCIF4 ((uint32_t)0x00002000) /*!< Channel 4 Transfer Complete clear */ -#define DMA_IFCR_CHTIF4 ((uint32_t)0x00004000) /*!< Channel 4 Half Transfer clear */ -#define DMA_IFCR_CTEIF4 ((uint32_t)0x00008000) /*!< Channel 4 Transfer Error clear */ -#define DMA_IFCR_CGIF5 ((uint32_t)0x00010000) /*!< Channel 5 Global interrupt clear */ -#define DMA_IFCR_CTCIF5 ((uint32_t)0x00020000) /*!< Channel 5 Transfer Complete clear */ -#define DMA_IFCR_CHTIF5 ((uint32_t)0x00040000) /*!< Channel 5 Half Transfer clear */ -#define DMA_IFCR_CTEIF5 ((uint32_t)0x00080000) /*!< Channel 5 Transfer Error clear */ -#define DMA_IFCR_CGIF6 ((uint32_t)0x00100000) /*!< Channel 6 Global interrupt clear */ -#define DMA_IFCR_CTCIF6 ((uint32_t)0x00200000) /*!< Channel 6 Transfer Complete clear */ -#define DMA_IFCR_CHTIF6 ((uint32_t)0x00400000) /*!< Channel 6 Half Transfer clear */ -#define DMA_IFCR_CTEIF6 ((uint32_t)0x00800000) /*!< Channel 6 Transfer Error clear */ -#define DMA_IFCR_CGIF7 ((uint32_t)0x01000000) /*!< Channel 7 Global interrupt clear */ -#define DMA_IFCR_CTCIF7 ((uint32_t)0x02000000) /*!< Channel 7 Transfer Complete clear */ -#define DMA_IFCR_CHTIF7 ((uint32_t)0x04000000) /*!< Channel 7 Half Transfer clear */ -#define DMA_IFCR_CTEIF7 ((uint32_t)0x08000000) /*!< Channel 7 Transfer Error clear */ - -/******************* Bit definition for DMA_CCR1 register *******************/ -#define DMA_CCR1_EN ((uint16_t)0x0001) /*!< Channel enable*/ -#define DMA_CCR1_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ -#define DMA_CCR1_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ -#define DMA_CCR1_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ -#define DMA_CCR1_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ -#define DMA_CCR1_CIRC ((uint16_t)0x0020) /*!< Circular mode */ -#define DMA_CCR1_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ -#define DMA_CCR1_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ - -#define DMA_CCR1_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ -#define DMA_CCR1_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ -#define DMA_CCR1_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ - -#define DMA_CCR1_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ -#define DMA_CCR1_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ -#define DMA_CCR1_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ - -#define DMA_CCR1_PL ((uint16_t)0x3000) /*!< PL[1:0] bits(Channel Priority level) */ -#define DMA_CCR1_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ -#define DMA_CCR1_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ - -#define DMA_CCR1_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ - -/******************* Bit definition for DMA_CCR2 register *******************/ -#define DMA_CCR2_EN ((uint16_t)0x0001) /*!< Channel enable */ -#define DMA_CCR2_TCIE ((uint16_t)0x0002) /*!< ransfer complete interrupt enable */ -#define DMA_CCR2_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ -#define DMA_CCR2_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ -#define DMA_CCR2_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ -#define DMA_CCR2_CIRC ((uint16_t)0x0020) /*!< Circular mode */ -#define DMA_CCR2_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ -#define DMA_CCR2_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ - -#define DMA_CCR2_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ -#define DMA_CCR2_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ -#define DMA_CCR2_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ - -#define DMA_CCR2_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ -#define DMA_CCR2_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ -#define DMA_CCR2_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ - -#define DMA_CCR2_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ -#define DMA_CCR2_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ -#define DMA_CCR2_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ - -#define DMA_CCR2_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ - -/******************* Bit definition for DMA_CCR3 register *******************/ -#define DMA_CCR3_EN ((uint16_t)0x0001) /*!< Channel enable */ -#define DMA_CCR3_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ -#define DMA_CCR3_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ -#define DMA_CCR3_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ -#define DMA_CCR3_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ -#define DMA_CCR3_CIRC ((uint16_t)0x0020) /*!< Circular mode */ -#define DMA_CCR3_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ -#define DMA_CCR3_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ - -#define DMA_CCR3_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ -#define DMA_CCR3_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ -#define DMA_CCR3_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ - -#define DMA_CCR3_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ -#define DMA_CCR3_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ -#define DMA_CCR3_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ - -#define DMA_CCR3_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ -#define DMA_CCR3_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ -#define DMA_CCR3_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ - -#define DMA_CCR3_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ - -/*!<****************** Bit definition for DMA_CCR4 register *******************/ -#define DMA_CCR4_EN ((uint16_t)0x0001) /*!
© COPYRIGHT 2010 STMicroelectronics
+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f10x + * @{ + */ + +#ifndef __STM32F10x_H +#define __STM32F10x_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup Library_configuration_section + * @{ + */ + +/* Uncomment the line below according to the target STM32 device used in your + application + */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_XL) && !defined (STM32F10X_CL) + /* #define STM32F10X_LD */ /*!< STM32F10X_LD: STM32 Low density devices */ + /* #define STM32F10X_LD_VL */ /*!< STM32F10X_LD_VL: STM32 Low density Value Line devices */ + /* #define STM32F10X_MD */ /*!< STM32F10X_MD: STM32 Medium density devices */ + /* #define STM32F10X_MD_VL */ /*!< STM32F10X_MD_VL: STM32 Medium density Value Line devices */ + /* #define STM32F10X_HD */ /*!< STM32F10X_HD: STM32 High density devices */ + /* #define STM32F10X_HD_VL */ /*!< STM32F10X_HD_VL: STM32 High density value line devices */ + /* #define STM32F10X_XL */ /*!< STM32F10X_XL: STM32 XL-density devices */ + /* #define STM32F10X_CL */ /*!< STM32F10X_CL: STM32 Connectivity line devices */ +#endif +/* Tip: To avoid modifying this file each time you need to switch between these + devices, you can define the device in your toolchain compiler preprocessor. + + - Low-density devices are STM32F101xx, STM32F102xx and STM32F103xx microcontrollers + where the Flash memory density ranges between 16 and 32 Kbytes. + - Low-density value line devices are STM32F100xx microcontrollers where the Flash + memory density ranges between 16 and 32 Kbytes. + - Medium-density devices are STM32F101xx, STM32F102xx and STM32F103xx microcontrollers + where the Flash memory density ranges between 64 and 128 Kbytes. + - Medium-density value line devices are STM32F100xx microcontrollers where the + Flash memory density ranges between 64 and 128 Kbytes. + - High-density devices are STM32F101xx and STM32F103xx microcontrollers where + the Flash memory density ranges between 256 and 512 Kbytes. + - High-density value line devices are STM32F100xx microcontrollers where the + Flash memory density ranges between 256 and 512 Kbytes. + - XL-density devices are STM32F101xx and STM32F103xx microcontrollers where + the Flash memory density ranges between 512 and 1024 Kbytes. + - Connectivity line devices are STM32F105xx and STM32F107xx microcontrollers. + */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_XL) && !defined (STM32F10X_CL) + #error "Please select first the target STM32F10x device used in your application (in stm32f10x.h file)" +#endif + +#if !defined USE_STDPERIPH_DRIVER +/** + * @brief Comment the line below if you will not use the peripherals drivers. + In this case, these drivers will not be included and the application code will + be based on direct access to peripherals registers + */ + /*#define USE_STDPERIPH_DRIVER*/ +#endif + +/** + * @brief In the following line adjust the value of External High Speed oscillator (HSE) + used in your application + + Tip: To avoid modifying this file each time you need to use different HSE, you + can define the HSE value in your toolchain compiler preprocessor. + */ +#if !defined HSE_VALUE + #ifdef STM32F10X_CL + #define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ + #else + #define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */ + #endif /* STM32F10X_CL */ +#endif /* HSE_VALUE */ + + +/** + * @brief In the following line adjust the External High Speed oscillator (HSE) Startup + Timeout value + */ +#define HSE_STARTUP_TIMEOUT ((uint16_t)0x0500) /*!< Time out for HSE start up */ + +#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/ + +/** + * @brief STM32F10x Standard Peripheral Library version number + */ +#define __STM32F10X_STDPERIPH_VERSION_MAIN (0x03) /*!< [31:16] STM32F10x Standard Peripheral Library main version */ +#define __STM32F10X_STDPERIPH_VERSION_SUB1 (0x04) /*!< [15:8] STM32F10x Standard Peripheral Library sub1 version */ +#define __STM32F10X_STDPERIPH_VERSION_SUB2 (0x00) /*!< [7:0] STM32F10x Standard Peripheral Library sub2 version */ +#define __STM32F10X_STDPERIPH_VERSION ((__STM32F10X_STDPERIPH_VERSION_MAIN << 16)\ + | (__STM32F10X_STDPERIPH_VERSION_SUB1 << 8)\ + | __STM32F10X_STDPERIPH_VERSION_SUB2) + +/** + * @} + */ + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ + +/** + * @brief Configuration of the Cortex-M3 Processor and Core Peripherals + */ +#ifdef STM32F10X_XL + #define __MPU_PRESENT 1 /*!< STM32 XL-density devices provide an MPU */ +#else + #define __MPU_PRESENT 0 /*!< Other STM32 devices does not provide an MPU */ +#endif /* STM32F10X_XL */ +#define __NVIC_PRIO_BITS 4 /*!< STM32 uses 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ + +/** + * @brief STM32F10x Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ +typedef enum IRQn +{ +/****** Cortex-M3 Processor Exceptions Numbers ***************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */ + +/****** STM32 specific Interrupt Numbers *********************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ + TAMPER_IRQn = 2, /*!< Tamper Interrupt */ + RTC_IRQn = 3, /*!< RTC global Interrupt */ + FLASH_IRQn = 4, /*!< FLASH global Interrupt */ + RCC_IRQn = 5, /*!< RCC global Interrupt */ + EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ + EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ + EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ + EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ + EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ + DMA1_Channel1_IRQn = 11, /*!< DMA1 Channel 1 global Interrupt */ + DMA1_Channel2_IRQn = 12, /*!< DMA1 Channel 2 global Interrupt */ + DMA1_Channel3_IRQn = 13, /*!< DMA1 Channel 3 global Interrupt */ + DMA1_Channel4_IRQn = 14, /*!< DMA1 Channel 4 global Interrupt */ + DMA1_Channel5_IRQn = 15, /*!< DMA1 Channel 5 global Interrupt */ + DMA1_Channel6_IRQn = 16, /*!< DMA1 Channel 6 global Interrupt */ + DMA1_Channel7_IRQn = 17, /*!< DMA1 Channel 7 global Interrupt */ + +#ifdef STM32F10X_LD + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42 /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ +#endif /* STM32F10X_LD */ + +#ifdef STM32F10X_LD_VL + ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ + TIM7_IRQn = 55 /*!< TIM7 Interrupt */ +#endif /* STM32F10X_LD_VL */ + +#ifdef STM32F10X_MD + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42 /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ +#endif /* STM32F10X_MD */ + +#ifdef STM32F10X_MD_VL + ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ + TIM7_IRQn = 55 /*!< TIM7 Interrupt */ +#endif /* STM32F10X_MD_VL */ + +#ifdef STM32F10X_HD + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42, /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ + TIM8_BRK_IRQn = 43, /*!< TIM8 Break Interrupt */ + TIM8_UP_IRQn = 44, /*!< TIM8 Update Interrupt */ + TIM8_TRG_COM_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + ADC3_IRQn = 47, /*!< ADC3 global Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_5_IRQn = 59 /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ +#endif /* STM32F10X_HD */ + +#ifdef STM32F10X_HD_VL + ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ + TIM12_IRQn = 43, /*!< TIM12 global Interrupt */ + TIM13_IRQn = 44, /*!< TIM13 global Interrupt */ + TIM14_IRQn = 45, /*!< TIM14 global Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_5_IRQn = 59, /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ + DMA2_Channel5_IRQn = 60 /*!< DMA2 Channel 5 global Interrupt (DMA2 Channel 5 is + mapped at postion 60 only if the MISC_REMAP bit in + the AFIO_MAPR2 register is set) */ +#endif /* STM32F10X_HD_VL */ + +#ifdef STM32F10X_XL + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break Interrupt and TIM9 global Interrupt */ + TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global Interrupt */ + TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42, /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ + TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global Interrupt */ + TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global Interrupt */ + TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + ADC3_IRQn = 47, /*!< ADC3 global Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_5_IRQn = 59 /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ +#endif /* STM32F10X_XL */ + +#ifdef STM32F10X_CL + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS WakeUp from suspend through EXTI Line Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_IRQn = 59, /*!< DMA2 Channel 4 global Interrupt */ + DMA2_Channel5_IRQn = 60, /*!< DMA2 Channel 5 global Interrupt */ + ETH_IRQn = 61, /*!< Ethernet global Interrupt */ + ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ + CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ + CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ + CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ + CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ + OTG_FS_IRQn = 67 /*!< USB OTG FS global Interrupt */ +#endif /* STM32F10X_CL */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm3.h" +#include "system_stm32f10x.h" +#include + +/** @addtogroup Exported_types + * @{ + */ + +/*!< STM32F10x Standard Peripheral Library old types (maintained for legacy purpose) */ +typedef int32_t s32; +typedef int16_t s16; +typedef int8_t s8; + +typedef const int32_t sc32; /*!< Read Only */ +typedef const int16_t sc16; /*!< Read Only */ +typedef const int8_t sc8; /*!< Read Only */ + +typedef __IO int32_t vs32; +typedef __IO int16_t vs16; +typedef __IO int8_t vs8; + +typedef __I int32_t vsc32; /*!< Read Only */ +typedef __I int16_t vsc16; /*!< Read Only */ +typedef __I int8_t vsc8; /*!< Read Only */ + +typedef uint32_t u32; +typedef uint16_t u16; +typedef uint8_t u8; + +typedef const uint32_t uc32; /*!< Read Only */ +typedef const uint16_t uc16; /*!< Read Only */ +typedef const uint8_t uc8; /*!< Read Only */ + +typedef __IO uint32_t vu32; +typedef __IO uint16_t vu16; +typedef __IO uint8_t vu8; + +typedef __I uint32_t vuc32; /*!< Read Only */ +typedef __I uint16_t vuc16; /*!< Read Only */ +typedef __I uint8_t vuc8; /*!< Read Only */ + +#ifndef __cplusplus + typedef enum {FALSE = 0, TRUE = !FALSE} bool; +#endif + +typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus; + +typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; +#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) + +typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus; + +/*!< STM32F10x Standard Peripheral Library old definitions (maintained for legacy purpose) */ +#define HSEStartUp_TimeOut HSE_STARTUP_TIMEOUT +#define HSE_Value HSE_VALUE +#define HSI_Value HSI_VALUE +/** + * @} + */ + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t SR; + __IO uint32_t CR1; + __IO uint32_t CR2; + __IO uint32_t SMPR1; + __IO uint32_t SMPR2; + __IO uint32_t JOFR1; + __IO uint32_t JOFR2; + __IO uint32_t JOFR3; + __IO uint32_t JOFR4; + __IO uint32_t HTR; + __IO uint32_t LTR; + __IO uint32_t SQR1; + __IO uint32_t SQR2; + __IO uint32_t SQR3; + __IO uint32_t JSQR; + __IO uint32_t JDR1; + __IO uint32_t JDR2; + __IO uint32_t JDR3; + __IO uint32_t JDR4; + __IO uint32_t DR; +} ADC_TypeDef; + +/** + * @brief Backup Registers + */ + +typedef struct +{ + uint32_t RESERVED0; + __IO uint16_t DR1; + uint16_t RESERVED1; + __IO uint16_t DR2; + uint16_t RESERVED2; + __IO uint16_t DR3; + uint16_t RESERVED3; + __IO uint16_t DR4; + uint16_t RESERVED4; + __IO uint16_t DR5; + uint16_t RESERVED5; + __IO uint16_t DR6; + uint16_t RESERVED6; + __IO uint16_t DR7; + uint16_t RESERVED7; + __IO uint16_t DR8; + uint16_t RESERVED8; + __IO uint16_t DR9; + uint16_t RESERVED9; + __IO uint16_t DR10; + uint16_t RESERVED10; + __IO uint16_t RTCCR; + uint16_t RESERVED11; + __IO uint16_t CR; + uint16_t RESERVED12; + __IO uint16_t CSR; + uint16_t RESERVED13[5]; + __IO uint16_t DR11; + uint16_t RESERVED14; + __IO uint16_t DR12; + uint16_t RESERVED15; + __IO uint16_t DR13; + uint16_t RESERVED16; + __IO uint16_t DR14; + uint16_t RESERVED17; + __IO uint16_t DR15; + uint16_t RESERVED18; + __IO uint16_t DR16; + uint16_t RESERVED19; + __IO uint16_t DR17; + uint16_t RESERVED20; + __IO uint16_t DR18; + uint16_t RESERVED21; + __IO uint16_t DR19; + uint16_t RESERVED22; + __IO uint16_t DR20; + uint16_t RESERVED23; + __IO uint16_t DR21; + uint16_t RESERVED24; + __IO uint16_t DR22; + uint16_t RESERVED25; + __IO uint16_t DR23; + uint16_t RESERVED26; + __IO uint16_t DR24; + uint16_t RESERVED27; + __IO uint16_t DR25; + uint16_t RESERVED28; + __IO uint16_t DR26; + uint16_t RESERVED29; + __IO uint16_t DR27; + uint16_t RESERVED30; + __IO uint16_t DR28; + uint16_t RESERVED31; + __IO uint16_t DR29; + uint16_t RESERVED32; + __IO uint16_t DR30; + uint16_t RESERVED33; + __IO uint16_t DR31; + uint16_t RESERVED34; + __IO uint16_t DR32; + uint16_t RESERVED35; + __IO uint16_t DR33; + uint16_t RESERVED36; + __IO uint16_t DR34; + uint16_t RESERVED37; + __IO uint16_t DR35; + uint16_t RESERVED38; + __IO uint16_t DR36; + uint16_t RESERVED39; + __IO uint16_t DR37; + uint16_t RESERVED40; + __IO uint16_t DR38; + uint16_t RESERVED41; + __IO uint16_t DR39; + uint16_t RESERVED42; + __IO uint16_t DR40; + uint16_t RESERVED43; + __IO uint16_t DR41; + uint16_t RESERVED44; + __IO uint16_t DR42; + uint16_t RESERVED45; +} BKP_TypeDef; + +/** + * @brief Controller Area Network TxMailBox + */ + +typedef struct +{ + __IO uint32_t TIR; + __IO uint32_t TDTR; + __IO uint32_t TDLR; + __IO uint32_t TDHR; +} CAN_TxMailBox_TypeDef; + +/** + * @brief Controller Area Network FIFOMailBox + */ + +typedef struct +{ + __IO uint32_t RIR; + __IO uint32_t RDTR; + __IO uint32_t RDLR; + __IO uint32_t RDHR; +} CAN_FIFOMailBox_TypeDef; + +/** + * @brief Controller Area Network FilterRegister + */ + +typedef struct +{ + __IO uint32_t FR1; + __IO uint32_t FR2; +} CAN_FilterRegister_TypeDef; + +/** + * @brief Controller Area Network + */ + +typedef struct +{ + __IO uint32_t MCR; + __IO uint32_t MSR; + __IO uint32_t TSR; + __IO uint32_t RF0R; + __IO uint32_t RF1R; + __IO uint32_t IER; + __IO uint32_t ESR; + __IO uint32_t BTR; + uint32_t RESERVED0[88]; + CAN_TxMailBox_TypeDef sTxMailBox[3]; + CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; + uint32_t RESERVED1[12]; + __IO uint32_t FMR; + __IO uint32_t FM1R; + uint32_t RESERVED2; + __IO uint32_t FS1R; + uint32_t RESERVED3; + __IO uint32_t FFA1R; + uint32_t RESERVED4; + __IO uint32_t FA1R; + uint32_t RESERVED5[8]; +#ifndef STM32F10X_CL + CAN_FilterRegister_TypeDef sFilterRegister[14]; +#else + CAN_FilterRegister_TypeDef sFilterRegister[28]; +#endif /* STM32F10X_CL */ +} CAN_TypeDef; + +/** + * @brief Consumer Electronics Control (CEC) + */ +typedef struct +{ + __IO uint32_t CFGR; + __IO uint32_t OAR; + __IO uint32_t PRES; + __IO uint32_t ESR; + __IO uint32_t CSR; + __IO uint32_t TXD; + __IO uint32_t RXD; +} CEC_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; + __IO uint8_t IDR; + uint8_t RESERVED0; + uint16_t RESERVED1; + __IO uint32_t CR; +} CRC_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t SWTRIGR; + __IO uint32_t DHR12R1; + __IO uint32_t DHR12L1; + __IO uint32_t DHR8R1; + __IO uint32_t DHR12R2; + __IO uint32_t DHR12L2; + __IO uint32_t DHR8R2; + __IO uint32_t DHR12RD; + __IO uint32_t DHR12LD; + __IO uint32_t DHR8RD; + __IO uint32_t DOR1; + __IO uint32_t DOR2; +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + __IO uint32_t SR; +#endif +} DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; + __IO uint32_t CR; +}DBGMCU_TypeDef; + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CCR; + __IO uint32_t CNDTR; + __IO uint32_t CPAR; + __IO uint32_t CMAR; +} DMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; + __IO uint32_t IFCR; +} DMA_TypeDef; + +/** + * @brief Ethernet MAC + */ + +typedef struct +{ + __IO uint32_t MACCR; + __IO uint32_t MACFFR; + __IO uint32_t MACHTHR; + __IO uint32_t MACHTLR; + __IO uint32_t MACMIIAR; + __IO uint32_t MACMIIDR; + __IO uint32_t MACFCR; + __IO uint32_t MACVLANTR; /* 8 */ + uint32_t RESERVED0[2]; + __IO uint32_t MACRWUFFR; /* 11 */ + __IO uint32_t MACPMTCSR; + uint32_t RESERVED1[2]; + __IO uint32_t MACSR; /* 15 */ + __IO uint32_t MACIMR; + __IO uint32_t MACA0HR; + __IO uint32_t MACA0LR; + __IO uint32_t MACA1HR; + __IO uint32_t MACA1LR; + __IO uint32_t MACA2HR; + __IO uint32_t MACA2LR; + __IO uint32_t MACA3HR; + __IO uint32_t MACA3LR; /* 24 */ + uint32_t RESERVED2[40]; + __IO uint32_t MMCCR; /* 65 */ + __IO uint32_t MMCRIR; + __IO uint32_t MMCTIR; + __IO uint32_t MMCRIMR; + __IO uint32_t MMCTIMR; /* 69 */ + uint32_t RESERVED3[14]; + __IO uint32_t MMCTGFSCCR; /* 84 */ + __IO uint32_t MMCTGFMSCCR; + uint32_t RESERVED4[5]; + __IO uint32_t MMCTGFCR; + uint32_t RESERVED5[10]; + __IO uint32_t MMCRFCECR; + __IO uint32_t MMCRFAECR; + uint32_t RESERVED6[10]; + __IO uint32_t MMCRGUFCR; + uint32_t RESERVED7[334]; + __IO uint32_t PTPTSCR; + __IO uint32_t PTPSSIR; + __IO uint32_t PTPTSHR; + __IO uint32_t PTPTSLR; + __IO uint32_t PTPTSHUR; + __IO uint32_t PTPTSLUR; + __IO uint32_t PTPTSAR; + __IO uint32_t PTPTTHR; + __IO uint32_t PTPTTLR; + uint32_t RESERVED8[567]; + __IO uint32_t DMABMR; + __IO uint32_t DMATPDR; + __IO uint32_t DMARPDR; + __IO uint32_t DMARDLAR; + __IO uint32_t DMATDLAR; + __IO uint32_t DMASR; + __IO uint32_t DMAOMR; + __IO uint32_t DMAIER; + __IO uint32_t DMAMFBOCR; + uint32_t RESERVED9[9]; + __IO uint32_t DMACHTDR; + __IO uint32_t DMACHRDR; + __IO uint32_t DMACHTBAR; + __IO uint32_t DMACHRBAR; +} ETH_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; + __IO uint32_t EMR; + __IO uint32_t RTSR; + __IO uint32_t FTSR; + __IO uint32_t SWIER; + __IO uint32_t PR; +} EXTI_TypeDef; + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; + __IO uint32_t KEYR; + __IO uint32_t OPTKEYR; + __IO uint32_t SR; + __IO uint32_t CR; + __IO uint32_t AR; + __IO uint32_t RESERVED; + __IO uint32_t OBR; + __IO uint32_t WRPR; +#ifdef STM32F10X_XL + uint32_t RESERVED1[8]; + __IO uint32_t KEYR2; + uint32_t RESERVED2; + __IO uint32_t SR2; + __IO uint32_t CR2; + __IO uint32_t AR2; +#endif /* STM32F10X_XL */ +} FLASH_TypeDef; + +/** + * @brief Option Bytes Registers + */ + +typedef struct +{ + __IO uint16_t RDP; + __IO uint16_t USER; + __IO uint16_t Data0; + __IO uint16_t Data1; + __IO uint16_t WRP0; + __IO uint16_t WRP1; + __IO uint16_t WRP2; + __IO uint16_t WRP3; +} OB_TypeDef; + +/** + * @brief Flexible Static Memory Controller + */ + +typedef struct +{ + __IO uint32_t BTCR[8]; +} FSMC_Bank1_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; +} FSMC_Bank1E_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank2 + */ + +typedef struct +{ + __IO uint32_t PCR2; + __IO uint32_t SR2; + __IO uint32_t PMEM2; + __IO uint32_t PATT2; + uint32_t RESERVED0; + __IO uint32_t ECCR2; +} FSMC_Bank2_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank3 + */ + +typedef struct +{ + __IO uint32_t PCR3; + __IO uint32_t SR3; + __IO uint32_t PMEM3; + __IO uint32_t PATT3; + uint32_t RESERVED0; + __IO uint32_t ECCR3; +} FSMC_Bank3_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank4 + */ + +typedef struct +{ + __IO uint32_t PCR4; + __IO uint32_t SR4; + __IO uint32_t PMEM4; + __IO uint32_t PATT4; + __IO uint32_t PIO4; +} FSMC_Bank4_TypeDef; + +/** + * @brief General Purpose I/O + */ + +typedef struct +{ + __IO uint32_t CRL; + __IO uint32_t CRH; + __IO uint32_t IDR; + __IO uint32_t ODR; + __IO uint32_t BSRR; + __IO uint32_t BRR; + __IO uint32_t LCKR; +} GPIO_TypeDef; + +/** + * @brief Alternate Function I/O + */ + +typedef struct +{ + __IO uint32_t EVCR; + __IO uint32_t MAPR; + __IO uint32_t EXTICR[4]; + uint32_t RESERVED0; + __IO uint32_t MAPR2; +} AFIO_TypeDef; +/** + * @brief Inter-integrated Circuit Interface + */ + +typedef struct +{ + __IO uint16_t CR1; + uint16_t RESERVED0; + __IO uint16_t CR2; + uint16_t RESERVED1; + __IO uint16_t OAR1; + uint16_t RESERVED2; + __IO uint16_t OAR2; + uint16_t RESERVED3; + __IO uint16_t DR; + uint16_t RESERVED4; + __IO uint16_t SR1; + uint16_t RESERVED5; + __IO uint16_t SR2; + uint16_t RESERVED6; + __IO uint16_t CCR; + uint16_t RESERVED7; + __IO uint16_t TRISE; + uint16_t RESERVED8; +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; + __IO uint32_t PR; + __IO uint32_t RLR; + __IO uint32_t SR; +} IWDG_TypeDef; + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t CSR; +} PWR_TypeDef; + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t CFGR; + __IO uint32_t CIR; + __IO uint32_t APB2RSTR; + __IO uint32_t APB1RSTR; + __IO uint32_t AHBENR; + __IO uint32_t APB2ENR; + __IO uint32_t APB1ENR; + __IO uint32_t BDCR; + __IO uint32_t CSR; + +#ifdef STM32F10X_CL + __IO uint32_t AHBRSTR; + __IO uint32_t CFGR2; +#endif /* STM32F10X_CL */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + uint32_t RESERVED0; + __IO uint32_t CFGR2; +#endif /* STM32F10X_LD_VL || STM32F10X_MD_VL || STM32F10X_HD_VL */ +} RCC_TypeDef; + +/** + * @brief Real-Time Clock + */ + +typedef struct +{ + __IO uint16_t CRH; + uint16_t RESERVED0; + __IO uint16_t CRL; + uint16_t RESERVED1; + __IO uint16_t PRLH; + uint16_t RESERVED2; + __IO uint16_t PRLL; + uint16_t RESERVED3; + __IO uint16_t DIVH; + uint16_t RESERVED4; + __IO uint16_t DIVL; + uint16_t RESERVED5; + __IO uint16_t CNTH; + uint16_t RESERVED6; + __IO uint16_t CNTL; + uint16_t RESERVED7; + __IO uint16_t ALRH; + uint16_t RESERVED8; + __IO uint16_t ALRL; + uint16_t RESERVED9; +} RTC_TypeDef; + +/** + * @brief SD host Interface + */ + +typedef struct +{ + __IO uint32_t POWER; + __IO uint32_t CLKCR; + __IO uint32_t ARG; + __IO uint32_t CMD; + __I uint32_t RESPCMD; + __I uint32_t RESP1; + __I uint32_t RESP2; + __I uint32_t RESP3; + __I uint32_t RESP4; + __IO uint32_t DTIMER; + __IO uint32_t DLEN; + __IO uint32_t DCTRL; + __I uint32_t DCOUNT; + __I uint32_t STA; + __IO uint32_t ICR; + __IO uint32_t MASK; + uint32_t RESERVED0[2]; + __I uint32_t FIFOCNT; + uint32_t RESERVED1[13]; + __IO uint32_t FIFO; +} SDIO_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint16_t CR1; + uint16_t RESERVED0; + __IO uint16_t CR2; + uint16_t RESERVED1; + __IO uint16_t SR; + uint16_t RESERVED2; + __IO uint16_t DR; + uint16_t RESERVED3; + __IO uint16_t CRCPR; + uint16_t RESERVED4; + __IO uint16_t RXCRCR; + uint16_t RESERVED5; + __IO uint16_t TXCRCR; + uint16_t RESERVED6; + __IO uint16_t I2SCFGR; + uint16_t RESERVED7; + __IO uint16_t I2SPR; + uint16_t RESERVED8; +} SPI_TypeDef; + +/** + * @brief TIM + */ + +typedef struct +{ + __IO uint16_t CR1; + uint16_t RESERVED0; + __IO uint16_t CR2; + uint16_t RESERVED1; + __IO uint16_t SMCR; + uint16_t RESERVED2; + __IO uint16_t DIER; + uint16_t RESERVED3; + __IO uint16_t SR; + uint16_t RESERVED4; + __IO uint16_t EGR; + uint16_t RESERVED5; + __IO uint16_t CCMR1; + uint16_t RESERVED6; + __IO uint16_t CCMR2; + uint16_t RESERVED7; + __IO uint16_t CCER; + uint16_t RESERVED8; + __IO uint16_t CNT; + uint16_t RESERVED9; + __IO uint16_t PSC; + uint16_t RESERVED10; + __IO uint16_t ARR; + uint16_t RESERVED11; + __IO uint16_t RCR; + uint16_t RESERVED12; + __IO uint16_t CCR1; + uint16_t RESERVED13; + __IO uint16_t CCR2; + uint16_t RESERVED14; + __IO uint16_t CCR3; + uint16_t RESERVED15; + __IO uint16_t CCR4; + uint16_t RESERVED16; + __IO uint16_t BDTR; + uint16_t RESERVED17; + __IO uint16_t DCR; + uint16_t RESERVED18; + __IO uint16_t DMAR; + uint16_t RESERVED19; +} TIM_TypeDef; + +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ + +typedef struct +{ + __IO uint16_t SR; + uint16_t RESERVED0; + __IO uint16_t DR; + uint16_t RESERVED1; + __IO uint16_t BRR; + uint16_t RESERVED2; + __IO uint16_t CR1; + uint16_t RESERVED3; + __IO uint16_t CR2; + uint16_t RESERVED4; + __IO uint16_t CR3; + uint16_t RESERVED5; + __IO uint16_t GTPR; + uint16_t RESERVED6; +} USART_TypeDef; + +/** + * @brief Window WATCHDOG + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t CFR; + __IO uint32_t SR; +} WWDG_TypeDef; + +/** + * @} + */ + +/** @addtogroup Peripheral_memory_map + * @{ + */ + + +#define FLASH_BASE ((uint32_t)0x08000000) /*!< FLASH base address in the alias region */ +#define SRAM_BASE ((uint32_t)0x20000000) /*!< SRAM base address in the alias region */ +#define PERIPH_BASE ((uint32_t)0x40000000) /*!< Peripheral base address in the alias region */ + +#define SRAM_BB_BASE ((uint32_t)0x22000000) /*!< SRAM base address in the bit-band region */ +#define PERIPH_BB_BASE ((uint32_t)0x42000000) /*!< Peripheral base address in the bit-band region */ + +#define FSMC_R_BASE ((uint32_t)0xA0000000) /*!< FSMC registers base address */ + +/*!< Peripheral memory map */ +#define APB1PERIPH_BASE PERIPH_BASE +#define APB2PERIPH_BASE (PERIPH_BASE + 0x10000) +#define AHBPERIPH_BASE (PERIPH_BASE + 0x20000) + +#define TIM2_BASE (APB1PERIPH_BASE + 0x0000) +#define TIM3_BASE (APB1PERIPH_BASE + 0x0400) +#define TIM4_BASE (APB1PERIPH_BASE + 0x0800) +#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TIM6_BASE (APB1PERIPH_BASE + 0x1000) +#define TIM7_BASE (APB1PERIPH_BASE + 0x1400) +#define TIM12_BASE (APB1PERIPH_BASE + 0x1800) +#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TIM14_BASE (APB1PERIPH_BASE + 0x2000) +#define RTC_BASE (APB1PERIPH_BASE + 0x2800) +#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00) +#define IWDG_BASE (APB1PERIPH_BASE + 0x3000) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define BKP_BASE (APB1PERIPH_BASE + 0x6C00) +#define PWR_BASE (APB1PERIPH_BASE + 0x7000) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) +#define CEC_BASE (APB1PERIPH_BASE + 0x7800) + +#define AFIO_BASE (APB2PERIPH_BASE + 0x0000) +#define EXTI_BASE (APB2PERIPH_BASE + 0x0400) +#define GPIOA_BASE (APB2PERIPH_BASE + 0x0800) +#define GPIOB_BASE (APB2PERIPH_BASE + 0x0C00) +#define GPIOC_BASE (APB2PERIPH_BASE + 0x1000) +#define GPIOD_BASE (APB2PERIPH_BASE + 0x1400) +#define GPIOE_BASE (APB2PERIPH_BASE + 0x1800) +#define GPIOF_BASE (APB2PERIPH_BASE + 0x1C00) +#define GPIOG_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2400) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2800) +#define TIM1_BASE (APB2PERIPH_BASE + 0x2C00) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define TIM8_BASE (APB2PERIPH_BASE + 0x3400) +#define USART1_BASE (APB2PERIPH_BASE + 0x3800) +#define ADC3_BASE (APB2PERIPH_BASE + 0x3C00) +#define TIM15_BASE (APB2PERIPH_BASE + 0x4000) +#define TIM16_BASE (APB2PERIPH_BASE + 0x4400) +#define TIM17_BASE (APB2PERIPH_BASE + 0x4800) +#define TIM9_BASE (APB2PERIPH_BASE + 0x4C00) +#define TIM10_BASE (APB2PERIPH_BASE + 0x5000) +#define TIM11_BASE (APB2PERIPH_BASE + 0x5400) + +#define SDIO_BASE (PERIPH_BASE + 0x18000) + +#define DMA1_BASE (AHBPERIPH_BASE + 0x0000) +#define DMA1_Channel1_BASE (AHBPERIPH_BASE + 0x0008) +#define DMA1_Channel2_BASE (AHBPERIPH_BASE + 0x001C) +#define DMA1_Channel3_BASE (AHBPERIPH_BASE + 0x0030) +#define DMA1_Channel4_BASE (AHBPERIPH_BASE + 0x0044) +#define DMA1_Channel5_BASE (AHBPERIPH_BASE + 0x0058) +#define DMA1_Channel6_BASE (AHBPERIPH_BASE + 0x006C) +#define DMA1_Channel7_BASE (AHBPERIPH_BASE + 0x0080) +#define DMA2_BASE (AHBPERIPH_BASE + 0x0400) +#define DMA2_Channel1_BASE (AHBPERIPH_BASE + 0x0408) +#define DMA2_Channel2_BASE (AHBPERIPH_BASE + 0x041C) +#define DMA2_Channel3_BASE (AHBPERIPH_BASE + 0x0430) +#define DMA2_Channel4_BASE (AHBPERIPH_BASE + 0x0444) +#define DMA2_Channel5_BASE (AHBPERIPH_BASE + 0x0458) +#define RCC_BASE (AHBPERIPH_BASE + 0x1000) +#define CRC_BASE (AHBPERIPH_BASE + 0x3000) + +#define FLASH_R_BASE (AHBPERIPH_BASE + 0x2000) /*!< Flash registers base address */ +#define OB_BASE ((uint32_t)0x1FFFF800) /*!< Flash Option Bytes base address */ + +#define ETH_BASE (AHBPERIPH_BASE + 0x8000) +#define ETH_MAC_BASE (ETH_BASE) +#define ETH_MMC_BASE (ETH_BASE + 0x0100) +#define ETH_PTP_BASE (ETH_BASE + 0x0700) +#define ETH_DMA_BASE (ETH_BASE + 0x1000) + +#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000) /*!< FSMC Bank1 registers base address */ +#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104) /*!< FSMC Bank1E registers base address */ +#define FSMC_Bank2_R_BASE (FSMC_R_BASE + 0x0060) /*!< FSMC Bank2 registers base address */ +#define FSMC_Bank3_R_BASE (FSMC_R_BASE + 0x0080) /*!< FSMC Bank3 registers base address */ +#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0) /*!< FSMC Bank4 registers base address */ + +#define DBGMCU_BASE ((uint32_t)0xE0042000) /*!< Debug MCU registers base address */ + +/** + * @} + */ + +/** @addtogroup Peripheral_declaration + * @{ + */ + +#define TIM2 ((TIM_TypeDef *) TIM2_BASE) +#define TIM3 ((TIM_TypeDef *) TIM3_BASE) +#define TIM4 ((TIM_TypeDef *) TIM4_BASE) +#define TIM5 ((TIM_TypeDef *) TIM5_BASE) +#define TIM6 ((TIM_TypeDef *) TIM6_BASE) +#define TIM7 ((TIM_TypeDef *) TIM7_BASE) +#define TIM12 ((TIM_TypeDef *) TIM12_BASE) +#define TIM13 ((TIM_TypeDef *) TIM13_BASE) +#define TIM14 ((TIM_TypeDef *) TIM14_BASE) +#define RTC ((RTC_TypeDef *) RTC_BASE) +#define WWDG ((WWDG_TypeDef *) WWDG_BASE) +#define IWDG ((IWDG_TypeDef *) IWDG_BASE) +#define SPI2 ((SPI_TypeDef *) SPI2_BASE) +#define SPI3 ((SPI_TypeDef *) SPI3_BASE) +#define USART2 ((USART_TypeDef *) USART2_BASE) +#define USART3 ((USART_TypeDef *) USART3_BASE) +#define UART4 ((USART_TypeDef *) UART4_BASE) +#define UART5 ((USART_TypeDef *) UART5_BASE) +#define I2C1 ((I2C_TypeDef *) I2C1_BASE) +#define I2C2 ((I2C_TypeDef *) I2C2_BASE) +#define CAN1 ((CAN_TypeDef *) CAN1_BASE) +#define CAN2 ((CAN_TypeDef *) CAN2_BASE) +#define BKP ((BKP_TypeDef *) BKP_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define DAC ((DAC_TypeDef *) DAC_BASE) +#define CEC ((CEC_TypeDef *) CEC_BASE) +#define AFIO ((AFIO_TypeDef *) AFIO_BASE) +#define EXTI ((EXTI_TypeDef *) EXTI_BASE) +#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) +#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) +#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) +#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) +#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) +#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) +#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) +#define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC2 ((ADC_TypeDef *) ADC2_BASE) +#define TIM1 ((TIM_TypeDef *) TIM1_BASE) +#define SPI1 ((SPI_TypeDef *) SPI1_BASE) +#define TIM8 ((TIM_TypeDef *) TIM8_BASE) +#define USART1 ((USART_TypeDef *) USART1_BASE) +#define ADC3 ((ADC_TypeDef *) ADC3_BASE) +#define TIM15 ((TIM_TypeDef *) TIM15_BASE) +#define TIM16 ((TIM_TypeDef *) TIM16_BASE) +#define TIM17 ((TIM_TypeDef *) TIM17_BASE) +#define TIM9 ((TIM_TypeDef *) TIM9_BASE) +#define TIM10 ((TIM_TypeDef *) TIM10_BASE) +#define TIM11 ((TIM_TypeDef *) TIM11_BASE) +#define SDIO ((SDIO_TypeDef *) SDIO_BASE) +#define DMA1 ((DMA_TypeDef *) DMA1_BASE) +#define DMA2 ((DMA_TypeDef *) DMA2_BASE) +#define DMA1_Channel1 ((DMA_Channel_TypeDef *) DMA1_Channel1_BASE) +#define DMA1_Channel2 ((DMA_Channel_TypeDef *) DMA1_Channel2_BASE) +#define DMA1_Channel3 ((DMA_Channel_TypeDef *) DMA1_Channel3_BASE) +#define DMA1_Channel4 ((DMA_Channel_TypeDef *) DMA1_Channel4_BASE) +#define DMA1_Channel5 ((DMA_Channel_TypeDef *) DMA1_Channel5_BASE) +#define DMA1_Channel6 ((DMA_Channel_TypeDef *) DMA1_Channel6_BASE) +#define DMA1_Channel7 ((DMA_Channel_TypeDef *) DMA1_Channel7_BASE) +#define DMA2_Channel1 ((DMA_Channel_TypeDef *) DMA2_Channel1_BASE) +#define DMA2_Channel2 ((DMA_Channel_TypeDef *) DMA2_Channel2_BASE) +#define DMA2_Channel3 ((DMA_Channel_TypeDef *) DMA2_Channel3_BASE) +#define DMA2_Channel4 ((DMA_Channel_TypeDef *) DMA2_Channel4_BASE) +#define DMA2_Channel5 ((DMA_Channel_TypeDef *) DMA2_Channel5_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define CRC ((CRC_TypeDef *) CRC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define OB ((OB_TypeDef *) OB_BASE) +#define ETH ((ETH_TypeDef *) ETH_BASE) +#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) +#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) +#define FSMC_Bank2 ((FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE) +#define FSMC_Bank3 ((FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE) +#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + + /** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* CRC calculation unit */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for CRC_DR register *********************/ +#define CRC_DR_DR ((uint32_t)0xFFFFFFFF) /*!< Data register bits */ + + +/******************* Bit definition for CRC_IDR register ********************/ +#define CRC_IDR_IDR ((uint8_t)0xFF) /*!< General-purpose 8-bit data register bits */ + + +/******************** Bit definition for CRC_CR register ********************/ +#define CRC_CR_RESET ((uint8_t)0x01) /*!< RESET bit */ + +/******************************************************************************/ +/* */ +/* Power Control */ +/* */ +/******************************************************************************/ + +/******************** Bit definition for PWR_CR register ********************/ +#define PWR_CR_LPDS ((uint16_t)0x0001) /*!< Low-Power Deepsleep */ +#define PWR_CR_PDDS ((uint16_t)0x0002) /*!< Power Down Deepsleep */ +#define PWR_CR_CWUF ((uint16_t)0x0004) /*!< Clear Wakeup Flag */ +#define PWR_CR_CSBF ((uint16_t)0x0008) /*!< Clear Standby Flag */ +#define PWR_CR_PVDE ((uint16_t)0x0010) /*!< Power Voltage Detector Enable */ + +#define PWR_CR_PLS ((uint16_t)0x00E0) /*!< PLS[2:0] bits (PVD Level Selection) */ +#define PWR_CR_PLS_0 ((uint16_t)0x0020) /*!< Bit 0 */ +#define PWR_CR_PLS_1 ((uint16_t)0x0040) /*!< Bit 1 */ +#define PWR_CR_PLS_2 ((uint16_t)0x0080) /*!< Bit 2 */ + +/*!< PVD level configuration */ +#define PWR_CR_PLS_2V2 ((uint16_t)0x0000) /*!< PVD level 2.2V */ +#define PWR_CR_PLS_2V3 ((uint16_t)0x0020) /*!< PVD level 2.3V */ +#define PWR_CR_PLS_2V4 ((uint16_t)0x0040) /*!< PVD level 2.4V */ +#define PWR_CR_PLS_2V5 ((uint16_t)0x0060) /*!< PVD level 2.5V */ +#define PWR_CR_PLS_2V6 ((uint16_t)0x0080) /*!< PVD level 2.6V */ +#define PWR_CR_PLS_2V7 ((uint16_t)0x00A0) /*!< PVD level 2.7V */ +#define PWR_CR_PLS_2V8 ((uint16_t)0x00C0) /*!< PVD level 2.8V */ +#define PWR_CR_PLS_2V9 ((uint16_t)0x00E0) /*!< PVD level 2.9V */ + +#define PWR_CR_DBP ((uint16_t)0x0100) /*!< Disable Backup Domain write protection */ + + +/******************* Bit definition for PWR_CSR register ********************/ +#define PWR_CSR_WUF ((uint16_t)0x0001) /*!< Wakeup Flag */ +#define PWR_CSR_SBF ((uint16_t)0x0002) /*!< Standby Flag */ +#define PWR_CSR_PVDO ((uint16_t)0x0004) /*!< PVD Output */ +#define PWR_CSR_EWUP ((uint16_t)0x0100) /*!< Enable WKUP pin */ + +/******************************************************************************/ +/* */ +/* Backup registers */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for BKP_DR1 register ********************/ +#define BKP_DR1_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR2 register ********************/ +#define BKP_DR2_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR3 register ********************/ +#define BKP_DR3_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR4 register ********************/ +#define BKP_DR4_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR5 register ********************/ +#define BKP_DR5_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR6 register ********************/ +#define BKP_DR6_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR7 register ********************/ +#define BKP_DR7_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR8 register ********************/ +#define BKP_DR8_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR9 register ********************/ +#define BKP_DR9_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR10 register *******************/ +#define BKP_DR10_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR11 register *******************/ +#define BKP_DR11_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR12 register *******************/ +#define BKP_DR12_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR13 register *******************/ +#define BKP_DR13_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR14 register *******************/ +#define BKP_DR14_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR15 register *******************/ +#define BKP_DR15_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR16 register *******************/ +#define BKP_DR16_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR17 register *******************/ +#define BKP_DR17_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/****************** Bit definition for BKP_DR18 register ********************/ +#define BKP_DR18_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR19 register *******************/ +#define BKP_DR19_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR20 register *******************/ +#define BKP_DR20_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR21 register *******************/ +#define BKP_DR21_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR22 register *******************/ +#define BKP_DR22_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR23 register *******************/ +#define BKP_DR23_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR24 register *******************/ +#define BKP_DR24_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR25 register *******************/ +#define BKP_DR25_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR26 register *******************/ +#define BKP_DR26_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR27 register *******************/ +#define BKP_DR27_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR28 register *******************/ +#define BKP_DR28_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR29 register *******************/ +#define BKP_DR29_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR30 register *******************/ +#define BKP_DR30_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR31 register *******************/ +#define BKP_DR31_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR32 register *******************/ +#define BKP_DR32_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR33 register *******************/ +#define BKP_DR33_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR34 register *******************/ +#define BKP_DR34_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR35 register *******************/ +#define BKP_DR35_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR36 register *******************/ +#define BKP_DR36_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR37 register *******************/ +#define BKP_DR37_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR38 register *******************/ +#define BKP_DR38_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR39 register *******************/ +#define BKP_DR39_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR40 register *******************/ +#define BKP_DR40_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR41 register *******************/ +#define BKP_DR41_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR42 register *******************/ +#define BKP_DR42_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/****************** Bit definition for BKP_RTCCR register *******************/ +#define BKP_RTCCR_CAL ((uint16_t)0x007F) /*!< Calibration value */ +#define BKP_RTCCR_CCO ((uint16_t)0x0080) /*!< Calibration Clock Output */ +#define BKP_RTCCR_ASOE ((uint16_t)0x0100) /*!< Alarm or Second Output Enable */ +#define BKP_RTCCR_ASOS ((uint16_t)0x0200) /*!< Alarm or Second Output Selection */ + +/******************** Bit definition for BKP_CR register ********************/ +#define BKP_CR_TPE ((uint8_t)0x01) /*!< TAMPER pin enable */ +#define BKP_CR_TPAL ((uint8_t)0x02) /*!< TAMPER pin active level */ + +/******************* Bit definition for BKP_CSR register ********************/ +#define BKP_CSR_CTE ((uint16_t)0x0001) /*!< Clear Tamper event */ +#define BKP_CSR_CTI ((uint16_t)0x0002) /*!< Clear Tamper Interrupt */ +#define BKP_CSR_TPIE ((uint16_t)0x0004) /*!< TAMPER Pin interrupt enable */ +#define BKP_CSR_TEF ((uint16_t)0x0100) /*!< Tamper Event Flag */ +#define BKP_CSR_TIF ((uint16_t)0x0200) /*!< Tamper Interrupt Flag */ + +/******************************************************************************/ +/* */ +/* Reset and Clock Control */ +/* */ +/******************************************************************************/ + +/******************** Bit definition for RCC_CR register ********************/ +#define RCC_CR_HSION ((uint32_t)0x00000001) /*!< Internal High Speed clock enable */ +#define RCC_CR_HSIRDY ((uint32_t)0x00000002) /*!< Internal High Speed clock ready flag */ +#define RCC_CR_HSITRIM ((uint32_t)0x000000F8) /*!< Internal High Speed clock trimming */ +#define RCC_CR_HSICAL ((uint32_t)0x0000FF00) /*!< Internal High Speed clock Calibration */ +#define RCC_CR_HSEON ((uint32_t)0x00010000) /*!< External High Speed clock enable */ +#define RCC_CR_HSERDY ((uint32_t)0x00020000) /*!< External High Speed clock ready flag */ +#define RCC_CR_HSEBYP ((uint32_t)0x00040000) /*!< External High Speed clock Bypass */ +#define RCC_CR_CSSON ((uint32_t)0x00080000) /*!< Clock Security System enable */ +#define RCC_CR_PLLON ((uint32_t)0x01000000) /*!< PLL enable */ +#define RCC_CR_PLLRDY ((uint32_t)0x02000000) /*!< PLL clock ready flag */ + +#ifdef STM32F10X_CL + #define RCC_CR_PLL2ON ((uint32_t)0x04000000) /*!< PLL2 enable */ + #define RCC_CR_PLL2RDY ((uint32_t)0x08000000) /*!< PLL2 clock ready flag */ + #define RCC_CR_PLL3ON ((uint32_t)0x10000000) /*!< PLL3 enable */ + #define RCC_CR_PLL3RDY ((uint32_t)0x20000000) /*!< PLL3 clock ready flag */ +#endif /* STM32F10X_CL */ + +/******************* Bit definition for RCC_CFGR register *******************/ +/*!< SW configuration */ +#define RCC_CFGR_SW ((uint32_t)0x00000003) /*!< SW[1:0] bits (System clock Switch) */ +#define RCC_CFGR_SW_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define RCC_CFGR_SW_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + +#define RCC_CFGR_SW_HSI ((uint32_t)0x00000000) /*!< HSI selected as system clock */ +#define RCC_CFGR_SW_HSE ((uint32_t)0x00000001) /*!< HSE selected as system clock */ +#define RCC_CFGR_SW_PLL ((uint32_t)0x00000002) /*!< PLL selected as system clock */ + +/*!< SWS configuration */ +#define RCC_CFGR_SWS ((uint32_t)0x0000000C) /*!< SWS[1:0] bits (System Clock Switch Status) */ +#define RCC_CFGR_SWS_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define RCC_CFGR_SWS_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define RCC_CFGR_SWS_HSI ((uint32_t)0x00000000) /*!< HSI oscillator used as system clock */ +#define RCC_CFGR_SWS_HSE ((uint32_t)0x00000004) /*!< HSE oscillator used as system clock */ +#define RCC_CFGR_SWS_PLL ((uint32_t)0x00000008) /*!< PLL used as system clock */ + +/*!< HPRE configuration */ +#define RCC_CFGR_HPRE ((uint32_t)0x000000F0) /*!< HPRE[3:0] bits (AHB prescaler) */ +#define RCC_CFGR_HPRE_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define RCC_CFGR_HPRE_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define RCC_CFGR_HPRE_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define RCC_CFGR_HPRE_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define RCC_CFGR_HPRE_DIV1 ((uint32_t)0x00000000) /*!< SYSCLK not divided */ +#define RCC_CFGR_HPRE_DIV2 ((uint32_t)0x00000080) /*!< SYSCLK divided by 2 */ +#define RCC_CFGR_HPRE_DIV4 ((uint32_t)0x00000090) /*!< SYSCLK divided by 4 */ +#define RCC_CFGR_HPRE_DIV8 ((uint32_t)0x000000A0) /*!< SYSCLK divided by 8 */ +#define RCC_CFGR_HPRE_DIV16 ((uint32_t)0x000000B0) /*!< SYSCLK divided by 16 */ +#define RCC_CFGR_HPRE_DIV64 ((uint32_t)0x000000C0) /*!< SYSCLK divided by 64 */ +#define RCC_CFGR_HPRE_DIV128 ((uint32_t)0x000000D0) /*!< SYSCLK divided by 128 */ +#define RCC_CFGR_HPRE_DIV256 ((uint32_t)0x000000E0) /*!< SYSCLK divided by 256 */ +#define RCC_CFGR_HPRE_DIV512 ((uint32_t)0x000000F0) /*!< SYSCLK divided by 512 */ + +/*!< PPRE1 configuration */ +#define RCC_CFGR_PPRE1 ((uint32_t)0x00000700) /*!< PRE1[2:0] bits (APB1 prescaler) */ +#define RCC_CFGR_PPRE1_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define RCC_CFGR_PPRE1_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define RCC_CFGR_PPRE1_2 ((uint32_t)0x00000400) /*!< Bit 2 */ + +#define RCC_CFGR_PPRE1_DIV1 ((uint32_t)0x00000000) /*!< HCLK not divided */ +#define RCC_CFGR_PPRE1_DIV2 ((uint32_t)0x00000400) /*!< HCLK divided by 2 */ +#define RCC_CFGR_PPRE1_DIV4 ((uint32_t)0x00000500) /*!< HCLK divided by 4 */ +#define RCC_CFGR_PPRE1_DIV8 ((uint32_t)0x00000600) /*!< HCLK divided by 8 */ +#define RCC_CFGR_PPRE1_DIV16 ((uint32_t)0x00000700) /*!< HCLK divided by 16 */ + +/*!< PPRE2 configuration */ +#define RCC_CFGR_PPRE2 ((uint32_t)0x00003800) /*!< PRE2[2:0] bits (APB2 prescaler) */ +#define RCC_CFGR_PPRE2_0 ((uint32_t)0x00000800) /*!< Bit 0 */ +#define RCC_CFGR_PPRE2_1 ((uint32_t)0x00001000) /*!< Bit 1 */ +#define RCC_CFGR_PPRE2_2 ((uint32_t)0x00002000) /*!< Bit 2 */ + +#define RCC_CFGR_PPRE2_DIV1 ((uint32_t)0x00000000) /*!< HCLK not divided */ +#define RCC_CFGR_PPRE2_DIV2 ((uint32_t)0x00002000) /*!< HCLK divided by 2 */ +#define RCC_CFGR_PPRE2_DIV4 ((uint32_t)0x00002800) /*!< HCLK divided by 4 */ +#define RCC_CFGR_PPRE2_DIV8 ((uint32_t)0x00003000) /*!< HCLK divided by 8 */ +#define RCC_CFGR_PPRE2_DIV16 ((uint32_t)0x00003800) /*!< HCLK divided by 16 */ + +/*!< ADCPPRE configuration */ +#define RCC_CFGR_ADCPRE ((uint32_t)0x0000C000) /*!< ADCPRE[1:0] bits (ADC prescaler) */ +#define RCC_CFGR_ADCPRE_0 ((uint32_t)0x00004000) /*!< Bit 0 */ +#define RCC_CFGR_ADCPRE_1 ((uint32_t)0x00008000) /*!< Bit 1 */ + +#define RCC_CFGR_ADCPRE_DIV2 ((uint32_t)0x00000000) /*!< PCLK2 divided by 2 */ +#define RCC_CFGR_ADCPRE_DIV4 ((uint32_t)0x00004000) /*!< PCLK2 divided by 4 */ +#define RCC_CFGR_ADCPRE_DIV6 ((uint32_t)0x00008000) /*!< PCLK2 divided by 6 */ +#define RCC_CFGR_ADCPRE_DIV8 ((uint32_t)0x0000C000) /*!< PCLK2 divided by 8 */ + +#define RCC_CFGR_PLLSRC ((uint32_t)0x00010000) /*!< PLL entry clock source */ + +#define RCC_CFGR_PLLXTPRE ((uint32_t)0x00020000) /*!< HSE divider for PLL entry */ + +/*!< PLLMUL configuration */ +#define RCC_CFGR_PLLMULL ((uint32_t)0x003C0000) /*!< PLLMUL[3:0] bits (PLL multiplication factor) */ +#define RCC_CFGR_PLLMULL_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define RCC_CFGR_PLLMULL_1 ((uint32_t)0x00080000) /*!< Bit 1 */ +#define RCC_CFGR_PLLMULL_2 ((uint32_t)0x00100000) /*!< Bit 2 */ +#define RCC_CFGR_PLLMULL_3 ((uint32_t)0x00200000) /*!< Bit 3 */ + +#ifdef STM32F10X_CL + #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ + #define RCC_CFGR_PLLSRC_PREDIV1 ((uint32_t)0x00010000) /*!< PREDIV1 clock selected as PLL entry clock source */ + + #define RCC_CFGR_PLLXTPRE_PREDIV1 ((uint32_t)0x00000000) /*!< PREDIV1 clock not divided for PLL entry */ + #define RCC_CFGR_PLLXTPRE_PREDIV1_Div2 ((uint32_t)0x00020000) /*!< PREDIV1 clock divided by 2 for PLL entry */ + + #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock * 4 */ + #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock * 5 */ + #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock * 6 */ + #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock * 7 */ + #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock * 8 */ + #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock * 9 */ + #define RCC_CFGR_PLLMULL6_5 ((uint32_t)0x00340000) /*!< PLL input clock * 6.5 */ + + #define RCC_CFGR_OTGFSPRE ((uint32_t)0x00400000) /*!< USB OTG FS prescaler */ + +/*!< MCO configuration */ + #define RCC_CFGR_MCO ((uint32_t)0x0F000000) /*!< MCO[3:0] bits (Microcontroller Clock Output) */ + #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ + #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + #define RCC_CFGR_MCO_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + + #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ + #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ + #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ + #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ + #define RCC_CFGR_MCO_PLLCLK_Div2 ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ + #define RCC_CFGR_MCO_PLL2CLK ((uint32_t)0x08000000) /*!< PLL2 clock selected as MCO source*/ + #define RCC_CFGR_MCO_PLL3CLK_Div2 ((uint32_t)0x09000000) /*!< PLL3 clock divided by 2 selected as MCO source*/ + #define RCC_CFGR_MCO_Ext_HSE ((uint32_t)0x0A000000) /*!< XT1 external 3-25 MHz oscillator clock selected as MCO source */ + #define RCC_CFGR_MCO_PLL3CLK ((uint32_t)0x0B000000) /*!< PLL3 clock selected as MCO source */ +#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ + #define RCC_CFGR_PLLSRC_PREDIV1 ((uint32_t)0x00010000) /*!< PREDIV1 clock selected as PLL entry clock source */ + + #define RCC_CFGR_PLLXTPRE_PREDIV1 ((uint32_t)0x00000000) /*!< PREDIV1 clock not divided for PLL entry */ + #define RCC_CFGR_PLLXTPRE_PREDIV1_Div2 ((uint32_t)0x00020000) /*!< PREDIV1 clock divided by 2 for PLL entry */ + + #define RCC_CFGR_PLLMULL2 ((uint32_t)0x00000000) /*!< PLL input clock*2 */ + #define RCC_CFGR_PLLMULL3 ((uint32_t)0x00040000) /*!< PLL input clock*3 */ + #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock*4 */ + #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock*5 */ + #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock*6 */ + #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock*7 */ + #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock*8 */ + #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock*9 */ + #define RCC_CFGR_PLLMULL10 ((uint32_t)0x00200000) /*!< PLL input clock10 */ + #define RCC_CFGR_PLLMULL11 ((uint32_t)0x00240000) /*!< PLL input clock*11 */ + #define RCC_CFGR_PLLMULL12 ((uint32_t)0x00280000) /*!< PLL input clock*12 */ + #define RCC_CFGR_PLLMULL13 ((uint32_t)0x002C0000) /*!< PLL input clock*13 */ + #define RCC_CFGR_PLLMULL14 ((uint32_t)0x00300000) /*!< PLL input clock*14 */ + #define RCC_CFGR_PLLMULL15 ((uint32_t)0x00340000) /*!< PLL input clock*15 */ + #define RCC_CFGR_PLLMULL16 ((uint32_t)0x00380000) /*!< PLL input clock*16 */ + +/*!< MCO configuration */ + #define RCC_CFGR_MCO ((uint32_t)0x07000000) /*!< MCO[2:0] bits (Microcontroller Clock Output) */ + #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ + #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + + #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ + #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ + #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ + #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ + #define RCC_CFGR_MCO_PLL ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ +#else + #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ + #define RCC_CFGR_PLLSRC_HSE ((uint32_t)0x00010000) /*!< HSE clock selected as PLL entry clock source */ + + #define RCC_CFGR_PLLXTPRE_HSE ((uint32_t)0x00000000) /*!< HSE clock not divided for PLL entry */ + #define RCC_CFGR_PLLXTPRE_HSE_Div2 ((uint32_t)0x00020000) /*!< HSE clock divided by 2 for PLL entry */ + + #define RCC_CFGR_PLLMULL2 ((uint32_t)0x00000000) /*!< PLL input clock*2 */ + #define RCC_CFGR_PLLMULL3 ((uint32_t)0x00040000) /*!< PLL input clock*3 */ + #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock*4 */ + #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock*5 */ + #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock*6 */ + #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock*7 */ + #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock*8 */ + #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock*9 */ + #define RCC_CFGR_PLLMULL10 ((uint32_t)0x00200000) /*!< PLL input clock10 */ + #define RCC_CFGR_PLLMULL11 ((uint32_t)0x00240000) /*!< PLL input clock*11 */ + #define RCC_CFGR_PLLMULL12 ((uint32_t)0x00280000) /*!< PLL input clock*12 */ + #define RCC_CFGR_PLLMULL13 ((uint32_t)0x002C0000) /*!< PLL input clock*13 */ + #define RCC_CFGR_PLLMULL14 ((uint32_t)0x00300000) /*!< PLL input clock*14 */ + #define RCC_CFGR_PLLMULL15 ((uint32_t)0x00340000) /*!< PLL input clock*15 */ + #define RCC_CFGR_PLLMULL16 ((uint32_t)0x00380000) /*!< PLL input clock*16 */ + #define RCC_CFGR_USBPRE ((uint32_t)0x00400000) /*!< USB Device prescaler */ + +/*!< MCO configuration */ + #define RCC_CFGR_MCO ((uint32_t)0x07000000) /*!< MCO[2:0] bits (Microcontroller Clock Output) */ + #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ + #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + + #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ + #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ + #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ + #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ + #define RCC_CFGR_MCO_PLL ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ +#endif /* STM32F10X_CL */ + +/*!<****************** Bit definition for RCC_CIR register ********************/ +#define RCC_CIR_LSIRDYF ((uint32_t)0x00000001) /*!< LSI Ready Interrupt flag */ +#define RCC_CIR_LSERDYF ((uint32_t)0x00000002) /*!< LSE Ready Interrupt flag */ +#define RCC_CIR_HSIRDYF ((uint32_t)0x00000004) /*!< HSI Ready Interrupt flag */ +#define RCC_CIR_HSERDYF ((uint32_t)0x00000008) /*!< HSE Ready Interrupt flag */ +#define RCC_CIR_PLLRDYF ((uint32_t)0x00000010) /*!< PLL Ready Interrupt flag */ +#define RCC_CIR_CSSF ((uint32_t)0x00000080) /*!< Clock Security System Interrupt flag */ +#define RCC_CIR_LSIRDYIE ((uint32_t)0x00000100) /*!< LSI Ready Interrupt Enable */ +#define RCC_CIR_LSERDYIE ((uint32_t)0x00000200) /*!< LSE Ready Interrupt Enable */ +#define RCC_CIR_HSIRDYIE ((uint32_t)0x00000400) /*!< HSI Ready Interrupt Enable */ +#define RCC_CIR_HSERDYIE ((uint32_t)0x00000800) /*!< HSE Ready Interrupt Enable */ +#define RCC_CIR_PLLRDYIE ((uint32_t)0x00001000) /*!< PLL Ready Interrupt Enable */ +#define RCC_CIR_LSIRDYC ((uint32_t)0x00010000) /*!< LSI Ready Interrupt Clear */ +#define RCC_CIR_LSERDYC ((uint32_t)0x00020000) /*!< LSE Ready Interrupt Clear */ +#define RCC_CIR_HSIRDYC ((uint32_t)0x00040000) /*!< HSI Ready Interrupt Clear */ +#define RCC_CIR_HSERDYC ((uint32_t)0x00080000) /*!< HSE Ready Interrupt Clear */ +#define RCC_CIR_PLLRDYC ((uint32_t)0x00100000) /*!< PLL Ready Interrupt Clear */ +#define RCC_CIR_CSSC ((uint32_t)0x00800000) /*!< Clock Security System Interrupt Clear */ + +#ifdef STM32F10X_CL + #define RCC_CIR_PLL2RDYF ((uint32_t)0x00000020) /*!< PLL2 Ready Interrupt flag */ + #define RCC_CIR_PLL3RDYF ((uint32_t)0x00000040) /*!< PLL3 Ready Interrupt flag */ + #define RCC_CIR_PLL2RDYIE ((uint32_t)0x00002000) /*!< PLL2 Ready Interrupt Enable */ + #define RCC_CIR_PLL3RDYIE ((uint32_t)0x00004000) /*!< PLL3 Ready Interrupt Enable */ + #define RCC_CIR_PLL2RDYC ((uint32_t)0x00200000) /*!< PLL2 Ready Interrupt Clear */ + #define RCC_CIR_PLL3RDYC ((uint32_t)0x00400000) /*!< PLL3 Ready Interrupt Clear */ +#endif /* STM32F10X_CL */ + +/***************** Bit definition for RCC_APB2RSTR register *****************/ +#define RCC_APB2RSTR_AFIORST ((uint32_t)0x00000001) /*!< Alternate Function I/O reset */ +#define RCC_APB2RSTR_IOPARST ((uint32_t)0x00000004) /*!< I/O port A reset */ +#define RCC_APB2RSTR_IOPBRST ((uint32_t)0x00000008) /*!< I/O port B reset */ +#define RCC_APB2RSTR_IOPCRST ((uint32_t)0x00000010) /*!< I/O port C reset */ +#define RCC_APB2RSTR_IOPDRST ((uint32_t)0x00000020) /*!< I/O port D reset */ +#define RCC_APB2RSTR_ADC1RST ((uint32_t)0x00000200) /*!< ADC 1 interface reset */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB2RSTR_ADC2RST ((uint32_t)0x00000400) /*!< ADC 2 interface reset */ +#endif + +#define RCC_APB2RSTR_TIM1RST ((uint32_t)0x00000800) /*!< TIM1 Timer reset */ +#define RCC_APB2RSTR_SPI1RST ((uint32_t)0x00001000) /*!< SPI 1 reset */ +#define RCC_APB2RSTR_USART1RST ((uint32_t)0x00004000) /*!< USART1 reset */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +#define RCC_APB2RSTR_TIM15RST ((uint32_t)0x00010000) /*!< TIM15 Timer reset */ +#define RCC_APB2RSTR_TIM16RST ((uint32_t)0x00020000) /*!< TIM16 Timer reset */ +#define RCC_APB2RSTR_TIM17RST ((uint32_t)0x00040000) /*!< TIM17 Timer reset */ +#endif + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB2RSTR_IOPERST ((uint32_t)0x00000040) /*!< I/O port E reset */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) + #define RCC_APB2RSTR_IOPFRST ((uint32_t)0x00000080) /*!< I/O port F reset */ + #define RCC_APB2RSTR_IOPGRST ((uint32_t)0x00000100) /*!< I/O port G reset */ + #define RCC_APB2RSTR_TIM8RST ((uint32_t)0x00002000) /*!< TIM8 Timer reset */ + #define RCC_APB2RSTR_ADC3RST ((uint32_t)0x00008000) /*!< ADC3 interface reset */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_APB2RSTR_IOPFRST ((uint32_t)0x00000080) /*!< I/O port F reset */ + #define RCC_APB2RSTR_IOPGRST ((uint32_t)0x00000100) /*!< I/O port G reset */ +#endif + +#ifdef STM32F10X_XL + #define RCC_APB2RSTR_TIM9RST ((uint32_t)0x00080000) /*!< TIM9 Timer reset */ + #define RCC_APB2RSTR_TIM10RST ((uint32_t)0x00100000) /*!< TIM10 Timer reset */ + #define RCC_APB2RSTR_TIM11RST ((uint32_t)0x00200000) /*!< TIM11 Timer reset */ +#endif /* STM32F10X_XL */ + +/***************** Bit definition for RCC_APB1RSTR register *****************/ +#define RCC_APB1RSTR_TIM2RST ((uint32_t)0x00000001) /*!< Timer 2 reset */ +#define RCC_APB1RSTR_TIM3RST ((uint32_t)0x00000002) /*!< Timer 3 reset */ +#define RCC_APB1RSTR_WWDGRST ((uint32_t)0x00000800) /*!< Window Watchdog reset */ +#define RCC_APB1RSTR_USART2RST ((uint32_t)0x00020000) /*!< USART 2 reset */ +#define RCC_APB1RSTR_I2C1RST ((uint32_t)0x00200000) /*!< I2C 1 reset */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB1RSTR_CAN1RST ((uint32_t)0x02000000) /*!< CAN1 reset */ +#endif + +#define RCC_APB1RSTR_BKPRST ((uint32_t)0x08000000) /*!< Backup interface reset */ +#define RCC_APB1RSTR_PWRRST ((uint32_t)0x10000000) /*!< Power interface reset */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB1RSTR_TIM4RST ((uint32_t)0x00000004) /*!< Timer 4 reset */ + #define RCC_APB1RSTR_SPI2RST ((uint32_t)0x00004000) /*!< SPI 2 reset */ + #define RCC_APB1RSTR_USART3RST ((uint32_t)0x00040000) /*!< RUSART 3 reset */ + #define RCC_APB1RSTR_I2C2RST ((uint32_t)0x00400000) /*!< I2C 2 reset */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_MD) || defined (STM32F10X_LD) || defined (STM32F10X_XL) + #define RCC_APB1RSTR_USBRST ((uint32_t)0x00800000) /*!< USB Device reset */ +#endif + +#if defined (STM32F10X_HD) || defined (STM32F10X_CL) || defined (STM32F10X_XL) + #define RCC_APB1RSTR_TIM5RST ((uint32_t)0x00000008) /*!< Timer 5 reset */ + #define RCC_APB1RSTR_TIM6RST ((uint32_t)0x00000010) /*!< Timer 6 reset */ + #define RCC_APB1RSTR_TIM7RST ((uint32_t)0x00000020) /*!< Timer 7 reset */ + #define RCC_APB1RSTR_SPI3RST ((uint32_t)0x00008000) /*!< SPI 3 reset */ + #define RCC_APB1RSTR_UART4RST ((uint32_t)0x00080000) /*!< UART 4 reset */ + #define RCC_APB1RSTR_UART5RST ((uint32_t)0x00100000) /*!< UART 5 reset */ + #define RCC_APB1RSTR_DACRST ((uint32_t)0x20000000) /*!< DAC interface reset */ +#endif + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + #define RCC_APB1RSTR_TIM6RST ((uint32_t)0x00000010) /*!< Timer 6 reset */ + #define RCC_APB1RSTR_TIM7RST ((uint32_t)0x00000020) /*!< Timer 7 reset */ + #define RCC_APB1RSTR_DACRST ((uint32_t)0x20000000) /*!< DAC interface reset */ + #define RCC_APB1RSTR_CECRST ((uint32_t)0x40000000) /*!< CEC interface reset */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_APB1RSTR_TIM5RST ((uint32_t)0x00000008) /*!< Timer 5 reset */ + #define RCC_APB1RSTR_TIM12RST ((uint32_t)0x00000040) /*!< TIM12 Timer reset */ + #define RCC_APB1RSTR_TIM13RST ((uint32_t)0x00000080) /*!< TIM13 Timer reset */ + #define RCC_APB1RSTR_TIM14RST ((uint32_t)0x00000100) /*!< TIM14 Timer reset */ + #define RCC_APB1RSTR_SPI3RST ((uint32_t)0x00008000) /*!< SPI 3 reset */ + #define RCC_APB1RSTR_UART4RST ((uint32_t)0x00080000) /*!< UART 4 reset */ + #define RCC_APB1RSTR_UART5RST ((uint32_t)0x00100000) /*!< UART 5 reset */ +#endif + +#ifdef STM32F10X_CL + #define RCC_APB1RSTR_CAN2RST ((uint32_t)0x04000000) /*!< CAN2 reset */ +#endif /* STM32F10X_CL */ + +#ifdef STM32F10X_XL + #define RCC_APB1RSTR_TIM12RST ((uint32_t)0x00000040) /*!< TIM12 Timer reset */ + #define RCC_APB1RSTR_TIM13RST ((uint32_t)0x00000080) /*!< TIM13 Timer reset */ + #define RCC_APB1RSTR_TIM14RST ((uint32_t)0x00000100) /*!< TIM14 Timer reset */ +#endif /* STM32F10X_XL */ + +/****************** Bit definition for RCC_AHBENR register ******************/ +#define RCC_AHBENR_DMA1EN ((uint16_t)0x0001) /*!< DMA1 clock enable */ +#define RCC_AHBENR_SRAMEN ((uint16_t)0x0004) /*!< SRAM interface clock enable */ +#define RCC_AHBENR_FLITFEN ((uint16_t)0x0010) /*!< FLITF clock enable */ +#define RCC_AHBENR_CRCEN ((uint16_t)0x0040) /*!< CRC clock enable */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_CL) || defined (STM32F10X_HD_VL) + #define RCC_AHBENR_DMA2EN ((uint16_t)0x0002) /*!< DMA2 clock enable */ +#endif + +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) + #define RCC_AHBENR_FSMCEN ((uint16_t)0x0100) /*!< FSMC clock enable */ + #define RCC_AHBENR_SDIOEN ((uint16_t)0x0400) /*!< SDIO clock enable */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_AHBENR_FSMCEN ((uint16_t)0x0100) /*!< FSMC clock enable */ +#endif + +#ifdef STM32F10X_CL + #define RCC_AHBENR_OTGFSEN ((uint32_t)0x00001000) /*!< USB OTG FS clock enable */ + #define RCC_AHBENR_ETHMACEN ((uint32_t)0x00004000) /*!< ETHERNET MAC clock enable */ + #define RCC_AHBENR_ETHMACTXEN ((uint32_t)0x00008000) /*!< ETHERNET MAC Tx clock enable */ + #define RCC_AHBENR_ETHMACRXEN ((uint32_t)0x00010000) /*!< ETHERNET MAC Rx clock enable */ +#endif /* STM32F10X_CL */ + +/****************** Bit definition for RCC_APB2ENR register *****************/ +#define RCC_APB2ENR_AFIOEN ((uint32_t)0x00000001) /*!< Alternate Function I/O clock enable */ +#define RCC_APB2ENR_IOPAEN ((uint32_t)0x00000004) /*!< I/O port A clock enable */ +#define RCC_APB2ENR_IOPBEN ((uint32_t)0x00000008) /*!< I/O port B clock enable */ +#define RCC_APB2ENR_IOPCEN ((uint32_t)0x00000010) /*!< I/O port C clock enable */ +#define RCC_APB2ENR_IOPDEN ((uint32_t)0x00000020) /*!< I/O port D clock enable */ +#define RCC_APB2ENR_ADC1EN ((uint32_t)0x00000200) /*!< ADC 1 interface clock enable */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB2ENR_ADC2EN ((uint32_t)0x00000400) /*!< ADC 2 interface clock enable */ +#endif + +#define RCC_APB2ENR_TIM1EN ((uint32_t)0x00000800) /*!< TIM1 Timer clock enable */ +#define RCC_APB2ENR_SPI1EN ((uint32_t)0x00001000) /*!< SPI 1 clock enable */ +#define RCC_APB2ENR_USART1EN ((uint32_t)0x00004000) /*!< USART1 clock enable */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +#define RCC_APB2ENR_TIM15EN ((uint32_t)0x00010000) /*!< TIM15 Timer clock enable */ +#define RCC_APB2ENR_TIM16EN ((uint32_t)0x00020000) /*!< TIM16 Timer clock enable */ +#define RCC_APB2ENR_TIM17EN ((uint32_t)0x00040000) /*!< TIM17 Timer clock enable */ +#endif + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB2ENR_IOPEEN ((uint32_t)0x00000040) /*!< I/O port E clock enable */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) + #define RCC_APB2ENR_IOPFEN ((uint32_t)0x00000080) /*!< I/O port F clock enable */ + #define RCC_APB2ENR_IOPGEN ((uint32_t)0x00000100) /*!< I/O port G clock enable */ + #define RCC_APB2ENR_TIM8EN ((uint32_t)0x00002000) /*!< TIM8 Timer clock enable */ + #define RCC_APB2ENR_ADC3EN ((uint32_t)0x00008000) /*!< DMA1 clock enable */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_APB2ENR_IOPFEN ((uint32_t)0x00000080) /*!< I/O port F clock enable */ + #define RCC_APB2ENR_IOPGEN ((uint32_t)0x00000100) /*!< I/O port G clock enable */ +#endif + +#ifdef STM32F10X_XL + #define RCC_APB2ENR_TIM9EN ((uint32_t)0x00080000) /*!< TIM9 Timer clock enable */ + #define RCC_APB2ENR_TIM10EN ((uint32_t)0x00100000) /*!< TIM10 Timer clock enable */ + #define RCC_APB2ENR_TIM11EN ((uint32_t)0x00200000) /*!< TIM11 Timer clock enable */ +#endif + +/***************** Bit definition for RCC_APB1ENR register ******************/ +#define RCC_APB1ENR_TIM2EN ((uint32_t)0x00000001) /*!< Timer 2 clock enabled*/ +#define RCC_APB1ENR_TIM3EN ((uint32_t)0x00000002) /*!< Timer 3 clock enable */ +#define RCC_APB1ENR_WWDGEN ((uint32_t)0x00000800) /*!< Window Watchdog clock enable */ +#define RCC_APB1ENR_USART2EN ((uint32_t)0x00020000) /*!< USART 2 clock enable */ +#define RCC_APB1ENR_I2C1EN ((uint32_t)0x00200000) /*!< I2C 1 clock enable */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB1ENR_CAN1EN ((uint32_t)0x02000000) /*!< CAN1 clock enable */ +#endif + +#define RCC_APB1ENR_BKPEN ((uint32_t)0x08000000) /*!< Backup interface clock enable */ +#define RCC_APB1ENR_PWREN ((uint32_t)0x10000000) /*!< Power interface clock enable */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB1ENR_TIM4EN ((uint32_t)0x00000004) /*!< Timer 4 clock enable */ + #define RCC_APB1ENR_SPI2EN ((uint32_t)0x00004000) /*!< SPI 2 clock enable */ + #define RCC_APB1ENR_USART3EN ((uint32_t)0x00040000) /*!< USART 3 clock enable */ + #define RCC_APB1ENR_I2C2EN ((uint32_t)0x00400000) /*!< I2C 2 clock enable */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_MD) || defined (STM32F10X_LD) + #define RCC_APB1ENR_USBEN ((uint32_t)0x00800000) /*!< USB Device clock enable */ +#endif + +#if defined (STM32F10X_HD) || defined (STM32F10X_CL) + #define RCC_APB1ENR_TIM5EN ((uint32_t)0x00000008) /*!< Timer 5 clock enable */ + #define RCC_APB1ENR_TIM6EN ((uint32_t)0x00000010) /*!< Timer 6 clock enable */ + #define RCC_APB1ENR_TIM7EN ((uint32_t)0x00000020) /*!< Timer 7 clock enable */ + #define RCC_APB1ENR_SPI3EN ((uint32_t)0x00008000) /*!< SPI 3 clock enable */ + #define RCC_APB1ENR_UART4EN ((uint32_t)0x00080000) /*!< UART 4 clock enable */ + #define RCC_APB1ENR_UART5EN ((uint32_t)0x00100000) /*!< UART 5 clock enable */ + #define RCC_APB1ENR_DACEN ((uint32_t)0x20000000) /*!< DAC interface clock enable */ +#endif + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + #define RCC_APB1ENR_TIM6EN ((uint32_t)0x00000010) /*!< Timer 6 clock enable */ + #define RCC_APB1ENR_TIM7EN ((uint32_t)0x00000020) /*!< Timer 7 clock enable */ + #define RCC_APB1ENR_DACEN ((uint32_t)0x20000000) /*!< DAC interface clock enable */ + #define RCC_APB1ENR_CECEN ((uint32_t)0x40000000) /*!< CEC interface clock enable */ +#endif + +#ifdef STM32F10X_HD_VL + #define RCC_APB1ENR_TIM5EN ((uint32_t)0x00000008) /*!< Timer 5 clock enable */ + #define RCC_APB1ENR_TIM12EN ((uint32_t)0x00000040) /*!< TIM12 Timer clock enable */ + #define RCC_APB1ENR_TIM13EN ((uint32_t)0x00000080) /*!< TIM13 Timer clock enable */ + #define RCC_APB1ENR_TIM14EN ((uint32_t)0x00000100) /*!< TIM14 Timer clock enable */ + #define RCC_APB1ENR_SPI3EN ((uint32_t)0x00008000) /*!< SPI 3 clock enable */ + #define RCC_APB1ENR_UART4EN ((uint32_t)0x00080000) /*!< UART 4 clock enable */ + #define RCC_APB1ENR_UART5EN ((uint32_t)0x00100000) /*!< UART 5 clock enable */ +#endif /* STM32F10X_HD_VL */ + +#ifdef STM32F10X_CL + #define RCC_APB1ENR_CAN2EN ((uint32_t)0x04000000) /*!< CAN2 clock enable */ +#endif /* STM32F10X_CL */ + +#ifdef STM32F10X_XL + #define RCC_APB1ENR_TIM12EN ((uint32_t)0x00000040) /*!< TIM12 Timer clock enable */ + #define RCC_APB1ENR_TIM13EN ((uint32_t)0x00000080) /*!< TIM13 Timer clock enable */ + #define RCC_APB1ENR_TIM14EN ((uint32_t)0x00000100) /*!< TIM14 Timer clock enable */ +#endif /* STM32F10X_XL */ + +/******************* Bit definition for RCC_BDCR register *******************/ +#define RCC_BDCR_LSEON ((uint32_t)0x00000001) /*!< External Low Speed oscillator enable */ +#define RCC_BDCR_LSERDY ((uint32_t)0x00000002) /*!< External Low Speed oscillator Ready */ +#define RCC_BDCR_LSEBYP ((uint32_t)0x00000004) /*!< External Low Speed oscillator Bypass */ + +#define RCC_BDCR_RTCSEL ((uint32_t)0x00000300) /*!< RTCSEL[1:0] bits (RTC clock source selection) */ +#define RCC_BDCR_RTCSEL_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define RCC_BDCR_RTCSEL_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +/*!< RTC congiguration */ +#define RCC_BDCR_RTCSEL_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ +#define RCC_BDCR_RTCSEL_LSE ((uint32_t)0x00000100) /*!< LSE oscillator clock used as RTC clock */ +#define RCC_BDCR_RTCSEL_LSI ((uint32_t)0x00000200) /*!< LSI oscillator clock used as RTC clock */ +#define RCC_BDCR_RTCSEL_HSE ((uint32_t)0x00000300) /*!< HSE oscillator clock divided by 128 used as RTC clock */ + +#define RCC_BDCR_RTCEN ((uint32_t)0x00008000) /*!< RTC clock enable */ +#define RCC_BDCR_BDRST ((uint32_t)0x00010000) /*!< Backup domain software reset */ + +/******************* Bit definition for RCC_CSR register ********************/ +#define RCC_CSR_LSION ((uint32_t)0x00000001) /*!< Internal Low Speed oscillator enable */ +#define RCC_CSR_LSIRDY ((uint32_t)0x00000002) /*!< Internal Low Speed oscillator Ready */ +#define RCC_CSR_RMVF ((uint32_t)0x01000000) /*!< Remove reset flag */ +#define RCC_CSR_PINRSTF ((uint32_t)0x04000000) /*!< PIN reset flag */ +#define RCC_CSR_PORRSTF ((uint32_t)0x08000000) /*!< POR/PDR reset flag */ +#define RCC_CSR_SFTRSTF ((uint32_t)0x10000000) /*!< Software Reset flag */ +#define RCC_CSR_IWDGRSTF ((uint32_t)0x20000000) /*!< Independent Watchdog reset flag */ +#define RCC_CSR_WWDGRSTF ((uint32_t)0x40000000) /*!< Window watchdog reset flag */ +#define RCC_CSR_LPWRRSTF ((uint32_t)0x80000000) /*!< Low-Power reset flag */ + +#ifdef STM32F10X_CL +/******************* Bit definition for RCC_AHBRSTR register ****************/ + #define RCC_AHBRSTR_OTGFSRST ((uint32_t)0x00001000) /*!< USB OTG FS reset */ + #define RCC_AHBRSTR_ETHMACRST ((uint32_t)0x00004000) /*!< ETHERNET MAC reset */ + +/******************* Bit definition for RCC_CFGR2 register ******************/ +/*!< PREDIV1 configuration */ + #define RCC_CFGR2_PREDIV1 ((uint32_t)0x0000000F) /*!< PREDIV1[3:0] bits */ + #define RCC_CFGR2_PREDIV1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ + #define RCC_CFGR2_PREDIV1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + #define RCC_CFGR2_PREDIV1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ + #define RCC_CFGR2_PREDIV1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + + #define RCC_CFGR2_PREDIV1_DIV1 ((uint32_t)0x00000000) /*!< PREDIV1 input clock not divided */ + #define RCC_CFGR2_PREDIV1_DIV2 ((uint32_t)0x00000001) /*!< PREDIV1 input clock divided by 2 */ + #define RCC_CFGR2_PREDIV1_DIV3 ((uint32_t)0x00000002) /*!< PREDIV1 input clock divided by 3 */ + #define RCC_CFGR2_PREDIV1_DIV4 ((uint32_t)0x00000003) /*!< PREDIV1 input clock divided by 4 */ + #define RCC_CFGR2_PREDIV1_DIV5 ((uint32_t)0x00000004) /*!< PREDIV1 input clock divided by 5 */ + #define RCC_CFGR2_PREDIV1_DIV6 ((uint32_t)0x00000005) /*!< PREDIV1 input clock divided by 6 */ + #define RCC_CFGR2_PREDIV1_DIV7 ((uint32_t)0x00000006) /*!< PREDIV1 input clock divided by 7 */ + #define RCC_CFGR2_PREDIV1_DIV8 ((uint32_t)0x00000007) /*!< PREDIV1 input clock divided by 8 */ + #define RCC_CFGR2_PREDIV1_DIV9 ((uint32_t)0x00000008) /*!< PREDIV1 input clock divided by 9 */ + #define RCC_CFGR2_PREDIV1_DIV10 ((uint32_t)0x00000009) /*!< PREDIV1 input clock divided by 10 */ + #define RCC_CFGR2_PREDIV1_DIV11 ((uint32_t)0x0000000A) /*!< PREDIV1 input clock divided by 11 */ + #define RCC_CFGR2_PREDIV1_DIV12 ((uint32_t)0x0000000B) /*!< PREDIV1 input clock divided by 12 */ + #define RCC_CFGR2_PREDIV1_DIV13 ((uint32_t)0x0000000C) /*!< PREDIV1 input clock divided by 13 */ + #define RCC_CFGR2_PREDIV1_DIV14 ((uint32_t)0x0000000D) /*!< PREDIV1 input clock divided by 14 */ + #define RCC_CFGR2_PREDIV1_DIV15 ((uint32_t)0x0000000E) /*!< PREDIV1 input clock divided by 15 */ + #define RCC_CFGR2_PREDIV1_DIV16 ((uint32_t)0x0000000F) /*!< PREDIV1 input clock divided by 16 */ + +/*!< PREDIV2 configuration */ + #define RCC_CFGR2_PREDIV2 ((uint32_t)0x000000F0) /*!< PREDIV2[3:0] bits */ + #define RCC_CFGR2_PREDIV2_0 ((uint32_t)0x00000010) /*!< Bit 0 */ + #define RCC_CFGR2_PREDIV2_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + #define RCC_CFGR2_PREDIV2_2 ((uint32_t)0x00000040) /*!< Bit 2 */ + #define RCC_CFGR2_PREDIV2_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + + #define RCC_CFGR2_PREDIV2_DIV1 ((uint32_t)0x00000000) /*!< PREDIV2 input clock not divided */ + #define RCC_CFGR2_PREDIV2_DIV2 ((uint32_t)0x00000010) /*!< PREDIV2 input clock divided by 2 */ + #define RCC_CFGR2_PREDIV2_DIV3 ((uint32_t)0x00000020) /*!< PREDIV2 input clock divided by 3 */ + #define RCC_CFGR2_PREDIV2_DIV4 ((uint32_t)0x00000030) /*!< PREDIV2 input clock divided by 4 */ + #define RCC_CFGR2_PREDIV2_DIV5 ((uint32_t)0x00000040) /*!< PREDIV2 input clock divided by 5 */ + #define RCC_CFGR2_PREDIV2_DIV6 ((uint32_t)0x00000050) /*!< PREDIV2 input clock divided by 6 */ + #define RCC_CFGR2_PREDIV2_DIV7 ((uint32_t)0x00000060) /*!< PREDIV2 input clock divided by 7 */ + #define RCC_CFGR2_PREDIV2_DIV8 ((uint32_t)0x00000070) /*!< PREDIV2 input clock divided by 8 */ + #define RCC_CFGR2_PREDIV2_DIV9 ((uint32_t)0x00000080) /*!< PREDIV2 input clock divided by 9 */ + #define RCC_CFGR2_PREDIV2_DIV10 ((uint32_t)0x00000090) /*!< PREDIV2 input clock divided by 10 */ + #define RCC_CFGR2_PREDIV2_DIV11 ((uint32_t)0x000000A0) /*!< PREDIV2 input clock divided by 11 */ + #define RCC_CFGR2_PREDIV2_DIV12 ((uint32_t)0x000000B0) /*!< PREDIV2 input clock divided by 12 */ + #define RCC_CFGR2_PREDIV2_DIV13 ((uint32_t)0x000000C0) /*!< PREDIV2 input clock divided by 13 */ + #define RCC_CFGR2_PREDIV2_DIV14 ((uint32_t)0x000000D0) /*!< PREDIV2 input clock divided by 14 */ + #define RCC_CFGR2_PREDIV2_DIV15 ((uint32_t)0x000000E0) /*!< PREDIV2 input clock divided by 15 */ + #define RCC_CFGR2_PREDIV2_DIV16 ((uint32_t)0x000000F0) /*!< PREDIV2 input clock divided by 16 */ + +/*!< PLL2MUL configuration */ + #define RCC_CFGR2_PLL2MUL ((uint32_t)0x00000F00) /*!< PLL2MUL[3:0] bits */ + #define RCC_CFGR2_PLL2MUL_0 ((uint32_t)0x00000100) /*!< Bit 0 */ + #define RCC_CFGR2_PLL2MUL_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + #define RCC_CFGR2_PLL2MUL_2 ((uint32_t)0x00000400) /*!< Bit 2 */ + #define RCC_CFGR2_PLL2MUL_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + + #define RCC_CFGR2_PLL2MUL8 ((uint32_t)0x00000600) /*!< PLL2 input clock * 8 */ + #define RCC_CFGR2_PLL2MUL9 ((uint32_t)0x00000700) /*!< PLL2 input clock * 9 */ + #define RCC_CFGR2_PLL2MUL10 ((uint32_t)0x00000800) /*!< PLL2 input clock * 10 */ + #define RCC_CFGR2_PLL2MUL11 ((uint32_t)0x00000900) /*!< PLL2 input clock * 11 */ + #define RCC_CFGR2_PLL2MUL12 ((uint32_t)0x00000A00) /*!< PLL2 input clock * 12 */ + #define RCC_CFGR2_PLL2MUL13 ((uint32_t)0x00000B00) /*!< PLL2 input clock * 13 */ + #define RCC_CFGR2_PLL2MUL14 ((uint32_t)0x00000C00) /*!< PLL2 input clock * 14 */ + #define RCC_CFGR2_PLL2MUL16 ((uint32_t)0x00000E00) /*!< PLL2 input clock * 16 */ + #define RCC_CFGR2_PLL2MUL20 ((uint32_t)0x00000F00) /*!< PLL2 input clock * 20 */ + +/*!< PLL3MUL configuration */ + #define RCC_CFGR2_PLL3MUL ((uint32_t)0x0000F000) /*!< PLL3MUL[3:0] bits */ + #define RCC_CFGR2_PLL3MUL_0 ((uint32_t)0x00001000) /*!< Bit 0 */ + #define RCC_CFGR2_PLL3MUL_1 ((uint32_t)0x00002000) /*!< Bit 1 */ + #define RCC_CFGR2_PLL3MUL_2 ((uint32_t)0x00004000) /*!< Bit 2 */ + #define RCC_CFGR2_PLL3MUL_3 ((uint32_t)0x00008000) /*!< Bit 3 */ + + #define RCC_CFGR2_PLL3MUL8 ((uint32_t)0x00006000) /*!< PLL3 input clock * 8 */ + #define RCC_CFGR2_PLL3MUL9 ((uint32_t)0x00007000) /*!< PLL3 input clock * 9 */ + #define RCC_CFGR2_PLL3MUL10 ((uint32_t)0x00008000) /*!< PLL3 input clock * 10 */ + #define RCC_CFGR2_PLL3MUL11 ((uint32_t)0x00009000) /*!< PLL3 input clock * 11 */ + #define RCC_CFGR2_PLL3MUL12 ((uint32_t)0x0000A000) /*!< PLL3 input clock * 12 */ + #define RCC_CFGR2_PLL3MUL13 ((uint32_t)0x0000B000) /*!< PLL3 input clock * 13 */ + #define RCC_CFGR2_PLL3MUL14 ((uint32_t)0x0000C000) /*!< PLL3 input clock * 14 */ + #define RCC_CFGR2_PLL3MUL16 ((uint32_t)0x0000E000) /*!< PLL3 input clock * 16 */ + #define RCC_CFGR2_PLL3MUL20 ((uint32_t)0x0000F000) /*!< PLL3 input clock * 20 */ + + #define RCC_CFGR2_PREDIV1SRC ((uint32_t)0x00010000) /*!< PREDIV1 entry clock source */ + #define RCC_CFGR2_PREDIV1SRC_PLL2 ((uint32_t)0x00010000) /*!< PLL2 selected as PREDIV1 entry clock source */ + #define RCC_CFGR2_PREDIV1SRC_HSE ((uint32_t)0x00000000) /*!< HSE selected as PREDIV1 entry clock source */ + #define RCC_CFGR2_I2S2SRC ((uint32_t)0x00020000) /*!< I2S2 entry clock source */ + #define RCC_CFGR2_I2S3SRC ((uint32_t)0x00040000) /*!< I2S3 clock source */ +#endif /* STM32F10X_CL */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/******************* Bit definition for RCC_CFGR2 register ******************/ +/*!< PREDIV1 configuration */ + #define RCC_CFGR2_PREDIV1 ((uint32_t)0x0000000F) /*!< PREDIV1[3:0] bits */ + #define RCC_CFGR2_PREDIV1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ + #define RCC_CFGR2_PREDIV1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + #define RCC_CFGR2_PREDIV1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ + #define RCC_CFGR2_PREDIV1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + + #define RCC_CFGR2_PREDIV1_DIV1 ((uint32_t)0x00000000) /*!< PREDIV1 input clock not divided */ + #define RCC_CFGR2_PREDIV1_DIV2 ((uint32_t)0x00000001) /*!< PREDIV1 input clock divided by 2 */ + #define RCC_CFGR2_PREDIV1_DIV3 ((uint32_t)0x00000002) /*!< PREDIV1 input clock divided by 3 */ + #define RCC_CFGR2_PREDIV1_DIV4 ((uint32_t)0x00000003) /*!< PREDIV1 input clock divided by 4 */ + #define RCC_CFGR2_PREDIV1_DIV5 ((uint32_t)0x00000004) /*!< PREDIV1 input clock divided by 5 */ + #define RCC_CFGR2_PREDIV1_DIV6 ((uint32_t)0x00000005) /*!< PREDIV1 input clock divided by 6 */ + #define RCC_CFGR2_PREDIV1_DIV7 ((uint32_t)0x00000006) /*!< PREDIV1 input clock divided by 7 */ + #define RCC_CFGR2_PREDIV1_DIV8 ((uint32_t)0x00000007) /*!< PREDIV1 input clock divided by 8 */ + #define RCC_CFGR2_PREDIV1_DIV9 ((uint32_t)0x00000008) /*!< PREDIV1 input clock divided by 9 */ + #define RCC_CFGR2_PREDIV1_DIV10 ((uint32_t)0x00000009) /*!< PREDIV1 input clock divided by 10 */ + #define RCC_CFGR2_PREDIV1_DIV11 ((uint32_t)0x0000000A) /*!< PREDIV1 input clock divided by 11 */ + #define RCC_CFGR2_PREDIV1_DIV12 ((uint32_t)0x0000000B) /*!< PREDIV1 input clock divided by 12 */ + #define RCC_CFGR2_PREDIV1_DIV13 ((uint32_t)0x0000000C) /*!< PREDIV1 input clock divided by 13 */ + #define RCC_CFGR2_PREDIV1_DIV14 ((uint32_t)0x0000000D) /*!< PREDIV1 input clock divided by 14 */ + #define RCC_CFGR2_PREDIV1_DIV15 ((uint32_t)0x0000000E) /*!< PREDIV1 input clock divided by 15 */ + #define RCC_CFGR2_PREDIV1_DIV16 ((uint32_t)0x0000000F) /*!< PREDIV1 input clock divided by 16 */ +#endif + +/******************************************************************************/ +/* */ +/* General Purpose and Alternate Function I/O */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for GPIO_CRL register *******************/ +#define GPIO_CRL_MODE ((uint32_t)0x33333333) /*!< Port x mode bits */ + +#define GPIO_CRL_MODE0 ((uint32_t)0x00000003) /*!< MODE0[1:0] bits (Port x mode bits, pin 0) */ +#define GPIO_CRL_MODE0_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define GPIO_CRL_MODE0_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + +#define GPIO_CRL_MODE1 ((uint32_t)0x00000030) /*!< MODE1[1:0] bits (Port x mode bits, pin 1) */ +#define GPIO_CRL_MODE1_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define GPIO_CRL_MODE1_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define GPIO_CRL_MODE2 ((uint32_t)0x00000300) /*!< MODE2[1:0] bits (Port x mode bits, pin 2) */ +#define GPIO_CRL_MODE2_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define GPIO_CRL_MODE2_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +#define GPIO_CRL_MODE3 ((uint32_t)0x00003000) /*!< MODE3[1:0] bits (Port x mode bits, pin 3) */ +#define GPIO_CRL_MODE3_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define GPIO_CRL_MODE3_1 ((uint32_t)0x00002000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE4 ((uint32_t)0x00030000) /*!< MODE4[1:0] bits (Port x mode bits, pin 4) */ +#define GPIO_CRL_MODE4_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define GPIO_CRL_MODE4_1 ((uint32_t)0x00020000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE5 ((uint32_t)0x00300000) /*!< MODE5[1:0] bits (Port x mode bits, pin 5) */ +#define GPIO_CRL_MODE5_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define GPIO_CRL_MODE5_1 ((uint32_t)0x00200000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE6 ((uint32_t)0x03000000) /*!< MODE6[1:0] bits (Port x mode bits, pin 6) */ +#define GPIO_CRL_MODE6_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define GPIO_CRL_MODE6_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE7 ((uint32_t)0x30000000) /*!< MODE7[1:0] bits (Port x mode bits, pin 7) */ +#define GPIO_CRL_MODE7_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define GPIO_CRL_MODE7_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF ((uint32_t)0xCCCCCCCC) /*!< Port x configuration bits */ + +#define GPIO_CRL_CNF0 ((uint32_t)0x0000000C) /*!< CNF0[1:0] bits (Port x configuration bits, pin 0) */ +#define GPIO_CRL_CNF0_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define GPIO_CRL_CNF0_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define GPIO_CRL_CNF1 ((uint32_t)0x000000C0) /*!< CNF1[1:0] bits (Port x configuration bits, pin 1) */ +#define GPIO_CRL_CNF1_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define GPIO_CRL_CNF1_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +#define GPIO_CRL_CNF2 ((uint32_t)0x00000C00) /*!< CNF2[1:0] bits (Port x configuration bits, pin 2) */ +#define GPIO_CRL_CNF2_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define GPIO_CRL_CNF2_1 ((uint32_t)0x00000800) /*!< Bit 1 */ + +#define GPIO_CRL_CNF3 ((uint32_t)0x0000C000) /*!< CNF3[1:0] bits (Port x configuration bits, pin 3) */ +#define GPIO_CRL_CNF3_0 ((uint32_t)0x00004000) /*!< Bit 0 */ +#define GPIO_CRL_CNF3_1 ((uint32_t)0x00008000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF4 ((uint32_t)0x000C0000) /*!< CNF4[1:0] bits (Port x configuration bits, pin 4) */ +#define GPIO_CRL_CNF4_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define GPIO_CRL_CNF4_1 ((uint32_t)0x00080000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF5 ((uint32_t)0x00C00000) /*!< CNF5[1:0] bits (Port x configuration bits, pin 5) */ +#define GPIO_CRL_CNF5_0 ((uint32_t)0x00400000) /*!< Bit 0 */ +#define GPIO_CRL_CNF5_1 ((uint32_t)0x00800000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF6 ((uint32_t)0x0C000000) /*!< CNF6[1:0] bits (Port x configuration bits, pin 6) */ +#define GPIO_CRL_CNF6_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define GPIO_CRL_CNF6_1 ((uint32_t)0x08000000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF7 ((uint32_t)0xC0000000) /*!< CNF7[1:0] bits (Port x configuration bits, pin 7) */ +#define GPIO_CRL_CNF7_0 ((uint32_t)0x40000000) /*!< Bit 0 */ +#define GPIO_CRL_CNF7_1 ((uint32_t)0x80000000) /*!< Bit 1 */ + +/******************* Bit definition for GPIO_CRH register *******************/ +#define GPIO_CRH_MODE ((uint32_t)0x33333333) /*!< Port x mode bits */ + +#define GPIO_CRH_MODE8 ((uint32_t)0x00000003) /*!< MODE8[1:0] bits (Port x mode bits, pin 8) */ +#define GPIO_CRH_MODE8_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define GPIO_CRH_MODE8_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + +#define GPIO_CRH_MODE9 ((uint32_t)0x00000030) /*!< MODE9[1:0] bits (Port x mode bits, pin 9) */ +#define GPIO_CRH_MODE9_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define GPIO_CRH_MODE9_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define GPIO_CRH_MODE10 ((uint32_t)0x00000300) /*!< MODE10[1:0] bits (Port x mode bits, pin 10) */ +#define GPIO_CRH_MODE10_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define GPIO_CRH_MODE10_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +#define GPIO_CRH_MODE11 ((uint32_t)0x00003000) /*!< MODE11[1:0] bits (Port x mode bits, pin 11) */ +#define GPIO_CRH_MODE11_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define GPIO_CRH_MODE11_1 ((uint32_t)0x00002000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE12 ((uint32_t)0x00030000) /*!< MODE12[1:0] bits (Port x mode bits, pin 12) */ +#define GPIO_CRH_MODE12_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define GPIO_CRH_MODE12_1 ((uint32_t)0x00020000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE13 ((uint32_t)0x00300000) /*!< MODE13[1:0] bits (Port x mode bits, pin 13) */ +#define GPIO_CRH_MODE13_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define GPIO_CRH_MODE13_1 ((uint32_t)0x00200000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE14 ((uint32_t)0x03000000) /*!< MODE14[1:0] bits (Port x mode bits, pin 14) */ +#define GPIO_CRH_MODE14_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define GPIO_CRH_MODE14_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE15 ((uint32_t)0x30000000) /*!< MODE15[1:0] bits (Port x mode bits, pin 15) */ +#define GPIO_CRH_MODE15_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define GPIO_CRH_MODE15_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF ((uint32_t)0xCCCCCCCC) /*!< Port x configuration bits */ + +#define GPIO_CRH_CNF8 ((uint32_t)0x0000000C) /*!< CNF8[1:0] bits (Port x configuration bits, pin 8) */ +#define GPIO_CRH_CNF8_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define GPIO_CRH_CNF8_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define GPIO_CRH_CNF9 ((uint32_t)0x000000C0) /*!< CNF9[1:0] bits (Port x configuration bits, pin 9) */ +#define GPIO_CRH_CNF9_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define GPIO_CRH_CNF9_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +#define GPIO_CRH_CNF10 ((uint32_t)0x00000C00) /*!< CNF10[1:0] bits (Port x configuration bits, pin 10) */ +#define GPIO_CRH_CNF10_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define GPIO_CRH_CNF10_1 ((uint32_t)0x00000800) /*!< Bit 1 */ + +#define GPIO_CRH_CNF11 ((uint32_t)0x0000C000) /*!< CNF11[1:0] bits (Port x configuration bits, pin 11) */ +#define GPIO_CRH_CNF11_0 ((uint32_t)0x00004000) /*!< Bit 0 */ +#define GPIO_CRH_CNF11_1 ((uint32_t)0x00008000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF12 ((uint32_t)0x000C0000) /*!< CNF12[1:0] bits (Port x configuration bits, pin 12) */ +#define GPIO_CRH_CNF12_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define GPIO_CRH_CNF12_1 ((uint32_t)0x00080000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF13 ((uint32_t)0x00C00000) /*!< CNF13[1:0] bits (Port x configuration bits, pin 13) */ +#define GPIO_CRH_CNF13_0 ((uint32_t)0x00400000) /*!< Bit 0 */ +#define GPIO_CRH_CNF13_1 ((uint32_t)0x00800000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF14 ((uint32_t)0x0C000000) /*!< CNF14[1:0] bits (Port x configuration bits, pin 14) */ +#define GPIO_CRH_CNF14_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define GPIO_CRH_CNF14_1 ((uint32_t)0x08000000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF15 ((uint32_t)0xC0000000) /*!< CNF15[1:0] bits (Port x configuration bits, pin 15) */ +#define GPIO_CRH_CNF15_0 ((uint32_t)0x40000000) /*!< Bit 0 */ +#define GPIO_CRH_CNF15_1 ((uint32_t)0x80000000) /*!< Bit 1 */ + +/*!<****************** Bit definition for GPIO_IDR register *******************/ +#define GPIO_IDR_IDR0 ((uint16_t)0x0001) /*!< Port input data, bit 0 */ +#define GPIO_IDR_IDR1 ((uint16_t)0x0002) /*!< Port input data, bit 1 */ +#define GPIO_IDR_IDR2 ((uint16_t)0x0004) /*!< Port input data, bit 2 */ +#define GPIO_IDR_IDR3 ((uint16_t)0x0008) /*!< Port input data, bit 3 */ +#define GPIO_IDR_IDR4 ((uint16_t)0x0010) /*!< Port input data, bit 4 */ +#define GPIO_IDR_IDR5 ((uint16_t)0x0020) /*!< Port input data, bit 5 */ +#define GPIO_IDR_IDR6 ((uint16_t)0x0040) /*!< Port input data, bit 6 */ +#define GPIO_IDR_IDR7 ((uint16_t)0x0080) /*!< Port input data, bit 7 */ +#define GPIO_IDR_IDR8 ((uint16_t)0x0100) /*!< Port input data, bit 8 */ +#define GPIO_IDR_IDR9 ((uint16_t)0x0200) /*!< Port input data, bit 9 */ +#define GPIO_IDR_IDR10 ((uint16_t)0x0400) /*!< Port input data, bit 10 */ +#define GPIO_IDR_IDR11 ((uint16_t)0x0800) /*!< Port input data, bit 11 */ +#define GPIO_IDR_IDR12 ((uint16_t)0x1000) /*!< Port input data, bit 12 */ +#define GPIO_IDR_IDR13 ((uint16_t)0x2000) /*!< Port input data, bit 13 */ +#define GPIO_IDR_IDR14 ((uint16_t)0x4000) /*!< Port input data, bit 14 */ +#define GPIO_IDR_IDR15 ((uint16_t)0x8000) /*!< Port input data, bit 15 */ + +/******************* Bit definition for GPIO_ODR register *******************/ +#define GPIO_ODR_ODR0 ((uint16_t)0x0001) /*!< Port output data, bit 0 */ +#define GPIO_ODR_ODR1 ((uint16_t)0x0002) /*!< Port output data, bit 1 */ +#define GPIO_ODR_ODR2 ((uint16_t)0x0004) /*!< Port output data, bit 2 */ +#define GPIO_ODR_ODR3 ((uint16_t)0x0008) /*!< Port output data, bit 3 */ +#define GPIO_ODR_ODR4 ((uint16_t)0x0010) /*!< Port output data, bit 4 */ +#define GPIO_ODR_ODR5 ((uint16_t)0x0020) /*!< Port output data, bit 5 */ +#define GPIO_ODR_ODR6 ((uint16_t)0x0040) /*!< Port output data, bit 6 */ +#define GPIO_ODR_ODR7 ((uint16_t)0x0080) /*!< Port output data, bit 7 */ +#define GPIO_ODR_ODR8 ((uint16_t)0x0100) /*!< Port output data, bit 8 */ +#define GPIO_ODR_ODR9 ((uint16_t)0x0200) /*!< Port output data, bit 9 */ +#define GPIO_ODR_ODR10 ((uint16_t)0x0400) /*!< Port output data, bit 10 */ +#define GPIO_ODR_ODR11 ((uint16_t)0x0800) /*!< Port output data, bit 11 */ +#define GPIO_ODR_ODR12 ((uint16_t)0x1000) /*!< Port output data, bit 12 */ +#define GPIO_ODR_ODR13 ((uint16_t)0x2000) /*!< Port output data, bit 13 */ +#define GPIO_ODR_ODR14 ((uint16_t)0x4000) /*!< Port output data, bit 14 */ +#define GPIO_ODR_ODR15 ((uint16_t)0x8000) /*!< Port output data, bit 15 */ + +/****************** Bit definition for GPIO_BSRR register *******************/ +#define GPIO_BSRR_BS0 ((uint32_t)0x00000001) /*!< Port x Set bit 0 */ +#define GPIO_BSRR_BS1 ((uint32_t)0x00000002) /*!< Port x Set bit 1 */ +#define GPIO_BSRR_BS2 ((uint32_t)0x00000004) /*!< Port x Set bit 2 */ +#define GPIO_BSRR_BS3 ((uint32_t)0x00000008) /*!< Port x Set bit 3 */ +#define GPIO_BSRR_BS4 ((uint32_t)0x00000010) /*!< Port x Set bit 4 */ +#define GPIO_BSRR_BS5 ((uint32_t)0x00000020) /*!< Port x Set bit 5 */ +#define GPIO_BSRR_BS6 ((uint32_t)0x00000040) /*!< Port x Set bit 6 */ +#define GPIO_BSRR_BS7 ((uint32_t)0x00000080) /*!< Port x Set bit 7 */ +#define GPIO_BSRR_BS8 ((uint32_t)0x00000100) /*!< Port x Set bit 8 */ +#define GPIO_BSRR_BS9 ((uint32_t)0x00000200) /*!< Port x Set bit 9 */ +#define GPIO_BSRR_BS10 ((uint32_t)0x00000400) /*!< Port x Set bit 10 */ +#define GPIO_BSRR_BS11 ((uint32_t)0x00000800) /*!< Port x Set bit 11 */ +#define GPIO_BSRR_BS12 ((uint32_t)0x00001000) /*!< Port x Set bit 12 */ +#define GPIO_BSRR_BS13 ((uint32_t)0x00002000) /*!< Port x Set bit 13 */ +#define GPIO_BSRR_BS14 ((uint32_t)0x00004000) /*!< Port x Set bit 14 */ +#define GPIO_BSRR_BS15 ((uint32_t)0x00008000) /*!< Port x Set bit 15 */ + +#define GPIO_BSRR_BR0 ((uint32_t)0x00010000) /*!< Port x Reset bit 0 */ +#define GPIO_BSRR_BR1 ((uint32_t)0x00020000) /*!< Port x Reset bit 1 */ +#define GPIO_BSRR_BR2 ((uint32_t)0x00040000) /*!< Port x Reset bit 2 */ +#define GPIO_BSRR_BR3 ((uint32_t)0x00080000) /*!< Port x Reset bit 3 */ +#define GPIO_BSRR_BR4 ((uint32_t)0x00100000) /*!< Port x Reset bit 4 */ +#define GPIO_BSRR_BR5 ((uint32_t)0x00200000) /*!< Port x Reset bit 5 */ +#define GPIO_BSRR_BR6 ((uint32_t)0x00400000) /*!< Port x Reset bit 6 */ +#define GPIO_BSRR_BR7 ((uint32_t)0x00800000) /*!< Port x Reset bit 7 */ +#define GPIO_BSRR_BR8 ((uint32_t)0x01000000) /*!< Port x Reset bit 8 */ +#define GPIO_BSRR_BR9 ((uint32_t)0x02000000) /*!< Port x Reset bit 9 */ +#define GPIO_BSRR_BR10 ((uint32_t)0x04000000) /*!< Port x Reset bit 10 */ +#define GPIO_BSRR_BR11 ((uint32_t)0x08000000) /*!< Port x Reset bit 11 */ +#define GPIO_BSRR_BR12 ((uint32_t)0x10000000) /*!< Port x Reset bit 12 */ +#define GPIO_BSRR_BR13 ((uint32_t)0x20000000) /*!< Port x Reset bit 13 */ +#define GPIO_BSRR_BR14 ((uint32_t)0x40000000) /*!< Port x Reset bit 14 */ +#define GPIO_BSRR_BR15 ((uint32_t)0x80000000) /*!< Port x Reset bit 15 */ + +/******************* Bit definition for GPIO_BRR register *******************/ +#define GPIO_BRR_BR0 ((uint16_t)0x0001) /*!< Port x Reset bit 0 */ +#define GPIO_BRR_BR1 ((uint16_t)0x0002) /*!< Port x Reset bit 1 */ +#define GPIO_BRR_BR2 ((uint16_t)0x0004) /*!< Port x Reset bit 2 */ +#define GPIO_BRR_BR3 ((uint16_t)0x0008) /*!< Port x Reset bit 3 */ +#define GPIO_BRR_BR4 ((uint16_t)0x0010) /*!< Port x Reset bit 4 */ +#define GPIO_BRR_BR5 ((uint16_t)0x0020) /*!< Port x Reset bit 5 */ +#define GPIO_BRR_BR6 ((uint16_t)0x0040) /*!< Port x Reset bit 6 */ +#define GPIO_BRR_BR7 ((uint16_t)0x0080) /*!< Port x Reset bit 7 */ +#define GPIO_BRR_BR8 ((uint16_t)0x0100) /*!< Port x Reset bit 8 */ +#define GPIO_BRR_BR9 ((uint16_t)0x0200) /*!< Port x Reset bit 9 */ +#define GPIO_BRR_BR10 ((uint16_t)0x0400) /*!< Port x Reset bit 10 */ +#define GPIO_BRR_BR11 ((uint16_t)0x0800) /*!< Port x Reset bit 11 */ +#define GPIO_BRR_BR12 ((uint16_t)0x1000) /*!< Port x Reset bit 12 */ +#define GPIO_BRR_BR13 ((uint16_t)0x2000) /*!< Port x Reset bit 13 */ +#define GPIO_BRR_BR14 ((uint16_t)0x4000) /*!< Port x Reset bit 14 */ +#define GPIO_BRR_BR15 ((uint16_t)0x8000) /*!< Port x Reset bit 15 */ + +/****************** Bit definition for GPIO_LCKR register *******************/ +#define GPIO_LCKR_LCK0 ((uint32_t)0x00000001) /*!< Port x Lock bit 0 */ +#define GPIO_LCKR_LCK1 ((uint32_t)0x00000002) /*!< Port x Lock bit 1 */ +#define GPIO_LCKR_LCK2 ((uint32_t)0x00000004) /*!< Port x Lock bit 2 */ +#define GPIO_LCKR_LCK3 ((uint32_t)0x00000008) /*!< Port x Lock bit 3 */ +#define GPIO_LCKR_LCK4 ((uint32_t)0x00000010) /*!< Port x Lock bit 4 */ +#define GPIO_LCKR_LCK5 ((uint32_t)0x00000020) /*!< Port x Lock bit 5 */ +#define GPIO_LCKR_LCK6 ((uint32_t)0x00000040) /*!< Port x Lock bit 6 */ +#define GPIO_LCKR_LCK7 ((uint32_t)0x00000080) /*!< Port x Lock bit 7 */ +#define GPIO_LCKR_LCK8 ((uint32_t)0x00000100) /*!< Port x Lock bit 8 */ +#define GPIO_LCKR_LCK9 ((uint32_t)0x00000200) /*!< Port x Lock bit 9 */ +#define GPIO_LCKR_LCK10 ((uint32_t)0x00000400) /*!< Port x Lock bit 10 */ +#define GPIO_LCKR_LCK11 ((uint32_t)0x00000800) /*!< Port x Lock bit 11 */ +#define GPIO_LCKR_LCK12 ((uint32_t)0x00001000) /*!< Port x Lock bit 12 */ +#define GPIO_LCKR_LCK13 ((uint32_t)0x00002000) /*!< Port x Lock bit 13 */ +#define GPIO_LCKR_LCK14 ((uint32_t)0x00004000) /*!< Port x Lock bit 14 */ +#define GPIO_LCKR_LCK15 ((uint32_t)0x00008000) /*!< Port x Lock bit 15 */ +#define GPIO_LCKR_LCKK ((uint32_t)0x00010000) /*!< Lock key */ + +/*----------------------------------------------------------------------------*/ + +/****************** Bit definition for AFIO_EVCR register *******************/ +#define AFIO_EVCR_PIN ((uint8_t)0x0F) /*!< PIN[3:0] bits (Pin selection) */ +#define AFIO_EVCR_PIN_0 ((uint8_t)0x01) /*!< Bit 0 */ +#define AFIO_EVCR_PIN_1 ((uint8_t)0x02) /*!< Bit 1 */ +#define AFIO_EVCR_PIN_2 ((uint8_t)0x04) /*!< Bit 2 */ +#define AFIO_EVCR_PIN_3 ((uint8_t)0x08) /*!< Bit 3 */ + +/*!< PIN configuration */ +#define AFIO_EVCR_PIN_PX0 ((uint8_t)0x00) /*!< Pin 0 selected */ +#define AFIO_EVCR_PIN_PX1 ((uint8_t)0x01) /*!< Pin 1 selected */ +#define AFIO_EVCR_PIN_PX2 ((uint8_t)0x02) /*!< Pin 2 selected */ +#define AFIO_EVCR_PIN_PX3 ((uint8_t)0x03) /*!< Pin 3 selected */ +#define AFIO_EVCR_PIN_PX4 ((uint8_t)0x04) /*!< Pin 4 selected */ +#define AFIO_EVCR_PIN_PX5 ((uint8_t)0x05) /*!< Pin 5 selected */ +#define AFIO_EVCR_PIN_PX6 ((uint8_t)0x06) /*!< Pin 6 selected */ +#define AFIO_EVCR_PIN_PX7 ((uint8_t)0x07) /*!< Pin 7 selected */ +#define AFIO_EVCR_PIN_PX8 ((uint8_t)0x08) /*!< Pin 8 selected */ +#define AFIO_EVCR_PIN_PX9 ((uint8_t)0x09) /*!< Pin 9 selected */ +#define AFIO_EVCR_PIN_PX10 ((uint8_t)0x0A) /*!< Pin 10 selected */ +#define AFIO_EVCR_PIN_PX11 ((uint8_t)0x0B) /*!< Pin 11 selected */ +#define AFIO_EVCR_PIN_PX12 ((uint8_t)0x0C) /*!< Pin 12 selected */ +#define AFIO_EVCR_PIN_PX13 ((uint8_t)0x0D) /*!< Pin 13 selected */ +#define AFIO_EVCR_PIN_PX14 ((uint8_t)0x0E) /*!< Pin 14 selected */ +#define AFIO_EVCR_PIN_PX15 ((uint8_t)0x0F) /*!< Pin 15 selected */ + +#define AFIO_EVCR_PORT ((uint8_t)0x70) /*!< PORT[2:0] bits (Port selection) */ +#define AFIO_EVCR_PORT_0 ((uint8_t)0x10) /*!< Bit 0 */ +#define AFIO_EVCR_PORT_1 ((uint8_t)0x20) /*!< Bit 1 */ +#define AFIO_EVCR_PORT_2 ((uint8_t)0x40) /*!< Bit 2 */ + +/*!< PORT configuration */ +#define AFIO_EVCR_PORT_PA ((uint8_t)0x00) /*!< Port A selected */ +#define AFIO_EVCR_PORT_PB ((uint8_t)0x10) /*!< Port B selected */ +#define AFIO_EVCR_PORT_PC ((uint8_t)0x20) /*!< Port C selected */ +#define AFIO_EVCR_PORT_PD ((uint8_t)0x30) /*!< Port D selected */ +#define AFIO_EVCR_PORT_PE ((uint8_t)0x40) /*!< Port E selected */ + +#define AFIO_EVCR_EVOE ((uint8_t)0x80) /*!< Event Output Enable */ + +/****************** Bit definition for AFIO_MAPR register *******************/ +#define AFIO_MAPR_SPI1_REMAP ((uint32_t)0x00000001) /*!< SPI1 remapping */ +#define AFIO_MAPR_I2C1_REMAP ((uint32_t)0x00000002) /*!< I2C1 remapping */ +#define AFIO_MAPR_USART1_REMAP ((uint32_t)0x00000004) /*!< USART1 remapping */ +#define AFIO_MAPR_USART2_REMAP ((uint32_t)0x00000008) /*!< USART2 remapping */ + +#define AFIO_MAPR_USART3_REMAP ((uint32_t)0x00000030) /*!< USART3_REMAP[1:0] bits (USART3 remapping) */ +#define AFIO_MAPR_USART3_REMAP_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define AFIO_MAPR_USART3_REMAP_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +/* USART3_REMAP configuration */ +#define AFIO_MAPR_USART3_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (TX/PB10, RX/PB11, CK/PB12, CTS/PB13, RTS/PB14) */ +#define AFIO_MAPR_USART3_REMAP_PARTIALREMAP ((uint32_t)0x00000010) /*!< Partial remap (TX/PC10, RX/PC11, CK/PC12, CTS/PB13, RTS/PB14) */ +#define AFIO_MAPR_USART3_REMAP_FULLREMAP ((uint32_t)0x00000030) /*!< Full remap (TX/PD8, RX/PD9, CK/PD10, CTS/PD11, RTS/PD12) */ + +#define AFIO_MAPR_TIM1_REMAP ((uint32_t)0x000000C0) /*!< TIM1_REMAP[1:0] bits (TIM1 remapping) */ +#define AFIO_MAPR_TIM1_REMAP_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define AFIO_MAPR_TIM1_REMAP_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +/*!< TIM1_REMAP configuration */ +#define AFIO_MAPR_TIM1_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PB12, CH1N/PB13, CH2N/PB14, CH3N/PB15) */ +#define AFIO_MAPR_TIM1_REMAP_PARTIALREMAP ((uint32_t)0x00000040) /*!< Partial remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PA6, CH1N/PA7, CH2N/PB0, CH3N/PB1) */ +#define AFIO_MAPR_TIM1_REMAP_FULLREMAP ((uint32_t)0x000000C0) /*!< Full remap (ETR/PE7, CH1/PE9, CH2/PE11, CH3/PE13, CH4/PE14, BKIN/PE15, CH1N/PE8, CH2N/PE10, CH3N/PE12) */ + +#define AFIO_MAPR_TIM2_REMAP ((uint32_t)0x00000300) /*!< TIM2_REMAP[1:0] bits (TIM2 remapping) */ +#define AFIO_MAPR_TIM2_REMAP_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define AFIO_MAPR_TIM2_REMAP_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +/*!< TIM2_REMAP configuration */ +#define AFIO_MAPR_TIM2_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (CH1/ETR/PA0, CH2/PA1, CH3/PA2, CH4/PA3) */ +#define AFIO_MAPR_TIM2_REMAP_PARTIALREMAP1 ((uint32_t)0x00000100) /*!< Partial remap (CH1/ETR/PA15, CH2/PB3, CH3/PA2, CH4/PA3) */ +#define AFIO_MAPR_TIM2_REMAP_PARTIALREMAP2 ((uint32_t)0x00000200) /*!< Partial remap (CH1/ETR/PA0, CH2/PA1, CH3/PB10, CH4/PB11) */ +#define AFIO_MAPR_TIM2_REMAP_FULLREMAP ((uint32_t)0x00000300) /*!< Full remap (CH1/ETR/PA15, CH2/PB3, CH3/PB10, CH4/PB11) */ + +#define AFIO_MAPR_TIM3_REMAP ((uint32_t)0x00000C00) /*!< TIM3_REMAP[1:0] bits (TIM3 remapping) */ +#define AFIO_MAPR_TIM3_REMAP_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define AFIO_MAPR_TIM3_REMAP_1 ((uint32_t)0x00000800) /*!< Bit 1 */ + +/*!< TIM3_REMAP configuration */ +#define AFIO_MAPR_TIM3_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (CH1/PA6, CH2/PA7, CH3/PB0, CH4/PB1) */ +#define AFIO_MAPR_TIM3_REMAP_PARTIALREMAP ((uint32_t)0x00000800) /*!< Partial remap (CH1/PB4, CH2/PB5, CH3/PB0, CH4/PB1) */ +#define AFIO_MAPR_TIM3_REMAP_FULLREMAP ((uint32_t)0x00000C00) /*!< Full remap (CH1/PC6, CH2/PC7, CH3/PC8, CH4/PC9) */ + +#define AFIO_MAPR_TIM4_REMAP ((uint32_t)0x00001000) /*!< TIM4_REMAP bit (TIM4 remapping) */ + +#define AFIO_MAPR_CAN_REMAP ((uint32_t)0x00006000) /*!< CAN_REMAP[1:0] bits (CAN Alternate function remapping) */ +#define AFIO_MAPR_CAN_REMAP_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define AFIO_MAPR_CAN_REMAP_1 ((uint32_t)0x00004000) /*!< Bit 1 */ + +/*!< CAN_REMAP configuration */ +#define AFIO_MAPR_CAN_REMAP_REMAP1 ((uint32_t)0x00000000) /*!< CANRX mapped to PA11, CANTX mapped to PA12 */ +#define AFIO_MAPR_CAN_REMAP_REMAP2 ((uint32_t)0x00004000) /*!< CANRX mapped to PB8, CANTX mapped to PB9 */ +#define AFIO_MAPR_CAN_REMAP_REMAP3 ((uint32_t)0x00006000) /*!< CANRX mapped to PD0, CANTX mapped to PD1 */ + +#define AFIO_MAPR_PD01_REMAP ((uint32_t)0x00008000) /*!< Port D0/Port D1 mapping on OSC_IN/OSC_OUT */ +#define AFIO_MAPR_TIM5CH4_IREMAP ((uint32_t)0x00010000) /*!< TIM5 Channel4 Internal Remap */ +#define AFIO_MAPR_ADC1_ETRGINJ_REMAP ((uint32_t)0x00020000) /*!< ADC 1 External Trigger Injected Conversion remapping */ +#define AFIO_MAPR_ADC1_ETRGREG_REMAP ((uint32_t)0x00040000) /*!< ADC 1 External Trigger Regular Conversion remapping */ +#define AFIO_MAPR_ADC2_ETRGINJ_REMAP ((uint32_t)0x00080000) /*!< ADC 2 External Trigger Injected Conversion remapping */ +#define AFIO_MAPR_ADC2_ETRGREG_REMAP ((uint32_t)0x00100000) /*!< ADC 2 External Trigger Regular Conversion remapping */ + +/*!< SWJ_CFG configuration */ +#define AFIO_MAPR_SWJ_CFG ((uint32_t)0x07000000) /*!< SWJ_CFG[2:0] bits (Serial Wire JTAG configuration) */ +#define AFIO_MAPR_SWJ_CFG_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define AFIO_MAPR_SWJ_CFG_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define AFIO_MAPR_SWJ_CFG_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + +#define AFIO_MAPR_SWJ_CFG_RESET ((uint32_t)0x00000000) /*!< Full SWJ (JTAG-DP + SW-DP) : Reset State */ +#define AFIO_MAPR_SWJ_CFG_NOJNTRST ((uint32_t)0x01000000) /*!< Full SWJ (JTAG-DP + SW-DP) but without JNTRST */ +#define AFIO_MAPR_SWJ_CFG_JTAGDISABLE ((uint32_t)0x02000000) /*!< JTAG-DP Disabled and SW-DP Enabled */ +#define AFIO_MAPR_SWJ_CFG_DISABLE ((uint32_t)0x04000000) /*!< JTAG-DP Disabled and SW-DP Disabled */ + +#ifdef STM32F10X_CL +/*!< ETH_REMAP configuration */ + #define AFIO_MAPR_ETH_REMAP ((uint32_t)0x00200000) /*!< SPI3_REMAP bit (Ethernet MAC I/O remapping) */ + +/*!< CAN2_REMAP configuration */ + #define AFIO_MAPR_CAN2_REMAP ((uint32_t)0x00400000) /*!< CAN2_REMAP bit (CAN2 I/O remapping) */ + +/*!< MII_RMII_SEL configuration */ + #define AFIO_MAPR_MII_RMII_SEL ((uint32_t)0x00800000) /*!< MII_RMII_SEL bit (Ethernet MII or RMII selection) */ + +/*!< SPI3_REMAP configuration */ + #define AFIO_MAPR_SPI3_REMAP ((uint32_t)0x10000000) /*!< SPI3_REMAP bit (SPI3 remapping) */ + +/*!< TIM2ITR1_IREMAP configuration */ + #define AFIO_MAPR_TIM2ITR1_IREMAP ((uint32_t)0x20000000) /*!< TIM2ITR1_IREMAP bit (TIM2 internal trigger 1 remapping) */ + +/*!< PTP_PPS_REMAP configuration */ + #define AFIO_MAPR_PTP_PPS_REMAP ((uint32_t)0x20000000) /*!< PTP_PPS_REMAP bit (Ethernet PTP PPS remapping) */ +#endif + +/***************** Bit definition for AFIO_EXTICR1 register *****************/ +#define AFIO_EXTICR1_EXTI0 ((uint16_t)0x000F) /*!< EXTI 0 configuration */ +#define AFIO_EXTICR1_EXTI1 ((uint16_t)0x00F0) /*!< EXTI 1 configuration */ +#define AFIO_EXTICR1_EXTI2 ((uint16_t)0x0F00) /*!< EXTI 2 configuration */ +#define AFIO_EXTICR1_EXTI3 ((uint16_t)0xF000) /*!< EXTI 3 configuration */ + +/*!< EXTI0 configuration */ +#define AFIO_EXTICR1_EXTI0_PA ((uint16_t)0x0000) /*!< PA[0] pin */ +#define AFIO_EXTICR1_EXTI0_PB ((uint16_t)0x0001) /*!< PB[0] pin */ +#define AFIO_EXTICR1_EXTI0_PC ((uint16_t)0x0002) /*!< PC[0] pin */ +#define AFIO_EXTICR1_EXTI0_PD ((uint16_t)0x0003) /*!< PD[0] pin */ +#define AFIO_EXTICR1_EXTI0_PE ((uint16_t)0x0004) /*!< PE[0] pin */ +#define AFIO_EXTICR1_EXTI0_PF ((uint16_t)0x0005) /*!< PF[0] pin */ +#define AFIO_EXTICR1_EXTI0_PG ((uint16_t)0x0006) /*!< PG[0] pin */ + +/*!< EXTI1 configuration */ +#define AFIO_EXTICR1_EXTI1_PA ((uint16_t)0x0000) /*!< PA[1] pin */ +#define AFIO_EXTICR1_EXTI1_PB ((uint16_t)0x0010) /*!< PB[1] pin */ +#define AFIO_EXTICR1_EXTI1_PC ((uint16_t)0x0020) /*!< PC[1] pin */ +#define AFIO_EXTICR1_EXTI1_PD ((uint16_t)0x0030) /*!< PD[1] pin */ +#define AFIO_EXTICR1_EXTI1_PE ((uint16_t)0x0040) /*!< PE[1] pin */ +#define AFIO_EXTICR1_EXTI1_PF ((uint16_t)0x0050) /*!< PF[1] pin */ +#define AFIO_EXTICR1_EXTI1_PG ((uint16_t)0x0060) /*!< PG[1] pin */ + +/*!< EXTI2 configuration */ +#define AFIO_EXTICR1_EXTI2_PA ((uint16_t)0x0000) /*!< PA[2] pin */ +#define AFIO_EXTICR1_EXTI2_PB ((uint16_t)0x0100) /*!< PB[2] pin */ +#define AFIO_EXTICR1_EXTI2_PC ((uint16_t)0x0200) /*!< PC[2] pin */ +#define AFIO_EXTICR1_EXTI2_PD ((uint16_t)0x0300) /*!< PD[2] pin */ +#define AFIO_EXTICR1_EXTI2_PE ((uint16_t)0x0400) /*!< PE[2] pin */ +#define AFIO_EXTICR1_EXTI2_PF ((uint16_t)0x0500) /*!< PF[2] pin */ +#define AFIO_EXTICR1_EXTI2_PG ((uint16_t)0x0600) /*!< PG[2] pin */ + +/*!< EXTI3 configuration */ +#define AFIO_EXTICR1_EXTI3_PA ((uint16_t)0x0000) /*!< PA[3] pin */ +#define AFIO_EXTICR1_EXTI3_PB ((uint16_t)0x1000) /*!< PB[3] pin */ +#define AFIO_EXTICR1_EXTI3_PC ((uint16_t)0x2000) /*!< PC[3] pin */ +#define AFIO_EXTICR1_EXTI3_PD ((uint16_t)0x3000) /*!< PD[3] pin */ +#define AFIO_EXTICR1_EXTI3_PE ((uint16_t)0x4000) /*!< PE[3] pin */ +#define AFIO_EXTICR1_EXTI3_PF ((uint16_t)0x5000) /*!< PF[3] pin */ +#define AFIO_EXTICR1_EXTI3_PG ((uint16_t)0x6000) /*!< PG[3] pin */ + +/***************** Bit definition for AFIO_EXTICR2 register *****************/ +#define AFIO_EXTICR2_EXTI4 ((uint16_t)0x000F) /*!< EXTI 4 configuration */ +#define AFIO_EXTICR2_EXTI5 ((uint16_t)0x00F0) /*!< EXTI 5 configuration */ +#define AFIO_EXTICR2_EXTI6 ((uint16_t)0x0F00) /*!< EXTI 6 configuration */ +#define AFIO_EXTICR2_EXTI7 ((uint16_t)0xF000) /*!< EXTI 7 configuration */ + +/*!< EXTI4 configuration */ +#define AFIO_EXTICR2_EXTI4_PA ((uint16_t)0x0000) /*!< PA[4] pin */ +#define AFIO_EXTICR2_EXTI4_PB ((uint16_t)0x0001) /*!< PB[4] pin */ +#define AFIO_EXTICR2_EXTI4_PC ((uint16_t)0x0002) /*!< PC[4] pin */ +#define AFIO_EXTICR2_EXTI4_PD ((uint16_t)0x0003) /*!< PD[4] pin */ +#define AFIO_EXTICR2_EXTI4_PE ((uint16_t)0x0004) /*!< PE[4] pin */ +#define AFIO_EXTICR2_EXTI4_PF ((uint16_t)0x0005) /*!< PF[4] pin */ +#define AFIO_EXTICR2_EXTI4_PG ((uint16_t)0x0006) /*!< PG[4] pin */ + +/* EXTI5 configuration */ +#define AFIO_EXTICR2_EXTI5_PA ((uint16_t)0x0000) /*!< PA[5] pin */ +#define AFIO_EXTICR2_EXTI5_PB ((uint16_t)0x0010) /*!< PB[5] pin */ +#define AFIO_EXTICR2_EXTI5_PC ((uint16_t)0x0020) /*!< PC[5] pin */ +#define AFIO_EXTICR2_EXTI5_PD ((uint16_t)0x0030) /*!< PD[5] pin */ +#define AFIO_EXTICR2_EXTI5_PE ((uint16_t)0x0040) /*!< PE[5] pin */ +#define AFIO_EXTICR2_EXTI5_PF ((uint16_t)0x0050) /*!< PF[5] pin */ +#define AFIO_EXTICR2_EXTI5_PG ((uint16_t)0x0060) /*!< PG[5] pin */ + +/*!< EXTI6 configuration */ +#define AFIO_EXTICR2_EXTI6_PA ((uint16_t)0x0000) /*!< PA[6] pin */ +#define AFIO_EXTICR2_EXTI6_PB ((uint16_t)0x0100) /*!< PB[6] pin */ +#define AFIO_EXTICR2_EXTI6_PC ((uint16_t)0x0200) /*!< PC[6] pin */ +#define AFIO_EXTICR2_EXTI6_PD ((uint16_t)0x0300) /*!< PD[6] pin */ +#define AFIO_EXTICR2_EXTI6_PE ((uint16_t)0x0400) /*!< PE[6] pin */ +#define AFIO_EXTICR2_EXTI6_PF ((uint16_t)0x0500) /*!< PF[6] pin */ +#define AFIO_EXTICR2_EXTI6_PG ((uint16_t)0x0600) /*!< PG[6] pin */ + +/*!< EXTI7 configuration */ +#define AFIO_EXTICR2_EXTI7_PA ((uint16_t)0x0000) /*!< PA[7] pin */ +#define AFIO_EXTICR2_EXTI7_PB ((uint16_t)0x1000) /*!< PB[7] pin */ +#define AFIO_EXTICR2_EXTI7_PC ((uint16_t)0x2000) /*!< PC[7] pin */ +#define AFIO_EXTICR2_EXTI7_PD ((uint16_t)0x3000) /*!< PD[7] pin */ +#define AFIO_EXTICR2_EXTI7_PE ((uint16_t)0x4000) /*!< PE[7] pin */ +#define AFIO_EXTICR2_EXTI7_PF ((uint16_t)0x5000) /*!< PF[7] pin */ +#define AFIO_EXTICR2_EXTI7_PG ((uint16_t)0x6000) /*!< PG[7] pin */ + +/***************** Bit definition for AFIO_EXTICR3 register *****************/ +#define AFIO_EXTICR3_EXTI8 ((uint16_t)0x000F) /*!< EXTI 8 configuration */ +#define AFIO_EXTICR3_EXTI9 ((uint16_t)0x00F0) /*!< EXTI 9 configuration */ +#define AFIO_EXTICR3_EXTI10 ((uint16_t)0x0F00) /*!< EXTI 10 configuration */ +#define AFIO_EXTICR3_EXTI11 ((uint16_t)0xF000) /*!< EXTI 11 configuration */ + +/*!< EXTI8 configuration */ +#define AFIO_EXTICR3_EXTI8_PA ((uint16_t)0x0000) /*!< PA[8] pin */ +#define AFIO_EXTICR3_EXTI8_PB ((uint16_t)0x0001) /*!< PB[8] pin */ +#define AFIO_EXTICR3_EXTI8_PC ((uint16_t)0x0002) /*!< PC[8] pin */ +#define AFIO_EXTICR3_EXTI8_PD ((uint16_t)0x0003) /*!< PD[8] pin */ +#define AFIO_EXTICR3_EXTI8_PE ((uint16_t)0x0004) /*!< PE[8] pin */ +#define AFIO_EXTICR3_EXTI8_PF ((uint16_t)0x0005) /*!< PF[8] pin */ +#define AFIO_EXTICR3_EXTI8_PG ((uint16_t)0x0006) /*!< PG[8] pin */ + +/*!< EXTI9 configuration */ +#define AFIO_EXTICR3_EXTI9_PA ((uint16_t)0x0000) /*!< PA[9] pin */ +#define AFIO_EXTICR3_EXTI9_PB ((uint16_t)0x0010) /*!< PB[9] pin */ +#define AFIO_EXTICR3_EXTI9_PC ((uint16_t)0x0020) /*!< PC[9] pin */ +#define AFIO_EXTICR3_EXTI9_PD ((uint16_t)0x0030) /*!< PD[9] pin */ +#define AFIO_EXTICR3_EXTI9_PE ((uint16_t)0x0040) /*!< PE[9] pin */ +#define AFIO_EXTICR3_EXTI9_PF ((uint16_t)0x0050) /*!< PF[9] pin */ +#define AFIO_EXTICR3_EXTI9_PG ((uint16_t)0x0060) /*!< PG[9] pin */ + +/*!< EXTI10 configuration */ +#define AFIO_EXTICR3_EXTI10_PA ((uint16_t)0x0000) /*!< PA[10] pin */ +#define AFIO_EXTICR3_EXTI10_PB ((uint16_t)0x0100) /*!< PB[10] pin */ +#define AFIO_EXTICR3_EXTI10_PC ((uint16_t)0x0200) /*!< PC[10] pin */ +#define AFIO_EXTICR3_EXTI10_PD ((uint16_t)0x0300) /*!< PD[10] pin */ +#define AFIO_EXTICR3_EXTI10_PE ((uint16_t)0x0400) /*!< PE[10] pin */ +#define AFIO_EXTICR3_EXTI10_PF ((uint16_t)0x0500) /*!< PF[10] pin */ +#define AFIO_EXTICR3_EXTI10_PG ((uint16_t)0x0600) /*!< PG[10] pin */ + +/*!< EXTI11 configuration */ +#define AFIO_EXTICR3_EXTI11_PA ((uint16_t)0x0000) /*!< PA[11] pin */ +#define AFIO_EXTICR3_EXTI11_PB ((uint16_t)0x1000) /*!< PB[11] pin */ +#define AFIO_EXTICR3_EXTI11_PC ((uint16_t)0x2000) /*!< PC[11] pin */ +#define AFIO_EXTICR3_EXTI11_PD ((uint16_t)0x3000) /*!< PD[11] pin */ +#define AFIO_EXTICR3_EXTI11_PE ((uint16_t)0x4000) /*!< PE[11] pin */ +#define AFIO_EXTICR3_EXTI11_PF ((uint16_t)0x5000) /*!< PF[11] pin */ +#define AFIO_EXTICR3_EXTI11_PG ((uint16_t)0x6000) /*!< PG[11] pin */ + +/***************** Bit definition for AFIO_EXTICR4 register *****************/ +#define AFIO_EXTICR4_EXTI12 ((uint16_t)0x000F) /*!< EXTI 12 configuration */ +#define AFIO_EXTICR4_EXTI13 ((uint16_t)0x00F0) /*!< EXTI 13 configuration */ +#define AFIO_EXTICR4_EXTI14 ((uint16_t)0x0F00) /*!< EXTI 14 configuration */ +#define AFIO_EXTICR4_EXTI15 ((uint16_t)0xF000) /*!< EXTI 15 configuration */ + +/* EXTI12 configuration */ +#define AFIO_EXTICR4_EXTI12_PA ((uint16_t)0x0000) /*!< PA[12] pin */ +#define AFIO_EXTICR4_EXTI12_PB ((uint16_t)0x0001) /*!< PB[12] pin */ +#define AFIO_EXTICR4_EXTI12_PC ((uint16_t)0x0002) /*!< PC[12] pin */ +#define AFIO_EXTICR4_EXTI12_PD ((uint16_t)0x0003) /*!< PD[12] pin */ +#define AFIO_EXTICR4_EXTI12_PE ((uint16_t)0x0004) /*!< PE[12] pin */ +#define AFIO_EXTICR4_EXTI12_PF ((uint16_t)0x0005) /*!< PF[12] pin */ +#define AFIO_EXTICR4_EXTI12_PG ((uint16_t)0x0006) /*!< PG[12] pin */ + +/* EXTI13 configuration */ +#define AFIO_EXTICR4_EXTI13_PA ((uint16_t)0x0000) /*!< PA[13] pin */ +#define AFIO_EXTICR4_EXTI13_PB ((uint16_t)0x0010) /*!< PB[13] pin */ +#define AFIO_EXTICR4_EXTI13_PC ((uint16_t)0x0020) /*!< PC[13] pin */ +#define AFIO_EXTICR4_EXTI13_PD ((uint16_t)0x0030) /*!< PD[13] pin */ +#define AFIO_EXTICR4_EXTI13_PE ((uint16_t)0x0040) /*!< PE[13] pin */ +#define AFIO_EXTICR4_EXTI13_PF ((uint16_t)0x0050) /*!< PF[13] pin */ +#define AFIO_EXTICR4_EXTI13_PG ((uint16_t)0x0060) /*!< PG[13] pin */ + +/*!< EXTI14 configuration */ +#define AFIO_EXTICR4_EXTI14_PA ((uint16_t)0x0000) /*!< PA[14] pin */ +#define AFIO_EXTICR4_EXTI14_PB ((uint16_t)0x0100) /*!< PB[14] pin */ +#define AFIO_EXTICR4_EXTI14_PC ((uint16_t)0x0200) /*!< PC[14] pin */ +#define AFIO_EXTICR4_EXTI14_PD ((uint16_t)0x0300) /*!< PD[14] pin */ +#define AFIO_EXTICR4_EXTI14_PE ((uint16_t)0x0400) /*!< PE[14] pin */ +#define AFIO_EXTICR4_EXTI14_PF ((uint16_t)0x0500) /*!< PF[14] pin */ +#define AFIO_EXTICR4_EXTI14_PG ((uint16_t)0x0600) /*!< PG[14] pin */ + +/*!< EXTI15 configuration */ +#define AFIO_EXTICR4_EXTI15_PA ((uint16_t)0x0000) /*!< PA[15] pin */ +#define AFIO_EXTICR4_EXTI15_PB ((uint16_t)0x1000) /*!< PB[15] pin */ +#define AFIO_EXTICR4_EXTI15_PC ((uint16_t)0x2000) /*!< PC[15] pin */ +#define AFIO_EXTICR4_EXTI15_PD ((uint16_t)0x3000) /*!< PD[15] pin */ +#define AFIO_EXTICR4_EXTI15_PE ((uint16_t)0x4000) /*!< PE[15] pin */ +#define AFIO_EXTICR4_EXTI15_PF ((uint16_t)0x5000) /*!< PF[15] pin */ +#define AFIO_EXTICR4_EXTI15_PG ((uint16_t)0x6000) /*!< PG[15] pin */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/****************** Bit definition for AFIO_MAPR2 register ******************/ +#define AFIO_MAPR2_TIM15_REMAP ((uint32_t)0x00000001) /*!< TIM15 remapping */ +#define AFIO_MAPR2_TIM16_REMAP ((uint32_t)0x00000002) /*!< TIM16 remapping */ +#define AFIO_MAPR2_TIM17_REMAP ((uint32_t)0x00000004) /*!< TIM17 remapping */ +#define AFIO_MAPR2_CEC_REMAP ((uint32_t)0x00000008) /*!< CEC remapping */ +#define AFIO_MAPR2_TIM1_DMA_REMAP ((uint32_t)0x00000010) /*!< TIM1_DMA remapping */ +#endif + +#ifdef STM32F10X_HD_VL +#define AFIO_MAPR2_TIM13_REMAP ((uint32_t)0x00000100) /*!< TIM13 remapping */ +#define AFIO_MAPR2_TIM14_REMAP ((uint32_t)0x00000200) /*!< TIM14 remapping */ +#define AFIO_MAPR2_FSMC_NADV_REMAP ((uint32_t)0x00000400) /*!< FSMC NADV remapping */ +#define AFIO_MAPR2_TIM67_DAC_DMA_REMAP ((uint32_t)0x00000800) /*!< TIM6/TIM7 and DAC DMA remapping */ +#define AFIO_MAPR2_TIM12_REMAP ((uint32_t)0x00001000) /*!< TIM12 remapping */ +#define AFIO_MAPR2_MISC_REMAP ((uint32_t)0x00002000) /*!< Miscellaneous remapping */ +#endif + +#ifdef STM32F10X_XL +/****************** Bit definition for AFIO_MAPR2 register ******************/ +#define AFIO_MAPR2_TIM9_REMAP ((uint32_t)0x00000020) /*!< TIM9 remapping */ +#define AFIO_MAPR2_TIM10_REMAP ((uint32_t)0x00000040) /*!< TIM10 remapping */ +#define AFIO_MAPR2_TIM11_REMAP ((uint32_t)0x00000080) /*!< TIM11 remapping */ +#define AFIO_MAPR2_TIM13_REMAP ((uint32_t)0x00000100) /*!< TIM13 remapping */ +#define AFIO_MAPR2_TIM14_REMAP ((uint32_t)0x00000200) /*!< TIM14 remapping */ +#define AFIO_MAPR2_FSMC_NADV_REMAP ((uint32_t)0x00000400) /*!< FSMC NADV remapping */ +#endif + +/******************************************************************************/ +/* */ +/* SystemTick */ +/* */ +/******************************************************************************/ + +/***************** Bit definition for SysTick_CTRL register *****************/ +#define SysTick_CTRL_ENABLE ((uint32_t)0x00000001) /*!< Counter enable */ +#define SysTick_CTRL_TICKINT ((uint32_t)0x00000002) /*!< Counting down to 0 pends the SysTick handler */ +#define SysTick_CTRL_CLKSOURCE ((uint32_t)0x00000004) /*!< Clock source */ +#define SysTick_CTRL_COUNTFLAG ((uint32_t)0x00010000) /*!< Count Flag */ + +/***************** Bit definition for SysTick_LOAD register *****************/ +#define SysTick_LOAD_RELOAD ((uint32_t)0x00FFFFFF) /*!< Value to load into the SysTick Current Value Register when the counter reaches 0 */ + +/***************** Bit definition for SysTick_VAL register ******************/ +#define SysTick_VAL_CURRENT ((uint32_t)0x00FFFFFF) /*!< Current value at the time the register is accessed */ + +/***************** Bit definition for SysTick_CALIB register ****************/ +#define SysTick_CALIB_TENMS ((uint32_t)0x00FFFFFF) /*!< Reload value to use for 10ms timing */ +#define SysTick_CALIB_SKEW ((uint32_t)0x40000000) /*!< Calibration value is not exactly 10 ms */ +#define SysTick_CALIB_NOREF ((uint32_t)0x80000000) /*!< The reference clock is not provided */ + +/******************************************************************************/ +/* */ +/* Nested Vectored Interrupt Controller */ +/* */ +/******************************************************************************/ + +/****************** Bit definition for NVIC_ISER register *******************/ +#define NVIC_ISER_SETENA ((uint32_t)0xFFFFFFFF) /*!< Interrupt set enable bits */ +#define NVIC_ISER_SETENA_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ISER_SETENA_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ISER_SETENA_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ISER_SETENA_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ISER_SETENA_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ISER_SETENA_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ISER_SETENA_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ISER_SETENA_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ISER_SETENA_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ISER_SETENA_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ISER_SETENA_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ISER_SETENA_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ISER_SETENA_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ISER_SETENA_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ISER_SETENA_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ISER_SETENA_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ISER_SETENA_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ISER_SETENA_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ISER_SETENA_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ISER_SETENA_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ISER_SETENA_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ISER_SETENA_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ISER_SETENA_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ISER_SETENA_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ISER_SETENA_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ISER_SETENA_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ISER_SETENA_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ISER_SETENA_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ISER_SETENA_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ISER_SETENA_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ISER_SETENA_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ISER_SETENA_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_ICER register *******************/ +#define NVIC_ICER_CLRENA ((uint32_t)0xFFFFFFFF) /*!< Interrupt clear-enable bits */ +#define NVIC_ICER_CLRENA_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ICER_CLRENA_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ICER_CLRENA_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ICER_CLRENA_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ICER_CLRENA_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ICER_CLRENA_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ICER_CLRENA_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ICER_CLRENA_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ICER_CLRENA_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ICER_CLRENA_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ICER_CLRENA_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ICER_CLRENA_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ICER_CLRENA_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ICER_CLRENA_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ICER_CLRENA_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ICER_CLRENA_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ICER_CLRENA_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ICER_CLRENA_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ICER_CLRENA_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ICER_CLRENA_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ICER_CLRENA_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ICER_CLRENA_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ICER_CLRENA_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ICER_CLRENA_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ICER_CLRENA_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ICER_CLRENA_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ICER_CLRENA_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ICER_CLRENA_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ICER_CLRENA_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ICER_CLRENA_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ICER_CLRENA_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ICER_CLRENA_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_ISPR register *******************/ +#define NVIC_ISPR_SETPEND ((uint32_t)0xFFFFFFFF) /*!< Interrupt set-pending bits */ +#define NVIC_ISPR_SETPEND_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ISPR_SETPEND_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ISPR_SETPEND_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ISPR_SETPEND_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ISPR_SETPEND_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ISPR_SETPEND_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ISPR_SETPEND_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ISPR_SETPEND_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ISPR_SETPEND_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ISPR_SETPEND_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ISPR_SETPEND_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ISPR_SETPEND_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ISPR_SETPEND_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ISPR_SETPEND_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ISPR_SETPEND_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ISPR_SETPEND_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ISPR_SETPEND_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ISPR_SETPEND_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ISPR_SETPEND_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ISPR_SETPEND_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ISPR_SETPEND_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ISPR_SETPEND_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ISPR_SETPEND_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ISPR_SETPEND_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ISPR_SETPEND_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ISPR_SETPEND_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ISPR_SETPEND_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ISPR_SETPEND_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ISPR_SETPEND_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ISPR_SETPEND_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ISPR_SETPEND_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ISPR_SETPEND_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_ICPR register *******************/ +#define NVIC_ICPR_CLRPEND ((uint32_t)0xFFFFFFFF) /*!< Interrupt clear-pending bits */ +#define NVIC_ICPR_CLRPEND_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ICPR_CLRPEND_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ICPR_CLRPEND_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ICPR_CLRPEND_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ICPR_CLRPEND_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ICPR_CLRPEND_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ICPR_CLRPEND_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ICPR_CLRPEND_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ICPR_CLRPEND_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ICPR_CLRPEND_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ICPR_CLRPEND_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ICPR_CLRPEND_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ICPR_CLRPEND_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ICPR_CLRPEND_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ICPR_CLRPEND_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ICPR_CLRPEND_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ICPR_CLRPEND_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ICPR_CLRPEND_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ICPR_CLRPEND_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ICPR_CLRPEND_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ICPR_CLRPEND_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ICPR_CLRPEND_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ICPR_CLRPEND_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ICPR_CLRPEND_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ICPR_CLRPEND_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ICPR_CLRPEND_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ICPR_CLRPEND_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ICPR_CLRPEND_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ICPR_CLRPEND_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ICPR_CLRPEND_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ICPR_CLRPEND_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ICPR_CLRPEND_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_IABR register *******************/ +#define NVIC_IABR_ACTIVE ((uint32_t)0xFFFFFFFF) /*!< Interrupt active flags */ +#define NVIC_IABR_ACTIVE_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_IABR_ACTIVE_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_IABR_ACTIVE_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_IABR_ACTIVE_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_IABR_ACTIVE_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_IABR_ACTIVE_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_IABR_ACTIVE_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_IABR_ACTIVE_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_IABR_ACTIVE_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_IABR_ACTIVE_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_IABR_ACTIVE_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_IABR_ACTIVE_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_IABR_ACTIVE_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_IABR_ACTIVE_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_IABR_ACTIVE_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_IABR_ACTIVE_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_IABR_ACTIVE_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_IABR_ACTIVE_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_IABR_ACTIVE_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_IABR_ACTIVE_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_IABR_ACTIVE_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_IABR_ACTIVE_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_IABR_ACTIVE_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_IABR_ACTIVE_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_IABR_ACTIVE_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_IABR_ACTIVE_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_IABR_ACTIVE_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_IABR_ACTIVE_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_IABR_ACTIVE_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_IABR_ACTIVE_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_IABR_ACTIVE_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_IABR_ACTIVE_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_PRI0 register *******************/ +#define NVIC_IPR0_PRI_0 ((uint32_t)0x000000FF) /*!< Priority of interrupt 0 */ +#define NVIC_IPR0_PRI_1 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 1 */ +#define NVIC_IPR0_PRI_2 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 2 */ +#define NVIC_IPR0_PRI_3 ((uint32_t)0xFF000000) /*!< Priority of interrupt 3 */ + +/****************** Bit definition for NVIC_PRI1 register *******************/ +#define NVIC_IPR1_PRI_4 ((uint32_t)0x000000FF) /*!< Priority of interrupt 4 */ +#define NVIC_IPR1_PRI_5 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 5 */ +#define NVIC_IPR1_PRI_6 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 6 */ +#define NVIC_IPR1_PRI_7 ((uint32_t)0xFF000000) /*!< Priority of interrupt 7 */ + +/****************** Bit definition for NVIC_PRI2 register *******************/ +#define NVIC_IPR2_PRI_8 ((uint32_t)0x000000FF) /*!< Priority of interrupt 8 */ +#define NVIC_IPR2_PRI_9 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 9 */ +#define NVIC_IPR2_PRI_10 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 10 */ +#define NVIC_IPR2_PRI_11 ((uint32_t)0xFF000000) /*!< Priority of interrupt 11 */ + +/****************** Bit definition for NVIC_PRI3 register *******************/ +#define NVIC_IPR3_PRI_12 ((uint32_t)0x000000FF) /*!< Priority of interrupt 12 */ +#define NVIC_IPR3_PRI_13 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 13 */ +#define NVIC_IPR3_PRI_14 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 14 */ +#define NVIC_IPR3_PRI_15 ((uint32_t)0xFF000000) /*!< Priority of interrupt 15 */ + +/****************** Bit definition for NVIC_PRI4 register *******************/ +#define NVIC_IPR4_PRI_16 ((uint32_t)0x000000FF) /*!< Priority of interrupt 16 */ +#define NVIC_IPR4_PRI_17 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 17 */ +#define NVIC_IPR4_PRI_18 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 18 */ +#define NVIC_IPR4_PRI_19 ((uint32_t)0xFF000000) /*!< Priority of interrupt 19 */ + +/****************** Bit definition for NVIC_PRI5 register *******************/ +#define NVIC_IPR5_PRI_20 ((uint32_t)0x000000FF) /*!< Priority of interrupt 20 */ +#define NVIC_IPR5_PRI_21 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 21 */ +#define NVIC_IPR5_PRI_22 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 22 */ +#define NVIC_IPR5_PRI_23 ((uint32_t)0xFF000000) /*!< Priority of interrupt 23 */ + +/****************** Bit definition for NVIC_PRI6 register *******************/ +#define NVIC_IPR6_PRI_24 ((uint32_t)0x000000FF) /*!< Priority of interrupt 24 */ +#define NVIC_IPR6_PRI_25 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 25 */ +#define NVIC_IPR6_PRI_26 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 26 */ +#define NVIC_IPR6_PRI_27 ((uint32_t)0xFF000000) /*!< Priority of interrupt 27 */ + +/****************** Bit definition for NVIC_PRI7 register *******************/ +#define NVIC_IPR7_PRI_28 ((uint32_t)0x000000FF) /*!< Priority of interrupt 28 */ +#define NVIC_IPR7_PRI_29 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 29 */ +#define NVIC_IPR7_PRI_30 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 30 */ +#define NVIC_IPR7_PRI_31 ((uint32_t)0xFF000000) /*!< Priority of interrupt 31 */ + +/****************** Bit definition for SCB_CPUID register *******************/ +#define SCB_CPUID_REVISION ((uint32_t)0x0000000F) /*!< Implementation defined revision number */ +#define SCB_CPUID_PARTNO ((uint32_t)0x0000FFF0) /*!< Number of processor within family */ +#define SCB_CPUID_Constant ((uint32_t)0x000F0000) /*!< Reads as 0x0F */ +#define SCB_CPUID_VARIANT ((uint32_t)0x00F00000) /*!< Implementation defined variant number */ +#define SCB_CPUID_IMPLEMENTER ((uint32_t)0xFF000000) /*!< Implementer code. ARM is 0x41 */ + +/******************* Bit definition for SCB_ICSR register *******************/ +#define SCB_ICSR_VECTACTIVE ((uint32_t)0x000001FF) /*!< Active ISR number field */ +#define SCB_ICSR_RETTOBASE ((uint32_t)0x00000800) /*!< All active exceptions minus the IPSR_current_exception yields the empty set */ +#define SCB_ICSR_VECTPENDING ((uint32_t)0x003FF000) /*!< Pending ISR number field */ +#define SCB_ICSR_ISRPENDING ((uint32_t)0x00400000) /*!< Interrupt pending flag */ +#define SCB_ICSR_ISRPREEMPT ((uint32_t)0x00800000) /*!< It indicates that a pending interrupt becomes active in the next running cycle */ +#define SCB_ICSR_PENDSTCLR ((uint32_t)0x02000000) /*!< Clear pending SysTick bit */ +#define SCB_ICSR_PENDSTSET ((uint32_t)0x04000000) /*!< Set pending SysTick bit */ +#define SCB_ICSR_PENDSVCLR ((uint32_t)0x08000000) /*!< Clear pending pendSV bit */ +#define SCB_ICSR_PENDSVSET ((uint32_t)0x10000000) /*!< Set pending pendSV bit */ +#define SCB_ICSR_NMIPENDSET ((uint32_t)0x80000000) /*!< Set pending NMI bit */ + +/******************* Bit definition for SCB_VTOR register *******************/ +#define SCB_VTOR_TBLOFF ((uint32_t)0x1FFFFF80) /*!< Vector table base offset field */ +#define SCB_VTOR_TBLBASE ((uint32_t)0x20000000) /*!< Table base in code(0) or RAM(1) */ + +/*!<***************** Bit definition for SCB_AIRCR register *******************/ +#define SCB_AIRCR_VECTRESET ((uint32_t)0x00000001) /*!< System Reset bit */ +#define SCB_AIRCR_VECTCLRACTIVE ((uint32_t)0x00000002) /*!< Clear active vector bit */ +#define SCB_AIRCR_SYSRESETREQ ((uint32_t)0x00000004) /*!< Requests chip control logic to generate a reset */ + +#define SCB_AIRCR_PRIGROUP ((uint32_t)0x00000700) /*!< PRIGROUP[2:0] bits (Priority group) */ +#define SCB_AIRCR_PRIGROUP_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define SCB_AIRCR_PRIGROUP_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define SCB_AIRCR_PRIGROUP_2 ((uint32_t)0x00000400) /*!< Bit 2 */ + +/* prority group configuration */ +#define SCB_AIRCR_PRIGROUP0 ((uint32_t)0x00000000) /*!< Priority group=0 (7 bits of pre-emption priority, 1 bit of subpriority) */ +#define SCB_AIRCR_PRIGROUP1 ((uint32_t)0x00000100) /*!< Priority group=1 (6 bits of pre-emption priority, 2 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP2 ((uint32_t)0x00000200) /*!< Priority group=2 (5 bits of pre-emption priority, 3 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP3 ((uint32_t)0x00000300) /*!< Priority group=3 (4 bits of pre-emption priority, 4 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP4 ((uint32_t)0x00000400) /*!< Priority group=4 (3 bits of pre-emption priority, 5 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP5 ((uint32_t)0x00000500) /*!< Priority group=5 (2 bits of pre-emption priority, 6 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP6 ((uint32_t)0x00000600) /*!< Priority group=6 (1 bit of pre-emption priority, 7 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP7 ((uint32_t)0x00000700) /*!< Priority group=7 (no pre-emption priority, 8 bits of subpriority) */ + +#define SCB_AIRCR_ENDIANESS ((uint32_t)0x00008000) /*!< Data endianness bit */ +#define SCB_AIRCR_VECTKEY ((uint32_t)0xFFFF0000) /*!< Register key (VECTKEY) - Reads as 0xFA05 (VECTKEYSTAT) */ + +/******************* Bit definition for SCB_SCR register ********************/ +#define SCB_SCR_SLEEPONEXIT ((uint8_t)0x02) /*!< Sleep on exit bit */ +#define SCB_SCR_SLEEPDEEP ((uint8_t)0x04) /*!< Sleep deep bit */ +#define SCB_SCR_SEVONPEND ((uint8_t)0x10) /*!< Wake up from WFE */ + +/******************** Bit definition for SCB_CCR register *******************/ +#define SCB_CCR_NONBASETHRDENA ((uint16_t)0x0001) /*!< Thread mode can be entered from any level in Handler mode by controlled return value */ +#define SCB_CCR_USERSETMPEND ((uint16_t)0x0002) /*!< Enables user code to write the Software Trigger Interrupt register to trigger (pend) a Main exception */ +#define SCB_CCR_UNALIGN_TRP ((uint16_t)0x0008) /*!< Trap for unaligned access */ +#define SCB_CCR_DIV_0_TRP ((uint16_t)0x0010) /*!< Trap on Divide by 0 */ +#define SCB_CCR_BFHFNMIGN ((uint16_t)0x0100) /*!< Handlers running at priority -1 and -2 */ +#define SCB_CCR_STKALIGN ((uint16_t)0x0200) /*!< On exception entry, the SP used prior to the exception is adjusted to be 8-byte aligned */ + +/******************* Bit definition for SCB_SHPR register ********************/ +#define SCB_SHPR_PRI_N ((uint32_t)0x000000FF) /*!< Priority of system handler 4,8, and 12. Mem Manage, reserved and Debug Monitor */ +#define SCB_SHPR_PRI_N1 ((uint32_t)0x0000FF00) /*!< Priority of system handler 5,9, and 13. Bus Fault, reserved and reserved */ +#define SCB_SHPR_PRI_N2 ((uint32_t)0x00FF0000) /*!< Priority of system handler 6,10, and 14. Usage Fault, reserved and PendSV */ +#define SCB_SHPR_PRI_N3 ((uint32_t)0xFF000000) /*!< Priority of system handler 7,11, and 15. Reserved, SVCall and SysTick */ + +/****************** Bit definition for SCB_SHCSR register *******************/ +#define SCB_SHCSR_MEMFAULTACT ((uint32_t)0x00000001) /*!< MemManage is active */ +#define SCB_SHCSR_BUSFAULTACT ((uint32_t)0x00000002) /*!< BusFault is active */ +#define SCB_SHCSR_USGFAULTACT ((uint32_t)0x00000008) /*!< UsageFault is active */ +#define SCB_SHCSR_SVCALLACT ((uint32_t)0x00000080) /*!< SVCall is active */ +#define SCB_SHCSR_MONITORACT ((uint32_t)0x00000100) /*!< Monitor is active */ +#define SCB_SHCSR_PENDSVACT ((uint32_t)0x00000400) /*!< PendSV is active */ +#define SCB_SHCSR_SYSTICKACT ((uint32_t)0x00000800) /*!< SysTick is active */ +#define SCB_SHCSR_USGFAULTPENDED ((uint32_t)0x00001000) /*!< Usage Fault is pended */ +#define SCB_SHCSR_MEMFAULTPENDED ((uint32_t)0x00002000) /*!< MemManage is pended */ +#define SCB_SHCSR_BUSFAULTPENDED ((uint32_t)0x00004000) /*!< Bus Fault is pended */ +#define SCB_SHCSR_SVCALLPENDED ((uint32_t)0x00008000) /*!< SVCall is pended */ +#define SCB_SHCSR_MEMFAULTENA ((uint32_t)0x00010000) /*!< MemManage enable */ +#define SCB_SHCSR_BUSFAULTENA ((uint32_t)0x00020000) /*!< Bus Fault enable */ +#define SCB_SHCSR_USGFAULTENA ((uint32_t)0x00040000) /*!< UsageFault enable */ + +/******************* Bit definition for SCB_CFSR register *******************/ +/*!< MFSR */ +#define SCB_CFSR_IACCVIOL ((uint32_t)0x00000001) /*!< Instruction access violation */ +#define SCB_CFSR_DACCVIOL ((uint32_t)0x00000002) /*!< Data access violation */ +#define SCB_CFSR_MUNSTKERR ((uint32_t)0x00000008) /*!< Unstacking error */ +#define SCB_CFSR_MSTKERR ((uint32_t)0x00000010) /*!< Stacking error */ +#define SCB_CFSR_MMARVALID ((uint32_t)0x00000080) /*!< Memory Manage Address Register address valid flag */ +/*!< BFSR */ +#define SCB_CFSR_IBUSERR ((uint32_t)0x00000100) /*!< Instruction bus error flag */ +#define SCB_CFSR_PRECISERR ((uint32_t)0x00000200) /*!< Precise data bus error */ +#define SCB_CFSR_IMPRECISERR ((uint32_t)0x00000400) /*!< Imprecise data bus error */ +#define SCB_CFSR_UNSTKERR ((uint32_t)0x00000800) /*!< Unstacking error */ +#define SCB_CFSR_STKERR ((uint32_t)0x00001000) /*!< Stacking error */ +#define SCB_CFSR_BFARVALID ((uint32_t)0x00008000) /*!< Bus Fault Address Register address valid flag */ +/*!< UFSR */ +#define SCB_CFSR_UNDEFINSTR ((uint32_t)0x00010000) /*!< The processor attempt to excecute an undefined instruction */ +#define SCB_CFSR_INVSTATE ((uint32_t)0x00020000) /*!< Invalid combination of EPSR and instruction */ +#define SCB_CFSR_INVPC ((uint32_t)0x00040000) /*!< Attempt to load EXC_RETURN into pc illegally */ +#define SCB_CFSR_NOCP ((uint32_t)0x00080000) /*!< Attempt to use a coprocessor instruction */ +#define SCB_CFSR_UNALIGNED ((uint32_t)0x01000000) /*!< Fault occurs when there is an attempt to make an unaligned memory access */ +#define SCB_CFSR_DIVBYZERO ((uint32_t)0x02000000) /*!< Fault occurs when SDIV or DIV instruction is used with a divisor of 0 */ + +/******************* Bit definition for SCB_HFSR register *******************/ +#define SCB_HFSR_VECTTBL ((uint32_t)0x00000002) /*!< Fault occures because of vector table read on exception processing */ +#define SCB_HFSR_FORCED ((uint32_t)0x40000000) /*!< Hard Fault activated when a configurable Fault was received and cannot activate */ +#define SCB_HFSR_DEBUGEVT ((uint32_t)0x80000000) /*!< Fault related to debug */ + +/******************* Bit definition for SCB_DFSR register *******************/ +#define SCB_DFSR_HALTED ((uint8_t)0x01) /*!< Halt request flag */ +#define SCB_DFSR_BKPT ((uint8_t)0x02) /*!< BKPT flag */ +#define SCB_DFSR_DWTTRAP ((uint8_t)0x04) /*!< Data Watchpoint and Trace (DWT) flag */ +#define SCB_DFSR_VCATCH ((uint8_t)0x08) /*!< Vector catch flag */ +#define SCB_DFSR_EXTERNAL ((uint8_t)0x10) /*!< External debug request flag */ + +/******************* Bit definition for SCB_MMFAR register ******************/ +#define SCB_MMFAR_ADDRESS ((uint32_t)0xFFFFFFFF) /*!< Mem Manage fault address field */ + +/******************* Bit definition for SCB_BFAR register *******************/ +#define SCB_BFAR_ADDRESS ((uint32_t)0xFFFFFFFF) /*!< Bus fault address field */ + +/******************* Bit definition for SCB_afsr register *******************/ +#define SCB_AFSR_IMPDEF ((uint32_t)0xFFFFFFFF) /*!< Implementation defined */ + +/******************************************************************************/ +/* */ +/* External Interrupt/Event Controller */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for EXTI_IMR register *******************/ +#define EXTI_IMR_MR0 ((uint32_t)0x00000001) /*!< Interrupt Mask on line 0 */ +#define EXTI_IMR_MR1 ((uint32_t)0x00000002) /*!< Interrupt Mask on line 1 */ +#define EXTI_IMR_MR2 ((uint32_t)0x00000004) /*!< Interrupt Mask on line 2 */ +#define EXTI_IMR_MR3 ((uint32_t)0x00000008) /*!< Interrupt Mask on line 3 */ +#define EXTI_IMR_MR4 ((uint32_t)0x00000010) /*!< Interrupt Mask on line 4 */ +#define EXTI_IMR_MR5 ((uint32_t)0x00000020) /*!< Interrupt Mask on line 5 */ +#define EXTI_IMR_MR6 ((uint32_t)0x00000040) /*!< Interrupt Mask on line 6 */ +#define EXTI_IMR_MR7 ((uint32_t)0x00000080) /*!< Interrupt Mask on line 7 */ +#define EXTI_IMR_MR8 ((uint32_t)0x00000100) /*!< Interrupt Mask on line 8 */ +#define EXTI_IMR_MR9 ((uint32_t)0x00000200) /*!< Interrupt Mask on line 9 */ +#define EXTI_IMR_MR10 ((uint32_t)0x00000400) /*!< Interrupt Mask on line 10 */ +#define EXTI_IMR_MR11 ((uint32_t)0x00000800) /*!< Interrupt Mask on line 11 */ +#define EXTI_IMR_MR12 ((uint32_t)0x00001000) /*!< Interrupt Mask on line 12 */ +#define EXTI_IMR_MR13 ((uint32_t)0x00002000) /*!< Interrupt Mask on line 13 */ +#define EXTI_IMR_MR14 ((uint32_t)0x00004000) /*!< Interrupt Mask on line 14 */ +#define EXTI_IMR_MR15 ((uint32_t)0x00008000) /*!< Interrupt Mask on line 15 */ +#define EXTI_IMR_MR16 ((uint32_t)0x00010000) /*!< Interrupt Mask on line 16 */ +#define EXTI_IMR_MR17 ((uint32_t)0x00020000) /*!< Interrupt Mask on line 17 */ +#define EXTI_IMR_MR18 ((uint32_t)0x00040000) /*!< Interrupt Mask on line 18 */ +#define EXTI_IMR_MR19 ((uint32_t)0x00080000) /*!< Interrupt Mask on line 19 */ + +/******************* Bit definition for EXTI_EMR register *******************/ +#define EXTI_EMR_MR0 ((uint32_t)0x00000001) /*!< Event Mask on line 0 */ +#define EXTI_EMR_MR1 ((uint32_t)0x00000002) /*!< Event Mask on line 1 */ +#define EXTI_EMR_MR2 ((uint32_t)0x00000004) /*!< Event Mask on line 2 */ +#define EXTI_EMR_MR3 ((uint32_t)0x00000008) /*!< Event Mask on line 3 */ +#define EXTI_EMR_MR4 ((uint32_t)0x00000010) /*!< Event Mask on line 4 */ +#define EXTI_EMR_MR5 ((uint32_t)0x00000020) /*!< Event Mask on line 5 */ +#define EXTI_EMR_MR6 ((uint32_t)0x00000040) /*!< Event Mask on line 6 */ +#define EXTI_EMR_MR7 ((uint32_t)0x00000080) /*!< Event Mask on line 7 */ +#define EXTI_EMR_MR8 ((uint32_t)0x00000100) /*!< Event Mask on line 8 */ +#define EXTI_EMR_MR9 ((uint32_t)0x00000200) /*!< Event Mask on line 9 */ +#define EXTI_EMR_MR10 ((uint32_t)0x00000400) /*!< Event Mask on line 10 */ +#define EXTI_EMR_MR11 ((uint32_t)0x00000800) /*!< Event Mask on line 11 */ +#define EXTI_EMR_MR12 ((uint32_t)0x00001000) /*!< Event Mask on line 12 */ +#define EXTI_EMR_MR13 ((uint32_t)0x00002000) /*!< Event Mask on line 13 */ +#define EXTI_EMR_MR14 ((uint32_t)0x00004000) /*!< Event Mask on line 14 */ +#define EXTI_EMR_MR15 ((uint32_t)0x00008000) /*!< Event Mask on line 15 */ +#define EXTI_EMR_MR16 ((uint32_t)0x00010000) /*!< Event Mask on line 16 */ +#define EXTI_EMR_MR17 ((uint32_t)0x00020000) /*!< Event Mask on line 17 */ +#define EXTI_EMR_MR18 ((uint32_t)0x00040000) /*!< Event Mask on line 18 */ +#define EXTI_EMR_MR19 ((uint32_t)0x00080000) /*!< Event Mask on line 19 */ + +/****************** Bit definition for EXTI_RTSR register *******************/ +#define EXTI_RTSR_TR0 ((uint32_t)0x00000001) /*!< Rising trigger event configuration bit of line 0 */ +#define EXTI_RTSR_TR1 ((uint32_t)0x00000002) /*!< Rising trigger event configuration bit of line 1 */ +#define EXTI_RTSR_TR2 ((uint32_t)0x00000004) /*!< Rising trigger event configuration bit of line 2 */ +#define EXTI_RTSR_TR3 ((uint32_t)0x00000008) /*!< Rising trigger event configuration bit of line 3 */ +#define EXTI_RTSR_TR4 ((uint32_t)0x00000010) /*!< Rising trigger event configuration bit of line 4 */ +#define EXTI_RTSR_TR5 ((uint32_t)0x00000020) /*!< Rising trigger event configuration bit of line 5 */ +#define EXTI_RTSR_TR6 ((uint32_t)0x00000040) /*!< Rising trigger event configuration bit of line 6 */ +#define EXTI_RTSR_TR7 ((uint32_t)0x00000080) /*!< Rising trigger event configuration bit of line 7 */ +#define EXTI_RTSR_TR8 ((uint32_t)0x00000100) /*!< Rising trigger event configuration bit of line 8 */ +#define EXTI_RTSR_TR9 ((uint32_t)0x00000200) /*!< Rising trigger event configuration bit of line 9 */ +#define EXTI_RTSR_TR10 ((uint32_t)0x00000400) /*!< Rising trigger event configuration bit of line 10 */ +#define EXTI_RTSR_TR11 ((uint32_t)0x00000800) /*!< Rising trigger event configuration bit of line 11 */ +#define EXTI_RTSR_TR12 ((uint32_t)0x00001000) /*!< Rising trigger event configuration bit of line 12 */ +#define EXTI_RTSR_TR13 ((uint32_t)0x00002000) /*!< Rising trigger event configuration bit of line 13 */ +#define EXTI_RTSR_TR14 ((uint32_t)0x00004000) /*!< Rising trigger event configuration bit of line 14 */ +#define EXTI_RTSR_TR15 ((uint32_t)0x00008000) /*!< Rising trigger event configuration bit of line 15 */ +#define EXTI_RTSR_TR16 ((uint32_t)0x00010000) /*!< Rising trigger event configuration bit of line 16 */ +#define EXTI_RTSR_TR17 ((uint32_t)0x00020000) /*!< Rising trigger event configuration bit of line 17 */ +#define EXTI_RTSR_TR18 ((uint32_t)0x00040000) /*!< Rising trigger event configuration bit of line 18 */ +#define EXTI_RTSR_TR19 ((uint32_t)0x00080000) /*!< Rising trigger event configuration bit of line 19 */ + +/****************** Bit definition for EXTI_FTSR register *******************/ +#define EXTI_FTSR_TR0 ((uint32_t)0x00000001) /*!< Falling trigger event configuration bit of line 0 */ +#define EXTI_FTSR_TR1 ((uint32_t)0x00000002) /*!< Falling trigger event configuration bit of line 1 */ +#define EXTI_FTSR_TR2 ((uint32_t)0x00000004) /*!< Falling trigger event configuration bit of line 2 */ +#define EXTI_FTSR_TR3 ((uint32_t)0x00000008) /*!< Falling trigger event configuration bit of line 3 */ +#define EXTI_FTSR_TR4 ((uint32_t)0x00000010) /*!< Falling trigger event configuration bit of line 4 */ +#define EXTI_FTSR_TR5 ((uint32_t)0x00000020) /*!< Falling trigger event configuration bit of line 5 */ +#define EXTI_FTSR_TR6 ((uint32_t)0x00000040) /*!< Falling trigger event configuration bit of line 6 */ +#define EXTI_FTSR_TR7 ((uint32_t)0x00000080) /*!< Falling trigger event configuration bit of line 7 */ +#define EXTI_FTSR_TR8 ((uint32_t)0x00000100) /*!< Falling trigger event configuration bit of line 8 */ +#define EXTI_FTSR_TR9 ((uint32_t)0x00000200) /*!< Falling trigger event configuration bit of line 9 */ +#define EXTI_FTSR_TR10 ((uint32_t)0x00000400) /*!< Falling trigger event configuration bit of line 10 */ +#define EXTI_FTSR_TR11 ((uint32_t)0x00000800) /*!< Falling trigger event configuration bit of line 11 */ +#define EXTI_FTSR_TR12 ((uint32_t)0x00001000) /*!< Falling trigger event configuration bit of line 12 */ +#define EXTI_FTSR_TR13 ((uint32_t)0x00002000) /*!< Falling trigger event configuration bit of line 13 */ +#define EXTI_FTSR_TR14 ((uint32_t)0x00004000) /*!< Falling trigger event configuration bit of line 14 */ +#define EXTI_FTSR_TR15 ((uint32_t)0x00008000) /*!< Falling trigger event configuration bit of line 15 */ +#define EXTI_FTSR_TR16 ((uint32_t)0x00010000) /*!< Falling trigger event configuration bit of line 16 */ +#define EXTI_FTSR_TR17 ((uint32_t)0x00020000) /*!< Falling trigger event configuration bit of line 17 */ +#define EXTI_FTSR_TR18 ((uint32_t)0x00040000) /*!< Falling trigger event configuration bit of line 18 */ +#define EXTI_FTSR_TR19 ((uint32_t)0x00080000) /*!< Falling trigger event configuration bit of line 19 */ + +/****************** Bit definition for EXTI_SWIER register ******************/ +#define EXTI_SWIER_SWIER0 ((uint32_t)0x00000001) /*!< Software Interrupt on line 0 */ +#define EXTI_SWIER_SWIER1 ((uint32_t)0x00000002) /*!< Software Interrupt on line 1 */ +#define EXTI_SWIER_SWIER2 ((uint32_t)0x00000004) /*!< Software Interrupt on line 2 */ +#define EXTI_SWIER_SWIER3 ((uint32_t)0x00000008) /*!< Software Interrupt on line 3 */ +#define EXTI_SWIER_SWIER4 ((uint32_t)0x00000010) /*!< Software Interrupt on line 4 */ +#define EXTI_SWIER_SWIER5 ((uint32_t)0x00000020) /*!< Software Interrupt on line 5 */ +#define EXTI_SWIER_SWIER6 ((uint32_t)0x00000040) /*!< Software Interrupt on line 6 */ +#define EXTI_SWIER_SWIER7 ((uint32_t)0x00000080) /*!< Software Interrupt on line 7 */ +#define EXTI_SWIER_SWIER8 ((uint32_t)0x00000100) /*!< Software Interrupt on line 8 */ +#define EXTI_SWIER_SWIER9 ((uint32_t)0x00000200) /*!< Software Interrupt on line 9 */ +#define EXTI_SWIER_SWIER10 ((uint32_t)0x00000400) /*!< Software Interrupt on line 10 */ +#define EXTI_SWIER_SWIER11 ((uint32_t)0x00000800) /*!< Software Interrupt on line 11 */ +#define EXTI_SWIER_SWIER12 ((uint32_t)0x00001000) /*!< Software Interrupt on line 12 */ +#define EXTI_SWIER_SWIER13 ((uint32_t)0x00002000) /*!< Software Interrupt on line 13 */ +#define EXTI_SWIER_SWIER14 ((uint32_t)0x00004000) /*!< Software Interrupt on line 14 */ +#define EXTI_SWIER_SWIER15 ((uint32_t)0x00008000) /*!< Software Interrupt on line 15 */ +#define EXTI_SWIER_SWIER16 ((uint32_t)0x00010000) /*!< Software Interrupt on line 16 */ +#define EXTI_SWIER_SWIER17 ((uint32_t)0x00020000) /*!< Software Interrupt on line 17 */ +#define EXTI_SWIER_SWIER18 ((uint32_t)0x00040000) /*!< Software Interrupt on line 18 */ +#define EXTI_SWIER_SWIER19 ((uint32_t)0x00080000) /*!< Software Interrupt on line 19 */ + +/******************* Bit definition for EXTI_PR register ********************/ +#define EXTI_PR_PR0 ((uint32_t)0x00000001) /*!< Pending bit for line 0 */ +#define EXTI_PR_PR1 ((uint32_t)0x00000002) /*!< Pending bit for line 1 */ +#define EXTI_PR_PR2 ((uint32_t)0x00000004) /*!< Pending bit for line 2 */ +#define EXTI_PR_PR3 ((uint32_t)0x00000008) /*!< Pending bit for line 3 */ +#define EXTI_PR_PR4 ((uint32_t)0x00000010) /*!< Pending bit for line 4 */ +#define EXTI_PR_PR5 ((uint32_t)0x00000020) /*!< Pending bit for line 5 */ +#define EXTI_PR_PR6 ((uint32_t)0x00000040) /*!< Pending bit for line 6 */ +#define EXTI_PR_PR7 ((uint32_t)0x00000080) /*!< Pending bit for line 7 */ +#define EXTI_PR_PR8 ((uint32_t)0x00000100) /*!< Pending bit for line 8 */ +#define EXTI_PR_PR9 ((uint32_t)0x00000200) /*!< Pending bit for line 9 */ +#define EXTI_PR_PR10 ((uint32_t)0x00000400) /*!< Pending bit for line 10 */ +#define EXTI_PR_PR11 ((uint32_t)0x00000800) /*!< Pending bit for line 11 */ +#define EXTI_PR_PR12 ((uint32_t)0x00001000) /*!< Pending bit for line 12 */ +#define EXTI_PR_PR13 ((uint32_t)0x00002000) /*!< Pending bit for line 13 */ +#define EXTI_PR_PR14 ((uint32_t)0x00004000) /*!< Pending bit for line 14 */ +#define EXTI_PR_PR15 ((uint32_t)0x00008000) /*!< Pending bit for line 15 */ +#define EXTI_PR_PR16 ((uint32_t)0x00010000) /*!< Pending bit for line 16 */ +#define EXTI_PR_PR17 ((uint32_t)0x00020000) /*!< Pending bit for line 17 */ +#define EXTI_PR_PR18 ((uint32_t)0x00040000) /*!< Pending bit for line 18 */ +#define EXTI_PR_PR19 ((uint32_t)0x00080000) /*!< Pending bit for line 19 */ + +/******************************************************************************/ +/* */ +/* DMA Controller */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for DMA_ISR register ********************/ +#define DMA_ISR_GIF1 ((uint32_t)0x00000001) /*!< Channel 1 Global interrupt flag */ +#define DMA_ISR_TCIF1 ((uint32_t)0x00000002) /*!< Channel 1 Transfer Complete flag */ +#define DMA_ISR_HTIF1 ((uint32_t)0x00000004) /*!< Channel 1 Half Transfer flag */ +#define DMA_ISR_TEIF1 ((uint32_t)0x00000008) /*!< Channel 1 Transfer Error flag */ +#define DMA_ISR_GIF2 ((uint32_t)0x00000010) /*!< Channel 2 Global interrupt flag */ +#define DMA_ISR_TCIF2 ((uint32_t)0x00000020) /*!< Channel 2 Transfer Complete flag */ +#define DMA_ISR_HTIF2 ((uint32_t)0x00000040) /*!< Channel 2 Half Transfer flag */ +#define DMA_ISR_TEIF2 ((uint32_t)0x00000080) /*!< Channel 2 Transfer Error flag */ +#define DMA_ISR_GIF3 ((uint32_t)0x00000100) /*!< Channel 3 Global interrupt flag */ +#define DMA_ISR_TCIF3 ((uint32_t)0x00000200) /*!< Channel 3 Transfer Complete flag */ +#define DMA_ISR_HTIF3 ((uint32_t)0x00000400) /*!< Channel 3 Half Transfer flag */ +#define DMA_ISR_TEIF3 ((uint32_t)0x00000800) /*!< Channel 3 Transfer Error flag */ +#define DMA_ISR_GIF4 ((uint32_t)0x00001000) /*!< Channel 4 Global interrupt flag */ +#define DMA_ISR_TCIF4 ((uint32_t)0x00002000) /*!< Channel 4 Transfer Complete flag */ +#define DMA_ISR_HTIF4 ((uint32_t)0x00004000) /*!< Channel 4 Half Transfer flag */ +#define DMA_ISR_TEIF4 ((uint32_t)0x00008000) /*!< Channel 4 Transfer Error flag */ +#define DMA_ISR_GIF5 ((uint32_t)0x00010000) /*!< Channel 5 Global interrupt flag */ +#define DMA_ISR_TCIF5 ((uint32_t)0x00020000) /*!< Channel 5 Transfer Complete flag */ +#define DMA_ISR_HTIF5 ((uint32_t)0x00040000) /*!< Channel 5 Half Transfer flag */ +#define DMA_ISR_TEIF5 ((uint32_t)0x00080000) /*!< Channel 5 Transfer Error flag */ +#define DMA_ISR_GIF6 ((uint32_t)0x00100000) /*!< Channel 6 Global interrupt flag */ +#define DMA_ISR_TCIF6 ((uint32_t)0x00200000) /*!< Channel 6 Transfer Complete flag */ +#define DMA_ISR_HTIF6 ((uint32_t)0x00400000) /*!< Channel 6 Half Transfer flag */ +#define DMA_ISR_TEIF6 ((uint32_t)0x00800000) /*!< Channel 6 Transfer Error flag */ +#define DMA_ISR_GIF7 ((uint32_t)0x01000000) /*!< Channel 7 Global interrupt flag */ +#define DMA_ISR_TCIF7 ((uint32_t)0x02000000) /*!< Channel 7 Transfer Complete flag */ +#define DMA_ISR_HTIF7 ((uint32_t)0x04000000) /*!< Channel 7 Half Transfer flag */ +#define DMA_ISR_TEIF7 ((uint32_t)0x08000000) /*!< Channel 7 Transfer Error flag */ + +/******************* Bit definition for DMA_IFCR register *******************/ +#define DMA_IFCR_CGIF1 ((uint32_t)0x00000001) /*!< Channel 1 Global interrupt clearr */ +#define DMA_IFCR_CTCIF1 ((uint32_t)0x00000002) /*!< Channel 1 Transfer Complete clear */ +#define DMA_IFCR_CHTIF1 ((uint32_t)0x00000004) /*!< Channel 1 Half Transfer clear */ +#define DMA_IFCR_CTEIF1 ((uint32_t)0x00000008) /*!< Channel 1 Transfer Error clear */ +#define DMA_IFCR_CGIF2 ((uint32_t)0x00000010) /*!< Channel 2 Global interrupt clear */ +#define DMA_IFCR_CTCIF2 ((uint32_t)0x00000020) /*!< Channel 2 Transfer Complete clear */ +#define DMA_IFCR_CHTIF2 ((uint32_t)0x00000040) /*!< Channel 2 Half Transfer clear */ +#define DMA_IFCR_CTEIF2 ((uint32_t)0x00000080) /*!< Channel 2 Transfer Error clear */ +#define DMA_IFCR_CGIF3 ((uint32_t)0x00000100) /*!< Channel 3 Global interrupt clear */ +#define DMA_IFCR_CTCIF3 ((uint32_t)0x00000200) /*!< Channel 3 Transfer Complete clear */ +#define DMA_IFCR_CHTIF3 ((uint32_t)0x00000400) /*!< Channel 3 Half Transfer clear */ +#define DMA_IFCR_CTEIF3 ((uint32_t)0x00000800) /*!< Channel 3 Transfer Error clear */ +#define DMA_IFCR_CGIF4 ((uint32_t)0x00001000) /*!< Channel 4 Global interrupt clear */ +#define DMA_IFCR_CTCIF4 ((uint32_t)0x00002000) /*!< Channel 4 Transfer Complete clear */ +#define DMA_IFCR_CHTIF4 ((uint32_t)0x00004000) /*!< Channel 4 Half Transfer clear */ +#define DMA_IFCR_CTEIF4 ((uint32_t)0x00008000) /*!< Channel 4 Transfer Error clear */ +#define DMA_IFCR_CGIF5 ((uint32_t)0x00010000) /*!< Channel 5 Global interrupt clear */ +#define DMA_IFCR_CTCIF5 ((uint32_t)0x00020000) /*!< Channel 5 Transfer Complete clear */ +#define DMA_IFCR_CHTIF5 ((uint32_t)0x00040000) /*!< Channel 5 Half Transfer clear */ +#define DMA_IFCR_CTEIF5 ((uint32_t)0x00080000) /*!< Channel 5 Transfer Error clear */ +#define DMA_IFCR_CGIF6 ((uint32_t)0x00100000) /*!< Channel 6 Global interrupt clear */ +#define DMA_IFCR_CTCIF6 ((uint32_t)0x00200000) /*!< Channel 6 Transfer Complete clear */ +#define DMA_IFCR_CHTIF6 ((uint32_t)0x00400000) /*!< Channel 6 Half Transfer clear */ +#define DMA_IFCR_CTEIF6 ((uint32_t)0x00800000) /*!< Channel 6 Transfer Error clear */ +#define DMA_IFCR_CGIF7 ((uint32_t)0x01000000) /*!< Channel 7 Global interrupt clear */ +#define DMA_IFCR_CTCIF7 ((uint32_t)0x02000000) /*!< Channel 7 Transfer Complete clear */ +#define DMA_IFCR_CHTIF7 ((uint32_t)0x04000000) /*!< Channel 7 Half Transfer clear */ +#define DMA_IFCR_CTEIF7 ((uint32_t)0x08000000) /*!< Channel 7 Transfer Error clear */ + +/******************* Bit definition for DMA_CCR1 register *******************/ +#define DMA_CCR1_EN ((uint16_t)0x0001) /*!< Channel enable*/ +#define DMA_CCR1_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR1_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR1_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR1_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR1_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR1_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR1_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR1_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR1_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR1_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR1_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR1_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR1_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR1_PL ((uint16_t)0x3000) /*!< PL[1:0] bits(Channel Priority level) */ +#define DMA_CCR1_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR1_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR1_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/******************* Bit definition for DMA_CCR2 register *******************/ +#define DMA_CCR2_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR2_TCIE ((uint16_t)0x0002) /*!< ransfer complete interrupt enable */ +#define DMA_CCR2_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR2_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR2_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR2_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR2_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR2_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR2_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR2_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR2_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR2_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR2_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR2_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR2_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR2_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR2_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR2_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/******************* Bit definition for DMA_CCR3 register *******************/ +#define DMA_CCR3_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR3_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR3_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR3_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR3_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR3_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR3_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR3_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR3_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR3_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR3_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR3_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR3_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR3_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR3_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR3_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR3_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR3_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/*!<****************** Bit definition for DMA_CCR4 register *******************/ +#define DMA_CCR4_EN ((uint16_t)0x0001) /*!
© COPYRIGHT 2009 STMicroelectronics
- ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f10x_system - * @{ - */ - -/** @addtogroup STM32F10x_System_Private_Includes - * @{ - */ - -#include "stm32f10x.h" - -/** - * @} - */ - -/** @addtogroup STM32F10x_System_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F10x_System_Private_Defines - * @{ - */ - -/*!< Uncomment the line corresponding to the desired System clock (SYSCLK) - frequency (after reset the HSI is used as SYSCLK source) - - IMPORTANT NOTE: - ============== - 1. After each device reset the HSI is used as System clock source. - - 2. Please make sure that the selected System clock doesn't exceed your device's - maximum frequency. - - 3. If none of the define below is enabled, the HSI is used as System clock - source. - - 4. The System clock configuration functions provided within this file assume that: - - For Low, Medium and High density devices an external 8MHz crystal is - used to drive the System clock. - - For Connectivity line devices an external 25MHz crystal is used to drive - the System clock. - If you are using different crystal you have to adapt those functions accordingly. - */ - -/* #define SYSCLK_FREQ_HSE HSE_Value */ -/* #define SYSCLK_FREQ_24MHz 24000000 */ -/* #define SYSCLK_FREQ_36MHz 36000000 */ -/* #define SYSCLK_FREQ_48MHz 48000000 */ -/* #define SYSCLK_FREQ_56MHz 56000000 */ -#define SYSCLK_FREQ_72MHz 72000000 - -/*!< Uncomment the following line if you need to use external SRAM mounted - on STM3210E-EVAL board (STM32 High density devices) as data memory */ -#ifdef STM32F10X_HD -/* #define DATA_IN_ExtSRAM */ -#endif /* STM32F10X_HD */ - -/** - * @} - */ - -/** @addtogroup STM32F10x_System_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F10x_System_Private_Variables - * @{ - */ - -/******************************************************************************* -* Clock Definitions -*******************************************************************************/ -#ifdef SYSCLK_FREQ_HSE - const uint32_t SystemFrequency = SYSCLK_FREQ_HSE; /*!< System Clock Frequency (Core Clock) */ - const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_HSE; /*!< System clock */ - const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_HSE; /*!< AHB System bus speed */ - const uint32_t SystemFrequency_APB1Clk = SYSCLK_FREQ_HSE; /*!< APB Peripheral bus 1 (low) speed */ - const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_HSE; /*!< APB Peripheral bus 2 (high) speed */ -#elif defined SYSCLK_FREQ_24MHz - const uint32_t SystemFrequency = SYSCLK_FREQ_24MHz; /*!< System Clock Frequency (Core Clock) */ - const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_24MHz; /*!< System clock */ - const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_24MHz; /*!< AHB System bus speed */ - const uint32_t SystemFrequency_APB1Clk = SYSCLK_FREQ_24MHz; /*!< APB Peripheral bus 1 (low) speed */ - const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_24MHz; /*!< APB Peripheral bus 2 (high) speed */ -#elif defined SYSCLK_FREQ_36MHz - const uint32_t SystemFrequency = SYSCLK_FREQ_36MHz; /*!< System Clock Frequency (Core Clock) */ - const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_36MHz; /*!< System clock */ - const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_36MHz; /*!< AHB System bus speed */ - const uint32_t SystemFrequency_APB1Clk = SYSCLK_FREQ_36MHz; /*!< APB Peripheral bus 1 (low) speed */ - const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_36MHz; /*!< APB Peripheral bus 2 (high) speed */ -#elif defined SYSCLK_FREQ_48MHz - const uint32_t SystemFrequency = SYSCLK_FREQ_48MHz; /*!< System Clock Frequency (Core Clock) */ - const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_48MHz; /*!< System clock */ - const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_48MHz; /*!< AHB System bus speed */ - const uint32_t SystemFrequency_APB1Clk = (SYSCLK_FREQ_48MHz/2); /*!< APB Peripheral bus 1 (low) speed */ - const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_48MHz; /*!< APB Peripheral bus 2 (high) speed */ -#elif defined SYSCLK_FREQ_56MHz - const uint32_t SystemFrequency = SYSCLK_FREQ_56MHz; /*!< System Clock Frequency (Core Clock) */ - const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_56MHz; /*!< System clock */ - const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_56MHz; /*!< AHB System bus speed */ - const uint32_t SystemFrequency_APB1Clk = (SYSCLK_FREQ_56MHz/2); /*!< APB Peripheral bus 1 (low) speed */ - const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_56MHz; /*!< APB Peripheral bus 2 (high) speed */ -#elif defined SYSCLK_FREQ_72MHz - const uint32_t SystemFrequency = SYSCLK_FREQ_72MHz; /*!< System Clock Frequency (Core Clock) */ - const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_72MHz; /*!< System clock */ - const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_72MHz; /*!< AHB System bus speed */ - const uint32_t SystemFrequency_APB1Clk = (SYSCLK_FREQ_72MHz/2); /*!< APB Peripheral bus 1 (low) speed */ - const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_72MHz; /*!< APB Peripheral bus 2 (high) speed */ -#else /*!< HSI Selected as System Clock source */ - const uint32_t SystemFrequency = HSI_Value; /*!< System Clock Frequency (Core Clock) */ - const uint32_t SystemFrequency_SysClk = HSI_Value; /*!< System clock */ - const uint32_t SystemFrequency_AHBClk = HSI_Value; /*!< AHB System bus speed */ - const uint32_t SystemFrequency_APB1Clk = HSI_Value; /*!< APB Peripheral bus 1 (low) speed */ - const uint32_t SystemFrequency_APB2Clk = HSI_Value; /*!< APB Peripheral bus 2 (high) speed */ -#endif - -/** - * @} - */ - -/** @addtogroup STM32F10x_System_Private_FunctionPrototypes - * @{ - */ - -static void SetSysClock(void); - -#ifdef SYSCLK_FREQ_HSE - static void SetSysClockToHSE(void); -#elif defined SYSCLK_FREQ_24MHz - static void SetSysClockTo24(void); -#elif defined SYSCLK_FREQ_36MHz - static void SetSysClockTo36(void); -#elif defined SYSCLK_FREQ_48MHz - static void SetSysClockTo48(void); -#elif defined SYSCLK_FREQ_56MHz - static void SetSysClockTo56(void); -#elif defined SYSCLK_FREQ_72MHz - static void SetSysClockTo72(void); -#endif - -/** - * @} - */ - -/** @addtogroup STM32F10x_System_Private_Functions - * @{ - */ - -/** - * @brief Setup the microcontroller system - * Initialize the Embedded Flash Interface, the PLL and update the SystemFrequency variable. - * @note This function should be used only after reset. - * @param None - * @retval None - */ -void SystemInit (void) -{ - /* Reset the RCC clock configuration to the default reset state(for debug purpose) */ - /* Set HSION bit */ - RCC->CR |= (uint32_t)0x00000001; - - /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ -#ifndef STM32F10X_CL - RCC->CFGR &= (uint32_t)0xF8FF0000; -#else - RCC->CFGR &= (uint32_t)0xF0FF0000; -#endif /* STM32F10X_CL */ - - /* Reset HSEON, CSSON and PLLON bits */ - RCC->CR &= (uint32_t)0xFEF6FFFF; - - /* Reset HSEBYP bit */ - RCC->CR &= (uint32_t)0xFFFBFFFF; - - /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ - RCC->CFGR &= (uint32_t)0xFF80FFFF; - -#ifndef STM32F10X_CL - /* Disable all interrupts and clear pending bits */ - RCC->CIR = 0x009F0000; -#else - /* Reset PLL2ON and PLL3ON bits */ - RCC->CR &= (uint32_t)0xEBFFFFFF; - - /* Disable all interrupts and clear pending bits */ - RCC->CIR = 0x00FF0000; - - /* Reset CFGR2 register */ - RCC->CFGR2 = 0x00000000; -#endif /* STM32F10X_CL */ - - /* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */ - /* Configure the Flash Latency cycles and enable prefetch buffer */ - SetSysClock(); - -} - -/** - * @brief Configures the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers. - * @param None - * @retval None - */ -static void SetSysClock(void) -{ -#ifdef SYSCLK_FREQ_HSE - SetSysClockToHSE(); -#elif defined SYSCLK_FREQ_24MHz - SetSysClockTo24(); -#elif defined SYSCLK_FREQ_36MHz - SetSysClockTo36(); -#elif defined SYSCLK_FREQ_48MHz - SetSysClockTo48(); -#elif defined SYSCLK_FREQ_56MHz - SetSysClockTo56(); -#elif defined SYSCLK_FREQ_72MHz - SetSysClockTo72(); -#endif - - /* If none of the define above is enabled, the HSI is used as System clock - source (default after reset) */ -} - -/** - * @brief Setup the external memory controller. Called in startup_stm32f10x.s - * before jump to __main - * @param None - * @retval None - */ -#ifdef DATA_IN_ExtSRAM -/** - * @brief Setup the external memory controller. - * Called in startup_stm32f10x_xx.s/.c before jump to main. - * This function configures the external SRAM mounted on STM3210E-EVAL - * board (STM32 High density devices). This SRAM will be used as program - * data memory (including heap and stack). - * @param None - * @retval None - */ -void SystemInit_ExtMemCtl(void) -{ -/*!< FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is - required, then adjust the Register Addresses */ - - /* Enable FSMC clock */ - RCC->AHBENR = 0x00000114; - - /* Enable GPIOD, GPIOE, GPIOF and GPIOG clocks */ - RCC->APB2ENR = 0x000001E0; - -/* --------------- SRAM Data lines, NOE and NWE configuration ---------------*/ -/*---------------- SRAM Address lines configuration -------------------------*/ -/*---------------- NOE and NWE configuration --------------------------------*/ -/*---------------- NE3 configuration ----------------------------------------*/ -/*---------------- NBL0, NBL1 configuration ---------------------------------*/ - - GPIOD->CRL = 0x44BB44BB; - GPIOD->CRH = 0xBBBBBBBB; - - GPIOE->CRL = 0xB44444BB; - GPIOE->CRH = 0xBBBBBBBB; - - GPIOF->CRL = 0x44BBBBBB; - GPIOF->CRH = 0xBBBB4444; - - GPIOG->CRL = 0x44BBBBBB; - GPIOG->CRH = 0x44444B44; - -/*---------------- FSMC Configuration ---------------------------------------*/ -/*---------------- Enable FSMC Bank1_SRAM Bank ------------------------------*/ - - FSMC_Bank1->BTCR[4] = 0x00001011; - FSMC_Bank1->BTCR[5] = 0x00000200; -} -#endif /* DATA_IN_ExtSRAM */ - -#ifdef SYSCLK_FREQ_HSE -/** - * @brief Selects HSE as System clock source and configure HCLK, PCLK2 - * and PCLK1 prescalers. - * @note This function should be used only after reset. - * @param None - * @retval None - */ -static void SetSysClockToHSE(void) -{ - __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ - /* Enable HSE */ - RCC->CR |= ((uint32_t)RCC_CR_HSEON); - - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC->CR & RCC_CR_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); - - if ((RCC->CR & RCC_CR_HSERDY) != RESET) - { - HSEStatus = (uint32_t)0x01; - } - else - { - HSEStatus = (uint32_t)0x00; - } - - if (HSEStatus == (uint32_t)0x01) - { - /* Enable Prefetch Buffer */ - FLASH->ACR |= FLASH_ACR_PRFTBE; - - /* Flash 0 wait state */ - FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); - -#ifndef STM32F10X_CL - FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0; -#else - if (HSE_Value <= 24000000) - { - FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0; - } - else - { - FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1; - } -#endif /* STM32F10X_CL */ - - /* HCLK = SYSCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; - - /* PCLK2 = HCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; - - /* PCLK1 = HCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1; - - /* Select HSE as system clock source */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); - RCC->CFGR |= (uint32_t)RCC_CFGR_SW_HSE; - - /* Wait till HSE is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x04) - { - } - } - else - { /* If HSE fails to start-up, the application will have wrong clock - configuration. User can add here some code to deal with this error */ - - /* Go to infinite loop */ - while (1) - { - } - } -} -#elif defined SYSCLK_FREQ_24MHz -/** - * @brief Sets System clock frequency to 24MHz and configure HCLK, PCLK2 - * and PCLK1 prescalers. - * @note This function should be used only after reset. - * @param None - * @retval None - */ -static void SetSysClockTo24(void) -{ - __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ - /* Enable HSE */ - RCC->CR |= ((uint32_t)RCC_CR_HSEON); - - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC->CR & RCC_CR_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); - - if ((RCC->CR & RCC_CR_HSERDY) != RESET) - { - HSEStatus = (uint32_t)0x01; - } - else - { - HSEStatus = (uint32_t)0x00; - } - - if (HSEStatus == (uint32_t)0x01) - { - /* Enable Prefetch Buffer */ - FLASH->ACR |= FLASH_ACR_PRFTBE; - - /* Flash 0 wait state */ - FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); - FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0; - - /* HCLK = SYSCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; - - /* PCLK2 = HCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; - - /* PCLK1 = HCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1; - -#ifdef STM32F10X_CL - /* Configure PLLs ------------------------------------------------------*/ - /* PLL configuration: PLLCLK = PREDIV1 * 6 = 24 MHz */ - RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL); - RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | - RCC_CFGR_PLLMULL6); - - /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */ - /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 10 = 4 MHz */ - RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL | - RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC); - RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 | - RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV10); - - /* Enable PLL2 */ - RCC->CR |= RCC_CR_PLL2ON; - /* Wait till PLL2 is ready */ - while((RCC->CR & RCC_CR_PLL2RDY) == 0) - { - } -#else - /* PLL configuration: = (HSE / 2) * 6 = 24 MHz */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); - RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLXTPRE_HSE_Div2 | RCC_CFGR_PLLMULL6); -#endif /* STM32F10X_CL */ - - /* Enable PLL */ - RCC->CR |= RCC_CR_PLLON; - - /* Wait till PLL is ready */ - while((RCC->CR & RCC_CR_PLLRDY) == 0) - { - } - - /* Select PLL as system clock source */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); - RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; - - /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) - { - } - } - else - { /* If HSE fails to start-up, the application will have wrong clock - configuration. User can add here some code to deal with this error */ - - /* Go to infinite loop */ - while (1) - { - } - } -} -#elif defined SYSCLK_FREQ_36MHz -/** - * @brief Sets System clock frequency to 36MHz and configure HCLK, PCLK2 - * and PCLK1 prescalers. - * @note This function should be used only after reset. - * @param None - * @retval None - */ -static void SetSysClockTo36(void) -{ - __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ - /* Enable HSE */ - RCC->CR |= ((uint32_t)RCC_CR_HSEON); - - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC->CR & RCC_CR_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); - - if ((RCC->CR & RCC_CR_HSERDY) != RESET) - { - HSEStatus = (uint32_t)0x01; - } - else - { - HSEStatus = (uint32_t)0x00; - } - - if (HSEStatus == (uint32_t)0x01) - { - /* Enable Prefetch Buffer */ - FLASH->ACR |= FLASH_ACR_PRFTBE; - - /* Flash 1 wait state */ - FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); - FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1; - - /* HCLK = SYSCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; - - /* PCLK2 = HCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; - - /* PCLK1 = HCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1; - -#ifdef STM32F10X_CL - /* Configure PLLs ------------------------------------------------------*/ - - /* PLL configuration: PLLCLK = PREDIV1 * 9 = 36 MHz */ - RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL); - RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | - RCC_CFGR_PLLMULL9); - - /*!< PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */ - /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 10 = 4 MHz */ - - RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL | - RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC); - RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 | - RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV10); - - /* Enable PLL2 */ - RCC->CR |= RCC_CR_PLL2ON; - /* Wait till PLL2 is ready */ - while((RCC->CR & RCC_CR_PLL2RDY) == 0) - { - } - -#else - /* PLL configuration: PLLCLK = (HSE / 2) * 9 = 36 MHz */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); - RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLXTPRE_HSE_Div2 | RCC_CFGR_PLLMULL9); -#endif /* STM32F10X_CL */ - - /* Enable PLL */ - RCC->CR |= RCC_CR_PLLON; - - /* Wait till PLL is ready */ - while((RCC->CR & RCC_CR_PLLRDY) == 0) - { - } - - /* Select PLL as system clock source */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); - RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; - - /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) - { - } - } - else - { /* If HSE fails to start-up, the application will have wrong clock - configuration. User can add here some code to deal with this error */ - - /* Go to infinite loop */ - while (1) - { - } - } -} -#elif defined SYSCLK_FREQ_48MHz -/** - * @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2 - * and PCLK1 prescalers. - * @note This function should be used only after reset. - * @param None - * @retval None - */ -static void SetSysClockTo48(void) -{ - __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ - /* Enable HSE */ - RCC->CR |= ((uint32_t)RCC_CR_HSEON); - - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC->CR & RCC_CR_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); - - if ((RCC->CR & RCC_CR_HSERDY) != RESET) - { - HSEStatus = (uint32_t)0x01; - } - else - { - HSEStatus = (uint32_t)0x00; - } - - if (HSEStatus == (uint32_t)0x01) - { - /* Enable Prefetch Buffer */ - FLASH->ACR |= FLASH_ACR_PRFTBE; - - /* Flash 1 wait state */ - FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); - FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1; - - /* HCLK = SYSCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; - - /* PCLK2 = HCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; - - /* PCLK1 = HCLK/2 */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; - -#ifdef STM32F10X_CL - /* Configure PLLs ------------------------------------------------------*/ - /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */ - /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */ - - RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL | - RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC); - RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 | - RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5); - - /* Enable PLL2 */ - RCC->CR |= RCC_CR_PLL2ON; - /* Wait till PLL2 is ready */ - while((RCC->CR & RCC_CR_PLL2RDY) == 0) - { - } - - - /* PLL configuration: PLLCLK = PREDIV1 * 6 = 48 MHz */ - RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL); - RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | - RCC_CFGR_PLLMULL6); -#else - /* PLL configuration: PLLCLK = HSE * 6 = 48 MHz */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); - RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL6); -#endif /* STM32F10X_CL */ - - /* Enable PLL */ - RCC->CR |= RCC_CR_PLLON; - - /* Wait till PLL is ready */ - while((RCC->CR & RCC_CR_PLLRDY) == 0) - { - } - - /* Select PLL as system clock source */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); - RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; - - /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) - { - } - } - else - { /* If HSE fails to start-up, the application will have wrong clock - configuration. User can add here some code to deal with this error */ - - /* Go to infinite loop */ - while (1) - { - } - } -} - -#elif defined SYSCLK_FREQ_56MHz -/** - * @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2 - * and PCLK1 prescalers. - * @note This function should be used only after reset. - * @param None - * @retval None - */ -static void SetSysClockTo56(void) -{ - __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ - /* Enable HSE */ - RCC->CR |= ((uint32_t)RCC_CR_HSEON); - - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC->CR & RCC_CR_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); - - if ((RCC->CR & RCC_CR_HSERDY) != RESET) - { - HSEStatus = (uint32_t)0x01; - } - else - { - HSEStatus = (uint32_t)0x00; - } - - if (HSEStatus == (uint32_t)0x01) - { - /* Enable Prefetch Buffer */ - FLASH->ACR |= FLASH_ACR_PRFTBE; - - /* Flash 2 wait state */ - FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); - FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2; - - /* HCLK = SYSCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; - - /* PCLK2 = HCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; - - /* PCLK1 = HCLK/2 */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; - -#ifdef STM32F10X_CL - /* Configure PLLs ------------------------------------------------------*/ - /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */ - /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */ - - RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL | - RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC); - RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 | - RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5); - - /* Enable PLL2 */ - RCC->CR |= RCC_CR_PLL2ON; - /* Wait till PLL2 is ready */ - while((RCC->CR & RCC_CR_PLL2RDY) == 0) - { - } - - - /* PLL configuration: PLLCLK = PREDIV1 * 7 = 56 MHz */ - RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL); - RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | - RCC_CFGR_PLLMULL7); -#else - /* PLL configuration: PLLCLK = HSE * 7 = 56 MHz */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); - RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL7); - -#endif /* STM32F10X_CL */ - - /* Enable PLL */ - RCC->CR |= RCC_CR_PLLON; - - /* Wait till PLL is ready */ - while((RCC->CR & RCC_CR_PLLRDY) == 0) - { - } - - /* Select PLL as system clock source */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); - RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; - - /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) - { - } - } - else - { /* If HSE fails to start-up, the application will have wrong clock - configuration. User can add here some code to deal with this error */ - - /* Go to infinite loop */ - while (1) - { - } - } -} - -#elif defined SYSCLK_FREQ_72MHz -/** - * @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2 - * and PCLK1 prescalers. - * @note This function should be used only after reset. - * @param None - * @retval None - */ -static void SetSysClockTo72(void) -{ - __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ - /* Enable HSE */ - RCC->CR |= ((uint32_t)RCC_CR_HSEON); - - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC->CR & RCC_CR_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); - - if ((RCC->CR & RCC_CR_HSERDY) != RESET) - { - HSEStatus = (uint32_t)0x01; - } - else - { - HSEStatus = (uint32_t)0x00; - } - - if (HSEStatus == (uint32_t)0x01) - { - /* Enable Prefetch Buffer */ - FLASH->ACR |= FLASH_ACR_PRFTBE; - - /* Flash 2 wait state */ - FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); - FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2; - - - /* HCLK = SYSCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; - - /* PCLK2 = HCLK */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; - - /* PCLK1 = HCLK/2 */ - RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; - -#ifdef STM32F10X_CL - /* Configure PLLs ------------------------------------------------------*/ - /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */ - /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */ - - RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL | - RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC); - RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 | - RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5); - - /* Enable PLL2 */ - RCC->CR |= RCC_CR_PLL2ON; - /* Wait till PLL2 is ready */ - while((RCC->CR & RCC_CR_PLL2RDY) == 0) - { - } - - - /* PLL configuration: PLLCLK = PREDIV1 * 9 = 72 MHz */ - RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL); - RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | - RCC_CFGR_PLLMULL9); -#else - /* PLL configuration: PLLCLK = HSE * 9 = 72 MHz */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | - RCC_CFGR_PLLMULL)); - RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL9); -#endif /* STM32F10X_CL */ - - /* Enable PLL */ - RCC->CR |= RCC_CR_PLLON; - - /* Wait till PLL is ready */ - while((RCC->CR & RCC_CR_PLLRDY) == 0) - { - } - - /* Select PLL as system clock source */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); - RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; - - /* Wait till PLL is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) - { - } - } - else - { /* If HSE fails to start-up, the application will have wrong clock - configuration. User can add here some code to deal with this error */ - - /* Go to infinite loop */ - while (1) - { - } - } -} -#endif - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file system_stm32f10x.c + * @author MCD Application Team + * @version V3.1.2 + * @date 09/28/2009 + * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Source File. + ****************************************************************************** + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2009 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f10x_system + * @{ + */ + +/** @addtogroup STM32F10x_System_Private_Includes + * @{ + */ + +#include "stm32f10x.h" + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Private_Defines + * @{ + */ + +/*!< Uncomment the line corresponding to the desired System clock (SYSCLK) + frequency (after reset the HSI is used as SYSCLK source) + + IMPORTANT NOTE: + ============== + 1. After each device reset the HSI is used as System clock source. + + 2. Please make sure that the selected System clock doesn't exceed your device's + maximum frequency. + + 3. If none of the define below is enabled, the HSI is used as System clock + source. + + 4. The System clock configuration functions provided within this file assume that: + - For Low, Medium and High density devices an external 8MHz crystal is + used to drive the System clock. + - For Connectivity line devices an external 25MHz crystal is used to drive + the System clock. + If you are using different crystal you have to adapt those functions accordingly. + */ + +/* #define SYSCLK_FREQ_HSE HSE_Value */ +/* #define SYSCLK_FREQ_24MHz 24000000 */ +/* #define SYSCLK_FREQ_36MHz 36000000 */ +/* #define SYSCLK_FREQ_48MHz 48000000 */ +/* #define SYSCLK_FREQ_56MHz 56000000 */ +#define SYSCLK_FREQ_72MHz 72000000 + +/*!< Uncomment the following line if you need to use external SRAM mounted + on STM3210E-EVAL board (STM32 High density devices) as data memory */ +#ifdef STM32F10X_HD +/* #define DATA_IN_ExtSRAM */ +#endif /* STM32F10X_HD */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Private_Variables + * @{ + */ + +/******************************************************************************* +* Clock Definitions +*******************************************************************************/ +#ifdef SYSCLK_FREQ_HSE + const uint32_t SystemFrequency = SYSCLK_FREQ_HSE; /*!< System Clock Frequency (Core Clock) */ + const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_HSE; /*!< System clock */ + const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_HSE; /*!< AHB System bus speed */ + const uint32_t SystemFrequency_APB1Clk = SYSCLK_FREQ_HSE; /*!< APB Peripheral bus 1 (low) speed */ + const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_HSE; /*!< APB Peripheral bus 2 (high) speed */ +#elif defined SYSCLK_FREQ_24MHz + const uint32_t SystemFrequency = SYSCLK_FREQ_24MHz; /*!< System Clock Frequency (Core Clock) */ + const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_24MHz; /*!< System clock */ + const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_24MHz; /*!< AHB System bus speed */ + const uint32_t SystemFrequency_APB1Clk = SYSCLK_FREQ_24MHz; /*!< APB Peripheral bus 1 (low) speed */ + const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_24MHz; /*!< APB Peripheral bus 2 (high) speed */ +#elif defined SYSCLK_FREQ_36MHz + const uint32_t SystemFrequency = SYSCLK_FREQ_36MHz; /*!< System Clock Frequency (Core Clock) */ + const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_36MHz; /*!< System clock */ + const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_36MHz; /*!< AHB System bus speed */ + const uint32_t SystemFrequency_APB1Clk = SYSCLK_FREQ_36MHz; /*!< APB Peripheral bus 1 (low) speed */ + const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_36MHz; /*!< APB Peripheral bus 2 (high) speed */ +#elif defined SYSCLK_FREQ_48MHz + const uint32_t SystemFrequency = SYSCLK_FREQ_48MHz; /*!< System Clock Frequency (Core Clock) */ + const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_48MHz; /*!< System clock */ + const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_48MHz; /*!< AHB System bus speed */ + const uint32_t SystemFrequency_APB1Clk = (SYSCLK_FREQ_48MHz/2); /*!< APB Peripheral bus 1 (low) speed */ + const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_48MHz; /*!< APB Peripheral bus 2 (high) speed */ +#elif defined SYSCLK_FREQ_56MHz + const uint32_t SystemFrequency = SYSCLK_FREQ_56MHz; /*!< System Clock Frequency (Core Clock) */ + const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_56MHz; /*!< System clock */ + const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_56MHz; /*!< AHB System bus speed */ + const uint32_t SystemFrequency_APB1Clk = (SYSCLK_FREQ_56MHz/2); /*!< APB Peripheral bus 1 (low) speed */ + const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_56MHz; /*!< APB Peripheral bus 2 (high) speed */ +#elif defined SYSCLK_FREQ_72MHz + const uint32_t SystemFrequency = SYSCLK_FREQ_72MHz; /*!< System Clock Frequency (Core Clock) */ + const uint32_t SystemFrequency_SysClk = SYSCLK_FREQ_72MHz; /*!< System clock */ + const uint32_t SystemFrequency_AHBClk = SYSCLK_FREQ_72MHz; /*!< AHB System bus speed */ + const uint32_t SystemFrequency_APB1Clk = (SYSCLK_FREQ_72MHz/2); /*!< APB Peripheral bus 1 (low) speed */ + const uint32_t SystemFrequency_APB2Clk = SYSCLK_FREQ_72MHz; /*!< APB Peripheral bus 2 (high) speed */ +#else /*!< HSI Selected as System Clock source */ + const uint32_t SystemFrequency = HSI_Value; /*!< System Clock Frequency (Core Clock) */ + const uint32_t SystemFrequency_SysClk = HSI_Value; /*!< System clock */ + const uint32_t SystemFrequency_AHBClk = HSI_Value; /*!< AHB System bus speed */ + const uint32_t SystemFrequency_APB1Clk = HSI_Value; /*!< APB Peripheral bus 1 (low) speed */ + const uint32_t SystemFrequency_APB2Clk = HSI_Value; /*!< APB Peripheral bus 2 (high) speed */ +#endif + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Private_FunctionPrototypes + * @{ + */ + +static void SetSysClock(void); + +#ifdef SYSCLK_FREQ_HSE + static void SetSysClockToHSE(void); +#elif defined SYSCLK_FREQ_24MHz + static void SetSysClockTo24(void); +#elif defined SYSCLK_FREQ_36MHz + static void SetSysClockTo36(void); +#elif defined SYSCLK_FREQ_48MHz + static void SetSysClockTo48(void); +#elif defined SYSCLK_FREQ_56MHz + static void SetSysClockTo56(void); +#elif defined SYSCLK_FREQ_72MHz + static void SetSysClockTo72(void); +#endif + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system + * Initialize the Embedded Flash Interface, the PLL and update the SystemFrequency variable. + * @note This function should be used only after reset. + * @param None + * @retval None + */ +void SystemInit (void) +{ + /* Reset the RCC clock configuration to the default reset state(for debug purpose) */ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ +#ifndef STM32F10X_CL + RCC->CFGR &= (uint32_t)0xF8FF0000; +#else + RCC->CFGR &= (uint32_t)0xF0FF0000; +#endif /* STM32F10X_CL */ + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ + RCC->CFGR &= (uint32_t)0xFF80FFFF; + +#ifndef STM32F10X_CL + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; +#else + /* Reset PLL2ON and PLL3ON bits */ + RCC->CR &= (uint32_t)0xEBFFFFFF; + + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x00FF0000; + + /* Reset CFGR2 register */ + RCC->CFGR2 = 0x00000000; +#endif /* STM32F10X_CL */ + + /* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */ + /* Configure the Flash Latency cycles and enable prefetch buffer */ + SetSysClock(); + +} + +/** + * @brief Configures the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers. + * @param None + * @retval None + */ +static void SetSysClock(void) +{ +#ifdef SYSCLK_FREQ_HSE + SetSysClockToHSE(); +#elif defined SYSCLK_FREQ_24MHz + SetSysClockTo24(); +#elif defined SYSCLK_FREQ_36MHz + SetSysClockTo36(); +#elif defined SYSCLK_FREQ_48MHz + SetSysClockTo48(); +#elif defined SYSCLK_FREQ_56MHz + SetSysClockTo56(); +#elif defined SYSCLK_FREQ_72MHz + SetSysClockTo72(); +#endif + + /* If none of the define above is enabled, the HSI is used as System clock + source (default after reset) */ +} + +/** + * @brief Setup the external memory controller. Called in startup_stm32f10x.s + * before jump to __main + * @param None + * @retval None + */ +#ifdef DATA_IN_ExtSRAM +/** + * @brief Setup the external memory controller. + * Called in startup_stm32f10x_xx.s/.c before jump to main. + * This function configures the external SRAM mounted on STM3210E-EVAL + * board (STM32 High density devices). This SRAM will be used as program + * data memory (including heap and stack). + * @param None + * @retval None + */ +void SystemInit_ExtMemCtl(void) +{ +/*!< FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is + required, then adjust the Register Addresses */ + + /* Enable FSMC clock */ + RCC->AHBENR = 0x00000114; + + /* Enable GPIOD, GPIOE, GPIOF and GPIOG clocks */ + RCC->APB2ENR = 0x000001E0; + +/* --------------- SRAM Data lines, NOE and NWE configuration ---------------*/ +/*---------------- SRAM Address lines configuration -------------------------*/ +/*---------------- NOE and NWE configuration --------------------------------*/ +/*---------------- NE3 configuration ----------------------------------------*/ +/*---------------- NBL0, NBL1 configuration ---------------------------------*/ + + GPIOD->CRL = 0x44BB44BB; + GPIOD->CRH = 0xBBBBBBBB; + + GPIOE->CRL = 0xB44444BB; + GPIOE->CRH = 0xBBBBBBBB; + + GPIOF->CRL = 0x44BBBBBB; + GPIOF->CRH = 0xBBBB4444; + + GPIOG->CRL = 0x44BBBBBB; + GPIOG->CRH = 0x44444B44; + +/*---------------- FSMC Configuration ---------------------------------------*/ +/*---------------- Enable FSMC Bank1_SRAM Bank ------------------------------*/ + + FSMC_Bank1->BTCR[4] = 0x00001011; + FSMC_Bank1->BTCR[5] = 0x00000200; +} +#endif /* DATA_IN_ExtSRAM */ + +#ifdef SYSCLK_FREQ_HSE +/** + * @brief Selects HSE as System clock source and configure HCLK, PCLK2 + * and PCLK1 prescalers. + * @note This function should be used only after reset. + * @param None + * @retval None + */ +static void SetSysClockToHSE(void) +{ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Enable Prefetch Buffer */ + FLASH->ACR |= FLASH_ACR_PRFTBE; + + /* Flash 0 wait state */ + FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); + +#ifndef STM32F10X_CL + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0; +#else + if (HSE_Value <= 24000000) + { + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0; + } + else + { + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1; + } +#endif /* STM32F10X_CL */ + + /* HCLK = SYSCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1; + + /* Select HSE as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_HSE; + + /* Wait till HSE is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x04) + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + + /* Go to infinite loop */ + while (1) + { + } + } +} +#elif defined SYSCLK_FREQ_24MHz +/** + * @brief Sets System clock frequency to 24MHz and configure HCLK, PCLK2 + * and PCLK1 prescalers. + * @note This function should be used only after reset. + * @param None + * @retval None + */ +static void SetSysClockTo24(void) +{ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Enable Prefetch Buffer */ + FLASH->ACR |= FLASH_ACR_PRFTBE; + + /* Flash 0 wait state */ + FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0; + + /* HCLK = SYSCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1; + +#ifdef STM32F10X_CL + /* Configure PLLs ------------------------------------------------------*/ + /* PLL configuration: PLLCLK = PREDIV1 * 6 = 24 MHz */ + RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | + RCC_CFGR_PLLMULL6); + + /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */ + /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 10 = 4 MHz */ + RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL | + RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC); + RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 | + RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV10); + + /* Enable PLL2 */ + RCC->CR |= RCC_CR_PLL2ON; + /* Wait till PLL2 is ready */ + while((RCC->CR & RCC_CR_PLL2RDY) == 0) + { + } +#else + /* PLL configuration: = (HSE / 2) * 6 = 24 MHz */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLXTPRE_HSE_Div2 | RCC_CFGR_PLLMULL6); +#endif /* STM32F10X_CL */ + + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Select PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + + /* Go to infinite loop */ + while (1) + { + } + } +} +#elif defined SYSCLK_FREQ_36MHz +/** + * @brief Sets System clock frequency to 36MHz and configure HCLK, PCLK2 + * and PCLK1 prescalers. + * @note This function should be used only after reset. + * @param None + * @retval None + */ +static void SetSysClockTo36(void) +{ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Enable Prefetch Buffer */ + FLASH->ACR |= FLASH_ACR_PRFTBE; + + /* Flash 1 wait state */ + FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1; + + /* HCLK = SYSCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1; + +#ifdef STM32F10X_CL + /* Configure PLLs ------------------------------------------------------*/ + + /* PLL configuration: PLLCLK = PREDIV1 * 9 = 36 MHz */ + RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | + RCC_CFGR_PLLMULL9); + + /*!< PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */ + /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 10 = 4 MHz */ + + RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL | + RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC); + RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 | + RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV10); + + /* Enable PLL2 */ + RCC->CR |= RCC_CR_PLL2ON; + /* Wait till PLL2 is ready */ + while((RCC->CR & RCC_CR_PLL2RDY) == 0) + { + } + +#else + /* PLL configuration: PLLCLK = (HSE / 2) * 9 = 36 MHz */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLXTPRE_HSE_Div2 | RCC_CFGR_PLLMULL9); +#endif /* STM32F10X_CL */ + + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Select PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + + /* Go to infinite loop */ + while (1) + { + } + } +} +#elif defined SYSCLK_FREQ_48MHz +/** + * @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2 + * and PCLK1 prescalers. + * @note This function should be used only after reset. + * @param None + * @retval None + */ +static void SetSysClockTo48(void) +{ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Enable Prefetch Buffer */ + FLASH->ACR |= FLASH_ACR_PRFTBE; + + /* Flash 1 wait state */ + FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1; + + /* HCLK = SYSCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK/2 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; + +#ifdef STM32F10X_CL + /* Configure PLLs ------------------------------------------------------*/ + /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */ + /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */ + + RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL | + RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC); + RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 | + RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5); + + /* Enable PLL2 */ + RCC->CR |= RCC_CR_PLL2ON; + /* Wait till PLL2 is ready */ + while((RCC->CR & RCC_CR_PLL2RDY) == 0) + { + } + + + /* PLL configuration: PLLCLK = PREDIV1 * 6 = 48 MHz */ + RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | + RCC_CFGR_PLLMULL6); +#else + /* PLL configuration: PLLCLK = HSE * 6 = 48 MHz */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL6); +#endif /* STM32F10X_CL */ + + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Select PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + + /* Go to infinite loop */ + while (1) + { + } + } +} + +#elif defined SYSCLK_FREQ_56MHz +/** + * @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2 + * and PCLK1 prescalers. + * @note This function should be used only after reset. + * @param None + * @retval None + */ +static void SetSysClockTo56(void) +{ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Enable Prefetch Buffer */ + FLASH->ACR |= FLASH_ACR_PRFTBE; + + /* Flash 2 wait state */ + FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2; + + /* HCLK = SYSCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK/2 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; + +#ifdef STM32F10X_CL + /* Configure PLLs ------------------------------------------------------*/ + /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */ + /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */ + + RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL | + RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC); + RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 | + RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5); + + /* Enable PLL2 */ + RCC->CR |= RCC_CR_PLL2ON; + /* Wait till PLL2 is ready */ + while((RCC->CR & RCC_CR_PLL2RDY) == 0) + { + } + + + /* PLL configuration: PLLCLK = PREDIV1 * 7 = 56 MHz */ + RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | + RCC_CFGR_PLLMULL7); +#else + /* PLL configuration: PLLCLK = HSE * 7 = 56 MHz */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL7); + +#endif /* STM32F10X_CL */ + + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Select PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + + /* Go to infinite loop */ + while (1) + { + } + } +} + +#elif defined SYSCLK_FREQ_72MHz +/** + * @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2 + * and PCLK1 prescalers. + * @note This function should be used only after reset. + * @param None + * @retval None + */ +static void SetSysClockTo72(void) +{ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSEStartUp_TimeOut)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Enable Prefetch Buffer */ + FLASH->ACR |= FLASH_ACR_PRFTBE; + + /* Flash 2 wait state */ + FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2; + + + /* HCLK = SYSCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK/2 */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; + +#ifdef STM32F10X_CL + /* Configure PLLs ------------------------------------------------------*/ + /* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */ + /* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */ + + RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL | + RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC); + RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 | + RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5); + + /* Enable PLL2 */ + RCC->CR |= RCC_CR_PLL2ON; + /* Wait till PLL2 is ready */ + while((RCC->CR & RCC_CR_PLL2RDY) == 0) + { + } + + + /* PLL configuration: PLLCLK = PREDIV1 * 9 = 72 MHz */ + RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 | + RCC_CFGR_PLLMULL9); +#else + /* PLL configuration: PLLCLK = HSE * 9 = 72 MHz */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | + RCC_CFGR_PLLMULL)); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL9); +#endif /* STM32F10X_CL */ + + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Select PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + + /* Go to infinite loop */ + while (1) + { + } + } +} +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/system_stm32f10x.h b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/system_stm32f10x.h index 22ce5a06f..6c5393913 100755 --- a/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/system_stm32f10x.h +++ b/flight/PiOS/STM32F10x/Libraries/CMSIS/Core/CM3/system_stm32f10x.h @@ -1,97 +1,97 @@ -/** - ****************************************************************************** - * @file system_stm32f10x.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File. - ****************************************************************************** - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f10x_system - * @{ - */ - -/** - * @brief Define to prevent recursive inclusion - */ -#ifndef __SYSTEM_STM32F10X_H -#define __SYSTEM_STM32F10X_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup STM32F10x_System_Includes - * @{ - */ - -/** - * @} - */ - - -/** @addtogroup STM32F10x_System_Exported_types - * @{ - */ - -extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ - -/** - * @} - */ - -/** @addtogroup STM32F10x_System_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F10x_System_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F10x_System_Exported_Functions - * @{ - */ - -extern void SystemInit(void); -extern void SystemCoreClockUpdate(void); -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__SYSTEM_STM32F10X_H */ - -/** - * @} - */ - -/** - * @} - */ -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file system_stm32f10x.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File. + ****************************************************************************** + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f10x_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32F10X_H +#define __SYSTEM_STM32F10X_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup STM32F10x_System_Includes + * @{ + */ + +/** + * @} + */ + + +/** @addtogroup STM32F10x_System_Exported_types + * @{ + */ + +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32F10X_H */ + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c index a02804ade..d9686b893 100755 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c @@ -1,300 +1,300 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the ARM CM3 port. - *----------------------------------------------------------*/ - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" - -/* For backward compatibility, ensure configKERNEL_INTERRUPT_PRIORITY is -defined. The value should also ensure backward compatibility. -FreeRTOS.org versions prior to V4.4.0 did not include this definition. */ -#ifndef configKERNEL_INTERRUPT_PRIORITY - #define configKERNEL_INTERRUPT_PRIORITY 255 -#endif - -/* Constants required to manipulate the NVIC. */ -#define portNVIC_SYSTICK_CTRL ( ( volatile unsigned long *) 0xe000e010 ) -#define portNVIC_SYSTICK_LOAD ( ( volatile unsigned long *) 0xe000e014 ) -#define portNVIC_INT_CTRL ( ( volatile unsigned long *) 0xe000ed04 ) -#define portNVIC_SYSPRI2 ( ( volatile unsigned long *) 0xe000ed20 ) -#define portNVIC_SYSTICK_CLK 0x00000004 -#define portNVIC_SYSTICK_INT 0x00000002 -#define portNVIC_SYSTICK_ENABLE 0x00000001 -#define portNVIC_PENDSVSET 0x10000000 -#define portNVIC_PENDSV_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 16 ) -#define portNVIC_SYSTICK_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 24 ) - -/* Constants required to set up the initial stack. */ -#define portINITIAL_XPSR ( 0x01000000 ) - -/* The priority used by the kernel is assigned to a variable to make access -from inline assembler easier. */ -const unsigned long ulKernelPriority = configKERNEL_INTERRUPT_PRIORITY; - -/* Each task maintains its own interrupt status in the critical nesting -variable. */ -static unsigned portBASE_TYPE uxCriticalNesting = 0xaaaaaaaa; - -/* - * Setup the timer to generate the tick interrupts. - */ -static void prvSetupTimerInterrupt( void ); - -/* - * Exception handlers. - */ -void xPortPendSVHandler( void ) __attribute__ (( naked )); -void xPortSysTickHandler( void ); -void vPortSVCHandler( void ) __attribute__ (( naked )); - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -static void prvPortStartFirstTask( void ) __attribute__ (( naked )); - -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ - /* Simulate the stack frame as it would be created by a context switch - interrupt. */ - pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */ - *pxTopOfStack = portINITIAL_XPSR; /* xPSR */ - pxTopOfStack--; - *pxTopOfStack = ( portSTACK_TYPE ) pxCode; /* PC */ - pxTopOfStack--; - *pxTopOfStack = 0; /* LR */ - pxTopOfStack -= 5; /* R12, R3, R2 and R1. */ - *pxTopOfStack = ( portSTACK_TYPE ) pvParameters; /* R0 */ - pxTopOfStack -= 8; /* R11, R10, R9, R8, R7, R6, R5 and R4. */ - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortSVCHandler( void ) -{ - __asm volatile ( - " ldr r3, pxCurrentTCBConst2 \n" /* Restore the context. */ - " ldr r1, [r3] \n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */ - " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */ - " ldmia r0!, {r4-r11} \n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */ - " msr psp, r0 \n" /* Restore the task stack pointer. */ - " mov r0, #0 \n" - " msr basepri, r0 \n" - " orr r14, #0xd \n" - " bx r14 \n" - " \n" - " .align 2 \n" - "pxCurrentTCBConst2: .word pxCurrentTCB \n" - ); -} -/*-----------------------------------------------------------*/ - -static void prvPortStartFirstTask( void ) -{ - __asm volatile( - " ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */ - " ldr r0, [r0] \n" - " ldr r0, [r0] \n" - " msr msp, r0 \n" /* Set the msp back to the start of the stack. */ - " cpsie i \n" /* Globally enable interrupts. */ - " svc 0 \n" /* System call to start first task. */ - " nop \n" - ); -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ - /* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0. - See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */ - configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY ); - - /* Make PendSV, CallSV and SysTick the same priroity as the kernel. */ - *(portNVIC_SYSPRI2) |= portNVIC_PENDSV_PRI; - *(portNVIC_SYSPRI2) |= portNVIC_SYSTICK_PRI; - - /* Start the timer that generates the tick ISR. Interrupts are disabled - here already. */ - prvSetupTimerInterrupt(); - - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - /* Start the first task. */ - prvPortStartFirstTask(); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ - /* It is unlikely that the CM3 port will require this function as there - is nothing to return to. */ -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Set a PendSV to request a context switch. */ - *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - portDISABLE_INTERRUPTS(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - uxCriticalNesting--; - if( uxCriticalNesting == 0 ) - { - portENABLE_INTERRUPTS(); - } -} -/*-----------------------------------------------------------*/ - -void xPortPendSVHandler( void ) -{ - /* This is a naked function. */ - - __asm volatile - ( - " mrs r0, psp \n" - " \n" - " ldr r3, pxCurrentTCBConst \n" /* Get the location of the current TCB. */ - " ldr r2, [r3] \n" - " \n" - " stmdb r0!, {r4-r11} \n" /* Save the remaining registers. */ - " str r0, [r2] \n" /* Save the new top of stack into the first member of the TCB. */ - " \n" - " stmdb sp!, {r3, r14} \n" - " mov r0, %0 \n" - " msr basepri, r0 \n" - " bl vTaskSwitchContext \n" - " mov r0, #0 \n" - " msr basepri, r0 \n" - " ldmia sp!, {r3, r14} \n" - " \n" /* Restore the context, including the critical nesting count. */ - " ldr r1, [r3] \n" - " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */ - " ldmia r0!, {r4-r11} \n" /* Pop the registers. */ - " msr psp, r0 \n" - " bx r14 \n" - " \n" - " .align 2 \n" - "pxCurrentTCBConst: .word pxCurrentTCB \n" - ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY) - ); -} -/*-----------------------------------------------------------*/ - -void xPortSysTickHandler( void ) -{ -unsigned long ulDummy; - - /* If using preemption, also force a context switch. */ - #if configUSE_PREEMPTION == 1 - *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; - #endif - - ulDummy = portSET_INTERRUPT_MASK_FROM_ISR(); - { - vTaskIncrementTick(); - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( ulDummy ); -} -/*-----------------------------------------------------------*/ - -/* - * Setup the systick timer to generate the tick interrupts at the required - * frequency. - */ -void prvSetupTimerInterrupt( void ) -{ - /* Configure SysTick to interrupt at the requested rate. */ - *(portNVIC_SYSTICK_LOAD) = ( configCPU_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL; - *(portNVIC_SYSTICK_CTRL) = portNVIC_SYSTICK_CLK | portNVIC_SYSTICK_INT | portNVIC_SYSTICK_ENABLE; -} -/*-----------------------------------------------------------*/ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +/*----------------------------------------------------------- + * Implementation of functions defined in portable.h for the ARM CM3 port. + *----------------------------------------------------------*/ + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" + +/* For backward compatibility, ensure configKERNEL_INTERRUPT_PRIORITY is +defined. The value should also ensure backward compatibility. +FreeRTOS.org versions prior to V4.4.0 did not include this definition. */ +#ifndef configKERNEL_INTERRUPT_PRIORITY + #define configKERNEL_INTERRUPT_PRIORITY 255 +#endif + +/* Constants required to manipulate the NVIC. */ +#define portNVIC_SYSTICK_CTRL ( ( volatile unsigned long *) 0xe000e010 ) +#define portNVIC_SYSTICK_LOAD ( ( volatile unsigned long *) 0xe000e014 ) +#define portNVIC_INT_CTRL ( ( volatile unsigned long *) 0xe000ed04 ) +#define portNVIC_SYSPRI2 ( ( volatile unsigned long *) 0xe000ed20 ) +#define portNVIC_SYSTICK_CLK 0x00000004 +#define portNVIC_SYSTICK_INT 0x00000002 +#define portNVIC_SYSTICK_ENABLE 0x00000001 +#define portNVIC_PENDSVSET 0x10000000 +#define portNVIC_PENDSV_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 16 ) +#define portNVIC_SYSTICK_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 24 ) + +/* Constants required to set up the initial stack. */ +#define portINITIAL_XPSR ( 0x01000000 ) + +/* The priority used by the kernel is assigned to a variable to make access +from inline assembler easier. */ +const unsigned long ulKernelPriority = configKERNEL_INTERRUPT_PRIORITY; + +/* Each task maintains its own interrupt status in the critical nesting +variable. */ +static unsigned portBASE_TYPE uxCriticalNesting = 0xaaaaaaaa; + +/* + * Setup the timer to generate the tick interrupts. + */ +static void prvSetupTimerInterrupt( void ); + +/* + * Exception handlers. + */ +void xPortPendSVHandler( void ) __attribute__ (( naked )); +void xPortSysTickHandler( void ); +void vPortSVCHandler( void ) __attribute__ (( naked )); + +/* + * Start first task is a separate function so it can be tested in isolation. + */ +static void prvPortStartFirstTask( void ) __attribute__ (( naked )); + +/*-----------------------------------------------------------*/ + +/* + * See header file for description. + */ +portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) +{ + /* Simulate the stack frame as it would be created by a context switch + interrupt. */ + pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */ + *pxTopOfStack = portINITIAL_XPSR; /* xPSR */ + pxTopOfStack--; + *pxTopOfStack = ( portSTACK_TYPE ) pxCode; /* PC */ + pxTopOfStack--; + *pxTopOfStack = 0; /* LR */ + pxTopOfStack -= 5; /* R12, R3, R2 and R1. */ + *pxTopOfStack = ( portSTACK_TYPE ) pvParameters; /* R0 */ + pxTopOfStack -= 8; /* R11, R10, R9, R8, R7, R6, R5 and R4. */ + + return pxTopOfStack; +} +/*-----------------------------------------------------------*/ + +void vPortSVCHandler( void ) +{ + __asm volatile ( + " ldr r3, pxCurrentTCBConst2 \n" /* Restore the context. */ + " ldr r1, [r3] \n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */ + " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */ + " ldmia r0!, {r4-r11} \n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */ + " msr psp, r0 \n" /* Restore the task stack pointer. */ + " mov r0, #0 \n" + " msr basepri, r0 \n" + " orr r14, #0xd \n" + " bx r14 \n" + " \n" + " .align 2 \n" + "pxCurrentTCBConst2: .word pxCurrentTCB \n" + ); +} +/*-----------------------------------------------------------*/ + +static void prvPortStartFirstTask( void ) +{ + __asm volatile( + " ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */ + " ldr r0, [r0] \n" + " ldr r0, [r0] \n" + " msr msp, r0 \n" /* Set the msp back to the start of the stack. */ + " cpsie i \n" /* Globally enable interrupts. */ + " svc 0 \n" /* System call to start first task. */ + " nop \n" + ); +} +/*-----------------------------------------------------------*/ + +/* + * See header file for description. + */ +portBASE_TYPE xPortStartScheduler( void ) +{ + /* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0. + See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */ + configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY ); + + /* Make PendSV, CallSV and SysTick the same priroity as the kernel. */ + *(portNVIC_SYSPRI2) |= portNVIC_PENDSV_PRI; + *(portNVIC_SYSPRI2) |= portNVIC_SYSTICK_PRI; + + /* Start the timer that generates the tick ISR. Interrupts are disabled + here already. */ + prvSetupTimerInterrupt(); + + /* Initialise the critical nesting count ready for the first task. */ + uxCriticalNesting = 0; + + /* Start the first task. */ + prvPortStartFirstTask(); + + /* Should not get here! */ + return 0; +} +/*-----------------------------------------------------------*/ + +void vPortEndScheduler( void ) +{ + /* It is unlikely that the CM3 port will require this function as there + is nothing to return to. */ +} +/*-----------------------------------------------------------*/ + +void vPortYieldFromISR( void ) +{ + /* Set a PendSV to request a context switch. */ + *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; +} +/*-----------------------------------------------------------*/ + +void vPortEnterCritical( void ) +{ + portDISABLE_INTERRUPTS(); + uxCriticalNesting++; +} +/*-----------------------------------------------------------*/ + +void vPortExitCritical( void ) +{ + uxCriticalNesting--; + if( uxCriticalNesting == 0 ) + { + portENABLE_INTERRUPTS(); + } +} +/*-----------------------------------------------------------*/ + +void xPortPendSVHandler( void ) +{ + /* This is a naked function. */ + + __asm volatile + ( + " mrs r0, psp \n" + " \n" + " ldr r3, pxCurrentTCBConst \n" /* Get the location of the current TCB. */ + " ldr r2, [r3] \n" + " \n" + " stmdb r0!, {r4-r11} \n" /* Save the remaining registers. */ + " str r0, [r2] \n" /* Save the new top of stack into the first member of the TCB. */ + " \n" + " stmdb sp!, {r3, r14} \n" + " mov r0, %0 \n" + " msr basepri, r0 \n" + " bl vTaskSwitchContext \n" + " mov r0, #0 \n" + " msr basepri, r0 \n" + " ldmia sp!, {r3, r14} \n" + " \n" /* Restore the context, including the critical nesting count. */ + " ldr r1, [r3] \n" + " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */ + " ldmia r0!, {r4-r11} \n" /* Pop the registers. */ + " msr psp, r0 \n" + " bx r14 \n" + " \n" + " .align 2 \n" + "pxCurrentTCBConst: .word pxCurrentTCB \n" + ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY) + ); +} +/*-----------------------------------------------------------*/ + +void xPortSysTickHandler( void ) +{ +unsigned long ulDummy; + + /* If using preemption, also force a context switch. */ + #if configUSE_PREEMPTION == 1 + *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; + #endif + + ulDummy = portSET_INTERRUPT_MASK_FROM_ISR(); + { + vTaskIncrementTick(); + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( ulDummy ); +} +/*-----------------------------------------------------------*/ + +/* + * Setup the systick timer to generate the tick interrupts at the required + * frequency. + */ +void prvSetupTimerInterrupt( void ) +{ + /* Configure SysTick to interrupt at the requested rate. */ + *(portNVIC_SYSTICK_LOAD) = ( configCPU_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL; + *(portNVIC_SYSTICK_CTRL) = portNVIC_SYSTICK_CLK | portNVIC_SYSTICK_INT | portNVIC_SYSTICK_ENABLE; +} +/*-----------------------------------------------------------*/ + diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h index f932fc858..e323dfc43 100755 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h @@ -1,173 +1,173 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#ifndef PORTMACRO_H -#define PORTMACRO_H - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * Port specific definitions. - * - * The settings in this file configure FreeRTOS correctly for the - * given hardware and compiler. - * - * These settings should not be altered. - *----------------------------------------------------------- - */ - -/* Type definitions. */ -#define portCHAR char -#define portFLOAT float -#define portDOUBLE double -#define portLONG long -#define portSHORT short -#define portSTACK_TYPE unsigned portLONG -#define portBASE_TYPE long - -#if( configUSE_16_BIT_TICKS == 1 ) - typedef unsigned portSHORT portTickType; - #define portMAX_DELAY ( portTickType ) 0xffff -#else - typedef unsigned portLONG portTickType; - #define portMAX_DELAY ( portTickType ) 0xffffffff -#endif -/*-----------------------------------------------------------*/ - -/* Architecture specifics. */ -#define portSTACK_GROWTH ( -1 ) -#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) -#define portBYTE_ALIGNMENT 4 -/*-----------------------------------------------------------*/ - - -/* Scheduler utilities. */ -extern void vPortYieldFromISR( void ); - -#define portYIELD() vPortYieldFromISR() - -#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() -/*-----------------------------------------------------------*/ - - -/* Critical section management. */ - -/* - * Set basepri to portMAX_SYSCALL_INTERRUPT_PRIORITY without effecting other - * registers. r0 is clobbered. - */ -#define portSET_INTERRUPT_MASK() \ - __asm volatile \ - ( \ - " mov r0, %0 \n" \ - " msr basepri, r0 \n" \ - ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY):"r0" \ - ) - -/* - * Set basepri back to 0 without effective other registers. - * r0 is clobbered. FAQ: Setting BASEPRI to 0 is not a bug. Please see - * http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before disagreeing. - */ -#define portCLEAR_INTERRUPT_MASK() \ - __asm volatile \ - ( \ - " mov r0, #0 \n" \ - " msr basepri, r0 \n" \ - :::"r0" \ - ) - -/* FAQ: Setting BASEPRI to 0 in portCLEAR_INTERRUPT_MASK_FROM_ISR() is not a -bug. Please see http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before -disagreeing. */ -#define portSET_INTERRUPT_MASK_FROM_ISR() 0;portSET_INTERRUPT_MASK() -#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) portCLEAR_INTERRUPT_MASK();(void)x - - -extern void vPortEnterCritical( void ); -extern void vPortExitCritical( void ); - -#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() -#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() -#define portENTER_CRITICAL() vPortEnterCritical() -#define portEXIT_CRITICAL() vPortExitCritical() -/*-----------------------------------------------------------*/ - -/* Task function macros as described on the FreeRTOS.org WEB site. */ -#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) -#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) - -#define portNOP() - -#ifdef __cplusplus -} -#endif - -#endif /* PORTMACRO_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#ifndef PORTMACRO_H +#define PORTMACRO_H + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * Port specific definitions. + * + * The settings in this file configure FreeRTOS correctly for the + * given hardware and compiler. + * + * These settings should not be altered. + *----------------------------------------------------------- + */ + +/* Type definitions. */ +#define portCHAR char +#define portFLOAT float +#define portDOUBLE double +#define portLONG long +#define portSHORT short +#define portSTACK_TYPE unsigned portLONG +#define portBASE_TYPE long + +#if( configUSE_16_BIT_TICKS == 1 ) + typedef unsigned portSHORT portTickType; + #define portMAX_DELAY ( portTickType ) 0xffff +#else + typedef unsigned portLONG portTickType; + #define portMAX_DELAY ( portTickType ) 0xffffffff +#endif +/*-----------------------------------------------------------*/ + +/* Architecture specifics. */ +#define portSTACK_GROWTH ( -1 ) +#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) +#define portBYTE_ALIGNMENT 4 +/*-----------------------------------------------------------*/ + + +/* Scheduler utilities. */ +extern void vPortYieldFromISR( void ); + +#define portYIELD() vPortYieldFromISR() + +#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() +/*-----------------------------------------------------------*/ + + +/* Critical section management. */ + +/* + * Set basepri to portMAX_SYSCALL_INTERRUPT_PRIORITY without effecting other + * registers. r0 is clobbered. + */ +#define portSET_INTERRUPT_MASK() \ + __asm volatile \ + ( \ + " mov r0, %0 \n" \ + " msr basepri, r0 \n" \ + ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY):"r0" \ + ) + +/* + * Set basepri back to 0 without effective other registers. + * r0 is clobbered. FAQ: Setting BASEPRI to 0 is not a bug. Please see + * http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before disagreeing. + */ +#define portCLEAR_INTERRUPT_MASK() \ + __asm volatile \ + ( \ + " mov r0, #0 \n" \ + " msr basepri, r0 \n" \ + :::"r0" \ + ) + +/* FAQ: Setting BASEPRI to 0 in portCLEAR_INTERRUPT_MASK_FROM_ISR() is not a +bug. Please see http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before +disagreeing. */ +#define portSET_INTERRUPT_MASK_FROM_ISR() 0;portSET_INTERRUPT_MASK() +#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) portCLEAR_INTERRUPT_MASK();(void)x + + +extern void vPortEnterCritical( void ); +extern void vPortExitCritical( void ); + +#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() +#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() +#define portENTER_CRITICAL() vPortEnterCritical() +#define portEXIT_CRITICAL() vPortExitCritical() +/*-----------------------------------------------------------*/ + +/* Task function macros as described on the FreeRTOS.org WEB site. */ +#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) +#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) + +#define portNOP() + +#ifdef __cplusplus +} +#endif + +#endif /* PORTMACRO_H */ + diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_1.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_1.c index f3abbb52c..166c897a7 100644 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_1.c +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_1.c @@ -1,160 +1,160 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -/* - * The simplest possible implementation of pvPortMalloc(). Note that this - * implementation does NOT allow allocated memory to be freed again. - * - * See heap_2.c and heap_3.c for alternative implementations, and the memory - * management pages of http://www.FreeRTOS.org for more information. - */ -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* Allocate the memory for the heap. The struct is used to force byte -alignment without using any non-portable code. */ -static union xRTOS_HEAP -{ - #if portBYTE_ALIGNMENT == 8 - volatile portDOUBLE dDummy; - #else - volatile unsigned long ulDummy; - #endif - unsigned char ucHeap[ configTOTAL_HEAP_SIZE ]; -} xHeap __attribute__ ((section (".heap"))); - -static size_t xNextFreeByte = ( size_t ) 0; -static size_t currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE; - -/*-----------------------------------------------------------*/ - -void *pvPortMalloc( size_t xWantedSize ) -{ -void *pvReturn = NULL; - - /* Ensure that blocks are always aligned to the required number of bytes. */ - #if portBYTE_ALIGNMENT != 1 - if( xWantedSize & portBYTE_ALIGNMENT_MASK ) - { - /* Byte alignment required. */ - xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); - } - #endif - - vTaskSuspendAll(); - { - /* Check there is enough room left for the allocation. */ - if( ( ( xNextFreeByte + xWantedSize ) < currentTOTAL_HEAP_SIZE ) && - ( ( xNextFreeByte + xWantedSize ) > xNextFreeByte ) )/* Check for overflow. */ - { - /* Return the next free byte then increment the index past this - block. */ - pvReturn = &( xHeap.ucHeap[ xNextFreeByte ] ); - xNextFreeByte += xWantedSize; - } - } - xTaskResumeAll(); - - #if( configUSE_MALLOC_FAILED_HOOK == 1 ) - { - if( pvReturn == NULL ) - { - extern void vApplicationMallocFailedHook( void ); - vApplicationMallocFailedHook(); - } - } - #endif - - return pvReturn; -} -/*-----------------------------------------------------------*/ - -void vPortFree( void *pv ) -{ - /* Memory cannot be freed using this scheme. See heap_2.c and heap_3.c - for alternative implementations, and the memory management pages of - http://www.FreeRTOS.org for more information. */ - ( void ) pv; -} -/*-----------------------------------------------------------*/ - -void vPortInitialiseBlocks( void ) -{ - /* Only required when static memory is not cleared. */ - xNextFreeByte = ( size_t ) 0; -} -/*-----------------------------------------------------------*/ - -size_t xPortGetFreeHeapSize( void ) -{ - return ( currentTOTAL_HEAP_SIZE - xNextFreeByte ); -} -/*-----------------------------------------------------------*/ - -void xPortIncreaseHeapSize( size_t bytes ) -{ - vTaskSuspendAll(); - currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE + bytes; - xTaskResumeAll(); -} -/*-----------------------------------------------------------*/ +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +/* + * The simplest possible implementation of pvPortMalloc(). Note that this + * implementation does NOT allow allocated memory to be freed again. + * + * See heap_2.c and heap_3.c for alternative implementations, and the memory + * management pages of http://www.FreeRTOS.org for more information. + */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* Allocate the memory for the heap. The struct is used to force byte +alignment without using any non-portable code. */ +static union xRTOS_HEAP +{ + #if portBYTE_ALIGNMENT == 8 + volatile portDOUBLE dDummy; + #else + volatile unsigned long ulDummy; + #endif + unsigned char ucHeap[ configTOTAL_HEAP_SIZE ]; +} xHeap __attribute__ ((section (".heap"))); + +static size_t xNextFreeByte = ( size_t ) 0; +static size_t currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE; + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +void *pvReturn = NULL; + + /* Ensure that blocks are always aligned to the required number of bytes. */ + #if portBYTE_ALIGNMENT != 1 + if( xWantedSize & portBYTE_ALIGNMENT_MASK ) + { + /* Byte alignment required. */ + xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); + } + #endif + + vTaskSuspendAll(); + { + /* Check there is enough room left for the allocation. */ + if( ( ( xNextFreeByte + xWantedSize ) < currentTOTAL_HEAP_SIZE ) && + ( ( xNextFreeByte + xWantedSize ) > xNextFreeByte ) )/* Check for overflow. */ + { + /* Return the next free byte then increment the index past this + block. */ + pvReturn = &( xHeap.ucHeap[ xNextFreeByte ] ); + xNextFreeByte += xWantedSize; + } + } + xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ + /* Memory cannot be freed using this scheme. See heap_2.c and heap_3.c + for alternative implementations, and the memory management pages of + http://www.FreeRTOS.org for more information. */ + ( void ) pv; +} +/*-----------------------------------------------------------*/ + +void vPortInitialiseBlocks( void ) +{ + /* Only required when static memory is not cleared. */ + xNextFreeByte = ( size_t ) 0; +} +/*-----------------------------------------------------------*/ + +size_t xPortGetFreeHeapSize( void ) +{ + return ( currentTOTAL_HEAP_SIZE - xNextFreeByte ); +} +/*-----------------------------------------------------------*/ + +void xPortIncreaseHeapSize( size_t bytes ) +{ + vTaskSuspendAll(); + currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE + bytes; + xTaskResumeAll(); +} +/*-----------------------------------------------------------*/ diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_2.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_2.c index 91258edd6..c95653ff8 100644 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_2.c +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_2.c @@ -1,294 +1,294 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/* - * A sample implementation of pvPortMalloc() and vPortFree() that permits - * allocated blocks to be freed, but does not combine adjacent free blocks - * into a single larger block. - * - * See heap_1.c and heap_3.c for alternative implementations, and the memory - * management pages of http://www.FreeRTOS.org for more information. - */ -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/* Allocate the memory for the heap. The struct is used to force byte -alignment without using any non-portable code. */ -static union xRTOS_HEAP -{ - #if portBYTE_ALIGNMENT == 8 - volatile portDOUBLE dDummy; - #else - volatile unsigned long ulDummy; - #endif - unsigned char ucHeap[ configTOTAL_HEAP_SIZE ]; -} xHeap __attribute__ ((section (".heap"))); - -/* Define the linked list structure. This is used to link free blocks in order -of their size. */ -typedef struct A_BLOCK_LINK -{ - struct A_BLOCK_LINK *pxNextFreeBlock; /*<< The next free block in the list. */ - size_t xBlockSize; /*<< The size of the free block. */ -} xBlockLink; - - -static const unsigned short heapSTRUCT_SIZE = ( sizeof( xBlockLink ) + portBYTE_ALIGNMENT - ( sizeof( xBlockLink ) % portBYTE_ALIGNMENT ) ); -#define heapMINIMUM_BLOCK_SIZE ( ( size_t ) ( heapSTRUCT_SIZE * 2 ) ) - -/* Create a couple of list links to mark the start and end of the list. */ -static xBlockLink xStart, xEnd; - -/* Keeps track of the number of free bytes remaining, but says nothing about -fragmentation. */ -static size_t xFreeBytesRemaining = configTOTAL_HEAP_SIZE; -static size_t currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE; - -/* STATIC FUNCTIONS ARE DEFINED AS MACROS TO MINIMIZE THE FUNCTION CALL DEPTH. */ - -/* - * Insert a block into the list of free blocks - which is ordered by size of - * the block. Small blocks at the start of the list and large blocks at the end - * of the list. - */ -#define prvInsertBlockIntoFreeList( pxBlockToInsert ) \ -{ \ -xBlockLink *pxIterator; \ -size_t xBlockSize; \ - \ - xBlockSize = pxBlockToInsert->xBlockSize; \ - \ - /* Iterate through the list until a block is found that has a larger size */ \ - /* than the block we are inserting. */ \ - for( pxIterator = &xStart; pxIterator->pxNextFreeBlock->xBlockSize < xBlockSize; pxIterator = pxIterator->pxNextFreeBlock ) \ - { \ - /* There is nothing to do here - just iterate to the correct position. */ \ - } \ - \ - /* Update the list to include the block being inserted in the correct */ \ - /* position. */ \ - pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock; \ - pxIterator->pxNextFreeBlock = pxBlockToInsert; \ -} -/*-----------------------------------------------------------*/ - -#define prvHeapInit() \ -{ \ -xBlockLink *pxFirstFreeBlock; \ - \ - /* xStart is used to hold a pointer to the first item in the list of free */ \ - /* blocks. The void cast is used to prevent compiler warnings. */ \ - xStart.pxNextFreeBlock = ( void * ) xHeap.ucHeap; \ - xStart.xBlockSize = ( size_t ) 0; \ - \ - /* xEnd is used to mark the end of the list of free blocks. */ \ - xEnd.xBlockSize = currentTOTAL_HEAP_SIZE; \ - xEnd.pxNextFreeBlock = NULL; \ - \ - /* To start with there is a single free block that is sized to take up the \ - entire heap space. */ \ - pxFirstFreeBlock = ( void * ) xHeap.ucHeap; \ - pxFirstFreeBlock->xBlockSize = currentTOTAL_HEAP_SIZE; \ - pxFirstFreeBlock->pxNextFreeBlock = &xEnd; \ -} -/*-----------------------------------------------------------*/ - -void *pvPortMalloc( size_t xWantedSize ) -{ -xBlockLink *pxBlock, *pxPreviousBlock, *pxNewBlockLink; -static portBASE_TYPE xHeapHasBeenInitialised = pdFALSE; -void *pvReturn = NULL; - - vTaskSuspendAll(); - { - /* If this is the first call to malloc then the heap will require - initialisation to setup the list of free blocks. */ - if( xHeapHasBeenInitialised == pdFALSE ) - { - prvHeapInit(); - xHeapHasBeenInitialised = pdTRUE; - } - - /* The wanted size is increased so it can contain a xBlockLink - structure in addition to the requested amount of bytes. */ - if( xWantedSize > 0 ) - { - xWantedSize += heapSTRUCT_SIZE; - - /* Ensure that blocks are always aligned to the required number of bytes. */ - if( xWantedSize & portBYTE_ALIGNMENT_MASK ) - { - /* Byte alignment required. */ - xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); - } - } - - if( ( xWantedSize > 0 ) && ( xWantedSize < currentTOTAL_HEAP_SIZE ) ) - { - /* Blocks are stored in byte order - traverse the list from the start - (smallest) block until one of adequate size is found. */ - pxPreviousBlock = &xStart; - pxBlock = xStart.pxNextFreeBlock; - while( ( pxBlock->xBlockSize < xWantedSize ) && ( pxBlock->pxNextFreeBlock ) ) - { - pxPreviousBlock = pxBlock; - pxBlock = pxBlock->pxNextFreeBlock; - } - - /* If we found the end marker then a block of adequate size was not found. */ - if( pxBlock != &xEnd ) - { - /* Return the memory space - jumping over the xBlockLink structure - at its start. */ - pvReturn = ( void * ) ( ( ( unsigned char * ) pxPreviousBlock->pxNextFreeBlock ) + heapSTRUCT_SIZE ); - - /* This block is being returned for use so must be taken our of the - list of free blocks. */ - pxPreviousBlock->pxNextFreeBlock = pxBlock->pxNextFreeBlock; - - /* If the block is larger than required it can be split into two. */ - if( ( pxBlock->xBlockSize - xWantedSize ) > heapMINIMUM_BLOCK_SIZE ) - { - /* This block is to be split into two. Create a new block - following the number of bytes requested. The void cast is - used to prevent byte alignment warnings from the compiler. */ - pxNewBlockLink = ( void * ) ( ( ( unsigned char * ) pxBlock ) + xWantedSize ); - - /* Calculate the sizes of two blocks split from the single - block. */ - pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - xWantedSize; - pxBlock->xBlockSize = xWantedSize; - - /* Insert the new block into the list of free blocks. */ - prvInsertBlockIntoFreeList( ( pxNewBlockLink ) ); - } - - xFreeBytesRemaining -= pxBlock->xBlockSize; - } - } - } - xTaskResumeAll(); - - #if( configUSE_MALLOC_FAILED_HOOK == 1 ) - { - if( pvReturn == NULL ) - { - extern void vApplicationMallocFailedHook( void ); - vApplicationMallocFailedHook(); - } - } - #endif - - return pvReturn; -} -/*-----------------------------------------------------------*/ - -void vPortFree( void *pv ) -{ -unsigned char *puc = ( unsigned char * ) pv; -xBlockLink *pxLink; - - if( pv ) - { - /* The memory being freed will have an xBlockLink structure immediately - before it. */ - puc -= heapSTRUCT_SIZE; - - /* This casting is to keep the compiler from issuing warnings. */ - pxLink = ( void * ) puc; - - vTaskSuspendAll(); - { - /* Add this block to the list of free blocks. */ - prvInsertBlockIntoFreeList( ( ( xBlockLink * ) pxLink ) ); - xFreeBytesRemaining += pxLink->xBlockSize; - } - xTaskResumeAll(); - } -} -/*-----------------------------------------------------------*/ - -size_t xPortGetFreeHeapSize( void ) -{ - return xFreeBytesRemaining; -} -/*-----------------------------------------------------------*/ - -void vPortInitialiseBlocks( void ) -{ - /* This just exists to keep the linker quiet. */ -} - -void xPortIncreaseHeapSize( size_t bytes ) -{ - xBlockLink *pxNewBlockLink; - vTaskSuspendAll(); - currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE + bytes; - xEnd.xBlockSize = currentTOTAL_HEAP_SIZE; - xFreeBytesRemaining += bytes; - /* Insert the new block into the list of free blocks. */ - pxNewBlockLink = ( void * ) &xHeap.ucHeap[ configTOTAL_HEAP_SIZE ]; - pxNewBlockLink->xBlockSize = bytes; - prvInsertBlockIntoFreeList( ( pxNewBlockLink ) ); - xTaskResumeAll(); -} -/*-----------------------------------------------------------*/ +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/* + * A sample implementation of pvPortMalloc() and vPortFree() that permits + * allocated blocks to be freed, but does not combine adjacent free blocks + * into a single larger block. + * + * See heap_1.c and heap_3.c for alternative implementations, and the memory + * management pages of http://www.FreeRTOS.org for more information. + */ +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/* Allocate the memory for the heap. The struct is used to force byte +alignment without using any non-portable code. */ +static union xRTOS_HEAP +{ + #if portBYTE_ALIGNMENT == 8 + volatile portDOUBLE dDummy; + #else + volatile unsigned long ulDummy; + #endif + unsigned char ucHeap[ configTOTAL_HEAP_SIZE ]; +} xHeap __attribute__ ((section (".heap"))); + +/* Define the linked list structure. This is used to link free blocks in order +of their size. */ +typedef struct A_BLOCK_LINK +{ + struct A_BLOCK_LINK *pxNextFreeBlock; /*<< The next free block in the list. */ + size_t xBlockSize; /*<< The size of the free block. */ +} xBlockLink; + + +static const unsigned short heapSTRUCT_SIZE = ( sizeof( xBlockLink ) + portBYTE_ALIGNMENT - ( sizeof( xBlockLink ) % portBYTE_ALIGNMENT ) ); +#define heapMINIMUM_BLOCK_SIZE ( ( size_t ) ( heapSTRUCT_SIZE * 2 ) ) + +/* Create a couple of list links to mark the start and end of the list. */ +static xBlockLink xStart, xEnd; + +/* Keeps track of the number of free bytes remaining, but says nothing about +fragmentation. */ +static size_t xFreeBytesRemaining = configTOTAL_HEAP_SIZE; +static size_t currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE; + +/* STATIC FUNCTIONS ARE DEFINED AS MACROS TO MINIMIZE THE FUNCTION CALL DEPTH. */ + +/* + * Insert a block into the list of free blocks - which is ordered by size of + * the block. Small blocks at the start of the list and large blocks at the end + * of the list. + */ +#define prvInsertBlockIntoFreeList( pxBlockToInsert ) \ +{ \ +xBlockLink *pxIterator; \ +size_t xBlockSize; \ + \ + xBlockSize = pxBlockToInsert->xBlockSize; \ + \ + /* Iterate through the list until a block is found that has a larger size */ \ + /* than the block we are inserting. */ \ + for( pxIterator = &xStart; pxIterator->pxNextFreeBlock->xBlockSize < xBlockSize; pxIterator = pxIterator->pxNextFreeBlock ) \ + { \ + /* There is nothing to do here - just iterate to the correct position. */ \ + } \ + \ + /* Update the list to include the block being inserted in the correct */ \ + /* position. */ \ + pxBlockToInsert->pxNextFreeBlock = pxIterator->pxNextFreeBlock; \ + pxIterator->pxNextFreeBlock = pxBlockToInsert; \ +} +/*-----------------------------------------------------------*/ + +#define prvHeapInit() \ +{ \ +xBlockLink *pxFirstFreeBlock; \ + \ + /* xStart is used to hold a pointer to the first item in the list of free */ \ + /* blocks. The void cast is used to prevent compiler warnings. */ \ + xStart.pxNextFreeBlock = ( void * ) xHeap.ucHeap; \ + xStart.xBlockSize = ( size_t ) 0; \ + \ + /* xEnd is used to mark the end of the list of free blocks. */ \ + xEnd.xBlockSize = currentTOTAL_HEAP_SIZE; \ + xEnd.pxNextFreeBlock = NULL; \ + \ + /* To start with there is a single free block that is sized to take up the \ + entire heap space. */ \ + pxFirstFreeBlock = ( void * ) xHeap.ucHeap; \ + pxFirstFreeBlock->xBlockSize = currentTOTAL_HEAP_SIZE; \ + pxFirstFreeBlock->pxNextFreeBlock = &xEnd; \ +} +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +xBlockLink *pxBlock, *pxPreviousBlock, *pxNewBlockLink; +static portBASE_TYPE xHeapHasBeenInitialised = pdFALSE; +void *pvReturn = NULL; + + vTaskSuspendAll(); + { + /* If this is the first call to malloc then the heap will require + initialisation to setup the list of free blocks. */ + if( xHeapHasBeenInitialised == pdFALSE ) + { + prvHeapInit(); + xHeapHasBeenInitialised = pdTRUE; + } + + /* The wanted size is increased so it can contain a xBlockLink + structure in addition to the requested amount of bytes. */ + if( xWantedSize > 0 ) + { + xWantedSize += heapSTRUCT_SIZE; + + /* Ensure that blocks are always aligned to the required number of bytes. */ + if( xWantedSize & portBYTE_ALIGNMENT_MASK ) + { + /* Byte alignment required. */ + xWantedSize += ( portBYTE_ALIGNMENT - ( xWantedSize & portBYTE_ALIGNMENT_MASK ) ); + } + } + + if( ( xWantedSize > 0 ) && ( xWantedSize < currentTOTAL_HEAP_SIZE ) ) + { + /* Blocks are stored in byte order - traverse the list from the start + (smallest) block until one of adequate size is found. */ + pxPreviousBlock = &xStart; + pxBlock = xStart.pxNextFreeBlock; + while( ( pxBlock->xBlockSize < xWantedSize ) && ( pxBlock->pxNextFreeBlock ) ) + { + pxPreviousBlock = pxBlock; + pxBlock = pxBlock->pxNextFreeBlock; + } + + /* If we found the end marker then a block of adequate size was not found. */ + if( pxBlock != &xEnd ) + { + /* Return the memory space - jumping over the xBlockLink structure + at its start. */ + pvReturn = ( void * ) ( ( ( unsigned char * ) pxPreviousBlock->pxNextFreeBlock ) + heapSTRUCT_SIZE ); + + /* This block is being returned for use so must be taken our of the + list of free blocks. */ + pxPreviousBlock->pxNextFreeBlock = pxBlock->pxNextFreeBlock; + + /* If the block is larger than required it can be split into two. */ + if( ( pxBlock->xBlockSize - xWantedSize ) > heapMINIMUM_BLOCK_SIZE ) + { + /* This block is to be split into two. Create a new block + following the number of bytes requested. The void cast is + used to prevent byte alignment warnings from the compiler. */ + pxNewBlockLink = ( void * ) ( ( ( unsigned char * ) pxBlock ) + xWantedSize ); + + /* Calculate the sizes of two blocks split from the single + block. */ + pxNewBlockLink->xBlockSize = pxBlock->xBlockSize - xWantedSize; + pxBlock->xBlockSize = xWantedSize; + + /* Insert the new block into the list of free blocks. */ + prvInsertBlockIntoFreeList( ( pxNewBlockLink ) ); + } + + xFreeBytesRemaining -= pxBlock->xBlockSize; + } + } + } + xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ +unsigned char *puc = ( unsigned char * ) pv; +xBlockLink *pxLink; + + if( pv ) + { + /* The memory being freed will have an xBlockLink structure immediately + before it. */ + puc -= heapSTRUCT_SIZE; + + /* This casting is to keep the compiler from issuing warnings. */ + pxLink = ( void * ) puc; + + vTaskSuspendAll(); + { + /* Add this block to the list of free blocks. */ + prvInsertBlockIntoFreeList( ( ( xBlockLink * ) pxLink ) ); + xFreeBytesRemaining += pxLink->xBlockSize; + } + xTaskResumeAll(); + } +} +/*-----------------------------------------------------------*/ + +size_t xPortGetFreeHeapSize( void ) +{ + return xFreeBytesRemaining; +} +/*-----------------------------------------------------------*/ + +void vPortInitialiseBlocks( void ) +{ + /* This just exists to keep the linker quiet. */ +} + +void xPortIncreaseHeapSize( size_t bytes ) +{ + xBlockLink *pxNewBlockLink; + vTaskSuspendAll(); + currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE + bytes; + xEnd.xBlockSize = currentTOTAL_HEAP_SIZE; + xFreeBytesRemaining += bytes; + /* Insert the new block into the list of free blocks. */ + pxNewBlockLink = ( void * ) &xHeap.ucHeap[ configTOTAL_HEAP_SIZE ]; + pxNewBlockLink->xBlockSize = bytes; + prvInsertBlockIntoFreeList( ( pxNewBlockLink ) ); + xTaskResumeAll(); +} +/*-----------------------------------------------------------*/ diff --git a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c index fa799a0c2..079c6cfdb 100644 --- a/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c +++ b/flight/PiOS/STM32F10x/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c @@ -1,117 +1,117 @@ -/* - FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -/* - * Implementation of pvPortMalloc() and vPortFree() that relies on the - * compilers own malloc() and free() implementations. - * - * This file can only be used if the linker is configured to to generate - * a heap memory area. - * - * See heap_2.c and heap_1.c for alternative implementations, and the memory - * management pages of http://www.FreeRTOS.org for more information. - */ - -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/*-----------------------------------------------------------*/ - -void *pvPortMalloc( size_t xWantedSize ) -{ -void *pvReturn; - - vTaskSuspendAll(); - { - pvReturn = malloc( xWantedSize ); - } - xTaskResumeAll(); - - #if( configUSE_MALLOC_FAILED_HOOK == 1 ) - { - if( pvReturn == NULL ) - { - extern void vApplicationMallocFailedHook( void ); - vApplicationMallocFailedHook(); - } - } - #endif - - return pvReturn; -} -/*-----------------------------------------------------------*/ - -void vPortFree( void *pv ) -{ - if( pv ) - { - vTaskSuspendAll(); - { - free( pv ); - } - xTaskResumeAll(); - } -} - - - +/* + FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +/* + * Implementation of pvPortMalloc() and vPortFree() that relies on the + * compilers own malloc() and free() implementations. + * + * This file can only be used if the linker is configured to to generate + * a heap memory area. + * + * See heap_2.c and heap_1.c for alternative implementations, and the memory + * management pages of http://www.FreeRTOS.org for more information. + */ + +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +void *pvReturn; + + vTaskSuspendAll(); + { + pvReturn = malloc( xWantedSize ); + } + xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ + if( pv ) + { + vTaskSuspendAll(); + { + free( pv ); + } + xTaskResumeAll(); + } +} + + + diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/misc.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/misc.h index 9702ae187..8aa193699 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/misc.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/misc.h @@ -1,219 +1,219 @@ -/** - ****************************************************************************** - * @file misc.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the miscellaneous - * firmware library functions (add-on to CMSIS functions). - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __MISC_H -#define __MISC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup MISC - * @{ - */ - -/** @defgroup MISC_Exported_Types - * @{ - */ - -/** - * @brief NVIC Init Structure definition - */ - -typedef struct -{ - uint8_t NVIC_IRQChannel; /*!< Specifies the IRQ channel to be enabled or disabled. - This parameter can be a value of @ref IRQn_Type - (For the complete STM32 Devices IRQ Channels list, please - refer to stm32f10x.h file) */ - - uint8_t NVIC_IRQChannelPreemptionPriority; /*!< Specifies the pre-emption priority for the IRQ channel - specified in NVIC_IRQChannel. This parameter can be a value - between 0 and 15 as described in the table @ref NVIC_Priority_Table */ - - uint8_t NVIC_IRQChannelSubPriority; /*!< Specifies the subpriority level for the IRQ channel specified - in NVIC_IRQChannel. This parameter can be a value - between 0 and 15 as described in the table @ref NVIC_Priority_Table */ - - FunctionalState NVIC_IRQChannelCmd; /*!< Specifies whether the IRQ channel defined in NVIC_IRQChannel - will be enabled or disabled. - This parameter can be set either to ENABLE or DISABLE */ -} NVIC_InitTypeDef; - -/** - * @} - */ - -/** @defgroup NVIC_Priority_Table - * @{ - */ - -/** -@code - The table below gives the allowed values of the pre-emption priority and subpriority according - to the Priority Grouping configuration performed by NVIC_PriorityGroupConfig function - ============================================================================================================================ - NVIC_PriorityGroup | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority | Description - ============================================================================================================================ - NVIC_PriorityGroup_0 | 0 | 0-15 | 0 bits for pre-emption priority - | | | 4 bits for subpriority - ---------------------------------------------------------------------------------------------------------------------------- - NVIC_PriorityGroup_1 | 0-1 | 0-7 | 1 bits for pre-emption priority - | | | 3 bits for subpriority - ---------------------------------------------------------------------------------------------------------------------------- - NVIC_PriorityGroup_2 | 0-3 | 0-3 | 2 bits for pre-emption priority - | | | 2 bits for subpriority - ---------------------------------------------------------------------------------------------------------------------------- - NVIC_PriorityGroup_3 | 0-7 | 0-1 | 3 bits for pre-emption priority - | | | 1 bits for subpriority - ---------------------------------------------------------------------------------------------------------------------------- - NVIC_PriorityGroup_4 | 0-15 | 0 | 4 bits for pre-emption priority - | | | 0 bits for subpriority - ============================================================================================================================ -@endcode -*/ - -/** - * @} - */ - -/** @defgroup MISC_Exported_Constants - * @{ - */ - -/** @defgroup Vector_Table_Base - * @{ - */ - -#define NVIC_VectTab_RAM ((uint32_t)0x20000000) -#define NVIC_VectTab_FLASH ((uint32_t)0x08000000) -#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \ - ((VECTTAB) == NVIC_VectTab_FLASH)) -/** - * @} - */ - -/** @defgroup System_Low_Power - * @{ - */ - -#define NVIC_LP_SEVONPEND ((uint8_t)0x10) -#define NVIC_LP_SLEEPDEEP ((uint8_t)0x04) -#define NVIC_LP_SLEEPONEXIT ((uint8_t)0x02) -#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \ - ((LP) == NVIC_LP_SLEEPDEEP) || \ - ((LP) == NVIC_LP_SLEEPONEXIT)) -/** - * @} - */ - -/** @defgroup Preemption_Priority_Group - * @{ - */ - -#define NVIC_PriorityGroup_0 ((uint32_t)0x700) /*!< 0 bits for pre-emption priority - 4 bits for subpriority */ -#define NVIC_PriorityGroup_1 ((uint32_t)0x600) /*!< 1 bits for pre-emption priority - 3 bits for subpriority */ -#define NVIC_PriorityGroup_2 ((uint32_t)0x500) /*!< 2 bits for pre-emption priority - 2 bits for subpriority */ -#define NVIC_PriorityGroup_3 ((uint32_t)0x400) /*!< 3 bits for pre-emption priority - 1 bits for subpriority */ -#define NVIC_PriorityGroup_4 ((uint32_t)0x300) /*!< 4 bits for pre-emption priority - 0 bits for subpriority */ - -#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \ - ((GROUP) == NVIC_PriorityGroup_1) || \ - ((GROUP) == NVIC_PriorityGroup_2) || \ - ((GROUP) == NVIC_PriorityGroup_3) || \ - ((GROUP) == NVIC_PriorityGroup_4)) - -#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) - -#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) - -#define IS_NVIC_OFFSET(OFFSET) ((OFFSET) < 0x000FFFFF) - -/** - * @} - */ - -/** @defgroup SysTick_clock_source - * @{ - */ - -#define SysTick_CLKSource_HCLK_Div8 ((uint32_t)0xFFFFFFFB) -#define SysTick_CLKSource_HCLK ((uint32_t)0x00000004) -#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \ - ((SOURCE) == SysTick_CLKSource_HCLK_Div8)) -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup MISC_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup MISC_Exported_Functions - * @{ - */ - -void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup); -void NVIC_Init(const NVIC_InitTypeDef* NVIC_InitStruct); -void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset); -void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState); -void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource); - -#ifdef __cplusplus -} -#endif - -#endif /* __MISC_H */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file misc.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the miscellaneous + * firmware library functions (add-on to CMSIS functions). + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MISC_H +#define __MISC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup MISC + * @{ + */ + +/** @defgroup MISC_Exported_Types + * @{ + */ + +/** + * @brief NVIC Init Structure definition + */ + +typedef struct +{ + uint8_t NVIC_IRQChannel; /*!< Specifies the IRQ channel to be enabled or disabled. + This parameter can be a value of @ref IRQn_Type + (For the complete STM32 Devices IRQ Channels list, please + refer to stm32f10x.h file) */ + + uint8_t NVIC_IRQChannelPreemptionPriority; /*!< Specifies the pre-emption priority for the IRQ channel + specified in NVIC_IRQChannel. This parameter can be a value + between 0 and 15 as described in the table @ref NVIC_Priority_Table */ + + uint8_t NVIC_IRQChannelSubPriority; /*!< Specifies the subpriority level for the IRQ channel specified + in NVIC_IRQChannel. This parameter can be a value + between 0 and 15 as described in the table @ref NVIC_Priority_Table */ + + FunctionalState NVIC_IRQChannelCmd; /*!< Specifies whether the IRQ channel defined in NVIC_IRQChannel + will be enabled or disabled. + This parameter can be set either to ENABLE or DISABLE */ +} NVIC_InitTypeDef; + +/** + * @} + */ + +/** @defgroup NVIC_Priority_Table + * @{ + */ + +/** +@code + The table below gives the allowed values of the pre-emption priority and subpriority according + to the Priority Grouping configuration performed by NVIC_PriorityGroupConfig function + ============================================================================================================================ + NVIC_PriorityGroup | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority | Description + ============================================================================================================================ + NVIC_PriorityGroup_0 | 0 | 0-15 | 0 bits for pre-emption priority + | | | 4 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_1 | 0-1 | 0-7 | 1 bits for pre-emption priority + | | | 3 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_2 | 0-3 | 0-3 | 2 bits for pre-emption priority + | | | 2 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_3 | 0-7 | 0-1 | 3 bits for pre-emption priority + | | | 1 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_4 | 0-15 | 0 | 4 bits for pre-emption priority + | | | 0 bits for subpriority + ============================================================================================================================ +@endcode +*/ + +/** + * @} + */ + +/** @defgroup MISC_Exported_Constants + * @{ + */ + +/** @defgroup Vector_Table_Base + * @{ + */ + +#define NVIC_VectTab_RAM ((uint32_t)0x20000000) +#define NVIC_VectTab_FLASH ((uint32_t)0x08000000) +#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \ + ((VECTTAB) == NVIC_VectTab_FLASH)) +/** + * @} + */ + +/** @defgroup System_Low_Power + * @{ + */ + +#define NVIC_LP_SEVONPEND ((uint8_t)0x10) +#define NVIC_LP_SLEEPDEEP ((uint8_t)0x04) +#define NVIC_LP_SLEEPONEXIT ((uint8_t)0x02) +#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \ + ((LP) == NVIC_LP_SLEEPDEEP) || \ + ((LP) == NVIC_LP_SLEEPONEXIT)) +/** + * @} + */ + +/** @defgroup Preemption_Priority_Group + * @{ + */ + +#define NVIC_PriorityGroup_0 ((uint32_t)0x700) /*!< 0 bits for pre-emption priority + 4 bits for subpriority */ +#define NVIC_PriorityGroup_1 ((uint32_t)0x600) /*!< 1 bits for pre-emption priority + 3 bits for subpriority */ +#define NVIC_PriorityGroup_2 ((uint32_t)0x500) /*!< 2 bits for pre-emption priority + 2 bits for subpriority */ +#define NVIC_PriorityGroup_3 ((uint32_t)0x400) /*!< 3 bits for pre-emption priority + 1 bits for subpriority */ +#define NVIC_PriorityGroup_4 ((uint32_t)0x300) /*!< 4 bits for pre-emption priority + 0 bits for subpriority */ + +#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \ + ((GROUP) == NVIC_PriorityGroup_1) || \ + ((GROUP) == NVIC_PriorityGroup_2) || \ + ((GROUP) == NVIC_PriorityGroup_3) || \ + ((GROUP) == NVIC_PriorityGroup_4)) + +#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) + +#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) + +#define IS_NVIC_OFFSET(OFFSET) ((OFFSET) < 0x000FFFFF) + +/** + * @} + */ + +/** @defgroup SysTick_clock_source + * @{ + */ + +#define SysTick_CLKSource_HCLK_Div8 ((uint32_t)0xFFFFFFFB) +#define SysTick_CLKSource_HCLK ((uint32_t)0x00000004) +#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \ + ((SOURCE) == SysTick_CLKSource_HCLK_Div8)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup MISC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Exported_Functions + * @{ + */ + +void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup); +void NVIC_Init(const NVIC_InitTypeDef* NVIC_InitStruct); +void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset); +void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState); +void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource); + +#ifdef __cplusplus +} +#endif + +#endif /* __MISC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h index 26e725fa1..b775ceb1d 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h @@ -1,482 +1,482 @@ -/** - ****************************************************************************** - * @file stm32f10x_adc.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the ADC firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_ADC_H -#define __STM32F10x_ADC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup ADC - * @{ - */ - -/** @defgroup ADC_Exported_Types - * @{ - */ - -/** - * @brief ADC Init structure definition - */ - -typedef struct -{ - uint32_t ADC_Mode; /*!< Configures the ADC to operate in independent or - dual mode. - This parameter can be a value of @ref ADC_mode */ - - FunctionalState ADC_ScanConvMode; /*!< Specifies whether the conversion is performed in - Scan (multichannels) or Single (one channel) mode. - This parameter can be set to ENABLE or DISABLE */ - - FunctionalState ADC_ContinuousConvMode; /*!< Specifies whether the conversion is performed in - Continuous or Single mode. - This parameter can be set to ENABLE or DISABLE. */ - - uint32_t ADC_ExternalTrigConv; /*!< Defines the external trigger used to start the analog - to digital conversion of regular channels. This parameter - can be a value of @ref ADC_external_trigger_sources_for_regular_channels_conversion */ - - uint32_t ADC_DataAlign; /*!< Specifies whether the ADC data alignment is left or right. - This parameter can be a value of @ref ADC_data_align */ - - uint8_t ADC_NbrOfChannel; /*!< Specifies the number of ADC channels that will be converted - using the sequencer for regular channel group. - This parameter must range from 1 to 16. */ -}ADC_InitTypeDef; -/** - * @} - */ - -/** @defgroup ADC_Exported_Constants - * @{ - */ - -#define IS_ADC_ALL_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ - ((PERIPH) == ADC2) || \ - ((PERIPH) == ADC3)) - -#define IS_ADC_DMA_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ - ((PERIPH) == ADC3)) - -/** @defgroup ADC_mode - * @{ - */ - -#define ADC_Mode_Independent ((uint32_t)0x00000000) -#define ADC_Mode_RegInjecSimult ((uint32_t)0x00010000) -#define ADC_Mode_RegSimult_AlterTrig ((uint32_t)0x00020000) -#define ADC_Mode_InjecSimult_FastInterl ((uint32_t)0x00030000) -#define ADC_Mode_InjecSimult_SlowInterl ((uint32_t)0x00040000) -#define ADC_Mode_InjecSimult ((uint32_t)0x00050000) -#define ADC_Mode_RegSimult ((uint32_t)0x00060000) -#define ADC_Mode_FastInterl ((uint32_t)0x00070000) -#define ADC_Mode_SlowInterl ((uint32_t)0x00080000) -#define ADC_Mode_AlterTrig ((uint32_t)0x00090000) - -#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \ - ((MODE) == ADC_Mode_RegInjecSimult) || \ - ((MODE) == ADC_Mode_RegSimult_AlterTrig) || \ - ((MODE) == ADC_Mode_InjecSimult_FastInterl) || \ - ((MODE) == ADC_Mode_InjecSimult_SlowInterl) || \ - ((MODE) == ADC_Mode_InjecSimult) || \ - ((MODE) == ADC_Mode_RegSimult) || \ - ((MODE) == ADC_Mode_FastInterl) || \ - ((MODE) == ADC_Mode_SlowInterl) || \ - ((MODE) == ADC_Mode_AlterTrig)) -/** - * @} - */ - -/** @defgroup ADC_external_trigger_sources_for_regular_channels_conversion - * @{ - */ - -#define ADC_ExternalTrigConv_T1_CC1 ((uint32_t)0x00000000) /*!< For ADC1 and ADC2 */ -#define ADC_ExternalTrigConv_T1_CC2 ((uint32_t)0x00020000) /*!< For ADC1 and ADC2 */ -#define ADC_ExternalTrigConv_T2_CC2 ((uint32_t)0x00060000) /*!< For ADC1 and ADC2 */ -#define ADC_ExternalTrigConv_T3_TRGO ((uint32_t)0x00080000) /*!< For ADC1 and ADC2 */ -#define ADC_ExternalTrigConv_T4_CC4 ((uint32_t)0x000A0000) /*!< For ADC1 and ADC2 */ -#define ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO ((uint32_t)0x000C0000) /*!< For ADC1 and ADC2 */ - -#define ADC_ExternalTrigConv_T1_CC3 ((uint32_t)0x00040000) /*!< For ADC1, ADC2 and ADC3 */ -#define ADC_ExternalTrigConv_None ((uint32_t)0x000E0000) /*!< For ADC1, ADC2 and ADC3 */ - -#define ADC_ExternalTrigConv_T3_CC1 ((uint32_t)0x00000000) /*!< For ADC3 only */ -#define ADC_ExternalTrigConv_T2_CC3 ((uint32_t)0x00020000) /*!< For ADC3 only */ -#define ADC_ExternalTrigConv_T8_CC1 ((uint32_t)0x00060000) /*!< For ADC3 only */ -#define ADC_ExternalTrigConv_T8_TRGO ((uint32_t)0x00080000) /*!< For ADC3 only */ -#define ADC_ExternalTrigConv_T5_CC1 ((uint32_t)0x000A0000) /*!< For ADC3 only */ -#define ADC_ExternalTrigConv_T5_CC3 ((uint32_t)0x000C0000) /*!< For ADC3 only */ - -#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \ - ((REGTRIG) == ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO) || \ - ((REGTRIG) == ADC_ExternalTrigConv_None) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \ - ((REGTRIG) == ADC_ExternalTrigConv_T5_CC3)) -/** - * @} - */ - -/** @defgroup ADC_data_align - * @{ - */ - -#define ADC_DataAlign_Right ((uint32_t)0x00000000) -#define ADC_DataAlign_Left ((uint32_t)0x00000800) -#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \ - ((ALIGN) == ADC_DataAlign_Left)) -/** - * @} - */ - -/** @defgroup ADC_channels - * @{ - */ - -#define ADC_Channel_0 ((uint8_t)0x00) -#define ADC_Channel_1 ((uint8_t)0x01) -#define ADC_Channel_2 ((uint8_t)0x02) -#define ADC_Channel_3 ((uint8_t)0x03) -#define ADC_Channel_4 ((uint8_t)0x04) -#define ADC_Channel_5 ((uint8_t)0x05) -#define ADC_Channel_6 ((uint8_t)0x06) -#define ADC_Channel_7 ((uint8_t)0x07) -#define ADC_Channel_8 ((uint8_t)0x08) -#define ADC_Channel_9 ((uint8_t)0x09) -#define ADC_Channel_10 ((uint8_t)0x0A) -#define ADC_Channel_11 ((uint8_t)0x0B) -#define ADC_Channel_12 ((uint8_t)0x0C) -#define ADC_Channel_13 ((uint8_t)0x0D) -#define ADC_Channel_14 ((uint8_t)0x0E) -#define ADC_Channel_15 ((uint8_t)0x0F) -#define ADC_Channel_16 ((uint8_t)0x10) -#define ADC_Channel_17 ((uint8_t)0x11) - -#define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_16) -#define ADC_Channel_Vrefint ((uint8_t)ADC_Channel_17) - -#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || ((CHANNEL) == ADC_Channel_1) || \ - ((CHANNEL) == ADC_Channel_2) || ((CHANNEL) == ADC_Channel_3) || \ - ((CHANNEL) == ADC_Channel_4) || ((CHANNEL) == ADC_Channel_5) || \ - ((CHANNEL) == ADC_Channel_6) || ((CHANNEL) == ADC_Channel_7) || \ - ((CHANNEL) == ADC_Channel_8) || ((CHANNEL) == ADC_Channel_9) || \ - ((CHANNEL) == ADC_Channel_10) || ((CHANNEL) == ADC_Channel_11) || \ - ((CHANNEL) == ADC_Channel_12) || ((CHANNEL) == ADC_Channel_13) || \ - ((CHANNEL) == ADC_Channel_14) || ((CHANNEL) == ADC_Channel_15) || \ - ((CHANNEL) == ADC_Channel_16) || ((CHANNEL) == ADC_Channel_17)) -/** - * @} - */ - -/** @defgroup ADC_sampling_time - * @{ - */ - -#define ADC_SampleTime_1Cycles5 ((uint8_t)0x00) -#define ADC_SampleTime_7Cycles5 ((uint8_t)0x01) -#define ADC_SampleTime_13Cycles5 ((uint8_t)0x02) -#define ADC_SampleTime_28Cycles5 ((uint8_t)0x03) -#define ADC_SampleTime_41Cycles5 ((uint8_t)0x04) -#define ADC_SampleTime_55Cycles5 ((uint8_t)0x05) -#define ADC_SampleTime_71Cycles5 ((uint8_t)0x06) -#define ADC_SampleTime_239Cycles5 ((uint8_t)0x07) -#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1Cycles5) || \ - ((TIME) == ADC_SampleTime_7Cycles5) || \ - ((TIME) == ADC_SampleTime_13Cycles5) || \ - ((TIME) == ADC_SampleTime_28Cycles5) || \ - ((TIME) == ADC_SampleTime_41Cycles5) || \ - ((TIME) == ADC_SampleTime_55Cycles5) || \ - ((TIME) == ADC_SampleTime_71Cycles5) || \ - ((TIME) == ADC_SampleTime_239Cycles5)) -/** - * @} - */ - -/** @defgroup ADC_external_trigger_sources_for_injected_channels_conversion - * @{ - */ - -#define ADC_ExternalTrigInjecConv_T2_TRGO ((uint32_t)0x00002000) /*!< For ADC1 and ADC2 */ -#define ADC_ExternalTrigInjecConv_T2_CC1 ((uint32_t)0x00003000) /*!< For ADC1 and ADC2 */ -#define ADC_ExternalTrigInjecConv_T3_CC4 ((uint32_t)0x00004000) /*!< For ADC1 and ADC2 */ -#define ADC_ExternalTrigInjecConv_T4_TRGO ((uint32_t)0x00005000) /*!< For ADC1 and ADC2 */ -#define ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4 ((uint32_t)0x00006000) /*!< For ADC1 and ADC2 */ - -#define ADC_ExternalTrigInjecConv_T1_TRGO ((uint32_t)0x00000000) /*!< For ADC1, ADC2 and ADC3 */ -#define ADC_ExternalTrigInjecConv_T1_CC4 ((uint32_t)0x00001000) /*!< For ADC1, ADC2 and ADC3 */ -#define ADC_ExternalTrigInjecConv_None ((uint32_t)0x00007000) /*!< For ADC1, ADC2 and ADC3 */ - -#define ADC_ExternalTrigInjecConv_T4_CC3 ((uint32_t)0x00002000) /*!< For ADC3 only */ -#define ADC_ExternalTrigInjecConv_T8_CC2 ((uint32_t)0x00003000) /*!< For ADC3 only */ -#define ADC_ExternalTrigInjecConv_T8_CC4 ((uint32_t)0x00004000) /*!< For ADC3 only */ -#define ADC_ExternalTrigInjecConv_T5_TRGO ((uint32_t)0x00005000) /*!< For ADC3 only */ -#define ADC_ExternalTrigInjecConv_T5_CC4 ((uint32_t)0x00006000) /*!< For ADC3 only */ - -#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_None) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \ - ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4)) -/** - * @} - */ - -/** @defgroup ADC_injected_channel_selection - * @{ - */ - -#define ADC_InjectedChannel_1 ((uint8_t)0x14) -#define ADC_InjectedChannel_2 ((uint8_t)0x18) -#define ADC_InjectedChannel_3 ((uint8_t)0x1C) -#define ADC_InjectedChannel_4 ((uint8_t)0x20) -#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \ - ((CHANNEL) == ADC_InjectedChannel_2) || \ - ((CHANNEL) == ADC_InjectedChannel_3) || \ - ((CHANNEL) == ADC_InjectedChannel_4)) -/** - * @} - */ - -/** @defgroup ADC_analog_watchdog_selection - * @{ - */ - -#define ADC_AnalogWatchdog_SingleRegEnable ((uint32_t)0x00800200) -#define ADC_AnalogWatchdog_SingleInjecEnable ((uint32_t)0x00400200) -#define ADC_AnalogWatchdog_SingleRegOrInjecEnable ((uint32_t)0x00C00200) -#define ADC_AnalogWatchdog_AllRegEnable ((uint32_t)0x00800000) -#define ADC_AnalogWatchdog_AllInjecEnable ((uint32_t)0x00400000) -#define ADC_AnalogWatchdog_AllRegAllInjecEnable ((uint32_t)0x00C00000) -#define ADC_AnalogWatchdog_None ((uint32_t)0x00000000) - -#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \ - ((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \ - ((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \ - ((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \ - ((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \ - ((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \ - ((WATCHDOG) == ADC_AnalogWatchdog_None)) -/** - * @} - */ - -/** @defgroup ADC_interrupts_definition - * @{ - */ - -#define ADC_IT_EOC ((uint16_t)0x0220) -#define ADC_IT_AWD ((uint16_t)0x0140) -#define ADC_IT_JEOC ((uint16_t)0x0480) - -#define IS_ADC_IT(IT) ((((IT) & (uint16_t)0xF81F) == 0x00) && ((IT) != 0x00)) - -#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \ - ((IT) == ADC_IT_JEOC)) -/** - * @} - */ - -/** @defgroup ADC_flags_definition - * @{ - */ - -#define ADC_FLAG_AWD ((uint8_t)0x01) -#define ADC_FLAG_EOC ((uint8_t)0x02) -#define ADC_FLAG_JEOC ((uint8_t)0x04) -#define ADC_FLAG_JSTRT ((uint8_t)0x08) -#define ADC_FLAG_STRT ((uint8_t)0x10) -#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint8_t)0xE0) == 0x00) && ((FLAG) != 0x00)) -#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || ((FLAG) == ADC_FLAG_EOC) || \ - ((FLAG) == ADC_FLAG_JEOC) || ((FLAG)== ADC_FLAG_JSTRT) || \ - ((FLAG) == ADC_FLAG_STRT)) -/** - * @} - */ - -/** @defgroup ADC_thresholds - * @{ - */ - -#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF) - -/** - * @} - */ - -/** @defgroup ADC_injected_offset - * @{ - */ - -#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF) - -/** - * @} - */ - -/** @defgroup ADC_injected_length - * @{ - */ - -#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4)) - -/** - * @} - */ - -/** @defgroup ADC_injected_rank - * @{ - */ - -#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4)) - -/** - * @} - */ - - -/** @defgroup ADC_regular_length - * @{ - */ - -#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10)) -/** - * @} - */ - -/** @defgroup ADC_regular_rank - * @{ - */ - -#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10)) - -/** - * @} - */ - -/** @defgroup ADC_regular_discontinuous_mode_number - * @{ - */ - -#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8)) - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup ADC_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup ADC_Exported_Functions - * @{ - */ - -void ADC_DeInit(ADC_TypeDef* ADCx); -void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct); -void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct); -void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState); -void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState); -void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState); -void ADC_ResetCalibration(ADC_TypeDef* ADCx); -FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx); -void ADC_StartCalibration(ADC_TypeDef* ADCx); -FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx); -void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); -FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx); -void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number); -void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); -void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); -void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); -uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx); -uint32_t ADC_GetDualModeConversionValue(void); -void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); -void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); -void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv); -void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); -void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); -FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx); -void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); -void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length); -void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset); -uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel); -void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog); -void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, uint16_t LowThreshold); -void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel); -void ADC_TempSensorVrefintCmd(FunctionalState NewState); -FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG); -void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG); -ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT); -void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT); - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F10x_ADC_H */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_adc.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the ADC firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_ADC_H +#define __STM32F10x_ADC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup ADC + * @{ + */ + +/** @defgroup ADC_Exported_Types + * @{ + */ + +/** + * @brief ADC Init structure definition + */ + +typedef struct +{ + uint32_t ADC_Mode; /*!< Configures the ADC to operate in independent or + dual mode. + This parameter can be a value of @ref ADC_mode */ + + FunctionalState ADC_ScanConvMode; /*!< Specifies whether the conversion is performed in + Scan (multichannels) or Single (one channel) mode. + This parameter can be set to ENABLE or DISABLE */ + + FunctionalState ADC_ContinuousConvMode; /*!< Specifies whether the conversion is performed in + Continuous or Single mode. + This parameter can be set to ENABLE or DISABLE. */ + + uint32_t ADC_ExternalTrigConv; /*!< Defines the external trigger used to start the analog + to digital conversion of regular channels. This parameter + can be a value of @ref ADC_external_trigger_sources_for_regular_channels_conversion */ + + uint32_t ADC_DataAlign; /*!< Specifies whether the ADC data alignment is left or right. + This parameter can be a value of @ref ADC_data_align */ + + uint8_t ADC_NbrOfChannel; /*!< Specifies the number of ADC channels that will be converted + using the sequencer for regular channel group. + This parameter must range from 1 to 16. */ +}ADC_InitTypeDef; +/** + * @} + */ + +/** @defgroup ADC_Exported_Constants + * @{ + */ + +#define IS_ADC_ALL_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ + ((PERIPH) == ADC2) || \ + ((PERIPH) == ADC3)) + +#define IS_ADC_DMA_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ + ((PERIPH) == ADC3)) + +/** @defgroup ADC_mode + * @{ + */ + +#define ADC_Mode_Independent ((uint32_t)0x00000000) +#define ADC_Mode_RegInjecSimult ((uint32_t)0x00010000) +#define ADC_Mode_RegSimult_AlterTrig ((uint32_t)0x00020000) +#define ADC_Mode_InjecSimult_FastInterl ((uint32_t)0x00030000) +#define ADC_Mode_InjecSimult_SlowInterl ((uint32_t)0x00040000) +#define ADC_Mode_InjecSimult ((uint32_t)0x00050000) +#define ADC_Mode_RegSimult ((uint32_t)0x00060000) +#define ADC_Mode_FastInterl ((uint32_t)0x00070000) +#define ADC_Mode_SlowInterl ((uint32_t)0x00080000) +#define ADC_Mode_AlterTrig ((uint32_t)0x00090000) + +#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \ + ((MODE) == ADC_Mode_RegInjecSimult) || \ + ((MODE) == ADC_Mode_RegSimult_AlterTrig) || \ + ((MODE) == ADC_Mode_InjecSimult_FastInterl) || \ + ((MODE) == ADC_Mode_InjecSimult_SlowInterl) || \ + ((MODE) == ADC_Mode_InjecSimult) || \ + ((MODE) == ADC_Mode_RegSimult) || \ + ((MODE) == ADC_Mode_FastInterl) || \ + ((MODE) == ADC_Mode_SlowInterl) || \ + ((MODE) == ADC_Mode_AlterTrig)) +/** + * @} + */ + +/** @defgroup ADC_external_trigger_sources_for_regular_channels_conversion + * @{ + */ + +#define ADC_ExternalTrigConv_T1_CC1 ((uint32_t)0x00000000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T1_CC2 ((uint32_t)0x00020000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T2_CC2 ((uint32_t)0x00060000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T3_TRGO ((uint32_t)0x00080000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T4_CC4 ((uint32_t)0x000A0000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO ((uint32_t)0x000C0000) /*!< For ADC1 and ADC2 */ + +#define ADC_ExternalTrigConv_T1_CC3 ((uint32_t)0x00040000) /*!< For ADC1, ADC2 and ADC3 */ +#define ADC_ExternalTrigConv_None ((uint32_t)0x000E0000) /*!< For ADC1, ADC2 and ADC3 */ + +#define ADC_ExternalTrigConv_T3_CC1 ((uint32_t)0x00000000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T2_CC3 ((uint32_t)0x00020000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T8_CC1 ((uint32_t)0x00060000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T8_TRGO ((uint32_t)0x00080000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T5_CC1 ((uint32_t)0x000A0000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T5_CC3 ((uint32_t)0x000C0000) /*!< For ADC3 only */ + +#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \ + ((REGTRIG) == ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_None) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T5_CC3)) +/** + * @} + */ + +/** @defgroup ADC_data_align + * @{ + */ + +#define ADC_DataAlign_Right ((uint32_t)0x00000000) +#define ADC_DataAlign_Left ((uint32_t)0x00000800) +#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \ + ((ALIGN) == ADC_DataAlign_Left)) +/** + * @} + */ + +/** @defgroup ADC_channels + * @{ + */ + +#define ADC_Channel_0 ((uint8_t)0x00) +#define ADC_Channel_1 ((uint8_t)0x01) +#define ADC_Channel_2 ((uint8_t)0x02) +#define ADC_Channel_3 ((uint8_t)0x03) +#define ADC_Channel_4 ((uint8_t)0x04) +#define ADC_Channel_5 ((uint8_t)0x05) +#define ADC_Channel_6 ((uint8_t)0x06) +#define ADC_Channel_7 ((uint8_t)0x07) +#define ADC_Channel_8 ((uint8_t)0x08) +#define ADC_Channel_9 ((uint8_t)0x09) +#define ADC_Channel_10 ((uint8_t)0x0A) +#define ADC_Channel_11 ((uint8_t)0x0B) +#define ADC_Channel_12 ((uint8_t)0x0C) +#define ADC_Channel_13 ((uint8_t)0x0D) +#define ADC_Channel_14 ((uint8_t)0x0E) +#define ADC_Channel_15 ((uint8_t)0x0F) +#define ADC_Channel_16 ((uint8_t)0x10) +#define ADC_Channel_17 ((uint8_t)0x11) + +#define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_16) +#define ADC_Channel_Vrefint ((uint8_t)ADC_Channel_17) + +#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || ((CHANNEL) == ADC_Channel_1) || \ + ((CHANNEL) == ADC_Channel_2) || ((CHANNEL) == ADC_Channel_3) || \ + ((CHANNEL) == ADC_Channel_4) || ((CHANNEL) == ADC_Channel_5) || \ + ((CHANNEL) == ADC_Channel_6) || ((CHANNEL) == ADC_Channel_7) || \ + ((CHANNEL) == ADC_Channel_8) || ((CHANNEL) == ADC_Channel_9) || \ + ((CHANNEL) == ADC_Channel_10) || ((CHANNEL) == ADC_Channel_11) || \ + ((CHANNEL) == ADC_Channel_12) || ((CHANNEL) == ADC_Channel_13) || \ + ((CHANNEL) == ADC_Channel_14) || ((CHANNEL) == ADC_Channel_15) || \ + ((CHANNEL) == ADC_Channel_16) || ((CHANNEL) == ADC_Channel_17)) +/** + * @} + */ + +/** @defgroup ADC_sampling_time + * @{ + */ + +#define ADC_SampleTime_1Cycles5 ((uint8_t)0x00) +#define ADC_SampleTime_7Cycles5 ((uint8_t)0x01) +#define ADC_SampleTime_13Cycles5 ((uint8_t)0x02) +#define ADC_SampleTime_28Cycles5 ((uint8_t)0x03) +#define ADC_SampleTime_41Cycles5 ((uint8_t)0x04) +#define ADC_SampleTime_55Cycles5 ((uint8_t)0x05) +#define ADC_SampleTime_71Cycles5 ((uint8_t)0x06) +#define ADC_SampleTime_239Cycles5 ((uint8_t)0x07) +#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1Cycles5) || \ + ((TIME) == ADC_SampleTime_7Cycles5) || \ + ((TIME) == ADC_SampleTime_13Cycles5) || \ + ((TIME) == ADC_SampleTime_28Cycles5) || \ + ((TIME) == ADC_SampleTime_41Cycles5) || \ + ((TIME) == ADC_SampleTime_55Cycles5) || \ + ((TIME) == ADC_SampleTime_71Cycles5) || \ + ((TIME) == ADC_SampleTime_239Cycles5)) +/** + * @} + */ + +/** @defgroup ADC_external_trigger_sources_for_injected_channels_conversion + * @{ + */ + +#define ADC_ExternalTrigInjecConv_T2_TRGO ((uint32_t)0x00002000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_T2_CC1 ((uint32_t)0x00003000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_T3_CC4 ((uint32_t)0x00004000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_T4_TRGO ((uint32_t)0x00005000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4 ((uint32_t)0x00006000) /*!< For ADC1 and ADC2 */ + +#define ADC_ExternalTrigInjecConv_T1_TRGO ((uint32_t)0x00000000) /*!< For ADC1, ADC2 and ADC3 */ +#define ADC_ExternalTrigInjecConv_T1_CC4 ((uint32_t)0x00001000) /*!< For ADC1, ADC2 and ADC3 */ +#define ADC_ExternalTrigInjecConv_None ((uint32_t)0x00007000) /*!< For ADC1, ADC2 and ADC3 */ + +#define ADC_ExternalTrigInjecConv_T4_CC3 ((uint32_t)0x00002000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T8_CC2 ((uint32_t)0x00003000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T8_CC4 ((uint32_t)0x00004000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T5_TRGO ((uint32_t)0x00005000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T5_CC4 ((uint32_t)0x00006000) /*!< For ADC3 only */ + +#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_None) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4)) +/** + * @} + */ + +/** @defgroup ADC_injected_channel_selection + * @{ + */ + +#define ADC_InjectedChannel_1 ((uint8_t)0x14) +#define ADC_InjectedChannel_2 ((uint8_t)0x18) +#define ADC_InjectedChannel_3 ((uint8_t)0x1C) +#define ADC_InjectedChannel_4 ((uint8_t)0x20) +#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \ + ((CHANNEL) == ADC_InjectedChannel_2) || \ + ((CHANNEL) == ADC_InjectedChannel_3) || \ + ((CHANNEL) == ADC_InjectedChannel_4)) +/** + * @} + */ + +/** @defgroup ADC_analog_watchdog_selection + * @{ + */ + +#define ADC_AnalogWatchdog_SingleRegEnable ((uint32_t)0x00800200) +#define ADC_AnalogWatchdog_SingleInjecEnable ((uint32_t)0x00400200) +#define ADC_AnalogWatchdog_SingleRegOrInjecEnable ((uint32_t)0x00C00200) +#define ADC_AnalogWatchdog_AllRegEnable ((uint32_t)0x00800000) +#define ADC_AnalogWatchdog_AllInjecEnable ((uint32_t)0x00400000) +#define ADC_AnalogWatchdog_AllRegAllInjecEnable ((uint32_t)0x00C00000) +#define ADC_AnalogWatchdog_None ((uint32_t)0x00000000) + +#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_None)) +/** + * @} + */ + +/** @defgroup ADC_interrupts_definition + * @{ + */ + +#define ADC_IT_EOC ((uint16_t)0x0220) +#define ADC_IT_AWD ((uint16_t)0x0140) +#define ADC_IT_JEOC ((uint16_t)0x0480) + +#define IS_ADC_IT(IT) ((((IT) & (uint16_t)0xF81F) == 0x00) && ((IT) != 0x00)) + +#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \ + ((IT) == ADC_IT_JEOC)) +/** + * @} + */ + +/** @defgroup ADC_flags_definition + * @{ + */ + +#define ADC_FLAG_AWD ((uint8_t)0x01) +#define ADC_FLAG_EOC ((uint8_t)0x02) +#define ADC_FLAG_JEOC ((uint8_t)0x04) +#define ADC_FLAG_JSTRT ((uint8_t)0x08) +#define ADC_FLAG_STRT ((uint8_t)0x10) +#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint8_t)0xE0) == 0x00) && ((FLAG) != 0x00)) +#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || ((FLAG) == ADC_FLAG_EOC) || \ + ((FLAG) == ADC_FLAG_JEOC) || ((FLAG)== ADC_FLAG_JSTRT) || \ + ((FLAG) == ADC_FLAG_STRT)) +/** + * @} + */ + +/** @defgroup ADC_thresholds + * @{ + */ + +#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF) + +/** + * @} + */ + +/** @defgroup ADC_injected_offset + * @{ + */ + +#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF) + +/** + * @} + */ + +/** @defgroup ADC_injected_length + * @{ + */ + +#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4)) + +/** + * @} + */ + +/** @defgroup ADC_injected_rank + * @{ + */ + +#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4)) + +/** + * @} + */ + + +/** @defgroup ADC_regular_length + * @{ + */ + +#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10)) +/** + * @} + */ + +/** @defgroup ADC_regular_rank + * @{ + */ + +#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10)) + +/** + * @} + */ + +/** @defgroup ADC_regular_discontinuous_mode_number + * @{ + */ + +#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup ADC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Exported_Functions + * @{ + */ + +void ADC_DeInit(ADC_TypeDef* ADCx); +void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct); +void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct); +void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState); +void ADC_ResetCalibration(ADC_TypeDef* ADCx); +FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx); +void ADC_StartCalibration(ADC_TypeDef* ADCx); +FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx); +void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx); +void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number); +void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); +void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx); +uint32_t ADC_GetDualModeConversionValue(void); +void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv); +void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx); +void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); +void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length); +void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset); +uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel); +void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog); +void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, uint16_t LowThreshold); +void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel); +void ADC_TempSensorVrefintCmd(FunctionalState NewState); +FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG); +void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG); +ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT); +void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_ADC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h index dc40ec22e..8e2083ae2 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h @@ -1,194 +1,194 @@ -/** - ****************************************************************************** - * @file stm32f10x_bkp.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the BKP firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_BKP_H -#define __STM32F10x_BKP_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup BKP - * @{ - */ - -/** @defgroup BKP_Exported_Types - * @{ - */ - -/** - * @} - */ - -/** @defgroup BKP_Exported_Constants - * @{ - */ - -/** @defgroup Tamper_Pin_active_level - * @{ - */ - -#define BKP_TamperPinLevel_High ((uint16_t)0x0000) -#define BKP_TamperPinLevel_Low ((uint16_t)0x0001) -#define IS_BKP_TAMPER_PIN_LEVEL(LEVEL) (((LEVEL) == BKP_TamperPinLevel_High) || \ - ((LEVEL) == BKP_TamperPinLevel_Low)) -/** - * @} - */ - -/** @defgroup RTC_output_source_to_output_on_the_Tamper_pin - * @{ - */ - -#define BKP_RTCOutputSource_None ((uint16_t)0x0000) -#define BKP_RTCOutputSource_CalibClock ((uint16_t)0x0080) -#define BKP_RTCOutputSource_Alarm ((uint16_t)0x0100) -#define BKP_RTCOutputSource_Second ((uint16_t)0x0300) -#define IS_BKP_RTC_OUTPUT_SOURCE(SOURCE) (((SOURCE) == BKP_RTCOutputSource_None) || \ - ((SOURCE) == BKP_RTCOutputSource_CalibClock) || \ - ((SOURCE) == BKP_RTCOutputSource_Alarm) || \ - ((SOURCE) == BKP_RTCOutputSource_Second)) -/** - * @} - */ - -/** @defgroup Data_Backup_Register - * @{ - */ - -#define BKP_DR1 ((uint16_t)0x0004) -#define BKP_DR2 ((uint16_t)0x0008) -#define BKP_DR3 ((uint16_t)0x000C) -#define BKP_DR4 ((uint16_t)0x0010) -#define BKP_DR5 ((uint16_t)0x0014) -#define BKP_DR6 ((uint16_t)0x0018) -#define BKP_DR7 ((uint16_t)0x001C) -#define BKP_DR8 ((uint16_t)0x0020) -#define BKP_DR9 ((uint16_t)0x0024) -#define BKP_DR10 ((uint16_t)0x0028) -#define BKP_DR11 ((uint16_t)0x0040) -#define BKP_DR12 ((uint16_t)0x0044) -#define BKP_DR13 ((uint16_t)0x0048) -#define BKP_DR14 ((uint16_t)0x004C) -#define BKP_DR15 ((uint16_t)0x0050) -#define BKP_DR16 ((uint16_t)0x0054) -#define BKP_DR17 ((uint16_t)0x0058) -#define BKP_DR18 ((uint16_t)0x005C) -#define BKP_DR19 ((uint16_t)0x0060) -#define BKP_DR20 ((uint16_t)0x0064) -#define BKP_DR21 ((uint16_t)0x0068) -#define BKP_DR22 ((uint16_t)0x006C) -#define BKP_DR23 ((uint16_t)0x0070) -#define BKP_DR24 ((uint16_t)0x0074) -#define BKP_DR25 ((uint16_t)0x0078) -#define BKP_DR26 ((uint16_t)0x007C) -#define BKP_DR27 ((uint16_t)0x0080) -#define BKP_DR28 ((uint16_t)0x0084) -#define BKP_DR29 ((uint16_t)0x0088) -#define BKP_DR30 ((uint16_t)0x008C) -#define BKP_DR31 ((uint16_t)0x0090) -#define BKP_DR32 ((uint16_t)0x0094) -#define BKP_DR33 ((uint16_t)0x0098) -#define BKP_DR34 ((uint16_t)0x009C) -#define BKP_DR35 ((uint16_t)0x00A0) -#define BKP_DR36 ((uint16_t)0x00A4) -#define BKP_DR37 ((uint16_t)0x00A8) -#define BKP_DR38 ((uint16_t)0x00AC) -#define BKP_DR39 ((uint16_t)0x00B0) -#define BKP_DR40 ((uint16_t)0x00B4) -#define BKP_DR41 ((uint16_t)0x00B8) -#define BKP_DR42 ((uint16_t)0x00BC) - -#define IS_BKP_DR(DR) (((DR) == BKP_DR1) || ((DR) == BKP_DR2) || ((DR) == BKP_DR3) || \ - ((DR) == BKP_DR4) || ((DR) == BKP_DR5) || ((DR) == BKP_DR6) || \ - ((DR) == BKP_DR7) || ((DR) == BKP_DR8) || ((DR) == BKP_DR9) || \ - ((DR) == BKP_DR10) || ((DR) == BKP_DR11) || ((DR) == BKP_DR12) || \ - ((DR) == BKP_DR13) || ((DR) == BKP_DR14) || ((DR) == BKP_DR15) || \ - ((DR) == BKP_DR16) || ((DR) == BKP_DR17) || ((DR) == BKP_DR18) || \ - ((DR) == BKP_DR19) || ((DR) == BKP_DR20) || ((DR) == BKP_DR21) || \ - ((DR) == BKP_DR22) || ((DR) == BKP_DR23) || ((DR) == BKP_DR24) || \ - ((DR) == BKP_DR25) || ((DR) == BKP_DR26) || ((DR) == BKP_DR27) || \ - ((DR) == BKP_DR28) || ((DR) == BKP_DR29) || ((DR) == BKP_DR30) || \ - ((DR) == BKP_DR31) || ((DR) == BKP_DR32) || ((DR) == BKP_DR33) || \ - ((DR) == BKP_DR34) || ((DR) == BKP_DR35) || ((DR) == BKP_DR36) || \ - ((DR) == BKP_DR37) || ((DR) == BKP_DR38) || ((DR) == BKP_DR39) || \ - ((DR) == BKP_DR40) || ((DR) == BKP_DR41) || ((DR) == BKP_DR42)) - -#define IS_BKP_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x7F) -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup BKP_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup BKP_Exported_Functions - * @{ - */ - -void BKP_DeInit(void); -void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel); -void BKP_TamperPinCmd(FunctionalState NewState); -void BKP_ITConfig(FunctionalState NewState); -void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource); -void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue); -void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data); -uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR); -FlagStatus BKP_GetFlagStatus(void); -void BKP_ClearFlag(void); -ITStatus BKP_GetITStatus(void); -void BKP_ClearITPendingBit(void); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_BKP_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_bkp.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the BKP firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_BKP_H +#define __STM32F10x_BKP_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup BKP + * @{ + */ + +/** @defgroup BKP_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Exported_Constants + * @{ + */ + +/** @defgroup Tamper_Pin_active_level + * @{ + */ + +#define BKP_TamperPinLevel_High ((uint16_t)0x0000) +#define BKP_TamperPinLevel_Low ((uint16_t)0x0001) +#define IS_BKP_TAMPER_PIN_LEVEL(LEVEL) (((LEVEL) == BKP_TamperPinLevel_High) || \ + ((LEVEL) == BKP_TamperPinLevel_Low)) +/** + * @} + */ + +/** @defgroup RTC_output_source_to_output_on_the_Tamper_pin + * @{ + */ + +#define BKP_RTCOutputSource_None ((uint16_t)0x0000) +#define BKP_RTCOutputSource_CalibClock ((uint16_t)0x0080) +#define BKP_RTCOutputSource_Alarm ((uint16_t)0x0100) +#define BKP_RTCOutputSource_Second ((uint16_t)0x0300) +#define IS_BKP_RTC_OUTPUT_SOURCE(SOURCE) (((SOURCE) == BKP_RTCOutputSource_None) || \ + ((SOURCE) == BKP_RTCOutputSource_CalibClock) || \ + ((SOURCE) == BKP_RTCOutputSource_Alarm) || \ + ((SOURCE) == BKP_RTCOutputSource_Second)) +/** + * @} + */ + +/** @defgroup Data_Backup_Register + * @{ + */ + +#define BKP_DR1 ((uint16_t)0x0004) +#define BKP_DR2 ((uint16_t)0x0008) +#define BKP_DR3 ((uint16_t)0x000C) +#define BKP_DR4 ((uint16_t)0x0010) +#define BKP_DR5 ((uint16_t)0x0014) +#define BKP_DR6 ((uint16_t)0x0018) +#define BKP_DR7 ((uint16_t)0x001C) +#define BKP_DR8 ((uint16_t)0x0020) +#define BKP_DR9 ((uint16_t)0x0024) +#define BKP_DR10 ((uint16_t)0x0028) +#define BKP_DR11 ((uint16_t)0x0040) +#define BKP_DR12 ((uint16_t)0x0044) +#define BKP_DR13 ((uint16_t)0x0048) +#define BKP_DR14 ((uint16_t)0x004C) +#define BKP_DR15 ((uint16_t)0x0050) +#define BKP_DR16 ((uint16_t)0x0054) +#define BKP_DR17 ((uint16_t)0x0058) +#define BKP_DR18 ((uint16_t)0x005C) +#define BKP_DR19 ((uint16_t)0x0060) +#define BKP_DR20 ((uint16_t)0x0064) +#define BKP_DR21 ((uint16_t)0x0068) +#define BKP_DR22 ((uint16_t)0x006C) +#define BKP_DR23 ((uint16_t)0x0070) +#define BKP_DR24 ((uint16_t)0x0074) +#define BKP_DR25 ((uint16_t)0x0078) +#define BKP_DR26 ((uint16_t)0x007C) +#define BKP_DR27 ((uint16_t)0x0080) +#define BKP_DR28 ((uint16_t)0x0084) +#define BKP_DR29 ((uint16_t)0x0088) +#define BKP_DR30 ((uint16_t)0x008C) +#define BKP_DR31 ((uint16_t)0x0090) +#define BKP_DR32 ((uint16_t)0x0094) +#define BKP_DR33 ((uint16_t)0x0098) +#define BKP_DR34 ((uint16_t)0x009C) +#define BKP_DR35 ((uint16_t)0x00A0) +#define BKP_DR36 ((uint16_t)0x00A4) +#define BKP_DR37 ((uint16_t)0x00A8) +#define BKP_DR38 ((uint16_t)0x00AC) +#define BKP_DR39 ((uint16_t)0x00B0) +#define BKP_DR40 ((uint16_t)0x00B4) +#define BKP_DR41 ((uint16_t)0x00B8) +#define BKP_DR42 ((uint16_t)0x00BC) + +#define IS_BKP_DR(DR) (((DR) == BKP_DR1) || ((DR) == BKP_DR2) || ((DR) == BKP_DR3) || \ + ((DR) == BKP_DR4) || ((DR) == BKP_DR5) || ((DR) == BKP_DR6) || \ + ((DR) == BKP_DR7) || ((DR) == BKP_DR8) || ((DR) == BKP_DR9) || \ + ((DR) == BKP_DR10) || ((DR) == BKP_DR11) || ((DR) == BKP_DR12) || \ + ((DR) == BKP_DR13) || ((DR) == BKP_DR14) || ((DR) == BKP_DR15) || \ + ((DR) == BKP_DR16) || ((DR) == BKP_DR17) || ((DR) == BKP_DR18) || \ + ((DR) == BKP_DR19) || ((DR) == BKP_DR20) || ((DR) == BKP_DR21) || \ + ((DR) == BKP_DR22) || ((DR) == BKP_DR23) || ((DR) == BKP_DR24) || \ + ((DR) == BKP_DR25) || ((DR) == BKP_DR26) || ((DR) == BKP_DR27) || \ + ((DR) == BKP_DR28) || ((DR) == BKP_DR29) || ((DR) == BKP_DR30) || \ + ((DR) == BKP_DR31) || ((DR) == BKP_DR32) || ((DR) == BKP_DR33) || \ + ((DR) == BKP_DR34) || ((DR) == BKP_DR35) || ((DR) == BKP_DR36) || \ + ((DR) == BKP_DR37) || ((DR) == BKP_DR38) || ((DR) == BKP_DR39) || \ + ((DR) == BKP_DR40) || ((DR) == BKP_DR41) || ((DR) == BKP_DR42)) + +#define IS_BKP_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x7F) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup BKP_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Exported_Functions + * @{ + */ + +void BKP_DeInit(void); +void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel); +void BKP_TamperPinCmd(FunctionalState NewState); +void BKP_ITConfig(FunctionalState NewState); +void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource); +void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue); +void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data); +uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR); +FlagStatus BKP_GetFlagStatus(void); +void BKP_ClearFlag(void); +ITStatus BKP_GetITStatus(void); +void BKP_ClearITPendingBit(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_BKP_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h index 544d779c0..057db5918 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h @@ -1,583 +1,583 @@ -/** - ****************************************************************************** - * @file stm32f10x_can.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the CAN firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_CAN_H -#define __STM32F10x_CAN_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup CAN - * @{ - */ - -/** @defgroup CAN_Exported_Types - * @{ - */ - -#define IS_CAN_ALL_PERIPH(PERIPH) (((PERIPH) == CAN1) || \ - ((PERIPH) == CAN2)) - -/** - * @brief CAN init structure definition - */ - -typedef struct -{ - uint16_t CAN_Prescaler; /*!< Specifies the length of a time quantum. It ranges from 1 to 1024. */ - - uint8_t CAN_Mode; /*!< Specifies the CAN operating mode. - This parameter can be a value of @ref CAN_operating_mode */ - - uint8_t CAN_SJW; /*!< Specifies the maximum number of time quanta the CAN hardware - is allowed to lengthen or shorten a bit to perform resynchronization. - This parameter can be a value of @ref CAN_synchronisation_jump_width */ - - uint8_t CAN_BS1; /*!< Specifies the number of time quanta in Bit Segment 1. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_1 */ - - uint8_t CAN_BS2; /*!< Specifies the number of time quanta in Bit Segment 2. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */ - - FunctionalState CAN_TTCM; /*!< Enable or disable the time triggered communication mode. - This parameter can be set either to ENABLE or DISABLE. */ - - FunctionalState CAN_ABOM; /*!< Enable or disable the automatic bus-off management. - This parameter can be set either to ENABLE or DISABLE. */ - - FunctionalState CAN_AWUM; /*!< Enable or disable the automatic wake-up mode. - This parameter can be set either to ENABLE or DISABLE. */ - - FunctionalState CAN_NART; /*!< Enable or disable the no-automatic retransmission mode. - This parameter can be set either to ENABLE or DISABLE. */ - - FunctionalState CAN_RFLM; /*!< Enable or disable the Receive FIFO Locked mode. - This parameter can be set either to ENABLE or DISABLE. */ - - FunctionalState CAN_TXFP; /*!< Enable or disable the transmit FIFO priority. - This parameter can be set either to ENABLE or DISABLE. */ -} CAN_InitTypeDef; - -/** - * @brief CAN filter init structure definition - */ - -typedef struct -{ - uint16_t CAN_FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit - configuration, first one for a 16-bit configuration). - This parameter can be a value between 0x0000 and 0xFFFF */ - - uint16_t CAN_FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit - configuration, second one for a 16-bit configuration). - This parameter can be a value between 0x0000 and 0xFFFF */ - - uint16_t CAN_FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, - according to the mode (MSBs for a 32-bit configuration, - first one for a 16-bit configuration). - This parameter can be a value between 0x0000 and 0xFFFF */ - - uint16_t CAN_FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, - according to the mode (LSBs for a 32-bit configuration, - second one for a 16-bit configuration). - This parameter can be a value between 0x0000 and 0xFFFF */ - - uint16_t CAN_FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter. - This parameter can be a value of @ref CAN_filter_FIFO */ - - uint8_t CAN_FilterNumber; /*!< Specifies the filter which will be initialized. It ranges from 0 to 13. */ - - uint8_t CAN_FilterMode; /*!< Specifies the filter mode to be initialized. - This parameter can be a value of @ref CAN_filter_mode */ - - uint8_t CAN_FilterScale; /*!< Specifies the filter scale. - This parameter can be a value of @ref CAN_filter_scale */ - - FunctionalState CAN_FilterActivation; /*!< Enable or disable the filter. - This parameter can be set either to ENABLE or DISABLE. */ -} CAN_FilterInitTypeDef; - -/** - * @brief CAN Tx message structure definition - */ - -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter can be a value between 0 to 0x7FF. */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter can be a value between 0 to 0x1FFFFFFF. */ - - uint8_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. - This parameter can be a value of @ref CAN_identifier_type */ - - uint8_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint8_t DLC; /*!< Specifies the length of the frame that will be transmitted. - This parameter can be a value between 0 to 8 */ - - uint8_t Data[8]; /*!< Contains the data to be transmitted. It ranges from 0 to 0xFF. */ -} CanTxMsg; - -/** - * @brief CAN Rx message structure definition - */ - -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter can be a value between 0 to 0x7FF. */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter can be a value between 0 to 0x1FFFFFFF. */ - - uint8_t IDE; /*!< Specifies the type of identifier for the message that will be received. - This parameter can be a value of @ref CAN_identifier_type */ - - uint8_t RTR; /*!< Specifies the type of frame for the received message. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint8_t DLC; /*!< Specifies the length of the frame that will be received. - This parameter can be a value between 0 to 8 */ - - uint8_t Data[8]; /*!< Contains the data to be received. It ranges from 0 to 0xFF. */ - - uint8_t FMI; /*!< Specifies the index of the filter the message stored in the mailbox passes through. - This parameter can be a value between 0 to 0xFF */ -} CanRxMsg; - -/** - * @} - */ - -/** @defgroup CAN_Exported_Constants - * @{ - */ - -/** @defgroup CAN_sleep_constants - * @{ - */ - -#define CANINITFAILED ((uint8_t)0x00) /*!< CAN initialization failed */ -#define CANINITOK ((uint8_t)0x01) /*!< CAN initialization failed */ - -/** - * @} - */ - -/** @defgroup CAN_operating_mode - * @{ - */ - -#define CAN_Mode_Normal ((uint8_t)0x00) /*!< normal mode */ -#define CAN_Mode_LoopBack ((uint8_t)0x01) /*!< loopback mode */ -#define CAN_Mode_Silent ((uint8_t)0x02) /*!< silent mode */ -#define CAN_Mode_Silent_LoopBack ((uint8_t)0x03) /*!< loopback combined with silent mode */ - -#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || ((MODE) == CAN_Mode_LoopBack)|| \ - ((MODE) == CAN_Mode_Silent) || ((MODE) == CAN_Mode_Silent_LoopBack)) -/** - * @} - */ - -/** @defgroup CAN_synchronisation_jump_width - * @{ - */ - -#define CAN_SJW_1tq ((uint8_t)0x00) /*!< 1 time quantum */ -#define CAN_SJW_2tq ((uint8_t)0x01) /*!< 2 time quantum */ -#define CAN_SJW_3tq ((uint8_t)0x02) /*!< 3 time quantum */ -#define CAN_SJW_4tq ((uint8_t)0x03) /*!< 4 time quantum */ - -#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \ - ((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq)) -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_1 - * @{ - */ - -#define CAN_BS1_1tq ((uint8_t)0x00) /*!< 1 time quantum */ -#define CAN_BS1_2tq ((uint8_t)0x01) /*!< 2 time quantum */ -#define CAN_BS1_3tq ((uint8_t)0x02) /*!< 3 time quantum */ -#define CAN_BS1_4tq ((uint8_t)0x03) /*!< 4 time quantum */ -#define CAN_BS1_5tq ((uint8_t)0x04) /*!< 5 time quantum */ -#define CAN_BS1_6tq ((uint8_t)0x05) /*!< 6 time quantum */ -#define CAN_BS1_7tq ((uint8_t)0x06) /*!< 7 time quantum */ -#define CAN_BS1_8tq ((uint8_t)0x07) /*!< 8 time quantum */ -#define CAN_BS1_9tq ((uint8_t)0x08) /*!< 9 time quantum */ -#define CAN_BS1_10tq ((uint8_t)0x09) /*!< 10 time quantum */ -#define CAN_BS1_11tq ((uint8_t)0x0A) /*!< 11 time quantum */ -#define CAN_BS1_12tq ((uint8_t)0x0B) /*!< 12 time quantum */ -#define CAN_BS1_13tq ((uint8_t)0x0C) /*!< 13 time quantum */ -#define CAN_BS1_14tq ((uint8_t)0x0D) /*!< 14 time quantum */ -#define CAN_BS1_15tq ((uint8_t)0x0E) /*!< 15 time quantum */ -#define CAN_BS1_16tq ((uint8_t)0x0F) /*!< 16 time quantum */ - -#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq) -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_2 - * @{ - */ - -#define CAN_BS2_1tq ((uint8_t)0x00) /*!< 1 time quantum */ -#define CAN_BS2_2tq ((uint8_t)0x01) /*!< 2 time quantum */ -#define CAN_BS2_3tq ((uint8_t)0x02) /*!< 3 time quantum */ -#define CAN_BS2_4tq ((uint8_t)0x03) /*!< 4 time quantum */ -#define CAN_BS2_5tq ((uint8_t)0x04) /*!< 5 time quantum */ -#define CAN_BS2_6tq ((uint8_t)0x05) /*!< 6 time quantum */ -#define CAN_BS2_7tq ((uint8_t)0x06) /*!< 7 time quantum */ -#define CAN_BS2_8tq ((uint8_t)0x07) /*!< 8 time quantum */ - -#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq) - -/** - * @} - */ - -/** @defgroup CAN_clock_prescaler - * @{ - */ - -#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024)) - -/** - * @} - */ - -/** @defgroup CAN_filter_number - * @{ - */ -#ifndef STM32F10X_CL - #define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 13) -#else - #define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27) -#endif /* STM32F10X_CL */ -/** - * @} - */ - -/** @defgroup CAN_filter_mode - * @{ - */ - -#define CAN_FilterMode_IdMask ((uint8_t)0x00) /*!< id/mask mode */ -#define CAN_FilterMode_IdList ((uint8_t)0x01) /*!< identifier list mode */ - -#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \ - ((MODE) == CAN_FilterMode_IdList)) -/** - * @} - */ - -/** @defgroup CAN_filter_scale - * @{ - */ - -#define CAN_FilterScale_16bit ((uint8_t)0x00) /*!< Two 16-bit filters */ -#define CAN_FilterScale_32bit ((uint8_t)0x01) /*!< One 32-bit filter */ - -#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \ - ((SCALE) == CAN_FilterScale_32bit)) - -/** - * @} - */ - -/** @defgroup CAN_filter_FIFO - * @{ - */ - -#define CAN_FilterFIFO0 ((uint8_t)0x00) /*!< Filter FIFO 0 assignment for filter x */ -#define CAN_FilterFIFO1 ((uint8_t)0x01) /*!< Filter FIFO 1 assignment for filter x */ -#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \ - ((FIFO) == CAN_FilterFIFO1)) - -/** - * @} - */ - -/** @defgroup Start_bank_filter_for_slave_CAN - * @{ - */ -#define IS_CAN_BANKNUMBER(BANKNUMBER) (((BANKNUMBER) >= 1) && ((BANKNUMBER) <= 27)) -/** - * @} - */ - -/** @defgroup CAN_Tx - * @{ - */ - -#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02)) -#define IS_CAN_STDID(STDID) ((STDID) <= ((uint32_t)0x7FF)) -#define IS_CAN_EXTID(EXTID) ((EXTID) <= ((uint32_t)0x1FFFFFFF)) -#define IS_CAN_DLC(DLC) ((DLC) <= ((uint8_t)0x08)) - -/** - * @} - */ - -/** @defgroup CAN_identifier_type - * @{ - */ - -#define CAN_ID_STD ((uint32_t)0x00000000) /*!< Standard Id */ -#define CAN_ID_EXT ((uint32_t)0x00000004) /*!< Extended Id */ -#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || ((IDTYPE) == CAN_ID_EXT)) - -/** - * @} - */ - -/** @defgroup CAN_remote_transmission_request - * @{ - */ - -#define CAN_RTR_DATA ((uint32_t)0x00000000) /*!< Data frame */ -#define CAN_RTR_REMOTE ((uint32_t)0x00000002) /*!< Remote frame */ -#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE)) - -/** - * @} - */ - -/** @defgroup CAN_transmit_constants - * @{ - */ - -#define CANTXFAILED ((uint8_t)0x00) /*!< CAN transmission failed */ -#define CANTXOK ((uint8_t)0x01) /*!< CAN transmission succeeded */ -#define CANTXPENDING ((uint8_t)0x02) /*!< CAN transmission pending */ -#define CAN_NO_MB ((uint8_t)0x04) /*!< CAN cell did not provide an empty mailbox */ - -/** - * @} - */ - -/** @defgroup CAN_receive_FIFO_number_constants - * @{ - */ - -#define CAN_FIFO0 ((uint8_t)0x00) /*!< CAN FIFO0 used to receive */ -#define CAN_FIFO1 ((uint8_t)0x01) /*!< CAN FIFO1 used to receive */ - -#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1)) - -/** - * @} - */ - -/** @defgroup CAN_sleep_constants - * @{ - */ - -#define CANSLEEPFAILED ((uint8_t)0x00) /*!< CAN did not enter the sleep mode */ -#define CANSLEEPOK ((uint8_t)0x01) /*!< CAN entered the sleep mode */ - -/** - * @} - */ - -/** @defgroup CAN_wake_up_constants - * @{ - */ - -#define CANWAKEUPFAILED ((uint8_t)0x00) /*!< CAN did not leave the sleep mode */ -#define CANWAKEUPOK ((uint8_t)0x01) /*!< CAN leaved the sleep mode */ - -/** - * @} - */ - -/** @defgroup CAN_flags - * @{ - */ -/* If the flag is 0x3XXXXXXX, it means that it can be used with CAN_GetFlagStatus() - and CAN_ClearFlag() functions. */ -/* If the flag is 0x1XXXXXXX, it means that it can only be used with CAN_GetFlagStatus() function. */ - -/* Transmit Flags */ -#define CAN_FLAG_RQCP0 ((uint32_t)0x38000001) /*!< Request MailBox0 Flag */ -#define CAN_FLAG_RQCP1 ((uint32_t)0x38000100) /*!< Request MailBox1 Flag */ -#define CAN_FLAG_RQCP2 ((uint32_t)0x38010000) /*!< Request MailBox2 Flag */ - -/* Receive Flags */ -#define CAN_FLAG_FMP0 ((uint32_t)0x12000003) /*!< FIFO 0 Message Pending Flag */ -#define CAN_FLAG_FF0 ((uint32_t)0x32000008) /*!< FIFO 0 Full Flag */ -#define CAN_FLAG_FOV0 ((uint32_t)0x32000010) /*!< FIFO 0 Overrun Flag */ -#define CAN_FLAG_FMP1 ((uint32_t)0x14000003) /*!< FIFO 1 Message Pending Flag */ -#define CAN_FLAG_FF1 ((uint32_t)0x34000008) /*!< FIFO 1 Full Flag */ -#define CAN_FLAG_FOV1 ((uint32_t)0x34000010) /*!< FIFO 1 Overrun Flag */ - -/* Operating Mode Flags */ -#define CAN_FLAG_WKU ((uint32_t)0x31000008) /*!< Wake up Flag */ -#define CAN_FLAG_SLAK ((uint32_t)0x31000012) /*!< Sleep acknowledge Flag */ -/* Note: When SLAK intterupt is disabled (SLKIE=0), no polling on SLAKI is possible. - In this case the SLAK bit can be polled.*/ - -/* Error Flags */ -#define CAN_FLAG_EWG ((uint32_t)0x10F00001) /*!< Error Warning Flag */ -#define CAN_FLAG_EPV ((uint32_t)0x10F00002) /*!< Error Passive Flag */ -#define CAN_FLAG_BOF ((uint32_t)0x10F00004) /*!< Bus-Off Flag */ -#define CAN_FLAG_LEC ((uint32_t)0x30F00070) /*!< Last error code Flag */ - -#define IS_CAN_GET_FLAG(FLAG) (((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_BOF) || \ - ((FLAG) == CAN_FLAG_EPV) || ((FLAG) == CAN_FLAG_EWG) || \ - ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_FOV0) || \ - ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FMP0) || \ - ((FLAG) == CAN_FLAG_FOV1) || ((FLAG) == CAN_FLAG_FF1) || \ - ((FLAG) == CAN_FLAG_FMP1) || ((FLAG) == CAN_FLAG_RQCP2) || \ - ((FLAG) == CAN_FLAG_RQCP1)|| ((FLAG) == CAN_FLAG_RQCP0) || \ - ((FLAG) == CAN_FLAG_SLAK )) - -#define IS_CAN_CLEAR_FLAG(FLAG)(((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_RQCP2) || \ - ((FLAG) == CAN_FLAG_RQCP1) || ((FLAG) == CAN_FLAG_RQCP0) || \ - ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FOV0) ||\ - ((FLAG) == CAN_FLAG_FF1) || ((FLAG) == CAN_FLAG_FOV1) || \ - ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_SLAK)) -/** - * @} - */ - - -/** @defgroup CAN_interrupts - * @{ - */ - - - -#define CAN_IT_TME ((uint32_t)0x00000001) /*!< Transmit mailbox empty Interrupt*/ - -/* Receive Interrupts */ -#define CAN_IT_FMP0 ((uint32_t)0x00000002) /*!< FIFO 0 message pending Interrupt*/ -#define CAN_IT_FF0 ((uint32_t)0x00000004) /*!< FIFO 0 full Interrupt*/ -#define CAN_IT_FOV0 ((uint32_t)0x00000008) /*!< FIFO 0 overrun Interrupt*/ -#define CAN_IT_FMP1 ((uint32_t)0x00000010) /*!< FIFO 1 message pending Interrupt*/ -#define CAN_IT_FF1 ((uint32_t)0x00000020) /*!< FIFO 1 full Interrupt*/ -#define CAN_IT_FOV1 ((uint32_t)0x00000040) /*!< FIFO 1 overrun Interrupt*/ - -/* Operating Mode Interrupts */ -#define CAN_IT_WKU ((uint32_t)0x00010000) /*!< Wake-up Interrupt*/ -#define CAN_IT_SLK ((uint32_t)0x00020000) /*!< Sleep acknowledge Interrupt*/ - -/* Error Interrupts */ -#define CAN_IT_EWG ((uint32_t)0x00000100) /*!< Error warning Interrupt*/ -#define CAN_IT_EPV ((uint32_t)0x00000200) /*!< Error passive Interrupt*/ -#define CAN_IT_BOF ((uint32_t)0x00000400) /*!< Bus-off Interrupt*/ -#define CAN_IT_LEC ((uint32_t)0x00000800) /*!< Last error code Interrupt*/ -#define CAN_IT_ERR ((uint32_t)0x00008000) /*!< Error Interrupt*/ - -/* Flags named as Interrupts : kept only for FW compatibility */ -#define CAN_IT_RQCP0 CAN_IT_TME -#define CAN_IT_RQCP1 CAN_IT_TME -#define CAN_IT_RQCP2 CAN_IT_TME - - -#define IS_CAN_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FMP0) ||\ - ((IT) == CAN_IT_FF0) || ((IT) == CAN_IT_FOV0) ||\ - ((IT) == CAN_IT_FMP1) || ((IT) == CAN_IT_FF1) ||\ - ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\ - ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ - ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ - ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) - -#define IS_CAN_CLEAR_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FF0) ||\ - ((IT) == CAN_IT_FOV0) || ((IT) == CAN_IT_FF1) ||\ - ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\ - ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ - ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ - ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup CAN_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup CAN_Exported_Functions - * @{ - */ - -void CAN_DeInit(CAN_TypeDef* CANx); -uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct); -void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct); -void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct); -void CAN_SlaveStartBank(uint8_t CAN_BankNumber); -void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState); -uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage); -uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox); -void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox); -void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber); -uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber); -void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage); -void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState); -uint8_t CAN_Sleep(CAN_TypeDef* CANx); -uint8_t CAN_WakeUp(CAN_TypeDef* CANx); -FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG); -void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG); -ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT); -void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_CAN_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_can.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the CAN firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CAN_H +#define __STM32F10x_CAN_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CAN + * @{ + */ + +/** @defgroup CAN_Exported_Types + * @{ + */ + +#define IS_CAN_ALL_PERIPH(PERIPH) (((PERIPH) == CAN1) || \ + ((PERIPH) == CAN2)) + +/** + * @brief CAN init structure definition + */ + +typedef struct +{ + uint16_t CAN_Prescaler; /*!< Specifies the length of a time quantum. It ranges from 1 to 1024. */ + + uint8_t CAN_Mode; /*!< Specifies the CAN operating mode. + This parameter can be a value of @ref CAN_operating_mode */ + + uint8_t CAN_SJW; /*!< Specifies the maximum number of time quanta the CAN hardware + is allowed to lengthen or shorten a bit to perform resynchronization. + This parameter can be a value of @ref CAN_synchronisation_jump_width */ + + uint8_t CAN_BS1; /*!< Specifies the number of time quanta in Bit Segment 1. + This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_1 */ + + uint8_t CAN_BS2; /*!< Specifies the number of time quanta in Bit Segment 2. + This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */ + + FunctionalState CAN_TTCM; /*!< Enable or disable the time triggered communication mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_ABOM; /*!< Enable or disable the automatic bus-off management. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_AWUM; /*!< Enable or disable the automatic wake-up mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_NART; /*!< Enable or disable the no-automatic retransmission mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_RFLM; /*!< Enable or disable the Receive FIFO Locked mode. + This parameter can be set either to ENABLE or DISABLE. */ + + FunctionalState CAN_TXFP; /*!< Enable or disable the transmit FIFO priority. + This parameter can be set either to ENABLE or DISABLE. */ +} CAN_InitTypeDef; + +/** + * @brief CAN filter init structure definition + */ + +typedef struct +{ + uint16_t CAN_FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit + configuration, first one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit + configuration, second one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, + according to the mode (MSBs for a 32-bit configuration, + first one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, + according to the mode (LSBs for a 32-bit configuration, + second one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter. + This parameter can be a value of @ref CAN_filter_FIFO */ + + uint8_t CAN_FilterNumber; /*!< Specifies the filter which will be initialized. It ranges from 0 to 13. */ + + uint8_t CAN_FilterMode; /*!< Specifies the filter mode to be initialized. + This parameter can be a value of @ref CAN_filter_mode */ + + uint8_t CAN_FilterScale; /*!< Specifies the filter scale. + This parameter can be a value of @ref CAN_filter_scale */ + + FunctionalState CAN_FilterActivation; /*!< Enable or disable the filter. + This parameter can be set either to ENABLE or DISABLE. */ +} CAN_FilterInitTypeDef; + +/** + * @brief CAN Tx message structure definition + */ + +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter can be a value between 0 to 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter can be a value between 0 to 0x1FFFFFFF. */ + + uint8_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. + This parameter can be a value of @ref CAN_identifier_type */ + + uint8_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. + This parameter can be a value of @ref CAN_remote_transmission_request */ + + uint8_t DLC; /*!< Specifies the length of the frame that will be transmitted. + This parameter can be a value between 0 to 8 */ + + uint8_t Data[8]; /*!< Contains the data to be transmitted. It ranges from 0 to 0xFF. */ +} CanTxMsg; + +/** + * @brief CAN Rx message structure definition + */ + +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter can be a value between 0 to 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter can be a value between 0 to 0x1FFFFFFF. */ + + uint8_t IDE; /*!< Specifies the type of identifier for the message that will be received. + This parameter can be a value of @ref CAN_identifier_type */ + + uint8_t RTR; /*!< Specifies the type of frame for the received message. + This parameter can be a value of @ref CAN_remote_transmission_request */ + + uint8_t DLC; /*!< Specifies the length of the frame that will be received. + This parameter can be a value between 0 to 8 */ + + uint8_t Data[8]; /*!< Contains the data to be received. It ranges from 0 to 0xFF. */ + + uint8_t FMI; /*!< Specifies the index of the filter the message stored in the mailbox passes through. + This parameter can be a value between 0 to 0xFF */ +} CanRxMsg; + +/** + * @} + */ + +/** @defgroup CAN_Exported_Constants + * @{ + */ + +/** @defgroup CAN_sleep_constants + * @{ + */ + +#define CANINITFAILED ((uint8_t)0x00) /*!< CAN initialization failed */ +#define CANINITOK ((uint8_t)0x01) /*!< CAN initialization failed */ + +/** + * @} + */ + +/** @defgroup CAN_operating_mode + * @{ + */ + +#define CAN_Mode_Normal ((uint8_t)0x00) /*!< normal mode */ +#define CAN_Mode_LoopBack ((uint8_t)0x01) /*!< loopback mode */ +#define CAN_Mode_Silent ((uint8_t)0x02) /*!< silent mode */ +#define CAN_Mode_Silent_LoopBack ((uint8_t)0x03) /*!< loopback combined with silent mode */ + +#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || ((MODE) == CAN_Mode_LoopBack)|| \ + ((MODE) == CAN_Mode_Silent) || ((MODE) == CAN_Mode_Silent_LoopBack)) +/** + * @} + */ + +/** @defgroup CAN_synchronisation_jump_width + * @{ + */ + +#define CAN_SJW_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_SJW_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_SJW_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_SJW_4tq ((uint8_t)0x03) /*!< 4 time quantum */ + +#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \ + ((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq)) +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_1 + * @{ + */ + +#define CAN_BS1_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_BS1_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_BS1_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_BS1_4tq ((uint8_t)0x03) /*!< 4 time quantum */ +#define CAN_BS1_5tq ((uint8_t)0x04) /*!< 5 time quantum */ +#define CAN_BS1_6tq ((uint8_t)0x05) /*!< 6 time quantum */ +#define CAN_BS1_7tq ((uint8_t)0x06) /*!< 7 time quantum */ +#define CAN_BS1_8tq ((uint8_t)0x07) /*!< 8 time quantum */ +#define CAN_BS1_9tq ((uint8_t)0x08) /*!< 9 time quantum */ +#define CAN_BS1_10tq ((uint8_t)0x09) /*!< 10 time quantum */ +#define CAN_BS1_11tq ((uint8_t)0x0A) /*!< 11 time quantum */ +#define CAN_BS1_12tq ((uint8_t)0x0B) /*!< 12 time quantum */ +#define CAN_BS1_13tq ((uint8_t)0x0C) /*!< 13 time quantum */ +#define CAN_BS1_14tq ((uint8_t)0x0D) /*!< 14 time quantum */ +#define CAN_BS1_15tq ((uint8_t)0x0E) /*!< 15 time quantum */ +#define CAN_BS1_16tq ((uint8_t)0x0F) /*!< 16 time quantum */ + +#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq) +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_2 + * @{ + */ + +#define CAN_BS2_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_BS2_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_BS2_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_BS2_4tq ((uint8_t)0x03) /*!< 4 time quantum */ +#define CAN_BS2_5tq ((uint8_t)0x04) /*!< 5 time quantum */ +#define CAN_BS2_6tq ((uint8_t)0x05) /*!< 6 time quantum */ +#define CAN_BS2_7tq ((uint8_t)0x06) /*!< 7 time quantum */ +#define CAN_BS2_8tq ((uint8_t)0x07) /*!< 8 time quantum */ + +#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq) + +/** + * @} + */ + +/** @defgroup CAN_clock_prescaler + * @{ + */ + +#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024)) + +/** + * @} + */ + +/** @defgroup CAN_filter_number + * @{ + */ +#ifndef STM32F10X_CL + #define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 13) +#else + #define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27) +#endif /* STM32F10X_CL */ +/** + * @} + */ + +/** @defgroup CAN_filter_mode + * @{ + */ + +#define CAN_FilterMode_IdMask ((uint8_t)0x00) /*!< id/mask mode */ +#define CAN_FilterMode_IdList ((uint8_t)0x01) /*!< identifier list mode */ + +#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \ + ((MODE) == CAN_FilterMode_IdList)) +/** + * @} + */ + +/** @defgroup CAN_filter_scale + * @{ + */ + +#define CAN_FilterScale_16bit ((uint8_t)0x00) /*!< Two 16-bit filters */ +#define CAN_FilterScale_32bit ((uint8_t)0x01) /*!< One 32-bit filter */ + +#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \ + ((SCALE) == CAN_FilterScale_32bit)) + +/** + * @} + */ + +/** @defgroup CAN_filter_FIFO + * @{ + */ + +#define CAN_FilterFIFO0 ((uint8_t)0x00) /*!< Filter FIFO 0 assignment for filter x */ +#define CAN_FilterFIFO1 ((uint8_t)0x01) /*!< Filter FIFO 1 assignment for filter x */ +#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \ + ((FIFO) == CAN_FilterFIFO1)) + +/** + * @} + */ + +/** @defgroup Start_bank_filter_for_slave_CAN + * @{ + */ +#define IS_CAN_BANKNUMBER(BANKNUMBER) (((BANKNUMBER) >= 1) && ((BANKNUMBER) <= 27)) +/** + * @} + */ + +/** @defgroup CAN_Tx + * @{ + */ + +#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02)) +#define IS_CAN_STDID(STDID) ((STDID) <= ((uint32_t)0x7FF)) +#define IS_CAN_EXTID(EXTID) ((EXTID) <= ((uint32_t)0x1FFFFFFF)) +#define IS_CAN_DLC(DLC) ((DLC) <= ((uint8_t)0x08)) + +/** + * @} + */ + +/** @defgroup CAN_identifier_type + * @{ + */ + +#define CAN_ID_STD ((uint32_t)0x00000000) /*!< Standard Id */ +#define CAN_ID_EXT ((uint32_t)0x00000004) /*!< Extended Id */ +#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || ((IDTYPE) == CAN_ID_EXT)) + +/** + * @} + */ + +/** @defgroup CAN_remote_transmission_request + * @{ + */ + +#define CAN_RTR_DATA ((uint32_t)0x00000000) /*!< Data frame */ +#define CAN_RTR_REMOTE ((uint32_t)0x00000002) /*!< Remote frame */ +#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE)) + +/** + * @} + */ + +/** @defgroup CAN_transmit_constants + * @{ + */ + +#define CANTXFAILED ((uint8_t)0x00) /*!< CAN transmission failed */ +#define CANTXOK ((uint8_t)0x01) /*!< CAN transmission succeeded */ +#define CANTXPENDING ((uint8_t)0x02) /*!< CAN transmission pending */ +#define CAN_NO_MB ((uint8_t)0x04) /*!< CAN cell did not provide an empty mailbox */ + +/** + * @} + */ + +/** @defgroup CAN_receive_FIFO_number_constants + * @{ + */ + +#define CAN_FIFO0 ((uint8_t)0x00) /*!< CAN FIFO0 used to receive */ +#define CAN_FIFO1 ((uint8_t)0x01) /*!< CAN FIFO1 used to receive */ + +#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1)) + +/** + * @} + */ + +/** @defgroup CAN_sleep_constants + * @{ + */ + +#define CANSLEEPFAILED ((uint8_t)0x00) /*!< CAN did not enter the sleep mode */ +#define CANSLEEPOK ((uint8_t)0x01) /*!< CAN entered the sleep mode */ + +/** + * @} + */ + +/** @defgroup CAN_wake_up_constants + * @{ + */ + +#define CANWAKEUPFAILED ((uint8_t)0x00) /*!< CAN did not leave the sleep mode */ +#define CANWAKEUPOK ((uint8_t)0x01) /*!< CAN leaved the sleep mode */ + +/** + * @} + */ + +/** @defgroup CAN_flags + * @{ + */ +/* If the flag is 0x3XXXXXXX, it means that it can be used with CAN_GetFlagStatus() + and CAN_ClearFlag() functions. */ +/* If the flag is 0x1XXXXXXX, it means that it can only be used with CAN_GetFlagStatus() function. */ + +/* Transmit Flags */ +#define CAN_FLAG_RQCP0 ((uint32_t)0x38000001) /*!< Request MailBox0 Flag */ +#define CAN_FLAG_RQCP1 ((uint32_t)0x38000100) /*!< Request MailBox1 Flag */ +#define CAN_FLAG_RQCP2 ((uint32_t)0x38010000) /*!< Request MailBox2 Flag */ + +/* Receive Flags */ +#define CAN_FLAG_FMP0 ((uint32_t)0x12000003) /*!< FIFO 0 Message Pending Flag */ +#define CAN_FLAG_FF0 ((uint32_t)0x32000008) /*!< FIFO 0 Full Flag */ +#define CAN_FLAG_FOV0 ((uint32_t)0x32000010) /*!< FIFO 0 Overrun Flag */ +#define CAN_FLAG_FMP1 ((uint32_t)0x14000003) /*!< FIFO 1 Message Pending Flag */ +#define CAN_FLAG_FF1 ((uint32_t)0x34000008) /*!< FIFO 1 Full Flag */ +#define CAN_FLAG_FOV1 ((uint32_t)0x34000010) /*!< FIFO 1 Overrun Flag */ + +/* Operating Mode Flags */ +#define CAN_FLAG_WKU ((uint32_t)0x31000008) /*!< Wake up Flag */ +#define CAN_FLAG_SLAK ((uint32_t)0x31000012) /*!< Sleep acknowledge Flag */ +/* Note: When SLAK intterupt is disabled (SLKIE=0), no polling on SLAKI is possible. + In this case the SLAK bit can be polled.*/ + +/* Error Flags */ +#define CAN_FLAG_EWG ((uint32_t)0x10F00001) /*!< Error Warning Flag */ +#define CAN_FLAG_EPV ((uint32_t)0x10F00002) /*!< Error Passive Flag */ +#define CAN_FLAG_BOF ((uint32_t)0x10F00004) /*!< Bus-Off Flag */ +#define CAN_FLAG_LEC ((uint32_t)0x30F00070) /*!< Last error code Flag */ + +#define IS_CAN_GET_FLAG(FLAG) (((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_BOF) || \ + ((FLAG) == CAN_FLAG_EPV) || ((FLAG) == CAN_FLAG_EWG) || \ + ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_FOV0) || \ + ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FMP0) || \ + ((FLAG) == CAN_FLAG_FOV1) || ((FLAG) == CAN_FLAG_FF1) || \ + ((FLAG) == CAN_FLAG_FMP1) || ((FLAG) == CAN_FLAG_RQCP2) || \ + ((FLAG) == CAN_FLAG_RQCP1)|| ((FLAG) == CAN_FLAG_RQCP0) || \ + ((FLAG) == CAN_FLAG_SLAK )) + +#define IS_CAN_CLEAR_FLAG(FLAG)(((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_RQCP2) || \ + ((FLAG) == CAN_FLAG_RQCP1) || ((FLAG) == CAN_FLAG_RQCP0) || \ + ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FOV0) ||\ + ((FLAG) == CAN_FLAG_FF1) || ((FLAG) == CAN_FLAG_FOV1) || \ + ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_SLAK)) +/** + * @} + */ + + +/** @defgroup CAN_interrupts + * @{ + */ + + + +#define CAN_IT_TME ((uint32_t)0x00000001) /*!< Transmit mailbox empty Interrupt*/ + +/* Receive Interrupts */ +#define CAN_IT_FMP0 ((uint32_t)0x00000002) /*!< FIFO 0 message pending Interrupt*/ +#define CAN_IT_FF0 ((uint32_t)0x00000004) /*!< FIFO 0 full Interrupt*/ +#define CAN_IT_FOV0 ((uint32_t)0x00000008) /*!< FIFO 0 overrun Interrupt*/ +#define CAN_IT_FMP1 ((uint32_t)0x00000010) /*!< FIFO 1 message pending Interrupt*/ +#define CAN_IT_FF1 ((uint32_t)0x00000020) /*!< FIFO 1 full Interrupt*/ +#define CAN_IT_FOV1 ((uint32_t)0x00000040) /*!< FIFO 1 overrun Interrupt*/ + +/* Operating Mode Interrupts */ +#define CAN_IT_WKU ((uint32_t)0x00010000) /*!< Wake-up Interrupt*/ +#define CAN_IT_SLK ((uint32_t)0x00020000) /*!< Sleep acknowledge Interrupt*/ + +/* Error Interrupts */ +#define CAN_IT_EWG ((uint32_t)0x00000100) /*!< Error warning Interrupt*/ +#define CAN_IT_EPV ((uint32_t)0x00000200) /*!< Error passive Interrupt*/ +#define CAN_IT_BOF ((uint32_t)0x00000400) /*!< Bus-off Interrupt*/ +#define CAN_IT_LEC ((uint32_t)0x00000800) /*!< Last error code Interrupt*/ +#define CAN_IT_ERR ((uint32_t)0x00008000) /*!< Error Interrupt*/ + +/* Flags named as Interrupts : kept only for FW compatibility */ +#define CAN_IT_RQCP0 CAN_IT_TME +#define CAN_IT_RQCP1 CAN_IT_TME +#define CAN_IT_RQCP2 CAN_IT_TME + + +#define IS_CAN_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FMP0) ||\ + ((IT) == CAN_IT_FF0) || ((IT) == CAN_IT_FOV0) ||\ + ((IT) == CAN_IT_FMP1) || ((IT) == CAN_IT_FF1) ||\ + ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\ + ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ + ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ + ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) + +#define IS_CAN_CLEAR_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FF0) ||\ + ((IT) == CAN_IT_FOV0) || ((IT) == CAN_IT_FF1) ||\ + ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\ + ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ + ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ + ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup CAN_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions + * @{ + */ + +void CAN_DeInit(CAN_TypeDef* CANx); +uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct); +void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct); +void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct); +void CAN_SlaveStartBank(uint8_t CAN_BankNumber); +void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState); +uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage); +uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox); +void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox); +void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber); +uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber); +void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage); +void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState); +uint8_t CAN_Sleep(CAN_TypeDef* CANx); +uint8_t CAN_WakeUp(CAN_TypeDef* CANx); +FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG); +void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG); +ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT); +void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_CAN_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h index 10aaba7b1..69c256c94 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h @@ -1,209 +1,209 @@ -/** - ****************************************************************************** - * @file stm32f10x_cec.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the CEC firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_CEC_H -#define __STM32F10x_CEC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup CEC - * @{ - */ - - -/** @defgroup CEC_Exported_Types - * @{ - */ - -/** - * @brief CEC Init structure definition - */ -typedef struct -{ - uint16_t CEC_BitTimingMode; /*!< Configures the CEC Bit Timing Error Mode. - This parameter can be a value of @ref CEC_BitTiming_Mode */ - uint16_t CEC_BitPeriodMode; /*!< Configures the CEC Bit Period Error Mode. - This parameter can be a value of @ref CEC_BitPeriod_Mode */ -}CEC_InitTypeDef; - -/** - * @} - */ - -/** @defgroup CEC_Exported_Constants - * @{ - */ - -/** @defgroup CEC_BitTiming_Mode - * @{ - */ -#define CEC_BitTimingStdMode ((uint16_t)0x00) /*!< Bit timing error Standard Mode */ -#define CEC_BitTimingErrFreeMode CEC_CFGR_BTEM /*!< Bit timing error Free Mode */ - -#define IS_CEC_BIT_TIMING_ERROR_MODE(MODE) (((MODE) == CEC_BitTimingStdMode) || \ - ((MODE) == CEC_BitTimingErrFreeMode)) -/** - * @} - */ - -/** @defgroup CEC_BitPeriod_Mode - * @{ - */ -#define CEC_BitPeriodStdMode ((uint16_t)0x00) /*!< Bit period error Standard Mode */ -#define CEC_BitPeriodFlexibleMode CEC_CFGR_BPEM /*!< Bit period error Flexible Mode */ - -#define IS_CEC_BIT_PERIOD_ERROR_MODE(MODE) (((MODE) == CEC_BitPeriodStdMode) || \ - ((MODE) == CEC_BitPeriodFlexibleMode)) -/** - * @} - */ - - -/** @defgroup CEC_interrupts_definition - * @{ - */ -#define CEC_IT_TERR CEC_CSR_TERR -#define CEC_IT_TBTRF CEC_CSR_TBTRF -#define CEC_IT_RERR CEC_CSR_RERR -#define CEC_IT_RBTF CEC_CSR_RBTF -#define IS_CEC_GET_IT(IT) (((IT) == CEC_IT_TERR) || ((IT) == CEC_IT_TBTRF) || \ - ((IT) == CEC_IT_RERR) || ((IT) == CEC_IT_RBTF)) -/** - * @} - */ - - -/** @defgroup CEC_Own_Addres - * @{ - */ -#define IS_CEC_ADDRESS(ADDRESS) ((ADDRESS) < 0x10) -/** - * @} - */ - -/** @defgroup CEC_Prescaler - * @{ - */ -#define IS_CEC_PRESCALER(PRESCALER) ((PRESCALER) <= 0x3FFF) - -/** - * @} - */ - -/** @defgroup CEC_flags_definition - * @{ - */ - -/** - * @brief ESR register flags - */ -#define CEC_FLAG_BTE ((uint32_t)0x10010000) -#define CEC_FLAG_BPE ((uint32_t)0x10020000) -#define CEC_FLAG_RBTFE ((uint32_t)0x10040000) -#define CEC_FLAG_SBE ((uint32_t)0x10080000) -#define CEC_FLAG_ACKE ((uint32_t)0x10100000) -#define CEC_FLAG_LINE ((uint32_t)0x10200000) -#define CEC_FLAG_TBTFE ((uint32_t)0x10400000) - -/** - * @brief CSR register flags - */ -#define CEC_FLAG_TEOM ((uint32_t)0x00000002) -#define CEC_FLAG_TERR ((uint32_t)0x00000004) -#define CEC_FLAG_TBTRF ((uint32_t)0x00000008) -#define CEC_FLAG_RSOM ((uint32_t)0x00000010) -#define CEC_FLAG_REOM ((uint32_t)0x00000020) -#define CEC_FLAG_RERR ((uint32_t)0x00000040) -#define CEC_FLAG_RBTF ((uint32_t)0x00000080) - -#define IS_CEC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFF03) == 0x00) && ((FLAG) != 0x00)) - -#define IS_CEC_GET_FLAG(FLAG) (((FLAG) == CEC_FLAG_BTE) || ((FLAG) == CEC_FLAG_BPE) || \ - ((FLAG) == CEC_FLAG_RBTFE) || ((FLAG)== CEC_FLAG_SBE) || \ - ((FLAG) == CEC_FLAG_ACKE) || ((FLAG) == CEC_FLAG_LINE) || \ - ((FLAG) == CEC_FLAG_TBTFE) || ((FLAG) == CEC_FLAG_TEOM) || \ - ((FLAG) == CEC_FLAG_TERR) || ((FLAG) == CEC_FLAG_TBTRF) || \ - ((FLAG) == CEC_FLAG_RSOM) || ((FLAG) == CEC_FLAG_REOM) || \ - ((FLAG) == CEC_FLAG_RERR) || ((FLAG) == CEC_FLAG_RBTF)) - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup CEC_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup CEC_Exported_Functions - * @{ - */ -void CEC_DeInit(void); -void CEC_Init(CEC_InitTypeDef* CEC_InitStruct); -void CEC_Cmd(FunctionalState NewState); -void CEC_ITConfig(FunctionalState NewState); -void CEC_OwnAddressConfig(uint8_t CEC_OwnAddress); -void CEC_SetPrescaler(uint16_t CEC_Prescaler); -void CEC_SendDataByte(uint8_t Data); -uint8_t CEC_ReceiveDataByte(void); -void CEC_StartOfMessage(void); -void CEC_EndOfMessageCmd(FunctionalState NewState); -FlagStatus CEC_GetFlagStatus(uint32_t CEC_FLAG); -void CEC_ClearFlag(uint32_t CEC_FLAG); -ITStatus CEC_GetITStatus(uint8_t CEC_IT); -void CEC_ClearITPendingBit(uint16_t CEC_IT); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_CEC_H */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_cec.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the CEC firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CEC_H +#define __STM32F10x_CEC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CEC + * @{ + */ + + +/** @defgroup CEC_Exported_Types + * @{ + */ + +/** + * @brief CEC Init structure definition + */ +typedef struct +{ + uint16_t CEC_BitTimingMode; /*!< Configures the CEC Bit Timing Error Mode. + This parameter can be a value of @ref CEC_BitTiming_Mode */ + uint16_t CEC_BitPeriodMode; /*!< Configures the CEC Bit Period Error Mode. + This parameter can be a value of @ref CEC_BitPeriod_Mode */ +}CEC_InitTypeDef; + +/** + * @} + */ + +/** @defgroup CEC_Exported_Constants + * @{ + */ + +/** @defgroup CEC_BitTiming_Mode + * @{ + */ +#define CEC_BitTimingStdMode ((uint16_t)0x00) /*!< Bit timing error Standard Mode */ +#define CEC_BitTimingErrFreeMode CEC_CFGR_BTEM /*!< Bit timing error Free Mode */ + +#define IS_CEC_BIT_TIMING_ERROR_MODE(MODE) (((MODE) == CEC_BitTimingStdMode) || \ + ((MODE) == CEC_BitTimingErrFreeMode)) +/** + * @} + */ + +/** @defgroup CEC_BitPeriod_Mode + * @{ + */ +#define CEC_BitPeriodStdMode ((uint16_t)0x00) /*!< Bit period error Standard Mode */ +#define CEC_BitPeriodFlexibleMode CEC_CFGR_BPEM /*!< Bit period error Flexible Mode */ + +#define IS_CEC_BIT_PERIOD_ERROR_MODE(MODE) (((MODE) == CEC_BitPeriodStdMode) || \ + ((MODE) == CEC_BitPeriodFlexibleMode)) +/** + * @} + */ + + +/** @defgroup CEC_interrupts_definition + * @{ + */ +#define CEC_IT_TERR CEC_CSR_TERR +#define CEC_IT_TBTRF CEC_CSR_TBTRF +#define CEC_IT_RERR CEC_CSR_RERR +#define CEC_IT_RBTF CEC_CSR_RBTF +#define IS_CEC_GET_IT(IT) (((IT) == CEC_IT_TERR) || ((IT) == CEC_IT_TBTRF) || \ + ((IT) == CEC_IT_RERR) || ((IT) == CEC_IT_RBTF)) +/** + * @} + */ + + +/** @defgroup CEC_Own_Addres + * @{ + */ +#define IS_CEC_ADDRESS(ADDRESS) ((ADDRESS) < 0x10) +/** + * @} + */ + +/** @defgroup CEC_Prescaler + * @{ + */ +#define IS_CEC_PRESCALER(PRESCALER) ((PRESCALER) <= 0x3FFF) + +/** + * @} + */ + +/** @defgroup CEC_flags_definition + * @{ + */ + +/** + * @brief ESR register flags + */ +#define CEC_FLAG_BTE ((uint32_t)0x10010000) +#define CEC_FLAG_BPE ((uint32_t)0x10020000) +#define CEC_FLAG_RBTFE ((uint32_t)0x10040000) +#define CEC_FLAG_SBE ((uint32_t)0x10080000) +#define CEC_FLAG_ACKE ((uint32_t)0x10100000) +#define CEC_FLAG_LINE ((uint32_t)0x10200000) +#define CEC_FLAG_TBTFE ((uint32_t)0x10400000) + +/** + * @brief CSR register flags + */ +#define CEC_FLAG_TEOM ((uint32_t)0x00000002) +#define CEC_FLAG_TERR ((uint32_t)0x00000004) +#define CEC_FLAG_TBTRF ((uint32_t)0x00000008) +#define CEC_FLAG_RSOM ((uint32_t)0x00000010) +#define CEC_FLAG_REOM ((uint32_t)0x00000020) +#define CEC_FLAG_RERR ((uint32_t)0x00000040) +#define CEC_FLAG_RBTF ((uint32_t)0x00000080) + +#define IS_CEC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFF03) == 0x00) && ((FLAG) != 0x00)) + +#define IS_CEC_GET_FLAG(FLAG) (((FLAG) == CEC_FLAG_BTE) || ((FLAG) == CEC_FLAG_BPE) || \ + ((FLAG) == CEC_FLAG_RBTFE) || ((FLAG)== CEC_FLAG_SBE) || \ + ((FLAG) == CEC_FLAG_ACKE) || ((FLAG) == CEC_FLAG_LINE) || \ + ((FLAG) == CEC_FLAG_TBTFE) || ((FLAG) == CEC_FLAG_TEOM) || \ + ((FLAG) == CEC_FLAG_TERR) || ((FLAG) == CEC_FLAG_TBTRF) || \ + ((FLAG) == CEC_FLAG_RSOM) || ((FLAG) == CEC_FLAG_REOM) || \ + ((FLAG) == CEC_FLAG_RERR) || ((FLAG) == CEC_FLAG_RBTF)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup CEC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CEC_Exported_Functions + * @{ + */ +void CEC_DeInit(void); +void CEC_Init(CEC_InitTypeDef* CEC_InitStruct); +void CEC_Cmd(FunctionalState NewState); +void CEC_ITConfig(FunctionalState NewState); +void CEC_OwnAddressConfig(uint8_t CEC_OwnAddress); +void CEC_SetPrescaler(uint16_t CEC_Prescaler); +void CEC_SendDataByte(uint8_t Data); +uint8_t CEC_ReceiveDataByte(void); +void CEC_StartOfMessage(void); +void CEC_EndOfMessageCmd(FunctionalState NewState); +FlagStatus CEC_GetFlagStatus(uint32_t CEC_FLAG); +void CEC_ClearFlag(uint32_t CEC_FLAG); +ITStatus CEC_GetITStatus(uint8_t CEC_IT); +void CEC_ClearITPendingBit(uint16_t CEC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_CEC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h index 12acce09d..32f6264dc 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h @@ -1,93 +1,93 @@ -/** - ****************************************************************************** - * @file stm32f10x_crc.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the CRC firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_CRC_H -#define __STM32F10x_CRC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup CRC - * @{ - */ - -/** @defgroup CRC_Exported_Types - * @{ - */ - -/** - * @} - */ - -/** @defgroup CRC_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @defgroup CRC_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup CRC_Exported_Functions - * @{ - */ - -void CRC_ResetDR(void); -uint32_t CRC_CalcCRC(uint32_t Data); -uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength); -uint32_t CRC_GetCRC(void); -void CRC_SetIDRegister(uint8_t IDValue); -uint8_t CRC_GetIDRegister(void); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_CRC_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_crc.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the CRC firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CRC_H +#define __STM32F10x_CRC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CRC + * @{ + */ + +/** @defgroup CRC_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Exported_Functions + * @{ + */ + +void CRC_ResetDR(void); +uint32_t CRC_CalcCRC(uint32_t Data); +uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength); +uint32_t CRC_GetCRC(void); +void CRC_SetIDRegister(uint8_t IDValue); +uint8_t CRC_GetIDRegister(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_CRC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h index 9abd63618..1511e38fa 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h @@ -1,316 +1,316 @@ -/** - ****************************************************************************** - * @file stm32f10x_dac.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the DAC firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_DAC_H -#define __STM32F10x_DAC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup DAC - * @{ - */ - -/** @defgroup DAC_Exported_Types - * @{ - */ - -/** - * @brief DAC Init structure definition - */ - -typedef struct -{ - uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel. - This parameter can be a value of @ref DAC_trigger_selection */ - - uint32_t DAC_WaveGeneration; /*!< Specifies whether DAC channel noise waves or triangle waves - are generated, or whether no wave is generated. - This parameter can be a value of @ref DAC_wave_generation */ - - uint32_t DAC_LFSRUnmask_TriangleAmplitude; /*!< Specifies the LFSR mask for noise wave generation or - the maximum amplitude triangle generation for the DAC channel. - This parameter can be a value of @ref DAC_lfsrunmask_triangleamplitude */ - - uint32_t DAC_OutputBuffer; /*!< Specifies whether the DAC channel output buffer is enabled or disabled. - This parameter can be a value of @ref DAC_output_buffer */ -}DAC_InitTypeDef; - -/** - * @} - */ - -/** @defgroup DAC_Exported_Constants - * @{ - */ - -/** @defgroup DAC_trigger_selection - * @{ - */ - -#define DAC_Trigger_None ((uint32_t)0x00000000) /*!< Conversion is automatic once the DAC1_DHRxxxx register - has been loaded, and not by external trigger */ -#define DAC_Trigger_T6_TRGO ((uint32_t)0x00000004) /*!< TIM6 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_Trigger_T8_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel - only in High-density devices*/ -#define DAC_Trigger_T3_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel - only in Connectivity line, Medium-density and Low-density Value Line devices */ -#define DAC_Trigger_T7_TRGO ((uint32_t)0x00000014) /*!< TIM7 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_Trigger_T5_TRGO ((uint32_t)0x0000001C) /*!< TIM5 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_Trigger_T15_TRGO ((uint32_t)0x0000001C) /*!< TIM15 TRGO selected as external conversion trigger for DAC channel - only in Medium-density and Low-density Value Line devices*/ -#define DAC_Trigger_T2_TRGO ((uint32_t)0x00000024) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_Trigger_T4_TRGO ((uint32_t)0x0000002C) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_Trigger_Ext_IT9 ((uint32_t)0x00000034) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */ -#define DAC_Trigger_Software ((uint32_t)0x0000003C) /*!< Conversion started by software trigger for DAC channel */ - -#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \ - ((TRIGGER) == DAC_Trigger_T6_TRGO) || \ - ((TRIGGER) == DAC_Trigger_T8_TRGO) || \ - ((TRIGGER) == DAC_Trigger_T7_TRGO) || \ - ((TRIGGER) == DAC_Trigger_T5_TRGO) || \ - ((TRIGGER) == DAC_Trigger_T2_TRGO) || \ - ((TRIGGER) == DAC_Trigger_T4_TRGO) || \ - ((TRIGGER) == DAC_Trigger_Ext_IT9) || \ - ((TRIGGER) == DAC_Trigger_Software)) - -/** - * @} - */ - -/** @defgroup DAC_wave_generation - * @{ - */ - -#define DAC_WaveGeneration_None ((uint32_t)0x00000000) -#define DAC_WaveGeneration_Noise ((uint32_t)0x00000040) -#define DAC_WaveGeneration_Triangle ((uint32_t)0x00000080) -#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \ - ((WAVE) == DAC_WaveGeneration_Noise) || \ - ((WAVE) == DAC_WaveGeneration_Triangle)) -/** - * @} - */ - -/** @defgroup DAC_lfsrunmask_triangleamplitude - * @{ - */ - -#define DAC_LFSRUnmask_Bit0 ((uint32_t)0x00000000) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */ -#define DAC_LFSRUnmask_Bits1_0 ((uint32_t)0x00000100) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */ -#define DAC_LFSRUnmask_Bits2_0 ((uint32_t)0x00000200) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */ -#define DAC_LFSRUnmask_Bits3_0 ((uint32_t)0x00000300) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */ -#define DAC_LFSRUnmask_Bits4_0 ((uint32_t)0x00000400) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */ -#define DAC_LFSRUnmask_Bits5_0 ((uint32_t)0x00000500) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */ -#define DAC_LFSRUnmask_Bits6_0 ((uint32_t)0x00000600) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */ -#define DAC_LFSRUnmask_Bits7_0 ((uint32_t)0x00000700) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */ -#define DAC_LFSRUnmask_Bits8_0 ((uint32_t)0x00000800) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */ -#define DAC_LFSRUnmask_Bits9_0 ((uint32_t)0x00000900) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */ -#define DAC_LFSRUnmask_Bits10_0 ((uint32_t)0x00000A00) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */ -#define DAC_LFSRUnmask_Bits11_0 ((uint32_t)0x00000B00) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */ -#define DAC_TriangleAmplitude_1 ((uint32_t)0x00000000) /*!< Select max triangle amplitude of 1 */ -#define DAC_TriangleAmplitude_3 ((uint32_t)0x00000100) /*!< Select max triangle amplitude of 3 */ -#define DAC_TriangleAmplitude_7 ((uint32_t)0x00000200) /*!< Select max triangle amplitude of 7 */ -#define DAC_TriangleAmplitude_15 ((uint32_t)0x00000300) /*!< Select max triangle amplitude of 15 */ -#define DAC_TriangleAmplitude_31 ((uint32_t)0x00000400) /*!< Select max triangle amplitude of 31 */ -#define DAC_TriangleAmplitude_63 ((uint32_t)0x00000500) /*!< Select max triangle amplitude of 63 */ -#define DAC_TriangleAmplitude_127 ((uint32_t)0x00000600) /*!< Select max triangle amplitude of 127 */ -#define DAC_TriangleAmplitude_255 ((uint32_t)0x00000700) /*!< Select max triangle amplitude of 255 */ -#define DAC_TriangleAmplitude_511 ((uint32_t)0x00000800) /*!< Select max triangle amplitude of 511 */ -#define DAC_TriangleAmplitude_1023 ((uint32_t)0x00000900) /*!< Select max triangle amplitude of 1023 */ -#define DAC_TriangleAmplitude_2047 ((uint32_t)0x00000A00) /*!< Select max triangle amplitude of 2047 */ -#define DAC_TriangleAmplitude_4095 ((uint32_t)0x00000B00) /*!< Select max triangle amplitude of 4095 */ - -#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits1_0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits2_0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits3_0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits4_0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits5_0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits6_0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits7_0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits8_0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits9_0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits10_0) || \ - ((VALUE) == DAC_LFSRUnmask_Bits11_0) || \ - ((VALUE) == DAC_TriangleAmplitude_1) || \ - ((VALUE) == DAC_TriangleAmplitude_3) || \ - ((VALUE) == DAC_TriangleAmplitude_7) || \ - ((VALUE) == DAC_TriangleAmplitude_15) || \ - ((VALUE) == DAC_TriangleAmplitude_31) || \ - ((VALUE) == DAC_TriangleAmplitude_63) || \ - ((VALUE) == DAC_TriangleAmplitude_127) || \ - ((VALUE) == DAC_TriangleAmplitude_255) || \ - ((VALUE) == DAC_TriangleAmplitude_511) || \ - ((VALUE) == DAC_TriangleAmplitude_1023) || \ - ((VALUE) == DAC_TriangleAmplitude_2047) || \ - ((VALUE) == DAC_TriangleAmplitude_4095)) -/** - * @} - */ - -/** @defgroup DAC_output_buffer - * @{ - */ - -#define DAC_OutputBuffer_Enable ((uint32_t)0x00000000) -#define DAC_OutputBuffer_Disable ((uint32_t)0x00000002) -#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OutputBuffer_Enable) || \ - ((STATE) == DAC_OutputBuffer_Disable)) -/** - * @} - */ - -/** @defgroup DAC_Channel_selection - * @{ - */ - -#define DAC_Channel_1 ((uint32_t)0x00000000) -#define DAC_Channel_2 ((uint32_t)0x00000010) -#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \ - ((CHANNEL) == DAC_Channel_2)) -/** - * @} - */ - -/** @defgroup DAC_data_alignement - * @{ - */ - -#define DAC_Align_12b_R ((uint32_t)0x00000000) -#define DAC_Align_12b_L ((uint32_t)0x00000004) -#define DAC_Align_8b_R ((uint32_t)0x00000008) -#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \ - ((ALIGN) == DAC_Align_12b_L) || \ - ((ALIGN) == DAC_Align_8b_R)) -/** - * @} - */ - -/** @defgroup DAC_wave_generation - * @{ - */ - -#define DAC_Wave_Noise ((uint32_t)0x00000040) -#define DAC_Wave_Triangle ((uint32_t)0x00000080) -#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \ - ((WAVE) == DAC_Wave_Triangle)) -/** - * @} - */ - -/** @defgroup DAC_data - * @{ - */ - -#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0) -/** - * @} - */ -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) -/** @defgroup DAC_interrupts_definition - * @{ - */ - -#define DAC_IT_DMAUDR ((uint32_t)0x00002000) -#define IS_DAC_IT(IT) (((IT) == DAC_IT_DMAUDR)) - -/** - * @} - */ - -/** @defgroup DAC_flags_definition - * @{ - */ - -#define DAC_FLAG_DMAUDR ((uint32_t)0x00002000) -#define IS_DAC_FLAG(FLAG) (((FLAG) == DAC_FLAG_DMAUDR)) - -/** - * @} - */ -#endif - -/** - * @} - */ - -/** @defgroup DAC_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup DAC_Exported_Functions - * @{ - */ - -void DAC_DeInit(void); -void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct); -void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct); -void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState); -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) -void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState); -#endif -void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState); -void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState); -void DAC_DualSoftwareTriggerCmd(FunctionalState NewState); -void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState); -void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data); -void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data); -void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1); -uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel); -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) -FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG); -void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG); -ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT); -void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT); -#endif - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F10x_DAC_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_dac.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the DAC firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_DAC_H +#define __STM32F10x_DAC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DAC + * @{ + */ + +/** @defgroup DAC_Exported_Types + * @{ + */ + +/** + * @brief DAC Init structure definition + */ + +typedef struct +{ + uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel. + This parameter can be a value of @ref DAC_trigger_selection */ + + uint32_t DAC_WaveGeneration; /*!< Specifies whether DAC channel noise waves or triangle waves + are generated, or whether no wave is generated. + This parameter can be a value of @ref DAC_wave_generation */ + + uint32_t DAC_LFSRUnmask_TriangleAmplitude; /*!< Specifies the LFSR mask for noise wave generation or + the maximum amplitude triangle generation for the DAC channel. + This parameter can be a value of @ref DAC_lfsrunmask_triangleamplitude */ + + uint32_t DAC_OutputBuffer; /*!< Specifies whether the DAC channel output buffer is enabled or disabled. + This parameter can be a value of @ref DAC_output_buffer */ +}DAC_InitTypeDef; + +/** + * @} + */ + +/** @defgroup DAC_Exported_Constants + * @{ + */ + +/** @defgroup DAC_trigger_selection + * @{ + */ + +#define DAC_Trigger_None ((uint32_t)0x00000000) /*!< Conversion is automatic once the DAC1_DHRxxxx register + has been loaded, and not by external trigger */ +#define DAC_Trigger_T6_TRGO ((uint32_t)0x00000004) /*!< TIM6 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T8_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel + only in High-density devices*/ +#define DAC_Trigger_T3_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel + only in Connectivity line, Medium-density and Low-density Value Line devices */ +#define DAC_Trigger_T7_TRGO ((uint32_t)0x00000014) /*!< TIM7 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T5_TRGO ((uint32_t)0x0000001C) /*!< TIM5 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T15_TRGO ((uint32_t)0x0000001C) /*!< TIM15 TRGO selected as external conversion trigger for DAC channel + only in Medium-density and Low-density Value Line devices*/ +#define DAC_Trigger_T2_TRGO ((uint32_t)0x00000024) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T4_TRGO ((uint32_t)0x0000002C) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_Ext_IT9 ((uint32_t)0x00000034) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_Software ((uint32_t)0x0000003C) /*!< Conversion started by software trigger for DAC channel */ + +#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \ + ((TRIGGER) == DAC_Trigger_T6_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T8_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T7_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T5_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T2_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T4_TRGO) || \ + ((TRIGGER) == DAC_Trigger_Ext_IT9) || \ + ((TRIGGER) == DAC_Trigger_Software)) + +/** + * @} + */ + +/** @defgroup DAC_wave_generation + * @{ + */ + +#define DAC_WaveGeneration_None ((uint32_t)0x00000000) +#define DAC_WaveGeneration_Noise ((uint32_t)0x00000040) +#define DAC_WaveGeneration_Triangle ((uint32_t)0x00000080) +#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \ + ((WAVE) == DAC_WaveGeneration_Noise) || \ + ((WAVE) == DAC_WaveGeneration_Triangle)) +/** + * @} + */ + +/** @defgroup DAC_lfsrunmask_triangleamplitude + * @{ + */ + +#define DAC_LFSRUnmask_Bit0 ((uint32_t)0x00000000) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */ +#define DAC_LFSRUnmask_Bits1_0 ((uint32_t)0x00000100) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits2_0 ((uint32_t)0x00000200) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits3_0 ((uint32_t)0x00000300) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits4_0 ((uint32_t)0x00000400) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits5_0 ((uint32_t)0x00000500) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits6_0 ((uint32_t)0x00000600) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits7_0 ((uint32_t)0x00000700) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits8_0 ((uint32_t)0x00000800) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits9_0 ((uint32_t)0x00000900) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits10_0 ((uint32_t)0x00000A00) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits11_0 ((uint32_t)0x00000B00) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */ +#define DAC_TriangleAmplitude_1 ((uint32_t)0x00000000) /*!< Select max triangle amplitude of 1 */ +#define DAC_TriangleAmplitude_3 ((uint32_t)0x00000100) /*!< Select max triangle amplitude of 3 */ +#define DAC_TriangleAmplitude_7 ((uint32_t)0x00000200) /*!< Select max triangle amplitude of 7 */ +#define DAC_TriangleAmplitude_15 ((uint32_t)0x00000300) /*!< Select max triangle amplitude of 15 */ +#define DAC_TriangleAmplitude_31 ((uint32_t)0x00000400) /*!< Select max triangle amplitude of 31 */ +#define DAC_TriangleAmplitude_63 ((uint32_t)0x00000500) /*!< Select max triangle amplitude of 63 */ +#define DAC_TriangleAmplitude_127 ((uint32_t)0x00000600) /*!< Select max triangle amplitude of 127 */ +#define DAC_TriangleAmplitude_255 ((uint32_t)0x00000700) /*!< Select max triangle amplitude of 255 */ +#define DAC_TriangleAmplitude_511 ((uint32_t)0x00000800) /*!< Select max triangle amplitude of 511 */ +#define DAC_TriangleAmplitude_1023 ((uint32_t)0x00000900) /*!< Select max triangle amplitude of 1023 */ +#define DAC_TriangleAmplitude_2047 ((uint32_t)0x00000A00) /*!< Select max triangle amplitude of 2047 */ +#define DAC_TriangleAmplitude_4095 ((uint32_t)0x00000B00) /*!< Select max triangle amplitude of 4095 */ + +#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits1_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits2_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits3_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits4_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits5_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits6_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits7_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits8_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits9_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits10_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits11_0) || \ + ((VALUE) == DAC_TriangleAmplitude_1) || \ + ((VALUE) == DAC_TriangleAmplitude_3) || \ + ((VALUE) == DAC_TriangleAmplitude_7) || \ + ((VALUE) == DAC_TriangleAmplitude_15) || \ + ((VALUE) == DAC_TriangleAmplitude_31) || \ + ((VALUE) == DAC_TriangleAmplitude_63) || \ + ((VALUE) == DAC_TriangleAmplitude_127) || \ + ((VALUE) == DAC_TriangleAmplitude_255) || \ + ((VALUE) == DAC_TriangleAmplitude_511) || \ + ((VALUE) == DAC_TriangleAmplitude_1023) || \ + ((VALUE) == DAC_TriangleAmplitude_2047) || \ + ((VALUE) == DAC_TriangleAmplitude_4095)) +/** + * @} + */ + +/** @defgroup DAC_output_buffer + * @{ + */ + +#define DAC_OutputBuffer_Enable ((uint32_t)0x00000000) +#define DAC_OutputBuffer_Disable ((uint32_t)0x00000002) +#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OutputBuffer_Enable) || \ + ((STATE) == DAC_OutputBuffer_Disable)) +/** + * @} + */ + +/** @defgroup DAC_Channel_selection + * @{ + */ + +#define DAC_Channel_1 ((uint32_t)0x00000000) +#define DAC_Channel_2 ((uint32_t)0x00000010) +#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \ + ((CHANNEL) == DAC_Channel_2)) +/** + * @} + */ + +/** @defgroup DAC_data_alignement + * @{ + */ + +#define DAC_Align_12b_R ((uint32_t)0x00000000) +#define DAC_Align_12b_L ((uint32_t)0x00000004) +#define DAC_Align_8b_R ((uint32_t)0x00000008) +#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \ + ((ALIGN) == DAC_Align_12b_L) || \ + ((ALIGN) == DAC_Align_8b_R)) +/** + * @} + */ + +/** @defgroup DAC_wave_generation + * @{ + */ + +#define DAC_Wave_Noise ((uint32_t)0x00000040) +#define DAC_Wave_Triangle ((uint32_t)0x00000080) +#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \ + ((WAVE) == DAC_Wave_Triangle)) +/** + * @} + */ + +/** @defgroup DAC_data + * @{ + */ + +#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0) +/** + * @} + */ +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/** @defgroup DAC_interrupts_definition + * @{ + */ + +#define DAC_IT_DMAUDR ((uint32_t)0x00002000) +#define IS_DAC_IT(IT) (((IT) == DAC_IT_DMAUDR)) + +/** + * @} + */ + +/** @defgroup DAC_flags_definition + * @{ + */ + +#define DAC_FLAG_DMAUDR ((uint32_t)0x00002000) +#define IS_DAC_FLAG(FLAG) (((FLAG) == DAC_FLAG_DMAUDR)) + +/** + * @} + */ +#endif + +/** + * @} + */ + +/** @defgroup DAC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Exported_Functions + * @{ + */ + +void DAC_DeInit(void); +void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct); +void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct); +void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState); +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState); +#endif +void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState); +void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState); +void DAC_DualSoftwareTriggerCmd(FunctionalState NewState); +void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState); +void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data); +void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data); +void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1); +uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel); +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG); +void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG); +ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT); +void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT); +#endif + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_DAC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h index 918e25fa7..c55acd5bc 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h @@ -1,118 +1,118 @@ -/** - ****************************************************************************** - * @file stm32f10x_dbgmcu.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the DBGMCU - * firmware library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_DBGMCU_H -#define __STM32F10x_DBGMCU_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup DBGMCU - * @{ - */ - -/** @defgroup DBGMCU_Exported_Types - * @{ - */ - -/** - * @} - */ - -/** @defgroup DBGMCU_Exported_Constants - * @{ - */ - -#define DBGMCU_SLEEP ((uint32_t)0x00000001) -#define DBGMCU_STOP ((uint32_t)0x00000002) -#define DBGMCU_STANDBY ((uint32_t)0x00000004) -#define DBGMCU_IWDG_STOP ((uint32_t)0x00000100) -#define DBGMCU_WWDG_STOP ((uint32_t)0x00000200) -#define DBGMCU_TIM1_STOP ((uint32_t)0x00000400) -#define DBGMCU_TIM2_STOP ((uint32_t)0x00000800) -#define DBGMCU_TIM3_STOP ((uint32_t)0x00001000) -#define DBGMCU_TIM4_STOP ((uint32_t)0x00002000) -#define DBGMCU_CAN1_STOP ((uint32_t)0x00004000) -#define DBGMCU_I2C1_SMBUS_TIMEOUT ((uint32_t)0x00008000) -#define DBGMCU_I2C2_SMBUS_TIMEOUT ((uint32_t)0x00010000) -#define DBGMCU_TIM8_STOP ((uint32_t)0x00020000) -#define DBGMCU_TIM5_STOP ((uint32_t)0x00040000) -#define DBGMCU_TIM6_STOP ((uint32_t)0x00080000) -#define DBGMCU_TIM7_STOP ((uint32_t)0x00100000) -#define DBGMCU_CAN2_STOP ((uint32_t)0x00200000) -#define DBGMCU_TIM15_STOP ((uint32_t)0x00400000) -#define DBGMCU_TIM16_STOP ((uint32_t)0x00800000) -#define DBGMCU_TIM17_STOP ((uint32_t)0x01000000) -#define DBGMCU_TIM12_STOP ((uint32_t)0x02000000) -#define DBGMCU_TIM13_STOP ((uint32_t)0x04000000) -#define DBGMCU_TIM14_STOP ((uint32_t)0x08000000) -#define DBGMCU_TIM9_STOP ((uint32_t)0x10000000) -#define DBGMCU_TIM10_STOP ((uint32_t)0x20000000) -#define DBGMCU_TIM11_STOP ((uint32_t)0x40000000) - -#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0x800000F8) == 0x00) && ((PERIPH) != 0x00)) -/** - * @} - */ - -/** @defgroup DBGMCU_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup DBGMCU_Exported_Functions - * @{ - */ - -uint32_t DBGMCU_GetREVID(void); -uint32_t DBGMCU_GetDEVID(void); -void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_DBGMCU_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_dbgmcu.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the DBGMCU + * firmware library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_DBGMCU_H +#define __STM32F10x_DBGMCU_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DBGMCU + * @{ + */ + +/** @defgroup DBGMCU_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Exported_Constants + * @{ + */ + +#define DBGMCU_SLEEP ((uint32_t)0x00000001) +#define DBGMCU_STOP ((uint32_t)0x00000002) +#define DBGMCU_STANDBY ((uint32_t)0x00000004) +#define DBGMCU_IWDG_STOP ((uint32_t)0x00000100) +#define DBGMCU_WWDG_STOP ((uint32_t)0x00000200) +#define DBGMCU_TIM1_STOP ((uint32_t)0x00000400) +#define DBGMCU_TIM2_STOP ((uint32_t)0x00000800) +#define DBGMCU_TIM3_STOP ((uint32_t)0x00001000) +#define DBGMCU_TIM4_STOP ((uint32_t)0x00002000) +#define DBGMCU_CAN1_STOP ((uint32_t)0x00004000) +#define DBGMCU_I2C1_SMBUS_TIMEOUT ((uint32_t)0x00008000) +#define DBGMCU_I2C2_SMBUS_TIMEOUT ((uint32_t)0x00010000) +#define DBGMCU_TIM8_STOP ((uint32_t)0x00020000) +#define DBGMCU_TIM5_STOP ((uint32_t)0x00040000) +#define DBGMCU_TIM6_STOP ((uint32_t)0x00080000) +#define DBGMCU_TIM7_STOP ((uint32_t)0x00100000) +#define DBGMCU_CAN2_STOP ((uint32_t)0x00200000) +#define DBGMCU_TIM15_STOP ((uint32_t)0x00400000) +#define DBGMCU_TIM16_STOP ((uint32_t)0x00800000) +#define DBGMCU_TIM17_STOP ((uint32_t)0x01000000) +#define DBGMCU_TIM12_STOP ((uint32_t)0x02000000) +#define DBGMCU_TIM13_STOP ((uint32_t)0x04000000) +#define DBGMCU_TIM14_STOP ((uint32_t)0x08000000) +#define DBGMCU_TIM9_STOP ((uint32_t)0x10000000) +#define DBGMCU_TIM10_STOP ((uint32_t)0x20000000) +#define DBGMCU_TIM11_STOP ((uint32_t)0x40000000) + +#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0x800000F8) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup DBGMCU_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Exported_Functions + * @{ + */ + +uint32_t DBGMCU_GetREVID(void); +uint32_t DBGMCU_GetDEVID(void); +void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_DBGMCU_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h index 597f8b096..3653ef923 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h @@ -1,438 +1,438 @@ -/** - ****************************************************************************** - * @file stm32f10x_dma.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the DMA firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_DMA_H -#define __STM32F10x_DMA_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup DMA - * @{ - */ - -/** @defgroup DMA_Exported_Types - * @{ - */ - -/** - * @brief DMA Init structure definition - */ - -typedef struct -{ - uint32_t DMA_PeripheralBaseAddr; /*!< Specifies the peripheral base address for DMAy Channelx. */ - - uint32_t DMA_MemoryBaseAddr; /*!< Specifies the memory base address for DMAy Channelx. */ - - uint32_t DMA_DIR; /*!< Specifies if the peripheral is the source or destination. - This parameter can be a value of @ref DMA_data_transfer_direction */ - - uint32_t DMA_BufferSize; /*!< Specifies the buffer size, in data unit, of the specified Channel. - The data unit is equal to the configuration set in DMA_PeripheralDataSize - or DMA_MemoryDataSize members depending in the transfer direction. */ - - uint32_t DMA_PeripheralInc; /*!< Specifies whether the Peripheral address register is incremented or not. - This parameter can be a value of @ref DMA_peripheral_incremented_mode */ - - uint32_t DMA_MemoryInc; /*!< Specifies whether the memory address register is incremented or not. - This parameter can be a value of @ref DMA_memory_incremented_mode */ - - uint32_t DMA_PeripheralDataSize; /*!< Specifies the Peripheral data width. - This parameter can be a value of @ref DMA_peripheral_data_size */ - - uint32_t DMA_MemoryDataSize; /*!< Specifies the Memory data width. - This parameter can be a value of @ref DMA_memory_data_size */ - - uint32_t DMA_Mode; /*!< Specifies the operation mode of the DMAy Channelx. - This parameter can be a value of @ref DMA_circular_normal_mode. - @note: The circular buffer mode cannot be used if the memory-to-memory - data transfer is configured on the selected Channel */ - - uint32_t DMA_Priority; /*!< Specifies the software priority for the DMAy Channelx. - This parameter can be a value of @ref DMA_priority_level */ - - uint32_t DMA_M2M; /*!< Specifies if the DMAy Channelx will be used in memory-to-memory transfer. - This parameter can be a value of @ref DMA_memory_to_memory */ -}DMA_InitTypeDef; - -/** - * @} - */ - -/** @defgroup DMA_Exported_Constants - * @{ - */ - -#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Channel1) || \ - ((PERIPH) == DMA1_Channel2) || \ - ((PERIPH) == DMA1_Channel3) || \ - ((PERIPH) == DMA1_Channel4) || \ - ((PERIPH) == DMA1_Channel5) || \ - ((PERIPH) == DMA1_Channel6) || \ - ((PERIPH) == DMA1_Channel7) || \ - ((PERIPH) == DMA2_Channel1) || \ - ((PERIPH) == DMA2_Channel2) || \ - ((PERIPH) == DMA2_Channel3) || \ - ((PERIPH) == DMA2_Channel4) || \ - ((PERIPH) == DMA2_Channel5)) - -/** @defgroup DMA_data_transfer_direction - * @{ - */ - -#define DMA_DIR_PeripheralDST ((uint32_t)0x00000010) -#define DMA_DIR_PeripheralSRC ((uint32_t)0x00000000) -#define IS_DMA_DIR(DIR) (((DIR) == DMA_DIR_PeripheralDST) || \ - ((DIR) == DMA_DIR_PeripheralSRC)) -/** - * @} - */ - -/** @defgroup DMA_peripheral_incremented_mode - * @{ - */ - -#define DMA_PeripheralInc_Enable ((uint32_t)0x00000040) -#define DMA_PeripheralInc_Disable ((uint32_t)0x00000000) -#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \ - ((STATE) == DMA_PeripheralInc_Disable)) -/** - * @} - */ - -/** @defgroup DMA_memory_incremented_mode - * @{ - */ - -#define DMA_MemoryInc_Enable ((uint32_t)0x00000080) -#define DMA_MemoryInc_Disable ((uint32_t)0x00000000) -#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \ - ((STATE) == DMA_MemoryInc_Disable)) -/** - * @} - */ - -/** @defgroup DMA_peripheral_data_size - * @{ - */ - -#define DMA_PeripheralDataSize_Byte ((uint32_t)0x00000000) -#define DMA_PeripheralDataSize_HalfWord ((uint32_t)0x00000100) -#define DMA_PeripheralDataSize_Word ((uint32_t)0x00000200) -#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \ - ((SIZE) == DMA_PeripheralDataSize_HalfWord) || \ - ((SIZE) == DMA_PeripheralDataSize_Word)) -/** - * @} - */ - -/** @defgroup DMA_memory_data_size - * @{ - */ - -#define DMA_MemoryDataSize_Byte ((uint32_t)0x00000000) -#define DMA_MemoryDataSize_HalfWord ((uint32_t)0x00000400) -#define DMA_MemoryDataSize_Word ((uint32_t)0x00000800) -#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \ - ((SIZE) == DMA_MemoryDataSize_HalfWord) || \ - ((SIZE) == DMA_MemoryDataSize_Word)) -/** - * @} - */ - -/** @defgroup DMA_circular_normal_mode - * @{ - */ - -#define DMA_Mode_Circular ((uint32_t)0x00000020) -#define DMA_Mode_Normal ((uint32_t)0x00000000) -#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Circular) || ((MODE) == DMA_Mode_Normal)) -/** - * @} - */ - -/** @defgroup DMA_priority_level - * @{ - */ - -#define DMA_Priority_VeryHigh ((uint32_t)0x00003000) -#define DMA_Priority_High ((uint32_t)0x00002000) -#define DMA_Priority_Medium ((uint32_t)0x00001000) -#define DMA_Priority_Low ((uint32_t)0x00000000) -#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_VeryHigh) || \ - ((PRIORITY) == DMA_Priority_High) || \ - ((PRIORITY) == DMA_Priority_Medium) || \ - ((PRIORITY) == DMA_Priority_Low)) -/** - * @} - */ - -/** @defgroup DMA_memory_to_memory - * @{ - */ - -#define DMA_M2M_Enable ((uint32_t)0x00004000) -#define DMA_M2M_Disable ((uint32_t)0x00000000) -#define IS_DMA_M2M_STATE(STATE) (((STATE) == DMA_M2M_Enable) || ((STATE) == DMA_M2M_Disable)) - -/** - * @} - */ - -/** @defgroup DMA_interrupts_definition - * @{ - */ - -#define DMA_IT_TC ((uint32_t)0x00000002) -#define DMA_IT_HT ((uint32_t)0x00000004) -#define DMA_IT_TE ((uint32_t)0x00000008) -#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00)) - -#define DMA1_IT_GL1 ((uint32_t)0x00000001) -#define DMA1_IT_TC1 ((uint32_t)0x00000002) -#define DMA1_IT_HT1 ((uint32_t)0x00000004) -#define DMA1_IT_TE1 ((uint32_t)0x00000008) -#define DMA1_IT_GL2 ((uint32_t)0x00000010) -#define DMA1_IT_TC2 ((uint32_t)0x00000020) -#define DMA1_IT_HT2 ((uint32_t)0x00000040) -#define DMA1_IT_TE2 ((uint32_t)0x00000080) -#define DMA1_IT_GL3 ((uint32_t)0x00000100) -#define DMA1_IT_TC3 ((uint32_t)0x00000200) -#define DMA1_IT_HT3 ((uint32_t)0x00000400) -#define DMA1_IT_TE3 ((uint32_t)0x00000800) -#define DMA1_IT_GL4 ((uint32_t)0x00001000) -#define DMA1_IT_TC4 ((uint32_t)0x00002000) -#define DMA1_IT_HT4 ((uint32_t)0x00004000) -#define DMA1_IT_TE4 ((uint32_t)0x00008000) -#define DMA1_IT_GL5 ((uint32_t)0x00010000) -#define DMA1_IT_TC5 ((uint32_t)0x00020000) -#define DMA1_IT_HT5 ((uint32_t)0x00040000) -#define DMA1_IT_TE5 ((uint32_t)0x00080000) -#define DMA1_IT_GL6 ((uint32_t)0x00100000) -#define DMA1_IT_TC6 ((uint32_t)0x00200000) -#define DMA1_IT_HT6 ((uint32_t)0x00400000) -#define DMA1_IT_TE6 ((uint32_t)0x00800000) -#define DMA1_IT_GL7 ((uint32_t)0x01000000) -#define DMA1_IT_TC7 ((uint32_t)0x02000000) -#define DMA1_IT_HT7 ((uint32_t)0x04000000) -#define DMA1_IT_TE7 ((uint32_t)0x08000000) - -#define DMA2_IT_GL1 ((uint32_t)0x10000001) -#define DMA2_IT_TC1 ((uint32_t)0x10000002) -#define DMA2_IT_HT1 ((uint32_t)0x10000004) -#define DMA2_IT_TE1 ((uint32_t)0x10000008) -#define DMA2_IT_GL2 ((uint32_t)0x10000010) -#define DMA2_IT_TC2 ((uint32_t)0x10000020) -#define DMA2_IT_HT2 ((uint32_t)0x10000040) -#define DMA2_IT_TE2 ((uint32_t)0x10000080) -#define DMA2_IT_GL3 ((uint32_t)0x10000100) -#define DMA2_IT_TC3 ((uint32_t)0x10000200) -#define DMA2_IT_HT3 ((uint32_t)0x10000400) -#define DMA2_IT_TE3 ((uint32_t)0x10000800) -#define DMA2_IT_GL4 ((uint32_t)0x10001000) -#define DMA2_IT_TC4 ((uint32_t)0x10002000) -#define DMA2_IT_HT4 ((uint32_t)0x10004000) -#define DMA2_IT_TE4 ((uint32_t)0x10008000) -#define DMA2_IT_GL5 ((uint32_t)0x10010000) -#define DMA2_IT_TC5 ((uint32_t)0x10020000) -#define DMA2_IT_HT5 ((uint32_t)0x10040000) -#define DMA2_IT_TE5 ((uint32_t)0x10080000) - -#define IS_DMA_CLEAR_IT(IT) (((((IT) & 0xF0000000) == 0x00) || (((IT) & 0xEFF00000) == 0x00)) && ((IT) != 0x00)) - -#define IS_DMA_GET_IT(IT) (((IT) == DMA1_IT_GL1) || ((IT) == DMA1_IT_TC1) || \ - ((IT) == DMA1_IT_HT1) || ((IT) == DMA1_IT_TE1) || \ - ((IT) == DMA1_IT_GL2) || ((IT) == DMA1_IT_TC2) || \ - ((IT) == DMA1_IT_HT2) || ((IT) == DMA1_IT_TE2) || \ - ((IT) == DMA1_IT_GL3) || ((IT) == DMA1_IT_TC3) || \ - ((IT) == DMA1_IT_HT3) || ((IT) == DMA1_IT_TE3) || \ - ((IT) == DMA1_IT_GL4) || ((IT) == DMA1_IT_TC4) || \ - ((IT) == DMA1_IT_HT4) || ((IT) == DMA1_IT_TE4) || \ - ((IT) == DMA1_IT_GL5) || ((IT) == DMA1_IT_TC5) || \ - ((IT) == DMA1_IT_HT5) || ((IT) == DMA1_IT_TE5) || \ - ((IT) == DMA1_IT_GL6) || ((IT) == DMA1_IT_TC6) || \ - ((IT) == DMA1_IT_HT6) || ((IT) == DMA1_IT_TE6) || \ - ((IT) == DMA1_IT_GL7) || ((IT) == DMA1_IT_TC7) || \ - ((IT) == DMA1_IT_HT7) || ((IT) == DMA1_IT_TE7) || \ - ((IT) == DMA2_IT_GL1) || ((IT) == DMA2_IT_TC1) || \ - ((IT) == DMA2_IT_HT1) || ((IT) == DMA2_IT_TE1) || \ - ((IT) == DMA2_IT_GL2) || ((IT) == DMA2_IT_TC2) || \ - ((IT) == DMA2_IT_HT2) || ((IT) == DMA2_IT_TE2) || \ - ((IT) == DMA2_IT_GL3) || ((IT) == DMA2_IT_TC3) || \ - ((IT) == DMA2_IT_HT3) || ((IT) == DMA2_IT_TE3) || \ - ((IT) == DMA2_IT_GL4) || ((IT) == DMA2_IT_TC4) || \ - ((IT) == DMA2_IT_HT4) || ((IT) == DMA2_IT_TE4) || \ - ((IT) == DMA2_IT_GL5) || ((IT) == DMA2_IT_TC5) || \ - ((IT) == DMA2_IT_HT5) || ((IT) == DMA2_IT_TE5)) - -/** - * @} - */ - -/** @defgroup DMA_flags_definition - * @{ - */ -#define DMA1_FLAG_GL1 ((uint32_t)0x00000001) -#define DMA1_FLAG_TC1 ((uint32_t)0x00000002) -#define DMA1_FLAG_HT1 ((uint32_t)0x00000004) -#define DMA1_FLAG_TE1 ((uint32_t)0x00000008) -#define DMA1_FLAG_GL2 ((uint32_t)0x00000010) -#define DMA1_FLAG_TC2 ((uint32_t)0x00000020) -#define DMA1_FLAG_HT2 ((uint32_t)0x00000040) -#define DMA1_FLAG_TE2 ((uint32_t)0x00000080) -#define DMA1_FLAG_GL3 ((uint32_t)0x00000100) -#define DMA1_FLAG_TC3 ((uint32_t)0x00000200) -#define DMA1_FLAG_HT3 ((uint32_t)0x00000400) -#define DMA1_FLAG_TE3 ((uint32_t)0x00000800) -#define DMA1_FLAG_GL4 ((uint32_t)0x00001000) -#define DMA1_FLAG_TC4 ((uint32_t)0x00002000) -#define DMA1_FLAG_HT4 ((uint32_t)0x00004000) -#define DMA1_FLAG_TE4 ((uint32_t)0x00008000) -#define DMA1_FLAG_GL5 ((uint32_t)0x00010000) -#define DMA1_FLAG_TC5 ((uint32_t)0x00020000) -#define DMA1_FLAG_HT5 ((uint32_t)0x00040000) -#define DMA1_FLAG_TE5 ((uint32_t)0x00080000) -#define DMA1_FLAG_GL6 ((uint32_t)0x00100000) -#define DMA1_FLAG_TC6 ((uint32_t)0x00200000) -#define DMA1_FLAG_HT6 ((uint32_t)0x00400000) -#define DMA1_FLAG_TE6 ((uint32_t)0x00800000) -#define DMA1_FLAG_GL7 ((uint32_t)0x01000000) -#define DMA1_FLAG_TC7 ((uint32_t)0x02000000) -#define DMA1_FLAG_HT7 ((uint32_t)0x04000000) -#define DMA1_FLAG_TE7 ((uint32_t)0x08000000) - -#define DMA2_FLAG_GL1 ((uint32_t)0x10000001) -#define DMA2_FLAG_TC1 ((uint32_t)0x10000002) -#define DMA2_FLAG_HT1 ((uint32_t)0x10000004) -#define DMA2_FLAG_TE1 ((uint32_t)0x10000008) -#define DMA2_FLAG_GL2 ((uint32_t)0x10000010) -#define DMA2_FLAG_TC2 ((uint32_t)0x10000020) -#define DMA2_FLAG_HT2 ((uint32_t)0x10000040) -#define DMA2_FLAG_TE2 ((uint32_t)0x10000080) -#define DMA2_FLAG_GL3 ((uint32_t)0x10000100) -#define DMA2_FLAG_TC3 ((uint32_t)0x10000200) -#define DMA2_FLAG_HT3 ((uint32_t)0x10000400) -#define DMA2_FLAG_TE3 ((uint32_t)0x10000800) -#define DMA2_FLAG_GL4 ((uint32_t)0x10001000) -#define DMA2_FLAG_TC4 ((uint32_t)0x10002000) -#define DMA2_FLAG_HT4 ((uint32_t)0x10004000) -#define DMA2_FLAG_TE4 ((uint32_t)0x10008000) -#define DMA2_FLAG_GL5 ((uint32_t)0x10010000) -#define DMA2_FLAG_TC5 ((uint32_t)0x10020000) -#define DMA2_FLAG_HT5 ((uint32_t)0x10040000) -#define DMA2_FLAG_TE5 ((uint32_t)0x10080000) - -#define IS_DMA_CLEAR_FLAG(FLAG) (((((FLAG) & 0xF0000000) == 0x00) || (((FLAG) & 0xEFF00000) == 0x00)) && ((FLAG) != 0x00)) - -#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA1_FLAG_GL1) || ((FLAG) == DMA1_FLAG_TC1) || \ - ((FLAG) == DMA1_FLAG_HT1) || ((FLAG) == DMA1_FLAG_TE1) || \ - ((FLAG) == DMA1_FLAG_GL2) || ((FLAG) == DMA1_FLAG_TC2) || \ - ((FLAG) == DMA1_FLAG_HT2) || ((FLAG) == DMA1_FLAG_TE2) || \ - ((FLAG) == DMA1_FLAG_GL3) || ((FLAG) == DMA1_FLAG_TC3) || \ - ((FLAG) == DMA1_FLAG_HT3) || ((FLAG) == DMA1_FLAG_TE3) || \ - ((FLAG) == DMA1_FLAG_GL4) || ((FLAG) == DMA1_FLAG_TC4) || \ - ((FLAG) == DMA1_FLAG_HT4) || ((FLAG) == DMA1_FLAG_TE4) || \ - ((FLAG) == DMA1_FLAG_GL5) || ((FLAG) == DMA1_FLAG_TC5) || \ - ((FLAG) == DMA1_FLAG_HT5) || ((FLAG) == DMA1_FLAG_TE5) || \ - ((FLAG) == DMA1_FLAG_GL6) || ((FLAG) == DMA1_FLAG_TC6) || \ - ((FLAG) == DMA1_FLAG_HT6) || ((FLAG) == DMA1_FLAG_TE6) || \ - ((FLAG) == DMA1_FLAG_GL7) || ((FLAG) == DMA1_FLAG_TC7) || \ - ((FLAG) == DMA1_FLAG_HT7) || ((FLAG) == DMA1_FLAG_TE7) || \ - ((FLAG) == DMA2_FLAG_GL1) || ((FLAG) == DMA2_FLAG_TC1) || \ - ((FLAG) == DMA2_FLAG_HT1) || ((FLAG) == DMA2_FLAG_TE1) || \ - ((FLAG) == DMA2_FLAG_GL2) || ((FLAG) == DMA2_FLAG_TC2) || \ - ((FLAG) == DMA2_FLAG_HT2) || ((FLAG) == DMA2_FLAG_TE2) || \ - ((FLAG) == DMA2_FLAG_GL3) || ((FLAG) == DMA2_FLAG_TC3) || \ - ((FLAG) == DMA2_FLAG_HT3) || ((FLAG) == DMA2_FLAG_TE3) || \ - ((FLAG) == DMA2_FLAG_GL4) || ((FLAG) == DMA2_FLAG_TC4) || \ - ((FLAG) == DMA2_FLAG_HT4) || ((FLAG) == DMA2_FLAG_TE4) || \ - ((FLAG) == DMA2_FLAG_GL5) || ((FLAG) == DMA2_FLAG_TC5) || \ - ((FLAG) == DMA2_FLAG_HT5) || ((FLAG) == DMA2_FLAG_TE5)) -/** - * @} - */ - -/** @defgroup DMA_Buffer_Size - * @{ - */ - -#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000)) - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup DMA_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup DMA_Exported_Functions - * @{ - */ - -void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx); -void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, const DMA_InitTypeDef* DMA_InitStruct); -void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct); -void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState); -void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState); -void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber); -uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx); -FlagStatus DMA_GetFlagStatus(uint32_t DMA_FLAG); -void DMA_ClearFlag(uint32_t DMA_FLAG); -ITStatus DMA_GetITStatus(uint32_t DMA_IT); -void DMA_ClearITPendingBit(uint32_t DMA_IT); - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F10x_DMA_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_dma.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the DMA firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_DMA_H +#define __STM32F10x_DMA_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DMA + * @{ + */ + +/** @defgroup DMA_Exported_Types + * @{ + */ + +/** + * @brief DMA Init structure definition + */ + +typedef struct +{ + uint32_t DMA_PeripheralBaseAddr; /*!< Specifies the peripheral base address for DMAy Channelx. */ + + uint32_t DMA_MemoryBaseAddr; /*!< Specifies the memory base address for DMAy Channelx. */ + + uint32_t DMA_DIR; /*!< Specifies if the peripheral is the source or destination. + This parameter can be a value of @ref DMA_data_transfer_direction */ + + uint32_t DMA_BufferSize; /*!< Specifies the buffer size, in data unit, of the specified Channel. + The data unit is equal to the configuration set in DMA_PeripheralDataSize + or DMA_MemoryDataSize members depending in the transfer direction. */ + + uint32_t DMA_PeripheralInc; /*!< Specifies whether the Peripheral address register is incremented or not. + This parameter can be a value of @ref DMA_peripheral_incremented_mode */ + + uint32_t DMA_MemoryInc; /*!< Specifies whether the memory address register is incremented or not. + This parameter can be a value of @ref DMA_memory_incremented_mode */ + + uint32_t DMA_PeripheralDataSize; /*!< Specifies the Peripheral data width. + This parameter can be a value of @ref DMA_peripheral_data_size */ + + uint32_t DMA_MemoryDataSize; /*!< Specifies the Memory data width. + This parameter can be a value of @ref DMA_memory_data_size */ + + uint32_t DMA_Mode; /*!< Specifies the operation mode of the DMAy Channelx. + This parameter can be a value of @ref DMA_circular_normal_mode. + @note: The circular buffer mode cannot be used if the memory-to-memory + data transfer is configured on the selected Channel */ + + uint32_t DMA_Priority; /*!< Specifies the software priority for the DMAy Channelx. + This parameter can be a value of @ref DMA_priority_level */ + + uint32_t DMA_M2M; /*!< Specifies if the DMAy Channelx will be used in memory-to-memory transfer. + This parameter can be a value of @ref DMA_memory_to_memory */ +}DMA_InitTypeDef; + +/** + * @} + */ + +/** @defgroup DMA_Exported_Constants + * @{ + */ + +#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Channel1) || \ + ((PERIPH) == DMA1_Channel2) || \ + ((PERIPH) == DMA1_Channel3) || \ + ((PERIPH) == DMA1_Channel4) || \ + ((PERIPH) == DMA1_Channel5) || \ + ((PERIPH) == DMA1_Channel6) || \ + ((PERIPH) == DMA1_Channel7) || \ + ((PERIPH) == DMA2_Channel1) || \ + ((PERIPH) == DMA2_Channel2) || \ + ((PERIPH) == DMA2_Channel3) || \ + ((PERIPH) == DMA2_Channel4) || \ + ((PERIPH) == DMA2_Channel5)) + +/** @defgroup DMA_data_transfer_direction + * @{ + */ + +#define DMA_DIR_PeripheralDST ((uint32_t)0x00000010) +#define DMA_DIR_PeripheralSRC ((uint32_t)0x00000000) +#define IS_DMA_DIR(DIR) (((DIR) == DMA_DIR_PeripheralDST) || \ + ((DIR) == DMA_DIR_PeripheralSRC)) +/** + * @} + */ + +/** @defgroup DMA_peripheral_incremented_mode + * @{ + */ + +#define DMA_PeripheralInc_Enable ((uint32_t)0x00000040) +#define DMA_PeripheralInc_Disable ((uint32_t)0x00000000) +#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \ + ((STATE) == DMA_PeripheralInc_Disable)) +/** + * @} + */ + +/** @defgroup DMA_memory_incremented_mode + * @{ + */ + +#define DMA_MemoryInc_Enable ((uint32_t)0x00000080) +#define DMA_MemoryInc_Disable ((uint32_t)0x00000000) +#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \ + ((STATE) == DMA_MemoryInc_Disable)) +/** + * @} + */ + +/** @defgroup DMA_peripheral_data_size + * @{ + */ + +#define DMA_PeripheralDataSize_Byte ((uint32_t)0x00000000) +#define DMA_PeripheralDataSize_HalfWord ((uint32_t)0x00000100) +#define DMA_PeripheralDataSize_Word ((uint32_t)0x00000200) +#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \ + ((SIZE) == DMA_PeripheralDataSize_HalfWord) || \ + ((SIZE) == DMA_PeripheralDataSize_Word)) +/** + * @} + */ + +/** @defgroup DMA_memory_data_size + * @{ + */ + +#define DMA_MemoryDataSize_Byte ((uint32_t)0x00000000) +#define DMA_MemoryDataSize_HalfWord ((uint32_t)0x00000400) +#define DMA_MemoryDataSize_Word ((uint32_t)0x00000800) +#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \ + ((SIZE) == DMA_MemoryDataSize_HalfWord) || \ + ((SIZE) == DMA_MemoryDataSize_Word)) +/** + * @} + */ + +/** @defgroup DMA_circular_normal_mode + * @{ + */ + +#define DMA_Mode_Circular ((uint32_t)0x00000020) +#define DMA_Mode_Normal ((uint32_t)0x00000000) +#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Circular) || ((MODE) == DMA_Mode_Normal)) +/** + * @} + */ + +/** @defgroup DMA_priority_level + * @{ + */ + +#define DMA_Priority_VeryHigh ((uint32_t)0x00003000) +#define DMA_Priority_High ((uint32_t)0x00002000) +#define DMA_Priority_Medium ((uint32_t)0x00001000) +#define DMA_Priority_Low ((uint32_t)0x00000000) +#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_VeryHigh) || \ + ((PRIORITY) == DMA_Priority_High) || \ + ((PRIORITY) == DMA_Priority_Medium) || \ + ((PRIORITY) == DMA_Priority_Low)) +/** + * @} + */ + +/** @defgroup DMA_memory_to_memory + * @{ + */ + +#define DMA_M2M_Enable ((uint32_t)0x00004000) +#define DMA_M2M_Disable ((uint32_t)0x00000000) +#define IS_DMA_M2M_STATE(STATE) (((STATE) == DMA_M2M_Enable) || ((STATE) == DMA_M2M_Disable)) + +/** + * @} + */ + +/** @defgroup DMA_interrupts_definition + * @{ + */ + +#define DMA_IT_TC ((uint32_t)0x00000002) +#define DMA_IT_HT ((uint32_t)0x00000004) +#define DMA_IT_TE ((uint32_t)0x00000008) +#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00)) + +#define DMA1_IT_GL1 ((uint32_t)0x00000001) +#define DMA1_IT_TC1 ((uint32_t)0x00000002) +#define DMA1_IT_HT1 ((uint32_t)0x00000004) +#define DMA1_IT_TE1 ((uint32_t)0x00000008) +#define DMA1_IT_GL2 ((uint32_t)0x00000010) +#define DMA1_IT_TC2 ((uint32_t)0x00000020) +#define DMA1_IT_HT2 ((uint32_t)0x00000040) +#define DMA1_IT_TE2 ((uint32_t)0x00000080) +#define DMA1_IT_GL3 ((uint32_t)0x00000100) +#define DMA1_IT_TC3 ((uint32_t)0x00000200) +#define DMA1_IT_HT3 ((uint32_t)0x00000400) +#define DMA1_IT_TE3 ((uint32_t)0x00000800) +#define DMA1_IT_GL4 ((uint32_t)0x00001000) +#define DMA1_IT_TC4 ((uint32_t)0x00002000) +#define DMA1_IT_HT4 ((uint32_t)0x00004000) +#define DMA1_IT_TE4 ((uint32_t)0x00008000) +#define DMA1_IT_GL5 ((uint32_t)0x00010000) +#define DMA1_IT_TC5 ((uint32_t)0x00020000) +#define DMA1_IT_HT5 ((uint32_t)0x00040000) +#define DMA1_IT_TE5 ((uint32_t)0x00080000) +#define DMA1_IT_GL6 ((uint32_t)0x00100000) +#define DMA1_IT_TC6 ((uint32_t)0x00200000) +#define DMA1_IT_HT6 ((uint32_t)0x00400000) +#define DMA1_IT_TE6 ((uint32_t)0x00800000) +#define DMA1_IT_GL7 ((uint32_t)0x01000000) +#define DMA1_IT_TC7 ((uint32_t)0x02000000) +#define DMA1_IT_HT7 ((uint32_t)0x04000000) +#define DMA1_IT_TE7 ((uint32_t)0x08000000) + +#define DMA2_IT_GL1 ((uint32_t)0x10000001) +#define DMA2_IT_TC1 ((uint32_t)0x10000002) +#define DMA2_IT_HT1 ((uint32_t)0x10000004) +#define DMA2_IT_TE1 ((uint32_t)0x10000008) +#define DMA2_IT_GL2 ((uint32_t)0x10000010) +#define DMA2_IT_TC2 ((uint32_t)0x10000020) +#define DMA2_IT_HT2 ((uint32_t)0x10000040) +#define DMA2_IT_TE2 ((uint32_t)0x10000080) +#define DMA2_IT_GL3 ((uint32_t)0x10000100) +#define DMA2_IT_TC3 ((uint32_t)0x10000200) +#define DMA2_IT_HT3 ((uint32_t)0x10000400) +#define DMA2_IT_TE3 ((uint32_t)0x10000800) +#define DMA2_IT_GL4 ((uint32_t)0x10001000) +#define DMA2_IT_TC4 ((uint32_t)0x10002000) +#define DMA2_IT_HT4 ((uint32_t)0x10004000) +#define DMA2_IT_TE4 ((uint32_t)0x10008000) +#define DMA2_IT_GL5 ((uint32_t)0x10010000) +#define DMA2_IT_TC5 ((uint32_t)0x10020000) +#define DMA2_IT_HT5 ((uint32_t)0x10040000) +#define DMA2_IT_TE5 ((uint32_t)0x10080000) + +#define IS_DMA_CLEAR_IT(IT) (((((IT) & 0xF0000000) == 0x00) || (((IT) & 0xEFF00000) == 0x00)) && ((IT) != 0x00)) + +#define IS_DMA_GET_IT(IT) (((IT) == DMA1_IT_GL1) || ((IT) == DMA1_IT_TC1) || \ + ((IT) == DMA1_IT_HT1) || ((IT) == DMA1_IT_TE1) || \ + ((IT) == DMA1_IT_GL2) || ((IT) == DMA1_IT_TC2) || \ + ((IT) == DMA1_IT_HT2) || ((IT) == DMA1_IT_TE2) || \ + ((IT) == DMA1_IT_GL3) || ((IT) == DMA1_IT_TC3) || \ + ((IT) == DMA1_IT_HT3) || ((IT) == DMA1_IT_TE3) || \ + ((IT) == DMA1_IT_GL4) || ((IT) == DMA1_IT_TC4) || \ + ((IT) == DMA1_IT_HT4) || ((IT) == DMA1_IT_TE4) || \ + ((IT) == DMA1_IT_GL5) || ((IT) == DMA1_IT_TC5) || \ + ((IT) == DMA1_IT_HT5) || ((IT) == DMA1_IT_TE5) || \ + ((IT) == DMA1_IT_GL6) || ((IT) == DMA1_IT_TC6) || \ + ((IT) == DMA1_IT_HT6) || ((IT) == DMA1_IT_TE6) || \ + ((IT) == DMA1_IT_GL7) || ((IT) == DMA1_IT_TC7) || \ + ((IT) == DMA1_IT_HT7) || ((IT) == DMA1_IT_TE7) || \ + ((IT) == DMA2_IT_GL1) || ((IT) == DMA2_IT_TC1) || \ + ((IT) == DMA2_IT_HT1) || ((IT) == DMA2_IT_TE1) || \ + ((IT) == DMA2_IT_GL2) || ((IT) == DMA2_IT_TC2) || \ + ((IT) == DMA2_IT_HT2) || ((IT) == DMA2_IT_TE2) || \ + ((IT) == DMA2_IT_GL3) || ((IT) == DMA2_IT_TC3) || \ + ((IT) == DMA2_IT_HT3) || ((IT) == DMA2_IT_TE3) || \ + ((IT) == DMA2_IT_GL4) || ((IT) == DMA2_IT_TC4) || \ + ((IT) == DMA2_IT_HT4) || ((IT) == DMA2_IT_TE4) || \ + ((IT) == DMA2_IT_GL5) || ((IT) == DMA2_IT_TC5) || \ + ((IT) == DMA2_IT_HT5) || ((IT) == DMA2_IT_TE5)) + +/** + * @} + */ + +/** @defgroup DMA_flags_definition + * @{ + */ +#define DMA1_FLAG_GL1 ((uint32_t)0x00000001) +#define DMA1_FLAG_TC1 ((uint32_t)0x00000002) +#define DMA1_FLAG_HT1 ((uint32_t)0x00000004) +#define DMA1_FLAG_TE1 ((uint32_t)0x00000008) +#define DMA1_FLAG_GL2 ((uint32_t)0x00000010) +#define DMA1_FLAG_TC2 ((uint32_t)0x00000020) +#define DMA1_FLAG_HT2 ((uint32_t)0x00000040) +#define DMA1_FLAG_TE2 ((uint32_t)0x00000080) +#define DMA1_FLAG_GL3 ((uint32_t)0x00000100) +#define DMA1_FLAG_TC3 ((uint32_t)0x00000200) +#define DMA1_FLAG_HT3 ((uint32_t)0x00000400) +#define DMA1_FLAG_TE3 ((uint32_t)0x00000800) +#define DMA1_FLAG_GL4 ((uint32_t)0x00001000) +#define DMA1_FLAG_TC4 ((uint32_t)0x00002000) +#define DMA1_FLAG_HT4 ((uint32_t)0x00004000) +#define DMA1_FLAG_TE4 ((uint32_t)0x00008000) +#define DMA1_FLAG_GL5 ((uint32_t)0x00010000) +#define DMA1_FLAG_TC5 ((uint32_t)0x00020000) +#define DMA1_FLAG_HT5 ((uint32_t)0x00040000) +#define DMA1_FLAG_TE5 ((uint32_t)0x00080000) +#define DMA1_FLAG_GL6 ((uint32_t)0x00100000) +#define DMA1_FLAG_TC6 ((uint32_t)0x00200000) +#define DMA1_FLAG_HT6 ((uint32_t)0x00400000) +#define DMA1_FLAG_TE6 ((uint32_t)0x00800000) +#define DMA1_FLAG_GL7 ((uint32_t)0x01000000) +#define DMA1_FLAG_TC7 ((uint32_t)0x02000000) +#define DMA1_FLAG_HT7 ((uint32_t)0x04000000) +#define DMA1_FLAG_TE7 ((uint32_t)0x08000000) + +#define DMA2_FLAG_GL1 ((uint32_t)0x10000001) +#define DMA2_FLAG_TC1 ((uint32_t)0x10000002) +#define DMA2_FLAG_HT1 ((uint32_t)0x10000004) +#define DMA2_FLAG_TE1 ((uint32_t)0x10000008) +#define DMA2_FLAG_GL2 ((uint32_t)0x10000010) +#define DMA2_FLAG_TC2 ((uint32_t)0x10000020) +#define DMA2_FLAG_HT2 ((uint32_t)0x10000040) +#define DMA2_FLAG_TE2 ((uint32_t)0x10000080) +#define DMA2_FLAG_GL3 ((uint32_t)0x10000100) +#define DMA2_FLAG_TC3 ((uint32_t)0x10000200) +#define DMA2_FLAG_HT3 ((uint32_t)0x10000400) +#define DMA2_FLAG_TE3 ((uint32_t)0x10000800) +#define DMA2_FLAG_GL4 ((uint32_t)0x10001000) +#define DMA2_FLAG_TC4 ((uint32_t)0x10002000) +#define DMA2_FLAG_HT4 ((uint32_t)0x10004000) +#define DMA2_FLAG_TE4 ((uint32_t)0x10008000) +#define DMA2_FLAG_GL5 ((uint32_t)0x10010000) +#define DMA2_FLAG_TC5 ((uint32_t)0x10020000) +#define DMA2_FLAG_HT5 ((uint32_t)0x10040000) +#define DMA2_FLAG_TE5 ((uint32_t)0x10080000) + +#define IS_DMA_CLEAR_FLAG(FLAG) (((((FLAG) & 0xF0000000) == 0x00) || (((FLAG) & 0xEFF00000) == 0x00)) && ((FLAG) != 0x00)) + +#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA1_FLAG_GL1) || ((FLAG) == DMA1_FLAG_TC1) || \ + ((FLAG) == DMA1_FLAG_HT1) || ((FLAG) == DMA1_FLAG_TE1) || \ + ((FLAG) == DMA1_FLAG_GL2) || ((FLAG) == DMA1_FLAG_TC2) || \ + ((FLAG) == DMA1_FLAG_HT2) || ((FLAG) == DMA1_FLAG_TE2) || \ + ((FLAG) == DMA1_FLAG_GL3) || ((FLAG) == DMA1_FLAG_TC3) || \ + ((FLAG) == DMA1_FLAG_HT3) || ((FLAG) == DMA1_FLAG_TE3) || \ + ((FLAG) == DMA1_FLAG_GL4) || ((FLAG) == DMA1_FLAG_TC4) || \ + ((FLAG) == DMA1_FLAG_HT4) || ((FLAG) == DMA1_FLAG_TE4) || \ + ((FLAG) == DMA1_FLAG_GL5) || ((FLAG) == DMA1_FLAG_TC5) || \ + ((FLAG) == DMA1_FLAG_HT5) || ((FLAG) == DMA1_FLAG_TE5) || \ + ((FLAG) == DMA1_FLAG_GL6) || ((FLAG) == DMA1_FLAG_TC6) || \ + ((FLAG) == DMA1_FLAG_HT6) || ((FLAG) == DMA1_FLAG_TE6) || \ + ((FLAG) == DMA1_FLAG_GL7) || ((FLAG) == DMA1_FLAG_TC7) || \ + ((FLAG) == DMA1_FLAG_HT7) || ((FLAG) == DMA1_FLAG_TE7) || \ + ((FLAG) == DMA2_FLAG_GL1) || ((FLAG) == DMA2_FLAG_TC1) || \ + ((FLAG) == DMA2_FLAG_HT1) || ((FLAG) == DMA2_FLAG_TE1) || \ + ((FLAG) == DMA2_FLAG_GL2) || ((FLAG) == DMA2_FLAG_TC2) || \ + ((FLAG) == DMA2_FLAG_HT2) || ((FLAG) == DMA2_FLAG_TE2) || \ + ((FLAG) == DMA2_FLAG_GL3) || ((FLAG) == DMA2_FLAG_TC3) || \ + ((FLAG) == DMA2_FLAG_HT3) || ((FLAG) == DMA2_FLAG_TE3) || \ + ((FLAG) == DMA2_FLAG_GL4) || ((FLAG) == DMA2_FLAG_TC4) || \ + ((FLAG) == DMA2_FLAG_HT4) || ((FLAG) == DMA2_FLAG_TE4) || \ + ((FLAG) == DMA2_FLAG_GL5) || ((FLAG) == DMA2_FLAG_TC5) || \ + ((FLAG) == DMA2_FLAG_HT5) || ((FLAG) == DMA2_FLAG_TE5)) +/** + * @} + */ + +/** @defgroup DMA_Buffer_Size + * @{ + */ + +#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup DMA_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Exported_Functions + * @{ + */ + +void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx); +void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, const DMA_InitTypeDef* DMA_InitStruct); +void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct); +void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState); +void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState); +void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber); +uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx); +FlagStatus DMA_GetFlagStatus(uint32_t DMA_FLAG); +void DMA_ClearFlag(uint32_t DMA_FLAG); +ITStatus DMA_GetITStatus(uint32_t DMA_IT); +void DMA_ClearITPendingBit(uint32_t DMA_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_DMA_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h index 99084e3f3..ee9ad95c5 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h @@ -1,183 +1,183 @@ -/** - ****************************************************************************** - * @file stm32f10x_exti.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the EXTI firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_EXTI_H -#define __STM32F10x_EXTI_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup EXTI - * @{ - */ - -/** @defgroup EXTI_Exported_Types - * @{ - */ - -/** - * @brief EXTI mode enumeration - */ - -typedef enum -{ - EXTI_Mode_Interrupt = 0x00, - EXTI_Mode_Event = 0x04 -}EXTIMode_TypeDef; - -#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event)) - -/** - * @brief EXTI Trigger enumeration - */ - -typedef enum -{ - EXTI_Trigger_Rising = 0x08, - EXTI_Trigger_Falling = 0x0C, - EXTI_Trigger_Rising_Falling = 0x10 -}EXTITrigger_TypeDef; - -#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \ - ((TRIGGER) == EXTI_Trigger_Falling) || \ - ((TRIGGER) == EXTI_Trigger_Rising_Falling)) -/** - * @brief EXTI Init Structure definition - */ - -typedef struct -{ - uint32_t EXTI_Line; /*!< Specifies the EXTI lines to be enabled or disabled. - This parameter can be any combination of @ref EXTI_Lines */ - - EXTIMode_TypeDef EXTI_Mode; /*!< Specifies the mode for the EXTI lines. - This parameter can be a value of @ref EXTIMode_TypeDef */ - - EXTITrigger_TypeDef EXTI_Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines. - This parameter can be a value of @ref EXTIMode_TypeDef */ - - FunctionalState EXTI_LineCmd; /*!< Specifies the new state of the selected EXTI lines. - This parameter can be set either to ENABLE or DISABLE */ -}EXTI_InitTypeDef; - -/** - * @} - */ - -/** @defgroup EXTI_Exported_Constants - * @{ - */ - -/** @defgroup EXTI_Lines - * @{ - */ - -#define EXTI_Line0 ((uint32_t)0x00001) /*!< External interrupt line 0 */ -#define EXTI_Line1 ((uint32_t)0x00002) /*!< External interrupt line 1 */ -#define EXTI_Line2 ((uint32_t)0x00004) /*!< External interrupt line 2 */ -#define EXTI_Line3 ((uint32_t)0x00008) /*!< External interrupt line 3 */ -#define EXTI_Line4 ((uint32_t)0x00010) /*!< External interrupt line 4 */ -#define EXTI_Line5 ((uint32_t)0x00020) /*!< External interrupt line 5 */ -#define EXTI_Line6 ((uint32_t)0x00040) /*!< External interrupt line 6 */ -#define EXTI_Line7 ((uint32_t)0x00080) /*!< External interrupt line 7 */ -#define EXTI_Line8 ((uint32_t)0x00100) /*!< External interrupt line 8 */ -#define EXTI_Line9 ((uint32_t)0x00200) /*!< External interrupt line 9 */ -#define EXTI_Line10 ((uint32_t)0x00400) /*!< External interrupt line 10 */ -#define EXTI_Line11 ((uint32_t)0x00800) /*!< External interrupt line 11 */ -#define EXTI_Line12 ((uint32_t)0x01000) /*!< External interrupt line 12 */ -#define EXTI_Line13 ((uint32_t)0x02000) /*!< External interrupt line 13 */ -#define EXTI_Line14 ((uint32_t)0x04000) /*!< External interrupt line 14 */ -#define EXTI_Line15 ((uint32_t)0x08000) /*!< External interrupt line 15 */ -#define EXTI_Line16 ((uint32_t)0x10000) /*!< External interrupt line 16 Connected to the PVD Output */ -#define EXTI_Line17 ((uint32_t)0x20000) /*!< External interrupt line 17 Connected to the RTC Alarm event */ -#define EXTI_Line18 ((uint32_t)0x40000) /*!< External interrupt line 18 Connected to the USB Device/USB OTG FS - Wakeup from suspend event */ -#define EXTI_Line19 ((uint32_t)0x80000) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */ - -#define IS_EXTI_LINE(LINE) ((((LINE) & (uint32_t)0xFFF00000) == 0x00) && ((LINE) != (uint16_t)0x00)) -#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \ - ((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \ - ((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \ - ((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \ - ((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \ - ((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \ - ((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \ - ((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \ - ((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \ - ((LINE) == EXTI_Line18) || ((LINE) == EXTI_Line19)) - - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup EXTI_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup EXTI_Exported_Functions - * @{ - */ - -void EXTI_DeInit(void); -void EXTI_Init(const EXTI_InitTypeDef* EXTI_InitStruct); -void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct); -void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line); -FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line); -void EXTI_ClearFlag(uint32_t EXTI_Line); -ITStatus EXTI_GetITStatus(uint32_t EXTI_Line); -void EXTI_ClearITPendingBit(uint32_t EXTI_Line); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_EXTI_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_exti.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the EXTI firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_EXTI_H +#define __STM32F10x_EXTI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup EXTI + * @{ + */ + +/** @defgroup EXTI_Exported_Types + * @{ + */ + +/** + * @brief EXTI mode enumeration + */ + +typedef enum +{ + EXTI_Mode_Interrupt = 0x00, + EXTI_Mode_Event = 0x04 +}EXTIMode_TypeDef; + +#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event)) + +/** + * @brief EXTI Trigger enumeration + */ + +typedef enum +{ + EXTI_Trigger_Rising = 0x08, + EXTI_Trigger_Falling = 0x0C, + EXTI_Trigger_Rising_Falling = 0x10 +}EXTITrigger_TypeDef; + +#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \ + ((TRIGGER) == EXTI_Trigger_Falling) || \ + ((TRIGGER) == EXTI_Trigger_Rising_Falling)) +/** + * @brief EXTI Init Structure definition + */ + +typedef struct +{ + uint32_t EXTI_Line; /*!< Specifies the EXTI lines to be enabled or disabled. + This parameter can be any combination of @ref EXTI_Lines */ + + EXTIMode_TypeDef EXTI_Mode; /*!< Specifies the mode for the EXTI lines. + This parameter can be a value of @ref EXTIMode_TypeDef */ + + EXTITrigger_TypeDef EXTI_Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines. + This parameter can be a value of @ref EXTIMode_TypeDef */ + + FunctionalState EXTI_LineCmd; /*!< Specifies the new state of the selected EXTI lines. + This parameter can be set either to ENABLE or DISABLE */ +}EXTI_InitTypeDef; + +/** + * @} + */ + +/** @defgroup EXTI_Exported_Constants + * @{ + */ + +/** @defgroup EXTI_Lines + * @{ + */ + +#define EXTI_Line0 ((uint32_t)0x00001) /*!< External interrupt line 0 */ +#define EXTI_Line1 ((uint32_t)0x00002) /*!< External interrupt line 1 */ +#define EXTI_Line2 ((uint32_t)0x00004) /*!< External interrupt line 2 */ +#define EXTI_Line3 ((uint32_t)0x00008) /*!< External interrupt line 3 */ +#define EXTI_Line4 ((uint32_t)0x00010) /*!< External interrupt line 4 */ +#define EXTI_Line5 ((uint32_t)0x00020) /*!< External interrupt line 5 */ +#define EXTI_Line6 ((uint32_t)0x00040) /*!< External interrupt line 6 */ +#define EXTI_Line7 ((uint32_t)0x00080) /*!< External interrupt line 7 */ +#define EXTI_Line8 ((uint32_t)0x00100) /*!< External interrupt line 8 */ +#define EXTI_Line9 ((uint32_t)0x00200) /*!< External interrupt line 9 */ +#define EXTI_Line10 ((uint32_t)0x00400) /*!< External interrupt line 10 */ +#define EXTI_Line11 ((uint32_t)0x00800) /*!< External interrupt line 11 */ +#define EXTI_Line12 ((uint32_t)0x01000) /*!< External interrupt line 12 */ +#define EXTI_Line13 ((uint32_t)0x02000) /*!< External interrupt line 13 */ +#define EXTI_Line14 ((uint32_t)0x04000) /*!< External interrupt line 14 */ +#define EXTI_Line15 ((uint32_t)0x08000) /*!< External interrupt line 15 */ +#define EXTI_Line16 ((uint32_t)0x10000) /*!< External interrupt line 16 Connected to the PVD Output */ +#define EXTI_Line17 ((uint32_t)0x20000) /*!< External interrupt line 17 Connected to the RTC Alarm event */ +#define EXTI_Line18 ((uint32_t)0x40000) /*!< External interrupt line 18 Connected to the USB Device/USB OTG FS + Wakeup from suspend event */ +#define EXTI_Line19 ((uint32_t)0x80000) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */ + +#define IS_EXTI_LINE(LINE) ((((LINE) & (uint32_t)0xFFF00000) == 0x00) && ((LINE) != (uint16_t)0x00)) +#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \ + ((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \ + ((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \ + ((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \ + ((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \ + ((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \ + ((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \ + ((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \ + ((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \ + ((LINE) == EXTI_Line18) || ((LINE) == EXTI_Line19)) + + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup EXTI_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Exported_Functions + * @{ + */ + +void EXTI_DeInit(void); +void EXTI_Init(const EXTI_InitTypeDef* EXTI_InitStruct); +void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct); +void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line); +FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line); +void EXTI_ClearFlag(uint32_t EXTI_Line); +ITStatus EXTI_GetITStatus(uint32_t EXTI_Line); +void EXTI_ClearITPendingBit(uint32_t EXTI_Line); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_EXTI_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h index 5e2047d67..331c58b68 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h @@ -1,425 +1,425 @@ -/** - ****************************************************************************** - * @file stm32f10x_flash.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the FLASH - * firmware library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_FLASH_H -#define __STM32F10x_FLASH_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup FLASH - * @{ - */ - -/** @defgroup FLASH_Exported_Types - * @{ - */ - -/** - * @brief FLASH Status - */ - -typedef enum -{ - FLASH_BUSY = 1, - FLASH_ERROR_PG, - FLASH_ERROR_WRP, - FLASH_COMPLETE, - FLASH_TIMEOUT -}FLASH_Status; - -/** - * @} - */ - -/** @defgroup FLASH_Exported_Constants - * @{ - */ - -/** @defgroup Flash_Latency - * @{ - */ - -#define FLASH_Latency_0 ((uint32_t)0x00000000) /*!< FLASH Zero Latency cycle */ -#define FLASH_Latency_1 ((uint32_t)0x00000001) /*!< FLASH One Latency cycle */ -#define FLASH_Latency_2 ((uint32_t)0x00000002) /*!< FLASH Two Latency cycles */ -#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \ - ((LATENCY) == FLASH_Latency_1) || \ - ((LATENCY) == FLASH_Latency_2)) -/** - * @} - */ - -/** @defgroup Half_Cycle_Enable_Disable - * @{ - */ - -#define FLASH_HalfCycleAccess_Enable ((uint32_t)0x00000008) /*!< FLASH Half Cycle Enable */ -#define FLASH_HalfCycleAccess_Disable ((uint32_t)0x00000000) /*!< FLASH Half Cycle Disable */ -#define IS_FLASH_HALFCYCLEACCESS_STATE(STATE) (((STATE) == FLASH_HalfCycleAccess_Enable) || \ - ((STATE) == FLASH_HalfCycleAccess_Disable)) -/** - * @} - */ - -/** @defgroup Prefetch_Buffer_Enable_Disable - * @{ - */ - -#define FLASH_PrefetchBuffer_Enable ((uint32_t)0x00000010) /*!< FLASH Prefetch Buffer Enable */ -#define FLASH_PrefetchBuffer_Disable ((uint32_t)0x00000000) /*!< FLASH Prefetch Buffer Disable */ -#define IS_FLASH_PREFETCHBUFFER_STATE(STATE) (((STATE) == FLASH_PrefetchBuffer_Enable) || \ - ((STATE) == FLASH_PrefetchBuffer_Disable)) -/** - * @} - */ - -/** @defgroup Option_Bytes_Write_Protection - * @{ - */ - -/* Values to be used with STM32 Low and Medium density devices */ -#define FLASH_WRProt_Pages0to3 ((uint32_t)0x00000001) /*!< STM32 Low and Medium density devices: Write protection of page 0 to 3 */ -#define FLASH_WRProt_Pages4to7 ((uint32_t)0x00000002) /*!< STM32 Low and Medium density devices: Write protection of page 4 to 7 */ -#define FLASH_WRProt_Pages8to11 ((uint32_t)0x00000004) /*!< STM32 Low and Medium density devices: Write protection of page 8 to 11 */ -#define FLASH_WRProt_Pages12to15 ((uint32_t)0x00000008) /*!< STM32 Low and Medium density devices: Write protection of page 12 to 15 */ -#define FLASH_WRProt_Pages16to19 ((uint32_t)0x00000010) /*!< STM32 Low and Medium density devices: Write protection of page 16 to 19 */ -#define FLASH_WRProt_Pages20to23 ((uint32_t)0x00000020) /*!< STM32 Low and Medium density devices: Write protection of page 20 to 23 */ -#define FLASH_WRProt_Pages24to27 ((uint32_t)0x00000040) /*!< STM32 Low and Medium density devices: Write protection of page 24 to 27 */ -#define FLASH_WRProt_Pages28to31 ((uint32_t)0x00000080) /*!< STM32 Low and Medium density devices: Write protection of page 28 to 31 */ - -/* Values to be used with STM32 Medium-density devices */ -#define FLASH_WRProt_Pages32to35 ((uint32_t)0x00000100) /*!< STM32 Medium-density devices: Write protection of page 32 to 35 */ -#define FLASH_WRProt_Pages36to39 ((uint32_t)0x00000200) /*!< STM32 Medium-density devices: Write protection of page 36 to 39 */ -#define FLASH_WRProt_Pages40to43 ((uint32_t)0x00000400) /*!< STM32 Medium-density devices: Write protection of page 40 to 43 */ -#define FLASH_WRProt_Pages44to47 ((uint32_t)0x00000800) /*!< STM32 Medium-density devices: Write protection of page 44 to 47 */ -#define FLASH_WRProt_Pages48to51 ((uint32_t)0x00001000) /*!< STM32 Medium-density devices: Write protection of page 48 to 51 */ -#define FLASH_WRProt_Pages52to55 ((uint32_t)0x00002000) /*!< STM32 Medium-density devices: Write protection of page 52 to 55 */ -#define FLASH_WRProt_Pages56to59 ((uint32_t)0x00004000) /*!< STM32 Medium-density devices: Write protection of page 56 to 59 */ -#define FLASH_WRProt_Pages60to63 ((uint32_t)0x00008000) /*!< STM32 Medium-density devices: Write protection of page 60 to 63 */ -#define FLASH_WRProt_Pages64to67 ((uint32_t)0x00010000) /*!< STM32 Medium-density devices: Write protection of page 64 to 67 */ -#define FLASH_WRProt_Pages68to71 ((uint32_t)0x00020000) /*!< STM32 Medium-density devices: Write protection of page 68 to 71 */ -#define FLASH_WRProt_Pages72to75 ((uint32_t)0x00040000) /*!< STM32 Medium-density devices: Write protection of page 72 to 75 */ -#define FLASH_WRProt_Pages76to79 ((uint32_t)0x00080000) /*!< STM32 Medium-density devices: Write protection of page 76 to 79 */ -#define FLASH_WRProt_Pages80to83 ((uint32_t)0x00100000) /*!< STM32 Medium-density devices: Write protection of page 80 to 83 */ -#define FLASH_WRProt_Pages84to87 ((uint32_t)0x00200000) /*!< STM32 Medium-density devices: Write protection of page 84 to 87 */ -#define FLASH_WRProt_Pages88to91 ((uint32_t)0x00400000) /*!< STM32 Medium-density devices: Write protection of page 88 to 91 */ -#define FLASH_WRProt_Pages92to95 ((uint32_t)0x00800000) /*!< STM32 Medium-density devices: Write protection of page 92 to 95 */ -#define FLASH_WRProt_Pages96to99 ((uint32_t)0x01000000) /*!< STM32 Medium-density devices: Write protection of page 96 to 99 */ -#define FLASH_WRProt_Pages100to103 ((uint32_t)0x02000000) /*!< STM32 Medium-density devices: Write protection of page 100 to 103 */ -#define FLASH_WRProt_Pages104to107 ((uint32_t)0x04000000) /*!< STM32 Medium-density devices: Write protection of page 104 to 107 */ -#define FLASH_WRProt_Pages108to111 ((uint32_t)0x08000000) /*!< STM32 Medium-density devices: Write protection of page 108 to 111 */ -#define FLASH_WRProt_Pages112to115 ((uint32_t)0x10000000) /*!< STM32 Medium-density devices: Write protection of page 112 to 115 */ -#define FLASH_WRProt_Pages116to119 ((uint32_t)0x20000000) /*!< STM32 Medium-density devices: Write protection of page 115 to 119 */ -#define FLASH_WRProt_Pages120to123 ((uint32_t)0x40000000) /*!< STM32 Medium-density devices: Write protection of page 120 to 123 */ -#define FLASH_WRProt_Pages124to127 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 124 to 127 */ - -/* Values to be used with STM32 High-density and STM32F10X Connectivity line devices */ -#define FLASH_WRProt_Pages0to1 ((uint32_t)0x00000001) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 0 to 1 */ -#define FLASH_WRProt_Pages2to3 ((uint32_t)0x00000002) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 2 to 3 */ -#define FLASH_WRProt_Pages4to5 ((uint32_t)0x00000004) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 4 to 5 */ -#define FLASH_WRProt_Pages6to7 ((uint32_t)0x00000008) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 6 to 7 */ -#define FLASH_WRProt_Pages8to9 ((uint32_t)0x00000010) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 8 to 9 */ -#define FLASH_WRProt_Pages10to11 ((uint32_t)0x00000020) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 10 to 11 */ -#define FLASH_WRProt_Pages12to13 ((uint32_t)0x00000040) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 12 to 13 */ -#define FLASH_WRProt_Pages14to15 ((uint32_t)0x00000080) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 14 to 15 */ -#define FLASH_WRProt_Pages16to17 ((uint32_t)0x00000100) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 16 to 17 */ -#define FLASH_WRProt_Pages18to19 ((uint32_t)0x00000200) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 18 to 19 */ -#define FLASH_WRProt_Pages20to21 ((uint32_t)0x00000400) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 20 to 21 */ -#define FLASH_WRProt_Pages22to23 ((uint32_t)0x00000800) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 22 to 23 */ -#define FLASH_WRProt_Pages24to25 ((uint32_t)0x00001000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 24 to 25 */ -#define FLASH_WRProt_Pages26to27 ((uint32_t)0x00002000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 26 to 27 */ -#define FLASH_WRProt_Pages28to29 ((uint32_t)0x00004000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 28 to 29 */ -#define FLASH_WRProt_Pages30to31 ((uint32_t)0x00008000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 30 to 31 */ -#define FLASH_WRProt_Pages32to33 ((uint32_t)0x00010000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 32 to 33 */ -#define FLASH_WRProt_Pages34to35 ((uint32_t)0x00020000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 34 to 35 */ -#define FLASH_WRProt_Pages36to37 ((uint32_t)0x00040000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 36 to 37 */ -#define FLASH_WRProt_Pages38to39 ((uint32_t)0x00080000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 38 to 39 */ -#define FLASH_WRProt_Pages40to41 ((uint32_t)0x00100000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 40 to 41 */ -#define FLASH_WRProt_Pages42to43 ((uint32_t)0x00200000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 42 to 43 */ -#define FLASH_WRProt_Pages44to45 ((uint32_t)0x00400000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 44 to 45 */ -#define FLASH_WRProt_Pages46to47 ((uint32_t)0x00800000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 46 to 47 */ -#define FLASH_WRProt_Pages48to49 ((uint32_t)0x01000000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 48 to 49 */ -#define FLASH_WRProt_Pages50to51 ((uint32_t)0x02000000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 50 to 51 */ -#define FLASH_WRProt_Pages52to53 ((uint32_t)0x04000000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 52 to 53 */ -#define FLASH_WRProt_Pages54to55 ((uint32_t)0x08000000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 54 to 55 */ -#define FLASH_WRProt_Pages56to57 ((uint32_t)0x10000000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 56 to 57 */ -#define FLASH_WRProt_Pages58to59 ((uint32_t)0x20000000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 58 to 59 */ -#define FLASH_WRProt_Pages60to61 ((uint32_t)0x40000000) /*!< STM32 High-density, XL-density and Connectivity line devices: - Write protection of page 60 to 61 */ -#define FLASH_WRProt_Pages62to127 ((uint32_t)0x80000000) /*!< STM32 Connectivity line devices: Write protection of page 62 to 127 */ -#define FLASH_WRProt_Pages62to255 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 62 to 255 */ -#define FLASH_WRProt_Pages62to511 ((uint32_t)0x80000000) /*!< STM32 XL-density devices: Write protection of page 62 to 511 */ - -#define FLASH_WRProt_AllPages ((uint32_t)0xFFFFFFFF) /*!< Write protection of all Pages */ - -#define IS_FLASH_WRPROT_PAGE(PAGE) (((PAGE) != 0x00000000)) - -#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) - -#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == 0x1FFFF804) || ((ADDRESS) == 0x1FFFF806)) - -/** - * @} - */ - -/** @defgroup Option_Bytes_IWatchdog - * @{ - */ - -#define OB_IWDG_SW ((uint16_t)0x0001) /*!< Software IWDG selected */ -#define OB_IWDG_HW ((uint16_t)0x0000) /*!< Hardware IWDG selected */ -#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW)) - -/** - * @} - */ - -/** @defgroup Option_Bytes_nRST_STOP - * @{ - */ - -#define OB_STOP_NoRST ((uint16_t)0x0002) /*!< No reset generated when entering in STOP */ -#define OB_STOP_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STOP */ -#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST)) - -/** - * @} - */ - -/** @defgroup Option_Bytes_nRST_STDBY - * @{ - */ - -#define OB_STDBY_NoRST ((uint16_t)0x0004) /*!< No reset generated when entering in STANDBY */ -#define OB_STDBY_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STANDBY */ -#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST)) - -#ifdef STM32F10X_XL -/** - * @} - */ -/** @defgroup FLASH_Boot - * @{ - */ -#define FLASH_BOOT_Bank1 ((uint16_t)0x0000) /*!< At startup, if boot pins are set in boot from user Flash position - and this parameter is selected the device will boot from Bank1(Default) */ -#define FLASH_BOOT_Bank2 ((uint16_t)0x0001) /*!< At startup, if boot pins are set in boot from user Flash position - and this parameter is selected the device will boot from Bank 2 or Bank 1, - depending on the activation of the bank */ -#define IS_FLASH_BOOT(BOOT) (((BOOT) == FLASH_BOOT_Bank1) || ((BOOT) == FLASH_BOOT_Bank2)) -#endif -/** - * @} - */ -/** @defgroup FLASH_Interrupts - * @{ - */ -#ifdef STM32F10X_XL -#define FLASH_IT_BANK2_ERROR ((uint32_t)0x80000400) /*!< FPEC BANK2 error interrupt source */ -#define FLASH_IT_BANK2_EOP ((uint32_t)0x80001000) /*!< End of FLASH BANK2 Operation Interrupt source */ - -#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */ -#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */ - -#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC BANK1 error interrupt source */ -#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH BANK1 Operation Interrupt source */ -#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0x7FFFEBFF) == 0x00000000) && (((IT) != 0x00000000))) -#else -#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC error interrupt source */ -#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH Operation Interrupt source */ -#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */ -#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */ - -#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFFFFEBFF) == 0x00000000) && (((IT) != 0x00000000))) -#endif - -/** - * @} - */ - -/** @defgroup FLASH_Flags - * @{ - */ -#ifdef STM32F10X_XL -#define FLASH_FLAG_BANK2_BSY ((uint32_t)0x80000001) /*!< FLASH BANK2 Busy flag */ -#define FLASH_FLAG_BANK2_EOP ((uint32_t)0x80000020) /*!< FLASH BANK2 End of Operation flag */ -#define FLASH_FLAG_BANK2_PGERR ((uint32_t)0x80000004) /*!< FLASH BANK2 Program error flag */ -#define FLASH_FLAG_BANK2_WRPRTERR ((uint32_t)0x80000010) /*!< FLASH BANK2 Write protected error flag */ - -#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/ -#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */ -#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */ -#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */ - -#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */ -#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */ -#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */ -#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */ -#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */ - -#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0x7FFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000)) -#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \ - ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \ - ((FLAG) == FLASH_FLAG_OPTERR)|| \ - ((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \ - ((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \ - ((FLAG) == FLASH_FLAG_BANK2_BSY) || ((FLAG) == FLASH_FLAG_BANK2_EOP) || \ - ((FLAG) == FLASH_FLAG_BANK2_PGERR) || ((FLAG) == FLASH_FLAG_BANK2_WRPRTERR)) -#else -#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */ -#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */ -#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */ -#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */ -#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */ - -#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/ -#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */ -#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */ -#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */ - -#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000)) -#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \ - ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \ - ((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \ - ((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \ - ((FLAG) == FLASH_FLAG_OPTERR)) -#endif - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup FLASH_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup FLASH_Exported_Functions - * @{ - */ - -/*------------ Functions used for all STM32F10x devices -----*/ -void FLASH_SetLatency(uint32_t FLASH_Latency); -void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess); -void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer); -void FLASH_Unlock(void); -void FLASH_Lock(void); -FLASH_Status FLASH_ErasePage(uint32_t Page_Address); -FLASH_Status FLASH_EraseAllPages(void); -FLASH_Status FLASH_EraseOptionBytes(void); -FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data); -FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data); -FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data); -FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages); -FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState); -FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY); -uint32_t FLASH_GetUserOptionByte(void); -uint32_t FLASH_GetWriteProtectionOptionByte(void); -FlagStatus FLASH_GetReadOutProtectionStatus(void); -FlagStatus FLASH_GetPrefetchBufferStatus(void); -void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState); -FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG); -void FLASH_ClearFlag(uint32_t FLASH_FLAG); -FLASH_Status FLASH_GetStatus(void); -FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout); - -/*------------ New function used for all STM32F10x devices -----*/ -void FLASH_UnlockBank1(void); -void FLASH_LockBank1(void); -FLASH_Status FLASH_EraseAllBank1Pages(void); -FLASH_Status FLASH_GetBank1Status(void); -FLASH_Status FLASH_WaitForLastBank1Operation(uint32_t Timeout); - -#ifdef STM32F10X_XL -/*---- New Functions used only with STM32F10x_XL density devices -----*/ -void FLASH_UnlockBank2(void); -void FLASH_LockBank2(void); -FLASH_Status FLASH_EraseAllBank2Pages(void); -FLASH_Status FLASH_GetBank2Status(void); -FLASH_Status FLASH_WaitForLastBank2Operation(uint32_t Timeout); -FLASH_Status FLASH_BootConfig(uint16_t FLASH_BOOT); -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_FLASH_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_flash.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the FLASH + * firmware library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_FLASH_H +#define __STM32F10x_FLASH_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup FLASH + * @{ + */ + +/** @defgroup FLASH_Exported_Types + * @{ + */ + +/** + * @brief FLASH Status + */ + +typedef enum +{ + FLASH_BUSY = 1, + FLASH_ERROR_PG, + FLASH_ERROR_WRP, + FLASH_COMPLETE, + FLASH_TIMEOUT +}FLASH_Status; + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Constants + * @{ + */ + +/** @defgroup Flash_Latency + * @{ + */ + +#define FLASH_Latency_0 ((uint32_t)0x00000000) /*!< FLASH Zero Latency cycle */ +#define FLASH_Latency_1 ((uint32_t)0x00000001) /*!< FLASH One Latency cycle */ +#define FLASH_Latency_2 ((uint32_t)0x00000002) /*!< FLASH Two Latency cycles */ +#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \ + ((LATENCY) == FLASH_Latency_1) || \ + ((LATENCY) == FLASH_Latency_2)) +/** + * @} + */ + +/** @defgroup Half_Cycle_Enable_Disable + * @{ + */ + +#define FLASH_HalfCycleAccess_Enable ((uint32_t)0x00000008) /*!< FLASH Half Cycle Enable */ +#define FLASH_HalfCycleAccess_Disable ((uint32_t)0x00000000) /*!< FLASH Half Cycle Disable */ +#define IS_FLASH_HALFCYCLEACCESS_STATE(STATE) (((STATE) == FLASH_HalfCycleAccess_Enable) || \ + ((STATE) == FLASH_HalfCycleAccess_Disable)) +/** + * @} + */ + +/** @defgroup Prefetch_Buffer_Enable_Disable + * @{ + */ + +#define FLASH_PrefetchBuffer_Enable ((uint32_t)0x00000010) /*!< FLASH Prefetch Buffer Enable */ +#define FLASH_PrefetchBuffer_Disable ((uint32_t)0x00000000) /*!< FLASH Prefetch Buffer Disable */ +#define IS_FLASH_PREFETCHBUFFER_STATE(STATE) (((STATE) == FLASH_PrefetchBuffer_Enable) || \ + ((STATE) == FLASH_PrefetchBuffer_Disable)) +/** + * @} + */ + +/** @defgroup Option_Bytes_Write_Protection + * @{ + */ + +/* Values to be used with STM32 Low and Medium density devices */ +#define FLASH_WRProt_Pages0to3 ((uint32_t)0x00000001) /*!< STM32 Low and Medium density devices: Write protection of page 0 to 3 */ +#define FLASH_WRProt_Pages4to7 ((uint32_t)0x00000002) /*!< STM32 Low and Medium density devices: Write protection of page 4 to 7 */ +#define FLASH_WRProt_Pages8to11 ((uint32_t)0x00000004) /*!< STM32 Low and Medium density devices: Write protection of page 8 to 11 */ +#define FLASH_WRProt_Pages12to15 ((uint32_t)0x00000008) /*!< STM32 Low and Medium density devices: Write protection of page 12 to 15 */ +#define FLASH_WRProt_Pages16to19 ((uint32_t)0x00000010) /*!< STM32 Low and Medium density devices: Write protection of page 16 to 19 */ +#define FLASH_WRProt_Pages20to23 ((uint32_t)0x00000020) /*!< STM32 Low and Medium density devices: Write protection of page 20 to 23 */ +#define FLASH_WRProt_Pages24to27 ((uint32_t)0x00000040) /*!< STM32 Low and Medium density devices: Write protection of page 24 to 27 */ +#define FLASH_WRProt_Pages28to31 ((uint32_t)0x00000080) /*!< STM32 Low and Medium density devices: Write protection of page 28 to 31 */ + +/* Values to be used with STM32 Medium-density devices */ +#define FLASH_WRProt_Pages32to35 ((uint32_t)0x00000100) /*!< STM32 Medium-density devices: Write protection of page 32 to 35 */ +#define FLASH_WRProt_Pages36to39 ((uint32_t)0x00000200) /*!< STM32 Medium-density devices: Write protection of page 36 to 39 */ +#define FLASH_WRProt_Pages40to43 ((uint32_t)0x00000400) /*!< STM32 Medium-density devices: Write protection of page 40 to 43 */ +#define FLASH_WRProt_Pages44to47 ((uint32_t)0x00000800) /*!< STM32 Medium-density devices: Write protection of page 44 to 47 */ +#define FLASH_WRProt_Pages48to51 ((uint32_t)0x00001000) /*!< STM32 Medium-density devices: Write protection of page 48 to 51 */ +#define FLASH_WRProt_Pages52to55 ((uint32_t)0x00002000) /*!< STM32 Medium-density devices: Write protection of page 52 to 55 */ +#define FLASH_WRProt_Pages56to59 ((uint32_t)0x00004000) /*!< STM32 Medium-density devices: Write protection of page 56 to 59 */ +#define FLASH_WRProt_Pages60to63 ((uint32_t)0x00008000) /*!< STM32 Medium-density devices: Write protection of page 60 to 63 */ +#define FLASH_WRProt_Pages64to67 ((uint32_t)0x00010000) /*!< STM32 Medium-density devices: Write protection of page 64 to 67 */ +#define FLASH_WRProt_Pages68to71 ((uint32_t)0x00020000) /*!< STM32 Medium-density devices: Write protection of page 68 to 71 */ +#define FLASH_WRProt_Pages72to75 ((uint32_t)0x00040000) /*!< STM32 Medium-density devices: Write protection of page 72 to 75 */ +#define FLASH_WRProt_Pages76to79 ((uint32_t)0x00080000) /*!< STM32 Medium-density devices: Write protection of page 76 to 79 */ +#define FLASH_WRProt_Pages80to83 ((uint32_t)0x00100000) /*!< STM32 Medium-density devices: Write protection of page 80 to 83 */ +#define FLASH_WRProt_Pages84to87 ((uint32_t)0x00200000) /*!< STM32 Medium-density devices: Write protection of page 84 to 87 */ +#define FLASH_WRProt_Pages88to91 ((uint32_t)0x00400000) /*!< STM32 Medium-density devices: Write protection of page 88 to 91 */ +#define FLASH_WRProt_Pages92to95 ((uint32_t)0x00800000) /*!< STM32 Medium-density devices: Write protection of page 92 to 95 */ +#define FLASH_WRProt_Pages96to99 ((uint32_t)0x01000000) /*!< STM32 Medium-density devices: Write protection of page 96 to 99 */ +#define FLASH_WRProt_Pages100to103 ((uint32_t)0x02000000) /*!< STM32 Medium-density devices: Write protection of page 100 to 103 */ +#define FLASH_WRProt_Pages104to107 ((uint32_t)0x04000000) /*!< STM32 Medium-density devices: Write protection of page 104 to 107 */ +#define FLASH_WRProt_Pages108to111 ((uint32_t)0x08000000) /*!< STM32 Medium-density devices: Write protection of page 108 to 111 */ +#define FLASH_WRProt_Pages112to115 ((uint32_t)0x10000000) /*!< STM32 Medium-density devices: Write protection of page 112 to 115 */ +#define FLASH_WRProt_Pages116to119 ((uint32_t)0x20000000) /*!< STM32 Medium-density devices: Write protection of page 115 to 119 */ +#define FLASH_WRProt_Pages120to123 ((uint32_t)0x40000000) /*!< STM32 Medium-density devices: Write protection of page 120 to 123 */ +#define FLASH_WRProt_Pages124to127 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 124 to 127 */ + +/* Values to be used with STM32 High-density and STM32F10X Connectivity line devices */ +#define FLASH_WRProt_Pages0to1 ((uint32_t)0x00000001) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 0 to 1 */ +#define FLASH_WRProt_Pages2to3 ((uint32_t)0x00000002) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 2 to 3 */ +#define FLASH_WRProt_Pages4to5 ((uint32_t)0x00000004) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 4 to 5 */ +#define FLASH_WRProt_Pages6to7 ((uint32_t)0x00000008) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 6 to 7 */ +#define FLASH_WRProt_Pages8to9 ((uint32_t)0x00000010) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 8 to 9 */ +#define FLASH_WRProt_Pages10to11 ((uint32_t)0x00000020) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 10 to 11 */ +#define FLASH_WRProt_Pages12to13 ((uint32_t)0x00000040) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 12 to 13 */ +#define FLASH_WRProt_Pages14to15 ((uint32_t)0x00000080) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 14 to 15 */ +#define FLASH_WRProt_Pages16to17 ((uint32_t)0x00000100) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 16 to 17 */ +#define FLASH_WRProt_Pages18to19 ((uint32_t)0x00000200) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 18 to 19 */ +#define FLASH_WRProt_Pages20to21 ((uint32_t)0x00000400) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 20 to 21 */ +#define FLASH_WRProt_Pages22to23 ((uint32_t)0x00000800) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 22 to 23 */ +#define FLASH_WRProt_Pages24to25 ((uint32_t)0x00001000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 24 to 25 */ +#define FLASH_WRProt_Pages26to27 ((uint32_t)0x00002000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 26 to 27 */ +#define FLASH_WRProt_Pages28to29 ((uint32_t)0x00004000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 28 to 29 */ +#define FLASH_WRProt_Pages30to31 ((uint32_t)0x00008000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 30 to 31 */ +#define FLASH_WRProt_Pages32to33 ((uint32_t)0x00010000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 32 to 33 */ +#define FLASH_WRProt_Pages34to35 ((uint32_t)0x00020000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 34 to 35 */ +#define FLASH_WRProt_Pages36to37 ((uint32_t)0x00040000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 36 to 37 */ +#define FLASH_WRProt_Pages38to39 ((uint32_t)0x00080000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 38 to 39 */ +#define FLASH_WRProt_Pages40to41 ((uint32_t)0x00100000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 40 to 41 */ +#define FLASH_WRProt_Pages42to43 ((uint32_t)0x00200000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 42 to 43 */ +#define FLASH_WRProt_Pages44to45 ((uint32_t)0x00400000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 44 to 45 */ +#define FLASH_WRProt_Pages46to47 ((uint32_t)0x00800000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 46 to 47 */ +#define FLASH_WRProt_Pages48to49 ((uint32_t)0x01000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 48 to 49 */ +#define FLASH_WRProt_Pages50to51 ((uint32_t)0x02000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 50 to 51 */ +#define FLASH_WRProt_Pages52to53 ((uint32_t)0x04000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 52 to 53 */ +#define FLASH_WRProt_Pages54to55 ((uint32_t)0x08000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 54 to 55 */ +#define FLASH_WRProt_Pages56to57 ((uint32_t)0x10000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 56 to 57 */ +#define FLASH_WRProt_Pages58to59 ((uint32_t)0x20000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 58 to 59 */ +#define FLASH_WRProt_Pages60to61 ((uint32_t)0x40000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 60 to 61 */ +#define FLASH_WRProt_Pages62to127 ((uint32_t)0x80000000) /*!< STM32 Connectivity line devices: Write protection of page 62 to 127 */ +#define FLASH_WRProt_Pages62to255 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 62 to 255 */ +#define FLASH_WRProt_Pages62to511 ((uint32_t)0x80000000) /*!< STM32 XL-density devices: Write protection of page 62 to 511 */ + +#define FLASH_WRProt_AllPages ((uint32_t)0xFFFFFFFF) /*!< Write protection of all Pages */ + +#define IS_FLASH_WRPROT_PAGE(PAGE) (((PAGE) != 0x00000000)) + +#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) + +#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == 0x1FFFF804) || ((ADDRESS) == 0x1FFFF806)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_IWatchdog + * @{ + */ + +#define OB_IWDG_SW ((uint16_t)0x0001) /*!< Software IWDG selected */ +#define OB_IWDG_HW ((uint16_t)0x0000) /*!< Hardware IWDG selected */ +#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_nRST_STOP + * @{ + */ + +#define OB_STOP_NoRST ((uint16_t)0x0002) /*!< No reset generated when entering in STOP */ +#define OB_STOP_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STOP */ +#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_nRST_STDBY + * @{ + */ + +#define OB_STDBY_NoRST ((uint16_t)0x0004) /*!< No reset generated when entering in STANDBY */ +#define OB_STDBY_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STANDBY */ +#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST)) + +#ifdef STM32F10X_XL +/** + * @} + */ +/** @defgroup FLASH_Boot + * @{ + */ +#define FLASH_BOOT_Bank1 ((uint16_t)0x0000) /*!< At startup, if boot pins are set in boot from user Flash position + and this parameter is selected the device will boot from Bank1(Default) */ +#define FLASH_BOOT_Bank2 ((uint16_t)0x0001) /*!< At startup, if boot pins are set in boot from user Flash position + and this parameter is selected the device will boot from Bank 2 or Bank 1, + depending on the activation of the bank */ +#define IS_FLASH_BOOT(BOOT) (((BOOT) == FLASH_BOOT_Bank1) || ((BOOT) == FLASH_BOOT_Bank2)) +#endif +/** + * @} + */ +/** @defgroup FLASH_Interrupts + * @{ + */ +#ifdef STM32F10X_XL +#define FLASH_IT_BANK2_ERROR ((uint32_t)0x80000400) /*!< FPEC BANK2 error interrupt source */ +#define FLASH_IT_BANK2_EOP ((uint32_t)0x80001000) /*!< End of FLASH BANK2 Operation Interrupt source */ + +#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */ +#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */ + +#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC BANK1 error interrupt source */ +#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH BANK1 Operation Interrupt source */ +#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0x7FFFEBFF) == 0x00000000) && (((IT) != 0x00000000))) +#else +#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC error interrupt source */ +#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH Operation Interrupt source */ +#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */ +#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */ + +#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFFFFEBFF) == 0x00000000) && (((IT) != 0x00000000))) +#endif + +/** + * @} + */ + +/** @defgroup FLASH_Flags + * @{ + */ +#ifdef STM32F10X_XL +#define FLASH_FLAG_BANK2_BSY ((uint32_t)0x80000001) /*!< FLASH BANK2 Busy flag */ +#define FLASH_FLAG_BANK2_EOP ((uint32_t)0x80000020) /*!< FLASH BANK2 End of Operation flag */ +#define FLASH_FLAG_BANK2_PGERR ((uint32_t)0x80000004) /*!< FLASH BANK2 Program error flag */ +#define FLASH_FLAG_BANK2_WRPRTERR ((uint32_t)0x80000010) /*!< FLASH BANK2 Write protected error flag */ + +#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/ +#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */ +#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */ +#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */ + +#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */ +#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */ +#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */ +#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */ +#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */ + +#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0x7FFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000)) +#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \ + ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_OPTERR)|| \ + ((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \ + ((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_BANK2_BSY) || ((FLAG) == FLASH_FLAG_BANK2_EOP) || \ + ((FLAG) == FLASH_FLAG_BANK2_PGERR) || ((FLAG) == FLASH_FLAG_BANK2_WRPRTERR)) +#else +#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */ +#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */ +#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */ +#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */ +#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */ + +#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/ +#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */ +#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */ +#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */ + +#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000)) +#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \ + ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \ + ((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_OPTERR)) +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Functions + * @{ + */ + +/*------------ Functions used for all STM32F10x devices -----*/ +void FLASH_SetLatency(uint32_t FLASH_Latency); +void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess); +void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer); +void FLASH_Unlock(void); +void FLASH_Lock(void); +FLASH_Status FLASH_ErasePage(uint32_t Page_Address); +FLASH_Status FLASH_EraseAllPages(void); +FLASH_Status FLASH_EraseOptionBytes(void); +FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data); +FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data); +FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data); +FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages); +FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState); +FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY); +uint32_t FLASH_GetUserOptionByte(void); +uint32_t FLASH_GetWriteProtectionOptionByte(void); +FlagStatus FLASH_GetReadOutProtectionStatus(void); +FlagStatus FLASH_GetPrefetchBufferStatus(void); +void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState); +FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG); +void FLASH_ClearFlag(uint32_t FLASH_FLAG); +FLASH_Status FLASH_GetStatus(void); +FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout); + +/*------------ New function used for all STM32F10x devices -----*/ +void FLASH_UnlockBank1(void); +void FLASH_LockBank1(void); +FLASH_Status FLASH_EraseAllBank1Pages(void); +FLASH_Status FLASH_GetBank1Status(void); +FLASH_Status FLASH_WaitForLastBank1Operation(uint32_t Timeout); + +#ifdef STM32F10X_XL +/*---- New Functions used only with STM32F10x_XL density devices -----*/ +void FLASH_UnlockBank2(void); +void FLASH_LockBank2(void); +FLASH_Status FLASH_EraseAllBank2Pages(void); +FLASH_Status FLASH_GetBank2Status(void); +FLASH_Status FLASH_WaitForLastBank2Operation(uint32_t Timeout); +FLASH_Status FLASH_BootConfig(uint16_t FLASH_BOOT); +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_FLASH_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h index 9cf9847da..1fade96e8 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h @@ -1,732 +1,732 @@ -/** - ****************************************************************************** - * @file stm32f10x_fsmc.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the FSMC firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_FSMC_H -#define __STM32F10x_FSMC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup FSMC - * @{ - */ - -/** @defgroup FSMC_Exported_Types - * @{ - */ - -/** - * @brief Timing parameters For NOR/SRAM Banks - */ - -typedef struct -{ - uint32_t FSMC_AddressSetupTime; /*!< Defines the number of HCLK cycles to configure - the duration of the address setup time. - This parameter can be a value between 0 and 0xF. - @note: It is not used with synchronous NOR Flash memories. */ - - uint32_t FSMC_AddressHoldTime; /*!< Defines the number of HCLK cycles to configure - the duration of the address hold time. - This parameter can be a value between 0 and 0xF. - @note: It is not used with synchronous NOR Flash memories.*/ - - uint32_t FSMC_DataSetupTime; /*!< Defines the number of HCLK cycles to configure - the duration of the data setup time. - This parameter can be a value between 0 and 0xFF. - @note: It is used for SRAMs, ROMs and asynchronous multiplexed NOR Flash memories. */ - - uint32_t FSMC_BusTurnAroundDuration; /*!< Defines the number of HCLK cycles to configure - the duration of the bus turnaround. - This parameter can be a value between 0 and 0xF. - @note: It is only used for multiplexed NOR Flash memories. */ - - uint32_t FSMC_CLKDivision; /*!< Defines the period of CLK clock output signal, expressed in number of HCLK cycles. - This parameter can be a value between 1 and 0xF. - @note: This parameter is not used for asynchronous NOR Flash, SRAM or ROM accesses. */ - - uint32_t FSMC_DataLatency; /*!< Defines the number of memory clock cycles to issue - to the memory before getting the first data. - The value of this parameter depends on the memory type as shown below: - - It must be set to 0 in case of a CRAM - - It is don’t care in asynchronous NOR, SRAM or ROM accesses - - It may assume a value between 0 and 0xF in NOR Flash memories - with synchronous burst mode enable */ - - uint32_t FSMC_AccessMode; /*!< Specifies the asynchronous access mode. - This parameter can be a value of @ref FSMC_Access_Mode */ -}FSMC_NORSRAMTimingInitTypeDef; - -/** - * @brief FSMC NOR/SRAM Init structure definition - */ - -typedef struct -{ - uint32_t FSMC_Bank; /*!< Specifies the NOR/SRAM memory bank that will be used. - This parameter can be a value of @ref FSMC_NORSRAM_Bank */ - - uint32_t FSMC_DataAddressMux; /*!< Specifies whether the address and data values are - multiplexed on the databus or not. - This parameter can be a value of @ref FSMC_Data_Address_Bus_Multiplexing */ - - uint32_t FSMC_MemoryType; /*!< Specifies the type of external memory attached to - the corresponding memory bank. - This parameter can be a value of @ref FSMC_Memory_Type */ - - uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width. - This parameter can be a value of @ref FSMC_Data_Width */ - - uint32_t FSMC_BurstAccessMode; /*!< Enables or disables the burst access mode for Flash memory, - valid only with synchronous burst Flash memories. - This parameter can be a value of @ref FSMC_Burst_Access_Mode */ - - uint32_t FSMC_AsynchronousWait; /*!< Enables or disables wait signal during asynchronous transfers, - valid only with asynchronous Flash memories. - This parameter can be a value of @ref FSMC_AsynchronousWait */ - - uint32_t FSMC_WaitSignalPolarity; /*!< Specifies the wait signal polarity, valid only when accessing - the Flash memory in burst mode. - This parameter can be a value of @ref FSMC_Wait_Signal_Polarity */ - - uint32_t FSMC_WrapMode; /*!< Enables or disables the Wrapped burst access mode for Flash - memory, valid only when accessing Flash memories in burst mode. - This parameter can be a value of @ref FSMC_Wrap_Mode */ - - uint32_t FSMC_WaitSignalActive; /*!< Specifies if the wait signal is asserted by the memory one - clock cycle before the wait state or during the wait state, - valid only when accessing memories in burst mode. - This parameter can be a value of @ref FSMC_Wait_Timing */ - - uint32_t FSMC_WriteOperation; /*!< Enables or disables the write operation in the selected bank by the FSMC. - This parameter can be a value of @ref FSMC_Write_Operation */ - - uint32_t FSMC_WaitSignal; /*!< Enables or disables the wait-state insertion via wait - signal, valid for Flash memory access in burst mode. - This parameter can be a value of @ref FSMC_Wait_Signal */ - - uint32_t FSMC_ExtendedMode; /*!< Enables or disables the extended mode. - This parameter can be a value of @ref FSMC_Extended_Mode */ - - uint32_t FSMC_WriteBurst; /*!< Enables or disables the write burst operation. - This parameter can be a value of @ref FSMC_Write_Burst */ - - FSMC_NORSRAMTimingInitTypeDef* FSMC_ReadWriteTimingStruct; /*!< Timing Parameters for write and read access if the ExtendedMode is not used*/ - - FSMC_NORSRAMTimingInitTypeDef* FSMC_WriteTimingStruct; /*!< Timing Parameters for write access if the ExtendedMode is used*/ -}FSMC_NORSRAMInitTypeDef; - -/** - * @brief Timing parameters For FSMC NAND and PCCARD Banks - */ - -typedef struct -{ - uint32_t FSMC_SetupTime; /*!< Defines the number of HCLK cycles to setup address before - the command assertion for NAND-Flash read or write access - to common/Attribute or I/O memory space (depending on - the memory space timing to be configured). - This parameter can be a value between 0 and 0xFF.*/ - - uint32_t FSMC_WaitSetupTime; /*!< Defines the minimum number of HCLK cycles to assert the - command for NAND-Flash read or write access to - common/Attribute or I/O memory space (depending on the - memory space timing to be configured). - This parameter can be a number between 0x00 and 0xFF */ - - uint32_t FSMC_HoldSetupTime; /*!< Defines the number of HCLK clock cycles to hold address - (and data for write access) after the command deassertion - for NAND-Flash read or write access to common/Attribute - or I/O memory space (depending on the memory space timing - to be configured). - This parameter can be a number between 0x00 and 0xFF */ - - uint32_t FSMC_HiZSetupTime; /*!< Defines the number of HCLK clock cycles during which the - databus is kept in HiZ after the start of a NAND-Flash - write access to common/Attribute or I/O memory space (depending - on the memory space timing to be configured). - This parameter can be a number between 0x00 and 0xFF */ -}FSMC_NAND_PCCARDTimingInitTypeDef; - -/** - * @brief FSMC NAND Init structure definition - */ - -typedef struct -{ - uint32_t FSMC_Bank; /*!< Specifies the NAND memory bank that will be used. - This parameter can be a value of @ref FSMC_NAND_Bank */ - - uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the NAND Memory Bank. - This parameter can be any value of @ref FSMC_Wait_feature */ - - uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width. - This parameter can be any value of @ref FSMC_Data_Width */ - - uint32_t FSMC_ECC; /*!< Enables or disables the ECC computation. - This parameter can be any value of @ref FSMC_ECC */ - - uint32_t FSMC_ECCPageSize; /*!< Defines the page size for the extended ECC. - This parameter can be any value of @ref FSMC_ECC_Page_Size */ - - uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between CLE low and RE low. - This parameter can be a value between 0 and 0xFF. */ - - uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between ALE low and RE low. - This parameter can be a number between 0x0 and 0xFF */ - - FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */ - - FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */ -}FSMC_NANDInitTypeDef; - -/** - * @brief FSMC PCCARD Init structure definition - */ - -typedef struct -{ - uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the Memory Bank. - This parameter can be any value of @ref FSMC_Wait_feature */ - - uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between CLE low and RE low. - This parameter can be a value between 0 and 0xFF. */ - - uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between ALE low and RE low. - This parameter can be a number between 0x0 and 0xFF */ - - - FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */ - - FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */ - - FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_IOSpaceTimingStruct; /*!< FSMC IO Space Timing */ -}FSMC_PCCARDInitTypeDef; - -/** - * @} - */ - -/** @defgroup FSMC_Exported_Constants - * @{ - */ - -/** @defgroup FSMC_NORSRAM_Bank - * @{ - */ -#define FSMC_Bank1_NORSRAM1 ((uint32_t)0x00000000) -#define FSMC_Bank1_NORSRAM2 ((uint32_t)0x00000002) -#define FSMC_Bank1_NORSRAM3 ((uint32_t)0x00000004) -#define FSMC_Bank1_NORSRAM4 ((uint32_t)0x00000006) -/** - * @} - */ - -/** @defgroup FSMC_NAND_Bank - * @{ - */ -#define FSMC_Bank2_NAND ((uint32_t)0x00000010) -#define FSMC_Bank3_NAND ((uint32_t)0x00000100) -/** - * @} - */ - -/** @defgroup FSMC_PCCARD_Bank - * @{ - */ -#define FSMC_Bank4_PCCARD ((uint32_t)0x00001000) -/** - * @} - */ - -#define IS_FSMC_NORSRAM_BANK(BANK) (((BANK) == FSMC_Bank1_NORSRAM1) || \ - ((BANK) == FSMC_Bank1_NORSRAM2) || \ - ((BANK) == FSMC_Bank1_NORSRAM3) || \ - ((BANK) == FSMC_Bank1_NORSRAM4)) - -#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ - ((BANK) == FSMC_Bank3_NAND)) - -#define IS_FSMC_GETFLAG_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ - ((BANK) == FSMC_Bank3_NAND) || \ - ((BANK) == FSMC_Bank4_PCCARD)) - -#define IS_FSMC_IT_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ - ((BANK) == FSMC_Bank3_NAND) || \ - ((BANK) == FSMC_Bank4_PCCARD)) - -/** @defgroup NOR_SRAM_Controller - * @{ - */ - -/** @defgroup FSMC_Data_Address_Bus_Multiplexing - * @{ - */ - -#define FSMC_DataAddressMux_Disable ((uint32_t)0x00000000) -#define FSMC_DataAddressMux_Enable ((uint32_t)0x00000002) -#define IS_FSMC_MUX(MUX) (((MUX) == FSMC_DataAddressMux_Disable) || \ - ((MUX) == FSMC_DataAddressMux_Enable)) - -/** - * @} - */ - -/** @defgroup FSMC_Memory_Type - * @{ - */ - -#define FSMC_MemoryType_SRAM ((uint32_t)0x00000000) -#define FSMC_MemoryType_PSRAM ((uint32_t)0x00000004) -#define FSMC_MemoryType_NOR ((uint32_t)0x00000008) -#define IS_FSMC_MEMORY(MEMORY) (((MEMORY) == FSMC_MemoryType_SRAM) || \ - ((MEMORY) == FSMC_MemoryType_PSRAM)|| \ - ((MEMORY) == FSMC_MemoryType_NOR)) - -/** - * @} - */ - -/** @defgroup FSMC_Data_Width - * @{ - */ - -#define FSMC_MemoryDataWidth_8b ((uint32_t)0x00000000) -#define FSMC_MemoryDataWidth_16b ((uint32_t)0x00000010) -#define IS_FSMC_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \ - ((WIDTH) == FSMC_MemoryDataWidth_16b)) - -/** - * @} - */ - -/** @defgroup FSMC_Burst_Access_Mode - * @{ - */ - -#define FSMC_BurstAccessMode_Disable ((uint32_t)0x00000000) -#define FSMC_BurstAccessMode_Enable ((uint32_t)0x00000100) -#define IS_FSMC_BURSTMODE(STATE) (((STATE) == FSMC_BurstAccessMode_Disable) || \ - ((STATE) == FSMC_BurstAccessMode_Enable)) -/** - * @} - */ - -/** @defgroup FSMC_AsynchronousWait - * @{ - */ -#define FSMC_AsynchronousWait_Disable ((uint32_t)0x00000000) -#define FSMC_AsynchronousWait_Enable ((uint32_t)0x00008000) -#define IS_FSMC_ASYNWAIT(STATE) (((STATE) == FSMC_AsynchronousWait_Disable) || \ - ((STATE) == FSMC_AsynchronousWait_Enable)) - -/** - * @} - */ - -/** @defgroup FSMC_Wait_Signal_Polarity - * @{ - */ - -#define FSMC_WaitSignalPolarity_Low ((uint32_t)0x00000000) -#define FSMC_WaitSignalPolarity_High ((uint32_t)0x00000200) -#define IS_FSMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FSMC_WaitSignalPolarity_Low) || \ - ((POLARITY) == FSMC_WaitSignalPolarity_High)) - -/** - * @} - */ - -/** @defgroup FSMC_Wrap_Mode - * @{ - */ - -#define FSMC_WrapMode_Disable ((uint32_t)0x00000000) -#define FSMC_WrapMode_Enable ((uint32_t)0x00000400) -#define IS_FSMC_WRAP_MODE(MODE) (((MODE) == FSMC_WrapMode_Disable) || \ - ((MODE) == FSMC_WrapMode_Enable)) - -/** - * @} - */ - -/** @defgroup FSMC_Wait_Timing - * @{ - */ - -#define FSMC_WaitSignalActive_BeforeWaitState ((uint32_t)0x00000000) -#define FSMC_WaitSignalActive_DuringWaitState ((uint32_t)0x00000800) -#define IS_FSMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FSMC_WaitSignalActive_BeforeWaitState) || \ - ((ACTIVE) == FSMC_WaitSignalActive_DuringWaitState)) - -/** - * @} - */ - -/** @defgroup FSMC_Write_Operation - * @{ - */ - -#define FSMC_WriteOperation_Disable ((uint32_t)0x00000000) -#define FSMC_WriteOperation_Enable ((uint32_t)0x00001000) -#define IS_FSMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FSMC_WriteOperation_Disable) || \ - ((OPERATION) == FSMC_WriteOperation_Enable)) - -/** - * @} - */ - -/** @defgroup FSMC_Wait_Signal - * @{ - */ - -#define FSMC_WaitSignal_Disable ((uint32_t)0x00000000) -#define FSMC_WaitSignal_Enable ((uint32_t)0x00002000) -#define IS_FSMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FSMC_WaitSignal_Disable) || \ - ((SIGNAL) == FSMC_WaitSignal_Enable)) -/** - * @} - */ - -/** @defgroup FSMC_Extended_Mode - * @{ - */ - -#define FSMC_ExtendedMode_Disable ((uint32_t)0x00000000) -#define FSMC_ExtendedMode_Enable ((uint32_t)0x00004000) - -#define IS_FSMC_EXTENDED_MODE(MODE) (((MODE) == FSMC_ExtendedMode_Disable) || \ - ((MODE) == FSMC_ExtendedMode_Enable)) - -/** - * @} - */ - -/** @defgroup FSMC_Write_Burst - * @{ - */ - -#define FSMC_WriteBurst_Disable ((uint32_t)0x00000000) -#define FSMC_WriteBurst_Enable ((uint32_t)0x00080000) -#define IS_FSMC_WRITE_BURST(BURST) (((BURST) == FSMC_WriteBurst_Disable) || \ - ((BURST) == FSMC_WriteBurst_Enable)) -/** - * @} - */ - -/** @defgroup FSMC_Address_Setup_Time - * @{ - */ - -#define IS_FSMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 0xF) - -/** - * @} - */ - -/** @defgroup FSMC_Address_Hold_Time - * @{ - */ - -#define IS_FSMC_ADDRESS_HOLD_TIME(TIME) ((TIME) <= 0xF) - -/** - * @} - */ - -/** @defgroup FSMC_Data_Setup_Time - * @{ - */ - -#define IS_FSMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 0xFF)) - -/** - * @} - */ - -/** @defgroup FSMC_Bus_Turn_around_Duration - * @{ - */ - -#define IS_FSMC_TURNAROUND_TIME(TIME) ((TIME) <= 0xF) - -/** - * @} - */ - -/** @defgroup FSMC_CLK_Division - * @{ - */ - -#define IS_FSMC_CLK_DIV(DIV) ((DIV) <= 0xF) - -/** - * @} - */ - -/** @defgroup FSMC_Data_Latency - * @{ - */ - -#define IS_FSMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 0xF) - -/** - * @} - */ - -/** @defgroup FSMC_Access_Mode - * @{ - */ - -#define FSMC_AccessMode_A ((uint32_t)0x00000000) -#define FSMC_AccessMode_B ((uint32_t)0x10000000) -#define FSMC_AccessMode_C ((uint32_t)0x20000000) -#define FSMC_AccessMode_D ((uint32_t)0x30000000) -#define IS_FSMC_ACCESS_MODE(MODE) (((MODE) == FSMC_AccessMode_A) || \ - ((MODE) == FSMC_AccessMode_B) || \ - ((MODE) == FSMC_AccessMode_C) || \ - ((MODE) == FSMC_AccessMode_D)) - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup NAND_PCCARD_Controller - * @{ - */ - -/** @defgroup FSMC_Wait_feature - * @{ - */ - -#define FSMC_Waitfeature_Disable ((uint32_t)0x00000000) -#define FSMC_Waitfeature_Enable ((uint32_t)0x00000002) -#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_Waitfeature_Disable) || \ - ((FEATURE) == FSMC_Waitfeature_Enable)) - -/** - * @} - */ - - -/** @defgroup FSMC_ECC - * @{ - */ - -#define FSMC_ECC_Disable ((uint32_t)0x00000000) -#define FSMC_ECC_Enable ((uint32_t)0x00000040) -#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_ECC_Disable) || \ - ((STATE) == FSMC_ECC_Enable)) - -/** - * @} - */ - -/** @defgroup FSMC_ECC_Page_Size - * @{ - */ - -#define FSMC_ECCPageSize_256Bytes ((uint32_t)0x00000000) -#define FSMC_ECCPageSize_512Bytes ((uint32_t)0x00020000) -#define FSMC_ECCPageSize_1024Bytes ((uint32_t)0x00040000) -#define FSMC_ECCPageSize_2048Bytes ((uint32_t)0x00060000) -#define FSMC_ECCPageSize_4096Bytes ((uint32_t)0x00080000) -#define FSMC_ECCPageSize_8192Bytes ((uint32_t)0x000A0000) -#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_ECCPageSize_256Bytes) || \ - ((SIZE) == FSMC_ECCPageSize_512Bytes) || \ - ((SIZE) == FSMC_ECCPageSize_1024Bytes) || \ - ((SIZE) == FSMC_ECCPageSize_2048Bytes) || \ - ((SIZE) == FSMC_ECCPageSize_4096Bytes) || \ - ((SIZE) == FSMC_ECCPageSize_8192Bytes)) - -/** - * @} - */ - -/** @defgroup FSMC_TCLR_Setup_Time - * @{ - */ - -#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 0xFF) - -/** - * @} - */ - -/** @defgroup FSMC_TAR_Setup_Time - * @{ - */ - -#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 0xFF) - -/** - * @} - */ - -/** @defgroup FSMC_Setup_Time - * @{ - */ - -#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 0xFF) - -/** - * @} - */ - -/** @defgroup FSMC_Wait_Setup_Time - * @{ - */ - -#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 0xFF) - -/** - * @} - */ - -/** @defgroup FSMC_Hold_Setup_Time - * @{ - */ - -#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 0xFF) - -/** - * @} - */ - -/** @defgroup FSMC_HiZ_Setup_Time - * @{ - */ - -#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 0xFF) - -/** - * @} - */ - -/** @defgroup FSMC_Interrupt_sources - * @{ - */ - -#define FSMC_IT_RisingEdge ((uint32_t)0x00000008) -#define FSMC_IT_Level ((uint32_t)0x00000010) -#define FSMC_IT_FallingEdge ((uint32_t)0x00000020) -#define IS_FSMC_IT(IT) ((((IT) & (uint32_t)0xFFFFFFC7) == 0x00000000) && ((IT) != 0x00000000)) -#define IS_FSMC_GET_IT(IT) (((IT) == FSMC_IT_RisingEdge) || \ - ((IT) == FSMC_IT_Level) || \ - ((IT) == FSMC_IT_FallingEdge)) -/** - * @} - */ - -/** @defgroup FSMC_Flags - * @{ - */ - -#define FSMC_FLAG_RisingEdge ((uint32_t)0x00000001) -#define FSMC_FLAG_Level ((uint32_t)0x00000002) -#define FSMC_FLAG_FallingEdge ((uint32_t)0x00000004) -#define FSMC_FLAG_FEMPT ((uint32_t)0x00000040) -#define IS_FSMC_GET_FLAG(FLAG) (((FLAG) == FSMC_FLAG_RisingEdge) || \ - ((FLAG) == FSMC_FLAG_Level) || \ - ((FLAG) == FSMC_FLAG_FallingEdge) || \ - ((FLAG) == FSMC_FLAG_FEMPT)) - -#define IS_FSMC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000)) - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup FSMC_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup FSMC_Exported_Functions - * @{ - */ - -void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank); -void FSMC_NANDDeInit(uint32_t FSMC_Bank); -void FSMC_PCCARDDeInit(void); -void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct); -void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct); -void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct); -void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct); -void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct); -void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct); -void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState); -void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState); -void FSMC_PCCARDCmd(FunctionalState NewState); -void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState); -uint32_t FSMC_GetECC(uint32_t FSMC_Bank); -void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState); -FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG); -void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG); -ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT); -void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT); - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F10x_FSMC_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_fsmc.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the FSMC firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_FSMC_H +#define __STM32F10x_FSMC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup FSMC + * @{ + */ + +/** @defgroup FSMC_Exported_Types + * @{ + */ + +/** + * @brief Timing parameters For NOR/SRAM Banks + */ + +typedef struct +{ + uint32_t FSMC_AddressSetupTime; /*!< Defines the number of HCLK cycles to configure + the duration of the address setup time. + This parameter can be a value between 0 and 0xF. + @note: It is not used with synchronous NOR Flash memories. */ + + uint32_t FSMC_AddressHoldTime; /*!< Defines the number of HCLK cycles to configure + the duration of the address hold time. + This parameter can be a value between 0 and 0xF. + @note: It is not used with synchronous NOR Flash memories.*/ + + uint32_t FSMC_DataSetupTime; /*!< Defines the number of HCLK cycles to configure + the duration of the data setup time. + This parameter can be a value between 0 and 0xFF. + @note: It is used for SRAMs, ROMs and asynchronous multiplexed NOR Flash memories. */ + + uint32_t FSMC_BusTurnAroundDuration; /*!< Defines the number of HCLK cycles to configure + the duration of the bus turnaround. + This parameter can be a value between 0 and 0xF. + @note: It is only used for multiplexed NOR Flash memories. */ + + uint32_t FSMC_CLKDivision; /*!< Defines the period of CLK clock output signal, expressed in number of HCLK cycles. + This parameter can be a value between 1 and 0xF. + @note: This parameter is not used for asynchronous NOR Flash, SRAM or ROM accesses. */ + + uint32_t FSMC_DataLatency; /*!< Defines the number of memory clock cycles to issue + to the memory before getting the first data. + The value of this parameter depends on the memory type as shown below: + - It must be set to 0 in case of a CRAM + - It is don’t care in asynchronous NOR, SRAM or ROM accesses + - It may assume a value between 0 and 0xF in NOR Flash memories + with synchronous burst mode enable */ + + uint32_t FSMC_AccessMode; /*!< Specifies the asynchronous access mode. + This parameter can be a value of @ref FSMC_Access_Mode */ +}FSMC_NORSRAMTimingInitTypeDef; + +/** + * @brief FSMC NOR/SRAM Init structure definition + */ + +typedef struct +{ + uint32_t FSMC_Bank; /*!< Specifies the NOR/SRAM memory bank that will be used. + This parameter can be a value of @ref FSMC_NORSRAM_Bank */ + + uint32_t FSMC_DataAddressMux; /*!< Specifies whether the address and data values are + multiplexed on the databus or not. + This parameter can be a value of @ref FSMC_Data_Address_Bus_Multiplexing */ + + uint32_t FSMC_MemoryType; /*!< Specifies the type of external memory attached to + the corresponding memory bank. + This parameter can be a value of @ref FSMC_Memory_Type */ + + uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width. + This parameter can be a value of @ref FSMC_Data_Width */ + + uint32_t FSMC_BurstAccessMode; /*!< Enables or disables the burst access mode for Flash memory, + valid only with synchronous burst Flash memories. + This parameter can be a value of @ref FSMC_Burst_Access_Mode */ + + uint32_t FSMC_AsynchronousWait; /*!< Enables or disables wait signal during asynchronous transfers, + valid only with asynchronous Flash memories. + This parameter can be a value of @ref FSMC_AsynchronousWait */ + + uint32_t FSMC_WaitSignalPolarity; /*!< Specifies the wait signal polarity, valid only when accessing + the Flash memory in burst mode. + This parameter can be a value of @ref FSMC_Wait_Signal_Polarity */ + + uint32_t FSMC_WrapMode; /*!< Enables or disables the Wrapped burst access mode for Flash + memory, valid only when accessing Flash memories in burst mode. + This parameter can be a value of @ref FSMC_Wrap_Mode */ + + uint32_t FSMC_WaitSignalActive; /*!< Specifies if the wait signal is asserted by the memory one + clock cycle before the wait state or during the wait state, + valid only when accessing memories in burst mode. + This parameter can be a value of @ref FSMC_Wait_Timing */ + + uint32_t FSMC_WriteOperation; /*!< Enables or disables the write operation in the selected bank by the FSMC. + This parameter can be a value of @ref FSMC_Write_Operation */ + + uint32_t FSMC_WaitSignal; /*!< Enables or disables the wait-state insertion via wait + signal, valid for Flash memory access in burst mode. + This parameter can be a value of @ref FSMC_Wait_Signal */ + + uint32_t FSMC_ExtendedMode; /*!< Enables or disables the extended mode. + This parameter can be a value of @ref FSMC_Extended_Mode */ + + uint32_t FSMC_WriteBurst; /*!< Enables or disables the write burst operation. + This parameter can be a value of @ref FSMC_Write_Burst */ + + FSMC_NORSRAMTimingInitTypeDef* FSMC_ReadWriteTimingStruct; /*!< Timing Parameters for write and read access if the ExtendedMode is not used*/ + + FSMC_NORSRAMTimingInitTypeDef* FSMC_WriteTimingStruct; /*!< Timing Parameters for write access if the ExtendedMode is used*/ +}FSMC_NORSRAMInitTypeDef; + +/** + * @brief Timing parameters For FSMC NAND and PCCARD Banks + */ + +typedef struct +{ + uint32_t FSMC_SetupTime; /*!< Defines the number of HCLK cycles to setup address before + the command assertion for NAND-Flash read or write access + to common/Attribute or I/O memory space (depending on + the memory space timing to be configured). + This parameter can be a value between 0 and 0xFF.*/ + + uint32_t FSMC_WaitSetupTime; /*!< Defines the minimum number of HCLK cycles to assert the + command for NAND-Flash read or write access to + common/Attribute or I/O memory space (depending on the + memory space timing to be configured). + This parameter can be a number between 0x00 and 0xFF */ + + uint32_t FSMC_HoldSetupTime; /*!< Defines the number of HCLK clock cycles to hold address + (and data for write access) after the command deassertion + for NAND-Flash read or write access to common/Attribute + or I/O memory space (depending on the memory space timing + to be configured). + This parameter can be a number between 0x00 and 0xFF */ + + uint32_t FSMC_HiZSetupTime; /*!< Defines the number of HCLK clock cycles during which the + databus is kept in HiZ after the start of a NAND-Flash + write access to common/Attribute or I/O memory space (depending + on the memory space timing to be configured). + This parameter can be a number between 0x00 and 0xFF */ +}FSMC_NAND_PCCARDTimingInitTypeDef; + +/** + * @brief FSMC NAND Init structure definition + */ + +typedef struct +{ + uint32_t FSMC_Bank; /*!< Specifies the NAND memory bank that will be used. + This parameter can be a value of @ref FSMC_NAND_Bank */ + + uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the NAND Memory Bank. + This parameter can be any value of @ref FSMC_Wait_feature */ + + uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width. + This parameter can be any value of @ref FSMC_Data_Width */ + + uint32_t FSMC_ECC; /*!< Enables or disables the ECC computation. + This parameter can be any value of @ref FSMC_ECC */ + + uint32_t FSMC_ECCPageSize; /*!< Defines the page size for the extended ECC. + This parameter can be any value of @ref FSMC_ECC_Page_Size */ + + uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between CLE low and RE low. + This parameter can be a value between 0 and 0xFF. */ + + uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between ALE low and RE low. + This parameter can be a number between 0x0 and 0xFF */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */ +}FSMC_NANDInitTypeDef; + +/** + * @brief FSMC PCCARD Init structure definition + */ + +typedef struct +{ + uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the Memory Bank. + This parameter can be any value of @ref FSMC_Wait_feature */ + + uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between CLE low and RE low. + This parameter can be a value between 0 and 0xFF. */ + + uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between ALE low and RE low. + This parameter can be a number between 0x0 and 0xFF */ + + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_IOSpaceTimingStruct; /*!< FSMC IO Space Timing */ +}FSMC_PCCARDInitTypeDef; + +/** + * @} + */ + +/** @defgroup FSMC_Exported_Constants + * @{ + */ + +/** @defgroup FSMC_NORSRAM_Bank + * @{ + */ +#define FSMC_Bank1_NORSRAM1 ((uint32_t)0x00000000) +#define FSMC_Bank1_NORSRAM2 ((uint32_t)0x00000002) +#define FSMC_Bank1_NORSRAM3 ((uint32_t)0x00000004) +#define FSMC_Bank1_NORSRAM4 ((uint32_t)0x00000006) +/** + * @} + */ + +/** @defgroup FSMC_NAND_Bank + * @{ + */ +#define FSMC_Bank2_NAND ((uint32_t)0x00000010) +#define FSMC_Bank3_NAND ((uint32_t)0x00000100) +/** + * @} + */ + +/** @defgroup FSMC_PCCARD_Bank + * @{ + */ +#define FSMC_Bank4_PCCARD ((uint32_t)0x00001000) +/** + * @} + */ + +#define IS_FSMC_NORSRAM_BANK(BANK) (((BANK) == FSMC_Bank1_NORSRAM1) || \ + ((BANK) == FSMC_Bank1_NORSRAM2) || \ + ((BANK) == FSMC_Bank1_NORSRAM3) || \ + ((BANK) == FSMC_Bank1_NORSRAM4)) + +#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND)) + +#define IS_FSMC_GETFLAG_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND) || \ + ((BANK) == FSMC_Bank4_PCCARD)) + +#define IS_FSMC_IT_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND) || \ + ((BANK) == FSMC_Bank4_PCCARD)) + +/** @defgroup NOR_SRAM_Controller + * @{ + */ + +/** @defgroup FSMC_Data_Address_Bus_Multiplexing + * @{ + */ + +#define FSMC_DataAddressMux_Disable ((uint32_t)0x00000000) +#define FSMC_DataAddressMux_Enable ((uint32_t)0x00000002) +#define IS_FSMC_MUX(MUX) (((MUX) == FSMC_DataAddressMux_Disable) || \ + ((MUX) == FSMC_DataAddressMux_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Memory_Type + * @{ + */ + +#define FSMC_MemoryType_SRAM ((uint32_t)0x00000000) +#define FSMC_MemoryType_PSRAM ((uint32_t)0x00000004) +#define FSMC_MemoryType_NOR ((uint32_t)0x00000008) +#define IS_FSMC_MEMORY(MEMORY) (((MEMORY) == FSMC_MemoryType_SRAM) || \ + ((MEMORY) == FSMC_MemoryType_PSRAM)|| \ + ((MEMORY) == FSMC_MemoryType_NOR)) + +/** + * @} + */ + +/** @defgroup FSMC_Data_Width + * @{ + */ + +#define FSMC_MemoryDataWidth_8b ((uint32_t)0x00000000) +#define FSMC_MemoryDataWidth_16b ((uint32_t)0x00000010) +#define IS_FSMC_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \ + ((WIDTH) == FSMC_MemoryDataWidth_16b)) + +/** + * @} + */ + +/** @defgroup FSMC_Burst_Access_Mode + * @{ + */ + +#define FSMC_BurstAccessMode_Disable ((uint32_t)0x00000000) +#define FSMC_BurstAccessMode_Enable ((uint32_t)0x00000100) +#define IS_FSMC_BURSTMODE(STATE) (((STATE) == FSMC_BurstAccessMode_Disable) || \ + ((STATE) == FSMC_BurstAccessMode_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_AsynchronousWait + * @{ + */ +#define FSMC_AsynchronousWait_Disable ((uint32_t)0x00000000) +#define FSMC_AsynchronousWait_Enable ((uint32_t)0x00008000) +#define IS_FSMC_ASYNWAIT(STATE) (((STATE) == FSMC_AsynchronousWait_Disable) || \ + ((STATE) == FSMC_AsynchronousWait_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Signal_Polarity + * @{ + */ + +#define FSMC_WaitSignalPolarity_Low ((uint32_t)0x00000000) +#define FSMC_WaitSignalPolarity_High ((uint32_t)0x00000200) +#define IS_FSMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FSMC_WaitSignalPolarity_Low) || \ + ((POLARITY) == FSMC_WaitSignalPolarity_High)) + +/** + * @} + */ + +/** @defgroup FSMC_Wrap_Mode + * @{ + */ + +#define FSMC_WrapMode_Disable ((uint32_t)0x00000000) +#define FSMC_WrapMode_Enable ((uint32_t)0x00000400) +#define IS_FSMC_WRAP_MODE(MODE) (((MODE) == FSMC_WrapMode_Disable) || \ + ((MODE) == FSMC_WrapMode_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Timing + * @{ + */ + +#define FSMC_WaitSignalActive_BeforeWaitState ((uint32_t)0x00000000) +#define FSMC_WaitSignalActive_DuringWaitState ((uint32_t)0x00000800) +#define IS_FSMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FSMC_WaitSignalActive_BeforeWaitState) || \ + ((ACTIVE) == FSMC_WaitSignalActive_DuringWaitState)) + +/** + * @} + */ + +/** @defgroup FSMC_Write_Operation + * @{ + */ + +#define FSMC_WriteOperation_Disable ((uint32_t)0x00000000) +#define FSMC_WriteOperation_Enable ((uint32_t)0x00001000) +#define IS_FSMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FSMC_WriteOperation_Disable) || \ + ((OPERATION) == FSMC_WriteOperation_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Signal + * @{ + */ + +#define FSMC_WaitSignal_Disable ((uint32_t)0x00000000) +#define FSMC_WaitSignal_Enable ((uint32_t)0x00002000) +#define IS_FSMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FSMC_WaitSignal_Disable) || \ + ((SIGNAL) == FSMC_WaitSignal_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Extended_Mode + * @{ + */ + +#define FSMC_ExtendedMode_Disable ((uint32_t)0x00000000) +#define FSMC_ExtendedMode_Enable ((uint32_t)0x00004000) + +#define IS_FSMC_EXTENDED_MODE(MODE) (((MODE) == FSMC_ExtendedMode_Disable) || \ + ((MODE) == FSMC_ExtendedMode_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Write_Burst + * @{ + */ + +#define FSMC_WriteBurst_Disable ((uint32_t)0x00000000) +#define FSMC_WriteBurst_Enable ((uint32_t)0x00080000) +#define IS_FSMC_WRITE_BURST(BURST) (((BURST) == FSMC_WriteBurst_Disable) || \ + ((BURST) == FSMC_WriteBurst_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Address_Setup_Time + * @{ + */ + +#define IS_FSMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Address_Hold_Time + * @{ + */ + +#define IS_FSMC_ADDRESS_HOLD_TIME(TIME) ((TIME) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Data_Setup_Time + * @{ + */ + +#define IS_FSMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 0xFF)) + +/** + * @} + */ + +/** @defgroup FSMC_Bus_Turn_around_Duration + * @{ + */ + +#define IS_FSMC_TURNAROUND_TIME(TIME) ((TIME) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_CLK_Division + * @{ + */ + +#define IS_FSMC_CLK_DIV(DIV) ((DIV) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Data_Latency + * @{ + */ + +#define IS_FSMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Access_Mode + * @{ + */ + +#define FSMC_AccessMode_A ((uint32_t)0x00000000) +#define FSMC_AccessMode_B ((uint32_t)0x10000000) +#define FSMC_AccessMode_C ((uint32_t)0x20000000) +#define FSMC_AccessMode_D ((uint32_t)0x30000000) +#define IS_FSMC_ACCESS_MODE(MODE) (((MODE) == FSMC_AccessMode_A) || \ + ((MODE) == FSMC_AccessMode_B) || \ + ((MODE) == FSMC_AccessMode_C) || \ + ((MODE) == FSMC_AccessMode_D)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup NAND_PCCARD_Controller + * @{ + */ + +/** @defgroup FSMC_Wait_feature + * @{ + */ + +#define FSMC_Waitfeature_Disable ((uint32_t)0x00000000) +#define FSMC_Waitfeature_Enable ((uint32_t)0x00000002) +#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_Waitfeature_Disable) || \ + ((FEATURE) == FSMC_Waitfeature_Enable)) + +/** + * @} + */ + + +/** @defgroup FSMC_ECC + * @{ + */ + +#define FSMC_ECC_Disable ((uint32_t)0x00000000) +#define FSMC_ECC_Enable ((uint32_t)0x00000040) +#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_ECC_Disable) || \ + ((STATE) == FSMC_ECC_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_ECC_Page_Size + * @{ + */ + +#define FSMC_ECCPageSize_256Bytes ((uint32_t)0x00000000) +#define FSMC_ECCPageSize_512Bytes ((uint32_t)0x00020000) +#define FSMC_ECCPageSize_1024Bytes ((uint32_t)0x00040000) +#define FSMC_ECCPageSize_2048Bytes ((uint32_t)0x00060000) +#define FSMC_ECCPageSize_4096Bytes ((uint32_t)0x00080000) +#define FSMC_ECCPageSize_8192Bytes ((uint32_t)0x000A0000) +#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_ECCPageSize_256Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_512Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_1024Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_2048Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_4096Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_8192Bytes)) + +/** + * @} + */ + +/** @defgroup FSMC_TCLR_Setup_Time + * @{ + */ + +#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_TAR_Setup_Time + * @{ + */ + +#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Setup_Time + * @{ + */ + +#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Setup_Time + * @{ + */ + +#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Hold_Setup_Time + * @{ + */ + +#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_HiZ_Setup_Time + * @{ + */ + +#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Interrupt_sources + * @{ + */ + +#define FSMC_IT_RisingEdge ((uint32_t)0x00000008) +#define FSMC_IT_Level ((uint32_t)0x00000010) +#define FSMC_IT_FallingEdge ((uint32_t)0x00000020) +#define IS_FSMC_IT(IT) ((((IT) & (uint32_t)0xFFFFFFC7) == 0x00000000) && ((IT) != 0x00000000)) +#define IS_FSMC_GET_IT(IT) (((IT) == FSMC_IT_RisingEdge) || \ + ((IT) == FSMC_IT_Level) || \ + ((IT) == FSMC_IT_FallingEdge)) +/** + * @} + */ + +/** @defgroup FSMC_Flags + * @{ + */ + +#define FSMC_FLAG_RisingEdge ((uint32_t)0x00000001) +#define FSMC_FLAG_Level ((uint32_t)0x00000002) +#define FSMC_FLAG_FallingEdge ((uint32_t)0x00000004) +#define FSMC_FLAG_FEMPT ((uint32_t)0x00000040) +#define IS_FSMC_GET_FLAG(FLAG) (((FLAG) == FSMC_FLAG_RisingEdge) || \ + ((FLAG) == FSMC_FLAG_Level) || \ + ((FLAG) == FSMC_FLAG_FallingEdge) || \ + ((FLAG) == FSMC_FLAG_FEMPT)) + +#define IS_FSMC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000)) + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup FSMC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Exported_Functions + * @{ + */ + +void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank); +void FSMC_NANDDeInit(uint32_t FSMC_Bank); +void FSMC_PCCARDDeInit(void); +void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct); +void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct); +void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct); +void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct); +void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct); +void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct); +void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState); +void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState); +void FSMC_PCCARDCmd(FunctionalState NewState); +void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState); +uint32_t FSMC_GetECC(uint32_t FSMC_Bank); +void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState); +FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG); +void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG); +ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT); +void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_FSMC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h index 9cd50285e..1e655b537 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h @@ -1,384 +1,384 @@ -/** - ****************************************************************************** - * @file stm32f10x_gpio.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the GPIO - * firmware library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_GPIO_H -#define __STM32F10x_GPIO_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup GPIO - * @{ - */ - -/** @defgroup GPIO_Exported_Types - * @{ - */ - -#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \ - ((PERIPH) == GPIOB) || \ - ((PERIPH) == GPIOC) || \ - ((PERIPH) == GPIOD) || \ - ((PERIPH) == GPIOE) || \ - ((PERIPH) == GPIOF) || \ - ((PERIPH) == GPIOG)) - -/** - * @brief Output Maximum frequency selection - */ - -typedef enum -{ - GPIO_Speed_10MHz = 1, - GPIO_Speed_2MHz, - GPIO_Speed_50MHz -}GPIOSpeed_TypeDef; -#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_10MHz) || ((SPEED) == GPIO_Speed_2MHz) || \ - ((SPEED) == GPIO_Speed_50MHz)) - -/** - * @brief Configuration Mode enumeration - */ - -typedef enum -{ GPIO_Mode_AIN = 0x0, - GPIO_Mode_IN_FLOATING = 0x04, - GPIO_Mode_IPD = 0x28, - GPIO_Mode_IPU = 0x48, - GPIO_Mode_Out_OD = 0x14, - GPIO_Mode_Out_PP = 0x10, - GPIO_Mode_AF_OD = 0x1C, - GPIO_Mode_AF_PP = 0x18 -}GPIOMode_TypeDef; - -#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_AIN) || ((MODE) == GPIO_Mode_IN_FLOATING) || \ - ((MODE) == GPIO_Mode_IPD) || ((MODE) == GPIO_Mode_IPU) || \ - ((MODE) == GPIO_Mode_Out_OD) || ((MODE) == GPIO_Mode_Out_PP) || \ - ((MODE) == GPIO_Mode_AF_OD) || ((MODE) == GPIO_Mode_AF_PP)) - -/** - * @brief GPIO Init structure definition - */ - -typedef struct -{ - uint16_t GPIO_Pin; /*!< Specifies the GPIO pins to be configured. - This parameter can be any value of @ref GPIO_pins_define */ - - GPIOSpeed_TypeDef GPIO_Speed; /*!< Specifies the speed for the selected pins. - This parameter can be a value of @ref GPIOSpeed_TypeDef */ - - GPIOMode_TypeDef GPIO_Mode; /*!< Specifies the operating mode for the selected pins. - This parameter can be a value of @ref GPIOMode_TypeDef */ -}GPIO_InitTypeDef; - - -/** - * @brief Bit_SET and Bit_RESET enumeration - */ - -typedef enum -{ Bit_RESET = 0, - Bit_SET -}BitAction; - -#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET)) - -/** - * @} - */ - -/** @defgroup GPIO_Exported_Constants - * @{ - */ - -/** @defgroup GPIO_pins_define - * @{ - */ - -#define GPIO_Pin_0 ((uint16_t)0x0001) /*!< Pin 0 selected */ -#define GPIO_Pin_1 ((uint16_t)0x0002) /*!< Pin 1 selected */ -#define GPIO_Pin_2 ((uint16_t)0x0004) /*!< Pin 2 selected */ -#define GPIO_Pin_3 ((uint16_t)0x0008) /*!< Pin 3 selected */ -#define GPIO_Pin_4 ((uint16_t)0x0010) /*!< Pin 4 selected */ -#define GPIO_Pin_5 ((uint16_t)0x0020) /*!< Pin 5 selected */ -#define GPIO_Pin_6 ((uint16_t)0x0040) /*!< Pin 6 selected */ -#define GPIO_Pin_7 ((uint16_t)0x0080) /*!< Pin 7 selected */ -#define GPIO_Pin_8 ((uint16_t)0x0100) /*!< Pin 8 selected */ -#define GPIO_Pin_9 ((uint16_t)0x0200) /*!< Pin 9 selected */ -#define GPIO_Pin_10 ((uint16_t)0x0400) /*!< Pin 10 selected */ -#define GPIO_Pin_11 ((uint16_t)0x0800) /*!< Pin 11 selected */ -#define GPIO_Pin_12 ((uint16_t)0x1000) /*!< Pin 12 selected */ -#define GPIO_Pin_13 ((uint16_t)0x2000) /*!< Pin 13 selected */ -#define GPIO_Pin_14 ((uint16_t)0x4000) /*!< Pin 14 selected */ -#define GPIO_Pin_15 ((uint16_t)0x8000) /*!< Pin 15 selected */ -#define GPIO_Pin_All ((uint16_t)0xFFFF) /*!< All pins selected */ - -#define IS_GPIO_PIN(PIN) ((((PIN) & (uint16_t)0x00) == 0x00) && ((PIN) != (uint16_t)0x00)) - -#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \ - ((PIN) == GPIO_Pin_1) || \ - ((PIN) == GPIO_Pin_2) || \ - ((PIN) == GPIO_Pin_3) || \ - ((PIN) == GPIO_Pin_4) || \ - ((PIN) == GPIO_Pin_5) || \ - ((PIN) == GPIO_Pin_6) || \ - ((PIN) == GPIO_Pin_7) || \ - ((PIN) == GPIO_Pin_8) || \ - ((PIN) == GPIO_Pin_9) || \ - ((PIN) == GPIO_Pin_10) || \ - ((PIN) == GPIO_Pin_11) || \ - ((PIN) == GPIO_Pin_12) || \ - ((PIN) == GPIO_Pin_13) || \ - ((PIN) == GPIO_Pin_14) || \ - ((PIN) == GPIO_Pin_15)) - -/** - * @} - */ - -/** @defgroup GPIO_Remap_define - * @{ - */ - -#define GPIO_Remap_SPI1 ((uint32_t)0x00000001) /*!< SPI1 Alternate Function mapping */ -#define GPIO_Remap_I2C1 ((uint32_t)0x00000002) /*!< I2C1 Alternate Function mapping */ -#define GPIO_Remap_USART1 ((uint32_t)0x00000004) /*!< USART1 Alternate Function mapping */ -#define GPIO_Remap_USART2 ((uint32_t)0x00000008) /*!< USART2 Alternate Function mapping */ -#define GPIO_PartialRemap_USART3 ((uint32_t)0x00140010) /*!< USART3 Partial Alternate Function mapping */ -#define GPIO_FullRemap_USART3 ((uint32_t)0x00140030) /*!< USART3 Full Alternate Function mapping */ -#define GPIO_PartialRemap_TIM1 ((uint32_t)0x00160040) /*!< TIM1 Partial Alternate Function mapping */ -#define GPIO_FullRemap_TIM1 ((uint32_t)0x001600C0) /*!< TIM1 Full Alternate Function mapping */ -#define GPIO_PartialRemap1_TIM2 ((uint32_t)0x00180100) /*!< TIM2 Partial1 Alternate Function mapping */ -#define GPIO_PartialRemap2_TIM2 ((uint32_t)0x00180200) /*!< TIM2 Partial2 Alternate Function mapping */ -#define GPIO_FullRemap_TIM2 ((uint32_t)0x00180300) /*!< TIM2 Full Alternate Function mapping */ -#define GPIO_PartialRemap_TIM3 ((uint32_t)0x001A0800) /*!< TIM3 Partial Alternate Function mapping */ -#define GPIO_FullRemap_TIM3 ((uint32_t)0x001A0C00) /*!< TIM3 Full Alternate Function mapping */ -#define GPIO_Remap_TIM4 ((uint32_t)0x00001000) /*!< TIM4 Alternate Function mapping */ -#define GPIO_Remap1_CAN1 ((uint32_t)0x001D4000) /*!< CAN1 Alternate Function mapping */ -#define GPIO_Remap2_CAN1 ((uint32_t)0x001D6000) /*!< CAN1 Alternate Function mapping */ -#define GPIO_Remap_PD01 ((uint32_t)0x00008000) /*!< PD01 Alternate Function mapping */ -#define GPIO_Remap_TIM5CH4_LSI ((uint32_t)0x00200001) /*!< LSI connected to TIM5 Channel4 input capture for calibration */ -#define GPIO_Remap_ADC1_ETRGINJ ((uint32_t)0x00200002) /*!< ADC1 External Trigger Injected Conversion remapping */ -#define GPIO_Remap_ADC1_ETRGREG ((uint32_t)0x00200004) /*!< ADC1 External Trigger Regular Conversion remapping */ -#define GPIO_Remap_ADC2_ETRGINJ ((uint32_t)0x00200008) /*!< ADC2 External Trigger Injected Conversion remapping */ -#define GPIO_Remap_ADC2_ETRGREG ((uint32_t)0x00200010) /*!< ADC2 External Trigger Regular Conversion remapping */ -#define GPIO_Remap_ETH ((uint32_t)0x00200020) /*!< Ethernet remapping (only for Connectivity line devices) */ -#define GPIO_Remap_CAN2 ((uint32_t)0x00200040) /*!< CAN2 remapping (only for Connectivity line devices) */ -#define GPIO_Remap_SWJ_NoJTRST ((uint32_t)0x00300100) /*!< Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST */ -#define GPIO_Remap_SWJ_JTAGDisable ((uint32_t)0x00300200) /*!< JTAG-DP Disabled and SW-DP Enabled */ -#define GPIO_Remap_SWJ_Disable ((uint32_t)0x00300400) /*!< Full SWJ Disabled (JTAG-DP + SW-DP) */ -#define GPIO_Remap_SPI3 ((uint32_t)0x00201000) /*!< SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices) */ -#define GPIO_Remap_TIM2ITR1_PTP_SOF ((uint32_t)0x00202000) /*!< Ethernet PTP output or USB OTG SOF (Start of Frame) connected - to TIM2 Internal Trigger 1 for calibration - (only for Connectivity line devices) */ -#define GPIO_Remap_PTP_PPS ((uint32_t)0x00204000) /*!< Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) */ - -#define GPIO_Remap_TIM15 ((uint32_t)0x80000001) /*!< TIM15 Alternate Function mapping (only for Value line devices) */ -#define GPIO_Remap_TIM16 ((uint32_t)0x80000002) /*!< TIM16 Alternate Function mapping (only for Value line devices) */ -#define GPIO_Remap_TIM17 ((uint32_t)0x80000004) /*!< TIM17 Alternate Function mapping (only for Value line devices) */ -#define GPIO_Remap_CEC ((uint32_t)0x80000008) /*!< CEC Alternate Function mapping (only for Value line devices) */ -#define GPIO_Remap_TIM1_DMA ((uint32_t)0x80000010) /*!< TIM1 DMA requests mapping (only for Value line devices) */ - -#define GPIO_Remap_TIM9 ((uint32_t)0x80000020) /*!< TIM9 Alternate Function mapping (only for XL-density devices) */ -#define GPIO_Remap_TIM10 ((uint32_t)0x80000040) /*!< TIM10 Alternate Function mapping (only for XL-density devices) */ -#define GPIO_Remap_TIM11 ((uint32_t)0x80000080) /*!< TIM11 Alternate Function mapping (only for XL-density devices) */ -#define GPIO_Remap_TIM13 ((uint32_t)0x80000100) /*!< TIM13 Alternate Function mapping (only for High density Value line and XL-density devices) */ -#define GPIO_Remap_TIM14 ((uint32_t)0x80000200) /*!< TIM14 Alternate Function mapping (only for High density Value line and XL-density devices) */ -#define GPIO_Remap_FSMC_NADV ((uint32_t)0x80000400) /*!< FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices) */ - -#define GPIO_Remap_TIM67_DAC_DMA ((uint32_t)0x80000800) /*!< TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices) */ -#define GPIO_Remap_TIM12 ((uint32_t)0x80001000) /*!< TIM12 Alternate Function mapping (only for High density Value line devices) */ -#define GPIO_Remap_MISC ((uint32_t)0x80002000) /*!< Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping, - only for High density Value line devices) */ - -#define IS_GPIO_REMAP(REMAP) (((REMAP) == GPIO_Remap_SPI1) || ((REMAP) == GPIO_Remap_I2C1) || \ - ((REMAP) == GPIO_Remap_USART1) || ((REMAP) == GPIO_Remap_USART2) || \ - ((REMAP) == GPIO_PartialRemap_USART3) || ((REMAP) == GPIO_FullRemap_USART3) || \ - ((REMAP) == GPIO_PartialRemap_TIM1) || ((REMAP) == GPIO_FullRemap_TIM1) || \ - ((REMAP) == GPIO_PartialRemap1_TIM2) || ((REMAP) == GPIO_PartialRemap2_TIM2) || \ - ((REMAP) == GPIO_FullRemap_TIM2) || ((REMAP) == GPIO_PartialRemap_TIM3) || \ - ((REMAP) == GPIO_FullRemap_TIM3) || ((REMAP) == GPIO_Remap_TIM4) || \ - ((REMAP) == GPIO_Remap1_CAN1) || ((REMAP) == GPIO_Remap2_CAN1) || \ - ((REMAP) == GPIO_Remap_PD01) || ((REMAP) == GPIO_Remap_TIM5CH4_LSI) || \ - ((REMAP) == GPIO_Remap_ADC1_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC1_ETRGREG) || \ - ((REMAP) == GPIO_Remap_ADC2_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC2_ETRGREG) || \ - ((REMAP) == GPIO_Remap_ETH) ||((REMAP) == GPIO_Remap_CAN2) || \ - ((REMAP) == GPIO_Remap_SWJ_NoJTRST) || ((REMAP) == GPIO_Remap_SWJ_JTAGDisable) || \ - ((REMAP) == GPIO_Remap_SWJ_Disable)|| ((REMAP) == GPIO_Remap_SPI3) || \ - ((REMAP) == GPIO_Remap_TIM2ITR1_PTP_SOF) || ((REMAP) == GPIO_Remap_PTP_PPS) || \ - ((REMAP) == GPIO_Remap_TIM15) || ((REMAP) == GPIO_Remap_TIM16) || \ - ((REMAP) == GPIO_Remap_TIM17) || ((REMAP) == GPIO_Remap_CEC) || \ - ((REMAP) == GPIO_Remap_TIM1_DMA) || ((REMAP) == GPIO_Remap_TIM9) || \ - ((REMAP) == GPIO_Remap_TIM10) || ((REMAP) == GPIO_Remap_TIM11) || \ - ((REMAP) == GPIO_Remap_TIM13) || ((REMAP) == GPIO_Remap_TIM14) || \ - ((REMAP) == GPIO_Remap_FSMC_NADV) || ((REMAP) == GPIO_Remap_TIM67_DAC_DMA) || \ - ((REMAP) == GPIO_Remap_TIM12) || ((REMAP) == GPIO_Remap_MISC)) - -/** - * @} - */ - -/** @defgroup GPIO_Port_Sources - * @{ - */ - -#define GPIO_PortSourceGPIOA ((uint8_t)0x00) -#define GPIO_PortSourceGPIOB ((uint8_t)0x01) -#define GPIO_PortSourceGPIOC ((uint8_t)0x02) -#define GPIO_PortSourceGPIOD ((uint8_t)0x03) -#define GPIO_PortSourceGPIOE ((uint8_t)0x04) -#define GPIO_PortSourceGPIOF ((uint8_t)0x05) -#define GPIO_PortSourceGPIOG ((uint8_t)0x06) -#define IS_GPIO_EVENTOUT_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \ - ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \ - ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \ - ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \ - ((PORTSOURCE) == GPIO_PortSourceGPIOE)) - -#define IS_GPIO_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \ - ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \ - ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \ - ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \ - ((PORTSOURCE) == GPIO_PortSourceGPIOE) || \ - ((PORTSOURCE) == GPIO_PortSourceGPIOF) || \ - ((PORTSOURCE) == GPIO_PortSourceGPIOG)) - -/** - * @} - */ - -/** @defgroup GPIO_Pin_sources - * @{ - */ - -#define GPIO_PinSource0 ((uint8_t)0x00) -#define GPIO_PinSource1 ((uint8_t)0x01) -#define GPIO_PinSource2 ((uint8_t)0x02) -#define GPIO_PinSource3 ((uint8_t)0x03) -#define GPIO_PinSource4 ((uint8_t)0x04) -#define GPIO_PinSource5 ((uint8_t)0x05) -#define GPIO_PinSource6 ((uint8_t)0x06) -#define GPIO_PinSource7 ((uint8_t)0x07) -#define GPIO_PinSource8 ((uint8_t)0x08) -#define GPIO_PinSource9 ((uint8_t)0x09) -#define GPIO_PinSource10 ((uint8_t)0x0A) -#define GPIO_PinSource11 ((uint8_t)0x0B) -#define GPIO_PinSource12 ((uint8_t)0x0C) -#define GPIO_PinSource13 ((uint8_t)0x0D) -#define GPIO_PinSource14 ((uint8_t)0x0E) -#define GPIO_PinSource15 ((uint8_t)0x0F) - -#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \ - ((PINSOURCE) == GPIO_PinSource1) || \ - ((PINSOURCE) == GPIO_PinSource2) || \ - ((PINSOURCE) == GPIO_PinSource3) || \ - ((PINSOURCE) == GPIO_PinSource4) || \ - ((PINSOURCE) == GPIO_PinSource5) || \ - ((PINSOURCE) == GPIO_PinSource6) || \ - ((PINSOURCE) == GPIO_PinSource7) || \ - ((PINSOURCE) == GPIO_PinSource8) || \ - ((PINSOURCE) == GPIO_PinSource9) || \ - ((PINSOURCE) == GPIO_PinSource10) || \ - ((PINSOURCE) == GPIO_PinSource11) || \ - ((PINSOURCE) == GPIO_PinSource12) || \ - ((PINSOURCE) == GPIO_PinSource13) || \ - ((PINSOURCE) == GPIO_PinSource14) || \ - ((PINSOURCE) == GPIO_PinSource15)) - -/** - * @} - */ - -/** @defgroup Ethernet_Media_Interface - * @{ - */ -#define GPIO_ETH_MediaInterface_MII ((u32)0x00000000) -#define GPIO_ETH_MediaInterface_RMII ((u32)0x00000001) - -#define IS_GPIO_ETH_MEDIA_INTERFACE(INTERFACE) (((INTERFACE) == GPIO_ETH_MediaInterface_MII) || \ - ((INTERFACE) == GPIO_ETH_MediaInterface_RMII)) - -/** - * @} - */ -/** - * @} - */ - -/** @defgroup GPIO_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup GPIO_Exported_Functions - * @{ - */ - -void GPIO_DeInit(GPIO_TypeDef* GPIOx); -void GPIO_AFIODeInit(void); -void GPIO_Init(GPIO_TypeDef* GPIOx, const GPIO_InitTypeDef* GPIO_InitStruct); -void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct); -uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx); -uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx); -void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal); -void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal); -void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource); -void GPIO_EventOutputCmd(FunctionalState NewState); -void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState); -void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource); -void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_GPIO_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_gpio.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the GPIO + * firmware library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_GPIO_H +#define __STM32F10x_GPIO_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup GPIO + * @{ + */ + +/** @defgroup GPIO_Exported_Types + * @{ + */ + +#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \ + ((PERIPH) == GPIOB) || \ + ((PERIPH) == GPIOC) || \ + ((PERIPH) == GPIOD) || \ + ((PERIPH) == GPIOE) || \ + ((PERIPH) == GPIOF) || \ + ((PERIPH) == GPIOG)) + +/** + * @brief Output Maximum frequency selection + */ + +typedef enum +{ + GPIO_Speed_10MHz = 1, + GPIO_Speed_2MHz, + GPIO_Speed_50MHz +}GPIOSpeed_TypeDef; +#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_10MHz) || ((SPEED) == GPIO_Speed_2MHz) || \ + ((SPEED) == GPIO_Speed_50MHz)) + +/** + * @brief Configuration Mode enumeration + */ + +typedef enum +{ GPIO_Mode_AIN = 0x0, + GPIO_Mode_IN_FLOATING = 0x04, + GPIO_Mode_IPD = 0x28, + GPIO_Mode_IPU = 0x48, + GPIO_Mode_Out_OD = 0x14, + GPIO_Mode_Out_PP = 0x10, + GPIO_Mode_AF_OD = 0x1C, + GPIO_Mode_AF_PP = 0x18 +}GPIOMode_TypeDef; + +#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_AIN) || ((MODE) == GPIO_Mode_IN_FLOATING) || \ + ((MODE) == GPIO_Mode_IPD) || ((MODE) == GPIO_Mode_IPU) || \ + ((MODE) == GPIO_Mode_Out_OD) || ((MODE) == GPIO_Mode_Out_PP) || \ + ((MODE) == GPIO_Mode_AF_OD) || ((MODE) == GPIO_Mode_AF_PP)) + +/** + * @brief GPIO Init structure definition + */ + +typedef struct +{ + uint16_t GPIO_Pin; /*!< Specifies the GPIO pins to be configured. + This parameter can be any value of @ref GPIO_pins_define */ + + GPIOSpeed_TypeDef GPIO_Speed; /*!< Specifies the speed for the selected pins. + This parameter can be a value of @ref GPIOSpeed_TypeDef */ + + GPIOMode_TypeDef GPIO_Mode; /*!< Specifies the operating mode for the selected pins. + This parameter can be a value of @ref GPIOMode_TypeDef */ +}GPIO_InitTypeDef; + + +/** + * @brief Bit_SET and Bit_RESET enumeration + */ + +typedef enum +{ Bit_RESET = 0, + Bit_SET +}BitAction; + +#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET)) + +/** + * @} + */ + +/** @defgroup GPIO_Exported_Constants + * @{ + */ + +/** @defgroup GPIO_pins_define + * @{ + */ + +#define GPIO_Pin_0 ((uint16_t)0x0001) /*!< Pin 0 selected */ +#define GPIO_Pin_1 ((uint16_t)0x0002) /*!< Pin 1 selected */ +#define GPIO_Pin_2 ((uint16_t)0x0004) /*!< Pin 2 selected */ +#define GPIO_Pin_3 ((uint16_t)0x0008) /*!< Pin 3 selected */ +#define GPIO_Pin_4 ((uint16_t)0x0010) /*!< Pin 4 selected */ +#define GPIO_Pin_5 ((uint16_t)0x0020) /*!< Pin 5 selected */ +#define GPIO_Pin_6 ((uint16_t)0x0040) /*!< Pin 6 selected */ +#define GPIO_Pin_7 ((uint16_t)0x0080) /*!< Pin 7 selected */ +#define GPIO_Pin_8 ((uint16_t)0x0100) /*!< Pin 8 selected */ +#define GPIO_Pin_9 ((uint16_t)0x0200) /*!< Pin 9 selected */ +#define GPIO_Pin_10 ((uint16_t)0x0400) /*!< Pin 10 selected */ +#define GPIO_Pin_11 ((uint16_t)0x0800) /*!< Pin 11 selected */ +#define GPIO_Pin_12 ((uint16_t)0x1000) /*!< Pin 12 selected */ +#define GPIO_Pin_13 ((uint16_t)0x2000) /*!< Pin 13 selected */ +#define GPIO_Pin_14 ((uint16_t)0x4000) /*!< Pin 14 selected */ +#define GPIO_Pin_15 ((uint16_t)0x8000) /*!< Pin 15 selected */ +#define GPIO_Pin_All ((uint16_t)0xFFFF) /*!< All pins selected */ + +#define IS_GPIO_PIN(PIN) ((((PIN) & (uint16_t)0x00) == 0x00) && ((PIN) != (uint16_t)0x00)) + +#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \ + ((PIN) == GPIO_Pin_1) || \ + ((PIN) == GPIO_Pin_2) || \ + ((PIN) == GPIO_Pin_3) || \ + ((PIN) == GPIO_Pin_4) || \ + ((PIN) == GPIO_Pin_5) || \ + ((PIN) == GPIO_Pin_6) || \ + ((PIN) == GPIO_Pin_7) || \ + ((PIN) == GPIO_Pin_8) || \ + ((PIN) == GPIO_Pin_9) || \ + ((PIN) == GPIO_Pin_10) || \ + ((PIN) == GPIO_Pin_11) || \ + ((PIN) == GPIO_Pin_12) || \ + ((PIN) == GPIO_Pin_13) || \ + ((PIN) == GPIO_Pin_14) || \ + ((PIN) == GPIO_Pin_15)) + +/** + * @} + */ + +/** @defgroup GPIO_Remap_define + * @{ + */ + +#define GPIO_Remap_SPI1 ((uint32_t)0x00000001) /*!< SPI1 Alternate Function mapping */ +#define GPIO_Remap_I2C1 ((uint32_t)0x00000002) /*!< I2C1 Alternate Function mapping */ +#define GPIO_Remap_USART1 ((uint32_t)0x00000004) /*!< USART1 Alternate Function mapping */ +#define GPIO_Remap_USART2 ((uint32_t)0x00000008) /*!< USART2 Alternate Function mapping */ +#define GPIO_PartialRemap_USART3 ((uint32_t)0x00140010) /*!< USART3 Partial Alternate Function mapping */ +#define GPIO_FullRemap_USART3 ((uint32_t)0x00140030) /*!< USART3 Full Alternate Function mapping */ +#define GPIO_PartialRemap_TIM1 ((uint32_t)0x00160040) /*!< TIM1 Partial Alternate Function mapping */ +#define GPIO_FullRemap_TIM1 ((uint32_t)0x001600C0) /*!< TIM1 Full Alternate Function mapping */ +#define GPIO_PartialRemap1_TIM2 ((uint32_t)0x00180100) /*!< TIM2 Partial1 Alternate Function mapping */ +#define GPIO_PartialRemap2_TIM2 ((uint32_t)0x00180200) /*!< TIM2 Partial2 Alternate Function mapping */ +#define GPIO_FullRemap_TIM2 ((uint32_t)0x00180300) /*!< TIM2 Full Alternate Function mapping */ +#define GPIO_PartialRemap_TIM3 ((uint32_t)0x001A0800) /*!< TIM3 Partial Alternate Function mapping */ +#define GPIO_FullRemap_TIM3 ((uint32_t)0x001A0C00) /*!< TIM3 Full Alternate Function mapping */ +#define GPIO_Remap_TIM4 ((uint32_t)0x00001000) /*!< TIM4 Alternate Function mapping */ +#define GPIO_Remap1_CAN1 ((uint32_t)0x001D4000) /*!< CAN1 Alternate Function mapping */ +#define GPIO_Remap2_CAN1 ((uint32_t)0x001D6000) /*!< CAN1 Alternate Function mapping */ +#define GPIO_Remap_PD01 ((uint32_t)0x00008000) /*!< PD01 Alternate Function mapping */ +#define GPIO_Remap_TIM5CH4_LSI ((uint32_t)0x00200001) /*!< LSI connected to TIM5 Channel4 input capture for calibration */ +#define GPIO_Remap_ADC1_ETRGINJ ((uint32_t)0x00200002) /*!< ADC1 External Trigger Injected Conversion remapping */ +#define GPIO_Remap_ADC1_ETRGREG ((uint32_t)0x00200004) /*!< ADC1 External Trigger Regular Conversion remapping */ +#define GPIO_Remap_ADC2_ETRGINJ ((uint32_t)0x00200008) /*!< ADC2 External Trigger Injected Conversion remapping */ +#define GPIO_Remap_ADC2_ETRGREG ((uint32_t)0x00200010) /*!< ADC2 External Trigger Regular Conversion remapping */ +#define GPIO_Remap_ETH ((uint32_t)0x00200020) /*!< Ethernet remapping (only for Connectivity line devices) */ +#define GPIO_Remap_CAN2 ((uint32_t)0x00200040) /*!< CAN2 remapping (only for Connectivity line devices) */ +#define GPIO_Remap_SWJ_NoJTRST ((uint32_t)0x00300100) /*!< Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST */ +#define GPIO_Remap_SWJ_JTAGDisable ((uint32_t)0x00300200) /*!< JTAG-DP Disabled and SW-DP Enabled */ +#define GPIO_Remap_SWJ_Disable ((uint32_t)0x00300400) /*!< Full SWJ Disabled (JTAG-DP + SW-DP) */ +#define GPIO_Remap_SPI3 ((uint32_t)0x00201000) /*!< SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices) */ +#define GPIO_Remap_TIM2ITR1_PTP_SOF ((uint32_t)0x00202000) /*!< Ethernet PTP output or USB OTG SOF (Start of Frame) connected + to TIM2 Internal Trigger 1 for calibration + (only for Connectivity line devices) */ +#define GPIO_Remap_PTP_PPS ((uint32_t)0x00204000) /*!< Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) */ + +#define GPIO_Remap_TIM15 ((uint32_t)0x80000001) /*!< TIM15 Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_TIM16 ((uint32_t)0x80000002) /*!< TIM16 Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_TIM17 ((uint32_t)0x80000004) /*!< TIM17 Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_CEC ((uint32_t)0x80000008) /*!< CEC Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_TIM1_DMA ((uint32_t)0x80000010) /*!< TIM1 DMA requests mapping (only for Value line devices) */ + +#define GPIO_Remap_TIM9 ((uint32_t)0x80000020) /*!< TIM9 Alternate Function mapping (only for XL-density devices) */ +#define GPIO_Remap_TIM10 ((uint32_t)0x80000040) /*!< TIM10 Alternate Function mapping (only for XL-density devices) */ +#define GPIO_Remap_TIM11 ((uint32_t)0x80000080) /*!< TIM11 Alternate Function mapping (only for XL-density devices) */ +#define GPIO_Remap_TIM13 ((uint32_t)0x80000100) /*!< TIM13 Alternate Function mapping (only for High density Value line and XL-density devices) */ +#define GPIO_Remap_TIM14 ((uint32_t)0x80000200) /*!< TIM14 Alternate Function mapping (only for High density Value line and XL-density devices) */ +#define GPIO_Remap_FSMC_NADV ((uint32_t)0x80000400) /*!< FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices) */ + +#define GPIO_Remap_TIM67_DAC_DMA ((uint32_t)0x80000800) /*!< TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices) */ +#define GPIO_Remap_TIM12 ((uint32_t)0x80001000) /*!< TIM12 Alternate Function mapping (only for High density Value line devices) */ +#define GPIO_Remap_MISC ((uint32_t)0x80002000) /*!< Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping, + only for High density Value line devices) */ + +#define IS_GPIO_REMAP(REMAP) (((REMAP) == GPIO_Remap_SPI1) || ((REMAP) == GPIO_Remap_I2C1) || \ + ((REMAP) == GPIO_Remap_USART1) || ((REMAP) == GPIO_Remap_USART2) || \ + ((REMAP) == GPIO_PartialRemap_USART3) || ((REMAP) == GPIO_FullRemap_USART3) || \ + ((REMAP) == GPIO_PartialRemap_TIM1) || ((REMAP) == GPIO_FullRemap_TIM1) || \ + ((REMAP) == GPIO_PartialRemap1_TIM2) || ((REMAP) == GPIO_PartialRemap2_TIM2) || \ + ((REMAP) == GPIO_FullRemap_TIM2) || ((REMAP) == GPIO_PartialRemap_TIM3) || \ + ((REMAP) == GPIO_FullRemap_TIM3) || ((REMAP) == GPIO_Remap_TIM4) || \ + ((REMAP) == GPIO_Remap1_CAN1) || ((REMAP) == GPIO_Remap2_CAN1) || \ + ((REMAP) == GPIO_Remap_PD01) || ((REMAP) == GPIO_Remap_TIM5CH4_LSI) || \ + ((REMAP) == GPIO_Remap_ADC1_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC1_ETRGREG) || \ + ((REMAP) == GPIO_Remap_ADC2_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC2_ETRGREG) || \ + ((REMAP) == GPIO_Remap_ETH) ||((REMAP) == GPIO_Remap_CAN2) || \ + ((REMAP) == GPIO_Remap_SWJ_NoJTRST) || ((REMAP) == GPIO_Remap_SWJ_JTAGDisable) || \ + ((REMAP) == GPIO_Remap_SWJ_Disable)|| ((REMAP) == GPIO_Remap_SPI3) || \ + ((REMAP) == GPIO_Remap_TIM2ITR1_PTP_SOF) || ((REMAP) == GPIO_Remap_PTP_PPS) || \ + ((REMAP) == GPIO_Remap_TIM15) || ((REMAP) == GPIO_Remap_TIM16) || \ + ((REMAP) == GPIO_Remap_TIM17) || ((REMAP) == GPIO_Remap_CEC) || \ + ((REMAP) == GPIO_Remap_TIM1_DMA) || ((REMAP) == GPIO_Remap_TIM9) || \ + ((REMAP) == GPIO_Remap_TIM10) || ((REMAP) == GPIO_Remap_TIM11) || \ + ((REMAP) == GPIO_Remap_TIM13) || ((REMAP) == GPIO_Remap_TIM14) || \ + ((REMAP) == GPIO_Remap_FSMC_NADV) || ((REMAP) == GPIO_Remap_TIM67_DAC_DMA) || \ + ((REMAP) == GPIO_Remap_TIM12) || ((REMAP) == GPIO_Remap_MISC)) + +/** + * @} + */ + +/** @defgroup GPIO_Port_Sources + * @{ + */ + +#define GPIO_PortSourceGPIOA ((uint8_t)0x00) +#define GPIO_PortSourceGPIOB ((uint8_t)0x01) +#define GPIO_PortSourceGPIOC ((uint8_t)0x02) +#define GPIO_PortSourceGPIOD ((uint8_t)0x03) +#define GPIO_PortSourceGPIOE ((uint8_t)0x04) +#define GPIO_PortSourceGPIOF ((uint8_t)0x05) +#define GPIO_PortSourceGPIOG ((uint8_t)0x06) +#define IS_GPIO_EVENTOUT_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOE)) + +#define IS_GPIO_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOE) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOF) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOG)) + +/** + * @} + */ + +/** @defgroup GPIO_Pin_sources + * @{ + */ + +#define GPIO_PinSource0 ((uint8_t)0x00) +#define GPIO_PinSource1 ((uint8_t)0x01) +#define GPIO_PinSource2 ((uint8_t)0x02) +#define GPIO_PinSource3 ((uint8_t)0x03) +#define GPIO_PinSource4 ((uint8_t)0x04) +#define GPIO_PinSource5 ((uint8_t)0x05) +#define GPIO_PinSource6 ((uint8_t)0x06) +#define GPIO_PinSource7 ((uint8_t)0x07) +#define GPIO_PinSource8 ((uint8_t)0x08) +#define GPIO_PinSource9 ((uint8_t)0x09) +#define GPIO_PinSource10 ((uint8_t)0x0A) +#define GPIO_PinSource11 ((uint8_t)0x0B) +#define GPIO_PinSource12 ((uint8_t)0x0C) +#define GPIO_PinSource13 ((uint8_t)0x0D) +#define GPIO_PinSource14 ((uint8_t)0x0E) +#define GPIO_PinSource15 ((uint8_t)0x0F) + +#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \ + ((PINSOURCE) == GPIO_PinSource1) || \ + ((PINSOURCE) == GPIO_PinSource2) || \ + ((PINSOURCE) == GPIO_PinSource3) || \ + ((PINSOURCE) == GPIO_PinSource4) || \ + ((PINSOURCE) == GPIO_PinSource5) || \ + ((PINSOURCE) == GPIO_PinSource6) || \ + ((PINSOURCE) == GPIO_PinSource7) || \ + ((PINSOURCE) == GPIO_PinSource8) || \ + ((PINSOURCE) == GPIO_PinSource9) || \ + ((PINSOURCE) == GPIO_PinSource10) || \ + ((PINSOURCE) == GPIO_PinSource11) || \ + ((PINSOURCE) == GPIO_PinSource12) || \ + ((PINSOURCE) == GPIO_PinSource13) || \ + ((PINSOURCE) == GPIO_PinSource14) || \ + ((PINSOURCE) == GPIO_PinSource15)) + +/** + * @} + */ + +/** @defgroup Ethernet_Media_Interface + * @{ + */ +#define GPIO_ETH_MediaInterface_MII ((u32)0x00000000) +#define GPIO_ETH_MediaInterface_RMII ((u32)0x00000001) + +#define IS_GPIO_ETH_MEDIA_INTERFACE(INTERFACE) (((INTERFACE) == GPIO_ETH_MediaInterface_MII) || \ + ((INTERFACE) == GPIO_ETH_MediaInterface_RMII)) + +/** + * @} + */ +/** + * @} + */ + +/** @defgroup GPIO_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Exported_Functions + * @{ + */ + +void GPIO_DeInit(GPIO_TypeDef* GPIOx); +void GPIO_AFIODeInit(void); +void GPIO_Init(GPIO_TypeDef* GPIOx, const GPIO_InitTypeDef* GPIO_InitStruct); +void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct); +uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx); +uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx); +void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal); +void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal); +void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource); +void GPIO_EventOutputCmd(FunctionalState NewState); +void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState); +void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource); +void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_GPIO_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h index 1d9ef3b24..560e41cb0 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h @@ -1,670 +1,670 @@ -/** - ****************************************************************************** - * @file stm32f10x_i2c.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the I2C firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_I2C_H -#define __STM32F10x_I2C_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup I2C - * @{ - */ - -/** @defgroup I2C_Exported_Types - * @{ - */ - -/** - * @brief I2C Init structure definition - */ - -typedef struct -{ - uint32_t I2C_ClockSpeed; /*!< Specifies the clock frequency. - This parameter must be set to a value lower than 400kHz */ - - uint16_t I2C_Mode; /*!< Specifies the I2C mode. - This parameter can be a value of @ref I2C_mode */ - - uint16_t I2C_DutyCycle; /*!< Specifies the I2C fast mode duty cycle. - This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */ - - uint16_t I2C_OwnAddress1; /*!< Specifies the first device own address. - This parameter can be a 7-bit or 10-bit address. */ - - uint16_t I2C_Ack; /*!< Enables or disables the acknowledgement. - This parameter can be a value of @ref I2C_acknowledgement */ - - uint16_t I2C_AcknowledgedAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged. - This parameter can be a value of @ref I2C_acknowledged_address */ -}I2C_InitTypeDef; - -/** - * @} - */ - - -/** @defgroup I2C_Exported_Constants - * @{ - */ - -#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C1) || \ - ((PERIPH) == I2C2)) -/** @defgroup I2C_mode - * @{ - */ - -#define I2C_Mode_I2C ((uint16_t)0x0000) -#define I2C_Mode_SMBusDevice ((uint16_t)0x0002) -#define I2C_Mode_SMBusHost ((uint16_t)0x000A) -#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \ - ((MODE) == I2C_Mode_SMBusDevice) || \ - ((MODE) == I2C_Mode_SMBusHost)) -/** - * @} - */ - -/** @defgroup I2C_duty_cycle_in_fast_mode - * @{ - */ - -#define I2C_DutyCycle_16_9 ((uint16_t)0x4000) /*!< I2C fast mode Tlow/Thigh = 16/9 */ -#define I2C_DutyCycle_2 ((uint16_t)0xBFFF) /*!< I2C fast mode Tlow/Thigh = 2 */ -#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \ - ((CYCLE) == I2C_DutyCycle_2)) -/** - * @} - */ - -/** @defgroup I2C_acknowledgement - * @{ - */ - -#define I2C_Ack_Enable ((uint16_t)0x0400) -#define I2C_Ack_Disable ((uint16_t)0x0000) -#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \ - ((STATE) == I2C_Ack_Disable)) -/** - * @} - */ - -/** @defgroup I2C_transfer_direction - * @{ - */ - -#define I2C_Direction_Transmitter ((uint8_t)0x00) -#define I2C_Direction_Receiver ((uint8_t)0x01) -#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \ - ((DIRECTION) == I2C_Direction_Receiver)) -/** - * @} - */ - -/** @defgroup I2C_acknowledged_address - * @{ - */ - -#define I2C_AcknowledgedAddress_7bit ((uint16_t)0x4000) -#define I2C_AcknowledgedAddress_10bit ((uint16_t)0xC000) -#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \ - ((ADDRESS) == I2C_AcknowledgedAddress_10bit)) -/** - * @} - */ - -/** @defgroup I2C_registers - * @{ - */ - -#define I2C_Register_CR1 ((uint8_t)0x00) -#define I2C_Register_CR2 ((uint8_t)0x04) -#define I2C_Register_OAR1 ((uint8_t)0x08) -#define I2C_Register_OAR2 ((uint8_t)0x0C) -#define I2C_Register_DR ((uint8_t)0x10) -#define I2C_Register_SR1 ((uint8_t)0x14) -#define I2C_Register_SR2 ((uint8_t)0x18) -#define I2C_Register_CCR ((uint8_t)0x1C) -#define I2C_Register_TRISE ((uint8_t)0x20) -#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \ - ((REGISTER) == I2C_Register_CR2) || \ - ((REGISTER) == I2C_Register_OAR1) || \ - ((REGISTER) == I2C_Register_OAR2) || \ - ((REGISTER) == I2C_Register_DR) || \ - ((REGISTER) == I2C_Register_SR1) || \ - ((REGISTER) == I2C_Register_SR2) || \ - ((REGISTER) == I2C_Register_CCR) || \ - ((REGISTER) == I2C_Register_TRISE)) -/** - * @} - */ - -/** @defgroup I2C_SMBus_alert_pin_level - * @{ - */ - -#define I2C_SMBusAlert_Low ((uint16_t)0x2000) -#define I2C_SMBusAlert_High ((uint16_t)0xDFFF) -#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \ - ((ALERT) == I2C_SMBusAlert_High)) -/** - * @} - */ - -/** @defgroup I2C_PEC_position - * @{ - */ - -#define I2C_PECPosition_Next ((uint16_t)0x0800) -#define I2C_PECPosition_Current ((uint16_t)0xF7FF) -#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \ - ((POSITION) == I2C_PECPosition_Current)) -/** - * @} - */ - -/** @defgroup I2C_interrupts_definition - * @{ - */ - -#define I2C_IT_BUF ((uint16_t)0x0400) -#define I2C_IT_EVT ((uint16_t)0x0200) -#define I2C_IT_ERR ((uint16_t)0x0100) -#define IS_I2C_CONFIG_IT(IT) ((((IT) & (uint16_t)0xF8FF) == 0x00) && ((IT) != 0x00)) -/** - * @} - */ - -/** @defgroup I2C_interrupts_definition - * @{ - */ - -#define I2C_IT_SMBALERT ((uint32_t)0x01008000) -#define I2C_IT_TIMEOUT ((uint32_t)0x01004000) -#define I2C_IT_PECERR ((uint32_t)0x01001000) -#define I2C_IT_OVR ((uint32_t)0x01000800) -#define I2C_IT_AF ((uint32_t)0x01000400) -#define I2C_IT_ARLO ((uint32_t)0x01000200) -#define I2C_IT_BERR ((uint32_t)0x01000100) -#define I2C_IT_TXE ((uint32_t)0x06000080) -#define I2C_IT_RXNE ((uint32_t)0x06000040) -#define I2C_IT_STOPF ((uint32_t)0x02000010) -#define I2C_IT_ADD10 ((uint32_t)0x02000008) -#define I2C_IT_BTF ((uint32_t)0x02000004) -#define I2C_IT_ADDR ((uint32_t)0x02000002) -#define I2C_IT_SB ((uint32_t)0x02000001) - -#define IS_I2C_CLEAR_IT(IT) ((((IT) & (uint16_t)0x20FF) == 0x00) && ((IT) != (uint16_t)0x00)) - -#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \ - ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \ - ((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \ - ((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \ - ((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \ - ((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \ - ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB)) -/** - * @} - */ - -/** @defgroup I2C_flags_definition - * @{ - */ - -/** - * @brief SR2 register flags - */ - -#define I2C_FLAG_DUALF ((uint32_t)0x00800000) -#define I2C_FLAG_SMBHOST ((uint32_t)0x00400000) -#define I2C_FLAG_SMBDEFAULT ((uint32_t)0x00200000) -#define I2C_FLAG_GENCALL ((uint32_t)0x00100000) -#define I2C_FLAG_TRA ((uint32_t)0x00040000) -#define I2C_FLAG_BUSY ((uint32_t)0x00020000) -#define I2C_FLAG_MSL ((uint32_t)0x00010000) - -/** - * @brief SR1 register flags - */ - -#define I2C_FLAG_SMBALERT ((uint32_t)0x10008000) -#define I2C_FLAG_TIMEOUT ((uint32_t)0x10004000) -#define I2C_FLAG_PECERR ((uint32_t)0x10001000) -#define I2C_FLAG_OVR ((uint32_t)0x10000800) -#define I2C_FLAG_AF ((uint32_t)0x10000400) -#define I2C_FLAG_ARLO ((uint32_t)0x10000200) -#define I2C_FLAG_BERR ((uint32_t)0x10000100) -#define I2C_FLAG_TXE ((uint32_t)0x10000080) -#define I2C_FLAG_RXNE ((uint32_t)0x10000040) -#define I2C_FLAG_STOPF ((uint32_t)0x10000010) -#define I2C_FLAG_ADD10 ((uint32_t)0x10000008) -#define I2C_FLAG_BTF ((uint32_t)0x10000004) -#define I2C_FLAG_ADDR ((uint32_t)0x10000002) -#define I2C_FLAG_SB ((uint32_t)0x10000001) - -#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0x20FF) == 0x00) && ((FLAG) != (uint16_t)0x00)) - -#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \ - ((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \ - ((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \ - ((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \ - ((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \ - ((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \ - ((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \ - ((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \ - ((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \ - ((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \ - ((FLAG) == I2C_FLAG_SB)) -/** - * @} - */ - -/** @defgroup I2C_Events - * @{ - */ - -/*======================================== - - I2C Master Events (Events grouped in order of communication) - ==========================================*/ -/** - * @brief Communication start - * - * After sending the START condition (I2C_GenerateSTART() function) the master - * has to wait for this event. It means that the Start condition has been correctly - * released on the I2C bus (the bus is free, no other devices is communicating). - * - */ -/* --EV5 */ -#define I2C_EVENT_MASTER_MODE_SELECT ((uint32_t)0x00030001) /* BUSY, MSL and SB flag */ - -/** - * @brief Address Acknowledge - * - * After checking on EV5 (start condition correctly released on the bus), the - * master sends the address of the slave(s) with which it will communicate - * (I2C_Send7bitAddress() function, it also determines the direction of the communication: - * Master transmitter or Receiver). Then the master has to wait that a slave acknowledges - * his address. If an acknowledge is sent on the bus, one of the following events will - * be set: - * - * 1) In case of Master Receiver (7-bit addressing): the I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED - * event is set. - * - * 2) In case of Master Transmitter (7-bit addressing): the I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED - * is set - * - * 3) In case of 10-Bit addressing mode, the master (just after generating the START - * and checking on EV5) has to send the header of 10-bit addressing mode (I2C_SendData() - * function). Then master should wait on EV9. It means that the 10-bit addressing - * header has been correctly sent on the bus. Then master should send the second part of - * the 10-bit address (LSB) using the function I2C_Send7bitAddress(). Then master - * should wait for event EV6. - * - */ - -/* --EV6 */ -#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED ((uint32_t)0x00070082) /* BUSY, MSL, ADDR, TXE and TRA flags */ -#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED ((uint32_t)0x00030002) /* BUSY, MSL and ADDR flags */ -/* --EV9 */ -#define I2C_EVENT_MASTER_MODE_ADDRESS10 ((uint32_t)0x00030008) /* BUSY, MSL and ADD10 flags */ - -/** - * @brief Communication events - * - * If a communication is established (START condition generated and slave address - * acknowledged) then the master has to check on one of the following events for - * communication procedures: - * - * 1) Master Receiver mode: The master has to wait on the event EV7 then to read - * the data received from the slave (I2C_ReceiveData() function). - * - * 2) Master Transmitter mode: The master has to send data (I2C_SendData() - * function) then to wait on event EV8 or EV8_2. - * These two events are similar: - * - EV8 means that the data has been written in the data register and is - * being shifted out. - * - EV8_2 means that the data has been physically shifted out and output - * on the bus. - * In most cases, using EV8 is sufficient for the application. - * Using EV8_2 leads to a slower communication but ensure more reliable test. - * EV8_2 is also more suitable than EV8 for testing on the last data transmission - * (before Stop condition generation). - * - * @note In case the user software does not guarantee that this event EV7 is - * managed before the current byte end of transfer, then user may check on EV7 - * and BTF flag at the same time (ie. (I2C_EVENT_MASTER_BYTE_RECEIVED | I2C_FLAG_BTF)). - * In this case the communication may be slower. - * - */ - -/* Master RECEIVER mode -----------------------------*/ -/* --EV7 */ -#define I2C_EVENT_MASTER_BYTE_RECEIVED ((uint32_t)0x00030040) /* BUSY, MSL and RXNE flags */ - -/* Master TRANSMITTER mode --------------------------*/ -/* --EV8 */ -#define I2C_EVENT_MASTER_BYTE_TRANSMITTING ((uint32_t)0x00070080) /* TRA, BUSY, MSL, TXE flags */ -/* --EV8_2 */ -#define I2C_EVENT_MASTER_BYTE_TRANSMITTED ((uint32_t)0x00070084) /* TRA, BUSY, MSL, TXE and BTF flags */ - - -/*======================================== - - I2C Slave Events (Events grouped in order of communication) - ==========================================*/ - -/** - * @brief Communication start events - * - * Wait on one of these events at the start of the communication. It means that - * the I2C peripheral detected a Start condition on the bus (generated by master - * device) followed by the peripheral address. The peripheral generates an ACK - * condition on the bus (if the acknowledge feature is enabled through function - * I2C_AcknowledgeConfig()) and the events listed above are set : - * - * 1) In normal case (only one address managed by the slave), when the address - * sent by the master matches the own address of the peripheral (configured by - * I2C_OwnAddress1 field) the I2C_EVENT_SLAVE_XXX_ADDRESS_MATCHED event is set - * (where XXX could be TRANSMITTER or RECEIVER). - * - * 2) In case the address sent by the master matches the second address of the - * peripheral (configured by the function I2C_OwnAddress2Config() and enabled - * by the function I2C_DualAddressCmd()) the events I2C_EVENT_SLAVE_XXX_SECONDADDRESS_MATCHED - * (where XXX could be TRANSMITTER or RECEIVER) are set. - * - * 3) In case the address sent by the master is General Call (address 0x00) and - * if the General Call is enabled for the peripheral (using function I2C_GeneralCallCmd()) - * the following event is set I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED. - * - */ - -/* --EV1 (all the events below are variants of EV1) */ -/* 1) Case of One Single Address managed by the slave */ -#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((uint32_t)0x00020002) /* BUSY and ADDR flags */ -#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */ - -/* 2) Case of Dual address managed by the slave */ -#define I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED ((uint32_t)0x00820000) /* DUALF and BUSY flags */ -#define I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((uint32_t)0x00860080) /* DUALF, TRA, BUSY and TXE flags */ - -/* 3) Case of General Call enabled for the slave */ -#define I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED ((uint32_t)0x00120000) /* GENCALL and BUSY flags */ - -/** - * @brief Communication events - * - * Wait on one of these events when EV1 has already been checked and: - * - * - Slave RECEIVER mode: - * - EV2: When the application is expecting a data byte to be received. - * - EV4: When the application is expecting the end of the communication: master - * sends a stop condition and data transmission is stopped. - * - * - Slave Transmitter mode: - * - EV3: When a byte has been transmitted by the slave and the application is expecting - * the end of the byte transmission. The two events I2C_EVENT_SLAVE_BYTE_TRANSMITTED and - * I2C_EVENT_SLAVE_BYTE_TRANSMITTING are similar. The second one can optionally be - * used when the user software doesn't guarantee the EV3 is managed before the - * current byte end of tranfer. - * - EV3_2: When the master sends a NACK in order to tell slave that data transmission - * shall end (before sending the STOP condition). In this case slave has to stop sending - * data bytes and expect a Stop condition on the bus. - * - * @note In case the user software does not guarantee that the event EV2 is - * managed before the current byte end of transfer, then user may check on EV2 - * and BTF flag at the same time (ie. (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_BTF)). - * In this case the communication may be slower. - * - */ - -/* Slave RECEIVER mode --------------------------*/ -/* --EV2 */ -#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((uint32_t)0x00020040) /* BUSY and RXNE flags */ -/* --EV4 */ -#define I2C_EVENT_SLAVE_STOP_DETECTED ((uint32_t)0x00000010) /* STOPF flag */ - -/* Slave TRANSMITTER mode -----------------------*/ -/* --EV3 */ -#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((uint32_t)0x00060084) /* TRA, BUSY, TXE and BTF flags */ -#define I2C_EVENT_SLAVE_BYTE_TRANSMITTING ((uint32_t)0x00060080) /* TRA, BUSY and TXE flags */ -/* --EV3_2 */ -#define I2C_EVENT_SLAVE_ACK_FAILURE ((uint32_t)0x00000400) /* AF flag */ - -/*=========================== End of Events Description ==========================================*/ - -#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \ - ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \ - ((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \ - ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \ - ((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \ - ((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \ - ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \ - ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \ - ((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \ - ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \ - ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \ - ((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \ - ((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \ - ((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \ - ((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \ - ((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \ - ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \ - ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTING) || \ - ((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \ - ((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE)) -/** - * @} - */ - -/** @defgroup I2C_own_address1 - * @{ - */ - -#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF) -/** - * @} - */ - -/** @defgroup I2C_clock_speed - * @{ - */ - -#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000)) -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup I2C_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup I2C_Exported_Functions - * @{ - */ - -void I2C_DeInit(I2C_TypeDef* I2Cx); -void I2C_Init(I2C_TypeDef* I2Cx, const I2C_InitTypeDef* I2C_InitStruct); -void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct); -void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address); -void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState); -void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data); -uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx); -void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction); -uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register); -void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert); -void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition); -void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState); -uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx); -void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); -void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle); - -/** - * @brief - **************************************************************************************** - * - * I2C State Monitoring Functions - * - **************************************************************************************** - * This I2C driver provides three different ways for I2C state monitoring - * depending on the application requirements and constraints: - * - * - * 1) Basic state monitoring: - * Using I2C_CheckEvent() function: - * It compares the status registers (SR1 and SR2) content to a given event - * (can be the combination of one or more flags). - * It returns SUCCESS if the current status includes the given flags - * and returns ERROR if one or more flags are missing in the current status. - * - When to use: - * - This function is suitable for most applications as well as for startup - * activity since the events are fully described in the product reference manual - * (RM0008). - * - It is also suitable for users who need to define their own events. - * - Limitations: - * - If an error occurs (ie. error flags are set besides to the monitored flags), - * the I2C_CheckEvent() function may return SUCCESS despite the communication - * hold or corrupted real state. - * In this case, it is advised to use error interrupts to monitor the error - * events and handle them in the interrupt IRQ handler. - * - * @note - * For error management, it is advised to use the following functions: - * - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR). - * - I2Cx_ER_IRQHandler() which is called when the error interurpt occurs. - * Where x is the peripheral instance (I2C1, I2C2 ...) - * - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into I2Cx_ER_IRQHandler() - * in order to determine which error occured. - * - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() - * and/or I2C_GenerateStop() in order to clear the error flag and source, - * and return to correct communication status. - * - * - * 2) Advanced state monitoring: - * Using the function I2C_GetLastEvent() which returns the image of both status - * registers in a single word (uint32_t) (Status Register 2 value is shifted left - * by 16 bits and concatenated to Status Register 1). - * - When to use: - * - This function is suitable for the same applications above but it allows to - * overcome the limitations of I2C_GetFlagStatus() function (see below). - * The returned value could be compared to events already defined in the - * library (stm32f10x_i2c.h) or to custom values defined by user. - * - This function is suitable when multiple flags are monitored at the same time. - * - At the opposite of I2C_CheckEvent() function, this function allows user to - * choose when an event is accepted (when all events flags are set and no - * other flags are set or just when the needed flags are set like - * I2C_CheckEvent() function). - * - Limitations: - * - User may need to define his own events. - * - Same remark concerning the error management is applicable for this - * function if user decides to check only regular communication flags (and - * ignores error flags). - * - * - * 3) Flag-based state monitoring: - * Using the function I2C_GetFlagStatus() which simply returns the status of - * one single flag (ie. I2C_FLAG_RXNE ...). - * - When to use: - * - This function could be used for specific applications or in debug phase. - * - It is suitable when only one flag checking is needed (most I2C events - * are monitored through multiple flags). - * - Limitations: - * - When calling this function, the Status register is accessed. Some flags are - * cleared when the status register is accessed. So checking the status - * of one Flag, may clear other ones. - * - Function may need to be called twice or more in order to monitor one - * single event. - * - */ - -/** - * - * 1) Basic state monitoring - ******************************************************************************* - */ -ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT); -/** - * - * 2) Advanced state monitoring - ******************************************************************************* - */ -uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx); -/** - * - * 3) Flag-based state monitoring - ******************************************************************************* - */ -FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); -/** - * - ******************************************************************************* - */ - -void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); -ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT); -void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT); - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F10x_I2C_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_i2c.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the I2C firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_I2C_H +#define __STM32F10x_I2C_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup I2C + * @{ + */ + +/** @defgroup I2C_Exported_Types + * @{ + */ + +/** + * @brief I2C Init structure definition + */ + +typedef struct +{ + uint32_t I2C_ClockSpeed; /*!< Specifies the clock frequency. + This parameter must be set to a value lower than 400kHz */ + + uint16_t I2C_Mode; /*!< Specifies the I2C mode. + This parameter can be a value of @ref I2C_mode */ + + uint16_t I2C_DutyCycle; /*!< Specifies the I2C fast mode duty cycle. + This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */ + + uint16_t I2C_OwnAddress1; /*!< Specifies the first device own address. + This parameter can be a 7-bit or 10-bit address. */ + + uint16_t I2C_Ack; /*!< Enables or disables the acknowledgement. + This parameter can be a value of @ref I2C_acknowledgement */ + + uint16_t I2C_AcknowledgedAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged. + This parameter can be a value of @ref I2C_acknowledged_address */ +}I2C_InitTypeDef; + +/** + * @} + */ + + +/** @defgroup I2C_Exported_Constants + * @{ + */ + +#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C1) || \ + ((PERIPH) == I2C2)) +/** @defgroup I2C_mode + * @{ + */ + +#define I2C_Mode_I2C ((uint16_t)0x0000) +#define I2C_Mode_SMBusDevice ((uint16_t)0x0002) +#define I2C_Mode_SMBusHost ((uint16_t)0x000A) +#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \ + ((MODE) == I2C_Mode_SMBusDevice) || \ + ((MODE) == I2C_Mode_SMBusHost)) +/** + * @} + */ + +/** @defgroup I2C_duty_cycle_in_fast_mode + * @{ + */ + +#define I2C_DutyCycle_16_9 ((uint16_t)0x4000) /*!< I2C fast mode Tlow/Thigh = 16/9 */ +#define I2C_DutyCycle_2 ((uint16_t)0xBFFF) /*!< I2C fast mode Tlow/Thigh = 2 */ +#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \ + ((CYCLE) == I2C_DutyCycle_2)) +/** + * @} + */ + +/** @defgroup I2C_acknowledgement + * @{ + */ + +#define I2C_Ack_Enable ((uint16_t)0x0400) +#define I2C_Ack_Disable ((uint16_t)0x0000) +#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \ + ((STATE) == I2C_Ack_Disable)) +/** + * @} + */ + +/** @defgroup I2C_transfer_direction + * @{ + */ + +#define I2C_Direction_Transmitter ((uint8_t)0x00) +#define I2C_Direction_Receiver ((uint8_t)0x01) +#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \ + ((DIRECTION) == I2C_Direction_Receiver)) +/** + * @} + */ + +/** @defgroup I2C_acknowledged_address + * @{ + */ + +#define I2C_AcknowledgedAddress_7bit ((uint16_t)0x4000) +#define I2C_AcknowledgedAddress_10bit ((uint16_t)0xC000) +#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \ + ((ADDRESS) == I2C_AcknowledgedAddress_10bit)) +/** + * @} + */ + +/** @defgroup I2C_registers + * @{ + */ + +#define I2C_Register_CR1 ((uint8_t)0x00) +#define I2C_Register_CR2 ((uint8_t)0x04) +#define I2C_Register_OAR1 ((uint8_t)0x08) +#define I2C_Register_OAR2 ((uint8_t)0x0C) +#define I2C_Register_DR ((uint8_t)0x10) +#define I2C_Register_SR1 ((uint8_t)0x14) +#define I2C_Register_SR2 ((uint8_t)0x18) +#define I2C_Register_CCR ((uint8_t)0x1C) +#define I2C_Register_TRISE ((uint8_t)0x20) +#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \ + ((REGISTER) == I2C_Register_CR2) || \ + ((REGISTER) == I2C_Register_OAR1) || \ + ((REGISTER) == I2C_Register_OAR2) || \ + ((REGISTER) == I2C_Register_DR) || \ + ((REGISTER) == I2C_Register_SR1) || \ + ((REGISTER) == I2C_Register_SR2) || \ + ((REGISTER) == I2C_Register_CCR) || \ + ((REGISTER) == I2C_Register_TRISE)) +/** + * @} + */ + +/** @defgroup I2C_SMBus_alert_pin_level + * @{ + */ + +#define I2C_SMBusAlert_Low ((uint16_t)0x2000) +#define I2C_SMBusAlert_High ((uint16_t)0xDFFF) +#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \ + ((ALERT) == I2C_SMBusAlert_High)) +/** + * @} + */ + +/** @defgroup I2C_PEC_position + * @{ + */ + +#define I2C_PECPosition_Next ((uint16_t)0x0800) +#define I2C_PECPosition_Current ((uint16_t)0xF7FF) +#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \ + ((POSITION) == I2C_PECPosition_Current)) +/** + * @} + */ + +/** @defgroup I2C_interrupts_definition + * @{ + */ + +#define I2C_IT_BUF ((uint16_t)0x0400) +#define I2C_IT_EVT ((uint16_t)0x0200) +#define I2C_IT_ERR ((uint16_t)0x0100) +#define IS_I2C_CONFIG_IT(IT) ((((IT) & (uint16_t)0xF8FF) == 0x00) && ((IT) != 0x00)) +/** + * @} + */ + +/** @defgroup I2C_interrupts_definition + * @{ + */ + +#define I2C_IT_SMBALERT ((uint32_t)0x01008000) +#define I2C_IT_TIMEOUT ((uint32_t)0x01004000) +#define I2C_IT_PECERR ((uint32_t)0x01001000) +#define I2C_IT_OVR ((uint32_t)0x01000800) +#define I2C_IT_AF ((uint32_t)0x01000400) +#define I2C_IT_ARLO ((uint32_t)0x01000200) +#define I2C_IT_BERR ((uint32_t)0x01000100) +#define I2C_IT_TXE ((uint32_t)0x06000080) +#define I2C_IT_RXNE ((uint32_t)0x06000040) +#define I2C_IT_STOPF ((uint32_t)0x02000010) +#define I2C_IT_ADD10 ((uint32_t)0x02000008) +#define I2C_IT_BTF ((uint32_t)0x02000004) +#define I2C_IT_ADDR ((uint32_t)0x02000002) +#define I2C_IT_SB ((uint32_t)0x02000001) + +#define IS_I2C_CLEAR_IT(IT) ((((IT) & (uint16_t)0x20FF) == 0x00) && ((IT) != (uint16_t)0x00)) + +#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \ + ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \ + ((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \ + ((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \ + ((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \ + ((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \ + ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB)) +/** + * @} + */ + +/** @defgroup I2C_flags_definition + * @{ + */ + +/** + * @brief SR2 register flags + */ + +#define I2C_FLAG_DUALF ((uint32_t)0x00800000) +#define I2C_FLAG_SMBHOST ((uint32_t)0x00400000) +#define I2C_FLAG_SMBDEFAULT ((uint32_t)0x00200000) +#define I2C_FLAG_GENCALL ((uint32_t)0x00100000) +#define I2C_FLAG_TRA ((uint32_t)0x00040000) +#define I2C_FLAG_BUSY ((uint32_t)0x00020000) +#define I2C_FLAG_MSL ((uint32_t)0x00010000) + +/** + * @brief SR1 register flags + */ + +#define I2C_FLAG_SMBALERT ((uint32_t)0x10008000) +#define I2C_FLAG_TIMEOUT ((uint32_t)0x10004000) +#define I2C_FLAG_PECERR ((uint32_t)0x10001000) +#define I2C_FLAG_OVR ((uint32_t)0x10000800) +#define I2C_FLAG_AF ((uint32_t)0x10000400) +#define I2C_FLAG_ARLO ((uint32_t)0x10000200) +#define I2C_FLAG_BERR ((uint32_t)0x10000100) +#define I2C_FLAG_TXE ((uint32_t)0x10000080) +#define I2C_FLAG_RXNE ((uint32_t)0x10000040) +#define I2C_FLAG_STOPF ((uint32_t)0x10000010) +#define I2C_FLAG_ADD10 ((uint32_t)0x10000008) +#define I2C_FLAG_BTF ((uint32_t)0x10000004) +#define I2C_FLAG_ADDR ((uint32_t)0x10000002) +#define I2C_FLAG_SB ((uint32_t)0x10000001) + +#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0x20FF) == 0x00) && ((FLAG) != (uint16_t)0x00)) + +#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \ + ((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \ + ((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \ + ((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \ + ((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \ + ((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \ + ((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \ + ((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \ + ((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \ + ((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \ + ((FLAG) == I2C_FLAG_SB)) +/** + * @} + */ + +/** @defgroup I2C_Events + * @{ + */ + +/*======================================== + + I2C Master Events (Events grouped in order of communication) + ==========================================*/ +/** + * @brief Communication start + * + * After sending the START condition (I2C_GenerateSTART() function) the master + * has to wait for this event. It means that the Start condition has been correctly + * released on the I2C bus (the bus is free, no other devices is communicating). + * + */ +/* --EV5 */ +#define I2C_EVENT_MASTER_MODE_SELECT ((uint32_t)0x00030001) /* BUSY, MSL and SB flag */ + +/** + * @brief Address Acknowledge + * + * After checking on EV5 (start condition correctly released on the bus), the + * master sends the address of the slave(s) with which it will communicate + * (I2C_Send7bitAddress() function, it also determines the direction of the communication: + * Master transmitter or Receiver). Then the master has to wait that a slave acknowledges + * his address. If an acknowledge is sent on the bus, one of the following events will + * be set: + * + * 1) In case of Master Receiver (7-bit addressing): the I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED + * event is set. + * + * 2) In case of Master Transmitter (7-bit addressing): the I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED + * is set + * + * 3) In case of 10-Bit addressing mode, the master (just after generating the START + * and checking on EV5) has to send the header of 10-bit addressing mode (I2C_SendData() + * function). Then master should wait on EV9. It means that the 10-bit addressing + * header has been correctly sent on the bus. Then master should send the second part of + * the 10-bit address (LSB) using the function I2C_Send7bitAddress(). Then master + * should wait for event EV6. + * + */ + +/* --EV6 */ +#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED ((uint32_t)0x00070082) /* BUSY, MSL, ADDR, TXE and TRA flags */ +#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED ((uint32_t)0x00030002) /* BUSY, MSL and ADDR flags */ +/* --EV9 */ +#define I2C_EVENT_MASTER_MODE_ADDRESS10 ((uint32_t)0x00030008) /* BUSY, MSL and ADD10 flags */ + +/** + * @brief Communication events + * + * If a communication is established (START condition generated and slave address + * acknowledged) then the master has to check on one of the following events for + * communication procedures: + * + * 1) Master Receiver mode: The master has to wait on the event EV7 then to read + * the data received from the slave (I2C_ReceiveData() function). + * + * 2) Master Transmitter mode: The master has to send data (I2C_SendData() + * function) then to wait on event EV8 or EV8_2. + * These two events are similar: + * - EV8 means that the data has been written in the data register and is + * being shifted out. + * - EV8_2 means that the data has been physically shifted out and output + * on the bus. + * In most cases, using EV8 is sufficient for the application. + * Using EV8_2 leads to a slower communication but ensure more reliable test. + * EV8_2 is also more suitable than EV8 for testing on the last data transmission + * (before Stop condition generation). + * + * @note In case the user software does not guarantee that this event EV7 is + * managed before the current byte end of transfer, then user may check on EV7 + * and BTF flag at the same time (ie. (I2C_EVENT_MASTER_BYTE_RECEIVED | I2C_FLAG_BTF)). + * In this case the communication may be slower. + * + */ + +/* Master RECEIVER mode -----------------------------*/ +/* --EV7 */ +#define I2C_EVENT_MASTER_BYTE_RECEIVED ((uint32_t)0x00030040) /* BUSY, MSL and RXNE flags */ + +/* Master TRANSMITTER mode --------------------------*/ +/* --EV8 */ +#define I2C_EVENT_MASTER_BYTE_TRANSMITTING ((uint32_t)0x00070080) /* TRA, BUSY, MSL, TXE flags */ +/* --EV8_2 */ +#define I2C_EVENT_MASTER_BYTE_TRANSMITTED ((uint32_t)0x00070084) /* TRA, BUSY, MSL, TXE and BTF flags */ + + +/*======================================== + + I2C Slave Events (Events grouped in order of communication) + ==========================================*/ + +/** + * @brief Communication start events + * + * Wait on one of these events at the start of the communication. It means that + * the I2C peripheral detected a Start condition on the bus (generated by master + * device) followed by the peripheral address. The peripheral generates an ACK + * condition on the bus (if the acknowledge feature is enabled through function + * I2C_AcknowledgeConfig()) and the events listed above are set : + * + * 1) In normal case (only one address managed by the slave), when the address + * sent by the master matches the own address of the peripheral (configured by + * I2C_OwnAddress1 field) the I2C_EVENT_SLAVE_XXX_ADDRESS_MATCHED event is set + * (where XXX could be TRANSMITTER or RECEIVER). + * + * 2) In case the address sent by the master matches the second address of the + * peripheral (configured by the function I2C_OwnAddress2Config() and enabled + * by the function I2C_DualAddressCmd()) the events I2C_EVENT_SLAVE_XXX_SECONDADDRESS_MATCHED + * (where XXX could be TRANSMITTER or RECEIVER) are set. + * + * 3) In case the address sent by the master is General Call (address 0x00) and + * if the General Call is enabled for the peripheral (using function I2C_GeneralCallCmd()) + * the following event is set I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED. + * + */ + +/* --EV1 (all the events below are variants of EV1) */ +/* 1) Case of One Single Address managed by the slave */ +#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((uint32_t)0x00020002) /* BUSY and ADDR flags */ +#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */ + +/* 2) Case of Dual address managed by the slave */ +#define I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED ((uint32_t)0x00820000) /* DUALF and BUSY flags */ +#define I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((uint32_t)0x00860080) /* DUALF, TRA, BUSY and TXE flags */ + +/* 3) Case of General Call enabled for the slave */ +#define I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED ((uint32_t)0x00120000) /* GENCALL and BUSY flags */ + +/** + * @brief Communication events + * + * Wait on one of these events when EV1 has already been checked and: + * + * - Slave RECEIVER mode: + * - EV2: When the application is expecting a data byte to be received. + * - EV4: When the application is expecting the end of the communication: master + * sends a stop condition and data transmission is stopped. + * + * - Slave Transmitter mode: + * - EV3: When a byte has been transmitted by the slave and the application is expecting + * the end of the byte transmission. The two events I2C_EVENT_SLAVE_BYTE_TRANSMITTED and + * I2C_EVENT_SLAVE_BYTE_TRANSMITTING are similar. The second one can optionally be + * used when the user software doesn't guarantee the EV3 is managed before the + * current byte end of tranfer. + * - EV3_2: When the master sends a NACK in order to tell slave that data transmission + * shall end (before sending the STOP condition). In this case slave has to stop sending + * data bytes and expect a Stop condition on the bus. + * + * @note In case the user software does not guarantee that the event EV2 is + * managed before the current byte end of transfer, then user may check on EV2 + * and BTF flag at the same time (ie. (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_BTF)). + * In this case the communication may be slower. + * + */ + +/* Slave RECEIVER mode --------------------------*/ +/* --EV2 */ +#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((uint32_t)0x00020040) /* BUSY and RXNE flags */ +/* --EV4 */ +#define I2C_EVENT_SLAVE_STOP_DETECTED ((uint32_t)0x00000010) /* STOPF flag */ + +/* Slave TRANSMITTER mode -----------------------*/ +/* --EV3 */ +#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((uint32_t)0x00060084) /* TRA, BUSY, TXE and BTF flags */ +#define I2C_EVENT_SLAVE_BYTE_TRANSMITTING ((uint32_t)0x00060080) /* TRA, BUSY and TXE flags */ +/* --EV3_2 */ +#define I2C_EVENT_SLAVE_ACK_FAILURE ((uint32_t)0x00000400) /* AF flag */ + +/*=========================== End of Events Description ==========================================*/ + +#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \ + ((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \ + ((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \ + ((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTING) || \ + ((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \ + ((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE)) +/** + * @} + */ + +/** @defgroup I2C_own_address1 + * @{ + */ + +#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF) +/** + * @} + */ + +/** @defgroup I2C_clock_speed + * @{ + */ + +#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup I2C_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Exported_Functions + * @{ + */ + +void I2C_DeInit(I2C_TypeDef* I2Cx); +void I2C_Init(I2C_TypeDef* I2Cx, const I2C_InitTypeDef* I2C_InitStruct); +void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct); +void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address); +void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState); +void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data); +uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx); +void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction); +uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register); +void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert); +void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition); +void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState); +uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx); +void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle); + +/** + * @brief + **************************************************************************************** + * + * I2C State Monitoring Functions + * + **************************************************************************************** + * This I2C driver provides three different ways for I2C state monitoring + * depending on the application requirements and constraints: + * + * + * 1) Basic state monitoring: + * Using I2C_CheckEvent() function: + * It compares the status registers (SR1 and SR2) content to a given event + * (can be the combination of one or more flags). + * It returns SUCCESS if the current status includes the given flags + * and returns ERROR if one or more flags are missing in the current status. + * - When to use: + * - This function is suitable for most applications as well as for startup + * activity since the events are fully described in the product reference manual + * (RM0008). + * - It is also suitable for users who need to define their own events. + * - Limitations: + * - If an error occurs (ie. error flags are set besides to the monitored flags), + * the I2C_CheckEvent() function may return SUCCESS despite the communication + * hold or corrupted real state. + * In this case, it is advised to use error interrupts to monitor the error + * events and handle them in the interrupt IRQ handler. + * + * @note + * For error management, it is advised to use the following functions: + * - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR). + * - I2Cx_ER_IRQHandler() which is called when the error interurpt occurs. + * Where x is the peripheral instance (I2C1, I2C2 ...) + * - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into I2Cx_ER_IRQHandler() + * in order to determine which error occured. + * - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() + * and/or I2C_GenerateStop() in order to clear the error flag and source, + * and return to correct communication status. + * + * + * 2) Advanced state monitoring: + * Using the function I2C_GetLastEvent() which returns the image of both status + * registers in a single word (uint32_t) (Status Register 2 value is shifted left + * by 16 bits and concatenated to Status Register 1). + * - When to use: + * - This function is suitable for the same applications above but it allows to + * overcome the limitations of I2C_GetFlagStatus() function (see below). + * The returned value could be compared to events already defined in the + * library (stm32f10x_i2c.h) or to custom values defined by user. + * - This function is suitable when multiple flags are monitored at the same time. + * - At the opposite of I2C_CheckEvent() function, this function allows user to + * choose when an event is accepted (when all events flags are set and no + * other flags are set or just when the needed flags are set like + * I2C_CheckEvent() function). + * - Limitations: + * - User may need to define his own events. + * - Same remark concerning the error management is applicable for this + * function if user decides to check only regular communication flags (and + * ignores error flags). + * + * + * 3) Flag-based state monitoring: + * Using the function I2C_GetFlagStatus() which simply returns the status of + * one single flag (ie. I2C_FLAG_RXNE ...). + * - When to use: + * - This function could be used for specific applications or in debug phase. + * - It is suitable when only one flag checking is needed (most I2C events + * are monitored through multiple flags). + * - Limitations: + * - When calling this function, the Status register is accessed. Some flags are + * cleared when the status register is accessed. So checking the status + * of one Flag, may clear other ones. + * - Function may need to be called twice or more in order to monitor one + * single event. + * + */ + +/** + * + * 1) Basic state monitoring + ******************************************************************************* + */ +ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT); +/** + * + * 2) Advanced state monitoring + ******************************************************************************* + */ +uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx); +/** + * + * 3) Flag-based state monitoring + ******************************************************************************* + */ +FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); +/** + * + ******************************************************************************* + */ + +void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); +ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT); +void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_I2C_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h index 4325ad450..288a0cd8d 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h @@ -1,139 +1,139 @@ -/** - ****************************************************************************** - * @file stm32f10x_iwdg.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the IWDG - * firmware library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_IWDG_H -#define __STM32F10x_IWDG_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup IWDG - * @{ - */ - -/** @defgroup IWDG_Exported_Types - * @{ - */ - -/** - * @} - */ - -/** @defgroup IWDG_Exported_Constants - * @{ - */ - -/** @defgroup IWDG_WriteAccess - * @{ - */ - -#define IWDG_WriteAccess_Enable ((uint16_t)0x5555) -#define IWDG_WriteAccess_Disable ((uint16_t)0x0000) -#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \ - ((ACCESS) == IWDG_WriteAccess_Disable)) -/** - * @} - */ - -/** @defgroup IWDG_prescaler - * @{ - */ - -#define IWDG_Prescaler_4 ((uint8_t)0x00) -#define IWDG_Prescaler_8 ((uint8_t)0x01) -#define IWDG_Prescaler_16 ((uint8_t)0x02) -#define IWDG_Prescaler_32 ((uint8_t)0x03) -#define IWDG_Prescaler_64 ((uint8_t)0x04) -#define IWDG_Prescaler_128 ((uint8_t)0x05) -#define IWDG_Prescaler_256 ((uint8_t)0x06) -#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \ - ((PRESCALER) == IWDG_Prescaler_8) || \ - ((PRESCALER) == IWDG_Prescaler_16) || \ - ((PRESCALER) == IWDG_Prescaler_32) || \ - ((PRESCALER) == IWDG_Prescaler_64) || \ - ((PRESCALER) == IWDG_Prescaler_128)|| \ - ((PRESCALER) == IWDG_Prescaler_256)) -/** - * @} - */ - -/** @defgroup IWDG_Flag - * @{ - */ - -#define IWDG_FLAG_PVU ((uint16_t)0x0001) -#define IWDG_FLAG_RVU ((uint16_t)0x0002) -#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU)) -#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF) -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup IWDG_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup IWDG_Exported_Functions - * @{ - */ - -void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess); -void IWDG_SetPrescaler(uint8_t IWDG_Prescaler); -void IWDG_SetReload(uint16_t Reload); -void IWDG_ReloadCounter(void); -void IWDG_Enable(void); -FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_IWDG_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_iwdg.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the IWDG + * firmware library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_IWDG_H +#define __STM32F10x_IWDG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup IWDG + * @{ + */ + +/** @defgroup IWDG_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Exported_Constants + * @{ + */ + +/** @defgroup IWDG_WriteAccess + * @{ + */ + +#define IWDG_WriteAccess_Enable ((uint16_t)0x5555) +#define IWDG_WriteAccess_Disable ((uint16_t)0x0000) +#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \ + ((ACCESS) == IWDG_WriteAccess_Disable)) +/** + * @} + */ + +/** @defgroup IWDG_prescaler + * @{ + */ + +#define IWDG_Prescaler_4 ((uint8_t)0x00) +#define IWDG_Prescaler_8 ((uint8_t)0x01) +#define IWDG_Prescaler_16 ((uint8_t)0x02) +#define IWDG_Prescaler_32 ((uint8_t)0x03) +#define IWDG_Prescaler_64 ((uint8_t)0x04) +#define IWDG_Prescaler_128 ((uint8_t)0x05) +#define IWDG_Prescaler_256 ((uint8_t)0x06) +#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \ + ((PRESCALER) == IWDG_Prescaler_8) || \ + ((PRESCALER) == IWDG_Prescaler_16) || \ + ((PRESCALER) == IWDG_Prescaler_32) || \ + ((PRESCALER) == IWDG_Prescaler_64) || \ + ((PRESCALER) == IWDG_Prescaler_128)|| \ + ((PRESCALER) == IWDG_Prescaler_256)) +/** + * @} + */ + +/** @defgroup IWDG_Flag + * @{ + */ + +#define IWDG_FLAG_PVU ((uint16_t)0x0001) +#define IWDG_FLAG_RVU ((uint16_t)0x0002) +#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU)) +#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup IWDG_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Exported_Functions + * @{ + */ + +void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess); +void IWDG_SetPrescaler(uint8_t IWDG_Prescaler); +void IWDG_SetReload(uint16_t Reload); +void IWDG_ReloadCounter(void); +void IWDG_Enable(void); +FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_IWDG_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h index ad93abdca..c5a1ae1ac 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h @@ -1,155 +1,155 @@ -/** - ****************************************************************************** - * @file stm32f10x_pwr.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the PWR firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_PWR_H -#define __STM32F10x_PWR_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup PWR - * @{ - */ - -/** @defgroup PWR_Exported_Types - * @{ - */ - -/** - * @} - */ - -/** @defgroup PWR_Exported_Constants - * @{ - */ - -/** @defgroup PVD_detection_level - * @{ - */ - -#define PWR_PVDLevel_2V2 ((uint32_t)0x00000000) -#define PWR_PVDLevel_2V3 ((uint32_t)0x00000020) -#define PWR_PVDLevel_2V4 ((uint32_t)0x00000040) -#define PWR_PVDLevel_2V5 ((uint32_t)0x00000060) -#define PWR_PVDLevel_2V6 ((uint32_t)0x00000080) -#define PWR_PVDLevel_2V7 ((uint32_t)0x000000A0) -#define PWR_PVDLevel_2V8 ((uint32_t)0x000000C0) -#define PWR_PVDLevel_2V9 ((uint32_t)0x000000E0) -#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_2V2) || ((LEVEL) == PWR_PVDLevel_2V3)|| \ - ((LEVEL) == PWR_PVDLevel_2V4) || ((LEVEL) == PWR_PVDLevel_2V5)|| \ - ((LEVEL) == PWR_PVDLevel_2V6) || ((LEVEL) == PWR_PVDLevel_2V7)|| \ - ((LEVEL) == PWR_PVDLevel_2V8) || ((LEVEL) == PWR_PVDLevel_2V9)) -/** - * @} - */ - -/** @defgroup Regulator_state_is_STOP_mode - * @{ - */ - -#define PWR_Regulator_ON ((uint32_t)0x00000000) -#define PWR_Regulator_LowPower ((uint32_t)0x00000001) -#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \ - ((REGULATOR) == PWR_Regulator_LowPower)) -/** - * @} - */ - -/** @defgroup STOP_mode_entry - * @{ - */ - -#define PWR_STOPEntry_WFI ((uint8_t)0x01) -#define PWR_STOPEntry_WFE ((uint8_t)0x02) -#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE)) - -/** - * @} - */ - -/** @defgroup PWR_Flag - * @{ - */ - -#define PWR_FLAG_WU ((uint32_t)0x00000001) -#define PWR_FLAG_SB ((uint32_t)0x00000002) -#define PWR_FLAG_PVDO ((uint32_t)0x00000004) -#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \ - ((FLAG) == PWR_FLAG_PVDO)) - -#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB)) -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup PWR_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup PWR_Exported_Functions - * @{ - */ - -void PWR_DeInit(void); -void PWR_BackupAccessCmd(FunctionalState NewState); -void PWR_PVDCmd(FunctionalState NewState); -void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel); -void PWR_WakeUpPinCmd(FunctionalState NewState); -void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry); -void PWR_EnterSTANDBYMode(void); -FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG); -void PWR_ClearFlag(uint32_t PWR_FLAG); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_PWR_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_pwr.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the PWR firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_PWR_H +#define __STM32F10x_PWR_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup PWR + * @{ + */ + +/** @defgroup PWR_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Exported_Constants + * @{ + */ + +/** @defgroup PVD_detection_level + * @{ + */ + +#define PWR_PVDLevel_2V2 ((uint32_t)0x00000000) +#define PWR_PVDLevel_2V3 ((uint32_t)0x00000020) +#define PWR_PVDLevel_2V4 ((uint32_t)0x00000040) +#define PWR_PVDLevel_2V5 ((uint32_t)0x00000060) +#define PWR_PVDLevel_2V6 ((uint32_t)0x00000080) +#define PWR_PVDLevel_2V7 ((uint32_t)0x000000A0) +#define PWR_PVDLevel_2V8 ((uint32_t)0x000000C0) +#define PWR_PVDLevel_2V9 ((uint32_t)0x000000E0) +#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_2V2) || ((LEVEL) == PWR_PVDLevel_2V3)|| \ + ((LEVEL) == PWR_PVDLevel_2V4) || ((LEVEL) == PWR_PVDLevel_2V5)|| \ + ((LEVEL) == PWR_PVDLevel_2V6) || ((LEVEL) == PWR_PVDLevel_2V7)|| \ + ((LEVEL) == PWR_PVDLevel_2V8) || ((LEVEL) == PWR_PVDLevel_2V9)) +/** + * @} + */ + +/** @defgroup Regulator_state_is_STOP_mode + * @{ + */ + +#define PWR_Regulator_ON ((uint32_t)0x00000000) +#define PWR_Regulator_LowPower ((uint32_t)0x00000001) +#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \ + ((REGULATOR) == PWR_Regulator_LowPower)) +/** + * @} + */ + +/** @defgroup STOP_mode_entry + * @{ + */ + +#define PWR_STOPEntry_WFI ((uint8_t)0x01) +#define PWR_STOPEntry_WFE ((uint8_t)0x02) +#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE)) + +/** + * @} + */ + +/** @defgroup PWR_Flag + * @{ + */ + +#define PWR_FLAG_WU ((uint32_t)0x00000001) +#define PWR_FLAG_SB ((uint32_t)0x00000002) +#define PWR_FLAG_PVDO ((uint32_t)0x00000004) +#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \ + ((FLAG) == PWR_FLAG_PVDO)) + +#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup PWR_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Exported_Functions + * @{ + */ + +void PWR_DeInit(void); +void PWR_BackupAccessCmd(FunctionalState NewState); +void PWR_PVDCmd(FunctionalState NewState); +void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel); +void PWR_WakeUpPinCmd(FunctionalState NewState); +void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry); +void PWR_EnterSTANDBYMode(void); +FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG); +void PWR_ClearFlag(uint32_t PWR_FLAG); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_PWR_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h index 8f1473f92..be69b88d9 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h @@ -1,726 +1,726 @@ -/** - ****************************************************************************** - * @file stm32f10x_rcc.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the RCC firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_RCC_H -#define __STM32F10x_RCC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup RCC - * @{ - */ - -/** @defgroup RCC_Exported_Types - * @{ - */ - -typedef struct -{ - uint32_t SYSCLK_Frequency; /*!< returns SYSCLK clock frequency expressed in Hz */ - uint32_t HCLK_Frequency; /*!< returns HCLK clock frequency expressed in Hz */ - uint32_t PCLK1_Frequency; /*!< returns PCLK1 clock frequency expressed in Hz */ - uint32_t PCLK2_Frequency; /*!< returns PCLK2 clock frequency expressed in Hz */ - uint32_t ADCCLK_Frequency; /*!< returns ADCCLK clock frequency expressed in Hz */ -}RCC_ClocksTypeDef; - -/** - * @} - */ - -/** @defgroup RCC_Exported_Constants - * @{ - */ - -/** @defgroup HSE_configuration - * @{ - */ - -#define RCC_HSE_OFF ((uint32_t)0x00000000) -#define RCC_HSE_ON ((uint32_t)0x00010000) -#define RCC_HSE_Bypass ((uint32_t)0x00040000) -#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \ - ((HSE) == RCC_HSE_Bypass)) - -/** - * @} - */ - -/** @defgroup PLL_entry_clock_source - * @{ - */ - -#define RCC_PLLSource_HSI_Div2 ((uint32_t)0x00000000) - -#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_CL) - #define RCC_PLLSource_HSE_Div1 ((uint32_t)0x00010000) - #define RCC_PLLSource_HSE_Div2 ((uint32_t)0x00030000) - #define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \ - ((SOURCE) == RCC_PLLSource_HSE_Div1) || \ - ((SOURCE) == RCC_PLLSource_HSE_Div2)) -#else - #define RCC_PLLSource_PREDIV1 ((uint32_t)0x00010000) - #define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \ - ((SOURCE) == RCC_PLLSource_PREDIV1)) -#endif /* STM32F10X_CL */ - -/** - * @} - */ - -/** @defgroup PLL_multiplication_factor - * @{ - */ -#ifndef STM32F10X_CL - #define RCC_PLLMul_2 ((uint32_t)0x00000000) - #define RCC_PLLMul_3 ((uint32_t)0x00040000) - #define RCC_PLLMul_4 ((uint32_t)0x00080000) - #define RCC_PLLMul_5 ((uint32_t)0x000C0000) - #define RCC_PLLMul_6 ((uint32_t)0x00100000) - #define RCC_PLLMul_7 ((uint32_t)0x00140000) - #define RCC_PLLMul_8 ((uint32_t)0x00180000) - #define RCC_PLLMul_9 ((uint32_t)0x001C0000) - #define RCC_PLLMul_10 ((uint32_t)0x00200000) - #define RCC_PLLMul_11 ((uint32_t)0x00240000) - #define RCC_PLLMul_12 ((uint32_t)0x00280000) - #define RCC_PLLMul_13 ((uint32_t)0x002C0000) - #define RCC_PLLMul_14 ((uint32_t)0x00300000) - #define RCC_PLLMul_15 ((uint32_t)0x00340000) - #define RCC_PLLMul_16 ((uint32_t)0x00380000) - #define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3) || \ - ((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \ - ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \ - ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \ - ((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \ - ((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \ - ((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \ - ((MUL) == RCC_PLLMul_16)) - -#else - #define RCC_PLLMul_4 ((uint32_t)0x00080000) - #define RCC_PLLMul_5 ((uint32_t)0x000C0000) - #define RCC_PLLMul_6 ((uint32_t)0x00100000) - #define RCC_PLLMul_7 ((uint32_t)0x00140000) - #define RCC_PLLMul_8 ((uint32_t)0x00180000) - #define RCC_PLLMul_9 ((uint32_t)0x001C0000) - #define RCC_PLLMul_6_5 ((uint32_t)0x00340000) - - #define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \ - ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \ - ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \ - ((MUL) == RCC_PLLMul_6_5)) -#endif /* STM32F10X_CL */ -/** - * @} - */ - -/** @defgroup PREDIV1_division_factor - * @{ - */ -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) - #define RCC_PREDIV1_Div1 ((uint32_t)0x00000000) - #define RCC_PREDIV1_Div2 ((uint32_t)0x00000001) - #define RCC_PREDIV1_Div3 ((uint32_t)0x00000002) - #define RCC_PREDIV1_Div4 ((uint32_t)0x00000003) - #define RCC_PREDIV1_Div5 ((uint32_t)0x00000004) - #define RCC_PREDIV1_Div6 ((uint32_t)0x00000005) - #define RCC_PREDIV1_Div7 ((uint32_t)0x00000006) - #define RCC_PREDIV1_Div8 ((uint32_t)0x00000007) - #define RCC_PREDIV1_Div9 ((uint32_t)0x00000008) - #define RCC_PREDIV1_Div10 ((uint32_t)0x00000009) - #define RCC_PREDIV1_Div11 ((uint32_t)0x0000000A) - #define RCC_PREDIV1_Div12 ((uint32_t)0x0000000B) - #define RCC_PREDIV1_Div13 ((uint32_t)0x0000000C) - #define RCC_PREDIV1_Div14 ((uint32_t)0x0000000D) - #define RCC_PREDIV1_Div15 ((uint32_t)0x0000000E) - #define RCC_PREDIV1_Div16 ((uint32_t)0x0000000F) - - #define IS_RCC_PREDIV1(PREDIV1) (((PREDIV1) == RCC_PREDIV1_Div1) || ((PREDIV1) == RCC_PREDIV1_Div2) || \ - ((PREDIV1) == RCC_PREDIV1_Div3) || ((PREDIV1) == RCC_PREDIV1_Div4) || \ - ((PREDIV1) == RCC_PREDIV1_Div5) || ((PREDIV1) == RCC_PREDIV1_Div6) || \ - ((PREDIV1) == RCC_PREDIV1_Div7) || ((PREDIV1) == RCC_PREDIV1_Div8) || \ - ((PREDIV1) == RCC_PREDIV1_Div9) || ((PREDIV1) == RCC_PREDIV1_Div10) || \ - ((PREDIV1) == RCC_PREDIV1_Div11) || ((PREDIV1) == RCC_PREDIV1_Div12) || \ - ((PREDIV1) == RCC_PREDIV1_Div13) || ((PREDIV1) == RCC_PREDIV1_Div14) || \ - ((PREDIV1) == RCC_PREDIV1_Div15) || ((PREDIV1) == RCC_PREDIV1_Div16)) -#endif -/** - * @} - */ - - -/** @defgroup PREDIV1_clock_source - * @{ - */ -#ifdef STM32F10X_CL -/* PREDIV1 clock source (for STM32 connectivity line devices) */ - #define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000) - #define RCC_PREDIV1_Source_PLL2 ((uint32_t)0x00010000) - - #define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE) || \ - ((SOURCE) == RCC_PREDIV1_Source_PLL2)) -#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) -/* PREDIV1 clock source (for STM32 Value line devices) */ - #define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000) - - #define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE)) -#endif -/** - * @} - */ - -#ifdef STM32F10X_CL -/** @defgroup PREDIV2_division_factor - * @{ - */ - - #define RCC_PREDIV2_Div1 ((uint32_t)0x00000000) - #define RCC_PREDIV2_Div2 ((uint32_t)0x00000010) - #define RCC_PREDIV2_Div3 ((uint32_t)0x00000020) - #define RCC_PREDIV2_Div4 ((uint32_t)0x00000030) - #define RCC_PREDIV2_Div5 ((uint32_t)0x00000040) - #define RCC_PREDIV2_Div6 ((uint32_t)0x00000050) - #define RCC_PREDIV2_Div7 ((uint32_t)0x00000060) - #define RCC_PREDIV2_Div8 ((uint32_t)0x00000070) - #define RCC_PREDIV2_Div9 ((uint32_t)0x00000080) - #define RCC_PREDIV2_Div10 ((uint32_t)0x00000090) - #define RCC_PREDIV2_Div11 ((uint32_t)0x000000A0) - #define RCC_PREDIV2_Div12 ((uint32_t)0x000000B0) - #define RCC_PREDIV2_Div13 ((uint32_t)0x000000C0) - #define RCC_PREDIV2_Div14 ((uint32_t)0x000000D0) - #define RCC_PREDIV2_Div15 ((uint32_t)0x000000E0) - #define RCC_PREDIV2_Div16 ((uint32_t)0x000000F0) - - #define IS_RCC_PREDIV2(PREDIV2) (((PREDIV2) == RCC_PREDIV2_Div1) || ((PREDIV2) == RCC_PREDIV2_Div2) || \ - ((PREDIV2) == RCC_PREDIV2_Div3) || ((PREDIV2) == RCC_PREDIV2_Div4) || \ - ((PREDIV2) == RCC_PREDIV2_Div5) || ((PREDIV2) == RCC_PREDIV2_Div6) || \ - ((PREDIV2) == RCC_PREDIV2_Div7) || ((PREDIV2) == RCC_PREDIV2_Div8) || \ - ((PREDIV2) == RCC_PREDIV2_Div9) || ((PREDIV2) == RCC_PREDIV2_Div10) || \ - ((PREDIV2) == RCC_PREDIV2_Div11) || ((PREDIV2) == RCC_PREDIV2_Div12) || \ - ((PREDIV2) == RCC_PREDIV2_Div13) || ((PREDIV2) == RCC_PREDIV2_Div14) || \ - ((PREDIV2) == RCC_PREDIV2_Div15) || ((PREDIV2) == RCC_PREDIV2_Div16)) -/** - * @} - */ - - -/** @defgroup PLL2_multiplication_factor - * @{ - */ - - #define RCC_PLL2Mul_8 ((uint32_t)0x00000600) - #define RCC_PLL2Mul_9 ((uint32_t)0x00000700) - #define RCC_PLL2Mul_10 ((uint32_t)0x00000800) - #define RCC_PLL2Mul_11 ((uint32_t)0x00000900) - #define RCC_PLL2Mul_12 ((uint32_t)0x00000A00) - #define RCC_PLL2Mul_13 ((uint32_t)0x00000B00) - #define RCC_PLL2Mul_14 ((uint32_t)0x00000C00) - #define RCC_PLL2Mul_16 ((uint32_t)0x00000E00) - #define RCC_PLL2Mul_20 ((uint32_t)0x00000F00) - - #define IS_RCC_PLL2_MUL(MUL) (((MUL) == RCC_PLL2Mul_8) || ((MUL) == RCC_PLL2Mul_9) || \ - ((MUL) == RCC_PLL2Mul_10) || ((MUL) == RCC_PLL2Mul_11) || \ - ((MUL) == RCC_PLL2Mul_12) || ((MUL) == RCC_PLL2Mul_13) || \ - ((MUL) == RCC_PLL2Mul_14) || ((MUL) == RCC_PLL2Mul_16) || \ - ((MUL) == RCC_PLL2Mul_20)) -/** - * @} - */ - - -/** @defgroup PLL3_multiplication_factor - * @{ - */ - - #define RCC_PLL3Mul_8 ((uint32_t)0x00006000) - #define RCC_PLL3Mul_9 ((uint32_t)0x00007000) - #define RCC_PLL3Mul_10 ((uint32_t)0x00008000) - #define RCC_PLL3Mul_11 ((uint32_t)0x00009000) - #define RCC_PLL3Mul_12 ((uint32_t)0x0000A000) - #define RCC_PLL3Mul_13 ((uint32_t)0x0000B000) - #define RCC_PLL3Mul_14 ((uint32_t)0x0000C000) - #define RCC_PLL3Mul_16 ((uint32_t)0x0000E000) - #define RCC_PLL3Mul_20 ((uint32_t)0x0000F000) - - #define IS_RCC_PLL3_MUL(MUL) (((MUL) == RCC_PLL3Mul_8) || ((MUL) == RCC_PLL3Mul_9) || \ - ((MUL) == RCC_PLL3Mul_10) || ((MUL) == RCC_PLL3Mul_11) || \ - ((MUL) == RCC_PLL3Mul_12) || ((MUL) == RCC_PLL3Mul_13) || \ - ((MUL) == RCC_PLL3Mul_14) || ((MUL) == RCC_PLL3Mul_16) || \ - ((MUL) == RCC_PLL3Mul_20)) -/** - * @} - */ - -#endif /* STM32F10X_CL */ - - -/** @defgroup System_clock_source - * @{ - */ - -#define RCC_SYSCLKSource_HSI ((uint32_t)0x00000000) -#define RCC_SYSCLKSource_HSE ((uint32_t)0x00000001) -#define RCC_SYSCLKSource_PLLCLK ((uint32_t)0x00000002) -#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \ - ((SOURCE) == RCC_SYSCLKSource_HSE) || \ - ((SOURCE) == RCC_SYSCLKSource_PLLCLK)) -/** - * @} - */ - -/** @defgroup AHB_clock_source - * @{ - */ - -#define RCC_SYSCLK_Div1 ((uint32_t)0x00000000) -#define RCC_SYSCLK_Div2 ((uint32_t)0x00000080) -#define RCC_SYSCLK_Div4 ((uint32_t)0x00000090) -#define RCC_SYSCLK_Div8 ((uint32_t)0x000000A0) -#define RCC_SYSCLK_Div16 ((uint32_t)0x000000B0) -#define RCC_SYSCLK_Div64 ((uint32_t)0x000000C0) -#define RCC_SYSCLK_Div128 ((uint32_t)0x000000D0) -#define RCC_SYSCLK_Div256 ((uint32_t)0x000000E0) -#define RCC_SYSCLK_Div512 ((uint32_t)0x000000F0) -#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \ - ((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \ - ((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \ - ((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \ - ((HCLK) == RCC_SYSCLK_Div512)) -/** - * @} - */ - -/** @defgroup APB1_APB2_clock_source - * @{ - */ - -#define RCC_HCLK_Div1 ((uint32_t)0x00000000) -#define RCC_HCLK_Div2 ((uint32_t)0x00000400) -#define RCC_HCLK_Div4 ((uint32_t)0x00000500) -#define RCC_HCLK_Div8 ((uint32_t)0x00000600) -#define RCC_HCLK_Div16 ((uint32_t)0x00000700) -#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \ - ((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \ - ((PCLK) == RCC_HCLK_Div16)) -/** - * @} - */ - -/** @defgroup RCC_Interrupt_source - * @{ - */ - -#define RCC_IT_LSIRDY ((uint8_t)0x01) -#define RCC_IT_LSERDY ((uint8_t)0x02) -#define RCC_IT_HSIRDY ((uint8_t)0x04) -#define RCC_IT_HSERDY ((uint8_t)0x08) -#define RCC_IT_PLLRDY ((uint8_t)0x10) -#define RCC_IT_CSS ((uint8_t)0x80) - -#ifndef STM32F10X_CL - #define IS_RCC_IT(IT) ((((IT) & (uint8_t)0xE0) == 0x00) && ((IT) != 0x00)) - #define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \ - ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \ - ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS)) - #define IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x60) == 0x00) && ((IT) != 0x00)) -#else - #define RCC_IT_PLL2RDY ((uint8_t)0x20) - #define RCC_IT_PLL3RDY ((uint8_t)0x40) - #define IS_RCC_IT(IT) ((((IT) & (uint8_t)0x80) == 0x00) && ((IT) != 0x00)) - #define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \ - ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \ - ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS) || \ - ((IT) == RCC_IT_PLL2RDY) || ((IT) == RCC_IT_PLL3RDY)) - #define IS_RCC_CLEAR_IT(IT) ((IT) != 0x00) -#endif /* STM32F10X_CL */ - - -/** - * @} - */ - -#ifndef STM32F10X_CL -/** @defgroup USB_Device_clock_source - * @{ - */ - - #define RCC_USBCLKSource_PLLCLK_1Div5 ((uint8_t)0x00) - #define RCC_USBCLKSource_PLLCLK_Div1 ((uint8_t)0x01) - - #define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \ - ((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1)) -/** - * @} - */ -#else -/** @defgroup USB_OTG_FS_clock_source - * @{ - */ - #define RCC_OTGFSCLKSource_PLLVCO_Div3 ((uint8_t)0x00) - #define RCC_OTGFSCLKSource_PLLVCO_Div2 ((uint8_t)0x01) - - #define IS_RCC_OTGFSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div3) || \ - ((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div2)) -/** - * @} - */ -#endif /* STM32F10X_CL */ - - -#ifdef STM32F10X_CL -/** @defgroup I2S2_clock_source - * @{ - */ - #define RCC_I2S2CLKSource_SYSCLK ((uint8_t)0x00) - #define RCC_I2S2CLKSource_PLL3_VCO ((uint8_t)0x01) - - #define IS_RCC_I2S2CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_SYSCLK) || \ - ((SOURCE) == RCC_I2S2CLKSource_PLL3_VCO)) -/** - * @} - */ - -/** @defgroup I2S3_clock_source - * @{ - */ - #define RCC_I2S3CLKSource_SYSCLK ((uint8_t)0x00) - #define RCC_I2S3CLKSource_PLL3_VCO ((uint8_t)0x01) - - #define IS_RCC_I2S3CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S3CLKSource_SYSCLK) || \ - ((SOURCE) == RCC_I2S3CLKSource_PLL3_VCO)) -/** - * @} - */ -#endif /* STM32F10X_CL */ - - -/** @defgroup ADC_clock_source - * @{ - */ - -#define RCC_PCLK2_Div2 ((uint32_t)0x00000000) -#define RCC_PCLK2_Div4 ((uint32_t)0x00004000) -#define RCC_PCLK2_Div6 ((uint32_t)0x00008000) -#define RCC_PCLK2_Div8 ((uint32_t)0x0000C000) -#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_PCLK2_Div2) || ((ADCCLK) == RCC_PCLK2_Div4) || \ - ((ADCCLK) == RCC_PCLK2_Div6) || ((ADCCLK) == RCC_PCLK2_Div8)) -/** - * @} - */ - -/** @defgroup LSE_configuration - * @{ - */ - -#define RCC_LSE_OFF ((uint8_t)0x00) -#define RCC_LSE_ON ((uint8_t)0x01) -#define RCC_LSE_Bypass ((uint8_t)0x04) -#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \ - ((LSE) == RCC_LSE_Bypass)) -/** - * @} - */ - -/** @defgroup RTC_clock_source - * @{ - */ - -#define RCC_RTCCLKSource_LSE ((uint32_t)0x00000100) -#define RCC_RTCCLKSource_LSI ((uint32_t)0x00000200) -#define RCC_RTCCLKSource_HSE_Div128 ((uint32_t)0x00000300) -#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \ - ((SOURCE) == RCC_RTCCLKSource_LSI) || \ - ((SOURCE) == RCC_RTCCLKSource_HSE_Div128)) -/** - * @} - */ - -/** @defgroup AHB_peripheral - * @{ - */ - -#define RCC_AHBPeriph_DMA1 ((uint32_t)0x00000001) -#define RCC_AHBPeriph_DMA2 ((uint32_t)0x00000002) -#define RCC_AHBPeriph_SRAM ((uint32_t)0x00000004) -#define RCC_AHBPeriph_FLITF ((uint32_t)0x00000010) -#define RCC_AHBPeriph_CRC ((uint32_t)0x00000040) - -#ifndef STM32F10X_CL - #define RCC_AHBPeriph_FSMC ((uint32_t)0x00000100) - #define RCC_AHBPeriph_SDIO ((uint32_t)0x00000400) - #define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFAA8) == 0x00) && ((PERIPH) != 0x00)) -#else - #define RCC_AHBPeriph_OTG_FS ((uint32_t)0x00001000) - #define RCC_AHBPeriph_ETH_MAC ((uint32_t)0x00004000) - #define RCC_AHBPeriph_ETH_MAC_Tx ((uint32_t)0x00008000) - #define RCC_AHBPeriph_ETH_MAC_Rx ((uint32_t)0x00010000) - - #define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFE2FA8) == 0x00) && ((PERIPH) != 0x00)) - #define IS_RCC_AHB_PERIPH_RESET(PERIPH) ((((PERIPH) & 0xFFFFAFFF) == 0x00) && ((PERIPH) != 0x00)) -#endif /* STM32F10X_CL */ -/** - * @} - */ - -/** @defgroup APB2_peripheral - * @{ - */ - -#define RCC_APB2Periph_AFIO ((uint32_t)0x00000001) -#define RCC_APB2Periph_GPIOA ((uint32_t)0x00000004) -#define RCC_APB2Periph_GPIOB ((uint32_t)0x00000008) -#define RCC_APB2Periph_GPIOC ((uint32_t)0x00000010) -#define RCC_APB2Periph_GPIOD ((uint32_t)0x00000020) -#define RCC_APB2Periph_GPIOE ((uint32_t)0x00000040) -#define RCC_APB2Periph_GPIOF ((uint32_t)0x00000080) -#define RCC_APB2Periph_GPIOG ((uint32_t)0x00000100) -#define RCC_APB2Periph_ADC1 ((uint32_t)0x00000200) -#define RCC_APB2Periph_ADC2 ((uint32_t)0x00000400) -#define RCC_APB2Periph_TIM1 ((uint32_t)0x00000800) -#define RCC_APB2Periph_SPI1 ((uint32_t)0x00001000) -#define RCC_APB2Periph_TIM8 ((uint32_t)0x00002000) -#define RCC_APB2Periph_USART1 ((uint32_t)0x00004000) -#define RCC_APB2Periph_ADC3 ((uint32_t)0x00008000) -#define RCC_APB2Periph_TIM15 ((uint32_t)0x00010000) -#define RCC_APB2Periph_TIM16 ((uint32_t)0x00020000) -#define RCC_APB2Periph_TIM17 ((uint32_t)0x00040000) -#define RCC_APB2Periph_TIM9 ((uint32_t)0x00080000) -#define RCC_APB2Periph_TIM10 ((uint32_t)0x00100000) -#define RCC_APB2Periph_TIM11 ((uint32_t)0x00200000) - -#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFC00002) == 0x00) && ((PERIPH) != 0x00)) -/** - * @} - */ - -/** @defgroup APB1_peripheral - * @{ - */ - -#define RCC_APB1Periph_TIM2 ((uint32_t)0x00000001) -#define RCC_APB1Periph_TIM3 ((uint32_t)0x00000002) -#define RCC_APB1Periph_TIM4 ((uint32_t)0x00000004) -#define RCC_APB1Periph_TIM5 ((uint32_t)0x00000008) -#define RCC_APB1Periph_TIM6 ((uint32_t)0x00000010) -#define RCC_APB1Periph_TIM7 ((uint32_t)0x00000020) -#define RCC_APB1Periph_TIM12 ((uint32_t)0x00000040) -#define RCC_APB1Periph_TIM13 ((uint32_t)0x00000080) -#define RCC_APB1Periph_TIM14 ((uint32_t)0x00000100) -#define RCC_APB1Periph_WWDG ((uint32_t)0x00000800) -#define RCC_APB1Periph_SPI2 ((uint32_t)0x00004000) -#define RCC_APB1Periph_SPI3 ((uint32_t)0x00008000) -#define RCC_APB1Periph_USART2 ((uint32_t)0x00020000) -#define RCC_APB1Periph_USART3 ((uint32_t)0x00040000) -#define RCC_APB1Periph_UART4 ((uint32_t)0x00080000) -#define RCC_APB1Periph_UART5 ((uint32_t)0x00100000) -#define RCC_APB1Periph_I2C1 ((uint32_t)0x00200000) -#define RCC_APB1Periph_I2C2 ((uint32_t)0x00400000) -#define RCC_APB1Periph_USB ((uint32_t)0x00800000) -#define RCC_APB1Periph_CAN1 ((uint32_t)0x02000000) -#define RCC_APB1Periph_CAN2 ((uint32_t)0x04000000) -#define RCC_APB1Periph_BKP ((uint32_t)0x08000000) -#define RCC_APB1Periph_PWR ((uint32_t)0x10000000) -#define RCC_APB1Periph_DAC ((uint32_t)0x20000000) -#define RCC_APB1Periph_CEC ((uint32_t)0x40000000) - -#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0x81013600) == 0x00) && ((PERIPH) != 0x00)) - -/** - * @} - */ - -/** @defgroup Clock_source_to_output_on_MCO_pin - * @{ - */ - -#define RCC_MCO_NoClock ((uint8_t)0x00) -#define RCC_MCO_SYSCLK ((uint8_t)0x04) -#define RCC_MCO_HSI ((uint8_t)0x05) -#define RCC_MCO_HSE ((uint8_t)0x06) -#define RCC_MCO_PLLCLK_Div2 ((uint8_t)0x07) - -#ifndef STM32F10X_CL - #define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \ - ((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \ - ((MCO) == RCC_MCO_PLLCLK_Div2)) -#else - #define RCC_MCO_PLL2CLK ((uint8_t)0x08) - #define RCC_MCO_PLL3CLK_Div2 ((uint8_t)0x09) - #define RCC_MCO_XT1 ((uint8_t)0x0A) - #define RCC_MCO_PLL3CLK ((uint8_t)0x0B) - - #define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \ - ((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \ - ((MCO) == RCC_MCO_PLLCLK_Div2) || ((MCO) == RCC_MCO_PLL2CLK) || \ - ((MCO) == RCC_MCO_PLL3CLK_Div2) || ((MCO) == RCC_MCO_XT1) || \ - ((MCO) == RCC_MCO_PLL3CLK)) -#endif /* STM32F10X_CL */ - -/** - * @} - */ - -/** @defgroup RCC_Flag - * @{ - */ - -#define RCC_FLAG_HSIRDY ((uint8_t)0x21) -#define RCC_FLAG_HSERDY ((uint8_t)0x31) -#define RCC_FLAG_PLLRDY ((uint8_t)0x39) -#define RCC_FLAG_LSERDY ((uint8_t)0x41) -#define RCC_FLAG_LSIRDY ((uint8_t)0x61) -#define RCC_FLAG_PINRST ((uint8_t)0x7A) -#define RCC_FLAG_PORRST ((uint8_t)0x7B) -#define RCC_FLAG_SFTRST ((uint8_t)0x7C) -#define RCC_FLAG_IWDGRST ((uint8_t)0x7D) -#define RCC_FLAG_WWDGRST ((uint8_t)0x7E) -#define RCC_FLAG_LPWRRST ((uint8_t)0x7F) - -#ifndef STM32F10X_CL - #define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \ - ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \ - ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \ - ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \ - ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \ - ((FLAG) == RCC_FLAG_LPWRRST)) -#else - #define RCC_FLAG_PLL2RDY ((uint8_t)0x3B) - #define RCC_FLAG_PLL3RDY ((uint8_t)0x3D) - #define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \ - ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \ - ((FLAG) == RCC_FLAG_PLL2RDY) || ((FLAG) == RCC_FLAG_PLL3RDY) || \ - ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \ - ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \ - ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \ - ((FLAG) == RCC_FLAG_LPWRRST)) -#endif /* STM32F10X_CL */ - -#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F) -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup RCC_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup RCC_Exported_Functions - * @{ - */ - -void RCC_DeInit(void); -void RCC_HSEConfig(uint32_t RCC_HSE); -ErrorStatus RCC_WaitForHSEStartUp(void); -void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue); -void RCC_HSICmd(FunctionalState NewState); -void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul); -void RCC_PLLCmd(FunctionalState NewState); - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) - void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div); -#endif - -#ifdef STM32F10X_CL - void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div); - void RCC_PLL2Config(uint32_t RCC_PLL2Mul); - void RCC_PLL2Cmd(FunctionalState NewState); - void RCC_PLL3Config(uint32_t RCC_PLL3Mul); - void RCC_PLL3Cmd(FunctionalState NewState); -#endif /* STM32F10X_CL */ - -void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource); -uint8_t RCC_GetSYSCLKSource(void); -void RCC_HCLKConfig(uint32_t RCC_SYSCLK); -void RCC_PCLK1Config(uint32_t RCC_HCLK); -void RCC_PCLK2Config(uint32_t RCC_HCLK); -void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState); - -#ifndef STM32F10X_CL - void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource); -#else - void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource); -#endif /* STM32F10X_CL */ - -void RCC_ADCCLKConfig(uint32_t RCC_PCLK2); - -#ifdef STM32F10X_CL - void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource); - void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource); -#endif /* STM32F10X_CL */ - -void RCC_LSEConfig(uint8_t RCC_LSE); -void RCC_LSICmd(FunctionalState NewState); -void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource); -void RCC_RTCCLKCmd(FunctionalState NewState); -void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks); -void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState); -void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); -void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); - -#ifdef STM32F10X_CL -void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState); -#endif /* STM32F10X_CL */ - -void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); -void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); -void RCC_BackupResetCmd(FunctionalState NewState); -void RCC_ClockSecuritySystemCmd(FunctionalState NewState); -void RCC_MCOConfig(uint8_t RCC_MCO); -FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG); -void RCC_ClearFlag(void); -ITStatus RCC_GetITStatus(uint8_t RCC_IT); -void RCC_ClearITPendingBit(uint8_t RCC_IT); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_RCC_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_rcc.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the RCC firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_RCC_H +#define __STM32F10x_RCC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RCC + * @{ + */ + +/** @defgroup RCC_Exported_Types + * @{ + */ + +typedef struct +{ + uint32_t SYSCLK_Frequency; /*!< returns SYSCLK clock frequency expressed in Hz */ + uint32_t HCLK_Frequency; /*!< returns HCLK clock frequency expressed in Hz */ + uint32_t PCLK1_Frequency; /*!< returns PCLK1 clock frequency expressed in Hz */ + uint32_t PCLK2_Frequency; /*!< returns PCLK2 clock frequency expressed in Hz */ + uint32_t ADCCLK_Frequency; /*!< returns ADCCLK clock frequency expressed in Hz */ +}RCC_ClocksTypeDef; + +/** + * @} + */ + +/** @defgroup RCC_Exported_Constants + * @{ + */ + +/** @defgroup HSE_configuration + * @{ + */ + +#define RCC_HSE_OFF ((uint32_t)0x00000000) +#define RCC_HSE_ON ((uint32_t)0x00010000) +#define RCC_HSE_Bypass ((uint32_t)0x00040000) +#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \ + ((HSE) == RCC_HSE_Bypass)) + +/** + * @} + */ + +/** @defgroup PLL_entry_clock_source + * @{ + */ + +#define RCC_PLLSource_HSI_Div2 ((uint32_t)0x00000000) + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_CL) + #define RCC_PLLSource_HSE_Div1 ((uint32_t)0x00010000) + #define RCC_PLLSource_HSE_Div2 ((uint32_t)0x00030000) + #define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \ + ((SOURCE) == RCC_PLLSource_HSE_Div1) || \ + ((SOURCE) == RCC_PLLSource_HSE_Div2)) +#else + #define RCC_PLLSource_PREDIV1 ((uint32_t)0x00010000) + #define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \ + ((SOURCE) == RCC_PLLSource_PREDIV1)) +#endif /* STM32F10X_CL */ + +/** + * @} + */ + +/** @defgroup PLL_multiplication_factor + * @{ + */ +#ifndef STM32F10X_CL + #define RCC_PLLMul_2 ((uint32_t)0x00000000) + #define RCC_PLLMul_3 ((uint32_t)0x00040000) + #define RCC_PLLMul_4 ((uint32_t)0x00080000) + #define RCC_PLLMul_5 ((uint32_t)0x000C0000) + #define RCC_PLLMul_6 ((uint32_t)0x00100000) + #define RCC_PLLMul_7 ((uint32_t)0x00140000) + #define RCC_PLLMul_8 ((uint32_t)0x00180000) + #define RCC_PLLMul_9 ((uint32_t)0x001C0000) + #define RCC_PLLMul_10 ((uint32_t)0x00200000) + #define RCC_PLLMul_11 ((uint32_t)0x00240000) + #define RCC_PLLMul_12 ((uint32_t)0x00280000) + #define RCC_PLLMul_13 ((uint32_t)0x002C0000) + #define RCC_PLLMul_14 ((uint32_t)0x00300000) + #define RCC_PLLMul_15 ((uint32_t)0x00340000) + #define RCC_PLLMul_16 ((uint32_t)0x00380000) + #define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3) || \ + ((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \ + ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \ + ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \ + ((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \ + ((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \ + ((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \ + ((MUL) == RCC_PLLMul_16)) + +#else + #define RCC_PLLMul_4 ((uint32_t)0x00080000) + #define RCC_PLLMul_5 ((uint32_t)0x000C0000) + #define RCC_PLLMul_6 ((uint32_t)0x00100000) + #define RCC_PLLMul_7 ((uint32_t)0x00140000) + #define RCC_PLLMul_8 ((uint32_t)0x00180000) + #define RCC_PLLMul_9 ((uint32_t)0x001C0000) + #define RCC_PLLMul_6_5 ((uint32_t)0x00340000) + + #define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \ + ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \ + ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \ + ((MUL) == RCC_PLLMul_6_5)) +#endif /* STM32F10X_CL */ +/** + * @} + */ + +/** @defgroup PREDIV1_division_factor + * @{ + */ +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) + #define RCC_PREDIV1_Div1 ((uint32_t)0x00000000) + #define RCC_PREDIV1_Div2 ((uint32_t)0x00000001) + #define RCC_PREDIV1_Div3 ((uint32_t)0x00000002) + #define RCC_PREDIV1_Div4 ((uint32_t)0x00000003) + #define RCC_PREDIV1_Div5 ((uint32_t)0x00000004) + #define RCC_PREDIV1_Div6 ((uint32_t)0x00000005) + #define RCC_PREDIV1_Div7 ((uint32_t)0x00000006) + #define RCC_PREDIV1_Div8 ((uint32_t)0x00000007) + #define RCC_PREDIV1_Div9 ((uint32_t)0x00000008) + #define RCC_PREDIV1_Div10 ((uint32_t)0x00000009) + #define RCC_PREDIV1_Div11 ((uint32_t)0x0000000A) + #define RCC_PREDIV1_Div12 ((uint32_t)0x0000000B) + #define RCC_PREDIV1_Div13 ((uint32_t)0x0000000C) + #define RCC_PREDIV1_Div14 ((uint32_t)0x0000000D) + #define RCC_PREDIV1_Div15 ((uint32_t)0x0000000E) + #define RCC_PREDIV1_Div16 ((uint32_t)0x0000000F) + + #define IS_RCC_PREDIV1(PREDIV1) (((PREDIV1) == RCC_PREDIV1_Div1) || ((PREDIV1) == RCC_PREDIV1_Div2) || \ + ((PREDIV1) == RCC_PREDIV1_Div3) || ((PREDIV1) == RCC_PREDIV1_Div4) || \ + ((PREDIV1) == RCC_PREDIV1_Div5) || ((PREDIV1) == RCC_PREDIV1_Div6) || \ + ((PREDIV1) == RCC_PREDIV1_Div7) || ((PREDIV1) == RCC_PREDIV1_Div8) || \ + ((PREDIV1) == RCC_PREDIV1_Div9) || ((PREDIV1) == RCC_PREDIV1_Div10) || \ + ((PREDIV1) == RCC_PREDIV1_Div11) || ((PREDIV1) == RCC_PREDIV1_Div12) || \ + ((PREDIV1) == RCC_PREDIV1_Div13) || ((PREDIV1) == RCC_PREDIV1_Div14) || \ + ((PREDIV1) == RCC_PREDIV1_Div15) || ((PREDIV1) == RCC_PREDIV1_Div16)) +#endif +/** + * @} + */ + + +/** @defgroup PREDIV1_clock_source + * @{ + */ +#ifdef STM32F10X_CL +/* PREDIV1 clock source (for STM32 connectivity line devices) */ + #define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000) + #define RCC_PREDIV1_Source_PLL2 ((uint32_t)0x00010000) + + #define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE) || \ + ((SOURCE) == RCC_PREDIV1_Source_PLL2)) +#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/* PREDIV1 clock source (for STM32 Value line devices) */ + #define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000) + + #define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE)) +#endif +/** + * @} + */ + +#ifdef STM32F10X_CL +/** @defgroup PREDIV2_division_factor + * @{ + */ + + #define RCC_PREDIV2_Div1 ((uint32_t)0x00000000) + #define RCC_PREDIV2_Div2 ((uint32_t)0x00000010) + #define RCC_PREDIV2_Div3 ((uint32_t)0x00000020) + #define RCC_PREDIV2_Div4 ((uint32_t)0x00000030) + #define RCC_PREDIV2_Div5 ((uint32_t)0x00000040) + #define RCC_PREDIV2_Div6 ((uint32_t)0x00000050) + #define RCC_PREDIV2_Div7 ((uint32_t)0x00000060) + #define RCC_PREDIV2_Div8 ((uint32_t)0x00000070) + #define RCC_PREDIV2_Div9 ((uint32_t)0x00000080) + #define RCC_PREDIV2_Div10 ((uint32_t)0x00000090) + #define RCC_PREDIV2_Div11 ((uint32_t)0x000000A0) + #define RCC_PREDIV2_Div12 ((uint32_t)0x000000B0) + #define RCC_PREDIV2_Div13 ((uint32_t)0x000000C0) + #define RCC_PREDIV2_Div14 ((uint32_t)0x000000D0) + #define RCC_PREDIV2_Div15 ((uint32_t)0x000000E0) + #define RCC_PREDIV2_Div16 ((uint32_t)0x000000F0) + + #define IS_RCC_PREDIV2(PREDIV2) (((PREDIV2) == RCC_PREDIV2_Div1) || ((PREDIV2) == RCC_PREDIV2_Div2) || \ + ((PREDIV2) == RCC_PREDIV2_Div3) || ((PREDIV2) == RCC_PREDIV2_Div4) || \ + ((PREDIV2) == RCC_PREDIV2_Div5) || ((PREDIV2) == RCC_PREDIV2_Div6) || \ + ((PREDIV2) == RCC_PREDIV2_Div7) || ((PREDIV2) == RCC_PREDIV2_Div8) || \ + ((PREDIV2) == RCC_PREDIV2_Div9) || ((PREDIV2) == RCC_PREDIV2_Div10) || \ + ((PREDIV2) == RCC_PREDIV2_Div11) || ((PREDIV2) == RCC_PREDIV2_Div12) || \ + ((PREDIV2) == RCC_PREDIV2_Div13) || ((PREDIV2) == RCC_PREDIV2_Div14) || \ + ((PREDIV2) == RCC_PREDIV2_Div15) || ((PREDIV2) == RCC_PREDIV2_Div16)) +/** + * @} + */ + + +/** @defgroup PLL2_multiplication_factor + * @{ + */ + + #define RCC_PLL2Mul_8 ((uint32_t)0x00000600) + #define RCC_PLL2Mul_9 ((uint32_t)0x00000700) + #define RCC_PLL2Mul_10 ((uint32_t)0x00000800) + #define RCC_PLL2Mul_11 ((uint32_t)0x00000900) + #define RCC_PLL2Mul_12 ((uint32_t)0x00000A00) + #define RCC_PLL2Mul_13 ((uint32_t)0x00000B00) + #define RCC_PLL2Mul_14 ((uint32_t)0x00000C00) + #define RCC_PLL2Mul_16 ((uint32_t)0x00000E00) + #define RCC_PLL2Mul_20 ((uint32_t)0x00000F00) + + #define IS_RCC_PLL2_MUL(MUL) (((MUL) == RCC_PLL2Mul_8) || ((MUL) == RCC_PLL2Mul_9) || \ + ((MUL) == RCC_PLL2Mul_10) || ((MUL) == RCC_PLL2Mul_11) || \ + ((MUL) == RCC_PLL2Mul_12) || ((MUL) == RCC_PLL2Mul_13) || \ + ((MUL) == RCC_PLL2Mul_14) || ((MUL) == RCC_PLL2Mul_16) || \ + ((MUL) == RCC_PLL2Mul_20)) +/** + * @} + */ + + +/** @defgroup PLL3_multiplication_factor + * @{ + */ + + #define RCC_PLL3Mul_8 ((uint32_t)0x00006000) + #define RCC_PLL3Mul_9 ((uint32_t)0x00007000) + #define RCC_PLL3Mul_10 ((uint32_t)0x00008000) + #define RCC_PLL3Mul_11 ((uint32_t)0x00009000) + #define RCC_PLL3Mul_12 ((uint32_t)0x0000A000) + #define RCC_PLL3Mul_13 ((uint32_t)0x0000B000) + #define RCC_PLL3Mul_14 ((uint32_t)0x0000C000) + #define RCC_PLL3Mul_16 ((uint32_t)0x0000E000) + #define RCC_PLL3Mul_20 ((uint32_t)0x0000F000) + + #define IS_RCC_PLL3_MUL(MUL) (((MUL) == RCC_PLL3Mul_8) || ((MUL) == RCC_PLL3Mul_9) || \ + ((MUL) == RCC_PLL3Mul_10) || ((MUL) == RCC_PLL3Mul_11) || \ + ((MUL) == RCC_PLL3Mul_12) || ((MUL) == RCC_PLL3Mul_13) || \ + ((MUL) == RCC_PLL3Mul_14) || ((MUL) == RCC_PLL3Mul_16) || \ + ((MUL) == RCC_PLL3Mul_20)) +/** + * @} + */ + +#endif /* STM32F10X_CL */ + + +/** @defgroup System_clock_source + * @{ + */ + +#define RCC_SYSCLKSource_HSI ((uint32_t)0x00000000) +#define RCC_SYSCLKSource_HSE ((uint32_t)0x00000001) +#define RCC_SYSCLKSource_PLLCLK ((uint32_t)0x00000002) +#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \ + ((SOURCE) == RCC_SYSCLKSource_HSE) || \ + ((SOURCE) == RCC_SYSCLKSource_PLLCLK)) +/** + * @} + */ + +/** @defgroup AHB_clock_source + * @{ + */ + +#define RCC_SYSCLK_Div1 ((uint32_t)0x00000000) +#define RCC_SYSCLK_Div2 ((uint32_t)0x00000080) +#define RCC_SYSCLK_Div4 ((uint32_t)0x00000090) +#define RCC_SYSCLK_Div8 ((uint32_t)0x000000A0) +#define RCC_SYSCLK_Div16 ((uint32_t)0x000000B0) +#define RCC_SYSCLK_Div64 ((uint32_t)0x000000C0) +#define RCC_SYSCLK_Div128 ((uint32_t)0x000000D0) +#define RCC_SYSCLK_Div256 ((uint32_t)0x000000E0) +#define RCC_SYSCLK_Div512 ((uint32_t)0x000000F0) +#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \ + ((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \ + ((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \ + ((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \ + ((HCLK) == RCC_SYSCLK_Div512)) +/** + * @} + */ + +/** @defgroup APB1_APB2_clock_source + * @{ + */ + +#define RCC_HCLK_Div1 ((uint32_t)0x00000000) +#define RCC_HCLK_Div2 ((uint32_t)0x00000400) +#define RCC_HCLK_Div4 ((uint32_t)0x00000500) +#define RCC_HCLK_Div8 ((uint32_t)0x00000600) +#define RCC_HCLK_Div16 ((uint32_t)0x00000700) +#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \ + ((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \ + ((PCLK) == RCC_HCLK_Div16)) +/** + * @} + */ + +/** @defgroup RCC_Interrupt_source + * @{ + */ + +#define RCC_IT_LSIRDY ((uint8_t)0x01) +#define RCC_IT_LSERDY ((uint8_t)0x02) +#define RCC_IT_HSIRDY ((uint8_t)0x04) +#define RCC_IT_HSERDY ((uint8_t)0x08) +#define RCC_IT_PLLRDY ((uint8_t)0x10) +#define RCC_IT_CSS ((uint8_t)0x80) + +#ifndef STM32F10X_CL + #define IS_RCC_IT(IT) ((((IT) & (uint8_t)0xE0) == 0x00) && ((IT) != 0x00)) + #define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \ + ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \ + ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS)) + #define IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x60) == 0x00) && ((IT) != 0x00)) +#else + #define RCC_IT_PLL2RDY ((uint8_t)0x20) + #define RCC_IT_PLL3RDY ((uint8_t)0x40) + #define IS_RCC_IT(IT) ((((IT) & (uint8_t)0x80) == 0x00) && ((IT) != 0x00)) + #define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \ + ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \ + ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS) || \ + ((IT) == RCC_IT_PLL2RDY) || ((IT) == RCC_IT_PLL3RDY)) + #define IS_RCC_CLEAR_IT(IT) ((IT) != 0x00) +#endif /* STM32F10X_CL */ + + +/** + * @} + */ + +#ifndef STM32F10X_CL +/** @defgroup USB_Device_clock_source + * @{ + */ + + #define RCC_USBCLKSource_PLLCLK_1Div5 ((uint8_t)0x00) + #define RCC_USBCLKSource_PLLCLK_Div1 ((uint8_t)0x01) + + #define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \ + ((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1)) +/** + * @} + */ +#else +/** @defgroup USB_OTG_FS_clock_source + * @{ + */ + #define RCC_OTGFSCLKSource_PLLVCO_Div3 ((uint8_t)0x00) + #define RCC_OTGFSCLKSource_PLLVCO_Div2 ((uint8_t)0x01) + + #define IS_RCC_OTGFSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div3) || \ + ((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div2)) +/** + * @} + */ +#endif /* STM32F10X_CL */ + + +#ifdef STM32F10X_CL +/** @defgroup I2S2_clock_source + * @{ + */ + #define RCC_I2S2CLKSource_SYSCLK ((uint8_t)0x00) + #define RCC_I2S2CLKSource_PLL3_VCO ((uint8_t)0x01) + + #define IS_RCC_I2S2CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_SYSCLK) || \ + ((SOURCE) == RCC_I2S2CLKSource_PLL3_VCO)) +/** + * @} + */ + +/** @defgroup I2S3_clock_source + * @{ + */ + #define RCC_I2S3CLKSource_SYSCLK ((uint8_t)0x00) + #define RCC_I2S3CLKSource_PLL3_VCO ((uint8_t)0x01) + + #define IS_RCC_I2S3CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S3CLKSource_SYSCLK) || \ + ((SOURCE) == RCC_I2S3CLKSource_PLL3_VCO)) +/** + * @} + */ +#endif /* STM32F10X_CL */ + + +/** @defgroup ADC_clock_source + * @{ + */ + +#define RCC_PCLK2_Div2 ((uint32_t)0x00000000) +#define RCC_PCLK2_Div4 ((uint32_t)0x00004000) +#define RCC_PCLK2_Div6 ((uint32_t)0x00008000) +#define RCC_PCLK2_Div8 ((uint32_t)0x0000C000) +#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_PCLK2_Div2) || ((ADCCLK) == RCC_PCLK2_Div4) || \ + ((ADCCLK) == RCC_PCLK2_Div6) || ((ADCCLK) == RCC_PCLK2_Div8)) +/** + * @} + */ + +/** @defgroup LSE_configuration + * @{ + */ + +#define RCC_LSE_OFF ((uint8_t)0x00) +#define RCC_LSE_ON ((uint8_t)0x01) +#define RCC_LSE_Bypass ((uint8_t)0x04) +#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \ + ((LSE) == RCC_LSE_Bypass)) +/** + * @} + */ + +/** @defgroup RTC_clock_source + * @{ + */ + +#define RCC_RTCCLKSource_LSE ((uint32_t)0x00000100) +#define RCC_RTCCLKSource_LSI ((uint32_t)0x00000200) +#define RCC_RTCCLKSource_HSE_Div128 ((uint32_t)0x00000300) +#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \ + ((SOURCE) == RCC_RTCCLKSource_LSI) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div128)) +/** + * @} + */ + +/** @defgroup AHB_peripheral + * @{ + */ + +#define RCC_AHBPeriph_DMA1 ((uint32_t)0x00000001) +#define RCC_AHBPeriph_DMA2 ((uint32_t)0x00000002) +#define RCC_AHBPeriph_SRAM ((uint32_t)0x00000004) +#define RCC_AHBPeriph_FLITF ((uint32_t)0x00000010) +#define RCC_AHBPeriph_CRC ((uint32_t)0x00000040) + +#ifndef STM32F10X_CL + #define RCC_AHBPeriph_FSMC ((uint32_t)0x00000100) + #define RCC_AHBPeriph_SDIO ((uint32_t)0x00000400) + #define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFAA8) == 0x00) && ((PERIPH) != 0x00)) +#else + #define RCC_AHBPeriph_OTG_FS ((uint32_t)0x00001000) + #define RCC_AHBPeriph_ETH_MAC ((uint32_t)0x00004000) + #define RCC_AHBPeriph_ETH_MAC_Tx ((uint32_t)0x00008000) + #define RCC_AHBPeriph_ETH_MAC_Rx ((uint32_t)0x00010000) + + #define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFE2FA8) == 0x00) && ((PERIPH) != 0x00)) + #define IS_RCC_AHB_PERIPH_RESET(PERIPH) ((((PERIPH) & 0xFFFFAFFF) == 0x00) && ((PERIPH) != 0x00)) +#endif /* STM32F10X_CL */ +/** + * @} + */ + +/** @defgroup APB2_peripheral + * @{ + */ + +#define RCC_APB2Periph_AFIO ((uint32_t)0x00000001) +#define RCC_APB2Periph_GPIOA ((uint32_t)0x00000004) +#define RCC_APB2Periph_GPIOB ((uint32_t)0x00000008) +#define RCC_APB2Periph_GPIOC ((uint32_t)0x00000010) +#define RCC_APB2Periph_GPIOD ((uint32_t)0x00000020) +#define RCC_APB2Periph_GPIOE ((uint32_t)0x00000040) +#define RCC_APB2Periph_GPIOF ((uint32_t)0x00000080) +#define RCC_APB2Periph_GPIOG ((uint32_t)0x00000100) +#define RCC_APB2Periph_ADC1 ((uint32_t)0x00000200) +#define RCC_APB2Periph_ADC2 ((uint32_t)0x00000400) +#define RCC_APB2Periph_TIM1 ((uint32_t)0x00000800) +#define RCC_APB2Periph_SPI1 ((uint32_t)0x00001000) +#define RCC_APB2Periph_TIM8 ((uint32_t)0x00002000) +#define RCC_APB2Periph_USART1 ((uint32_t)0x00004000) +#define RCC_APB2Periph_ADC3 ((uint32_t)0x00008000) +#define RCC_APB2Periph_TIM15 ((uint32_t)0x00010000) +#define RCC_APB2Periph_TIM16 ((uint32_t)0x00020000) +#define RCC_APB2Periph_TIM17 ((uint32_t)0x00040000) +#define RCC_APB2Periph_TIM9 ((uint32_t)0x00080000) +#define RCC_APB2Periph_TIM10 ((uint32_t)0x00100000) +#define RCC_APB2Periph_TIM11 ((uint32_t)0x00200000) + +#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFC00002) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup APB1_peripheral + * @{ + */ + +#define RCC_APB1Periph_TIM2 ((uint32_t)0x00000001) +#define RCC_APB1Periph_TIM3 ((uint32_t)0x00000002) +#define RCC_APB1Periph_TIM4 ((uint32_t)0x00000004) +#define RCC_APB1Periph_TIM5 ((uint32_t)0x00000008) +#define RCC_APB1Periph_TIM6 ((uint32_t)0x00000010) +#define RCC_APB1Periph_TIM7 ((uint32_t)0x00000020) +#define RCC_APB1Periph_TIM12 ((uint32_t)0x00000040) +#define RCC_APB1Periph_TIM13 ((uint32_t)0x00000080) +#define RCC_APB1Periph_TIM14 ((uint32_t)0x00000100) +#define RCC_APB1Periph_WWDG ((uint32_t)0x00000800) +#define RCC_APB1Periph_SPI2 ((uint32_t)0x00004000) +#define RCC_APB1Periph_SPI3 ((uint32_t)0x00008000) +#define RCC_APB1Periph_USART2 ((uint32_t)0x00020000) +#define RCC_APB1Periph_USART3 ((uint32_t)0x00040000) +#define RCC_APB1Periph_UART4 ((uint32_t)0x00080000) +#define RCC_APB1Periph_UART5 ((uint32_t)0x00100000) +#define RCC_APB1Periph_I2C1 ((uint32_t)0x00200000) +#define RCC_APB1Periph_I2C2 ((uint32_t)0x00400000) +#define RCC_APB1Periph_USB ((uint32_t)0x00800000) +#define RCC_APB1Periph_CAN1 ((uint32_t)0x02000000) +#define RCC_APB1Periph_CAN2 ((uint32_t)0x04000000) +#define RCC_APB1Periph_BKP ((uint32_t)0x08000000) +#define RCC_APB1Periph_PWR ((uint32_t)0x10000000) +#define RCC_APB1Periph_DAC ((uint32_t)0x20000000) +#define RCC_APB1Periph_CEC ((uint32_t)0x40000000) + +#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0x81013600) == 0x00) && ((PERIPH) != 0x00)) + +/** + * @} + */ + +/** @defgroup Clock_source_to_output_on_MCO_pin + * @{ + */ + +#define RCC_MCO_NoClock ((uint8_t)0x00) +#define RCC_MCO_SYSCLK ((uint8_t)0x04) +#define RCC_MCO_HSI ((uint8_t)0x05) +#define RCC_MCO_HSE ((uint8_t)0x06) +#define RCC_MCO_PLLCLK_Div2 ((uint8_t)0x07) + +#ifndef STM32F10X_CL + #define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \ + ((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \ + ((MCO) == RCC_MCO_PLLCLK_Div2)) +#else + #define RCC_MCO_PLL2CLK ((uint8_t)0x08) + #define RCC_MCO_PLL3CLK_Div2 ((uint8_t)0x09) + #define RCC_MCO_XT1 ((uint8_t)0x0A) + #define RCC_MCO_PLL3CLK ((uint8_t)0x0B) + + #define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \ + ((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \ + ((MCO) == RCC_MCO_PLLCLK_Div2) || ((MCO) == RCC_MCO_PLL2CLK) || \ + ((MCO) == RCC_MCO_PLL3CLK_Div2) || ((MCO) == RCC_MCO_XT1) || \ + ((MCO) == RCC_MCO_PLL3CLK)) +#endif /* STM32F10X_CL */ + +/** + * @} + */ + +/** @defgroup RCC_Flag + * @{ + */ + +#define RCC_FLAG_HSIRDY ((uint8_t)0x21) +#define RCC_FLAG_HSERDY ((uint8_t)0x31) +#define RCC_FLAG_PLLRDY ((uint8_t)0x39) +#define RCC_FLAG_LSERDY ((uint8_t)0x41) +#define RCC_FLAG_LSIRDY ((uint8_t)0x61) +#define RCC_FLAG_PINRST ((uint8_t)0x7A) +#define RCC_FLAG_PORRST ((uint8_t)0x7B) +#define RCC_FLAG_SFTRST ((uint8_t)0x7C) +#define RCC_FLAG_IWDGRST ((uint8_t)0x7D) +#define RCC_FLAG_WWDGRST ((uint8_t)0x7E) +#define RCC_FLAG_LPWRRST ((uint8_t)0x7F) + +#ifndef STM32F10X_CL + #define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \ + ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \ + ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \ + ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \ + ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \ + ((FLAG) == RCC_FLAG_LPWRRST)) +#else + #define RCC_FLAG_PLL2RDY ((uint8_t)0x3B) + #define RCC_FLAG_PLL3RDY ((uint8_t)0x3D) + #define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \ + ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \ + ((FLAG) == RCC_FLAG_PLL2RDY) || ((FLAG) == RCC_FLAG_PLL3RDY) || \ + ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \ + ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \ + ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \ + ((FLAG) == RCC_FLAG_LPWRRST)) +#endif /* STM32F10X_CL */ + +#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup RCC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Exported_Functions + * @{ + */ + +void RCC_DeInit(void); +void RCC_HSEConfig(uint32_t RCC_HSE); +ErrorStatus RCC_WaitForHSEStartUp(void); +void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue); +void RCC_HSICmd(FunctionalState NewState); +void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul); +void RCC_PLLCmd(FunctionalState NewState); + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) + void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div); +#endif + +#ifdef STM32F10X_CL + void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div); + void RCC_PLL2Config(uint32_t RCC_PLL2Mul); + void RCC_PLL2Cmd(FunctionalState NewState); + void RCC_PLL3Config(uint32_t RCC_PLL3Mul); + void RCC_PLL3Cmd(FunctionalState NewState); +#endif /* STM32F10X_CL */ + +void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource); +uint8_t RCC_GetSYSCLKSource(void); +void RCC_HCLKConfig(uint32_t RCC_SYSCLK); +void RCC_PCLK1Config(uint32_t RCC_HCLK); +void RCC_PCLK2Config(uint32_t RCC_HCLK); +void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState); + +#ifndef STM32F10X_CL + void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource); +#else + void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource); +#endif /* STM32F10X_CL */ + +void RCC_ADCCLKConfig(uint32_t RCC_PCLK2); + +#ifdef STM32F10X_CL + void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource); + void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource); +#endif /* STM32F10X_CL */ + +void RCC_LSEConfig(uint8_t RCC_LSE); +void RCC_LSICmd(FunctionalState NewState); +void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource); +void RCC_RTCCLKCmd(FunctionalState NewState); +void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks); +void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState); +void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); +void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); + +#ifdef STM32F10X_CL +void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState); +#endif /* STM32F10X_CL */ + +void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); +void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); +void RCC_BackupResetCmd(FunctionalState NewState); +void RCC_ClockSecuritySystemCmd(FunctionalState NewState); +void RCC_MCOConfig(uint8_t RCC_MCO); +FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG); +void RCC_ClearFlag(void); +ITStatus RCC_GetITStatus(uint8_t RCC_IT); +void RCC_ClearITPendingBit(uint8_t RCC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_RCC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h index ac34ca971..17fefc2d7 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h @@ -1,134 +1,134 @@ -/** - ****************************************************************************** - * @file stm32f10x_rtc.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the RTC firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_RTC_H -#define __STM32F10x_RTC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup RTC - * @{ - */ - -/** @defgroup RTC_Exported_Types - * @{ - */ - -/** - * @} - */ - -/** @defgroup RTC_Exported_Constants - * @{ - */ - -/** @defgroup RTC_interrupts_define - * @{ - */ - -#define RTC_IT_OW ((uint16_t)0x0004) /*!< Overflow interrupt */ -#define RTC_IT_ALR ((uint16_t)0x0002) /*!< Alarm interrupt */ -#define RTC_IT_SEC ((uint16_t)0x0001) /*!< Second interrupt */ -#define IS_RTC_IT(IT) ((((IT) & (uint16_t)0xFFF8) == 0x00) && ((IT) != 0x00)) -#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_OW) || ((IT) == RTC_IT_ALR) || \ - ((IT) == RTC_IT_SEC)) -/** - * @} - */ - -/** @defgroup RTC_interrupts_flags - * @{ - */ - -#define RTC_FLAG_RTOFF ((uint16_t)0x0020) /*!< RTC Operation OFF flag */ -#define RTC_FLAG_RSF ((uint16_t)0x0008) /*!< Registers Synchronized flag */ -#define RTC_FLAG_OW ((uint16_t)0x0004) /*!< Overflow flag */ -#define RTC_FLAG_ALR ((uint16_t)0x0002) /*!< Alarm flag */ -#define RTC_FLAG_SEC ((uint16_t)0x0001) /*!< Second flag */ -#define IS_RTC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFFF0) == 0x00) && ((FLAG) != 0x00)) -#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_RTOFF) || ((FLAG) == RTC_FLAG_RSF) || \ - ((FLAG) == RTC_FLAG_OW) || ((FLAG) == RTC_FLAG_ALR) || \ - ((FLAG) == RTC_FLAG_SEC)) -#define IS_RTC_PRESCALER(PRESCALER) ((PRESCALER) <= 0xFFFFF) - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup RTC_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup RTC_Exported_Functions - * @{ - */ - -void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState); -void RTC_EnterConfigMode(void); -void RTC_ExitConfigMode(void); -uint32_t RTC_GetCounter(void); -void RTC_SetCounter(uint32_t CounterValue); -void RTC_SetPrescaler(uint32_t PrescalerValue); -void RTC_SetAlarm(uint32_t AlarmValue); -uint32_t RTC_GetDivider(void); -void RTC_WaitForLastTask(void); -void RTC_WaitForSynchro(void); -FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG); -void RTC_ClearFlag(uint16_t RTC_FLAG); -ITStatus RTC_GetITStatus(uint16_t RTC_IT); -void RTC_ClearITPendingBit(uint16_t RTC_IT); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_RTC_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_rtc.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the RTC firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_RTC_H +#define __STM32F10x_RTC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RTC + * @{ + */ + +/** @defgroup RTC_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Exported_Constants + * @{ + */ + +/** @defgroup RTC_interrupts_define + * @{ + */ + +#define RTC_IT_OW ((uint16_t)0x0004) /*!< Overflow interrupt */ +#define RTC_IT_ALR ((uint16_t)0x0002) /*!< Alarm interrupt */ +#define RTC_IT_SEC ((uint16_t)0x0001) /*!< Second interrupt */ +#define IS_RTC_IT(IT) ((((IT) & (uint16_t)0xFFF8) == 0x00) && ((IT) != 0x00)) +#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_OW) || ((IT) == RTC_IT_ALR) || \ + ((IT) == RTC_IT_SEC)) +/** + * @} + */ + +/** @defgroup RTC_interrupts_flags + * @{ + */ + +#define RTC_FLAG_RTOFF ((uint16_t)0x0020) /*!< RTC Operation OFF flag */ +#define RTC_FLAG_RSF ((uint16_t)0x0008) /*!< Registers Synchronized flag */ +#define RTC_FLAG_OW ((uint16_t)0x0004) /*!< Overflow flag */ +#define RTC_FLAG_ALR ((uint16_t)0x0002) /*!< Alarm flag */ +#define RTC_FLAG_SEC ((uint16_t)0x0001) /*!< Second flag */ +#define IS_RTC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFFF0) == 0x00) && ((FLAG) != 0x00)) +#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_RTOFF) || ((FLAG) == RTC_FLAG_RSF) || \ + ((FLAG) == RTC_FLAG_OW) || ((FLAG) == RTC_FLAG_ALR) || \ + ((FLAG) == RTC_FLAG_SEC)) +#define IS_RTC_PRESCALER(PRESCALER) ((PRESCALER) <= 0xFFFFF) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup RTC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Exported_Functions + * @{ + */ + +void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState); +void RTC_EnterConfigMode(void); +void RTC_ExitConfigMode(void); +uint32_t RTC_GetCounter(void); +void RTC_SetCounter(uint32_t CounterValue); +void RTC_SetPrescaler(uint32_t PrescalerValue); +void RTC_SetAlarm(uint32_t AlarmValue); +uint32_t RTC_GetDivider(void); +void RTC_WaitForLastTask(void); +void RTC_WaitForSynchro(void); +FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG); +void RTC_ClearFlag(uint16_t RTC_FLAG); +ITStatus RTC_GetITStatus(uint16_t RTC_IT); +void RTC_ClearITPendingBit(uint16_t RTC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_RTC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h index d15556ce7..7808c0693 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h @@ -1,530 +1,530 @@ -/** - ****************************************************************************** - * @file stm32f10x_sdio.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the SDIO firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_SDIO_H -#define __STM32F10x_SDIO_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup SDIO - * @{ - */ - -/** @defgroup SDIO_Exported_Types - * @{ - */ - -typedef struct -{ - uint32_t SDIO_ClockEdge; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref SDIO_Clock_Edge */ - - uint32_t SDIO_ClockBypass; /*!< Specifies whether the SDIO Clock divider bypass is - enabled or disabled. - This parameter can be a value of @ref SDIO_Clock_Bypass */ - - uint32_t SDIO_ClockPowerSave; /*!< Specifies whether SDIO Clock output is enabled or - disabled when the bus is idle. - This parameter can be a value of @ref SDIO_Clock_Power_Save */ - - uint32_t SDIO_BusWide; /*!< Specifies the SDIO bus width. - This parameter can be a value of @ref SDIO_Bus_Wide */ - - uint32_t SDIO_HardwareFlowControl; /*!< Specifies whether the SDIO hardware flow control is enabled or disabled. - This parameter can be a value of @ref SDIO_Hardware_Flow_Control */ - - uint8_t SDIO_ClockDiv; /*!< Specifies the clock frequency of the SDIO controller. - This parameter can be a value between 0x00 and 0xFF. */ - -} SDIO_InitTypeDef; - -typedef struct -{ - uint32_t SDIO_Argument; /*!< Specifies the SDIO command argument which is sent - to a card as part of a command message. If a command - contains an argument, it must be loaded into this register - before writing the command to the command register */ - - uint32_t SDIO_CmdIndex; /*!< Specifies the SDIO command index. It must be lower than 0x40. */ - - uint32_t SDIO_Response; /*!< Specifies the SDIO response type. - This parameter can be a value of @ref SDIO_Response_Type */ - - uint32_t SDIO_Wait; /*!< Specifies whether SDIO wait-for-interrupt request is enabled or disabled. - This parameter can be a value of @ref SDIO_Wait_Interrupt_State */ - - uint32_t SDIO_CPSM; /*!< Specifies whether SDIO Command path state machine (CPSM) - is enabled or disabled. - This parameter can be a value of @ref SDIO_CPSM_State */ -} SDIO_CmdInitTypeDef; - -typedef struct -{ - uint32_t SDIO_DataTimeOut; /*!< Specifies the data timeout period in card bus clock periods. */ - - uint32_t SDIO_DataLength; /*!< Specifies the number of data bytes to be transferred. */ - - uint32_t SDIO_DataBlockSize; /*!< Specifies the data block size for block transfer. - This parameter can be a value of @ref SDIO_Data_Block_Size */ - - uint32_t SDIO_TransferDir; /*!< Specifies the data transfer direction, whether the transfer - is a read or write. - This parameter can be a value of @ref SDIO_Transfer_Direction */ - - uint32_t SDIO_TransferMode; /*!< Specifies whether data transfer is in stream or block mode. - This parameter can be a value of @ref SDIO_Transfer_Type */ - - uint32_t SDIO_DPSM; /*!< Specifies whether SDIO Data path state machine (DPSM) - is enabled or disabled. - This parameter can be a value of @ref SDIO_DPSM_State */ -} SDIO_DataInitTypeDef; - -/** - * @} - */ - -/** @defgroup SDIO_Exported_Constants - * @{ - */ - -/** @defgroup SDIO_Clock_Edge - * @{ - */ - -#define SDIO_ClockEdge_Rising ((uint32_t)0x00000000) -#define SDIO_ClockEdge_Falling ((uint32_t)0x00002000) -#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_ClockEdge_Rising) || \ - ((EDGE) == SDIO_ClockEdge_Falling)) -/** - * @} - */ - -/** @defgroup SDIO_Clock_Bypass - * @{ - */ - -#define SDIO_ClockBypass_Disable ((uint32_t)0x00000000) -#define SDIO_ClockBypass_Enable ((uint32_t)0x00000400) -#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_ClockBypass_Disable) || \ - ((BYPASS) == SDIO_ClockBypass_Enable)) -/** - * @} - */ - -/** @defgroup SDIO_Clock_Power_Save - * @{ - */ - -#define SDIO_ClockPowerSave_Disable ((uint32_t)0x00000000) -#define SDIO_ClockPowerSave_Enable ((uint32_t)0x00000200) -#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_ClockPowerSave_Disable) || \ - ((SAVE) == SDIO_ClockPowerSave_Enable)) -/** - * @} - */ - -/** @defgroup SDIO_Bus_Wide - * @{ - */ - -#define SDIO_BusWide_1b ((uint32_t)0x00000000) -#define SDIO_BusWide_4b ((uint32_t)0x00000800) -#define SDIO_BusWide_8b ((uint32_t)0x00001000) -#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BusWide_1b) || ((WIDE) == SDIO_BusWide_4b) || \ - ((WIDE) == SDIO_BusWide_8b)) - -/** - * @} - */ - -/** @defgroup SDIO_Hardware_Flow_Control - * @{ - */ - -#define SDIO_HardwareFlowControl_Disable ((uint32_t)0x00000000) -#define SDIO_HardwareFlowControl_Enable ((uint32_t)0x00004000) -#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HardwareFlowControl_Disable) || \ - ((CONTROL) == SDIO_HardwareFlowControl_Enable)) -/** - * @} - */ - -/** @defgroup SDIO_Power_State - * @{ - */ - -#define SDIO_PowerState_OFF ((uint32_t)0x00000000) -#define SDIO_PowerState_ON ((uint32_t)0x00000003) -#define IS_SDIO_POWER_STATE(STATE) (((STATE) == SDIO_PowerState_OFF) || ((STATE) == SDIO_PowerState_ON)) -/** - * @} - */ - - -/** @defgroup SDIO_Interrupt_soucres - * @{ - */ - -#define SDIO_IT_CCRCFAIL ((uint32_t)0x00000001) -#define SDIO_IT_DCRCFAIL ((uint32_t)0x00000002) -#define SDIO_IT_CTIMEOUT ((uint32_t)0x00000004) -#define SDIO_IT_DTIMEOUT ((uint32_t)0x00000008) -#define SDIO_IT_TXUNDERR ((uint32_t)0x00000010) -#define SDIO_IT_RXOVERR ((uint32_t)0x00000020) -#define SDIO_IT_CMDREND ((uint32_t)0x00000040) -#define SDIO_IT_CMDSENT ((uint32_t)0x00000080) -#define SDIO_IT_DATAEND ((uint32_t)0x00000100) -#define SDIO_IT_STBITERR ((uint32_t)0x00000200) -#define SDIO_IT_DBCKEND ((uint32_t)0x00000400) -#define SDIO_IT_CMDACT ((uint32_t)0x00000800) -#define SDIO_IT_TXACT ((uint32_t)0x00001000) -#define SDIO_IT_RXACT ((uint32_t)0x00002000) -#define SDIO_IT_TXFIFOHE ((uint32_t)0x00004000) -#define SDIO_IT_RXFIFOHF ((uint32_t)0x00008000) -#define SDIO_IT_TXFIFOF ((uint32_t)0x00010000) -#define SDIO_IT_RXFIFOF ((uint32_t)0x00020000) -#define SDIO_IT_TXFIFOE ((uint32_t)0x00040000) -#define SDIO_IT_RXFIFOE ((uint32_t)0x00080000) -#define SDIO_IT_TXDAVL ((uint32_t)0x00100000) -#define SDIO_IT_RXDAVL ((uint32_t)0x00200000) -#define SDIO_IT_SDIOIT ((uint32_t)0x00400000) -#define SDIO_IT_CEATAEND ((uint32_t)0x00800000) -#define IS_SDIO_IT(IT) ((((IT) & (uint32_t)0xFF000000) == 0x00) && ((IT) != (uint32_t)0x00)) -/** - * @} - */ - -/** @defgroup SDIO_Command_Index - * @{ - */ - -#define IS_SDIO_CMD_INDEX(INDEX) ((INDEX) < 0x40) -/** - * @} - */ - -/** @defgroup SDIO_Response_Type - * @{ - */ - -#define SDIO_Response_No ((uint32_t)0x00000000) -#define SDIO_Response_Short ((uint32_t)0x00000040) -#define SDIO_Response_Long ((uint32_t)0x000000C0) -#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_Response_No) || \ - ((RESPONSE) == SDIO_Response_Short) || \ - ((RESPONSE) == SDIO_Response_Long)) -/** - * @} - */ - -/** @defgroup SDIO_Wait_Interrupt_State - * @{ - */ - -#define SDIO_Wait_No ((uint32_t)0x00000000) /*!< SDIO No Wait, TimeOut is enabled */ -#define SDIO_Wait_IT ((uint32_t)0x00000100) /*!< SDIO Wait Interrupt Request */ -#define SDIO_Wait_Pend ((uint32_t)0x00000200) /*!< SDIO Wait End of transfer */ -#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_Wait_No) || ((WAIT) == SDIO_Wait_IT) || \ - ((WAIT) == SDIO_Wait_Pend)) -/** - * @} - */ - -/** @defgroup SDIO_CPSM_State - * @{ - */ - -#define SDIO_CPSM_Disable ((uint32_t)0x00000000) -#define SDIO_CPSM_Enable ((uint32_t)0x00000400) -#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_Enable) || ((CPSM) == SDIO_CPSM_Disable)) -/** - * @} - */ - -/** @defgroup SDIO_Response_Registers - * @{ - */ - -#define SDIO_RESP1 ((uint32_t)0x00000000) -#define SDIO_RESP2 ((uint32_t)0x00000004) -#define SDIO_RESP3 ((uint32_t)0x00000008) -#define SDIO_RESP4 ((uint32_t)0x0000000C) -#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || ((RESP) == SDIO_RESP2) || \ - ((RESP) == SDIO_RESP3) || ((RESP) == SDIO_RESP4)) -/** - * @} - */ - -/** @defgroup SDIO_Data_Length - * @{ - */ - -#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFF) -/** - * @} - */ - -/** @defgroup SDIO_Data_Block_Size - * @{ - */ - -#define SDIO_DataBlockSize_1b ((uint32_t)0x00000000) -#define SDIO_DataBlockSize_2b ((uint32_t)0x00000010) -#define SDIO_DataBlockSize_4b ((uint32_t)0x00000020) -#define SDIO_DataBlockSize_8b ((uint32_t)0x00000030) -#define SDIO_DataBlockSize_16b ((uint32_t)0x00000040) -#define SDIO_DataBlockSize_32b ((uint32_t)0x00000050) -#define SDIO_DataBlockSize_64b ((uint32_t)0x00000060) -#define SDIO_DataBlockSize_128b ((uint32_t)0x00000070) -#define SDIO_DataBlockSize_256b ((uint32_t)0x00000080) -#define SDIO_DataBlockSize_512b ((uint32_t)0x00000090) -#define SDIO_DataBlockSize_1024b ((uint32_t)0x000000A0) -#define SDIO_DataBlockSize_2048b ((uint32_t)0x000000B0) -#define SDIO_DataBlockSize_4096b ((uint32_t)0x000000C0) -#define SDIO_DataBlockSize_8192b ((uint32_t)0x000000D0) -#define SDIO_DataBlockSize_16384b ((uint32_t)0x000000E0) -#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DataBlockSize_1b) || \ - ((SIZE) == SDIO_DataBlockSize_2b) || \ - ((SIZE) == SDIO_DataBlockSize_4b) || \ - ((SIZE) == SDIO_DataBlockSize_8b) || \ - ((SIZE) == SDIO_DataBlockSize_16b) || \ - ((SIZE) == SDIO_DataBlockSize_32b) || \ - ((SIZE) == SDIO_DataBlockSize_64b) || \ - ((SIZE) == SDIO_DataBlockSize_128b) || \ - ((SIZE) == SDIO_DataBlockSize_256b) || \ - ((SIZE) == SDIO_DataBlockSize_512b) || \ - ((SIZE) == SDIO_DataBlockSize_1024b) || \ - ((SIZE) == SDIO_DataBlockSize_2048b) || \ - ((SIZE) == SDIO_DataBlockSize_4096b) || \ - ((SIZE) == SDIO_DataBlockSize_8192b) || \ - ((SIZE) == SDIO_DataBlockSize_16384b)) -/** - * @} - */ - -/** @defgroup SDIO_Transfer_Direction - * @{ - */ - -#define SDIO_TransferDir_ToCard ((uint32_t)0x00000000) -#define SDIO_TransferDir_ToSDIO ((uint32_t)0x00000002) -#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TransferDir_ToCard) || \ - ((DIR) == SDIO_TransferDir_ToSDIO)) -/** - * @} - */ - -/** @defgroup SDIO_Transfer_Type - * @{ - */ - -#define SDIO_TransferMode_Block ((uint32_t)0x00000000) -#define SDIO_TransferMode_Stream ((uint32_t)0x00000004) -#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TransferMode_Stream) || \ - ((MODE) == SDIO_TransferMode_Block)) -/** - * @} - */ - -/** @defgroup SDIO_DPSM_State - * @{ - */ - -#define SDIO_DPSM_Disable ((uint32_t)0x00000000) -#define SDIO_DPSM_Enable ((uint32_t)0x00000001) -#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_Enable) || ((DPSM) == SDIO_DPSM_Disable)) -/** - * @} - */ - -/** @defgroup SDIO_Flags - * @{ - */ - -#define SDIO_FLAG_CCRCFAIL ((uint32_t)0x00000001) -#define SDIO_FLAG_DCRCFAIL ((uint32_t)0x00000002) -#define SDIO_FLAG_CTIMEOUT ((uint32_t)0x00000004) -#define SDIO_FLAG_DTIMEOUT ((uint32_t)0x00000008) -#define SDIO_FLAG_TXUNDERR ((uint32_t)0x00000010) -#define SDIO_FLAG_RXOVERR ((uint32_t)0x00000020) -#define SDIO_FLAG_CMDREND ((uint32_t)0x00000040) -#define SDIO_FLAG_CMDSENT ((uint32_t)0x00000080) -#define SDIO_FLAG_DATAEND ((uint32_t)0x00000100) -#define SDIO_FLAG_STBITERR ((uint32_t)0x00000200) -#define SDIO_FLAG_DBCKEND ((uint32_t)0x00000400) -#define SDIO_FLAG_CMDACT ((uint32_t)0x00000800) -#define SDIO_FLAG_TXACT ((uint32_t)0x00001000) -#define SDIO_FLAG_RXACT ((uint32_t)0x00002000) -#define SDIO_FLAG_TXFIFOHE ((uint32_t)0x00004000) -#define SDIO_FLAG_RXFIFOHF ((uint32_t)0x00008000) -#define SDIO_FLAG_TXFIFOF ((uint32_t)0x00010000) -#define SDIO_FLAG_RXFIFOF ((uint32_t)0x00020000) -#define SDIO_FLAG_TXFIFOE ((uint32_t)0x00040000) -#define SDIO_FLAG_RXFIFOE ((uint32_t)0x00080000) -#define SDIO_FLAG_TXDAVL ((uint32_t)0x00100000) -#define SDIO_FLAG_RXDAVL ((uint32_t)0x00200000) -#define SDIO_FLAG_SDIOIT ((uint32_t)0x00400000) -#define SDIO_FLAG_CEATAEND ((uint32_t)0x00800000) -#define IS_SDIO_FLAG(FLAG) (((FLAG) == SDIO_FLAG_CCRCFAIL) || \ - ((FLAG) == SDIO_FLAG_DCRCFAIL) || \ - ((FLAG) == SDIO_FLAG_CTIMEOUT) || \ - ((FLAG) == SDIO_FLAG_DTIMEOUT) || \ - ((FLAG) == SDIO_FLAG_TXUNDERR) || \ - ((FLAG) == SDIO_FLAG_RXOVERR) || \ - ((FLAG) == SDIO_FLAG_CMDREND) || \ - ((FLAG) == SDIO_FLAG_CMDSENT) || \ - ((FLAG) == SDIO_FLAG_DATAEND) || \ - ((FLAG) == SDIO_FLAG_STBITERR) || \ - ((FLAG) == SDIO_FLAG_DBCKEND) || \ - ((FLAG) == SDIO_FLAG_CMDACT) || \ - ((FLAG) == SDIO_FLAG_TXACT) || \ - ((FLAG) == SDIO_FLAG_RXACT) || \ - ((FLAG) == SDIO_FLAG_TXFIFOHE) || \ - ((FLAG) == SDIO_FLAG_RXFIFOHF) || \ - ((FLAG) == SDIO_FLAG_TXFIFOF) || \ - ((FLAG) == SDIO_FLAG_RXFIFOF) || \ - ((FLAG) == SDIO_FLAG_TXFIFOE) || \ - ((FLAG) == SDIO_FLAG_RXFIFOE) || \ - ((FLAG) == SDIO_FLAG_TXDAVL) || \ - ((FLAG) == SDIO_FLAG_RXDAVL) || \ - ((FLAG) == SDIO_FLAG_SDIOIT) || \ - ((FLAG) == SDIO_FLAG_CEATAEND)) - -#define IS_SDIO_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFF3FF800) == 0x00) && ((FLAG) != (uint32_t)0x00)) - -#define IS_SDIO_GET_IT(IT) (((IT) == SDIO_IT_CCRCFAIL) || \ - ((IT) == SDIO_IT_DCRCFAIL) || \ - ((IT) == SDIO_IT_CTIMEOUT) || \ - ((IT) == SDIO_IT_DTIMEOUT) || \ - ((IT) == SDIO_IT_TXUNDERR) || \ - ((IT) == SDIO_IT_RXOVERR) || \ - ((IT) == SDIO_IT_CMDREND) || \ - ((IT) == SDIO_IT_CMDSENT) || \ - ((IT) == SDIO_IT_DATAEND) || \ - ((IT) == SDIO_IT_STBITERR) || \ - ((IT) == SDIO_IT_DBCKEND) || \ - ((IT) == SDIO_IT_CMDACT) || \ - ((IT) == SDIO_IT_TXACT) || \ - ((IT) == SDIO_IT_RXACT) || \ - ((IT) == SDIO_IT_TXFIFOHE) || \ - ((IT) == SDIO_IT_RXFIFOHF) || \ - ((IT) == SDIO_IT_TXFIFOF) || \ - ((IT) == SDIO_IT_RXFIFOF) || \ - ((IT) == SDIO_IT_TXFIFOE) || \ - ((IT) == SDIO_IT_RXFIFOE) || \ - ((IT) == SDIO_IT_TXDAVL) || \ - ((IT) == SDIO_IT_RXDAVL) || \ - ((IT) == SDIO_IT_SDIOIT) || \ - ((IT) == SDIO_IT_CEATAEND)) - -#define IS_SDIO_CLEAR_IT(IT) ((((IT) & (uint32_t)0xFF3FF800) == 0x00) && ((IT) != (uint32_t)0x00)) - -/** - * @} - */ - -/** @defgroup SDIO_Read_Wait_Mode - * @{ - */ - -#define SDIO_ReadWaitMode_CLK ((uint32_t)0x00000001) -#define SDIO_ReadWaitMode_DATA2 ((uint32_t)0x00000000) -#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_ReadWaitMode_CLK) || \ - ((MODE) == SDIO_ReadWaitMode_DATA2)) -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup SDIO_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup SDIO_Exported_Functions - * @{ - */ - -void SDIO_DeInit(void); -void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct); -void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct); -void SDIO_ClockCmd(FunctionalState NewState); -void SDIO_SetPowerState(uint32_t SDIO_PowerState); -uint32_t SDIO_GetPowerState(void); -void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState); -void SDIO_DMACmd(FunctionalState NewState); -void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct); -void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct); -uint8_t SDIO_GetCommandResponse(void); -uint32_t SDIO_GetResponse(uint32_t SDIO_RESP); -void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct); -void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct); -uint32_t SDIO_GetDataCounter(void); -uint32_t SDIO_ReadData(void); -void SDIO_WriteData(uint32_t Data); -uint32_t SDIO_GetFIFOCount(void); -void SDIO_StartSDIOReadWait(FunctionalState NewState); -void SDIO_StopSDIOReadWait(FunctionalState NewState); -void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode); -void SDIO_SetSDIOOperation(FunctionalState NewState); -void SDIO_SendSDIOSuspendCmd(FunctionalState NewState); -void SDIO_CommandCompletionCmd(FunctionalState NewState); -void SDIO_CEATAITCmd(FunctionalState NewState); -void SDIO_SendCEATACmd(FunctionalState NewState); -FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG); -void SDIO_ClearFlag(uint32_t SDIO_FLAG); -ITStatus SDIO_GetITStatus(uint32_t SDIO_IT); -void SDIO_ClearITPendingBit(uint32_t SDIO_IT); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_SDIO_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_sdio.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the SDIO firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_SDIO_H +#define __STM32F10x_SDIO_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SDIO + * @{ + */ + +/** @defgroup SDIO_Exported_Types + * @{ + */ + +typedef struct +{ + uint32_t SDIO_ClockEdge; /*!< Specifies the clock transition on which the bit capture is made. + This parameter can be a value of @ref SDIO_Clock_Edge */ + + uint32_t SDIO_ClockBypass; /*!< Specifies whether the SDIO Clock divider bypass is + enabled or disabled. + This parameter can be a value of @ref SDIO_Clock_Bypass */ + + uint32_t SDIO_ClockPowerSave; /*!< Specifies whether SDIO Clock output is enabled or + disabled when the bus is idle. + This parameter can be a value of @ref SDIO_Clock_Power_Save */ + + uint32_t SDIO_BusWide; /*!< Specifies the SDIO bus width. + This parameter can be a value of @ref SDIO_Bus_Wide */ + + uint32_t SDIO_HardwareFlowControl; /*!< Specifies whether the SDIO hardware flow control is enabled or disabled. + This parameter can be a value of @ref SDIO_Hardware_Flow_Control */ + + uint8_t SDIO_ClockDiv; /*!< Specifies the clock frequency of the SDIO controller. + This parameter can be a value between 0x00 and 0xFF. */ + +} SDIO_InitTypeDef; + +typedef struct +{ + uint32_t SDIO_Argument; /*!< Specifies the SDIO command argument which is sent + to a card as part of a command message. If a command + contains an argument, it must be loaded into this register + before writing the command to the command register */ + + uint32_t SDIO_CmdIndex; /*!< Specifies the SDIO command index. It must be lower than 0x40. */ + + uint32_t SDIO_Response; /*!< Specifies the SDIO response type. + This parameter can be a value of @ref SDIO_Response_Type */ + + uint32_t SDIO_Wait; /*!< Specifies whether SDIO wait-for-interrupt request is enabled or disabled. + This parameter can be a value of @ref SDIO_Wait_Interrupt_State */ + + uint32_t SDIO_CPSM; /*!< Specifies whether SDIO Command path state machine (CPSM) + is enabled or disabled. + This parameter can be a value of @ref SDIO_CPSM_State */ +} SDIO_CmdInitTypeDef; + +typedef struct +{ + uint32_t SDIO_DataTimeOut; /*!< Specifies the data timeout period in card bus clock periods. */ + + uint32_t SDIO_DataLength; /*!< Specifies the number of data bytes to be transferred. */ + + uint32_t SDIO_DataBlockSize; /*!< Specifies the data block size for block transfer. + This parameter can be a value of @ref SDIO_Data_Block_Size */ + + uint32_t SDIO_TransferDir; /*!< Specifies the data transfer direction, whether the transfer + is a read or write. + This parameter can be a value of @ref SDIO_Transfer_Direction */ + + uint32_t SDIO_TransferMode; /*!< Specifies whether data transfer is in stream or block mode. + This parameter can be a value of @ref SDIO_Transfer_Type */ + + uint32_t SDIO_DPSM; /*!< Specifies whether SDIO Data path state machine (DPSM) + is enabled or disabled. + This parameter can be a value of @ref SDIO_DPSM_State */ +} SDIO_DataInitTypeDef; + +/** + * @} + */ + +/** @defgroup SDIO_Exported_Constants + * @{ + */ + +/** @defgroup SDIO_Clock_Edge + * @{ + */ + +#define SDIO_ClockEdge_Rising ((uint32_t)0x00000000) +#define SDIO_ClockEdge_Falling ((uint32_t)0x00002000) +#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_ClockEdge_Rising) || \ + ((EDGE) == SDIO_ClockEdge_Falling)) +/** + * @} + */ + +/** @defgroup SDIO_Clock_Bypass + * @{ + */ + +#define SDIO_ClockBypass_Disable ((uint32_t)0x00000000) +#define SDIO_ClockBypass_Enable ((uint32_t)0x00000400) +#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_ClockBypass_Disable) || \ + ((BYPASS) == SDIO_ClockBypass_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Clock_Power_Save + * @{ + */ + +#define SDIO_ClockPowerSave_Disable ((uint32_t)0x00000000) +#define SDIO_ClockPowerSave_Enable ((uint32_t)0x00000200) +#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_ClockPowerSave_Disable) || \ + ((SAVE) == SDIO_ClockPowerSave_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Bus_Wide + * @{ + */ + +#define SDIO_BusWide_1b ((uint32_t)0x00000000) +#define SDIO_BusWide_4b ((uint32_t)0x00000800) +#define SDIO_BusWide_8b ((uint32_t)0x00001000) +#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BusWide_1b) || ((WIDE) == SDIO_BusWide_4b) || \ + ((WIDE) == SDIO_BusWide_8b)) + +/** + * @} + */ + +/** @defgroup SDIO_Hardware_Flow_Control + * @{ + */ + +#define SDIO_HardwareFlowControl_Disable ((uint32_t)0x00000000) +#define SDIO_HardwareFlowControl_Enable ((uint32_t)0x00004000) +#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HardwareFlowControl_Disable) || \ + ((CONTROL) == SDIO_HardwareFlowControl_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Power_State + * @{ + */ + +#define SDIO_PowerState_OFF ((uint32_t)0x00000000) +#define SDIO_PowerState_ON ((uint32_t)0x00000003) +#define IS_SDIO_POWER_STATE(STATE) (((STATE) == SDIO_PowerState_OFF) || ((STATE) == SDIO_PowerState_ON)) +/** + * @} + */ + + +/** @defgroup SDIO_Interrupt_soucres + * @{ + */ + +#define SDIO_IT_CCRCFAIL ((uint32_t)0x00000001) +#define SDIO_IT_DCRCFAIL ((uint32_t)0x00000002) +#define SDIO_IT_CTIMEOUT ((uint32_t)0x00000004) +#define SDIO_IT_DTIMEOUT ((uint32_t)0x00000008) +#define SDIO_IT_TXUNDERR ((uint32_t)0x00000010) +#define SDIO_IT_RXOVERR ((uint32_t)0x00000020) +#define SDIO_IT_CMDREND ((uint32_t)0x00000040) +#define SDIO_IT_CMDSENT ((uint32_t)0x00000080) +#define SDIO_IT_DATAEND ((uint32_t)0x00000100) +#define SDIO_IT_STBITERR ((uint32_t)0x00000200) +#define SDIO_IT_DBCKEND ((uint32_t)0x00000400) +#define SDIO_IT_CMDACT ((uint32_t)0x00000800) +#define SDIO_IT_TXACT ((uint32_t)0x00001000) +#define SDIO_IT_RXACT ((uint32_t)0x00002000) +#define SDIO_IT_TXFIFOHE ((uint32_t)0x00004000) +#define SDIO_IT_RXFIFOHF ((uint32_t)0x00008000) +#define SDIO_IT_TXFIFOF ((uint32_t)0x00010000) +#define SDIO_IT_RXFIFOF ((uint32_t)0x00020000) +#define SDIO_IT_TXFIFOE ((uint32_t)0x00040000) +#define SDIO_IT_RXFIFOE ((uint32_t)0x00080000) +#define SDIO_IT_TXDAVL ((uint32_t)0x00100000) +#define SDIO_IT_RXDAVL ((uint32_t)0x00200000) +#define SDIO_IT_SDIOIT ((uint32_t)0x00400000) +#define SDIO_IT_CEATAEND ((uint32_t)0x00800000) +#define IS_SDIO_IT(IT) ((((IT) & (uint32_t)0xFF000000) == 0x00) && ((IT) != (uint32_t)0x00)) +/** + * @} + */ + +/** @defgroup SDIO_Command_Index + * @{ + */ + +#define IS_SDIO_CMD_INDEX(INDEX) ((INDEX) < 0x40) +/** + * @} + */ + +/** @defgroup SDIO_Response_Type + * @{ + */ + +#define SDIO_Response_No ((uint32_t)0x00000000) +#define SDIO_Response_Short ((uint32_t)0x00000040) +#define SDIO_Response_Long ((uint32_t)0x000000C0) +#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_Response_No) || \ + ((RESPONSE) == SDIO_Response_Short) || \ + ((RESPONSE) == SDIO_Response_Long)) +/** + * @} + */ + +/** @defgroup SDIO_Wait_Interrupt_State + * @{ + */ + +#define SDIO_Wait_No ((uint32_t)0x00000000) /*!< SDIO No Wait, TimeOut is enabled */ +#define SDIO_Wait_IT ((uint32_t)0x00000100) /*!< SDIO Wait Interrupt Request */ +#define SDIO_Wait_Pend ((uint32_t)0x00000200) /*!< SDIO Wait End of transfer */ +#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_Wait_No) || ((WAIT) == SDIO_Wait_IT) || \ + ((WAIT) == SDIO_Wait_Pend)) +/** + * @} + */ + +/** @defgroup SDIO_CPSM_State + * @{ + */ + +#define SDIO_CPSM_Disable ((uint32_t)0x00000000) +#define SDIO_CPSM_Enable ((uint32_t)0x00000400) +#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_Enable) || ((CPSM) == SDIO_CPSM_Disable)) +/** + * @} + */ + +/** @defgroup SDIO_Response_Registers + * @{ + */ + +#define SDIO_RESP1 ((uint32_t)0x00000000) +#define SDIO_RESP2 ((uint32_t)0x00000004) +#define SDIO_RESP3 ((uint32_t)0x00000008) +#define SDIO_RESP4 ((uint32_t)0x0000000C) +#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || ((RESP) == SDIO_RESP2) || \ + ((RESP) == SDIO_RESP3) || ((RESP) == SDIO_RESP4)) +/** + * @} + */ + +/** @defgroup SDIO_Data_Length + * @{ + */ + +#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFF) +/** + * @} + */ + +/** @defgroup SDIO_Data_Block_Size + * @{ + */ + +#define SDIO_DataBlockSize_1b ((uint32_t)0x00000000) +#define SDIO_DataBlockSize_2b ((uint32_t)0x00000010) +#define SDIO_DataBlockSize_4b ((uint32_t)0x00000020) +#define SDIO_DataBlockSize_8b ((uint32_t)0x00000030) +#define SDIO_DataBlockSize_16b ((uint32_t)0x00000040) +#define SDIO_DataBlockSize_32b ((uint32_t)0x00000050) +#define SDIO_DataBlockSize_64b ((uint32_t)0x00000060) +#define SDIO_DataBlockSize_128b ((uint32_t)0x00000070) +#define SDIO_DataBlockSize_256b ((uint32_t)0x00000080) +#define SDIO_DataBlockSize_512b ((uint32_t)0x00000090) +#define SDIO_DataBlockSize_1024b ((uint32_t)0x000000A0) +#define SDIO_DataBlockSize_2048b ((uint32_t)0x000000B0) +#define SDIO_DataBlockSize_4096b ((uint32_t)0x000000C0) +#define SDIO_DataBlockSize_8192b ((uint32_t)0x000000D0) +#define SDIO_DataBlockSize_16384b ((uint32_t)0x000000E0) +#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DataBlockSize_1b) || \ + ((SIZE) == SDIO_DataBlockSize_2b) || \ + ((SIZE) == SDIO_DataBlockSize_4b) || \ + ((SIZE) == SDIO_DataBlockSize_8b) || \ + ((SIZE) == SDIO_DataBlockSize_16b) || \ + ((SIZE) == SDIO_DataBlockSize_32b) || \ + ((SIZE) == SDIO_DataBlockSize_64b) || \ + ((SIZE) == SDIO_DataBlockSize_128b) || \ + ((SIZE) == SDIO_DataBlockSize_256b) || \ + ((SIZE) == SDIO_DataBlockSize_512b) || \ + ((SIZE) == SDIO_DataBlockSize_1024b) || \ + ((SIZE) == SDIO_DataBlockSize_2048b) || \ + ((SIZE) == SDIO_DataBlockSize_4096b) || \ + ((SIZE) == SDIO_DataBlockSize_8192b) || \ + ((SIZE) == SDIO_DataBlockSize_16384b)) +/** + * @} + */ + +/** @defgroup SDIO_Transfer_Direction + * @{ + */ + +#define SDIO_TransferDir_ToCard ((uint32_t)0x00000000) +#define SDIO_TransferDir_ToSDIO ((uint32_t)0x00000002) +#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TransferDir_ToCard) || \ + ((DIR) == SDIO_TransferDir_ToSDIO)) +/** + * @} + */ + +/** @defgroup SDIO_Transfer_Type + * @{ + */ + +#define SDIO_TransferMode_Block ((uint32_t)0x00000000) +#define SDIO_TransferMode_Stream ((uint32_t)0x00000004) +#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TransferMode_Stream) || \ + ((MODE) == SDIO_TransferMode_Block)) +/** + * @} + */ + +/** @defgroup SDIO_DPSM_State + * @{ + */ + +#define SDIO_DPSM_Disable ((uint32_t)0x00000000) +#define SDIO_DPSM_Enable ((uint32_t)0x00000001) +#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_Enable) || ((DPSM) == SDIO_DPSM_Disable)) +/** + * @} + */ + +/** @defgroup SDIO_Flags + * @{ + */ + +#define SDIO_FLAG_CCRCFAIL ((uint32_t)0x00000001) +#define SDIO_FLAG_DCRCFAIL ((uint32_t)0x00000002) +#define SDIO_FLAG_CTIMEOUT ((uint32_t)0x00000004) +#define SDIO_FLAG_DTIMEOUT ((uint32_t)0x00000008) +#define SDIO_FLAG_TXUNDERR ((uint32_t)0x00000010) +#define SDIO_FLAG_RXOVERR ((uint32_t)0x00000020) +#define SDIO_FLAG_CMDREND ((uint32_t)0x00000040) +#define SDIO_FLAG_CMDSENT ((uint32_t)0x00000080) +#define SDIO_FLAG_DATAEND ((uint32_t)0x00000100) +#define SDIO_FLAG_STBITERR ((uint32_t)0x00000200) +#define SDIO_FLAG_DBCKEND ((uint32_t)0x00000400) +#define SDIO_FLAG_CMDACT ((uint32_t)0x00000800) +#define SDIO_FLAG_TXACT ((uint32_t)0x00001000) +#define SDIO_FLAG_RXACT ((uint32_t)0x00002000) +#define SDIO_FLAG_TXFIFOHE ((uint32_t)0x00004000) +#define SDIO_FLAG_RXFIFOHF ((uint32_t)0x00008000) +#define SDIO_FLAG_TXFIFOF ((uint32_t)0x00010000) +#define SDIO_FLAG_RXFIFOF ((uint32_t)0x00020000) +#define SDIO_FLAG_TXFIFOE ((uint32_t)0x00040000) +#define SDIO_FLAG_RXFIFOE ((uint32_t)0x00080000) +#define SDIO_FLAG_TXDAVL ((uint32_t)0x00100000) +#define SDIO_FLAG_RXDAVL ((uint32_t)0x00200000) +#define SDIO_FLAG_SDIOIT ((uint32_t)0x00400000) +#define SDIO_FLAG_CEATAEND ((uint32_t)0x00800000) +#define IS_SDIO_FLAG(FLAG) (((FLAG) == SDIO_FLAG_CCRCFAIL) || \ + ((FLAG) == SDIO_FLAG_DCRCFAIL) || \ + ((FLAG) == SDIO_FLAG_CTIMEOUT) || \ + ((FLAG) == SDIO_FLAG_DTIMEOUT) || \ + ((FLAG) == SDIO_FLAG_TXUNDERR) || \ + ((FLAG) == SDIO_FLAG_RXOVERR) || \ + ((FLAG) == SDIO_FLAG_CMDREND) || \ + ((FLAG) == SDIO_FLAG_CMDSENT) || \ + ((FLAG) == SDIO_FLAG_DATAEND) || \ + ((FLAG) == SDIO_FLAG_STBITERR) || \ + ((FLAG) == SDIO_FLAG_DBCKEND) || \ + ((FLAG) == SDIO_FLAG_CMDACT) || \ + ((FLAG) == SDIO_FLAG_TXACT) || \ + ((FLAG) == SDIO_FLAG_RXACT) || \ + ((FLAG) == SDIO_FLAG_TXFIFOHE) || \ + ((FLAG) == SDIO_FLAG_RXFIFOHF) || \ + ((FLAG) == SDIO_FLAG_TXFIFOF) || \ + ((FLAG) == SDIO_FLAG_RXFIFOF) || \ + ((FLAG) == SDIO_FLAG_TXFIFOE) || \ + ((FLAG) == SDIO_FLAG_RXFIFOE) || \ + ((FLAG) == SDIO_FLAG_TXDAVL) || \ + ((FLAG) == SDIO_FLAG_RXDAVL) || \ + ((FLAG) == SDIO_FLAG_SDIOIT) || \ + ((FLAG) == SDIO_FLAG_CEATAEND)) + +#define IS_SDIO_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFF3FF800) == 0x00) && ((FLAG) != (uint32_t)0x00)) + +#define IS_SDIO_GET_IT(IT) (((IT) == SDIO_IT_CCRCFAIL) || \ + ((IT) == SDIO_IT_DCRCFAIL) || \ + ((IT) == SDIO_IT_CTIMEOUT) || \ + ((IT) == SDIO_IT_DTIMEOUT) || \ + ((IT) == SDIO_IT_TXUNDERR) || \ + ((IT) == SDIO_IT_RXOVERR) || \ + ((IT) == SDIO_IT_CMDREND) || \ + ((IT) == SDIO_IT_CMDSENT) || \ + ((IT) == SDIO_IT_DATAEND) || \ + ((IT) == SDIO_IT_STBITERR) || \ + ((IT) == SDIO_IT_DBCKEND) || \ + ((IT) == SDIO_IT_CMDACT) || \ + ((IT) == SDIO_IT_TXACT) || \ + ((IT) == SDIO_IT_RXACT) || \ + ((IT) == SDIO_IT_TXFIFOHE) || \ + ((IT) == SDIO_IT_RXFIFOHF) || \ + ((IT) == SDIO_IT_TXFIFOF) || \ + ((IT) == SDIO_IT_RXFIFOF) || \ + ((IT) == SDIO_IT_TXFIFOE) || \ + ((IT) == SDIO_IT_RXFIFOE) || \ + ((IT) == SDIO_IT_TXDAVL) || \ + ((IT) == SDIO_IT_RXDAVL) || \ + ((IT) == SDIO_IT_SDIOIT) || \ + ((IT) == SDIO_IT_CEATAEND)) + +#define IS_SDIO_CLEAR_IT(IT) ((((IT) & (uint32_t)0xFF3FF800) == 0x00) && ((IT) != (uint32_t)0x00)) + +/** + * @} + */ + +/** @defgroup SDIO_Read_Wait_Mode + * @{ + */ + +#define SDIO_ReadWaitMode_CLK ((uint32_t)0x00000001) +#define SDIO_ReadWaitMode_DATA2 ((uint32_t)0x00000000) +#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_ReadWaitMode_CLK) || \ + ((MODE) == SDIO_ReadWaitMode_DATA2)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup SDIO_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Exported_Functions + * @{ + */ + +void SDIO_DeInit(void); +void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct); +void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct); +void SDIO_ClockCmd(FunctionalState NewState); +void SDIO_SetPowerState(uint32_t SDIO_PowerState); +uint32_t SDIO_GetPowerState(void); +void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState); +void SDIO_DMACmd(FunctionalState NewState); +void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct); +void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct); +uint8_t SDIO_GetCommandResponse(void); +uint32_t SDIO_GetResponse(uint32_t SDIO_RESP); +void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct); +void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct); +uint32_t SDIO_GetDataCounter(void); +uint32_t SDIO_ReadData(void); +void SDIO_WriteData(uint32_t Data); +uint32_t SDIO_GetFIFOCount(void); +void SDIO_StartSDIOReadWait(FunctionalState NewState); +void SDIO_StopSDIOReadWait(FunctionalState NewState); +void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode); +void SDIO_SetSDIOOperation(FunctionalState NewState); +void SDIO_SendSDIOSuspendCmd(FunctionalState NewState); +void SDIO_CommandCompletionCmd(FunctionalState NewState); +void SDIO_CEATAITCmd(FunctionalState NewState); +void SDIO_SendCEATACmd(FunctionalState NewState); +FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG); +void SDIO_ClearFlag(uint32_t SDIO_FLAG); +ITStatus SDIO_GetITStatus(uint32_t SDIO_IT); +void SDIO_ClearITPendingBit(uint32_t SDIO_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_SDIO_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h index c095c95af..a33e52a05 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h @@ -1,486 +1,486 @@ -/** - ****************************************************************************** - * @file stm32f10x_spi.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the SPI firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_SPI_H -#define __STM32F10x_SPI_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup SPI - * @{ - */ - -/** @defgroup SPI_Exported_Types - * @{ - */ - -/** - * @brief SPI Init structure definition - */ - -typedef struct -{ - uint16_t SPI_Direction; /*!< Specifies the SPI unidirectional or bidirectional data mode. - This parameter can be a value of @ref SPI_data_direction */ - - uint16_t SPI_Mode; /*!< Specifies the SPI operating mode. - This parameter can be a value of @ref SPI_mode */ - - uint16_t SPI_DataSize; /*!< Specifies the SPI data size. - This parameter can be a value of @ref SPI_data_size */ - - uint16_t SPI_CPOL; /*!< Specifies the serial clock steady state. - This parameter can be a value of @ref SPI_Clock_Polarity */ - - uint16_t SPI_CPHA; /*!< Specifies the clock active edge for the bit capture. - This parameter can be a value of @ref SPI_Clock_Phase */ - - uint16_t SPI_NSS; /*!< Specifies whether the NSS signal is managed by - hardware (NSS pin) or by software using the SSI bit. - This parameter can be a value of @ref SPI_Slave_Select_management */ - - uint16_t SPI_BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be - used to configure the transmit and receive SCK clock. - This parameter can be a value of @ref SPI_BaudRate_Prescaler. - @note The communication clock is derived from the master - clock. The slave clock does not need to be set. */ - - uint16_t SPI_FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. - This parameter can be a value of @ref SPI_MSB_LSB_transmission */ - - uint16_t SPI_CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. */ -}SPI_InitTypeDef; - -/** - * @brief I2S Init structure definition - */ - -typedef struct -{ - - uint16_t I2S_Mode; /*!< Specifies the I2S operating mode. - This parameter can be a value of @ref I2S_Mode */ - - uint16_t I2S_Standard; /*!< Specifies the standard used for the I2S communication. - This parameter can be a value of @ref I2S_Standard */ - - uint16_t I2S_DataFormat; /*!< Specifies the data format for the I2S communication. - This parameter can be a value of @ref I2S_Data_Format */ - - uint16_t I2S_MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. - This parameter can be a value of @ref I2S_MCLK_Output */ - - uint32_t I2S_AudioFreq; /*!< Specifies the frequency selected for the I2S communication. - This parameter can be a value of @ref I2S_Audio_Frequency */ - - uint16_t I2S_CPOL; /*!< Specifies the idle state of the I2S clock. - This parameter can be a value of @ref I2S_Clock_Polarity */ -}I2S_InitTypeDef; - -/** - * @} - */ - -/** @defgroup SPI_Exported_Constants - * @{ - */ - -#define IS_SPI_ALL_PERIPH(PERIPH) (((PERIPH) == SPI1) || \ - ((PERIPH) == SPI2) || \ - ((PERIPH) == SPI3)) - -#define IS_SPI_23_PERIPH(PERIPH) (((PERIPH) == SPI2) || \ - ((PERIPH) == SPI3)) - -/** @defgroup SPI_data_direction - * @{ - */ - -#define SPI_Direction_2Lines_FullDuplex ((uint16_t)0x0000) -#define SPI_Direction_2Lines_RxOnly ((uint16_t)0x0400) -#define SPI_Direction_1Line_Rx ((uint16_t)0x8000) -#define SPI_Direction_1Line_Tx ((uint16_t)0xC000) -#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \ - ((MODE) == SPI_Direction_2Lines_RxOnly) || \ - ((MODE) == SPI_Direction_1Line_Rx) || \ - ((MODE) == SPI_Direction_1Line_Tx)) -/** - * @} - */ - -/** @defgroup SPI_mode - * @{ - */ - -#define SPI_Mode_Master ((uint16_t)0x0104) -#define SPI_Mode_Slave ((uint16_t)0x0000) -#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \ - ((MODE) == SPI_Mode_Slave)) -/** - * @} - */ - -/** @defgroup SPI_data_size - * @{ - */ - -#define SPI_DataSize_16b ((uint16_t)0x0800) -#define SPI_DataSize_8b ((uint16_t)0x0000) -#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \ - ((DATASIZE) == SPI_DataSize_8b)) -/** - * @} - */ - -/** @defgroup SPI_Clock_Polarity - * @{ - */ - -#define SPI_CPOL_Low ((uint16_t)0x0000) -#define SPI_CPOL_High ((uint16_t)0x0002) -#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \ - ((CPOL) == SPI_CPOL_High)) -/** - * @} - */ - -/** @defgroup SPI_Clock_Phase - * @{ - */ - -#define SPI_CPHA_1Edge ((uint16_t)0x0000) -#define SPI_CPHA_2Edge ((uint16_t)0x0001) -#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \ - ((CPHA) == SPI_CPHA_2Edge)) -/** - * @} - */ - -/** @defgroup SPI_Slave_Select_management - * @{ - */ - -#define SPI_NSS_Soft ((uint16_t)0x0200) -#define SPI_NSS_Hard ((uint16_t)0x0000) -#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \ - ((NSS) == SPI_NSS_Hard)) -/** - * @} - */ - -/** @defgroup SPI_BaudRate_Prescaler - * @{ - */ - -#define SPI_BaudRatePrescaler_2 ((uint16_t)0x0000) -#define SPI_BaudRatePrescaler_4 ((uint16_t)0x0008) -#define SPI_BaudRatePrescaler_8 ((uint16_t)0x0010) -#define SPI_BaudRatePrescaler_16 ((uint16_t)0x0018) -#define SPI_BaudRatePrescaler_32 ((uint16_t)0x0020) -#define SPI_BaudRatePrescaler_64 ((uint16_t)0x0028) -#define SPI_BaudRatePrescaler_128 ((uint16_t)0x0030) -#define SPI_BaudRatePrescaler_256 ((uint16_t)0x0038) -#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \ - ((PRESCALER) == SPI_BaudRatePrescaler_4) || \ - ((PRESCALER) == SPI_BaudRatePrescaler_8) || \ - ((PRESCALER) == SPI_BaudRatePrescaler_16) || \ - ((PRESCALER) == SPI_BaudRatePrescaler_32) || \ - ((PRESCALER) == SPI_BaudRatePrescaler_64) || \ - ((PRESCALER) == SPI_BaudRatePrescaler_128) || \ - ((PRESCALER) == SPI_BaudRatePrescaler_256)) -/** - * @} - */ - -/** @defgroup SPI_MSB_LSB_transmission - * @{ - */ - -#define SPI_FirstBit_MSB ((uint16_t)0x0000) -#define SPI_FirstBit_LSB ((uint16_t)0x0080) -#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \ - ((BIT) == SPI_FirstBit_LSB)) -/** - * @} - */ - -/** @defgroup I2S_Mode - * @{ - */ - -#define I2S_Mode_SlaveTx ((uint16_t)0x0000) -#define I2S_Mode_SlaveRx ((uint16_t)0x0100) -#define I2S_Mode_MasterTx ((uint16_t)0x0200) -#define I2S_Mode_MasterRx ((uint16_t)0x0300) -#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \ - ((MODE) == I2S_Mode_SlaveRx) || \ - ((MODE) == I2S_Mode_MasterTx) || \ - ((MODE) == I2S_Mode_MasterRx) ) -/** - * @} - */ - -/** @defgroup I2S_Standard - * @{ - */ - -#define I2S_Standard_Phillips ((uint16_t)0x0000) -#define I2S_Standard_MSB ((uint16_t)0x0010) -#define I2S_Standard_LSB ((uint16_t)0x0020) -#define I2S_Standard_PCMShort ((uint16_t)0x0030) -#define I2S_Standard_PCMLong ((uint16_t)0x00B0) -#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \ - ((STANDARD) == I2S_Standard_MSB) || \ - ((STANDARD) == I2S_Standard_LSB) || \ - ((STANDARD) == I2S_Standard_PCMShort) || \ - ((STANDARD) == I2S_Standard_PCMLong)) -/** - * @} - */ - -/** @defgroup I2S_Data_Format - * @{ - */ - -#define I2S_DataFormat_16b ((uint16_t)0x0000) -#define I2S_DataFormat_16bextended ((uint16_t)0x0001) -#define I2S_DataFormat_24b ((uint16_t)0x0003) -#define I2S_DataFormat_32b ((uint16_t)0x0005) -#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \ - ((FORMAT) == I2S_DataFormat_16bextended) || \ - ((FORMAT) == I2S_DataFormat_24b) || \ - ((FORMAT) == I2S_DataFormat_32b)) -/** - * @} - */ - -/** @defgroup I2S_MCLK_Output - * @{ - */ - -#define I2S_MCLKOutput_Enable ((uint16_t)0x0200) -#define I2S_MCLKOutput_Disable ((uint16_t)0x0000) -#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \ - ((OUTPUT) == I2S_MCLKOutput_Disable)) -/** - * @} - */ - -/** @defgroup I2S_Audio_Frequency - * @{ - */ - -#define I2S_AudioFreq_192k ((uint32_t)192000) -#define I2S_AudioFreq_96k ((uint32_t)96000) -#define I2S_AudioFreq_48k ((uint32_t)48000) -#define I2S_AudioFreq_44k ((uint32_t)44100) -#define I2S_AudioFreq_32k ((uint32_t)32000) -#define I2S_AudioFreq_22k ((uint32_t)22050) -#define I2S_AudioFreq_16k ((uint32_t)16000) -#define I2S_AudioFreq_11k ((uint32_t)11025) -#define I2S_AudioFreq_8k ((uint32_t)8000) -#define I2S_AudioFreq_Default ((uint32_t)2) - -#define IS_I2S_AUDIO_FREQ(FREQ) ((((FREQ) >= I2S_AudioFreq_8k) && \ - ((FREQ) <= I2S_AudioFreq_192k)) || \ - ((FREQ) == I2S_AudioFreq_Default)) -/** - * @} - */ - -/** @defgroup I2S_Clock_Polarity - * @{ - */ - -#define I2S_CPOL_Low ((uint16_t)0x0000) -#define I2S_CPOL_High ((uint16_t)0x0008) -#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \ - ((CPOL) == I2S_CPOL_High)) -/** - * @} - */ - -/** @defgroup SPI_I2S_DMA_transfer_requests - * @{ - */ - -#define SPI_I2S_DMAReq_Tx ((uint16_t)0x0002) -#define SPI_I2S_DMAReq_Rx ((uint16_t)0x0001) -#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFFFC) == 0x00) && ((DMAREQ) != 0x00)) -/** - * @} - */ - -/** @defgroup SPI_NSS_internal_software_mangement - * @{ - */ - -#define SPI_NSSInternalSoft_Set ((uint16_t)0x0100) -#define SPI_NSSInternalSoft_Reset ((uint16_t)0xFEFF) -#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \ - ((INTERNAL) == SPI_NSSInternalSoft_Reset)) -/** - * @} - */ - -/** @defgroup SPI_CRC_Transmit_Receive - * @{ - */ - -#define SPI_CRC_Tx ((uint8_t)0x00) -#define SPI_CRC_Rx ((uint8_t)0x01) -#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx)) -/** - * @} - */ - -/** @defgroup SPI_direction_transmit_receive - * @{ - */ - -#define SPI_Direction_Rx ((uint16_t)0xBFFF) -#define SPI_Direction_Tx ((uint16_t)0x4000) -#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \ - ((DIRECTION) == SPI_Direction_Tx)) -/** - * @} - */ - -/** @defgroup SPI_I2S_interrupts_definition - * @{ - */ - -#define SPI_I2S_IT_TXE ((uint8_t)0x71) -#define SPI_I2S_IT_RXNE ((uint8_t)0x60) -#define SPI_I2S_IT_ERR ((uint8_t)0x50) -#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \ - ((IT) == SPI_I2S_IT_RXNE) || \ - ((IT) == SPI_I2S_IT_ERR)) -#define SPI_I2S_IT_OVR ((uint8_t)0x56) -#define SPI_IT_MODF ((uint8_t)0x55) -#define SPI_IT_CRCERR ((uint8_t)0x54) -#define I2S_IT_UDR ((uint8_t)0x53) -#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_IT_CRCERR)) -#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE) || ((IT) == SPI_I2S_IT_TXE) || \ - ((IT) == I2S_IT_UDR) || ((IT) == SPI_IT_CRCERR) || \ - ((IT) == SPI_IT_MODF) || ((IT) == SPI_I2S_IT_OVR)) -/** - * @} - */ - -/** @defgroup SPI_I2S_flags_definition - * @{ - */ - -#define SPI_I2S_FLAG_RXNE ((uint16_t)0x0001) -#define SPI_I2S_FLAG_TXE ((uint16_t)0x0002) -#define I2S_FLAG_CHSIDE ((uint16_t)0x0004) -#define I2S_FLAG_UDR ((uint16_t)0x0008) -#define SPI_FLAG_CRCERR ((uint16_t)0x0010) -#define SPI_FLAG_MODF ((uint16_t)0x0020) -#define SPI_I2S_FLAG_OVR ((uint16_t)0x0040) -#define SPI_I2S_FLAG_BSY ((uint16_t)0x0080) -#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR)) -#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \ - ((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \ - ((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \ - ((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE)) -/** - * @} - */ - -/** @defgroup SPI_CRC_polynomial - * @{ - */ - -#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1) -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup SPI_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup SPI_Exported_Functions - * @{ - */ - -void SPI_I2S_DeInit(SPI_TypeDef* SPIx); -void SPI_Init(SPI_TypeDef* SPIx, const SPI_InitTypeDef* SPI_InitStruct); -void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct); -void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct); -void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct); -void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); -void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); -void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState); -void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState); -void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data); -uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx); -void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft); -void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState); -void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize); -void SPI_TransmitCRC(SPI_TypeDef* SPIx); -void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState); -uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC); -uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx); -void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction); -FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); -void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); -ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); -void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F10x_SPI_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_spi.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the SPI firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_SPI_H +#define __STM32F10x_SPI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SPI + * @{ + */ + +/** @defgroup SPI_Exported_Types + * @{ + */ + +/** + * @brief SPI Init structure definition + */ + +typedef struct +{ + uint16_t SPI_Direction; /*!< Specifies the SPI unidirectional or bidirectional data mode. + This parameter can be a value of @ref SPI_data_direction */ + + uint16_t SPI_Mode; /*!< Specifies the SPI operating mode. + This parameter can be a value of @ref SPI_mode */ + + uint16_t SPI_DataSize; /*!< Specifies the SPI data size. + This parameter can be a value of @ref SPI_data_size */ + + uint16_t SPI_CPOL; /*!< Specifies the serial clock steady state. + This parameter can be a value of @ref SPI_Clock_Polarity */ + + uint16_t SPI_CPHA; /*!< Specifies the clock active edge for the bit capture. + This parameter can be a value of @ref SPI_Clock_Phase */ + + uint16_t SPI_NSS; /*!< Specifies whether the NSS signal is managed by + hardware (NSS pin) or by software using the SSI bit. + This parameter can be a value of @ref SPI_Slave_Select_management */ + + uint16_t SPI_BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be + used to configure the transmit and receive SCK clock. + This parameter can be a value of @ref SPI_BaudRate_Prescaler. + @note The communication clock is derived from the master + clock. The slave clock does not need to be set. */ + + uint16_t SPI_FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. + This parameter can be a value of @ref SPI_MSB_LSB_transmission */ + + uint16_t SPI_CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. */ +}SPI_InitTypeDef; + +/** + * @brief I2S Init structure definition + */ + +typedef struct +{ + + uint16_t I2S_Mode; /*!< Specifies the I2S operating mode. + This parameter can be a value of @ref I2S_Mode */ + + uint16_t I2S_Standard; /*!< Specifies the standard used for the I2S communication. + This parameter can be a value of @ref I2S_Standard */ + + uint16_t I2S_DataFormat; /*!< Specifies the data format for the I2S communication. + This parameter can be a value of @ref I2S_Data_Format */ + + uint16_t I2S_MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. + This parameter can be a value of @ref I2S_MCLK_Output */ + + uint32_t I2S_AudioFreq; /*!< Specifies the frequency selected for the I2S communication. + This parameter can be a value of @ref I2S_Audio_Frequency */ + + uint16_t I2S_CPOL; /*!< Specifies the idle state of the I2S clock. + This parameter can be a value of @ref I2S_Clock_Polarity */ +}I2S_InitTypeDef; + +/** + * @} + */ + +/** @defgroup SPI_Exported_Constants + * @{ + */ + +#define IS_SPI_ALL_PERIPH(PERIPH) (((PERIPH) == SPI1) || \ + ((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3)) + +#define IS_SPI_23_PERIPH(PERIPH) (((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3)) + +/** @defgroup SPI_data_direction + * @{ + */ + +#define SPI_Direction_2Lines_FullDuplex ((uint16_t)0x0000) +#define SPI_Direction_2Lines_RxOnly ((uint16_t)0x0400) +#define SPI_Direction_1Line_Rx ((uint16_t)0x8000) +#define SPI_Direction_1Line_Tx ((uint16_t)0xC000) +#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \ + ((MODE) == SPI_Direction_2Lines_RxOnly) || \ + ((MODE) == SPI_Direction_1Line_Rx) || \ + ((MODE) == SPI_Direction_1Line_Tx)) +/** + * @} + */ + +/** @defgroup SPI_mode + * @{ + */ + +#define SPI_Mode_Master ((uint16_t)0x0104) +#define SPI_Mode_Slave ((uint16_t)0x0000) +#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \ + ((MODE) == SPI_Mode_Slave)) +/** + * @} + */ + +/** @defgroup SPI_data_size + * @{ + */ + +#define SPI_DataSize_16b ((uint16_t)0x0800) +#define SPI_DataSize_8b ((uint16_t)0x0000) +#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \ + ((DATASIZE) == SPI_DataSize_8b)) +/** + * @} + */ + +/** @defgroup SPI_Clock_Polarity + * @{ + */ + +#define SPI_CPOL_Low ((uint16_t)0x0000) +#define SPI_CPOL_High ((uint16_t)0x0002) +#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \ + ((CPOL) == SPI_CPOL_High)) +/** + * @} + */ + +/** @defgroup SPI_Clock_Phase + * @{ + */ + +#define SPI_CPHA_1Edge ((uint16_t)0x0000) +#define SPI_CPHA_2Edge ((uint16_t)0x0001) +#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \ + ((CPHA) == SPI_CPHA_2Edge)) +/** + * @} + */ + +/** @defgroup SPI_Slave_Select_management + * @{ + */ + +#define SPI_NSS_Soft ((uint16_t)0x0200) +#define SPI_NSS_Hard ((uint16_t)0x0000) +#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \ + ((NSS) == SPI_NSS_Hard)) +/** + * @} + */ + +/** @defgroup SPI_BaudRate_Prescaler + * @{ + */ + +#define SPI_BaudRatePrescaler_2 ((uint16_t)0x0000) +#define SPI_BaudRatePrescaler_4 ((uint16_t)0x0008) +#define SPI_BaudRatePrescaler_8 ((uint16_t)0x0010) +#define SPI_BaudRatePrescaler_16 ((uint16_t)0x0018) +#define SPI_BaudRatePrescaler_32 ((uint16_t)0x0020) +#define SPI_BaudRatePrescaler_64 ((uint16_t)0x0028) +#define SPI_BaudRatePrescaler_128 ((uint16_t)0x0030) +#define SPI_BaudRatePrescaler_256 ((uint16_t)0x0038) +#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_4) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_8) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_16) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_32) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_64) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_128) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_256)) +/** + * @} + */ + +/** @defgroup SPI_MSB_LSB_transmission + * @{ + */ + +#define SPI_FirstBit_MSB ((uint16_t)0x0000) +#define SPI_FirstBit_LSB ((uint16_t)0x0080) +#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \ + ((BIT) == SPI_FirstBit_LSB)) +/** + * @} + */ + +/** @defgroup I2S_Mode + * @{ + */ + +#define I2S_Mode_SlaveTx ((uint16_t)0x0000) +#define I2S_Mode_SlaveRx ((uint16_t)0x0100) +#define I2S_Mode_MasterTx ((uint16_t)0x0200) +#define I2S_Mode_MasterRx ((uint16_t)0x0300) +#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \ + ((MODE) == I2S_Mode_SlaveRx) || \ + ((MODE) == I2S_Mode_MasterTx) || \ + ((MODE) == I2S_Mode_MasterRx) ) +/** + * @} + */ + +/** @defgroup I2S_Standard + * @{ + */ + +#define I2S_Standard_Phillips ((uint16_t)0x0000) +#define I2S_Standard_MSB ((uint16_t)0x0010) +#define I2S_Standard_LSB ((uint16_t)0x0020) +#define I2S_Standard_PCMShort ((uint16_t)0x0030) +#define I2S_Standard_PCMLong ((uint16_t)0x00B0) +#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \ + ((STANDARD) == I2S_Standard_MSB) || \ + ((STANDARD) == I2S_Standard_LSB) || \ + ((STANDARD) == I2S_Standard_PCMShort) || \ + ((STANDARD) == I2S_Standard_PCMLong)) +/** + * @} + */ + +/** @defgroup I2S_Data_Format + * @{ + */ + +#define I2S_DataFormat_16b ((uint16_t)0x0000) +#define I2S_DataFormat_16bextended ((uint16_t)0x0001) +#define I2S_DataFormat_24b ((uint16_t)0x0003) +#define I2S_DataFormat_32b ((uint16_t)0x0005) +#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \ + ((FORMAT) == I2S_DataFormat_16bextended) || \ + ((FORMAT) == I2S_DataFormat_24b) || \ + ((FORMAT) == I2S_DataFormat_32b)) +/** + * @} + */ + +/** @defgroup I2S_MCLK_Output + * @{ + */ + +#define I2S_MCLKOutput_Enable ((uint16_t)0x0200) +#define I2S_MCLKOutput_Disable ((uint16_t)0x0000) +#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \ + ((OUTPUT) == I2S_MCLKOutput_Disable)) +/** + * @} + */ + +/** @defgroup I2S_Audio_Frequency + * @{ + */ + +#define I2S_AudioFreq_192k ((uint32_t)192000) +#define I2S_AudioFreq_96k ((uint32_t)96000) +#define I2S_AudioFreq_48k ((uint32_t)48000) +#define I2S_AudioFreq_44k ((uint32_t)44100) +#define I2S_AudioFreq_32k ((uint32_t)32000) +#define I2S_AudioFreq_22k ((uint32_t)22050) +#define I2S_AudioFreq_16k ((uint32_t)16000) +#define I2S_AudioFreq_11k ((uint32_t)11025) +#define I2S_AudioFreq_8k ((uint32_t)8000) +#define I2S_AudioFreq_Default ((uint32_t)2) + +#define IS_I2S_AUDIO_FREQ(FREQ) ((((FREQ) >= I2S_AudioFreq_8k) && \ + ((FREQ) <= I2S_AudioFreq_192k)) || \ + ((FREQ) == I2S_AudioFreq_Default)) +/** + * @} + */ + +/** @defgroup I2S_Clock_Polarity + * @{ + */ + +#define I2S_CPOL_Low ((uint16_t)0x0000) +#define I2S_CPOL_High ((uint16_t)0x0008) +#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \ + ((CPOL) == I2S_CPOL_High)) +/** + * @} + */ + +/** @defgroup SPI_I2S_DMA_transfer_requests + * @{ + */ + +#define SPI_I2S_DMAReq_Tx ((uint16_t)0x0002) +#define SPI_I2S_DMAReq_Rx ((uint16_t)0x0001) +#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFFFC) == 0x00) && ((DMAREQ) != 0x00)) +/** + * @} + */ + +/** @defgroup SPI_NSS_internal_software_mangement + * @{ + */ + +#define SPI_NSSInternalSoft_Set ((uint16_t)0x0100) +#define SPI_NSSInternalSoft_Reset ((uint16_t)0xFEFF) +#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \ + ((INTERNAL) == SPI_NSSInternalSoft_Reset)) +/** + * @} + */ + +/** @defgroup SPI_CRC_Transmit_Receive + * @{ + */ + +#define SPI_CRC_Tx ((uint8_t)0x00) +#define SPI_CRC_Rx ((uint8_t)0x01) +#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx)) +/** + * @} + */ + +/** @defgroup SPI_direction_transmit_receive + * @{ + */ + +#define SPI_Direction_Rx ((uint16_t)0xBFFF) +#define SPI_Direction_Tx ((uint16_t)0x4000) +#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \ + ((DIRECTION) == SPI_Direction_Tx)) +/** + * @} + */ + +/** @defgroup SPI_I2S_interrupts_definition + * @{ + */ + +#define SPI_I2S_IT_TXE ((uint8_t)0x71) +#define SPI_I2S_IT_RXNE ((uint8_t)0x60) +#define SPI_I2S_IT_ERR ((uint8_t)0x50) +#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \ + ((IT) == SPI_I2S_IT_RXNE) || \ + ((IT) == SPI_I2S_IT_ERR)) +#define SPI_I2S_IT_OVR ((uint8_t)0x56) +#define SPI_IT_MODF ((uint8_t)0x55) +#define SPI_IT_CRCERR ((uint8_t)0x54) +#define I2S_IT_UDR ((uint8_t)0x53) +#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_IT_CRCERR)) +#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE) || ((IT) == SPI_I2S_IT_TXE) || \ + ((IT) == I2S_IT_UDR) || ((IT) == SPI_IT_CRCERR) || \ + ((IT) == SPI_IT_MODF) || ((IT) == SPI_I2S_IT_OVR)) +/** + * @} + */ + +/** @defgroup SPI_I2S_flags_definition + * @{ + */ + +#define SPI_I2S_FLAG_RXNE ((uint16_t)0x0001) +#define SPI_I2S_FLAG_TXE ((uint16_t)0x0002) +#define I2S_FLAG_CHSIDE ((uint16_t)0x0004) +#define I2S_FLAG_UDR ((uint16_t)0x0008) +#define SPI_FLAG_CRCERR ((uint16_t)0x0010) +#define SPI_FLAG_MODF ((uint16_t)0x0020) +#define SPI_I2S_FLAG_OVR ((uint16_t)0x0040) +#define SPI_I2S_FLAG_BSY ((uint16_t)0x0080) +#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR)) +#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \ + ((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \ + ((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \ + ((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE)) +/** + * @} + */ + +/** @defgroup SPI_CRC_polynomial + * @{ + */ + +#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup SPI_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Exported_Functions + * @{ + */ + +void SPI_I2S_DeInit(SPI_TypeDef* SPIx); +void SPI_Init(SPI_TypeDef* SPIx, const SPI_InitTypeDef* SPI_InitStruct); +void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct); +void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct); +void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct); +void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState); +void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState); +void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data); +uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx); +void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft); +void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize); +void SPI_TransmitCRC(SPI_TypeDef* SPIx); +void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState); +uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC); +uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx); +void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction); +FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); +void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); +ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); +void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_SPI_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h index 388d276e4..1a09d25f7 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h @@ -1,1137 +1,1137 @@ -/** - ****************************************************************************** - * @file stm32f10x_tim.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the TIM firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_TIM_H -#define __STM32F10x_TIM_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup TIM - * @{ - */ - -/** @defgroup TIM_Exported_Types - * @{ - */ - -/** - * @brief TIM Time Base Init structure definition - * @note This sturcture is used with all TIMx except for TIM6 and TIM7. - */ - -typedef struct -{ - uint16_t TIM_Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. - This parameter can be a number between 0x0000 and 0xFFFF */ - - uint16_t TIM_CounterMode; /*!< Specifies the counter mode. - This parameter can be a value of @ref TIM_Counter_Mode */ - - uint16_t TIM_Period; /*!< Specifies the period value to be loaded into the active - Auto-Reload Register at the next update event. - This parameter must be a number between 0x0000 and 0xFFFF. */ - - uint16_t TIM_ClockDivision; /*!< Specifies the clock division. - This parameter can be a value of @ref TIM_Clock_Division_CKD */ - - uint8_t TIM_RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter - reaches zero, an update event is generated and counting restarts - from the RCR value (N). - This means in PWM mode that (N+1) corresponds to: - - the number of PWM periods in edge-aligned mode - - the number of half PWM period in center-aligned mode - This parameter must be a number between 0x00 and 0xFF. - @note This parameter is valid only for TIM1 and TIM8. */ -} TIM_TimeBaseInitTypeDef; - -/** - * @brief TIM Output Compare Init structure definition - */ - -typedef struct -{ - uint16_t TIM_OCMode; /*!< Specifies the TIM mode. - This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ - - uint16_t TIM_OutputState; /*!< Specifies the TIM Output Compare state. - This parameter can be a value of @ref TIM_Output_Compare_state */ - - uint16_t TIM_OutputNState; /*!< Specifies the TIM complementary Output Compare state. - This parameter can be a value of @ref TIM_Output_Compare_N_state - @note This parameter is valid only for TIM1 and TIM8. */ - - uint16_t TIM_Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. - This parameter can be a number between 0x0000 and 0xFFFF */ - - uint16_t TIM_OCPolarity; /*!< Specifies the output polarity. - This parameter can be a value of @ref TIM_Output_Compare_Polarity */ - - uint16_t TIM_OCNPolarity; /*!< Specifies the complementary output polarity. - This parameter can be a value of @ref TIM_Output_Compare_N_Polarity - @note This parameter is valid only for TIM1 and TIM8. */ - - uint16_t TIM_OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_Idle_State - @note This parameter is valid only for TIM1 and TIM8. */ - - uint16_t TIM_OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State - @note This parameter is valid only for TIM1 and TIM8. */ -} TIM_OCInitTypeDef; - -/** - * @brief TIM Input Capture Init structure definition - */ - -typedef struct -{ - - uint16_t TIM_Channel; /*!< Specifies the TIM channel. - This parameter can be a value of @ref TIM_Channel */ - - uint16_t TIM_ICPolarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Input_Capture_Polarity */ - - uint16_t TIM_ICSelection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint16_t TIM_ICPrescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint16_t TIM_ICFilter; /*!< Specifies the input capture filter. - This parameter can be a number between 0x0 and 0xF */ -} TIM_ICInitTypeDef; - -/** - * @brief BDTR structure definition - * @note This sturcture is used only with TIM1 and TIM8. - */ - -typedef struct -{ - - uint16_t TIM_OSSRState; /*!< Specifies the Off-State selection used in Run mode. - This parameter can be a value of @ref OSSR_Off_State_Selection_for_Run_mode_state */ - - uint16_t TIM_OSSIState; /*!< Specifies the Off-State used in Idle state. - This parameter can be a value of @ref OSSI_Off_State_Selection_for_Idle_mode_state */ - - uint16_t TIM_LOCKLevel; /*!< Specifies the LOCK level parameters. - This parameter can be a value of @ref Lock_level */ - - uint16_t TIM_DeadTime; /*!< Specifies the delay time between the switching-off and the - switching-on of the outputs. - This parameter can be a number between 0x00 and 0xFF */ - - uint16_t TIM_Break; /*!< Specifies whether the TIM Break input is enabled or not. - This parameter can be a value of @ref Break_Input_enable_disable */ - - uint16_t TIM_BreakPolarity; /*!< Specifies the TIM Break Input pin polarity. - This parameter can be a value of @ref Break_Polarity */ - - uint16_t TIM_AutomaticOutput; /*!< Specifies whether the TIM Automatic Output feature is enabled or not. - This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */ -} TIM_BDTRInitTypeDef; - -/** @defgroup TIM_Exported_constants - * @{ - */ - -#define IS_TIM_ALL_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ - ((PERIPH) == TIM2) || \ - ((PERIPH) == TIM3) || \ - ((PERIPH) == TIM4) || \ - ((PERIPH) == TIM5) || \ - ((PERIPH) == TIM6) || \ - ((PERIPH) == TIM7) || \ - ((PERIPH) == TIM8) || \ - ((PERIPH) == TIM9) || \ - ((PERIPH) == TIM10)|| \ - ((PERIPH) == TIM11)|| \ - ((PERIPH) == TIM12)|| \ - ((PERIPH) == TIM13)|| \ - ((PERIPH) == TIM14)|| \ - ((PERIPH) == TIM15)|| \ - ((PERIPH) == TIM16)|| \ - ((PERIPH) == TIM17)) - -/* LIST1: TIM 1 and 8 */ -#define IS_TIM_LIST1_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ - ((PERIPH) == TIM8)) - -/* LIST2: TIM 1, 8, 15 16 and 17 */ -#define IS_TIM_LIST2_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ - ((PERIPH) == TIM8) || \ - ((PERIPH) == TIM15)|| \ - ((PERIPH) == TIM16)|| \ - ((PERIPH) == TIM17)) - -/* LIST3: TIM 1, 2, 3, 4, 5 and 8 */ -#define IS_TIM_LIST3_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ - ((PERIPH) == TIM2) || \ - ((PERIPH) == TIM3) || \ - ((PERIPH) == TIM4) || \ - ((PERIPH) == TIM5) || \ - ((PERIPH) == TIM8)) - -/* LIST4: TIM 1, 2, 3, 4, 5, 8, 15, 16 and 17 */ -#define IS_TIM_LIST4_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ - ((PERIPH) == TIM2) || \ - ((PERIPH) == TIM3) || \ - ((PERIPH) == TIM4) || \ - ((PERIPH) == TIM5) || \ - ((PERIPH) == TIM8) || \ - ((PERIPH) == TIM15)|| \ - ((PERIPH) == TIM16)|| \ - ((PERIPH) == TIM17)) - -/* LIST5: TIM 1, 2, 3, 4, 5, 8 and 15 */ -#define IS_TIM_LIST5_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ - ((PERIPH) == TIM2) || \ - ((PERIPH) == TIM3) || \ - ((PERIPH) == TIM4) || \ - ((PERIPH) == TIM5) || \ - ((PERIPH) == TIM8) || \ - ((PERIPH) == TIM15)) - -/* LIST6: TIM 1, 2, 3, 4, 5, 8, 9, 12 and 15 */ -#define IS_TIM_LIST6_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ - ((PERIPH) == TIM2) || \ - ((PERIPH) == TIM3) || \ - ((PERIPH) == TIM4) || \ - ((PERIPH) == TIM5) || \ - ((PERIPH) == TIM8) || \ - ((PERIPH) == TIM9) || \ - ((PERIPH) == TIM12)|| \ - ((PERIPH) == TIM15)) - -/* LIST7: TIM 1, 2, 3, 4, 5, 6, 7, 8, 9, 12 and 15 */ -#define IS_TIM_LIST7_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ - ((PERIPH) == TIM2) || \ - ((PERIPH) == TIM3) || \ - ((PERIPH) == TIM4) || \ - ((PERIPH) == TIM5) || \ - ((PERIPH) == TIM6) || \ - ((PERIPH) == TIM7) || \ - ((PERIPH) == TIM8) || \ - ((PERIPH) == TIM9) || \ - ((PERIPH) == TIM12)|| \ - ((PERIPH) == TIM15)) - -/* LIST8: TIM 1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13, 14, 15, 16 and 17 */ -#define IS_TIM_LIST8_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ - ((PERIPH) == TIM2) || \ - ((PERIPH) == TIM3) || \ - ((PERIPH) == TIM4) || \ - ((PERIPH) == TIM5) || \ - ((PERIPH) == TIM8) || \ - ((PERIPH) == TIM9) || \ - ((PERIPH) == TIM10)|| \ - ((PERIPH) == TIM11)|| \ - ((PERIPH) == TIM12)|| \ - ((PERIPH) == TIM13)|| \ - ((PERIPH) == TIM14)|| \ - ((PERIPH) == TIM15)|| \ - ((PERIPH) == TIM16)|| \ - ((PERIPH) == TIM17)) - -/* LIST9: TIM 1, 2, 3, 4, 5, 6, 7, 8, 15, 16, and 17 */ -#define IS_TIM_LIST9_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ - ((PERIPH) == TIM2) || \ - ((PERIPH) == TIM3) || \ - ((PERIPH) == TIM4) || \ - ((PERIPH) == TIM5) || \ - ((PERIPH) == TIM6) || \ - ((PERIPH) == TIM7) || \ - ((PERIPH) == TIM8) || \ - ((PERIPH) == TIM15)|| \ - ((PERIPH) == TIM16)|| \ - ((PERIPH) == TIM17)) - -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_and_PWM_modes - * @{ - */ - -#define TIM_OCMode_Timing ((uint16_t)0x0000) -#define TIM_OCMode_Active ((uint16_t)0x0010) -#define TIM_OCMode_Inactive ((uint16_t)0x0020) -#define TIM_OCMode_Toggle ((uint16_t)0x0030) -#define TIM_OCMode_PWM1 ((uint16_t)0x0060) -#define TIM_OCMode_PWM2 ((uint16_t)0x0070) -#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \ - ((MODE) == TIM_OCMode_Active) || \ - ((MODE) == TIM_OCMode_Inactive) || \ - ((MODE) == TIM_OCMode_Toggle)|| \ - ((MODE) == TIM_OCMode_PWM1) || \ - ((MODE) == TIM_OCMode_PWM2)) -#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \ - ((MODE) == TIM_OCMode_Active) || \ - ((MODE) == TIM_OCMode_Inactive) || \ - ((MODE) == TIM_OCMode_Toggle)|| \ - ((MODE) == TIM_OCMode_PWM1) || \ - ((MODE) == TIM_OCMode_PWM2) || \ - ((MODE) == TIM_ForcedAction_Active) || \ - ((MODE) == TIM_ForcedAction_InActive)) -/** - * @} - */ - -/** @defgroup TIM_One_Pulse_Mode - * @{ - */ - -#define TIM_OPMode_Single ((uint16_t)0x0008) -#define TIM_OPMode_Repetitive ((uint16_t)0x0000) -#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \ - ((MODE) == TIM_OPMode_Repetitive)) -/** - * @} - */ - -/** @defgroup TIM_Channel - * @{ - */ - -#define TIM_Channel_1 ((uint16_t)0x0000) -#define TIM_Channel_2 ((uint16_t)0x0004) -#define TIM_Channel_3 ((uint16_t)0x0008) -#define TIM_Channel_4 ((uint16_t)0x000C) -#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ - ((CHANNEL) == TIM_Channel_2) || \ - ((CHANNEL) == TIM_Channel_3) || \ - ((CHANNEL) == TIM_Channel_4)) -#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ - ((CHANNEL) == TIM_Channel_2)) -#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ - ((CHANNEL) == TIM_Channel_2) || \ - ((CHANNEL) == TIM_Channel_3)) -/** - * @} - */ - -/** @defgroup TIM_Clock_Division_CKD - * @{ - */ - -#define TIM_CKD_DIV1 ((uint16_t)0x0000) -#define TIM_CKD_DIV2 ((uint16_t)0x0100) -#define TIM_CKD_DIV4 ((uint16_t)0x0200) -#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \ - ((DIV) == TIM_CKD_DIV2) || \ - ((DIV) == TIM_CKD_DIV4)) -/** - * @} - */ - -/** @defgroup TIM_Counter_Mode - * @{ - */ - -#define TIM_CounterMode_Up ((uint16_t)0x0000) -#define TIM_CounterMode_Down ((uint16_t)0x0010) -#define TIM_CounterMode_CenterAligned1 ((uint16_t)0x0020) -#define TIM_CounterMode_CenterAligned2 ((uint16_t)0x0040) -#define TIM_CounterMode_CenterAligned3 ((uint16_t)0x0060) -#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) || \ - ((MODE) == TIM_CounterMode_Down) || \ - ((MODE) == TIM_CounterMode_CenterAligned1) || \ - ((MODE) == TIM_CounterMode_CenterAligned2) || \ - ((MODE) == TIM_CounterMode_CenterAligned3)) -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_Polarity - * @{ - */ - -#define TIM_OCPolarity_High ((uint16_t)0x0000) -#define TIM_OCPolarity_Low ((uint16_t)0x0002) -#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \ - ((POLARITY) == TIM_OCPolarity_Low)) -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_Polarity - * @{ - */ - -#define TIM_OCNPolarity_High ((uint16_t)0x0000) -#define TIM_OCNPolarity_Low ((uint16_t)0x0008) -#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \ - ((POLARITY) == TIM_OCNPolarity_Low)) -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_state - * @{ - */ - -#define TIM_OutputState_Disable ((uint16_t)0x0000) -#define TIM_OutputState_Enable ((uint16_t)0x0001) -#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \ - ((STATE) == TIM_OutputState_Enable)) -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_state - * @{ - */ - -#define TIM_OutputNState_Disable ((uint16_t)0x0000) -#define TIM_OutputNState_Enable ((uint16_t)0x0004) -#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \ - ((STATE) == TIM_OutputNState_Enable)) -/** - * @} - */ - -/** @defgroup TIM_Capture_Compare_state - * @{ - */ - -#define TIM_CCx_Enable ((uint16_t)0x0001) -#define TIM_CCx_Disable ((uint16_t)0x0000) -#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \ - ((CCX) == TIM_CCx_Disable)) -/** - * @} - */ - -/** @defgroup TIM_Capture_Compare_N_state - * @{ - */ - -#define TIM_CCxN_Enable ((uint16_t)0x0004) -#define TIM_CCxN_Disable ((uint16_t)0x0000) -#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \ - ((CCXN) == TIM_CCxN_Disable)) -/** - * @} - */ - -/** @defgroup Break_Input_enable_disable - * @{ - */ - -#define TIM_Break_Enable ((uint16_t)0x1000) -#define TIM_Break_Disable ((uint16_t)0x0000) -#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \ - ((STATE) == TIM_Break_Disable)) -/** - * @} - */ - -/** @defgroup Break_Polarity - * @{ - */ - -#define TIM_BreakPolarity_Low ((uint16_t)0x0000) -#define TIM_BreakPolarity_High ((uint16_t)0x2000) -#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \ - ((POLARITY) == TIM_BreakPolarity_High)) -/** - * @} - */ - -/** @defgroup TIM_AOE_Bit_Set_Reset - * @{ - */ - -#define TIM_AutomaticOutput_Enable ((uint16_t)0x4000) -#define TIM_AutomaticOutput_Disable ((uint16_t)0x0000) -#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \ - ((STATE) == TIM_AutomaticOutput_Disable)) -/** - * @} - */ - -/** @defgroup Lock_level - * @{ - */ - -#define TIM_LOCKLevel_OFF ((uint16_t)0x0000) -#define TIM_LOCKLevel_1 ((uint16_t)0x0100) -#define TIM_LOCKLevel_2 ((uint16_t)0x0200) -#define TIM_LOCKLevel_3 ((uint16_t)0x0300) -#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \ - ((LEVEL) == TIM_LOCKLevel_1) || \ - ((LEVEL) == TIM_LOCKLevel_2) || \ - ((LEVEL) == TIM_LOCKLevel_3)) -/** - * @} - */ - -/** @defgroup OSSI_Off_State_Selection_for_Idle_mode_state - * @{ - */ - -#define TIM_OSSIState_Enable ((uint16_t)0x0400) -#define TIM_OSSIState_Disable ((uint16_t)0x0000) -#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \ - ((STATE) == TIM_OSSIState_Disable)) -/** - * @} - */ - -/** @defgroup OSSR_Off_State_Selection_for_Run_mode_state - * @{ - */ - -#define TIM_OSSRState_Enable ((uint16_t)0x0800) -#define TIM_OSSRState_Disable ((uint16_t)0x0000) -#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \ - ((STATE) == TIM_OSSRState_Disable)) -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_Idle_State - * @{ - */ - -#define TIM_OCIdleState_Set ((uint16_t)0x0100) -#define TIM_OCIdleState_Reset ((uint16_t)0x0000) -#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \ - ((STATE) == TIM_OCIdleState_Reset)) -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_Idle_State - * @{ - */ - -#define TIM_OCNIdleState_Set ((uint16_t)0x0200) -#define TIM_OCNIdleState_Reset ((uint16_t)0x0000) -#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \ - ((STATE) == TIM_OCNIdleState_Reset)) -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Polarity - * @{ - */ - -#define TIM_ICPolarity_Rising ((uint16_t)0x0000) -#define TIM_ICPolarity_Falling ((uint16_t)0x0002) -#define TIM_ICPolarity_BothEdge ((uint16_t)0x000A) -#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \ - ((POLARITY) == TIM_ICPolarity_Falling)) -#define IS_TIM_IC_POLARITY_LITE(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \ - ((POLARITY) == TIM_ICPolarity_Falling)|| \ - ((POLARITY) == TIM_ICPolarity_BothEdge)) -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Selection - * @{ - */ - -#define TIM_ICSelection_DirectTI ((uint16_t)0x0001) /*!< TIM Input 1, 2, 3 or 4 is selected to be - connected to IC1, IC2, IC3 or IC4, respectively */ -#define TIM_ICSelection_IndirectTI ((uint16_t)0x0002) /*!< TIM Input 1, 2, 3 or 4 is selected to be - connected to IC2, IC1, IC4 or IC3, respectively. */ -#define TIM_ICSelection_TRC ((uint16_t)0x0003) /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC. */ -#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \ - ((SELECTION) == TIM_ICSelection_IndirectTI) || \ - ((SELECTION) == TIM_ICSelection_TRC)) -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Prescaler - * @{ - */ - -#define TIM_ICPSC_DIV1 ((uint16_t)0x0000) /*!< Capture performed each time an edge is detected on the capture input. */ -#define TIM_ICPSC_DIV2 ((uint16_t)0x0004) /*!< Capture performed once every 2 events. */ -#define TIM_ICPSC_DIV4 ((uint16_t)0x0008) /*!< Capture performed once every 4 events. */ -#define TIM_ICPSC_DIV8 ((uint16_t)0x000C) /*!< Capture performed once every 8 events. */ -#define IS_TIM_IC_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ICPSC_DIV1) || \ - ((PRESCALER) == TIM_ICPSC_DIV2) || \ - ((PRESCALER) == TIM_ICPSC_DIV4) || \ - ((PRESCALER) == TIM_ICPSC_DIV8)) -/** - * @} - */ - -/** @defgroup TIM_interrupt_sources - * @{ - */ - -#define TIM_IT_Update ((uint16_t)0x0001) -#define TIM_IT_CC1 ((uint16_t)0x0002) -#define TIM_IT_CC2 ((uint16_t)0x0004) -#define TIM_IT_CC3 ((uint16_t)0x0008) -#define TIM_IT_CC4 ((uint16_t)0x0010) -#define TIM_IT_COM ((uint16_t)0x0020) -#define TIM_IT_Trigger ((uint16_t)0x0040) -#define TIM_IT_Break ((uint16_t)0x0080) -#define IS_TIM_IT(IT) ((((IT) & (uint16_t)0xFF00) == 0x0000) && ((IT) != 0x0000)) - -#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \ - ((IT) == TIM_IT_CC1) || \ - ((IT) == TIM_IT_CC2) || \ - ((IT) == TIM_IT_CC3) || \ - ((IT) == TIM_IT_CC4) || \ - ((IT) == TIM_IT_COM) || \ - ((IT) == TIM_IT_Trigger) || \ - ((IT) == TIM_IT_Break)) -/** - * @} - */ - -/** @defgroup TIM_DMA_Base_address - * @{ - */ - -#define TIM_DMABase_CR1 ((uint16_t)0x0000) -#define TIM_DMABase_CR2 ((uint16_t)0x0001) -#define TIM_DMABase_SMCR ((uint16_t)0x0002) -#define TIM_DMABase_DIER ((uint16_t)0x0003) -#define TIM_DMABase_SR ((uint16_t)0x0004) -#define TIM_DMABase_EGR ((uint16_t)0x0005) -#define TIM_DMABase_CCMR1 ((uint16_t)0x0006) -#define TIM_DMABase_CCMR2 ((uint16_t)0x0007) -#define TIM_DMABase_CCER ((uint16_t)0x0008) -#define TIM_DMABase_CNT ((uint16_t)0x0009) -#define TIM_DMABase_PSC ((uint16_t)0x000A) -#define TIM_DMABase_ARR ((uint16_t)0x000B) -#define TIM_DMABase_RCR ((uint16_t)0x000C) -#define TIM_DMABase_CCR1 ((uint16_t)0x000D) -#define TIM_DMABase_CCR2 ((uint16_t)0x000E) -#define TIM_DMABase_CCR3 ((uint16_t)0x000F) -#define TIM_DMABase_CCR4 ((uint16_t)0x0010) -#define TIM_DMABase_BDTR ((uint16_t)0x0011) -#define TIM_DMABase_DCR ((uint16_t)0x0012) -#define IS_TIM_DMA_BASE(BASE) (((BASE) == TIM_DMABase_CR1) || \ - ((BASE) == TIM_DMABase_CR2) || \ - ((BASE) == TIM_DMABase_SMCR) || \ - ((BASE) == TIM_DMABase_DIER) || \ - ((BASE) == TIM_DMABase_SR) || \ - ((BASE) == TIM_DMABase_EGR) || \ - ((BASE) == TIM_DMABase_CCMR1) || \ - ((BASE) == TIM_DMABase_CCMR2) || \ - ((BASE) == TIM_DMABase_CCER) || \ - ((BASE) == TIM_DMABase_CNT) || \ - ((BASE) == TIM_DMABase_PSC) || \ - ((BASE) == TIM_DMABase_ARR) || \ - ((BASE) == TIM_DMABase_RCR) || \ - ((BASE) == TIM_DMABase_CCR1) || \ - ((BASE) == TIM_DMABase_CCR2) || \ - ((BASE) == TIM_DMABase_CCR3) || \ - ((BASE) == TIM_DMABase_CCR4) || \ - ((BASE) == TIM_DMABase_BDTR) || \ - ((BASE) == TIM_DMABase_DCR)) -/** - * @} - */ - -/** @defgroup TIM_DMA_Burst_Length - * @{ - */ - -#define TIM_DMABurstLength_1Byte ((uint16_t)0x0000) -#define TIM_DMABurstLength_2Bytes ((uint16_t)0x0100) -#define TIM_DMABurstLength_3Bytes ((uint16_t)0x0200) -#define TIM_DMABurstLength_4Bytes ((uint16_t)0x0300) -#define TIM_DMABurstLength_5Bytes ((uint16_t)0x0400) -#define TIM_DMABurstLength_6Bytes ((uint16_t)0x0500) -#define TIM_DMABurstLength_7Bytes ((uint16_t)0x0600) -#define TIM_DMABurstLength_8Bytes ((uint16_t)0x0700) -#define TIM_DMABurstLength_9Bytes ((uint16_t)0x0800) -#define TIM_DMABurstLength_10Bytes ((uint16_t)0x0900) -#define TIM_DMABurstLength_11Bytes ((uint16_t)0x0A00) -#define TIM_DMABurstLength_12Bytes ((uint16_t)0x0B00) -#define TIM_DMABurstLength_13Bytes ((uint16_t)0x0C00) -#define TIM_DMABurstLength_14Bytes ((uint16_t)0x0D00) -#define TIM_DMABurstLength_15Bytes ((uint16_t)0x0E00) -#define TIM_DMABurstLength_16Bytes ((uint16_t)0x0F00) -#define TIM_DMABurstLength_17Bytes ((uint16_t)0x1000) -#define TIM_DMABurstLength_18Bytes ((uint16_t)0x1100) -#define IS_TIM_DMA_LENGTH(LENGTH) (((LENGTH) == TIM_DMABurstLength_1Byte) || \ - ((LENGTH) == TIM_DMABurstLength_2Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_3Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_4Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_5Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_6Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_7Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_8Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_9Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_10Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_11Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_12Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_13Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_14Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_15Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_16Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_17Bytes) || \ - ((LENGTH) == TIM_DMABurstLength_18Bytes)) -/** - * @} - */ - -/** @defgroup TIM_DMA_sources - * @{ - */ - -#define TIM_DMA_Update ((uint16_t)0x0100) -#define TIM_DMA_CC1 ((uint16_t)0x0200) -#define TIM_DMA_CC2 ((uint16_t)0x0400) -#define TIM_DMA_CC3 ((uint16_t)0x0800) -#define TIM_DMA_CC4 ((uint16_t)0x1000) -#define TIM_DMA_COM ((uint16_t)0x2000) -#define TIM_DMA_Trigger ((uint16_t)0x4000) -#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0x80FF) == 0x0000) && ((SOURCE) != 0x0000)) - -/** - * @} - */ - -/** @defgroup TIM_External_Trigger_Prescaler - * @{ - */ - -#define TIM_ExtTRGPSC_OFF ((uint16_t)0x0000) -#define TIM_ExtTRGPSC_DIV2 ((uint16_t)0x1000) -#define TIM_ExtTRGPSC_DIV4 ((uint16_t)0x2000) -#define TIM_ExtTRGPSC_DIV8 ((uint16_t)0x3000) -#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \ - ((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \ - ((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \ - ((PRESCALER) == TIM_ExtTRGPSC_DIV8)) -/** - * @} - */ - -/** @defgroup TIM_Internal_Trigger_Selection - * @{ - */ - -#define TIM_TS_ITR0 ((uint16_t)0x0000) -#define TIM_TS_ITR1 ((uint16_t)0x0010) -#define TIM_TS_ITR2 ((uint16_t)0x0020) -#define TIM_TS_ITR3 ((uint16_t)0x0030) -#define TIM_TS_TI1F_ED ((uint16_t)0x0040) -#define TIM_TS_TI1FP1 ((uint16_t)0x0050) -#define TIM_TS_TI2FP2 ((uint16_t)0x0060) -#define TIM_TS_ETRF ((uint16_t)0x0070) -#define IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ - ((SELECTION) == TIM_TS_ITR1) || \ - ((SELECTION) == TIM_TS_ITR2) || \ - ((SELECTION) == TIM_TS_ITR3) || \ - ((SELECTION) == TIM_TS_TI1F_ED) || \ - ((SELECTION) == TIM_TS_TI1FP1) || \ - ((SELECTION) == TIM_TS_TI2FP2) || \ - ((SELECTION) == TIM_TS_ETRF)) -#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ - ((SELECTION) == TIM_TS_ITR1) || \ - ((SELECTION) == TIM_TS_ITR2) || \ - ((SELECTION) == TIM_TS_ITR3)) -/** - * @} - */ - -/** @defgroup TIM_TIx_External_Clock_Source - * @{ - */ - -#define TIM_TIxExternalCLK1Source_TI1 ((uint16_t)0x0050) -#define TIM_TIxExternalCLK1Source_TI2 ((uint16_t)0x0060) -#define TIM_TIxExternalCLK1Source_TI1ED ((uint16_t)0x0040) -#define IS_TIM_TIXCLK_SOURCE(SOURCE) (((SOURCE) == TIM_TIxExternalCLK1Source_TI1) || \ - ((SOURCE) == TIM_TIxExternalCLK1Source_TI2) || \ - ((SOURCE) == TIM_TIxExternalCLK1Source_TI1ED)) -/** - * @} - */ - -/** @defgroup TIM_External_Trigger_Polarity - * @{ - */ -#define TIM_ExtTRGPolarity_Inverted ((uint16_t)0x8000) -#define TIM_ExtTRGPolarity_NonInverted ((uint16_t)0x0000) -#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \ - ((POLARITY) == TIM_ExtTRGPolarity_NonInverted)) -/** - * @} - */ - -/** @defgroup TIM_Prescaler_Reload_Mode - * @{ - */ - -#define TIM_PSCReloadMode_Update ((uint16_t)0x0000) -#define TIM_PSCReloadMode_Immediate ((uint16_t)0x0001) -#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \ - ((RELOAD) == TIM_PSCReloadMode_Immediate)) -/** - * @} - */ - -/** @defgroup TIM_Forced_Action - * @{ - */ - -#define TIM_ForcedAction_Active ((uint16_t)0x0050) -#define TIM_ForcedAction_InActive ((uint16_t)0x0040) -#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \ - ((ACTION) == TIM_ForcedAction_InActive)) -/** - * @} - */ - -/** @defgroup TIM_Encoder_Mode - * @{ - */ - -#define TIM_EncoderMode_TI1 ((uint16_t)0x0001) -#define TIM_EncoderMode_TI2 ((uint16_t)0x0002) -#define TIM_EncoderMode_TI12 ((uint16_t)0x0003) -#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \ - ((MODE) == TIM_EncoderMode_TI2) || \ - ((MODE) == TIM_EncoderMode_TI12)) -/** - * @} - */ - - -/** @defgroup TIM_Event_Source - * @{ - */ - -#define TIM_EventSource_Update ((uint16_t)0x0001) -#define TIM_EventSource_CC1 ((uint16_t)0x0002) -#define TIM_EventSource_CC2 ((uint16_t)0x0004) -#define TIM_EventSource_CC3 ((uint16_t)0x0008) -#define TIM_EventSource_CC4 ((uint16_t)0x0010) -#define TIM_EventSource_COM ((uint16_t)0x0020) -#define TIM_EventSource_Trigger ((uint16_t)0x0040) -#define TIM_EventSource_Break ((uint16_t)0x0080) -#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0xFF00) == 0x0000) && ((SOURCE) != 0x0000)) - -/** - * @} - */ - -/** @defgroup TIM_Update_Source - * @{ - */ - -#define TIM_UpdateSource_Global ((uint16_t)0x0000) /*!< Source of update is the counter overflow/underflow - or the setting of UG bit, or an update generation - through the slave mode controller. */ -#define TIM_UpdateSource_Regular ((uint16_t)0x0001) /*!< Source of update is counter overflow/underflow. */ -#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \ - ((SOURCE) == TIM_UpdateSource_Regular)) -/** - * @} - */ - -/** @defgroup TIM_Ouput_Compare_Preload_State - * @{ - */ - -#define TIM_OCPreload_Enable ((uint16_t)0x0008) -#define TIM_OCPreload_Disable ((uint16_t)0x0000) -#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \ - ((STATE) == TIM_OCPreload_Disable)) -/** - * @} - */ - -/** @defgroup TIM_Ouput_Compare_Fast_State - * @{ - */ - -#define TIM_OCFast_Enable ((uint16_t)0x0004) -#define TIM_OCFast_Disable ((uint16_t)0x0000) -#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \ - ((STATE) == TIM_OCFast_Disable)) - -/** - * @} - */ - -/** @defgroup TIM_Ouput_Compare_Clear_State - * @{ - */ - -#define TIM_OCClear_Enable ((uint16_t)0x0080) -#define TIM_OCClear_Disable ((uint16_t)0x0000) -#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \ - ((STATE) == TIM_OCClear_Disable)) -/** - * @} - */ - -/** @defgroup TIM_Trigger_Output_Source - * @{ - */ - -#define TIM_TRGOSource_Reset ((uint16_t)0x0000) -#define TIM_TRGOSource_Enable ((uint16_t)0x0010) -#define TIM_TRGOSource_Update ((uint16_t)0x0020) -#define TIM_TRGOSource_OC1 ((uint16_t)0x0030) -#define TIM_TRGOSource_OC1Ref ((uint16_t)0x0040) -#define TIM_TRGOSource_OC2Ref ((uint16_t)0x0050) -#define TIM_TRGOSource_OC3Ref ((uint16_t)0x0060) -#define TIM_TRGOSource_OC4Ref ((uint16_t)0x0070) -#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \ - ((SOURCE) == TIM_TRGOSource_Enable) || \ - ((SOURCE) == TIM_TRGOSource_Update) || \ - ((SOURCE) == TIM_TRGOSource_OC1) || \ - ((SOURCE) == TIM_TRGOSource_OC1Ref) || \ - ((SOURCE) == TIM_TRGOSource_OC2Ref) || \ - ((SOURCE) == TIM_TRGOSource_OC3Ref) || \ - ((SOURCE) == TIM_TRGOSource_OC4Ref)) -/** - * @} - */ - -/** @defgroup TIM_Slave_Mode - * @{ - */ - -#define TIM_SlaveMode_Reset ((uint16_t)0x0004) -#define TIM_SlaveMode_Gated ((uint16_t)0x0005) -#define TIM_SlaveMode_Trigger ((uint16_t)0x0006) -#define TIM_SlaveMode_External1 ((uint16_t)0x0007) -#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \ - ((MODE) == TIM_SlaveMode_Gated) || \ - ((MODE) == TIM_SlaveMode_Trigger) || \ - ((MODE) == TIM_SlaveMode_External1)) -/** - * @} - */ - -/** @defgroup TIM_Master_Slave_Mode - * @{ - */ - -#define TIM_MasterSlaveMode_Enable ((uint16_t)0x0080) -#define TIM_MasterSlaveMode_Disable ((uint16_t)0x0000) -#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \ - ((STATE) == TIM_MasterSlaveMode_Disable)) -/** - * @} - */ - -/** @defgroup TIM_Flags - * @{ - */ - -#define TIM_FLAG_Update ((uint16_t)0x0001) -#define TIM_FLAG_CC1 ((uint16_t)0x0002) -#define TIM_FLAG_CC2 ((uint16_t)0x0004) -#define TIM_FLAG_CC3 ((uint16_t)0x0008) -#define TIM_FLAG_CC4 ((uint16_t)0x0010) -#define TIM_FLAG_COM ((uint16_t)0x0020) -#define TIM_FLAG_Trigger ((uint16_t)0x0040) -#define TIM_FLAG_Break ((uint16_t)0x0080) -#define TIM_FLAG_CC1OF ((uint16_t)0x0200) -#define TIM_FLAG_CC2OF ((uint16_t)0x0400) -#define TIM_FLAG_CC3OF ((uint16_t)0x0800) -#define TIM_FLAG_CC4OF ((uint16_t)0x1000) -#define IS_TIM_GET_FLAG(FLAG) (((FLAG) == TIM_FLAG_Update) || \ - ((FLAG) == TIM_FLAG_CC1) || \ - ((FLAG) == TIM_FLAG_CC2) || \ - ((FLAG) == TIM_FLAG_CC3) || \ - ((FLAG) == TIM_FLAG_CC4) || \ - ((FLAG) == TIM_FLAG_COM) || \ - ((FLAG) == TIM_FLAG_Trigger) || \ - ((FLAG) == TIM_FLAG_Break) || \ - ((FLAG) == TIM_FLAG_CC1OF) || \ - ((FLAG) == TIM_FLAG_CC2OF) || \ - ((FLAG) == TIM_FLAG_CC3OF) || \ - ((FLAG) == TIM_FLAG_CC4OF)) - - -#define IS_TIM_CLEAR_FLAG(TIM_FLAG) ((((TIM_FLAG) & (uint16_t)0xE100) == 0x0000) && ((TIM_FLAG) != 0x0000)) -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Filer_Value - * @{ - */ - -#define IS_TIM_IC_FILTER(ICFILTER) ((ICFILTER) <= 0xF) -/** - * @} - */ - -/** @defgroup TIM_External_Trigger_Filter - * @{ - */ - -#define IS_TIM_EXT_FILTER(EXTFILTER) ((EXTFILTER) <= 0xF) -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup TIM_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions - * @{ - */ - -void TIM_DeInit(TIM_TypeDef* TIMx); -void TIM_TimeBaseInit(TIM_TypeDef* TIMx, const TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); -void TIM_OC1Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_OC2Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_OC3Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_OC4Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_ICInit(TIM_TypeDef* TIMx, const TIM_ICInitTypeDef* TIM_ICInitStruct); -void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); -void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct); -void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); -void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct); -void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct); -void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState); -void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState); -void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState); -void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource); -void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength); -void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState); -void TIM_InternalClockConfig(TIM_TypeDef* TIMx); -void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); -void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, - uint16_t TIM_ICPolarity, uint16_t ICFilter); -void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, - uint16_t ExtTRGFilter); -void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, - uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter); -void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, - uint16_t ExtTRGFilter); -void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode); -void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode); -void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); -void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, - uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity); -void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); -void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); -void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); -void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); -void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState); -void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState); -void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState); -void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState); -void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); -void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); -void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); -void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); -void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); -void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); -void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); -void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); -void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); -void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); -void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); -void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); -void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); -void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); -void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); -void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); -void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); -void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); -void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); -void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx); -void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN); -void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode); -void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState); -void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource); -void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState); -void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode); -void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource); -void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); -void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode); -void TIM_SetCounter(TIM_TypeDef* TIMx, uint16_t Counter); -void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint16_t Autoreload); -void TIM_SetCompare1(TIM_TypeDef* TIMx, uint16_t Compare1); -void TIM_SetCompare2(TIM_TypeDef* TIMx, uint16_t Compare2); -void TIM_SetCompare3(TIM_TypeDef* TIMx, uint16_t Compare3); -void TIM_SetCompare4(TIM_TypeDef* TIMx, uint16_t Compare4); -void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); -void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); -void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); -void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); -void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD); -uint16_t TIM_GetCapture1(TIM_TypeDef* TIMx); -uint16_t TIM_GetCapture2(TIM_TypeDef* TIMx); -uint16_t TIM_GetCapture3(TIM_TypeDef* TIMx); -uint16_t TIM_GetCapture4(TIM_TypeDef* TIMx); -uint16_t TIM_GetCounter(TIM_TypeDef* TIMx); -uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx); -FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); -void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); -ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT); -void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT); - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F10x_TIM_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_tim.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the TIM firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_TIM_H +#define __STM32F10x_TIM_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup TIM + * @{ + */ + +/** @defgroup TIM_Exported_Types + * @{ + */ + +/** + * @brief TIM Time Base Init structure definition + * @note This sturcture is used with all TIMx except for TIM6 and TIM7. + */ + +typedef struct +{ + uint16_t TIM_Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. + This parameter can be a number between 0x0000 and 0xFFFF */ + + uint16_t TIM_CounterMode; /*!< Specifies the counter mode. + This parameter can be a value of @ref TIM_Counter_Mode */ + + uint16_t TIM_Period; /*!< Specifies the period value to be loaded into the active + Auto-Reload Register at the next update event. + This parameter must be a number between 0x0000 and 0xFFFF. */ + + uint16_t TIM_ClockDivision; /*!< Specifies the clock division. + This parameter can be a value of @ref TIM_Clock_Division_CKD */ + + uint8_t TIM_RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter + reaches zero, an update event is generated and counting restarts + from the RCR value (N). + This means in PWM mode that (N+1) corresponds to: + - the number of PWM periods in edge-aligned mode + - the number of half PWM period in center-aligned mode + This parameter must be a number between 0x00 and 0xFF. + @note This parameter is valid only for TIM1 and TIM8. */ +} TIM_TimeBaseInitTypeDef; + +/** + * @brief TIM Output Compare Init structure definition + */ + +typedef struct +{ + uint16_t TIM_OCMode; /*!< Specifies the TIM mode. + This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ + + uint16_t TIM_OutputState; /*!< Specifies the TIM Output Compare state. + This parameter can be a value of @ref TIM_Output_Compare_state */ + + uint16_t TIM_OutputNState; /*!< Specifies the TIM complementary Output Compare state. + This parameter can be a value of @ref TIM_Output_Compare_N_state + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. + This parameter can be a number between 0x0000 and 0xFFFF */ + + uint16_t TIM_OCPolarity; /*!< Specifies the output polarity. + This parameter can be a value of @ref TIM_Output_Compare_Polarity */ + + uint16_t TIM_OCNPolarity; /*!< Specifies the complementary output polarity. + This parameter can be a value of @ref TIM_Output_Compare_N_Polarity + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_Idle_State + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State + @note This parameter is valid only for TIM1 and TIM8. */ +} TIM_OCInitTypeDef; + +/** + * @brief TIM Input Capture Init structure definition + */ + +typedef struct +{ + + uint16_t TIM_Channel; /*!< Specifies the TIM channel. + This parameter can be a value of @ref TIM_Channel */ + + uint16_t TIM_ICPolarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Input_Capture_Polarity */ + + uint16_t TIM_ICSelection; /*!< Specifies the input. + This parameter can be a value of @ref TIM_Input_Capture_Selection */ + + uint16_t TIM_ICPrescaler; /*!< Specifies the Input Capture Prescaler. + This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ + + uint16_t TIM_ICFilter; /*!< Specifies the input capture filter. + This parameter can be a number between 0x0 and 0xF */ +} TIM_ICInitTypeDef; + +/** + * @brief BDTR structure definition + * @note This sturcture is used only with TIM1 and TIM8. + */ + +typedef struct +{ + + uint16_t TIM_OSSRState; /*!< Specifies the Off-State selection used in Run mode. + This parameter can be a value of @ref OSSR_Off_State_Selection_for_Run_mode_state */ + + uint16_t TIM_OSSIState; /*!< Specifies the Off-State used in Idle state. + This parameter can be a value of @ref OSSI_Off_State_Selection_for_Idle_mode_state */ + + uint16_t TIM_LOCKLevel; /*!< Specifies the LOCK level parameters. + This parameter can be a value of @ref Lock_level */ + + uint16_t TIM_DeadTime; /*!< Specifies the delay time between the switching-off and the + switching-on of the outputs. + This parameter can be a number between 0x00 and 0xFF */ + + uint16_t TIM_Break; /*!< Specifies whether the TIM Break input is enabled or not. + This parameter can be a value of @ref Break_Input_enable_disable */ + + uint16_t TIM_BreakPolarity; /*!< Specifies the TIM Break Input pin polarity. + This parameter can be a value of @ref Break_Polarity */ + + uint16_t TIM_AutomaticOutput; /*!< Specifies whether the TIM Automatic Output feature is enabled or not. + This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */ +} TIM_BDTRInitTypeDef; + +/** @defgroup TIM_Exported_constants + * @{ + */ + +#define IS_TIM_ALL_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM10)|| \ + ((PERIPH) == TIM11)|| \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM13)|| \ + ((PERIPH) == TIM14)|| \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST1: TIM 1 and 8 */ +#define IS_TIM_LIST1_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM8)) + +/* LIST2: TIM 1, 8, 15 16 and 17 */ +#define IS_TIM_LIST2_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST3: TIM 1, 2, 3, 4, 5 and 8 */ +#define IS_TIM_LIST3_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8)) + +/* LIST4: TIM 1, 2, 3, 4, 5, 8, 15, 16 and 17 */ +#define IS_TIM_LIST4_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST5: TIM 1, 2, 3, 4, 5, 8 and 15 */ +#define IS_TIM_LIST5_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)) + +/* LIST6: TIM 1, 2, 3, 4, 5, 8, 9, 12 and 15 */ +#define IS_TIM_LIST6_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM15)) + +/* LIST7: TIM 1, 2, 3, 4, 5, 6, 7, 8, 9, 12 and 15 */ +#define IS_TIM_LIST7_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM15)) + +/* LIST8: TIM 1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13, 14, 15, 16 and 17 */ +#define IS_TIM_LIST8_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM10)|| \ + ((PERIPH) == TIM11)|| \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM13)|| \ + ((PERIPH) == TIM14)|| \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST9: TIM 1, 2, 3, 4, 5, 6, 7, 8, 15, 16, and 17 */ +#define IS_TIM_LIST9_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_and_PWM_modes + * @{ + */ + +#define TIM_OCMode_Timing ((uint16_t)0x0000) +#define TIM_OCMode_Active ((uint16_t)0x0010) +#define TIM_OCMode_Inactive ((uint16_t)0x0020) +#define TIM_OCMode_Toggle ((uint16_t)0x0030) +#define TIM_OCMode_PWM1 ((uint16_t)0x0060) +#define TIM_OCMode_PWM2 ((uint16_t)0x0070) +#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \ + ((MODE) == TIM_OCMode_Active) || \ + ((MODE) == TIM_OCMode_Inactive) || \ + ((MODE) == TIM_OCMode_Toggle)|| \ + ((MODE) == TIM_OCMode_PWM1) || \ + ((MODE) == TIM_OCMode_PWM2)) +#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \ + ((MODE) == TIM_OCMode_Active) || \ + ((MODE) == TIM_OCMode_Inactive) || \ + ((MODE) == TIM_OCMode_Toggle)|| \ + ((MODE) == TIM_OCMode_PWM1) || \ + ((MODE) == TIM_OCMode_PWM2) || \ + ((MODE) == TIM_ForcedAction_Active) || \ + ((MODE) == TIM_ForcedAction_InActive)) +/** + * @} + */ + +/** @defgroup TIM_One_Pulse_Mode + * @{ + */ + +#define TIM_OPMode_Single ((uint16_t)0x0008) +#define TIM_OPMode_Repetitive ((uint16_t)0x0000) +#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \ + ((MODE) == TIM_OPMode_Repetitive)) +/** + * @} + */ + +/** @defgroup TIM_Channel + * @{ + */ + +#define TIM_Channel_1 ((uint16_t)0x0000) +#define TIM_Channel_2 ((uint16_t)0x0004) +#define TIM_Channel_3 ((uint16_t)0x0008) +#define TIM_Channel_4 ((uint16_t)0x000C) +#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2) || \ + ((CHANNEL) == TIM_Channel_3) || \ + ((CHANNEL) == TIM_Channel_4)) +#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2)) +#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2) || \ + ((CHANNEL) == TIM_Channel_3)) +/** + * @} + */ + +/** @defgroup TIM_Clock_Division_CKD + * @{ + */ + +#define TIM_CKD_DIV1 ((uint16_t)0x0000) +#define TIM_CKD_DIV2 ((uint16_t)0x0100) +#define TIM_CKD_DIV4 ((uint16_t)0x0200) +#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \ + ((DIV) == TIM_CKD_DIV2) || \ + ((DIV) == TIM_CKD_DIV4)) +/** + * @} + */ + +/** @defgroup TIM_Counter_Mode + * @{ + */ + +#define TIM_CounterMode_Up ((uint16_t)0x0000) +#define TIM_CounterMode_Down ((uint16_t)0x0010) +#define TIM_CounterMode_CenterAligned1 ((uint16_t)0x0020) +#define TIM_CounterMode_CenterAligned2 ((uint16_t)0x0040) +#define TIM_CounterMode_CenterAligned3 ((uint16_t)0x0060) +#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) || \ + ((MODE) == TIM_CounterMode_Down) || \ + ((MODE) == TIM_CounterMode_CenterAligned1) || \ + ((MODE) == TIM_CounterMode_CenterAligned2) || \ + ((MODE) == TIM_CounterMode_CenterAligned3)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Polarity + * @{ + */ + +#define TIM_OCPolarity_High ((uint16_t)0x0000) +#define TIM_OCPolarity_Low ((uint16_t)0x0002) +#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \ + ((POLARITY) == TIM_OCPolarity_Low)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Polarity + * @{ + */ + +#define TIM_OCNPolarity_High ((uint16_t)0x0000) +#define TIM_OCNPolarity_Low ((uint16_t)0x0008) +#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \ + ((POLARITY) == TIM_OCNPolarity_Low)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_state + * @{ + */ + +#define TIM_OutputState_Disable ((uint16_t)0x0000) +#define TIM_OutputState_Enable ((uint16_t)0x0001) +#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \ + ((STATE) == TIM_OutputState_Enable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_state + * @{ + */ + +#define TIM_OutputNState_Disable ((uint16_t)0x0000) +#define TIM_OutputNState_Enable ((uint16_t)0x0004) +#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \ + ((STATE) == TIM_OutputNState_Enable)) +/** + * @} + */ + +/** @defgroup TIM_Capture_Compare_state + * @{ + */ + +#define TIM_CCx_Enable ((uint16_t)0x0001) +#define TIM_CCx_Disable ((uint16_t)0x0000) +#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \ + ((CCX) == TIM_CCx_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Capture_Compare_N_state + * @{ + */ + +#define TIM_CCxN_Enable ((uint16_t)0x0004) +#define TIM_CCxN_Disable ((uint16_t)0x0000) +#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \ + ((CCXN) == TIM_CCxN_Disable)) +/** + * @} + */ + +/** @defgroup Break_Input_enable_disable + * @{ + */ + +#define TIM_Break_Enable ((uint16_t)0x1000) +#define TIM_Break_Disable ((uint16_t)0x0000) +#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \ + ((STATE) == TIM_Break_Disable)) +/** + * @} + */ + +/** @defgroup Break_Polarity + * @{ + */ + +#define TIM_BreakPolarity_Low ((uint16_t)0x0000) +#define TIM_BreakPolarity_High ((uint16_t)0x2000) +#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \ + ((POLARITY) == TIM_BreakPolarity_High)) +/** + * @} + */ + +/** @defgroup TIM_AOE_Bit_Set_Reset + * @{ + */ + +#define TIM_AutomaticOutput_Enable ((uint16_t)0x4000) +#define TIM_AutomaticOutput_Disable ((uint16_t)0x0000) +#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \ + ((STATE) == TIM_AutomaticOutput_Disable)) +/** + * @} + */ + +/** @defgroup Lock_level + * @{ + */ + +#define TIM_LOCKLevel_OFF ((uint16_t)0x0000) +#define TIM_LOCKLevel_1 ((uint16_t)0x0100) +#define TIM_LOCKLevel_2 ((uint16_t)0x0200) +#define TIM_LOCKLevel_3 ((uint16_t)0x0300) +#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \ + ((LEVEL) == TIM_LOCKLevel_1) || \ + ((LEVEL) == TIM_LOCKLevel_2) || \ + ((LEVEL) == TIM_LOCKLevel_3)) +/** + * @} + */ + +/** @defgroup OSSI_Off_State_Selection_for_Idle_mode_state + * @{ + */ + +#define TIM_OSSIState_Enable ((uint16_t)0x0400) +#define TIM_OSSIState_Disable ((uint16_t)0x0000) +#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \ + ((STATE) == TIM_OSSIState_Disable)) +/** + * @} + */ + +/** @defgroup OSSR_Off_State_Selection_for_Run_mode_state + * @{ + */ + +#define TIM_OSSRState_Enable ((uint16_t)0x0800) +#define TIM_OSSRState_Disable ((uint16_t)0x0000) +#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \ + ((STATE) == TIM_OSSRState_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Idle_State + * @{ + */ + +#define TIM_OCIdleState_Set ((uint16_t)0x0100) +#define TIM_OCIdleState_Reset ((uint16_t)0x0000) +#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \ + ((STATE) == TIM_OCIdleState_Reset)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Idle_State + * @{ + */ + +#define TIM_OCNIdleState_Set ((uint16_t)0x0200) +#define TIM_OCNIdleState_Reset ((uint16_t)0x0000) +#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \ + ((STATE) == TIM_OCNIdleState_Reset)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Polarity + * @{ + */ + +#define TIM_ICPolarity_Rising ((uint16_t)0x0000) +#define TIM_ICPolarity_Falling ((uint16_t)0x0002) +#define TIM_ICPolarity_BothEdge ((uint16_t)0x000A) +#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \ + ((POLARITY) == TIM_ICPolarity_Falling)) +#define IS_TIM_IC_POLARITY_LITE(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \ + ((POLARITY) == TIM_ICPolarity_Falling)|| \ + ((POLARITY) == TIM_ICPolarity_BothEdge)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Selection + * @{ + */ + +#define TIM_ICSelection_DirectTI ((uint16_t)0x0001) /*!< TIM Input 1, 2, 3 or 4 is selected to be + connected to IC1, IC2, IC3 or IC4, respectively */ +#define TIM_ICSelection_IndirectTI ((uint16_t)0x0002) /*!< TIM Input 1, 2, 3 or 4 is selected to be + connected to IC2, IC1, IC4 or IC3, respectively. */ +#define TIM_ICSelection_TRC ((uint16_t)0x0003) /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC. */ +#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \ + ((SELECTION) == TIM_ICSelection_IndirectTI) || \ + ((SELECTION) == TIM_ICSelection_TRC)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Prescaler + * @{ + */ + +#define TIM_ICPSC_DIV1 ((uint16_t)0x0000) /*!< Capture performed each time an edge is detected on the capture input. */ +#define TIM_ICPSC_DIV2 ((uint16_t)0x0004) /*!< Capture performed once every 2 events. */ +#define TIM_ICPSC_DIV4 ((uint16_t)0x0008) /*!< Capture performed once every 4 events. */ +#define TIM_ICPSC_DIV8 ((uint16_t)0x000C) /*!< Capture performed once every 8 events. */ +#define IS_TIM_IC_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ICPSC_DIV1) || \ + ((PRESCALER) == TIM_ICPSC_DIV2) || \ + ((PRESCALER) == TIM_ICPSC_DIV4) || \ + ((PRESCALER) == TIM_ICPSC_DIV8)) +/** + * @} + */ + +/** @defgroup TIM_interrupt_sources + * @{ + */ + +#define TIM_IT_Update ((uint16_t)0x0001) +#define TIM_IT_CC1 ((uint16_t)0x0002) +#define TIM_IT_CC2 ((uint16_t)0x0004) +#define TIM_IT_CC3 ((uint16_t)0x0008) +#define TIM_IT_CC4 ((uint16_t)0x0010) +#define TIM_IT_COM ((uint16_t)0x0020) +#define TIM_IT_Trigger ((uint16_t)0x0040) +#define TIM_IT_Break ((uint16_t)0x0080) +#define IS_TIM_IT(IT) ((((IT) & (uint16_t)0xFF00) == 0x0000) && ((IT) != 0x0000)) + +#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \ + ((IT) == TIM_IT_CC1) || \ + ((IT) == TIM_IT_CC2) || \ + ((IT) == TIM_IT_CC3) || \ + ((IT) == TIM_IT_CC4) || \ + ((IT) == TIM_IT_COM) || \ + ((IT) == TIM_IT_Trigger) || \ + ((IT) == TIM_IT_Break)) +/** + * @} + */ + +/** @defgroup TIM_DMA_Base_address + * @{ + */ + +#define TIM_DMABase_CR1 ((uint16_t)0x0000) +#define TIM_DMABase_CR2 ((uint16_t)0x0001) +#define TIM_DMABase_SMCR ((uint16_t)0x0002) +#define TIM_DMABase_DIER ((uint16_t)0x0003) +#define TIM_DMABase_SR ((uint16_t)0x0004) +#define TIM_DMABase_EGR ((uint16_t)0x0005) +#define TIM_DMABase_CCMR1 ((uint16_t)0x0006) +#define TIM_DMABase_CCMR2 ((uint16_t)0x0007) +#define TIM_DMABase_CCER ((uint16_t)0x0008) +#define TIM_DMABase_CNT ((uint16_t)0x0009) +#define TIM_DMABase_PSC ((uint16_t)0x000A) +#define TIM_DMABase_ARR ((uint16_t)0x000B) +#define TIM_DMABase_RCR ((uint16_t)0x000C) +#define TIM_DMABase_CCR1 ((uint16_t)0x000D) +#define TIM_DMABase_CCR2 ((uint16_t)0x000E) +#define TIM_DMABase_CCR3 ((uint16_t)0x000F) +#define TIM_DMABase_CCR4 ((uint16_t)0x0010) +#define TIM_DMABase_BDTR ((uint16_t)0x0011) +#define TIM_DMABase_DCR ((uint16_t)0x0012) +#define IS_TIM_DMA_BASE(BASE) (((BASE) == TIM_DMABase_CR1) || \ + ((BASE) == TIM_DMABase_CR2) || \ + ((BASE) == TIM_DMABase_SMCR) || \ + ((BASE) == TIM_DMABase_DIER) || \ + ((BASE) == TIM_DMABase_SR) || \ + ((BASE) == TIM_DMABase_EGR) || \ + ((BASE) == TIM_DMABase_CCMR1) || \ + ((BASE) == TIM_DMABase_CCMR2) || \ + ((BASE) == TIM_DMABase_CCER) || \ + ((BASE) == TIM_DMABase_CNT) || \ + ((BASE) == TIM_DMABase_PSC) || \ + ((BASE) == TIM_DMABase_ARR) || \ + ((BASE) == TIM_DMABase_RCR) || \ + ((BASE) == TIM_DMABase_CCR1) || \ + ((BASE) == TIM_DMABase_CCR2) || \ + ((BASE) == TIM_DMABase_CCR3) || \ + ((BASE) == TIM_DMABase_CCR4) || \ + ((BASE) == TIM_DMABase_BDTR) || \ + ((BASE) == TIM_DMABase_DCR)) +/** + * @} + */ + +/** @defgroup TIM_DMA_Burst_Length + * @{ + */ + +#define TIM_DMABurstLength_1Byte ((uint16_t)0x0000) +#define TIM_DMABurstLength_2Bytes ((uint16_t)0x0100) +#define TIM_DMABurstLength_3Bytes ((uint16_t)0x0200) +#define TIM_DMABurstLength_4Bytes ((uint16_t)0x0300) +#define TIM_DMABurstLength_5Bytes ((uint16_t)0x0400) +#define TIM_DMABurstLength_6Bytes ((uint16_t)0x0500) +#define TIM_DMABurstLength_7Bytes ((uint16_t)0x0600) +#define TIM_DMABurstLength_8Bytes ((uint16_t)0x0700) +#define TIM_DMABurstLength_9Bytes ((uint16_t)0x0800) +#define TIM_DMABurstLength_10Bytes ((uint16_t)0x0900) +#define TIM_DMABurstLength_11Bytes ((uint16_t)0x0A00) +#define TIM_DMABurstLength_12Bytes ((uint16_t)0x0B00) +#define TIM_DMABurstLength_13Bytes ((uint16_t)0x0C00) +#define TIM_DMABurstLength_14Bytes ((uint16_t)0x0D00) +#define TIM_DMABurstLength_15Bytes ((uint16_t)0x0E00) +#define TIM_DMABurstLength_16Bytes ((uint16_t)0x0F00) +#define TIM_DMABurstLength_17Bytes ((uint16_t)0x1000) +#define TIM_DMABurstLength_18Bytes ((uint16_t)0x1100) +#define IS_TIM_DMA_LENGTH(LENGTH) (((LENGTH) == TIM_DMABurstLength_1Byte) || \ + ((LENGTH) == TIM_DMABurstLength_2Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_3Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_4Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_5Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_6Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_7Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_8Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_9Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_10Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_11Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_12Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_13Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_14Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_15Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_16Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_17Bytes) || \ + ((LENGTH) == TIM_DMABurstLength_18Bytes)) +/** + * @} + */ + +/** @defgroup TIM_DMA_sources + * @{ + */ + +#define TIM_DMA_Update ((uint16_t)0x0100) +#define TIM_DMA_CC1 ((uint16_t)0x0200) +#define TIM_DMA_CC2 ((uint16_t)0x0400) +#define TIM_DMA_CC3 ((uint16_t)0x0800) +#define TIM_DMA_CC4 ((uint16_t)0x1000) +#define TIM_DMA_COM ((uint16_t)0x2000) +#define TIM_DMA_Trigger ((uint16_t)0x4000) +#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0x80FF) == 0x0000) && ((SOURCE) != 0x0000)) + +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Prescaler + * @{ + */ + +#define TIM_ExtTRGPSC_OFF ((uint16_t)0x0000) +#define TIM_ExtTRGPSC_DIV2 ((uint16_t)0x1000) +#define TIM_ExtTRGPSC_DIV4 ((uint16_t)0x2000) +#define TIM_ExtTRGPSC_DIV8 ((uint16_t)0x3000) +#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV8)) +/** + * @} + */ + +/** @defgroup TIM_Internal_Trigger_Selection + * @{ + */ + +#define TIM_TS_ITR0 ((uint16_t)0x0000) +#define TIM_TS_ITR1 ((uint16_t)0x0010) +#define TIM_TS_ITR2 ((uint16_t)0x0020) +#define TIM_TS_ITR3 ((uint16_t)0x0030) +#define TIM_TS_TI1F_ED ((uint16_t)0x0040) +#define TIM_TS_TI1FP1 ((uint16_t)0x0050) +#define TIM_TS_TI2FP2 ((uint16_t)0x0060) +#define TIM_TS_ETRF ((uint16_t)0x0070) +#define IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ + ((SELECTION) == TIM_TS_ITR1) || \ + ((SELECTION) == TIM_TS_ITR2) || \ + ((SELECTION) == TIM_TS_ITR3) || \ + ((SELECTION) == TIM_TS_TI1F_ED) || \ + ((SELECTION) == TIM_TS_TI1FP1) || \ + ((SELECTION) == TIM_TS_TI2FP2) || \ + ((SELECTION) == TIM_TS_ETRF)) +#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ + ((SELECTION) == TIM_TS_ITR1) || \ + ((SELECTION) == TIM_TS_ITR2) || \ + ((SELECTION) == TIM_TS_ITR3)) +/** + * @} + */ + +/** @defgroup TIM_TIx_External_Clock_Source + * @{ + */ + +#define TIM_TIxExternalCLK1Source_TI1 ((uint16_t)0x0050) +#define TIM_TIxExternalCLK1Source_TI2 ((uint16_t)0x0060) +#define TIM_TIxExternalCLK1Source_TI1ED ((uint16_t)0x0040) +#define IS_TIM_TIXCLK_SOURCE(SOURCE) (((SOURCE) == TIM_TIxExternalCLK1Source_TI1) || \ + ((SOURCE) == TIM_TIxExternalCLK1Source_TI2) || \ + ((SOURCE) == TIM_TIxExternalCLK1Source_TI1ED)) +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Polarity + * @{ + */ +#define TIM_ExtTRGPolarity_Inverted ((uint16_t)0x8000) +#define TIM_ExtTRGPolarity_NonInverted ((uint16_t)0x0000) +#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \ + ((POLARITY) == TIM_ExtTRGPolarity_NonInverted)) +/** + * @} + */ + +/** @defgroup TIM_Prescaler_Reload_Mode + * @{ + */ + +#define TIM_PSCReloadMode_Update ((uint16_t)0x0000) +#define TIM_PSCReloadMode_Immediate ((uint16_t)0x0001) +#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \ + ((RELOAD) == TIM_PSCReloadMode_Immediate)) +/** + * @} + */ + +/** @defgroup TIM_Forced_Action + * @{ + */ + +#define TIM_ForcedAction_Active ((uint16_t)0x0050) +#define TIM_ForcedAction_InActive ((uint16_t)0x0040) +#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \ + ((ACTION) == TIM_ForcedAction_InActive)) +/** + * @} + */ + +/** @defgroup TIM_Encoder_Mode + * @{ + */ + +#define TIM_EncoderMode_TI1 ((uint16_t)0x0001) +#define TIM_EncoderMode_TI2 ((uint16_t)0x0002) +#define TIM_EncoderMode_TI12 ((uint16_t)0x0003) +#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \ + ((MODE) == TIM_EncoderMode_TI2) || \ + ((MODE) == TIM_EncoderMode_TI12)) +/** + * @} + */ + + +/** @defgroup TIM_Event_Source + * @{ + */ + +#define TIM_EventSource_Update ((uint16_t)0x0001) +#define TIM_EventSource_CC1 ((uint16_t)0x0002) +#define TIM_EventSource_CC2 ((uint16_t)0x0004) +#define TIM_EventSource_CC3 ((uint16_t)0x0008) +#define TIM_EventSource_CC4 ((uint16_t)0x0010) +#define TIM_EventSource_COM ((uint16_t)0x0020) +#define TIM_EventSource_Trigger ((uint16_t)0x0040) +#define TIM_EventSource_Break ((uint16_t)0x0080) +#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0xFF00) == 0x0000) && ((SOURCE) != 0x0000)) + +/** + * @} + */ + +/** @defgroup TIM_Update_Source + * @{ + */ + +#define TIM_UpdateSource_Global ((uint16_t)0x0000) /*!< Source of update is the counter overflow/underflow + or the setting of UG bit, or an update generation + through the slave mode controller. */ +#define TIM_UpdateSource_Regular ((uint16_t)0x0001) /*!< Source of update is counter overflow/underflow. */ +#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \ + ((SOURCE) == TIM_UpdateSource_Regular)) +/** + * @} + */ + +/** @defgroup TIM_Ouput_Compare_Preload_State + * @{ + */ + +#define TIM_OCPreload_Enable ((uint16_t)0x0008) +#define TIM_OCPreload_Disable ((uint16_t)0x0000) +#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \ + ((STATE) == TIM_OCPreload_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Ouput_Compare_Fast_State + * @{ + */ + +#define TIM_OCFast_Enable ((uint16_t)0x0004) +#define TIM_OCFast_Disable ((uint16_t)0x0000) +#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \ + ((STATE) == TIM_OCFast_Disable)) + +/** + * @} + */ + +/** @defgroup TIM_Ouput_Compare_Clear_State + * @{ + */ + +#define TIM_OCClear_Enable ((uint16_t)0x0080) +#define TIM_OCClear_Disable ((uint16_t)0x0000) +#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \ + ((STATE) == TIM_OCClear_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Trigger_Output_Source + * @{ + */ + +#define TIM_TRGOSource_Reset ((uint16_t)0x0000) +#define TIM_TRGOSource_Enable ((uint16_t)0x0010) +#define TIM_TRGOSource_Update ((uint16_t)0x0020) +#define TIM_TRGOSource_OC1 ((uint16_t)0x0030) +#define TIM_TRGOSource_OC1Ref ((uint16_t)0x0040) +#define TIM_TRGOSource_OC2Ref ((uint16_t)0x0050) +#define TIM_TRGOSource_OC3Ref ((uint16_t)0x0060) +#define TIM_TRGOSource_OC4Ref ((uint16_t)0x0070) +#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \ + ((SOURCE) == TIM_TRGOSource_Enable) || \ + ((SOURCE) == TIM_TRGOSource_Update) || \ + ((SOURCE) == TIM_TRGOSource_OC1) || \ + ((SOURCE) == TIM_TRGOSource_OC1Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC2Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC3Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC4Ref)) +/** + * @} + */ + +/** @defgroup TIM_Slave_Mode + * @{ + */ + +#define TIM_SlaveMode_Reset ((uint16_t)0x0004) +#define TIM_SlaveMode_Gated ((uint16_t)0x0005) +#define TIM_SlaveMode_Trigger ((uint16_t)0x0006) +#define TIM_SlaveMode_External1 ((uint16_t)0x0007) +#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \ + ((MODE) == TIM_SlaveMode_Gated) || \ + ((MODE) == TIM_SlaveMode_Trigger) || \ + ((MODE) == TIM_SlaveMode_External1)) +/** + * @} + */ + +/** @defgroup TIM_Master_Slave_Mode + * @{ + */ + +#define TIM_MasterSlaveMode_Enable ((uint16_t)0x0080) +#define TIM_MasterSlaveMode_Disable ((uint16_t)0x0000) +#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \ + ((STATE) == TIM_MasterSlaveMode_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Flags + * @{ + */ + +#define TIM_FLAG_Update ((uint16_t)0x0001) +#define TIM_FLAG_CC1 ((uint16_t)0x0002) +#define TIM_FLAG_CC2 ((uint16_t)0x0004) +#define TIM_FLAG_CC3 ((uint16_t)0x0008) +#define TIM_FLAG_CC4 ((uint16_t)0x0010) +#define TIM_FLAG_COM ((uint16_t)0x0020) +#define TIM_FLAG_Trigger ((uint16_t)0x0040) +#define TIM_FLAG_Break ((uint16_t)0x0080) +#define TIM_FLAG_CC1OF ((uint16_t)0x0200) +#define TIM_FLAG_CC2OF ((uint16_t)0x0400) +#define TIM_FLAG_CC3OF ((uint16_t)0x0800) +#define TIM_FLAG_CC4OF ((uint16_t)0x1000) +#define IS_TIM_GET_FLAG(FLAG) (((FLAG) == TIM_FLAG_Update) || \ + ((FLAG) == TIM_FLAG_CC1) || \ + ((FLAG) == TIM_FLAG_CC2) || \ + ((FLAG) == TIM_FLAG_CC3) || \ + ((FLAG) == TIM_FLAG_CC4) || \ + ((FLAG) == TIM_FLAG_COM) || \ + ((FLAG) == TIM_FLAG_Trigger) || \ + ((FLAG) == TIM_FLAG_Break) || \ + ((FLAG) == TIM_FLAG_CC1OF) || \ + ((FLAG) == TIM_FLAG_CC2OF) || \ + ((FLAG) == TIM_FLAG_CC3OF) || \ + ((FLAG) == TIM_FLAG_CC4OF)) + + +#define IS_TIM_CLEAR_FLAG(TIM_FLAG) ((((TIM_FLAG) & (uint16_t)0xE100) == 0x0000) && ((TIM_FLAG) != 0x0000)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Filer_Value + * @{ + */ + +#define IS_TIM_IC_FILTER(ICFILTER) ((ICFILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Filter + * @{ + */ + +#define IS_TIM_EXT_FILTER(EXTFILTER) ((EXTFILTER) <= 0xF) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup TIM_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions + * @{ + */ + +void TIM_DeInit(TIM_TypeDef* TIMx); +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, const TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_OC1Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC2Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC3Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC4Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_ICInit(TIM_TypeDef* TIMx, const TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct); +void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct); +void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState); +void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource); +void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength); +void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState); +void TIM_InternalClockConfig(TIM_TypeDef* TIMx); +void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); +void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, + uint16_t TIM_ICPolarity, uint16_t ICFilter); +void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); +void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter); +void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); +void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode); +void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode); +void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); +void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, + uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity); +void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx); +void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN); +void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode); +void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource); +void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode); +void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource); +void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); +void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode); +void TIM_SetCounter(TIM_TypeDef* TIMx, uint16_t Counter); +void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint16_t Autoreload); +void TIM_SetCompare1(TIM_TypeDef* TIMx, uint16_t Compare1); +void TIM_SetCompare2(TIM_TypeDef* TIMx, uint16_t Compare2); +void TIM_SetCompare3(TIM_TypeDef* TIMx, uint16_t Compare3); +void TIM_SetCompare4(TIM_TypeDef* TIMx, uint16_t Compare4); +void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD); +uint16_t TIM_GetCapture1(TIM_TypeDef* TIMx); +uint16_t TIM_GetCapture2(TIM_TypeDef* TIMx); +uint16_t TIM_GetCapture3(TIM_TypeDef* TIMx); +uint16_t TIM_GetCapture4(TIM_TypeDef* TIMx); +uint16_t TIM_GetCounter(TIM_TypeDef* TIMx); +uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx); +FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); +void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); +ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT); +void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_TIM_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h index 0f82e6931..b8180bc45 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h @@ -1,411 +1,411 @@ -/** - ****************************************************************************** - * @file stm32f10x_usart.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the USART - * firmware library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_USART_H -#define __STM32F10x_USART_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup USART - * @{ - */ - -/** @defgroup USART_Exported_Types - * @{ - */ - -/** - * @brief USART Init Structure definition - */ - -typedef struct -{ - uint32_t USART_BaudRate; /*!< This member configures the USART communication baud rate. - The baud rate is computed using the following formula: - - IntegerDivider = ((PCLKx) / (16 * (USART_InitStruct->USART_BaudRate))) - - FractionalDivider = ((IntegerDivider - ((u32) IntegerDivider)) * 16) + 0.5 */ - - uint16_t USART_WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref USART_Word_Length */ - - uint16_t USART_StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref USART_Stop_Bits */ - - uint16_t USART_Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref USART_Parity - @note When parity is enabled, the computed parity is inserted - at the MSB position of the transmitted data (9th bit when - the word length is set to 9 data bits; 8th bit when the - word length is set to 8 data bits). */ - - uint16_t USART_Mode; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled. - This parameter can be a value of @ref USART_Mode */ - - uint16_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled - or disabled. - This parameter can be a value of @ref USART_Hardware_Flow_Control */ -} USART_InitTypeDef; - -/** - * @brief USART Clock Init Structure definition - */ - -typedef struct -{ - - uint16_t USART_Clock; /*!< Specifies whether the USART clock is enabled or disabled. - This parameter can be a value of @ref USART_Clock */ - - uint16_t USART_CPOL; /*!< Specifies the steady state value of the serial clock. - This parameter can be a value of @ref USART_Clock_Polarity */ - - uint16_t USART_CPHA; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref USART_Clock_Phase */ - - uint16_t USART_LastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted - data bit (MSB) has to be output on the SCLK pin in synchronous mode. - This parameter can be a value of @ref USART_Last_Bit */ -} USART_ClockInitTypeDef; - -/** - * @} - */ - -/** @defgroup USART_Exported_Constants - * @{ - */ - -#define IS_USART_ALL_PERIPH(PERIPH) (((PERIPH) == USART1) || \ - ((PERIPH) == USART2) || \ - ((PERIPH) == USART3) || \ - ((PERIPH) == UART4) || \ - ((PERIPH) == UART5)) - -#define IS_USART_123_PERIPH(PERIPH) (((PERIPH) == USART1) || \ - ((PERIPH) == USART2) || \ - ((PERIPH) == USART3)) - -#define IS_USART_1234_PERIPH(PERIPH) (((PERIPH) == USART1) || \ - ((PERIPH) == USART2) || \ - ((PERIPH) == USART3) || \ - ((PERIPH) == UART4)) -/** @defgroup USART_Word_Length - * @{ - */ - -#define USART_WordLength_8b ((uint16_t)0x0000) -#define USART_WordLength_9b ((uint16_t)0x1000) - -#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \ - ((LENGTH) == USART_WordLength_9b)) -/** - * @} - */ - -/** @defgroup USART_Stop_Bits - * @{ - */ - -#define USART_StopBits_1 ((uint16_t)0x0000) -#define USART_StopBits_0_5 ((uint16_t)0x1000) -#define USART_StopBits_2 ((uint16_t)0x2000) -#define USART_StopBits_1_5 ((uint16_t)0x3000) -#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \ - ((STOPBITS) == USART_StopBits_0_5) || \ - ((STOPBITS) == USART_StopBits_2) || \ - ((STOPBITS) == USART_StopBits_1_5)) -/** - * @} - */ - -/** @defgroup USART_Parity - * @{ - */ - -#define USART_Parity_No ((uint16_t)0x0000) -#define USART_Parity_Even ((uint16_t)0x0400) -#define USART_Parity_Odd ((uint16_t)0x0600) -#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \ - ((PARITY) == USART_Parity_Even) || \ - ((PARITY) == USART_Parity_Odd)) -/** - * @} - */ - -/** @defgroup USART_Mode - * @{ - */ - -#define USART_Mode_Rx ((uint16_t)0x0004) -#define USART_Mode_Tx ((uint16_t)0x0008) -#define IS_USART_MODE(MODE) ((((MODE) & (uint16_t)0xFFF3) == 0x00) && ((MODE) != (uint16_t)0x00)) -/** - * @} - */ - -/** @defgroup USART_Hardware_Flow_Control - * @{ - */ -#define USART_HardwareFlowControl_None ((uint16_t)0x0000) -#define USART_HardwareFlowControl_RTS ((uint16_t)0x0100) -#define USART_HardwareFlowControl_CTS ((uint16_t)0x0200) -#define USART_HardwareFlowControl_RTS_CTS ((uint16_t)0x0300) -#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\ - (((CONTROL) == USART_HardwareFlowControl_None) || \ - ((CONTROL) == USART_HardwareFlowControl_RTS) || \ - ((CONTROL) == USART_HardwareFlowControl_CTS) || \ - ((CONTROL) == USART_HardwareFlowControl_RTS_CTS)) -/** - * @} - */ - -/** @defgroup USART_Clock - * @{ - */ -#define USART_Clock_Disable ((uint16_t)0x0000) -#define USART_Clock_Enable ((uint16_t)0x0800) -#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \ - ((CLOCK) == USART_Clock_Enable)) -/** - * @} - */ - -/** @defgroup USART_Clock_Polarity - * @{ - */ - -#define USART_CPOL_Low ((uint16_t)0x0000) -#define USART_CPOL_High ((uint16_t)0x0400) -#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High)) - -/** - * @} - */ - -/** @defgroup USART_Clock_Phase - * @{ - */ - -#define USART_CPHA_1Edge ((uint16_t)0x0000) -#define USART_CPHA_2Edge ((uint16_t)0x0200) -#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge)) - -/** - * @} - */ - -/** @defgroup USART_Last_Bit - * @{ - */ - -#define USART_LastBit_Disable ((uint16_t)0x0000) -#define USART_LastBit_Enable ((uint16_t)0x0100) -#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \ - ((LASTBIT) == USART_LastBit_Enable)) -/** - * @} - */ - -/** @defgroup USART_Interrupt_definition - * @{ - */ - -#define USART_IT_PE ((uint16_t)0x0028) -#define USART_IT_TXE ((uint16_t)0x0727) -#define USART_IT_TC ((uint16_t)0x0626) -#define USART_IT_RXNE ((uint16_t)0x0525) -#define USART_IT_IDLE ((uint16_t)0x0424) -#define USART_IT_LBD ((uint16_t)0x0846) -#define USART_IT_CTS ((uint16_t)0x096A) -#define USART_IT_ERR ((uint16_t)0x0060) -#define USART_IT_ORE ((uint16_t)0x0360) -#define USART_IT_NE ((uint16_t)0x0260) -#define USART_IT_FE ((uint16_t)0x0160) -#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ - ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ - ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ - ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR)) -#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ - ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ - ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ - ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \ - ((IT) == USART_IT_NE) || ((IT) == USART_IT_FE)) -#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ - ((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS)) -/** - * @} - */ - -/** @defgroup USART_DMA_Requests - * @{ - */ - -#define USART_DMAReq_Tx ((uint16_t)0x0080) -#define USART_DMAReq_Rx ((uint16_t)0x0040) -#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFF3F) == 0x00) && ((DMAREQ) != (uint16_t)0x00)) - -/** - * @} - */ - -/** @defgroup USART_WakeUp_methods - * @{ - */ - -#define USART_WakeUp_IdleLine ((uint16_t)0x0000) -#define USART_WakeUp_AddressMark ((uint16_t)0x0800) -#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \ - ((WAKEUP) == USART_WakeUp_AddressMark)) -/** - * @} - */ - -/** @defgroup USART_LIN_Break_Detection_Length - * @{ - */ - -#define USART_LINBreakDetectLength_10b ((uint16_t)0x0000) -#define USART_LINBreakDetectLength_11b ((uint16_t)0x0020) -#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \ - (((LENGTH) == USART_LINBreakDetectLength_10b) || \ - ((LENGTH) == USART_LINBreakDetectLength_11b)) -/** - * @} - */ - -/** @defgroup USART_IrDA_Low_Power - * @{ - */ - -#define USART_IrDAMode_LowPower ((uint16_t)0x0004) -#define USART_IrDAMode_Normal ((uint16_t)0x0000) -#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \ - ((MODE) == USART_IrDAMode_Normal)) -/** - * @} - */ - -/** @defgroup USART_Flags - * @{ - */ - -#define USART_FLAG_CTS ((uint16_t)0x0200) -#define USART_FLAG_LBD ((uint16_t)0x0100) -#define USART_FLAG_TXE ((uint16_t)0x0080) -#define USART_FLAG_TC ((uint16_t)0x0040) -#define USART_FLAG_RXNE ((uint16_t)0x0020) -#define USART_FLAG_IDLE ((uint16_t)0x0010) -#define USART_FLAG_ORE ((uint16_t)0x0008) -#define USART_FLAG_NE ((uint16_t)0x0004) -#define USART_FLAG_FE ((uint16_t)0x0002) -#define USART_FLAG_PE ((uint16_t)0x0001) -#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \ - ((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \ - ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \ - ((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \ - ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE)) - -#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFC9F) == 0x00) && ((FLAG) != (uint16_t)0x00)) -#define IS_USART_PERIPH_FLAG(PERIPH, USART_FLAG) ((((*(uint32_t*)&(PERIPH)) != UART4_BASE) &&\ - ((*(uint32_t*)&(PERIPH)) != UART5_BASE)) \ - || ((USART_FLAG) != USART_FLAG_CTS)) -#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x0044AA21)) -#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF) -#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF) - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup USART_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup USART_Exported_Functions - * @{ - */ - -void USART_DeInit(USART_TypeDef* USARTx); -void USART_Init(USART_TypeDef* USARTx, const USART_InitTypeDef* USART_InitStruct); -void USART_StructInit(USART_InitTypeDef* USART_InitStruct); -void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct); -void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct); -void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState); -void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState); -void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState); -void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address); -void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp); -void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState); -void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength); -void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState); -void USART_SendData(USART_TypeDef* USARTx, uint16_t Data); -uint16_t USART_ReceiveData(USART_TypeDef* USARTx); -void USART_SendBreak(USART_TypeDef* USARTx); -void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime); -void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler); -void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState); -void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState); -void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState); -void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState); -void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState); -void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode); -void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState); -FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG); -void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG); -ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT); -void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_USART_H */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_usart.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the USART + * firmware library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_USART_H +#define __STM32F10x_USART_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup USART + * @{ + */ + +/** @defgroup USART_Exported_Types + * @{ + */ + +/** + * @brief USART Init Structure definition + */ + +typedef struct +{ + uint32_t USART_BaudRate; /*!< This member configures the USART communication baud rate. + The baud rate is computed using the following formula: + - IntegerDivider = ((PCLKx) / (16 * (USART_InitStruct->USART_BaudRate))) + - FractionalDivider = ((IntegerDivider - ((u32) IntegerDivider)) * 16) + 0.5 */ + + uint16_t USART_WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. + This parameter can be a value of @ref USART_Word_Length */ + + uint16_t USART_StopBits; /*!< Specifies the number of stop bits transmitted. + This parameter can be a value of @ref USART_Stop_Bits */ + + uint16_t USART_Parity; /*!< Specifies the parity mode. + This parameter can be a value of @ref USART_Parity + @note When parity is enabled, the computed parity is inserted + at the MSB position of the transmitted data (9th bit when + the word length is set to 9 data bits; 8th bit when the + word length is set to 8 data bits). */ + + uint16_t USART_Mode; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled. + This parameter can be a value of @ref USART_Mode */ + + uint16_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled + or disabled. + This parameter can be a value of @ref USART_Hardware_Flow_Control */ +} USART_InitTypeDef; + +/** + * @brief USART Clock Init Structure definition + */ + +typedef struct +{ + + uint16_t USART_Clock; /*!< Specifies whether the USART clock is enabled or disabled. + This parameter can be a value of @ref USART_Clock */ + + uint16_t USART_CPOL; /*!< Specifies the steady state value of the serial clock. + This parameter can be a value of @ref USART_Clock_Polarity */ + + uint16_t USART_CPHA; /*!< Specifies the clock transition on which the bit capture is made. + This parameter can be a value of @ref USART_Clock_Phase */ + + uint16_t USART_LastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted + data bit (MSB) has to be output on the SCLK pin in synchronous mode. + This parameter can be a value of @ref USART_Last_Bit */ +} USART_ClockInitTypeDef; + +/** + * @} + */ + +/** @defgroup USART_Exported_Constants + * @{ + */ + +#define IS_USART_ALL_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3) || \ + ((PERIPH) == UART4) || \ + ((PERIPH) == UART5)) + +#define IS_USART_123_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3)) + +#define IS_USART_1234_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3) || \ + ((PERIPH) == UART4)) +/** @defgroup USART_Word_Length + * @{ + */ + +#define USART_WordLength_8b ((uint16_t)0x0000) +#define USART_WordLength_9b ((uint16_t)0x1000) + +#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \ + ((LENGTH) == USART_WordLength_9b)) +/** + * @} + */ + +/** @defgroup USART_Stop_Bits + * @{ + */ + +#define USART_StopBits_1 ((uint16_t)0x0000) +#define USART_StopBits_0_5 ((uint16_t)0x1000) +#define USART_StopBits_2 ((uint16_t)0x2000) +#define USART_StopBits_1_5 ((uint16_t)0x3000) +#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \ + ((STOPBITS) == USART_StopBits_0_5) || \ + ((STOPBITS) == USART_StopBits_2) || \ + ((STOPBITS) == USART_StopBits_1_5)) +/** + * @} + */ + +/** @defgroup USART_Parity + * @{ + */ + +#define USART_Parity_No ((uint16_t)0x0000) +#define USART_Parity_Even ((uint16_t)0x0400) +#define USART_Parity_Odd ((uint16_t)0x0600) +#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \ + ((PARITY) == USART_Parity_Even) || \ + ((PARITY) == USART_Parity_Odd)) +/** + * @} + */ + +/** @defgroup USART_Mode + * @{ + */ + +#define USART_Mode_Rx ((uint16_t)0x0004) +#define USART_Mode_Tx ((uint16_t)0x0008) +#define IS_USART_MODE(MODE) ((((MODE) & (uint16_t)0xFFF3) == 0x00) && ((MODE) != (uint16_t)0x00)) +/** + * @} + */ + +/** @defgroup USART_Hardware_Flow_Control + * @{ + */ +#define USART_HardwareFlowControl_None ((uint16_t)0x0000) +#define USART_HardwareFlowControl_RTS ((uint16_t)0x0100) +#define USART_HardwareFlowControl_CTS ((uint16_t)0x0200) +#define USART_HardwareFlowControl_RTS_CTS ((uint16_t)0x0300) +#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\ + (((CONTROL) == USART_HardwareFlowControl_None) || \ + ((CONTROL) == USART_HardwareFlowControl_RTS) || \ + ((CONTROL) == USART_HardwareFlowControl_CTS) || \ + ((CONTROL) == USART_HardwareFlowControl_RTS_CTS)) +/** + * @} + */ + +/** @defgroup USART_Clock + * @{ + */ +#define USART_Clock_Disable ((uint16_t)0x0000) +#define USART_Clock_Enable ((uint16_t)0x0800) +#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \ + ((CLOCK) == USART_Clock_Enable)) +/** + * @} + */ + +/** @defgroup USART_Clock_Polarity + * @{ + */ + +#define USART_CPOL_Low ((uint16_t)0x0000) +#define USART_CPOL_High ((uint16_t)0x0400) +#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High)) + +/** + * @} + */ + +/** @defgroup USART_Clock_Phase + * @{ + */ + +#define USART_CPHA_1Edge ((uint16_t)0x0000) +#define USART_CPHA_2Edge ((uint16_t)0x0200) +#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge)) + +/** + * @} + */ + +/** @defgroup USART_Last_Bit + * @{ + */ + +#define USART_LastBit_Disable ((uint16_t)0x0000) +#define USART_LastBit_Enable ((uint16_t)0x0100) +#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \ + ((LASTBIT) == USART_LastBit_Enable)) +/** + * @} + */ + +/** @defgroup USART_Interrupt_definition + * @{ + */ + +#define USART_IT_PE ((uint16_t)0x0028) +#define USART_IT_TXE ((uint16_t)0x0727) +#define USART_IT_TC ((uint16_t)0x0626) +#define USART_IT_RXNE ((uint16_t)0x0525) +#define USART_IT_IDLE ((uint16_t)0x0424) +#define USART_IT_LBD ((uint16_t)0x0846) +#define USART_IT_CTS ((uint16_t)0x096A) +#define USART_IT_ERR ((uint16_t)0x0060) +#define USART_IT_ORE ((uint16_t)0x0360) +#define USART_IT_NE ((uint16_t)0x0260) +#define USART_IT_FE ((uint16_t)0x0160) +#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ + ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ + ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR)) +#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ + ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ + ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \ + ((IT) == USART_IT_NE) || ((IT) == USART_IT_FE)) +#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS)) +/** + * @} + */ + +/** @defgroup USART_DMA_Requests + * @{ + */ + +#define USART_DMAReq_Tx ((uint16_t)0x0080) +#define USART_DMAReq_Rx ((uint16_t)0x0040) +#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFF3F) == 0x00) && ((DMAREQ) != (uint16_t)0x00)) + +/** + * @} + */ + +/** @defgroup USART_WakeUp_methods + * @{ + */ + +#define USART_WakeUp_IdleLine ((uint16_t)0x0000) +#define USART_WakeUp_AddressMark ((uint16_t)0x0800) +#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \ + ((WAKEUP) == USART_WakeUp_AddressMark)) +/** + * @} + */ + +/** @defgroup USART_LIN_Break_Detection_Length + * @{ + */ + +#define USART_LINBreakDetectLength_10b ((uint16_t)0x0000) +#define USART_LINBreakDetectLength_11b ((uint16_t)0x0020) +#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \ + (((LENGTH) == USART_LINBreakDetectLength_10b) || \ + ((LENGTH) == USART_LINBreakDetectLength_11b)) +/** + * @} + */ + +/** @defgroup USART_IrDA_Low_Power + * @{ + */ + +#define USART_IrDAMode_LowPower ((uint16_t)0x0004) +#define USART_IrDAMode_Normal ((uint16_t)0x0000) +#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \ + ((MODE) == USART_IrDAMode_Normal)) +/** + * @} + */ + +/** @defgroup USART_Flags + * @{ + */ + +#define USART_FLAG_CTS ((uint16_t)0x0200) +#define USART_FLAG_LBD ((uint16_t)0x0100) +#define USART_FLAG_TXE ((uint16_t)0x0080) +#define USART_FLAG_TC ((uint16_t)0x0040) +#define USART_FLAG_RXNE ((uint16_t)0x0020) +#define USART_FLAG_IDLE ((uint16_t)0x0010) +#define USART_FLAG_ORE ((uint16_t)0x0008) +#define USART_FLAG_NE ((uint16_t)0x0004) +#define USART_FLAG_FE ((uint16_t)0x0002) +#define USART_FLAG_PE ((uint16_t)0x0001) +#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \ + ((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \ + ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \ + ((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \ + ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE)) + +#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFC9F) == 0x00) && ((FLAG) != (uint16_t)0x00)) +#define IS_USART_PERIPH_FLAG(PERIPH, USART_FLAG) ((((*(uint32_t*)&(PERIPH)) != UART4_BASE) &&\ + ((*(uint32_t*)&(PERIPH)) != UART5_BASE)) \ + || ((USART_FLAG) != USART_FLAG_CTS)) +#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x0044AA21)) +#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF) +#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup USART_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Exported_Functions + * @{ + */ + +void USART_DeInit(USART_TypeDef* USARTx); +void USART_Init(USART_TypeDef* USARTx, const USART_InitTypeDef* USART_InitStruct); +void USART_StructInit(USART_InitTypeDef* USART_InitStruct); +void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct); +void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct); +void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState); +void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState); +void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address); +void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp); +void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength); +void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SendData(USART_TypeDef* USARTx, uint16_t Data); +uint16_t USART_ReceiveData(USART_TypeDef* USARTx); +void USART_SendBreak(USART_TypeDef* USARTx); +void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime); +void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler); +void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode); +void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState); +FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG); +void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG); +ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT); +void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_USART_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h index 859569841..09575eaa4 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h @@ -1,114 +1,114 @@ -/** - ****************************************************************************** - * @file stm32f10x_wwdg.h - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file contains all the functions prototypes for the WWDG firmware - * library. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F10x_WWDG_H -#define __STM32F10x_WWDG_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @addtogroup WWDG - * @{ - */ - -/** @defgroup WWDG_Exported_Types - * @{ - */ - -/** - * @} - */ - -/** @defgroup WWDG_Exported_Constants - * @{ - */ - -/** @defgroup WWDG_Prescaler - * @{ - */ - -#define WWDG_Prescaler_1 ((uint32_t)0x00000000) -#define WWDG_Prescaler_2 ((uint32_t)0x00000080) -#define WWDG_Prescaler_4 ((uint32_t)0x00000100) -#define WWDG_Prescaler_8 ((uint32_t)0x00000180) -#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \ - ((PRESCALER) == WWDG_Prescaler_2) || \ - ((PRESCALER) == WWDG_Prescaler_4) || \ - ((PRESCALER) == WWDG_Prescaler_8)) -#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F) -#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F)) - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup WWDG_Exported_Macros - * @{ - */ -/** - * @} - */ - -/** @defgroup WWDG_Exported_Functions - * @{ - */ - -void WWDG_DeInit(void); -void WWDG_SetPrescaler(uint32_t WWDG_Prescaler); -void WWDG_SetWindowValue(uint8_t WindowValue); -void WWDG_EnableIT(void); -void WWDG_SetCounter(uint8_t Counter); -void WWDG_Enable(uint8_t Counter); -FlagStatus WWDG_GetFlagStatus(void); -void WWDG_ClearFlag(void); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F10x_WWDG_H */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_wwdg.h + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file contains all the functions prototypes for the WWDG firmware + * library. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_WWDG_H +#define __STM32F10x_WWDG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup WWDG + * @{ + */ + +/** @defgroup WWDG_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Exported_Constants + * @{ + */ + +/** @defgroup WWDG_Prescaler + * @{ + */ + +#define WWDG_Prescaler_1 ((uint32_t)0x00000000) +#define WWDG_Prescaler_2 ((uint32_t)0x00000080) +#define WWDG_Prescaler_4 ((uint32_t)0x00000100) +#define WWDG_Prescaler_8 ((uint32_t)0x00000180) +#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \ + ((PRESCALER) == WWDG_Prescaler_2) || \ + ((PRESCALER) == WWDG_Prescaler_4) || \ + ((PRESCALER) == WWDG_Prescaler_8)) +#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F) +#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup WWDG_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup WWDG_Exported_Functions + * @{ + */ + +void WWDG_DeInit(void); +void WWDG_SetPrescaler(uint32_t WWDG_Prescaler); +void WWDG_SetWindowValue(uint8_t WindowValue); +void WWDG_EnableIT(void); +void WWDG_SetCounter(uint8_t Counter); +void WWDG_Enable(uint8_t Counter); +FlagStatus WWDG_GetFlagStatus(void); +void WWDG_ClearFlag(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_WWDG_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/misc.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/misc.c index e9871ad67..9340551f6 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/misc.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/misc.c @@ -1,223 +1,223 @@ -/** - ****************************************************************************** - * @file misc.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the miscellaneous firmware functions (add-on - * to CMSIS functions). - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "misc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup MISC - * @brief MISC driver modules - * @{ - */ - -/** @defgroup MISC_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup MISC_Private_Defines - * @{ - */ - -#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) -/** - * @} - */ - -/** @defgroup MISC_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup MISC_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup MISC_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup MISC_Private_Functions - * @{ - */ - -/** - * @brief Configures the priority grouping: pre-emption priority and subpriority. - * @param NVIC_PriorityGroup: specifies the priority grouping bits length. - * This parameter can be one of the following values: - * @arg NVIC_PriorityGroup_0: 0 bits for pre-emption priority - * 4 bits for subpriority - * @arg NVIC_PriorityGroup_1: 1 bits for pre-emption priority - * 3 bits for subpriority - * @arg NVIC_PriorityGroup_2: 2 bits for pre-emption priority - * 2 bits for subpriority - * @arg NVIC_PriorityGroup_3: 3 bits for pre-emption priority - * 1 bits for subpriority - * @arg NVIC_PriorityGroup_4: 4 bits for pre-emption priority - * 0 bits for subpriority - * @retval None - */ -void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup) -{ - /* Check the parameters */ - assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup)); - - /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */ - SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup; -} - -/** - * @brief Initializes the NVIC peripheral according to the specified - * parameters in the NVIC_InitStruct. - * @param NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure that contains - * the configuration information for the specified NVIC peripheral. - * @retval None - */ -void NVIC_Init(const NVIC_InitTypeDef* NVIC_InitStruct) -{ - uint32_t tmppriority = 0x00, tmppre = 0x00, tmpsub = 0x0F; - - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd)); - assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority)); - assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority)); - - if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE) - { - /* Compute the Corresponding IRQ Priority --------------------------------*/ - tmppriority = (0x700 - ((SCB->AIRCR) & (uint32_t)0x700))>> 0x08; - tmppre = (0x4 - tmppriority); - tmpsub = tmpsub >> tmppriority; - - tmppriority = (uint32_t)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre; - tmppriority |= NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub; - tmppriority = tmppriority << 0x04; - - NVIC->IP[NVIC_InitStruct->NVIC_IRQChannel] = tmppriority; - - /* Enable the Selected IRQ Channels --------------------------------------*/ - NVIC->ISER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = - (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); - } - else - { - /* Disable the Selected IRQ Channels -------------------------------------*/ - NVIC->ICER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = - (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); - } -} - -/** - * @brief Sets the vector table location and Offset. - * @param NVIC_VectTab: specifies if the vector table is in RAM or FLASH memory. - * This parameter can be one of the following values: - * @arg NVIC_VectTab_RAM - * @arg NVIC_VectTab_FLASH - * @param Offset: Vector Table base offset field. This value must be a multiple of 0x100. - * @retval None - */ -void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset) -{ - /* Check the parameters */ - assert_param(IS_NVIC_VECTTAB(NVIC_VectTab)); - assert_param(IS_NVIC_OFFSET(Offset)); - - SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80); -} - -/** - * @brief Selects the condition for the system to enter low power mode. - * @param LowPowerMode: Specifies the new mode for the system to enter low power mode. - * This parameter can be one of the following values: - * @arg NVIC_LP_SEVONPEND - * @arg NVIC_LP_SLEEPDEEP - * @arg NVIC_LP_SLEEPONEXIT - * @param NewState: new state of LP condition. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_NVIC_LP(LowPowerMode)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - SCB->SCR |= LowPowerMode; - } - else - { - SCB->SCR &= (uint32_t)(~(uint32_t)LowPowerMode); - } -} - -/** - * @brief Configures the SysTick clock source. - * @param SysTick_CLKSource: specifies the SysTick clock source. - * This parameter can be one of the following values: - * @arg SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source. - * @arg SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source. - * @retval None - */ -void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource) -{ - /* Check the parameters */ - assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource)); - if (SysTick_CLKSource == SysTick_CLKSource_HCLK) - { - SysTick->CTRL |= SysTick_CLKSource_HCLK; - } - else - { - SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8; - } -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file misc.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the miscellaneous firmware functions (add-on + * to CMSIS functions). + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "misc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup MISC + * @brief MISC driver modules + * @{ + */ + +/** @defgroup MISC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_Defines + * @{ + */ + +#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) +/** + * @} + */ + +/** @defgroup MISC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_Functions + * @{ + */ + +/** + * @brief Configures the priority grouping: pre-emption priority and subpriority. + * @param NVIC_PriorityGroup: specifies the priority grouping bits length. + * This parameter can be one of the following values: + * @arg NVIC_PriorityGroup_0: 0 bits for pre-emption priority + * 4 bits for subpriority + * @arg NVIC_PriorityGroup_1: 1 bits for pre-emption priority + * 3 bits for subpriority + * @arg NVIC_PriorityGroup_2: 2 bits for pre-emption priority + * 2 bits for subpriority + * @arg NVIC_PriorityGroup_3: 3 bits for pre-emption priority + * 1 bits for subpriority + * @arg NVIC_PriorityGroup_4: 4 bits for pre-emption priority + * 0 bits for subpriority + * @retval None + */ +void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup) +{ + /* Check the parameters */ + assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup)); + + /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */ + SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup; +} + +/** + * @brief Initializes the NVIC peripheral according to the specified + * parameters in the NVIC_InitStruct. + * @param NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure that contains + * the configuration information for the specified NVIC peripheral. + * @retval None + */ +void NVIC_Init(const NVIC_InitTypeDef* NVIC_InitStruct) +{ + uint32_t tmppriority = 0x00, tmppre = 0x00, tmpsub = 0x0F; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd)); + assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority)); + assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority)); + + if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE) + { + /* Compute the Corresponding IRQ Priority --------------------------------*/ + tmppriority = (0x700 - ((SCB->AIRCR) & (uint32_t)0x700))>> 0x08; + tmppre = (0x4 - tmppriority); + tmpsub = tmpsub >> tmppriority; + + tmppriority = (uint32_t)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre; + tmppriority |= NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub; + tmppriority = tmppriority << 0x04; + + NVIC->IP[NVIC_InitStruct->NVIC_IRQChannel] = tmppriority; + + /* Enable the Selected IRQ Channels --------------------------------------*/ + NVIC->ISER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = + (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); + } + else + { + /* Disable the Selected IRQ Channels -------------------------------------*/ + NVIC->ICER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = + (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); + } +} + +/** + * @brief Sets the vector table location and Offset. + * @param NVIC_VectTab: specifies if the vector table is in RAM or FLASH memory. + * This parameter can be one of the following values: + * @arg NVIC_VectTab_RAM + * @arg NVIC_VectTab_FLASH + * @param Offset: Vector Table base offset field. This value must be a multiple of 0x100. + * @retval None + */ +void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset) +{ + /* Check the parameters */ + assert_param(IS_NVIC_VECTTAB(NVIC_VectTab)); + assert_param(IS_NVIC_OFFSET(Offset)); + + SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80); +} + +/** + * @brief Selects the condition for the system to enter low power mode. + * @param LowPowerMode: Specifies the new mode for the system to enter low power mode. + * This parameter can be one of the following values: + * @arg NVIC_LP_SEVONPEND + * @arg NVIC_LP_SLEEPDEEP + * @arg NVIC_LP_SLEEPONEXIT + * @param NewState: new state of LP condition. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_NVIC_LP(LowPowerMode)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + SCB->SCR |= LowPowerMode; + } + else + { + SCB->SCR &= (uint32_t)(~(uint32_t)LowPowerMode); + } +} + +/** + * @brief Configures the SysTick clock source. + * @param SysTick_CLKSource: specifies the SysTick clock source. + * This parameter can be one of the following values: + * @arg SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source. + * @arg SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source. + * @retval None + */ +void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource) +{ + /* Check the parameters */ + assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource)); + if (SysTick_CLKSource == SysTick_CLKSource_HCLK) + { + SysTick->CTRL |= SysTick_CLKSource_HCLK; + } + else + { + SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c index 663b9bb3a..a2b305458 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c @@ -1,1306 +1,1306 @@ -/** - ****************************************************************************** - * @file stm32f10x_adc.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the ADC firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_adc.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup ADC - * @brief ADC driver modules - * @{ - */ - -/** @defgroup ADC_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup ADC_Private_Defines - * @{ - */ - -/* ADC DISCNUM mask */ -#define CR1_DISCNUM_Reset ((uint32_t)0xFFFF1FFF) - -/* ADC DISCEN mask */ -#define CR1_DISCEN_Set ((uint32_t)0x00000800) -#define CR1_DISCEN_Reset ((uint32_t)0xFFFFF7FF) - -/* ADC JAUTO mask */ -#define CR1_JAUTO_Set ((uint32_t)0x00000400) -#define CR1_JAUTO_Reset ((uint32_t)0xFFFFFBFF) - -/* ADC JDISCEN mask */ -#define CR1_JDISCEN_Set ((uint32_t)0x00001000) -#define CR1_JDISCEN_Reset ((uint32_t)0xFFFFEFFF) - -/* ADC AWDCH mask */ -#define CR1_AWDCH_Reset ((uint32_t)0xFFFFFFE0) - -/* ADC Analog watchdog enable mode mask */ -#define CR1_AWDMode_Reset ((uint32_t)0xFF3FFDFF) - -/* CR1 register Mask */ -#define CR1_CLEAR_Mask ((uint32_t)0xFFF0FEFF) - -/* ADC ADON mask */ -#define CR2_ADON_Set ((uint32_t)0x00000001) -#define CR2_ADON_Reset ((uint32_t)0xFFFFFFFE) - -/* ADC DMA mask */ -#define CR2_DMA_Set ((uint32_t)0x00000100) -#define CR2_DMA_Reset ((uint32_t)0xFFFFFEFF) - -/* ADC RSTCAL mask */ -#define CR2_RSTCAL_Set ((uint32_t)0x00000008) - -/* ADC CAL mask */ -#define CR2_CAL_Set ((uint32_t)0x00000004) - -/* ADC SWSTART mask */ -#define CR2_SWSTART_Set ((uint32_t)0x00400000) - -/* ADC EXTTRIG mask */ -#define CR2_EXTTRIG_Set ((uint32_t)0x00100000) -#define CR2_EXTTRIG_Reset ((uint32_t)0xFFEFFFFF) - -/* ADC Software start mask */ -#define CR2_EXTTRIG_SWSTART_Set ((uint32_t)0x00500000) -#define CR2_EXTTRIG_SWSTART_Reset ((uint32_t)0xFFAFFFFF) - -/* ADC JEXTSEL mask */ -#define CR2_JEXTSEL_Reset ((uint32_t)0xFFFF8FFF) - -/* ADC JEXTTRIG mask */ -#define CR2_JEXTTRIG_Set ((uint32_t)0x00008000) -#define CR2_JEXTTRIG_Reset ((uint32_t)0xFFFF7FFF) - -/* ADC JSWSTART mask */ -#define CR2_JSWSTART_Set ((uint32_t)0x00200000) - -/* ADC injected software start mask */ -#define CR2_JEXTTRIG_JSWSTART_Set ((uint32_t)0x00208000) -#define CR2_JEXTTRIG_JSWSTART_Reset ((uint32_t)0xFFDF7FFF) - -/* ADC TSPD mask */ -#define CR2_TSVREFE_Set ((uint32_t)0x00800000) -#define CR2_TSVREFE_Reset ((uint32_t)0xFF7FFFFF) - -/* CR2 register Mask */ -#define CR2_CLEAR_Mask ((uint32_t)0xFFF1F7FD) - -/* ADC SQx mask */ -#define SQR3_SQ_Set ((uint32_t)0x0000001F) -#define SQR2_SQ_Set ((uint32_t)0x0000001F) -#define SQR1_SQ_Set ((uint32_t)0x0000001F) - -/* SQR1 register Mask */ -#define SQR1_CLEAR_Mask ((uint32_t)0xFF0FFFFF) - -/* ADC JSQx mask */ -#define JSQR_JSQ_Set ((uint32_t)0x0000001F) - -/* ADC JL mask */ -#define JSQR_JL_Set ((uint32_t)0x00300000) -#define JSQR_JL_Reset ((uint32_t)0xFFCFFFFF) - -/* ADC SMPx mask */ -#define SMPR1_SMP_Set ((uint32_t)0x00000007) -#define SMPR2_SMP_Set ((uint32_t)0x00000007) - -/* ADC JDRx registers offset */ -#define JDR_Offset ((uint8_t)0x28) - -/* ADC1 DR register base address */ -#define DR_ADDRESS ((uint32_t)0x4001244C) - -/** - * @} - */ - -/** @defgroup ADC_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup ADC_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup ADC_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup ADC_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the ADCx peripheral registers to their default reset values. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @retval None - */ -void ADC_DeInit(ADC_TypeDef* ADCx) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - - if (ADCx == ADC1) - { - /* Enable ADC1 reset state */ - RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, ENABLE); - /* Release ADC1 from reset state */ - RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, DISABLE); - } - else if (ADCx == ADC2) - { - /* Enable ADC2 reset state */ - RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, ENABLE); - /* Release ADC2 from reset state */ - RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, DISABLE); - } - else - { - if (ADCx == ADC3) - { - /* Enable ADC3 reset state */ - RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, ENABLE); - /* Release ADC3 from reset state */ - RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, DISABLE); - } - } -} - -/** - * @brief Initializes the ADCx peripheral according to the specified parameters - * in the ADC_InitStruct. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_InitStruct: pointer to an ADC_InitTypeDef structure that contains - * the configuration information for the specified ADC peripheral. - * @retval None - */ -void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct) -{ - uint32_t tmpreg1 = 0; - uint8_t tmpreg2 = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_MODE(ADC_InitStruct->ADC_Mode)); - assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ScanConvMode)); - assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ContinuousConvMode)); - assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConv)); - assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign)); - assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfChannel)); - - /*---------------------------- ADCx CR1 Configuration -----------------*/ - /* Get the ADCx CR1 value */ - tmpreg1 = ADCx->CR1; - /* Clear DUALMOD and SCAN bits */ - tmpreg1 &= CR1_CLEAR_Mask; - /* Configure ADCx: Dual mode and scan conversion mode */ - /* Set DUALMOD bits according to ADC_Mode value */ - /* Set SCAN bit according to ADC_ScanConvMode value */ - tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_Mode | ((uint32_t)ADC_InitStruct->ADC_ScanConvMode << 8)); - /* Write to ADCx CR1 */ - ADCx->CR1 = tmpreg1; - - /*---------------------------- ADCx CR2 Configuration -----------------*/ - /* Get the ADCx CR2 value */ - tmpreg1 = ADCx->CR2; - /* Clear CONT, ALIGN and EXTSEL bits */ - tmpreg1 &= CR2_CLEAR_Mask; - /* Configure ADCx: external trigger event and continuous conversion mode */ - /* Set ALIGN bit according to ADC_DataAlign value */ - /* Set EXTSEL bits according to ADC_ExternalTrigConv value */ - /* Set CONT bit according to ADC_ContinuousConvMode value */ - tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_DataAlign | ADC_InitStruct->ADC_ExternalTrigConv | - ((uint32_t)ADC_InitStruct->ADC_ContinuousConvMode << 1)); - /* Write to ADCx CR2 */ - ADCx->CR2 = tmpreg1; - - /*---------------------------- ADCx SQR1 Configuration -----------------*/ - /* Get the ADCx SQR1 value */ - tmpreg1 = ADCx->SQR1; - /* Clear L bits */ - tmpreg1 &= SQR1_CLEAR_Mask; - /* Configure ADCx: regular channel sequence length */ - /* Set L bits according to ADC_NbrOfChannel value */ - tmpreg2 |= (uint8_t) (ADC_InitStruct->ADC_NbrOfChannel - (uint8_t)1); - tmpreg1 |= (uint32_t)tmpreg2 << 20; - /* Write to ADCx SQR1 */ - ADCx->SQR1 = tmpreg1; -} - -/** - * @brief Fills each ADC_InitStruct member with its default value. - * @param ADC_InitStruct : pointer to an ADC_InitTypeDef structure which will be initialized. - * @retval None - */ -void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct) -{ - /* Reset ADC init structure parameters values */ - /* Initialize the ADC_Mode member */ - ADC_InitStruct->ADC_Mode = ADC_Mode_Independent; - /* initialize the ADC_ScanConvMode member */ - ADC_InitStruct->ADC_ScanConvMode = DISABLE; - /* Initialize the ADC_ContinuousConvMode member */ - ADC_InitStruct->ADC_ContinuousConvMode = DISABLE; - /* Initialize the ADC_ExternalTrigConv member */ - ADC_InitStruct->ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1; - /* Initialize the ADC_DataAlign member */ - ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right; - /* Initialize the ADC_NbrOfChannel member */ - ADC_InitStruct->ADC_NbrOfChannel = 1; -} - -/** - * @brief Enables or disables the specified ADC peripheral. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param NewState: new state of the ADCx peripheral. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Set the ADON bit to wake up the ADC from power down mode */ - ADCx->CR2 |= CR2_ADON_Set; - } - else - { - /* Disable the selected ADC peripheral */ - ADCx->CR2 &= CR2_ADON_Reset; - } -} - -/** - * @brief Enables or disables the specified ADC DMA request. - * @param ADCx: where x can be 1 or 3 to select the ADC peripheral. - * Note: ADC2 hasn't a DMA capability. - * @param NewState: new state of the selected ADC DMA transfer. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_ADC_DMA_PERIPH(ADCx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected ADC DMA request */ - ADCx->CR2 |= CR2_DMA_Set; - } - else - { - /* Disable the selected ADC DMA request */ - ADCx->CR2 &= CR2_DMA_Reset; - } -} - -/** - * @brief Enables or disables the specified ADC interrupts. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_IT: specifies the ADC interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg ADC_IT_EOC: End of conversion interrupt mask - * @arg ADC_IT_AWD: Analog watchdog interrupt mask - * @arg ADC_IT_JEOC: End of injected conversion interrupt mask - * @param NewState: new state of the specified ADC interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState) -{ - uint8_t itmask = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - assert_param(IS_ADC_IT(ADC_IT)); - /* Get the ADC IT index */ - itmask = (uint8_t)ADC_IT; - if (NewState != DISABLE) - { - /* Enable the selected ADC interrupts */ - ADCx->CR1 |= itmask; - } - else - { - /* Disable the selected ADC interrupts */ - ADCx->CR1 &= (~(uint32_t)itmask); - } -} - -/** - * @brief Resets the selected ADC calibration registers. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @retval None - */ -void ADC_ResetCalibration(ADC_TypeDef* ADCx) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - /* Resets the selected ADC calibartion registers */ - ADCx->CR2 |= CR2_RSTCAL_Set; -} - -/** - * @brief Gets the selected ADC reset calibration registers status. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @retval The new state of ADC reset calibration registers (SET or RESET). - */ -FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - /* Check the status of RSTCAL bit */ - if ((ADCx->CR2 & CR2_RSTCAL_Set) != (uint32_t)RESET) - { - /* RSTCAL bit is set */ - bitstatus = SET; - } - else - { - /* RSTCAL bit is reset */ - bitstatus = RESET; - } - /* Return the RSTCAL bit status */ - return bitstatus; -} - -/** - * @brief Starts the selected ADC calibration process. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @retval None - */ -void ADC_StartCalibration(ADC_TypeDef* ADCx) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - /* Enable the selected ADC calibration process */ - ADCx->CR2 |= CR2_CAL_Set; -} - -/** - * @brief Gets the selected ADC calibration status. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @retval The new state of ADC calibration (SET or RESET). - */ -FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - /* Check the status of CAL bit */ - if ((ADCx->CR2 & CR2_CAL_Set) != (uint32_t)RESET) - { - /* CAL bit is set: calibration on going */ - bitstatus = SET; - } - else - { - /* CAL bit is reset: end of calibration */ - bitstatus = RESET; - } - /* Return the CAL bit status */ - return bitstatus; -} - -/** - * @brief Enables or disables the selected ADC software start conversion . - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param NewState: new state of the selected ADC software start conversion. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected ADC conversion on external event and start the selected - ADC conversion */ - ADCx->CR2 |= CR2_EXTTRIG_SWSTART_Set; - } - else - { - /* Disable the selected ADC conversion on external event and stop the selected - ADC conversion */ - ADCx->CR2 &= CR2_EXTTRIG_SWSTART_Reset; - } -} - -/** - * @brief Gets the selected ADC Software start conversion Status. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @retval The new state of ADC software start conversion (SET or RESET). - */ -FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - /* Check the status of SWSTART bit */ - if ((ADCx->CR2 & CR2_SWSTART_Set) != (uint32_t)RESET) - { - /* SWSTART bit is set */ - bitstatus = SET; - } - else - { - /* SWSTART bit is reset */ - bitstatus = RESET; - } - /* Return the SWSTART bit status */ - return bitstatus; -} - -/** - * @brief Configures the discontinuous mode for the selected ADC regular - * group channel. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param Number: specifies the discontinuous mode regular channel - * count value. This number must be between 1 and 8. - * @retval None - */ -void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number) -{ - uint32_t tmpreg1 = 0; - uint32_t tmpreg2 = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number)); - /* Get the old register value */ - tmpreg1 = ADCx->CR1; - /* Clear the old discontinuous mode channel count */ - tmpreg1 &= CR1_DISCNUM_Reset; - /* Set the discontinuous mode channel count */ - tmpreg2 = Number - 1; - tmpreg1 |= tmpreg2 << 13; - /* Store the new register value */ - ADCx->CR1 = tmpreg1; -} - -/** - * @brief Enables or disables the discontinuous mode on regular group - * channel for the specified ADC - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param NewState: new state of the selected ADC discontinuous mode - * on regular group channel. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected ADC regular discontinuous mode */ - ADCx->CR1 |= CR1_DISCEN_Set; - } - else - { - /* Disable the selected ADC regular discontinuous mode */ - ADCx->CR1 &= CR1_DISCEN_Reset; - } -} - -/** - * @brief Configures for the selected ADC regular channel its corresponding - * rank in the sequencer and its sample time. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_Channel: the ADC channel to configure. - * This parameter can be one of the following values: - * @arg ADC_Channel_0: ADC Channel0 selected - * @arg ADC_Channel_1: ADC Channel1 selected - * @arg ADC_Channel_2: ADC Channel2 selected - * @arg ADC_Channel_3: ADC Channel3 selected - * @arg ADC_Channel_4: ADC Channel4 selected - * @arg ADC_Channel_5: ADC Channel5 selected - * @arg ADC_Channel_6: ADC Channel6 selected - * @arg ADC_Channel_7: ADC Channel7 selected - * @arg ADC_Channel_8: ADC Channel8 selected - * @arg ADC_Channel_9: ADC Channel9 selected - * @arg ADC_Channel_10: ADC Channel10 selected - * @arg ADC_Channel_11: ADC Channel11 selected - * @arg ADC_Channel_12: ADC Channel12 selected - * @arg ADC_Channel_13: ADC Channel13 selected - * @arg ADC_Channel_14: ADC Channel14 selected - * @arg ADC_Channel_15: ADC Channel15 selected - * @arg ADC_Channel_16: ADC Channel16 selected - * @arg ADC_Channel_17: ADC Channel17 selected - * @param Rank: The rank in the regular group sequencer. This parameter must be between 1 to 16. - * @param ADC_SampleTime: The sample time value to be set for the selected channel. - * This parameter can be one of the following values: - * @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles - * @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles - * @arg ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles - * @arg ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles - * @arg ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles - * @arg ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles - * @arg ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles - * @arg ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles - * @retval None - */ -void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) -{ - uint32_t tmpreg1 = 0, tmpreg2 = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_CHANNEL(ADC_Channel)); - assert_param(IS_ADC_REGULAR_RANK(Rank)); - assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); - /* if ADC_Channel_10 ... ADC_Channel_17 is selected */ - if (ADC_Channel > ADC_Channel_9) - { - /* Get the old register value */ - tmpreg1 = ADCx->SMPR1; - /* Calculate the mask to clear */ - tmpreg2 = SMPR1_SMP_Set << (3 * (ADC_Channel - 10)); - /* Clear the old channel sample time */ - tmpreg1 &= ~tmpreg2; - /* Calculate the mask to set */ - tmpreg2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10)); - /* Set the new channel sample time */ - tmpreg1 |= tmpreg2; - /* Store the new register value */ - ADCx->SMPR1 = tmpreg1; - } - else /* ADC_Channel include in ADC_Channel_[0..9] */ - { - /* Get the old register value */ - tmpreg1 = ADCx->SMPR2; - /* Calculate the mask to clear */ - tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel); - /* Clear the old channel sample time */ - tmpreg1 &= ~tmpreg2; - /* Calculate the mask to set */ - tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); - /* Set the new channel sample time */ - tmpreg1 |= tmpreg2; - /* Store the new register value */ - ADCx->SMPR2 = tmpreg1; - } - /* For Rank 1 to 6 */ - if (Rank < 7) - { - /* Get the old register value */ - tmpreg1 = ADCx->SQR3; - /* Calculate the mask to clear */ - tmpreg2 = SQR3_SQ_Set << (5 * (Rank - 1)); - /* Clear the old SQx bits for the selected rank */ - tmpreg1 &= ~tmpreg2; - /* Calculate the mask to set */ - tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 1)); - /* Set the SQx bits for the selected rank */ - tmpreg1 |= tmpreg2; - /* Store the new register value */ - ADCx->SQR3 = tmpreg1; - } - /* For Rank 7 to 12 */ - else if (Rank < 13) - { - /* Get the old register value */ - tmpreg1 = ADCx->SQR2; - /* Calculate the mask to clear */ - tmpreg2 = SQR2_SQ_Set << (5 * (Rank - 7)); - /* Clear the old SQx bits for the selected rank */ - tmpreg1 &= ~tmpreg2; - /* Calculate the mask to set */ - tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 7)); - /* Set the SQx bits for the selected rank */ - tmpreg1 |= tmpreg2; - /* Store the new register value */ - ADCx->SQR2 = tmpreg1; - } - /* For Rank 13 to 16 */ - else - { - /* Get the old register value */ - tmpreg1 = ADCx->SQR1; - /* Calculate the mask to clear */ - tmpreg2 = SQR1_SQ_Set << (5 * (Rank - 13)); - /* Clear the old SQx bits for the selected rank */ - tmpreg1 &= ~tmpreg2; - /* Calculate the mask to set */ - tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 13)); - /* Set the SQx bits for the selected rank */ - tmpreg1 |= tmpreg2; - /* Store the new register value */ - ADCx->SQR1 = tmpreg1; - } -} - -/** - * @brief Enables or disables the ADCx conversion through external trigger. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param NewState: new state of the selected ADC external trigger start of conversion. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected ADC conversion on external event */ - ADCx->CR2 |= CR2_EXTTRIG_Set; - } - else - { - /* Disable the selected ADC conversion on external event */ - ADCx->CR2 &= CR2_EXTTRIG_Reset; - } -} - -/** - * @brief Returns the last ADCx conversion result data for regular channel. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @retval The Data conversion value. - */ -uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - /* Return the selected ADC conversion value */ - return (uint16_t) ADCx->DR; -} - -/** - * @brief Returns the last ADC1 and ADC2 conversion result data in dual mode. - * @retval The Data conversion value. - */ -uint32_t ADC_GetDualModeConversionValue(void) -{ - /* Return the dual mode conversion value */ - return (*(__IO uint32_t *) DR_ADDRESS); -} - -/** - * @brief Enables or disables the selected ADC automatic injected group - * conversion after regular one. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param NewState: new state of the selected ADC auto injected conversion - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected ADC automatic injected group conversion */ - ADCx->CR1 |= CR1_JAUTO_Set; - } - else - { - /* Disable the selected ADC automatic injected group conversion */ - ADCx->CR1 &= CR1_JAUTO_Reset; - } -} - -/** - * @brief Enables or disables the discontinuous mode for injected group - * channel for the specified ADC - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param NewState: new state of the selected ADC discontinuous mode - * on injected group channel. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected ADC injected discontinuous mode */ - ADCx->CR1 |= CR1_JDISCEN_Set; - } - else - { - /* Disable the selected ADC injected discontinuous mode */ - ADCx->CR1 &= CR1_JDISCEN_Reset; - } -} - -/** - * @brief Configures the ADCx external trigger for injected channels conversion. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_ExternalTrigInjecConv: specifies the ADC trigger to start injected conversion. - * This parameter can be one of the following values: - * @arg ADC_ExternalTrigInjecConv_T1_TRGO: Timer1 TRGO event selected (for ADC1, ADC2 and ADC3) - * @arg ADC_ExternalTrigInjecConv_T1_CC4: Timer1 capture compare4 selected (for ADC1, ADC2 and ADC3) - * @arg ADC_ExternalTrigInjecConv_T2_TRGO: Timer2 TRGO event selected (for ADC1 and ADC2) - * @arg ADC_ExternalTrigInjecConv_T2_CC1: Timer2 capture compare1 selected (for ADC1 and ADC2) - * @arg ADC_ExternalTrigInjecConv_T3_CC4: Timer3 capture compare4 selected (for ADC1 and ADC2) - * @arg ADC_ExternalTrigInjecConv_T4_TRGO: Timer4 TRGO event selected (for ADC1 and ADC2) - * @arg ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4: External interrupt line 15 or Timer8 - * capture compare4 event selected (for ADC1 and ADC2) - * @arg ADC_ExternalTrigInjecConv_T4_CC3: Timer4 capture compare3 selected (for ADC3 only) - * @arg ADC_ExternalTrigInjecConv_T8_CC2: Timer8 capture compare2 selected (for ADC3 only) - * @arg ADC_ExternalTrigInjecConv_T8_CC4: Timer8 capture compare4 selected (for ADC3 only) - * @arg ADC_ExternalTrigInjecConv_T5_TRGO: Timer5 TRGO event selected (for ADC3 only) - * @arg ADC_ExternalTrigInjecConv_T5_CC4: Timer5 capture compare4 selected (for ADC3 only) - * @arg ADC_ExternalTrigInjecConv_None: Injected conversion started by software and not - * by external trigger (for ADC1, ADC2 and ADC3) - * @retval None - */ -void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_ExternalTrigInjecConv)); - /* Get the old register value */ - tmpreg = ADCx->CR2; - /* Clear the old external event selection for injected group */ - tmpreg &= CR2_JEXTSEL_Reset; - /* Set the external event selection for injected group */ - tmpreg |= ADC_ExternalTrigInjecConv; - /* Store the new register value */ - ADCx->CR2 = tmpreg; -} - -/** - * @brief Enables or disables the ADCx injected channels conversion through - * external trigger - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param NewState: new state of the selected ADC external trigger start of - * injected conversion. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected ADC external event selection for injected group */ - ADCx->CR2 |= CR2_JEXTTRIG_Set; - } - else - { - /* Disable the selected ADC external event selection for injected group */ - ADCx->CR2 &= CR2_JEXTTRIG_Reset; - } -} - -/** - * @brief Enables or disables the selected ADC start of the injected - * channels conversion. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param NewState: new state of the selected ADC software start injected conversion. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected ADC conversion for injected group on external event and start the selected - ADC injected conversion */ - ADCx->CR2 |= CR2_JEXTTRIG_JSWSTART_Set; - } - else - { - /* Disable the selected ADC conversion on external event for injected group and stop the selected - ADC injected conversion */ - ADCx->CR2 &= CR2_JEXTTRIG_JSWSTART_Reset; - } -} - -/** - * @brief Gets the selected ADC Software start injected conversion Status. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @retval The new state of ADC software start injected conversion (SET or RESET). - */ -FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - /* Check the status of JSWSTART bit */ - if ((ADCx->CR2 & CR2_JSWSTART_Set) != (uint32_t)RESET) - { - /* JSWSTART bit is set */ - bitstatus = SET; - } - else - { - /* JSWSTART bit is reset */ - bitstatus = RESET; - } - /* Return the JSWSTART bit status */ - return bitstatus; -} - -/** - * @brief Configures for the selected ADC injected channel its corresponding - * rank in the sequencer and its sample time. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_Channel: the ADC channel to configure. - * This parameter can be one of the following values: - * @arg ADC_Channel_0: ADC Channel0 selected - * @arg ADC_Channel_1: ADC Channel1 selected - * @arg ADC_Channel_2: ADC Channel2 selected - * @arg ADC_Channel_3: ADC Channel3 selected - * @arg ADC_Channel_4: ADC Channel4 selected - * @arg ADC_Channel_5: ADC Channel5 selected - * @arg ADC_Channel_6: ADC Channel6 selected - * @arg ADC_Channel_7: ADC Channel7 selected - * @arg ADC_Channel_8: ADC Channel8 selected - * @arg ADC_Channel_9: ADC Channel9 selected - * @arg ADC_Channel_10: ADC Channel10 selected - * @arg ADC_Channel_11: ADC Channel11 selected - * @arg ADC_Channel_12: ADC Channel12 selected - * @arg ADC_Channel_13: ADC Channel13 selected - * @arg ADC_Channel_14: ADC Channel14 selected - * @arg ADC_Channel_15: ADC Channel15 selected - * @arg ADC_Channel_16: ADC Channel16 selected - * @arg ADC_Channel_17: ADC Channel17 selected - * @param Rank: The rank in the injected group sequencer. This parameter must be between 1 and 4. - * @param ADC_SampleTime: The sample time value to be set for the selected channel. - * This parameter can be one of the following values: - * @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles - * @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles - * @arg ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles - * @arg ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles - * @arg ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles - * @arg ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles - * @arg ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles - * @arg ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles - * @retval None - */ -void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) -{ - uint32_t tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_CHANNEL(ADC_Channel)); - assert_param(IS_ADC_INJECTED_RANK(Rank)); - assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); - /* if ADC_Channel_10 ... ADC_Channel_17 is selected */ - if (ADC_Channel > ADC_Channel_9) - { - /* Get the old register value */ - tmpreg1 = ADCx->SMPR1; - /* Calculate the mask to clear */ - tmpreg2 = SMPR1_SMP_Set << (3*(ADC_Channel - 10)); - /* Clear the old channel sample time */ - tmpreg1 &= ~tmpreg2; - /* Calculate the mask to set */ - tmpreg2 = (uint32_t)ADC_SampleTime << (3*(ADC_Channel - 10)); - /* Set the new channel sample time */ - tmpreg1 |= tmpreg2; - /* Store the new register value */ - ADCx->SMPR1 = tmpreg1; - } - else /* ADC_Channel include in ADC_Channel_[0..9] */ - { - /* Get the old register value */ - tmpreg1 = ADCx->SMPR2; - /* Calculate the mask to clear */ - tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel); - /* Clear the old channel sample time */ - tmpreg1 &= ~tmpreg2; - /* Calculate the mask to set */ - tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); - /* Set the new channel sample time */ - tmpreg1 |= tmpreg2; - /* Store the new register value */ - ADCx->SMPR2 = tmpreg1; - } - /* Rank configuration */ - /* Get the old register value */ - tmpreg1 = ADCx->JSQR; - /* Get JL value: Number = JL+1 */ - tmpreg3 = (tmpreg1 & JSQR_JL_Set)>> 20; - /* Calculate the mask to clear: ((Rank-1)+(4-JL-1)) */ - tmpreg2 = JSQR_JSQ_Set << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1))); - /* Clear the old JSQx bits for the selected rank */ - tmpreg1 &= ~tmpreg2; - /* Calculate the mask to set: ((Rank-1)+(4-JL-1)) */ - tmpreg2 = (uint32_t)ADC_Channel << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1))); - /* Set the JSQx bits for the selected rank */ - tmpreg1 |= tmpreg2; - /* Store the new register value */ - ADCx->JSQR = tmpreg1; -} - -/** - * @brief Configures the sequencer length for injected channels - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param Length: The sequencer length. - * This parameter must be a number between 1 to 4. - * @retval None - */ -void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length) -{ - uint32_t tmpreg1 = 0; - uint32_t tmpreg2 = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_INJECTED_LENGTH(Length)); - - /* Get the old register value */ - tmpreg1 = ADCx->JSQR; - /* Clear the old injected sequnence lenght JL bits */ - tmpreg1 &= JSQR_JL_Reset; - /* Set the injected sequnence lenght JL bits */ - tmpreg2 = Length - 1; - tmpreg1 |= tmpreg2 << 20; - /* Store the new register value */ - ADCx->JSQR = tmpreg1; -} - -/** - * @brief Set the injected channels conversion value offset - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_InjectedChannel: the ADC injected channel to set its offset. - * This parameter can be one of the following values: - * @arg ADC_InjectedChannel_1: Injected Channel1 selected - * @arg ADC_InjectedChannel_2: Injected Channel2 selected - * @arg ADC_InjectedChannel_3: Injected Channel3 selected - * @arg ADC_InjectedChannel_4: Injected Channel4 selected - * @param Offset: the offset value for the selected ADC injected channel - * This parameter must be a 12bit value. - * @retval None - */ -void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset) -{ - __IO uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); - assert_param(IS_ADC_OFFSET(Offset)); - - tmp = (uint32_t)ADCx; - tmp += ADC_InjectedChannel; - - /* Set the selected injected channel data offset */ - *(__IO uint32_t *) tmp = (uint32_t)Offset; -} - -/** - * @brief Returns the ADC injected channel conversion result - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_InjectedChannel: the converted ADC injected channel. - * This parameter can be one of the following values: - * @arg ADC_InjectedChannel_1: Injected Channel1 selected - * @arg ADC_InjectedChannel_2: Injected Channel2 selected - * @arg ADC_InjectedChannel_3: Injected Channel3 selected - * @arg ADC_InjectedChannel_4: Injected Channel4 selected - * @retval The Data conversion value. - */ -uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel) -{ - __IO uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); - - tmp = (uint32_t)ADCx; - tmp += ADC_InjectedChannel + JDR_Offset; - - /* Returns the selected injected channel conversion data value */ - return (uint16_t) (*(__IO uint32_t*) tmp); -} - -/** - * @brief Enables or disables the analog watchdog on single/all regular - * or injected channels - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_AnalogWatchdog: the ADC analog watchdog configuration. - * This parameter can be one of the following values: - * @arg ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on a single regular channel - * @arg ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on a single injected channel - * @arg ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog watchdog on a single regular or injected channel - * @arg ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on all regular channel - * @arg ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on all injected channel - * @arg ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog on all regular and injected channels - * @arg ADC_AnalogWatchdog_None: No channel guarded by the analog watchdog - * @retval None - */ -void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog)); - /* Get the old register value */ - tmpreg = ADCx->CR1; - /* Clear AWDEN, AWDENJ and AWDSGL bits */ - tmpreg &= CR1_AWDMode_Reset; - /* Set the analog watchdog enable mode */ - tmpreg |= ADC_AnalogWatchdog; - /* Store the new register value */ - ADCx->CR1 = tmpreg; -} - -/** - * @brief Configures the high and low thresholds of the analog watchdog. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param HighThreshold: the ADC analog watchdog High threshold value. - * This parameter must be a 12bit value. - * @param LowThreshold: the ADC analog watchdog Low threshold value. - * This parameter must be a 12bit value. - * @retval None - */ -void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, - uint16_t LowThreshold) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_THRESHOLD(HighThreshold)); - assert_param(IS_ADC_THRESHOLD(LowThreshold)); - /* Set the ADCx high threshold */ - ADCx->HTR = HighThreshold; - /* Set the ADCx low threshold */ - ADCx->LTR = LowThreshold; -} - -/** - * @brief Configures the analog watchdog guarded single channel - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_Channel: the ADC channel to configure for the analog watchdog. - * This parameter can be one of the following values: - * @arg ADC_Channel_0: ADC Channel0 selected - * @arg ADC_Channel_1: ADC Channel1 selected - * @arg ADC_Channel_2: ADC Channel2 selected - * @arg ADC_Channel_3: ADC Channel3 selected - * @arg ADC_Channel_4: ADC Channel4 selected - * @arg ADC_Channel_5: ADC Channel5 selected - * @arg ADC_Channel_6: ADC Channel6 selected - * @arg ADC_Channel_7: ADC Channel7 selected - * @arg ADC_Channel_8: ADC Channel8 selected - * @arg ADC_Channel_9: ADC Channel9 selected - * @arg ADC_Channel_10: ADC Channel10 selected - * @arg ADC_Channel_11: ADC Channel11 selected - * @arg ADC_Channel_12: ADC Channel12 selected - * @arg ADC_Channel_13: ADC Channel13 selected - * @arg ADC_Channel_14: ADC Channel14 selected - * @arg ADC_Channel_15: ADC Channel15 selected - * @arg ADC_Channel_16: ADC Channel16 selected - * @arg ADC_Channel_17: ADC Channel17 selected - * @retval None - */ -void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_CHANNEL(ADC_Channel)); - /* Get the old register value */ - tmpreg = ADCx->CR1; - /* Clear the Analog watchdog channel select bits */ - tmpreg &= CR1_AWDCH_Reset; - /* Set the Analog watchdog channel */ - tmpreg |= ADC_Channel; - /* Store the new register value */ - ADCx->CR1 = tmpreg; -} - -/** - * @brief Enables or disables the temperature sensor and Vrefint channel. - * @param NewState: new state of the temperature sensor. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void ADC_TempSensorVrefintCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the temperature sensor and Vrefint channel*/ - ADC1->CR2 |= CR2_TSVREFE_Set; - } - else - { - /* Disable the temperature sensor and Vrefint channel*/ - ADC1->CR2 &= CR2_TSVREFE_Reset; - } -} - -/** - * @brief Checks whether the specified ADC flag is set or not. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_FLAG: specifies the flag to check. - * This parameter can be one of the following values: - * @arg ADC_FLAG_AWD: Analog watchdog flag - * @arg ADC_FLAG_EOC: End of conversion flag - * @arg ADC_FLAG_JEOC: End of injected group conversion flag - * @arg ADC_FLAG_JSTRT: Start of injected group conversion flag - * @arg ADC_FLAG_STRT: Start of regular group conversion flag - * @retval The new state of ADC_FLAG (SET or RESET). - */ -FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_GET_FLAG(ADC_FLAG)); - /* Check the status of the specified ADC flag */ - if ((ADCx->SR & ADC_FLAG) != (uint8_t)RESET) - { - /* ADC_FLAG is set */ - bitstatus = SET; - } - else - { - /* ADC_FLAG is reset */ - bitstatus = RESET; - } - /* Return the ADC_FLAG status */ - return bitstatus; -} - -/** - * @brief Clears the ADCx's pending flags. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_FLAG: specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg ADC_FLAG_AWD: Analog watchdog flag - * @arg ADC_FLAG_EOC: End of conversion flag - * @arg ADC_FLAG_JEOC: End of injected group conversion flag - * @arg ADC_FLAG_JSTRT: Start of injected group conversion flag - * @arg ADC_FLAG_STRT: Start of regular group conversion flag - * @retval None - */ -void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG) -{ - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG)); - /* Clear the selected ADC flags */ - ADCx->SR = ~(uint32_t)ADC_FLAG; -} - -/** - * @brief Checks whether the specified ADC interrupt has occurred or not. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_IT: specifies the ADC interrupt source to check. - * This parameter can be one of the following values: - * @arg ADC_IT_EOC: End of conversion interrupt mask - * @arg ADC_IT_AWD: Analog watchdog interrupt mask - * @arg ADC_IT_JEOC: End of injected conversion interrupt mask - * @retval The new state of ADC_IT (SET or RESET). - */ -ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT) -{ - ITStatus bitstatus = RESET; - uint32_t itmask = 0, enablestatus = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_GET_IT(ADC_IT)); - /* Get the ADC IT index */ - itmask = ADC_IT >> 8; - /* Get the ADC_IT enable bit status */ - enablestatus = (ADCx->CR1 & (uint8_t)ADC_IT) ; - /* Check the status of the specified ADC interrupt */ - if (((ADCx->SR & itmask) != (uint32_t)RESET) && enablestatus) - { - /* ADC_IT is set */ - bitstatus = SET; - } - else - { - /* ADC_IT is reset */ - bitstatus = RESET; - } - /* Return the ADC_IT status */ - return bitstatus; -} - -/** - * @brief Clears the ADCx’s interrupt pending bits. - * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. - * @param ADC_IT: specifies the ADC interrupt pending bit to clear. - * This parameter can be any combination of the following values: - * @arg ADC_IT_EOC: End of conversion interrupt mask - * @arg ADC_IT_AWD: Analog watchdog interrupt mask - * @arg ADC_IT_JEOC: End of injected conversion interrupt mask - * @retval None - */ -void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT) -{ - uint8_t itmask = 0; - /* Check the parameters */ - assert_param(IS_ADC_ALL_PERIPH(ADCx)); - assert_param(IS_ADC_IT(ADC_IT)); - /* Get the ADC IT index */ - itmask = (uint8_t)(ADC_IT >> 8); - /* Clear the selected ADC interrupt pending bits */ - ADCx->SR = ~(uint32_t)itmask; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_adc.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the ADC firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_adc.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup ADC + * @brief ADC driver modules + * @{ + */ + +/** @defgroup ADC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_Defines + * @{ + */ + +/* ADC DISCNUM mask */ +#define CR1_DISCNUM_Reset ((uint32_t)0xFFFF1FFF) + +/* ADC DISCEN mask */ +#define CR1_DISCEN_Set ((uint32_t)0x00000800) +#define CR1_DISCEN_Reset ((uint32_t)0xFFFFF7FF) + +/* ADC JAUTO mask */ +#define CR1_JAUTO_Set ((uint32_t)0x00000400) +#define CR1_JAUTO_Reset ((uint32_t)0xFFFFFBFF) + +/* ADC JDISCEN mask */ +#define CR1_JDISCEN_Set ((uint32_t)0x00001000) +#define CR1_JDISCEN_Reset ((uint32_t)0xFFFFEFFF) + +/* ADC AWDCH mask */ +#define CR1_AWDCH_Reset ((uint32_t)0xFFFFFFE0) + +/* ADC Analog watchdog enable mode mask */ +#define CR1_AWDMode_Reset ((uint32_t)0xFF3FFDFF) + +/* CR1 register Mask */ +#define CR1_CLEAR_Mask ((uint32_t)0xFFF0FEFF) + +/* ADC ADON mask */ +#define CR2_ADON_Set ((uint32_t)0x00000001) +#define CR2_ADON_Reset ((uint32_t)0xFFFFFFFE) + +/* ADC DMA mask */ +#define CR2_DMA_Set ((uint32_t)0x00000100) +#define CR2_DMA_Reset ((uint32_t)0xFFFFFEFF) + +/* ADC RSTCAL mask */ +#define CR2_RSTCAL_Set ((uint32_t)0x00000008) + +/* ADC CAL mask */ +#define CR2_CAL_Set ((uint32_t)0x00000004) + +/* ADC SWSTART mask */ +#define CR2_SWSTART_Set ((uint32_t)0x00400000) + +/* ADC EXTTRIG mask */ +#define CR2_EXTTRIG_Set ((uint32_t)0x00100000) +#define CR2_EXTTRIG_Reset ((uint32_t)0xFFEFFFFF) + +/* ADC Software start mask */ +#define CR2_EXTTRIG_SWSTART_Set ((uint32_t)0x00500000) +#define CR2_EXTTRIG_SWSTART_Reset ((uint32_t)0xFFAFFFFF) + +/* ADC JEXTSEL mask */ +#define CR2_JEXTSEL_Reset ((uint32_t)0xFFFF8FFF) + +/* ADC JEXTTRIG mask */ +#define CR2_JEXTTRIG_Set ((uint32_t)0x00008000) +#define CR2_JEXTTRIG_Reset ((uint32_t)0xFFFF7FFF) + +/* ADC JSWSTART mask */ +#define CR2_JSWSTART_Set ((uint32_t)0x00200000) + +/* ADC injected software start mask */ +#define CR2_JEXTTRIG_JSWSTART_Set ((uint32_t)0x00208000) +#define CR2_JEXTTRIG_JSWSTART_Reset ((uint32_t)0xFFDF7FFF) + +/* ADC TSPD mask */ +#define CR2_TSVREFE_Set ((uint32_t)0x00800000) +#define CR2_TSVREFE_Reset ((uint32_t)0xFF7FFFFF) + +/* CR2 register Mask */ +#define CR2_CLEAR_Mask ((uint32_t)0xFFF1F7FD) + +/* ADC SQx mask */ +#define SQR3_SQ_Set ((uint32_t)0x0000001F) +#define SQR2_SQ_Set ((uint32_t)0x0000001F) +#define SQR1_SQ_Set ((uint32_t)0x0000001F) + +/* SQR1 register Mask */ +#define SQR1_CLEAR_Mask ((uint32_t)0xFF0FFFFF) + +/* ADC JSQx mask */ +#define JSQR_JSQ_Set ((uint32_t)0x0000001F) + +/* ADC JL mask */ +#define JSQR_JL_Set ((uint32_t)0x00300000) +#define JSQR_JL_Reset ((uint32_t)0xFFCFFFFF) + +/* ADC SMPx mask */ +#define SMPR1_SMP_Set ((uint32_t)0x00000007) +#define SMPR2_SMP_Set ((uint32_t)0x00000007) + +/* ADC JDRx registers offset */ +#define JDR_Offset ((uint8_t)0x28) + +/* ADC1 DR register base address */ +#define DR_ADDRESS ((uint32_t)0x4001244C) + +/** + * @} + */ + +/** @defgroup ADC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the ADCx peripheral registers to their default reset values. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_DeInit(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + if (ADCx == ADC1) + { + /* Enable ADC1 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, ENABLE); + /* Release ADC1 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, DISABLE); + } + else if (ADCx == ADC2) + { + /* Enable ADC2 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, ENABLE); + /* Release ADC2 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, DISABLE); + } + else + { + if (ADCx == ADC3) + { + /* Enable ADC3 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, ENABLE); + /* Release ADC3 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, DISABLE); + } + } +} + +/** + * @brief Initializes the ADCx peripheral according to the specified parameters + * in the ADC_InitStruct. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InitStruct: pointer to an ADC_InitTypeDef structure that contains + * the configuration information for the specified ADC peripheral. + * @retval None + */ +void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct) +{ + uint32_t tmpreg1 = 0; + uint8_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_MODE(ADC_InitStruct->ADC_Mode)); + assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ScanConvMode)); + assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConv)); + assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign)); + assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfChannel)); + + /*---------------------------- ADCx CR1 Configuration -----------------*/ + /* Get the ADCx CR1 value */ + tmpreg1 = ADCx->CR1; + /* Clear DUALMOD and SCAN bits */ + tmpreg1 &= CR1_CLEAR_Mask; + /* Configure ADCx: Dual mode and scan conversion mode */ + /* Set DUALMOD bits according to ADC_Mode value */ + /* Set SCAN bit according to ADC_ScanConvMode value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_Mode | ((uint32_t)ADC_InitStruct->ADC_ScanConvMode << 8)); + /* Write to ADCx CR1 */ + ADCx->CR1 = tmpreg1; + + /*---------------------------- ADCx CR2 Configuration -----------------*/ + /* Get the ADCx CR2 value */ + tmpreg1 = ADCx->CR2; + /* Clear CONT, ALIGN and EXTSEL bits */ + tmpreg1 &= CR2_CLEAR_Mask; + /* Configure ADCx: external trigger event and continuous conversion mode */ + /* Set ALIGN bit according to ADC_DataAlign value */ + /* Set EXTSEL bits according to ADC_ExternalTrigConv value */ + /* Set CONT bit according to ADC_ContinuousConvMode value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_DataAlign | ADC_InitStruct->ADC_ExternalTrigConv | + ((uint32_t)ADC_InitStruct->ADC_ContinuousConvMode << 1)); + /* Write to ADCx CR2 */ + ADCx->CR2 = tmpreg1; + + /*---------------------------- ADCx SQR1 Configuration -----------------*/ + /* Get the ADCx SQR1 value */ + tmpreg1 = ADCx->SQR1; + /* Clear L bits */ + tmpreg1 &= SQR1_CLEAR_Mask; + /* Configure ADCx: regular channel sequence length */ + /* Set L bits according to ADC_NbrOfChannel value */ + tmpreg2 |= (uint8_t) (ADC_InitStruct->ADC_NbrOfChannel - (uint8_t)1); + tmpreg1 |= (uint32_t)tmpreg2 << 20; + /* Write to ADCx SQR1 */ + ADCx->SQR1 = tmpreg1; +} + +/** + * @brief Fills each ADC_InitStruct member with its default value. + * @param ADC_InitStruct : pointer to an ADC_InitTypeDef structure which will be initialized. + * @retval None + */ +void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct) +{ + /* Reset ADC init structure parameters values */ + /* Initialize the ADC_Mode member */ + ADC_InitStruct->ADC_Mode = ADC_Mode_Independent; + /* initialize the ADC_ScanConvMode member */ + ADC_InitStruct->ADC_ScanConvMode = DISABLE; + /* Initialize the ADC_ContinuousConvMode member */ + ADC_InitStruct->ADC_ContinuousConvMode = DISABLE; + /* Initialize the ADC_ExternalTrigConv member */ + ADC_InitStruct->ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1; + /* Initialize the ADC_DataAlign member */ + ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right; + /* Initialize the ADC_NbrOfChannel member */ + ADC_InitStruct->ADC_NbrOfChannel = 1; +} + +/** + * @brief Enables or disables the specified ADC peripheral. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the ADCx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the ADON bit to wake up the ADC from power down mode */ + ADCx->CR2 |= CR2_ADON_Set; + } + else + { + /* Disable the selected ADC peripheral */ + ADCx->CR2 &= CR2_ADON_Reset; + } +} + +/** + * @brief Enables or disables the specified ADC DMA request. + * @param ADCx: where x can be 1 or 3 to select the ADC peripheral. + * Note: ADC2 hasn't a DMA capability. + * @param NewState: new state of the selected ADC DMA transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_DMA_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC DMA request */ + ADCx->CR2 |= CR2_DMA_Set; + } + else + { + /* Disable the selected ADC DMA request */ + ADCx->CR2 &= CR2_DMA_Reset; + } +} + +/** + * @brief Enables or disables the specified ADC interrupts. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @param NewState: new state of the specified ADC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState) +{ + uint8_t itmask = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_ADC_IT(ADC_IT)); + /* Get the ADC IT index */ + itmask = (uint8_t)ADC_IT; + if (NewState != DISABLE) + { + /* Enable the selected ADC interrupts */ + ADCx->CR1 |= itmask; + } + else + { + /* Disable the selected ADC interrupts */ + ADCx->CR1 &= (~(uint32_t)itmask); + } +} + +/** + * @brief Resets the selected ADC calibration registers. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_ResetCalibration(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Resets the selected ADC calibartion registers */ + ADCx->CR2 |= CR2_RSTCAL_Set; +} + +/** + * @brief Gets the selected ADC reset calibration registers status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC reset calibration registers (SET or RESET). + */ +FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of RSTCAL bit */ + if ((ADCx->CR2 & CR2_RSTCAL_Set) != (uint32_t)RESET) + { + /* RSTCAL bit is set */ + bitstatus = SET; + } + else + { + /* RSTCAL bit is reset */ + bitstatus = RESET; + } + /* Return the RSTCAL bit status */ + return bitstatus; +} + +/** + * @brief Starts the selected ADC calibration process. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_StartCalibration(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Enable the selected ADC calibration process */ + ADCx->CR2 |= CR2_CAL_Set; +} + +/** + * @brief Gets the selected ADC calibration status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC calibration (SET or RESET). + */ +FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of CAL bit */ + if ((ADCx->CR2 & CR2_CAL_Set) != (uint32_t)RESET) + { + /* CAL bit is set: calibration on going */ + bitstatus = SET; + } + else + { + /* CAL bit is reset: end of calibration */ + bitstatus = RESET; + } + /* Return the CAL bit status */ + return bitstatus; +} + +/** + * @brief Enables or disables the selected ADC software start conversion . + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC software start conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC conversion on external event and start the selected + ADC conversion */ + ADCx->CR2 |= CR2_EXTTRIG_SWSTART_Set; + } + else + { + /* Disable the selected ADC conversion on external event and stop the selected + ADC conversion */ + ADCx->CR2 &= CR2_EXTTRIG_SWSTART_Reset; + } +} + +/** + * @brief Gets the selected ADC Software start conversion Status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC software start conversion (SET or RESET). + */ +FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of SWSTART bit */ + if ((ADCx->CR2 & CR2_SWSTART_Set) != (uint32_t)RESET) + { + /* SWSTART bit is set */ + bitstatus = SET; + } + else + { + /* SWSTART bit is reset */ + bitstatus = RESET; + } + /* Return the SWSTART bit status */ + return bitstatus; +} + +/** + * @brief Configures the discontinuous mode for the selected ADC regular + * group channel. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param Number: specifies the discontinuous mode regular channel + * count value. This number must be between 1 and 8. + * @retval None + */ +void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number)); + /* Get the old register value */ + tmpreg1 = ADCx->CR1; + /* Clear the old discontinuous mode channel count */ + tmpreg1 &= CR1_DISCNUM_Reset; + /* Set the discontinuous mode channel count */ + tmpreg2 = Number - 1; + tmpreg1 |= tmpreg2 << 13; + /* Store the new register value */ + ADCx->CR1 = tmpreg1; +} + +/** + * @brief Enables or disables the discontinuous mode on regular group + * channel for the specified ADC + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC discontinuous mode + * on regular group channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC regular discontinuous mode */ + ADCx->CR1 |= CR1_DISCEN_Set; + } + else + { + /* Disable the selected ADC regular discontinuous mode */ + ADCx->CR1 &= CR1_DISCEN_Reset; + } +} + +/** + * @brief Configures for the selected ADC regular channel its corresponding + * rank in the sequencer and its sample time. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @param Rank: The rank in the regular group sequencer. This parameter must be between 1 to 16. + * @param ADC_SampleTime: The sample time value to be set for the selected channel. + * This parameter can be one of the following values: + * @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles + * @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles + * @arg ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles + * @arg ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles + * @arg ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles + * @arg ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles + * @arg ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles + * @arg ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles + * @retval None + */ +void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_REGULAR_RANK(Rank)); + assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + /* if ADC_Channel_10 ... ADC_Channel_17 is selected */ + if (ADC_Channel > ADC_Channel_9) + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR1; + /* Calculate the mask to clear */ + tmpreg2 = SMPR1_SMP_Set << (3 * (ADC_Channel - 10)); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10)); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR1 = tmpreg1; + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR2; + /* Calculate the mask to clear */ + tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR2 = tmpreg1; + } + /* For Rank 1 to 6 */ + if (Rank < 7) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR3; + /* Calculate the mask to clear */ + tmpreg2 = SQR3_SQ_Set << (5 * (Rank - 1)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 1)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR3 = tmpreg1; + } + /* For Rank 7 to 12 */ + else if (Rank < 13) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR2; + /* Calculate the mask to clear */ + tmpreg2 = SQR2_SQ_Set << (5 * (Rank - 7)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 7)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR2 = tmpreg1; + } + /* For Rank 13 to 16 */ + else + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR1; + /* Calculate the mask to clear */ + tmpreg2 = SQR1_SQ_Set << (5 * (Rank - 13)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 13)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR1 = tmpreg1; + } +} + +/** + * @brief Enables or disables the ADCx conversion through external trigger. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC external trigger start of conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC conversion on external event */ + ADCx->CR2 |= CR2_EXTTRIG_Set; + } + else + { + /* Disable the selected ADC conversion on external event */ + ADCx->CR2 &= CR2_EXTTRIG_Reset; + } +} + +/** + * @brief Returns the last ADCx conversion result data for regular channel. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The Data conversion value. + */ +uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Return the selected ADC conversion value */ + return (uint16_t) ADCx->DR; +} + +/** + * @brief Returns the last ADC1 and ADC2 conversion result data in dual mode. + * @retval The Data conversion value. + */ +uint32_t ADC_GetDualModeConversionValue(void) +{ + /* Return the dual mode conversion value */ + return (*(__IO uint32_t *) DR_ADDRESS); +} + +/** + * @brief Enables or disables the selected ADC automatic injected group + * conversion after regular one. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC auto injected conversion + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC automatic injected group conversion */ + ADCx->CR1 |= CR1_JAUTO_Set; + } + else + { + /* Disable the selected ADC automatic injected group conversion */ + ADCx->CR1 &= CR1_JAUTO_Reset; + } +} + +/** + * @brief Enables or disables the discontinuous mode for injected group + * channel for the specified ADC + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC discontinuous mode + * on injected group channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC injected discontinuous mode */ + ADCx->CR1 |= CR1_JDISCEN_Set; + } + else + { + /* Disable the selected ADC injected discontinuous mode */ + ADCx->CR1 &= CR1_JDISCEN_Reset; + } +} + +/** + * @brief Configures the ADCx external trigger for injected channels conversion. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_ExternalTrigInjecConv: specifies the ADC trigger to start injected conversion. + * This parameter can be one of the following values: + * @arg ADC_ExternalTrigInjecConv_T1_TRGO: Timer1 TRGO event selected (for ADC1, ADC2 and ADC3) + * @arg ADC_ExternalTrigInjecConv_T1_CC4: Timer1 capture compare4 selected (for ADC1, ADC2 and ADC3) + * @arg ADC_ExternalTrigInjecConv_T2_TRGO: Timer2 TRGO event selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T2_CC1: Timer2 capture compare1 selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T3_CC4: Timer3 capture compare4 selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T4_TRGO: Timer4 TRGO event selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4: External interrupt line 15 or Timer8 + * capture compare4 event selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T4_CC3: Timer4 capture compare3 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T8_CC2: Timer8 capture compare2 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T8_CC4: Timer8 capture compare4 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T5_TRGO: Timer5 TRGO event selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T5_CC4: Timer5 capture compare4 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_None: Injected conversion started by software and not + * by external trigger (for ADC1, ADC2 and ADC3) + * @retval None + */ +void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_ExternalTrigInjecConv)); + /* Get the old register value */ + tmpreg = ADCx->CR2; + /* Clear the old external event selection for injected group */ + tmpreg &= CR2_JEXTSEL_Reset; + /* Set the external event selection for injected group */ + tmpreg |= ADC_ExternalTrigInjecConv; + /* Store the new register value */ + ADCx->CR2 = tmpreg; +} + +/** + * @brief Enables or disables the ADCx injected channels conversion through + * external trigger + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC external trigger start of + * injected conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC external event selection for injected group */ + ADCx->CR2 |= CR2_JEXTTRIG_Set; + } + else + { + /* Disable the selected ADC external event selection for injected group */ + ADCx->CR2 &= CR2_JEXTTRIG_Reset; + } +} + +/** + * @brief Enables or disables the selected ADC start of the injected + * channels conversion. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC software start injected conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC conversion for injected group on external event and start the selected + ADC injected conversion */ + ADCx->CR2 |= CR2_JEXTTRIG_JSWSTART_Set; + } + else + { + /* Disable the selected ADC conversion on external event for injected group and stop the selected + ADC injected conversion */ + ADCx->CR2 &= CR2_JEXTTRIG_JSWSTART_Reset; + } +} + +/** + * @brief Gets the selected ADC Software start injected conversion Status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC software start injected conversion (SET or RESET). + */ +FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of JSWSTART bit */ + if ((ADCx->CR2 & CR2_JSWSTART_Set) != (uint32_t)RESET) + { + /* JSWSTART bit is set */ + bitstatus = SET; + } + else + { + /* JSWSTART bit is reset */ + bitstatus = RESET; + } + /* Return the JSWSTART bit status */ + return bitstatus; +} + +/** + * @brief Configures for the selected ADC injected channel its corresponding + * rank in the sequencer and its sample time. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @param Rank: The rank in the injected group sequencer. This parameter must be between 1 and 4. + * @param ADC_SampleTime: The sample time value to be set for the selected channel. + * This parameter can be one of the following values: + * @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles + * @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles + * @arg ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles + * @arg ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles + * @arg ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles + * @arg ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles + * @arg ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles + * @arg ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles + * @retval None + */ +void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_INJECTED_RANK(Rank)); + assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + /* if ADC_Channel_10 ... ADC_Channel_17 is selected */ + if (ADC_Channel > ADC_Channel_9) + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR1; + /* Calculate the mask to clear */ + tmpreg2 = SMPR1_SMP_Set << (3*(ADC_Channel - 10)); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3*(ADC_Channel - 10)); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR1 = tmpreg1; + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR2; + /* Calculate the mask to clear */ + tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR2 = tmpreg1; + } + /* Rank configuration */ + /* Get the old register value */ + tmpreg1 = ADCx->JSQR; + /* Get JL value: Number = JL+1 */ + tmpreg3 = (tmpreg1 & JSQR_JL_Set)>> 20; + /* Calculate the mask to clear: ((Rank-1)+(4-JL-1)) */ + tmpreg2 = JSQR_JSQ_Set << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1))); + /* Clear the old JSQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set: ((Rank-1)+(4-JL-1)) */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1))); + /* Set the JSQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->JSQR = tmpreg1; +} + +/** + * @brief Configures the sequencer length for injected channels + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param Length: The sequencer length. + * This parameter must be a number between 1 to 4. + * @retval None + */ +void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_LENGTH(Length)); + + /* Get the old register value */ + tmpreg1 = ADCx->JSQR; + /* Clear the old injected sequnence lenght JL bits */ + tmpreg1 &= JSQR_JL_Reset; + /* Set the injected sequnence lenght JL bits */ + tmpreg2 = Length - 1; + tmpreg1 |= tmpreg2 << 20; + /* Store the new register value */ + ADCx->JSQR = tmpreg1; +} + +/** + * @brief Set the injected channels conversion value offset + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InjectedChannel: the ADC injected channel to set its offset. + * This parameter can be one of the following values: + * @arg ADC_InjectedChannel_1: Injected Channel1 selected + * @arg ADC_InjectedChannel_2: Injected Channel2 selected + * @arg ADC_InjectedChannel_3: Injected Channel3 selected + * @arg ADC_InjectedChannel_4: Injected Channel4 selected + * @param Offset: the offset value for the selected ADC injected channel + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); + assert_param(IS_ADC_OFFSET(Offset)); + + tmp = (uint32_t)ADCx; + tmp += ADC_InjectedChannel; + + /* Set the selected injected channel data offset */ + *(__IO uint32_t *) tmp = (uint32_t)Offset; +} + +/** + * @brief Returns the ADC injected channel conversion result + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InjectedChannel: the converted ADC injected channel. + * This parameter can be one of the following values: + * @arg ADC_InjectedChannel_1: Injected Channel1 selected + * @arg ADC_InjectedChannel_2: Injected Channel2 selected + * @arg ADC_InjectedChannel_3: Injected Channel3 selected + * @arg ADC_InjectedChannel_4: Injected Channel4 selected + * @retval The Data conversion value. + */ +uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); + + tmp = (uint32_t)ADCx; + tmp += ADC_InjectedChannel + JDR_Offset; + + /* Returns the selected injected channel conversion data value */ + return (uint16_t) (*(__IO uint32_t*) tmp); +} + +/** + * @brief Enables or disables the analog watchdog on single/all regular + * or injected channels + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_AnalogWatchdog: the ADC analog watchdog configuration. + * This parameter can be one of the following values: + * @arg ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on a single regular channel + * @arg ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on a single injected channel + * @arg ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog watchdog on a single regular or injected channel + * @arg ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on all regular channel + * @arg ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on all injected channel + * @arg ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog on all regular and injected channels + * @arg ADC_AnalogWatchdog_None: No channel guarded by the analog watchdog + * @retval None + */ +void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog)); + /* Get the old register value */ + tmpreg = ADCx->CR1; + /* Clear AWDEN, AWDENJ and AWDSGL bits */ + tmpreg &= CR1_AWDMode_Reset; + /* Set the analog watchdog enable mode */ + tmpreg |= ADC_AnalogWatchdog; + /* Store the new register value */ + ADCx->CR1 = tmpreg; +} + +/** + * @brief Configures the high and low thresholds of the analog watchdog. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param HighThreshold: the ADC analog watchdog High threshold value. + * This parameter must be a 12bit value. + * @param LowThreshold: the ADC analog watchdog Low threshold value. + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, + uint16_t LowThreshold) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_THRESHOLD(HighThreshold)); + assert_param(IS_ADC_THRESHOLD(LowThreshold)); + /* Set the ADCx high threshold */ + ADCx->HTR = HighThreshold; + /* Set the ADCx low threshold */ + ADCx->LTR = LowThreshold; +} + +/** + * @brief Configures the analog watchdog guarded single channel + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure for the analog watchdog. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @retval None + */ +void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + /* Get the old register value */ + tmpreg = ADCx->CR1; + /* Clear the Analog watchdog channel select bits */ + tmpreg &= CR1_AWDCH_Reset; + /* Set the Analog watchdog channel */ + tmpreg |= ADC_Channel; + /* Store the new register value */ + ADCx->CR1 = tmpreg; +} + +/** + * @brief Enables or disables the temperature sensor and Vrefint channel. + * @param NewState: new state of the temperature sensor. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_TempSensorVrefintCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the temperature sensor and Vrefint channel*/ + ADC1->CR2 |= CR2_TSVREFE_Set; + } + else + { + /* Disable the temperature sensor and Vrefint channel*/ + ADC1->CR2 &= CR2_TSVREFE_Reset; + } +} + +/** + * @brief Checks whether the specified ADC flag is set or not. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg ADC_FLAG_AWD: Analog watchdog flag + * @arg ADC_FLAG_EOC: End of conversion flag + * @arg ADC_FLAG_JEOC: End of injected group conversion flag + * @arg ADC_FLAG_JSTRT: Start of injected group conversion flag + * @arg ADC_FLAG_STRT: Start of regular group conversion flag + * @retval The new state of ADC_FLAG (SET or RESET). + */ +FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_GET_FLAG(ADC_FLAG)); + /* Check the status of the specified ADC flag */ + if ((ADCx->SR & ADC_FLAG) != (uint8_t)RESET) + { + /* ADC_FLAG is set */ + bitstatus = SET; + } + else + { + /* ADC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the ADC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the ADCx's pending flags. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg ADC_FLAG_AWD: Analog watchdog flag + * @arg ADC_FLAG_EOC: End of conversion flag + * @arg ADC_FLAG_JEOC: End of injected group conversion flag + * @arg ADC_FLAG_JSTRT: Start of injected group conversion flag + * @arg ADC_FLAG_STRT: Start of regular group conversion flag + * @retval None + */ +void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG)); + /* Clear the selected ADC flags */ + ADCx->SR = ~(uint32_t)ADC_FLAG; +} + +/** + * @brief Checks whether the specified ADC interrupt has occurred or not. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt source to check. + * This parameter can be one of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @retval The new state of ADC_IT (SET or RESET). + */ +ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t itmask = 0, enablestatus = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_GET_IT(ADC_IT)); + /* Get the ADC IT index */ + itmask = ADC_IT >> 8; + /* Get the ADC_IT enable bit status */ + enablestatus = (ADCx->CR1 & (uint8_t)ADC_IT) ; + /* Check the status of the specified ADC interrupt */ + if (((ADCx->SR & itmask) != (uint32_t)RESET) && enablestatus) + { + /* ADC_IT is set */ + bitstatus = SET; + } + else + { + /* ADC_IT is reset */ + bitstatus = RESET; + } + /* Return the ADC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the ADCx’s interrupt pending bits. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @retval None + */ +void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT) +{ + uint8_t itmask = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_IT(ADC_IT)); + /* Get the ADC IT index */ + itmask = (uint8_t)(ADC_IT >> 8); + /* Clear the selected ADC interrupt pending bits */ + ADCx->SR = ~(uint32_t)itmask; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c index 3ad63af35..ce3519e07 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c @@ -1,307 +1,307 @@ -/** - ****************************************************************************** - * @file stm32f10x_bkp.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the BKP firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_bkp.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup BKP - * @brief BKP driver modules - * @{ - */ - -/** @defgroup BKP_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup BKP_Private_Defines - * @{ - */ - -/* ------------ BKP registers bit address in the alias region --------------- */ -#define BKP_OFFSET (BKP_BASE - PERIPH_BASE) - -/* --- CR Register ----*/ - -/* Alias word address of TPAL bit */ -#define CR_OFFSET (BKP_OFFSET + 0x30) -#define TPAL_BitNumber 0x01 -#define CR_TPAL_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPAL_BitNumber * 4)) - -/* Alias word address of TPE bit */ -#define TPE_BitNumber 0x00 -#define CR_TPE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPE_BitNumber * 4)) - -/* --- CSR Register ---*/ - -/* Alias word address of TPIE bit */ -#define CSR_OFFSET (BKP_OFFSET + 0x34) -#define TPIE_BitNumber 0x02 -#define CSR_TPIE_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TPIE_BitNumber * 4)) - -/* Alias word address of TIF bit */ -#define TIF_BitNumber 0x09 -#define CSR_TIF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TIF_BitNumber * 4)) - -/* Alias word address of TEF bit */ -#define TEF_BitNumber 0x08 -#define CSR_TEF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEF_BitNumber * 4)) - -/* ---------------------- BKP registers bit mask ------------------------ */ - -/* RTCCR register bit mask */ -#define RTCCR_CAL_MASK ((uint16_t)0xFF80) -#define RTCCR_MASK ((uint16_t)0xFC7F) - -/** - * @} - */ - - -/** @defgroup BKP_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup BKP_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup BKP_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup BKP_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the BKP peripheral registers to their default reset values. - * @param None - * @retval None - */ -void BKP_DeInit(void) -{ - RCC_BackupResetCmd(ENABLE); - RCC_BackupResetCmd(DISABLE); -} - -/** - * @brief Configures the Tamper Pin active level. - * @param BKP_TamperPinLevel: specifies the Tamper Pin active level. - * This parameter can be one of the following values: - * @arg BKP_TamperPinLevel_High: Tamper pin active on high level - * @arg BKP_TamperPinLevel_Low: Tamper pin active on low level - * @retval None - */ -void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel) -{ - /* Check the parameters */ - assert_param(IS_BKP_TAMPER_PIN_LEVEL(BKP_TamperPinLevel)); - *(__IO uint32_t *) CR_TPAL_BB = BKP_TamperPinLevel; -} - -/** - * @brief Enables or disables the Tamper Pin activation. - * @param NewState: new state of the Tamper Pin activation. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void BKP_TamperPinCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) CR_TPE_BB = (uint32_t)NewState; -} - -/** - * @brief Enables or disables the Tamper Pin Interrupt. - * @param NewState: new state of the Tamper Pin Interrupt. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void BKP_ITConfig(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) CSR_TPIE_BB = (uint32_t)NewState; -} - -/** - * @brief Select the RTC output source to output on the Tamper pin. - * @param BKP_RTCOutputSource: specifies the RTC output source. - * This parameter can be one of the following values: - * @arg BKP_RTCOutputSource_None: no RTC output on the Tamper pin. - * @arg BKP_RTCOutputSource_CalibClock: output the RTC clock with frequency - * divided by 64 on the Tamper pin. - * @arg BKP_RTCOutputSource_Alarm: output the RTC Alarm pulse signal on - * the Tamper pin. - * @arg BKP_RTCOutputSource_Second: output the RTC Second pulse signal on - * the Tamper pin. - * @retval None - */ -void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource) -{ - uint16_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_BKP_RTC_OUTPUT_SOURCE(BKP_RTCOutputSource)); - tmpreg = BKP->RTCCR; - /* Clear CCO, ASOE and ASOS bits */ - tmpreg &= RTCCR_MASK; - - /* Set CCO, ASOE and ASOS bits according to BKP_RTCOutputSource value */ - tmpreg |= BKP_RTCOutputSource; - /* Store the new value */ - BKP->RTCCR = tmpreg; -} - -/** - * @brief Sets RTC Clock Calibration value. - * @param CalibrationValue: specifies the RTC Clock Calibration value. - * This parameter must be a number between 0 and 0x7F. - * @retval None - */ -void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue) -{ - uint16_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_BKP_CALIBRATION_VALUE(CalibrationValue)); - tmpreg = BKP->RTCCR; - /* Clear CAL[6:0] bits */ - tmpreg &= RTCCR_CAL_MASK; - /* Set CAL[6:0] bits according to CalibrationValue value */ - tmpreg |= CalibrationValue; - /* Store the new value */ - BKP->RTCCR = tmpreg; -} - -/** - * @brief Writes user data to the specified Data Backup Register. - * @param BKP_DR: specifies the Data Backup Register. - * This parameter can be BKP_DRx where x:[1, 42] - * @param Data: data to write - * @retval None - */ -void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data) -{ - __IO uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_BKP_DR(BKP_DR)); - - tmp = (uint32_t)BKP_BASE; - tmp += BKP_DR; - - *(__IO uint32_t *) tmp = Data; -} - -/** - * @brief Reads data from the specified Data Backup Register. - * @param BKP_DR: specifies the Data Backup Register. - * This parameter can be BKP_DRx where x:[1, 42] - * @retval The content of the specified Data Backup Register - */ -uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR) -{ - __IO uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_BKP_DR(BKP_DR)); - - tmp = (uint32_t)BKP_BASE; - tmp += BKP_DR; - - return (*(__IO uint16_t *) tmp); -} - -/** - * @brief Checks whether the Tamper Pin Event flag is set or not. - * @param None - * @retval The new state of the Tamper Pin Event flag (SET or RESET). - */ -FlagStatus BKP_GetFlagStatus(void) -{ - return (FlagStatus)(*(__IO uint32_t *) CSR_TEF_BB); -} - -/** - * @brief Clears Tamper Pin Event pending flag. - * @param None - * @retval None - */ -void BKP_ClearFlag(void) -{ - /* Set CTE bit to clear Tamper Pin Event flag */ - BKP->CSR |= BKP_CSR_CTE; -} - -/** - * @brief Checks whether the Tamper Pin Interrupt has occurred or not. - * @param None - * @retval The new state of the Tamper Pin Interrupt (SET or RESET). - */ -ITStatus BKP_GetITStatus(void) -{ - return (ITStatus)(*(__IO uint32_t *) CSR_TIF_BB); -} - -/** - * @brief Clears Tamper Pin Interrupt pending bit. - * @param None - * @retval None - */ -void BKP_ClearITPendingBit(void) -{ - /* Set CTI bit to clear Tamper Pin Interrupt pending bit */ - BKP->CSR |= BKP_CSR_CTI; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_bkp.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the BKP firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_bkp.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup BKP + * @brief BKP driver modules + * @{ + */ + +/** @defgroup BKP_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_Defines + * @{ + */ + +/* ------------ BKP registers bit address in the alias region --------------- */ +#define BKP_OFFSET (BKP_BASE - PERIPH_BASE) + +/* --- CR Register ----*/ + +/* Alias word address of TPAL bit */ +#define CR_OFFSET (BKP_OFFSET + 0x30) +#define TPAL_BitNumber 0x01 +#define CR_TPAL_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPAL_BitNumber * 4)) + +/* Alias word address of TPE bit */ +#define TPE_BitNumber 0x00 +#define CR_TPE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPE_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of TPIE bit */ +#define CSR_OFFSET (BKP_OFFSET + 0x34) +#define TPIE_BitNumber 0x02 +#define CSR_TPIE_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TPIE_BitNumber * 4)) + +/* Alias word address of TIF bit */ +#define TIF_BitNumber 0x09 +#define CSR_TIF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TIF_BitNumber * 4)) + +/* Alias word address of TEF bit */ +#define TEF_BitNumber 0x08 +#define CSR_TEF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEF_BitNumber * 4)) + +/* ---------------------- BKP registers bit mask ------------------------ */ + +/* RTCCR register bit mask */ +#define RTCCR_CAL_MASK ((uint16_t)0xFF80) +#define RTCCR_MASK ((uint16_t)0xFC7F) + +/** + * @} + */ + + +/** @defgroup BKP_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the BKP peripheral registers to their default reset values. + * @param None + * @retval None + */ +void BKP_DeInit(void) +{ + RCC_BackupResetCmd(ENABLE); + RCC_BackupResetCmd(DISABLE); +} + +/** + * @brief Configures the Tamper Pin active level. + * @param BKP_TamperPinLevel: specifies the Tamper Pin active level. + * This parameter can be one of the following values: + * @arg BKP_TamperPinLevel_High: Tamper pin active on high level + * @arg BKP_TamperPinLevel_Low: Tamper pin active on low level + * @retval None + */ +void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel) +{ + /* Check the parameters */ + assert_param(IS_BKP_TAMPER_PIN_LEVEL(BKP_TamperPinLevel)); + *(__IO uint32_t *) CR_TPAL_BB = BKP_TamperPinLevel; +} + +/** + * @brief Enables or disables the Tamper Pin activation. + * @param NewState: new state of the Tamper Pin activation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void BKP_TamperPinCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_TPE_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the Tamper Pin Interrupt. + * @param NewState: new state of the Tamper Pin Interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void BKP_ITConfig(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CSR_TPIE_BB = (uint32_t)NewState; +} + +/** + * @brief Select the RTC output source to output on the Tamper pin. + * @param BKP_RTCOutputSource: specifies the RTC output source. + * This parameter can be one of the following values: + * @arg BKP_RTCOutputSource_None: no RTC output on the Tamper pin. + * @arg BKP_RTCOutputSource_CalibClock: output the RTC clock with frequency + * divided by 64 on the Tamper pin. + * @arg BKP_RTCOutputSource_Alarm: output the RTC Alarm pulse signal on + * the Tamper pin. + * @arg BKP_RTCOutputSource_Second: output the RTC Second pulse signal on + * the Tamper pin. + * @retval None + */ +void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource) +{ + uint16_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_BKP_RTC_OUTPUT_SOURCE(BKP_RTCOutputSource)); + tmpreg = BKP->RTCCR; + /* Clear CCO, ASOE and ASOS bits */ + tmpreg &= RTCCR_MASK; + + /* Set CCO, ASOE and ASOS bits according to BKP_RTCOutputSource value */ + tmpreg |= BKP_RTCOutputSource; + /* Store the new value */ + BKP->RTCCR = tmpreg; +} + +/** + * @brief Sets RTC Clock Calibration value. + * @param CalibrationValue: specifies the RTC Clock Calibration value. + * This parameter must be a number between 0 and 0x7F. + * @retval None + */ +void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue) +{ + uint16_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_BKP_CALIBRATION_VALUE(CalibrationValue)); + tmpreg = BKP->RTCCR; + /* Clear CAL[6:0] bits */ + tmpreg &= RTCCR_CAL_MASK; + /* Set CAL[6:0] bits according to CalibrationValue value */ + tmpreg |= CalibrationValue; + /* Store the new value */ + BKP->RTCCR = tmpreg; +} + +/** + * @brief Writes user data to the specified Data Backup Register. + * @param BKP_DR: specifies the Data Backup Register. + * This parameter can be BKP_DRx where x:[1, 42] + * @param Data: data to write + * @retval None + */ +void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_BKP_DR(BKP_DR)); + + tmp = (uint32_t)BKP_BASE; + tmp += BKP_DR; + + *(__IO uint32_t *) tmp = Data; +} + +/** + * @brief Reads data from the specified Data Backup Register. + * @param BKP_DR: specifies the Data Backup Register. + * This parameter can be BKP_DRx where x:[1, 42] + * @retval The content of the specified Data Backup Register + */ +uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_BKP_DR(BKP_DR)); + + tmp = (uint32_t)BKP_BASE; + tmp += BKP_DR; + + return (*(__IO uint16_t *) tmp); +} + +/** + * @brief Checks whether the Tamper Pin Event flag is set or not. + * @param None + * @retval The new state of the Tamper Pin Event flag (SET or RESET). + */ +FlagStatus BKP_GetFlagStatus(void) +{ + return (FlagStatus)(*(__IO uint32_t *) CSR_TEF_BB); +} + +/** + * @brief Clears Tamper Pin Event pending flag. + * @param None + * @retval None + */ +void BKP_ClearFlag(void) +{ + /* Set CTE bit to clear Tamper Pin Event flag */ + BKP->CSR |= BKP_CSR_CTE; +} + +/** + * @brief Checks whether the Tamper Pin Interrupt has occurred or not. + * @param None + * @retval The new state of the Tamper Pin Interrupt (SET or RESET). + */ +ITStatus BKP_GetITStatus(void) +{ + return (ITStatus)(*(__IO uint32_t *) CSR_TIF_BB); +} + +/** + * @brief Clears Tamper Pin Interrupt pending bit. + * @param None + * @retval None + */ +void BKP_ClearITPendingBit(void) +{ + /* Set CTI bit to clear Tamper Pin Interrupt pending bit */ + BKP->CSR |= BKP_CSR_CTI; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c index 043819a6f..dfbc158eb 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c @@ -1,1166 +1,1166 @@ -/** - ****************************************************************************** - * @file stm32f10x_can.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the CAN firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_can.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup CAN - * @brief CAN driver modules - * @{ - */ - -/** @defgroup CAN_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup CAN_Private_Defines - * @{ - */ - -/* CAN Master Control Register bits */ - -#define MCR_DBF ((uint32_t)0x00010000) /* software master reset */ - -/* CAN Mailbox Transmit Request */ -#define TMIDxR_TXRQ ((uint32_t)0x00000001) /* Transmit mailbox request */ - -/* CAN Filter Master Register bits */ -#define FMR_FINIT ((uint32_t)0x00000001) /* Filter init mode */ - -/* Time out for INAK bit */ -#define INAK_TIMEOUT ((uint32_t)0x0000FFFF) -/* Time out for SLAK bit */ -#define SLAK_TIMEOUT ((uint32_t)0x0000FFFF) - - - -/* Flags in TSR register */ -#define CAN_FLAGS_TSR ((uint32_t)0x08000000) -/* Flags in RF1R register */ -#define CAN_FLAGS_RF1R ((uint32_t)0x04000000) -/* Flags in RF0R register */ -#define CAN_FLAGS_RF0R ((uint32_t)0x02000000) -/* Flags in MSR register */ -#define CAN_FLAGS_MSR ((uint32_t)0x01000000) -/* Flags in ESR register */ -#define CAN_FLAGS_ESR ((uint32_t)0x00F00000) - - -/** - * @} - */ - -/** @defgroup CAN_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup CAN_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup CAN_Private_FunctionPrototypes - * @{ - */ - -static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit); - -/** - * @} - */ - -/** @defgroup CAN_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the CAN peripheral registers to their default reset values. - * @param CANx: where x can be 1 or 2 to select the CAN peripheral. - * @retval None. - */ -void CAN_DeInit(CAN_TypeDef* CANx) -{ - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - - if (CANx == CAN1) - { - /* Enable CAN1 reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, ENABLE); - /* Release CAN1 from reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, DISABLE); - } - else - { - /* Enable CAN2 reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, ENABLE); - /* Release CAN2 from reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, DISABLE); - } -} - -/** - * @brief Initializes the CAN peripheral according to the specified - * parameters in the CAN_InitStruct. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure that - * contains the configuration information for the CAN peripheral. - * @retval Constant indicates initialization succeed which will be - * CANINITFAILED or CANINITOK. - */ -uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct) -{ - uint8_t InitStatus = CANINITFAILED; - uint32_t wait_ack = 0x00000000; - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TTCM)); - assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_ABOM)); - assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_AWUM)); - assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_NART)); - assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_RFLM)); - assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TXFP)); - assert_param(IS_CAN_MODE(CAN_InitStruct->CAN_Mode)); - assert_param(IS_CAN_SJW(CAN_InitStruct->CAN_SJW)); - assert_param(IS_CAN_BS1(CAN_InitStruct->CAN_BS1)); - assert_param(IS_CAN_BS2(CAN_InitStruct->CAN_BS2)); - assert_param(IS_CAN_PRESCALER(CAN_InitStruct->CAN_Prescaler)); - - /* exit from sleep mode */ - CANx->MCR &= (~(uint32_t)CAN_MCR_SLEEP); - - /* Request initialisation */ - CANx->MCR |= CAN_MCR_INRQ ; - - /* Wait the acknowledge */ - while (((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) - { - wait_ack++; - } - - /* ...and check acknowledged */ - if ((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) - { - InitStatus = CANINITFAILED; - } - else - { - /* Set the time triggered communication mode */ - if (CAN_InitStruct->CAN_TTCM == ENABLE) - { - CANx->MCR |= CAN_MCR_TTCM; - } - else - { - CANx->MCR &= ~(uint32_t)CAN_MCR_TTCM; - } - - /* Set the automatic bus-off management */ - if (CAN_InitStruct->CAN_ABOM == ENABLE) - { - CANx->MCR |= CAN_MCR_ABOM; - } - else - { - CANx->MCR &= ~(uint32_t)CAN_MCR_ABOM; - } - - /* Set the automatic wake-up mode */ - if (CAN_InitStruct->CAN_AWUM == ENABLE) - { - CANx->MCR |= CAN_MCR_AWUM; - } - else - { - CANx->MCR &= ~(uint32_t)CAN_MCR_AWUM; - } - - /* Set the no automatic retransmission */ - if (CAN_InitStruct->CAN_NART == ENABLE) - { - CANx->MCR |= CAN_MCR_NART; - } - else - { - CANx->MCR &= ~(uint32_t)CAN_MCR_NART; - } - - /* Set the receive FIFO locked mode */ - if (CAN_InitStruct->CAN_RFLM == ENABLE) - { - CANx->MCR |= CAN_MCR_RFLM; - } - else - { - CANx->MCR &= ~(uint32_t)CAN_MCR_RFLM; - } - - /* Set the transmit FIFO priority */ - if (CAN_InitStruct->CAN_TXFP == ENABLE) - { - CANx->MCR |= CAN_MCR_TXFP; - } - else - { - CANx->MCR &= ~(uint32_t)CAN_MCR_TXFP; - } - - /* Set the bit timing register */ - CANx->BTR = (uint32_t)((uint32_t)CAN_InitStruct->CAN_Mode << 30) | ((uint32_t)CAN_InitStruct->CAN_SJW << 24) | - ((uint32_t)CAN_InitStruct->CAN_BS1 << 16) | ((uint32_t)CAN_InitStruct->CAN_BS2 << 20) | - ((uint32_t)CAN_InitStruct->CAN_Prescaler - 1); - - /* Request leave initialisation */ - CANx->MCR &= ~(uint32_t)CAN_MCR_INRQ; - - /* Wait the acknowledge */ - wait_ack = 0x00; - - while (((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) - { - wait_ack++; - } - - /* ...and check acknowledged */ - if ((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) - { - InitStatus = CANINITFAILED; - } - else - { - InitStatus = CANINITOK ; - } - } - - /* At this step, return the status of initialization */ - return InitStatus; -} - -/** - * @brief Initializes the CAN peripheral according to the specified - * parameters in the CAN_FilterInitStruct. - * @param CAN_FilterInitStruct: pointer to a CAN_FilterInitTypeDef - * structure that contains the configuration information. - * @retval None. - */ -void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct) -{ - uint32_t filter_number_bit_pos = 0; - /* Check the parameters */ - assert_param(IS_CAN_FILTER_NUMBER(CAN_FilterInitStruct->CAN_FilterNumber)); - assert_param(IS_CAN_FILTER_MODE(CAN_FilterInitStruct->CAN_FilterMode)); - assert_param(IS_CAN_FILTER_SCALE(CAN_FilterInitStruct->CAN_FilterScale)); - assert_param(IS_CAN_FILTER_FIFO(CAN_FilterInitStruct->CAN_FilterFIFOAssignment)); - assert_param(IS_FUNCTIONAL_STATE(CAN_FilterInitStruct->CAN_FilterActivation)); - - filter_number_bit_pos = ((uint32_t)0x00000001) << CAN_FilterInitStruct->CAN_FilterNumber; - - /* Initialisation mode for the filter */ - CAN1->FMR |= FMR_FINIT; - - /* Filter Deactivation */ - CAN1->FA1R &= ~(uint32_t)filter_number_bit_pos; - - /* Filter Scale */ - if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_16bit) - { - /* 16-bit scale for the filter */ - CAN1->FS1R &= ~(uint32_t)filter_number_bit_pos; - - /* First 16-bit identifier and First 16-bit mask */ - /* Or First 16-bit identifier and Second 16-bit identifier */ - CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = - ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow) << 16) | - (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); - - /* Second 16-bit identifier and Second 16-bit mask */ - /* Or Third 16-bit identifier and Fourth 16-bit identifier */ - CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = - ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | - (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh); - } - - if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_32bit) - { - /* 32-bit scale for the filter */ - CAN1->FS1R |= filter_number_bit_pos; - /* 32-bit identifier or First 32-bit identifier */ - CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = - ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh) << 16) | - (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); - /* 32-bit mask or Second 32-bit identifier */ - CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = - ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | - (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow); - } - - /* Filter Mode */ - if (CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdMask) - { - /*Id/Mask mode for the filter*/ - CAN1->FM1R &= ~(uint32_t)filter_number_bit_pos; - } - else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ - { - /*Identifier list mode for the filter*/ - CAN1->FM1R |= (uint32_t)filter_number_bit_pos; - } - - /* Filter FIFO assignment */ - if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_FilterFIFO0) - { - /* FIFO 0 assignation for the filter */ - CAN1->FFA1R &= ~(uint32_t)filter_number_bit_pos; - } - - if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_FilterFIFO1) - { - /* FIFO 1 assignation for the filter */ - CAN1->FFA1R |= (uint32_t)filter_number_bit_pos; - } - - /* Filter activation */ - if (CAN_FilterInitStruct->CAN_FilterActivation == ENABLE) - { - CAN1->FA1R |= filter_number_bit_pos; - } - - /* Leave the initialisation mode for the filter */ - CAN1->FMR &= ~FMR_FINIT; -} - -/** - * @brief Fills each CAN_InitStruct member with its default value. - * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure which - * will be initialized. - * @retval None. - */ -void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct) -{ - /* Reset CAN init structure parameters values */ - /* Initialize the time triggered communication mode */ - CAN_InitStruct->CAN_TTCM = DISABLE; - /* Initialize the automatic bus-off management */ - CAN_InitStruct->CAN_ABOM = DISABLE; - /* Initialize the automatic wake-up mode */ - CAN_InitStruct->CAN_AWUM = DISABLE; - /* Initialize the no automatic retransmission */ - CAN_InitStruct->CAN_NART = DISABLE; - /* Initialize the receive FIFO locked mode */ - CAN_InitStruct->CAN_RFLM = DISABLE; - /* Initialize the transmit FIFO priority */ - CAN_InitStruct->CAN_TXFP = DISABLE; - /* Initialize the CAN_Mode member */ - CAN_InitStruct->CAN_Mode = CAN_Mode_Normal; - /* Initialize the CAN_SJW member */ - CAN_InitStruct->CAN_SJW = CAN_SJW_1tq; - /* Initialize the CAN_BS1 member */ - CAN_InitStruct->CAN_BS1 = CAN_BS1_4tq; - /* Initialize the CAN_BS2 member */ - CAN_InitStruct->CAN_BS2 = CAN_BS2_3tq; - /* Initialize the CAN_Prescaler member */ - CAN_InitStruct->CAN_Prescaler = 1; -} - -/** - * @brief Select the start bank filter for slave CAN. - * @note This function applies only to STM32 Connectivity line devices. - * @param CAN_BankNumber: Select the start slave bank filter from 1..27. - * @retval None. - */ -void CAN_SlaveStartBank(uint8_t CAN_BankNumber) -{ - /* Check the parameters */ - assert_param(IS_CAN_BANKNUMBER(CAN_BankNumber)); - /* enter Initialisation mode for the filter */ - CAN1->FMR |= FMR_FINIT; - /* Select the start slave bank */ - CAN1->FMR &= (uint32_t)0xFFFFC0F1 ; - CAN1->FMR |= (uint32_t)(CAN_BankNumber)<<8; - /* Leave Initialisation mode for the filter */ - CAN1->FMR &= ~FMR_FINIT; -} - -/** - * @brief Enables or disables the specified CANx interrupts. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param CAN_IT: specifies the CAN interrupt sources to be enabled or disabled. - * This parameter can be: - * -CAN_IT_TME, - * -CAN_IT_FMP0, - * -CAN_IT_FF0, - * -CAN_IT_FOV0, - * -CAN_IT_FMP1, - * -CAN_IT_FF1, - * -CAN_IT_FOV1, - * -CAN_IT_EWG, - * -CAN_IT_EPV, - * -CAN_IT_LEC, - * -CAN_IT_ERR, - * -CAN_IT_WKU or - * -CAN_IT_SLK. - * @param NewState: new state of the CAN interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None. - */ -void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_IT(CAN_IT)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the selected CANx interrupt */ - CANx->IER |= CAN_IT; - } - else - { - /* Disable the selected CANx interrupt */ - CANx->IER &= ~CAN_IT; - } -} - -/** - * @brief Initiates the transmission of a message. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param TxMessage: pointer to a structure which contains CAN Id, CAN - * DLC and CAN datas. - * @retval The number of the mailbox that is used for transmission - * or CAN_NO_MB if there is no empty mailbox. - */ -uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage) -{ - uint8_t transmit_mailbox = 0; - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_IDTYPE(TxMessage->IDE)); - assert_param(IS_CAN_RTR(TxMessage->RTR)); - assert_param(IS_CAN_DLC(TxMessage->DLC)); - - /* Select one empty transmit mailbox */ - if ((CANx->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) - { - transmit_mailbox = 0; - } - else if ((CANx->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) - { - transmit_mailbox = 1; - } - else if ((CANx->TSR&CAN_TSR_TME2) == CAN_TSR_TME2) - { - transmit_mailbox = 2; - } - else - { - transmit_mailbox = CAN_NO_MB; - } - - if (transmit_mailbox != CAN_NO_MB) - { - /* Set up the Id */ - CANx->sTxMailBox[transmit_mailbox].TIR &= TMIDxR_TXRQ; - if (TxMessage->IDE == CAN_ID_STD) - { - assert_param(IS_CAN_STDID(TxMessage->StdId)); - CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->StdId << 21) | TxMessage->RTR); - } - else - { - assert_param(IS_CAN_EXTID(TxMessage->ExtId)); - CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->ExtId<<3) | TxMessage->IDE | - TxMessage->RTR); - } - - - /* Set up the DLC */ - TxMessage->DLC &= (uint8_t)0x0000000F; - CANx->sTxMailBox[transmit_mailbox].TDTR &= (uint32_t)0xFFFFFFF0; - CANx->sTxMailBox[transmit_mailbox].TDTR |= TxMessage->DLC; - - /* Set up the data field */ - CANx->sTxMailBox[transmit_mailbox].TDLR = (((uint32_t)TxMessage->Data[3] << 24) | - ((uint32_t)TxMessage->Data[2] << 16) | - ((uint32_t)TxMessage->Data[1] << 8) | - ((uint32_t)TxMessage->Data[0])); - CANx->sTxMailBox[transmit_mailbox].TDHR = (((uint32_t)TxMessage->Data[7] << 24) | - ((uint32_t)TxMessage->Data[6] << 16) | - ((uint32_t)TxMessage->Data[5] << 8) | - ((uint32_t)TxMessage->Data[4])); - /* Request transmission */ - CANx->sTxMailBox[transmit_mailbox].TIR |= TMIDxR_TXRQ; - } - return transmit_mailbox; -} - -/** - * @brief Checks the transmission of a message. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param TransmitMailbox: the number of the mailbox that is used for transmission. - * @retval CANTXOK if the CAN driver transmits the message, CANTXFAILED in an other case. - */ -uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox) -{ - /* RQCP, TXOK and TME bits */ - uint8_t state = 0; - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_TRANSMITMAILBOX(TransmitMailbox)); - switch (TransmitMailbox) - { - case (0): state |= (uint8_t)((CANx->TSR & CAN_TSR_RQCP0) << 2); - state |= (uint8_t)((CANx->TSR & CAN_TSR_TXOK0) >> 0); - state |= (uint8_t)((CANx->TSR & CAN_TSR_TME0) >> 26); - break; - case (1): state |= (uint8_t)((CANx->TSR & CAN_TSR_RQCP1) >> 6); - state |= (uint8_t)((CANx->TSR & CAN_TSR_TXOK1) >> 8); - state |= (uint8_t)((CANx->TSR & CAN_TSR_TME1) >> 27); - break; - case (2): state |= (uint8_t)((CANx->TSR & CAN_TSR_RQCP2) >> 14); - state |= (uint8_t)((CANx->TSR & CAN_TSR_TXOK2) >> 16); - state |= (uint8_t)((CANx->TSR & CAN_TSR_TME2) >> 28); - break; - default: - state = CANTXFAILED; - break; - } - switch (state) - { - /* transmit pending */ - case (0x0): state = CANTXPENDING; - break; - /* transmit failed */ - case (0x5): state = CANTXFAILED; - break; - /* transmit succedeed */ - case (0x7): state = CANTXOK; - break; - default: - state = CANTXFAILED; - break; - } - return state; -} - -/** - * @brief Cancels a transmit request. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param Mailbox: Mailbox number. - * @retval None. - */ -void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox) -{ - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_TRANSMITMAILBOX(Mailbox)); - /* abort transmission */ - switch (Mailbox) - { - case (0): CANx->TSR |= CAN_TSR_ABRQ0; - break; - case (1): CANx->TSR |= CAN_TSR_ABRQ1; - break; - case (2): CANx->TSR |= CAN_TSR_ABRQ2; - break; - default: - break; - } -} - -/** - * @brief Releases a FIFO. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param FIFONumber: FIFO to release, CAN_FIFO0 or CAN_FIFO1. - * @retval None. - */ -void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber) -{ - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_FIFO(FIFONumber)); - /* Release FIFO0 */ - if (FIFONumber == CAN_FIFO0) - { - CANx->RF0R |= CAN_RF0R_RFOM0; - } - /* Release FIFO1 */ - else /* FIFONumber == CAN_FIFO1 */ - { - CANx->RF1R |= CAN_RF1R_RFOM1; - } -} - -/** - * @brief Returns the number of pending messages. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. - * @retval NbMessage which is the number of pending message. - */ -uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber) -{ - uint8_t message_pending=0; - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_FIFO(FIFONumber)); - if (FIFONumber == CAN_FIFO0) - { - message_pending = (uint8_t)(CANx->RF0R&(uint32_t)0x03); - } - else if (FIFONumber == CAN_FIFO1) - { - message_pending = (uint8_t)(CANx->RF1R&(uint32_t)0x03); - } - else - { - message_pending = 0; - } - return message_pending; -} - -/** - * @brief Receives a message. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. - * @param RxMessage: pointer to a structure receive message which - * contains CAN Id, CAN DLC, CAN datas and FMI number. - * @retval None. - */ -void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage) -{ - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_FIFO(FIFONumber)); - /* Get the Id */ - RxMessage->IDE = (uint8_t)0x04 & CANx->sFIFOMailBox[FIFONumber].RIR; - if (RxMessage->IDE == CAN_ID_STD) - { - RxMessage->StdId = (uint32_t)0x000007FF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 21); - } - else - { - RxMessage->ExtId = (uint32_t)0x1FFFFFFF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 3); - } - - RxMessage->RTR = (uint8_t)0x02 & CANx->sFIFOMailBox[FIFONumber].RIR; - /* Get the DLC */ - RxMessage->DLC = (uint8_t)0x0F & CANx->sFIFOMailBox[FIFONumber].RDTR; - /* Get the FMI */ - RxMessage->FMI = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDTR >> 8); - /* Get the data field */ - RxMessage->Data[0] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDLR; - RxMessage->Data[1] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 8); - RxMessage->Data[2] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 16); - RxMessage->Data[3] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 24); - RxMessage->Data[4] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDHR; - RxMessage->Data[5] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 8); - RxMessage->Data[6] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 16); - RxMessage->Data[7] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 24); - /* Release the FIFO */ - CAN_FIFORelease(CANx, FIFONumber); -} - -/** - * @brief Enables or disables the DBG Freeze for CAN. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param NewState: new state of the CAN peripheral. - * This parameter can be: ENABLE or DISABLE. - * @retval None. - */ -void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable Debug Freeze */ - CANx->MCR |= MCR_DBF; - } - else - { - /* Disable Debug Freeze */ - CANx->MCR &= ~MCR_DBF; - } -} - -/** - * @brief Enters the low power mode. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @retval CANSLEEPOK if sleep entered, CANSLEEPFAILED in an other case. - */ -uint8_t CAN_Sleep(CAN_TypeDef* CANx) -{ - uint8_t sleepstatus = CANSLEEPFAILED; - - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - - /* Request Sleep mode */ - CANx->MCR = (((CANx->MCR) & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); - - /* Sleep mode status */ - if ((CANx->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) == CAN_MSR_SLAK) - { - /* Sleep mode not entered */ - sleepstatus = CANSLEEPOK; - } - /* At this step, sleep mode status */ - return (uint8_t)sleepstatus; -} - -/** - * @brief Wakes the CAN up. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @retval CANWAKEUPOK if sleep mode left, CANWAKEUPFAILED in an other case. - */ -uint8_t CAN_WakeUp(CAN_TypeDef* CANx) -{ - uint32_t wait_slak = SLAK_TIMEOUT; - uint8_t wakeupstatus = CANWAKEUPFAILED; - - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - - /* Wake up request */ - CANx->MCR &= ~(uint32_t)CAN_MCR_SLEEP; - - /* Sleep mode status */ - while(((CANx->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK)&&(wait_slak!=0x00)) - { - wait_slak--; - } - if((CANx->MSR & CAN_MSR_SLAK) != CAN_MSR_SLAK) - { - /* Sleep mode exited */ - wakeupstatus = CANWAKEUPOK; - } - /* At this step, sleep mode status */ - return (uint8_t)wakeupstatus; -} - -/** - * @brief Checks whether the specified CAN flag is set or not. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param CAN_FLAG: specifies the flag to check. - * This parameter can be one of the following flags: - * - CAN_FLAG_EWG - * - CAN_FLAG_EPV - * - CAN_FLAG_BOF - * - CAN_FLAG_RQCP0 - * - CAN_FLAG_RQCP1 - * - CAN_FLAG_RQCP2 - * - CAN_FLAG_FMP1 - * - CAN_FLAG_FF1 - * - CAN_FLAG_FOV1 - * - CAN_FLAG_FMP0 - * - CAN_FLAG_FF0 - * - CAN_FLAG_FOV0 - * - CAN_FLAG_WKU - * - CAN_FLAG_SLAK - * - CAN_FLAG_LEC - * @retval The new state of CAN_FLAG (SET or RESET). - */ -FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG) -{ - FlagStatus bitstatus = RESET; - - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_GET_FLAG(CAN_FLAG)); - - - if((CAN_FLAG & CAN_FLAGS_ESR) != (uint32_t)RESET) - { - /* Check the status of the specified CAN flag */ - if ((CANx->ESR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) - { - /* CAN_FLAG is set */ - bitstatus = SET; - } - else - { - /* CAN_FLAG is reset */ - bitstatus = RESET; - } - } - else if((CAN_FLAG & CAN_FLAGS_MSR) != (uint32_t)RESET) - { - /* Check the status of the specified CAN flag */ - if ((CANx->MSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) - { - /* CAN_FLAG is set */ - bitstatus = SET; - } - else - { - /* CAN_FLAG is reset */ - bitstatus = RESET; - } - } - else if((CAN_FLAG & CAN_FLAGS_TSR) != (uint32_t)RESET) - { - /* Check the status of the specified CAN flag */ - if ((CANx->TSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) - { - /* CAN_FLAG is set */ - bitstatus = SET; - } - else - { - /* CAN_FLAG is reset */ - bitstatus = RESET; - } - } - else if((CAN_FLAG & CAN_FLAGS_RF0R) != (uint32_t)RESET) - { - /* Check the status of the specified CAN flag */ - if ((CANx->RF0R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) - { - /* CAN_FLAG is set */ - bitstatus = SET; - } - else - { - /* CAN_FLAG is reset */ - bitstatus = RESET; - } - } - else /* If(CAN_FLAG & CAN_FLAGS_RF1R != (uint32_t)RESET) */ - { - /* Check the status of the specified CAN flag */ - if ((uint32_t)(CANx->RF1R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) - { - /* CAN_FLAG is set */ - bitstatus = SET; - } - else - { - /* CAN_FLAG is reset */ - bitstatus = RESET; - } - } - /* Return the CAN_FLAG status */ - return bitstatus; -} - -/** - * @brief Clears the CAN's pending flags. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param CAN_FLAG: specifies the flag to clear. - * This parameter can be one of the following flags: - * - CAN_FLAG_RQCP0 - * - CAN_FLAG_RQCP1 - * - CAN_FLAG_RQCP2 - * - CAN_FLAG_FF1 - * - CAN_FLAG_FOV1 - * - CAN_FLAG_FF0 - * - CAN_FLAG_FOV0 - * - CAN_FLAG_WKU - * - CAN_FLAG_SLAK - * - CAN_FLAG_LEC - * @retval None. - */ -void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG) -{ - uint32_t flagtmp=0; - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_CLEAR_FLAG(CAN_FLAG)); - - if (CAN_FLAG == CAN_FLAG_LEC) /* ESR register */ - { - /* Clear the selected CAN flags */ - CANx->ESR = (uint32_t)RESET; - } - else /* MSR or TSR or RF0R or RF1R */ - { - flagtmp = CAN_FLAG & 0x000FFFFF; - - if ((CAN_FLAG & CAN_FLAGS_RF0R)!=(uint32_t)RESET) - { - /* Receive Flags */ - CANx->RF0R = (uint32_t)(flagtmp); - } - else if ((CAN_FLAG & CAN_FLAGS_RF1R)!=(uint32_t)RESET) - { - /* Receive Flags */ - CANx->RF1R = (uint32_t)(flagtmp); - } - else if ((CAN_FLAG & CAN_FLAGS_TSR)!=(uint32_t)RESET) - { - /* Transmit Flags */ - CANx->TSR = (uint32_t)(flagtmp); - } - else /* If((CAN_FLAG & CAN_FLAGS_MSR)!=(uint32_t)RESET) */ - { - /* Operating mode Flags */ - CANx->MSR = (uint32_t)(flagtmp); - } - } -} - -/** - * @brief Checks whether the specified CANx interrupt has occurred or not. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param CAN_IT: specifies the CAN interrupt source to check. - * This parameter can be one of the following flags: - * - CAN_IT_TME - * - CAN_IT_FMP0 - * - CAN_IT_FF0 - * - CAN_IT_FOV0 - * - CAN_IT_FMP1 - * - CAN_IT_FF1 - * - CAN_IT_FOV1 - * - CAN_IT_WKU - * - CAN_IT_SLK - * - CAN_IT_EWG - * - CAN_IT_EPV - * - CAN_IT_BOF - * - CAN_IT_LEC - * - CAN_IT_ERR - * @retval The current state of CAN_IT (SET or RESET). - */ -ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT) -{ - ITStatus itstatus = RESET; - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_IT(CAN_IT)); - - /* check the enable interrupt bit */ - if((CANx->IER & CAN_IT) != RESET) - { - /* in case the Interrupt is enabled, .... */ - switch (CAN_IT) - { - case CAN_IT_TME: - /* Check CAN_TSR_RQCPx bits */ - itstatus = CheckITStatus(CANx->TSR, CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2); - break; - case CAN_IT_FMP0: - /* Check CAN_RF0R_FMP0 bit */ - itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FMP0); - break; - case CAN_IT_FF0: - /* Check CAN_RF0R_FULL0 bit */ - itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FULL0); - break; - case CAN_IT_FOV0: - /* Check CAN_RF0R_FOVR0 bit */ - itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FOVR0); - break; - case CAN_IT_FMP1: - /* Check CAN_RF1R_FMP1 bit */ - itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FMP1); - break; - case CAN_IT_FF1: - /* Check CAN_RF1R_FULL1 bit */ - itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FULL1); - break; - case CAN_IT_FOV1: - /* Check CAN_RF1R_FOVR1 bit */ - itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FOVR1); - break; - case CAN_IT_WKU: - /* Check CAN_MSR_WKUI bit */ - itstatus = CheckITStatus(CANx->MSR, CAN_MSR_WKUI); - break; - case CAN_IT_SLK: - /* Check CAN_MSR_SLAKI bit */ - itstatus = CheckITStatus(CANx->MSR, CAN_MSR_SLAKI); - break; - case CAN_IT_EWG: - /* Check CAN_ESR_EWGF bit */ - itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EWGF); - break; - case CAN_IT_EPV: - /* Check CAN_ESR_EPVF bit */ - itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EPVF); - break; - case CAN_IT_BOF: - /* Check CAN_ESR_BOFF bit */ - itstatus = CheckITStatus(CANx->ESR, CAN_ESR_BOFF); - break; - case CAN_IT_LEC: - /* Check CAN_ESR_LEC bit */ - itstatus = CheckITStatus(CANx->ESR, CAN_ESR_LEC); - break; - case CAN_IT_ERR: - /* Check CAN_MSR_ERRI, CAN_ESR_EWGF, CAN_ESR_EPVF, CAN_ESR_BOFF and CAN_ESR_LEC bits */ - itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EWGF|CAN_ESR_EPVF|CAN_ESR_BOFF|CAN_ESR_LEC); - itstatus |= CheckITStatus(CANx->MSR, CAN_MSR_ERRI); - break; - default : - /* in case of error, return RESET */ - itstatus = RESET; - break; - } - } - else - { - /* in case the Interrupt is not enabled, return RESET */ - itstatus = RESET; - } - - /* Return the CAN_IT status */ - return itstatus; -} - -/** - * @brief Clears the CANx’s interrupt pending bits. - * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. - * @param CAN_IT: specifies the interrupt pending bit to clear. - * - CAN_IT_TME - * - CAN_IT_FF0 - * - CAN_IT_FOV0 - * - CAN_IT_FF1 - * - CAN_IT_FOV1 - * - CAN_IT_WKU - * - CAN_IT_SLK - * - CAN_IT_EWG - * - CAN_IT_EPV - * - CAN_IT_BOF - * - CAN_IT_LEC - * - CAN_IT_ERR - * @retval None. - */ -void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT) -{ - /* Check the parameters */ - assert_param(IS_CAN_ALL_PERIPH(CANx)); - assert_param(IS_CAN_CLEAR_IT(CAN_IT)); - - switch (CAN_IT) - { - case CAN_IT_TME: - /* Clear CAN_TSR_RQCPx (rc_w1)*/ - CANx->TSR = CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2; - break; - case CAN_IT_FF0: - /* Clear CAN_RF0R_FULL0 (rc_w1)*/ - CANx->RF0R = CAN_RF0R_FULL0; - break; - case CAN_IT_FOV0: - /* Clear CAN_RF0R_FOVR0 (rc_w1)*/ - CANx->RF0R = CAN_RF0R_FOVR0; - break; - case CAN_IT_FF1: - /* Clear CAN_RF1R_FULL1 (rc_w1)*/ - CANx->RF1R = CAN_RF1R_FULL1; - break; - case CAN_IT_FOV1: - /* Clear CAN_RF1R_FOVR1 (rc_w1)*/ - CANx->RF1R = CAN_RF1R_FOVR1; - break; - case CAN_IT_WKU: - /* Clear CAN_MSR_WKUI (rc_w1)*/ - CANx->MSR = CAN_MSR_WKUI; - break; - case CAN_IT_SLK: - /* Clear CAN_MSR_SLAKI (rc_w1)*/ - CANx->MSR = CAN_MSR_SLAKI; - break; - case CAN_IT_EWG: - /* Clear CAN_MSR_ERRI (rc_w1) */ - CANx->MSR = CAN_MSR_ERRI; - /* Note : the corresponding Flag is cleared by hardware depending of the CAN Bus status*/ - break; - case CAN_IT_EPV: - /* Clear CAN_MSR_ERRI (rc_w1) */ - CANx->MSR = CAN_MSR_ERRI; - /* Note : the corresponding Flag is cleared by hardware depending of the CAN Bus status*/ - break; - case CAN_IT_BOF: - /* Clear CAN_MSR_ERRI (rc_w1) */ - CANx->MSR = CAN_MSR_ERRI; - /* Note : the corresponding Flag is cleared by hardware depending of the CAN Bus status*/ - break; - case CAN_IT_LEC: - /* Clear LEC bits */ - CANx->ESR = RESET; - /* Clear CAN_MSR_ERRI (rc_w1) */ - CANx->MSR = CAN_MSR_ERRI; - break; - case CAN_IT_ERR: - /*Clear LEC bits */ - CANx->ESR = RESET; - /* Clear CAN_MSR_ERRI (rc_w1) */ - CANx->MSR = CAN_MSR_ERRI; - /* Note : BOFF, EPVF and EWGF Flags are cleared by hardware depending of the CAN Bus status*/ - break; - default : - break; - } -} - -/** - * @brief Checks whether the CAN interrupt has occurred or not. - * @param CAN_Reg: specifies the CAN interrupt register to check. - * @param It_Bit: specifies the interrupt source bit to check. - * @retval The new state of the CAN Interrupt (SET or RESET). - */ -static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit) -{ - ITStatus pendingbitstatus = RESET; - - if ((CAN_Reg & It_Bit) != (uint32_t)RESET) - { - /* CAN_IT is set */ - pendingbitstatus = SET; - } - else - { - /* CAN_IT is reset */ - pendingbitstatus = RESET; - } - return pendingbitstatus; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_can.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the CAN firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_can.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CAN + * @brief CAN driver modules + * @{ + */ + +/** @defgroup CAN_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Private_Defines + * @{ + */ + +/* CAN Master Control Register bits */ + +#define MCR_DBF ((uint32_t)0x00010000) /* software master reset */ + +/* CAN Mailbox Transmit Request */ +#define TMIDxR_TXRQ ((uint32_t)0x00000001) /* Transmit mailbox request */ + +/* CAN Filter Master Register bits */ +#define FMR_FINIT ((uint32_t)0x00000001) /* Filter init mode */ + +/* Time out for INAK bit */ +#define INAK_TIMEOUT ((uint32_t)0x0000FFFF) +/* Time out for SLAK bit */ +#define SLAK_TIMEOUT ((uint32_t)0x0000FFFF) + + + +/* Flags in TSR register */ +#define CAN_FLAGS_TSR ((uint32_t)0x08000000) +/* Flags in RF1R register */ +#define CAN_FLAGS_RF1R ((uint32_t)0x04000000) +/* Flags in RF0R register */ +#define CAN_FLAGS_RF0R ((uint32_t)0x02000000) +/* Flags in MSR register */ +#define CAN_FLAGS_MSR ((uint32_t)0x01000000) +/* Flags in ESR register */ +#define CAN_FLAGS_ESR ((uint32_t)0x00F00000) + + +/** + * @} + */ + +/** @defgroup CAN_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Private_FunctionPrototypes + * @{ + */ + +static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit); + +/** + * @} + */ + +/** @defgroup CAN_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the CAN peripheral registers to their default reset values. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @retval None. + */ +void CAN_DeInit(CAN_TypeDef* CANx) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + if (CANx == CAN1) + { + /* Enable CAN1 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, ENABLE); + /* Release CAN1 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, DISABLE); + } + else + { + /* Enable CAN2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, ENABLE); + /* Release CAN2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, DISABLE); + } +} + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_InitStruct. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure that + * contains the configuration information for the CAN peripheral. + * @retval Constant indicates initialization succeed which will be + * CANINITFAILED or CANINITOK. + */ +uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct) +{ + uint8_t InitStatus = CANINITFAILED; + uint32_t wait_ack = 0x00000000; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TTCM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_ABOM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_AWUM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_NART)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_RFLM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TXFP)); + assert_param(IS_CAN_MODE(CAN_InitStruct->CAN_Mode)); + assert_param(IS_CAN_SJW(CAN_InitStruct->CAN_SJW)); + assert_param(IS_CAN_BS1(CAN_InitStruct->CAN_BS1)); + assert_param(IS_CAN_BS2(CAN_InitStruct->CAN_BS2)); + assert_param(IS_CAN_PRESCALER(CAN_InitStruct->CAN_Prescaler)); + + /* exit from sleep mode */ + CANx->MCR &= (~(uint32_t)CAN_MCR_SLEEP); + + /* Request initialisation */ + CANx->MCR |= CAN_MCR_INRQ ; + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) + { + wait_ack++; + } + + /* ...and check acknowledged */ + if ((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) + { + InitStatus = CANINITFAILED; + } + else + { + /* Set the time triggered communication mode */ + if (CAN_InitStruct->CAN_TTCM == ENABLE) + { + CANx->MCR |= CAN_MCR_TTCM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_TTCM; + } + + /* Set the automatic bus-off management */ + if (CAN_InitStruct->CAN_ABOM == ENABLE) + { + CANx->MCR |= CAN_MCR_ABOM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_ABOM; + } + + /* Set the automatic wake-up mode */ + if (CAN_InitStruct->CAN_AWUM == ENABLE) + { + CANx->MCR |= CAN_MCR_AWUM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_AWUM; + } + + /* Set the no automatic retransmission */ + if (CAN_InitStruct->CAN_NART == ENABLE) + { + CANx->MCR |= CAN_MCR_NART; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_NART; + } + + /* Set the receive FIFO locked mode */ + if (CAN_InitStruct->CAN_RFLM == ENABLE) + { + CANx->MCR |= CAN_MCR_RFLM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_RFLM; + } + + /* Set the transmit FIFO priority */ + if (CAN_InitStruct->CAN_TXFP == ENABLE) + { + CANx->MCR |= CAN_MCR_TXFP; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_TXFP; + } + + /* Set the bit timing register */ + CANx->BTR = (uint32_t)((uint32_t)CAN_InitStruct->CAN_Mode << 30) | ((uint32_t)CAN_InitStruct->CAN_SJW << 24) | + ((uint32_t)CAN_InitStruct->CAN_BS1 << 16) | ((uint32_t)CAN_InitStruct->CAN_BS2 << 20) | + ((uint32_t)CAN_InitStruct->CAN_Prescaler - 1); + + /* Request leave initialisation */ + CANx->MCR &= ~(uint32_t)CAN_MCR_INRQ; + + /* Wait the acknowledge */ + wait_ack = 0x00; + + while (((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) + { + wait_ack++; + } + + /* ...and check acknowledged */ + if ((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) + { + InitStatus = CANINITFAILED; + } + else + { + InitStatus = CANINITOK ; + } + } + + /* At this step, return the status of initialization */ + return InitStatus; +} + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_FilterInitStruct. + * @param CAN_FilterInitStruct: pointer to a CAN_FilterInitTypeDef + * structure that contains the configuration information. + * @retval None. + */ +void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct) +{ + uint32_t filter_number_bit_pos = 0; + /* Check the parameters */ + assert_param(IS_CAN_FILTER_NUMBER(CAN_FilterInitStruct->CAN_FilterNumber)); + assert_param(IS_CAN_FILTER_MODE(CAN_FilterInitStruct->CAN_FilterMode)); + assert_param(IS_CAN_FILTER_SCALE(CAN_FilterInitStruct->CAN_FilterScale)); + assert_param(IS_CAN_FILTER_FIFO(CAN_FilterInitStruct->CAN_FilterFIFOAssignment)); + assert_param(IS_FUNCTIONAL_STATE(CAN_FilterInitStruct->CAN_FilterActivation)); + + filter_number_bit_pos = ((uint32_t)0x00000001) << CAN_FilterInitStruct->CAN_FilterNumber; + + /* Initialisation mode for the filter */ + CAN1->FMR |= FMR_FINIT; + + /* Filter Deactivation */ + CAN1->FA1R &= ~(uint32_t)filter_number_bit_pos; + + /* Filter Scale */ + if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_16bit) + { + /* 16-bit scale for the filter */ + CAN1->FS1R &= ~(uint32_t)filter_number_bit_pos; + + /* First 16-bit identifier and First 16-bit mask */ + /* Or First 16-bit identifier and Second 16-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); + + /* Second 16-bit identifier and Second 16-bit mask */ + /* Or Third 16-bit identifier and Fourth 16-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh); + } + + if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_32bit) + { + /* 32-bit scale for the filter */ + CAN1->FS1R |= filter_number_bit_pos; + /* 32-bit identifier or First 32-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); + /* 32-bit mask or Second 32-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow); + } + + /* Filter Mode */ + if (CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdMask) + { + /*Id/Mask mode for the filter*/ + CAN1->FM1R &= ~(uint32_t)filter_number_bit_pos; + } + else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ + { + /*Identifier list mode for the filter*/ + CAN1->FM1R |= (uint32_t)filter_number_bit_pos; + } + + /* Filter FIFO assignment */ + if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_FilterFIFO0) + { + /* FIFO 0 assignation for the filter */ + CAN1->FFA1R &= ~(uint32_t)filter_number_bit_pos; + } + + if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_FilterFIFO1) + { + /* FIFO 1 assignation for the filter */ + CAN1->FFA1R |= (uint32_t)filter_number_bit_pos; + } + + /* Filter activation */ + if (CAN_FilterInitStruct->CAN_FilterActivation == ENABLE) + { + CAN1->FA1R |= filter_number_bit_pos; + } + + /* Leave the initialisation mode for the filter */ + CAN1->FMR &= ~FMR_FINIT; +} + +/** + * @brief Fills each CAN_InitStruct member with its default value. + * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure which + * will be initialized. + * @retval None. + */ +void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct) +{ + /* Reset CAN init structure parameters values */ + /* Initialize the time triggered communication mode */ + CAN_InitStruct->CAN_TTCM = DISABLE; + /* Initialize the automatic bus-off management */ + CAN_InitStruct->CAN_ABOM = DISABLE; + /* Initialize the automatic wake-up mode */ + CAN_InitStruct->CAN_AWUM = DISABLE; + /* Initialize the no automatic retransmission */ + CAN_InitStruct->CAN_NART = DISABLE; + /* Initialize the receive FIFO locked mode */ + CAN_InitStruct->CAN_RFLM = DISABLE; + /* Initialize the transmit FIFO priority */ + CAN_InitStruct->CAN_TXFP = DISABLE; + /* Initialize the CAN_Mode member */ + CAN_InitStruct->CAN_Mode = CAN_Mode_Normal; + /* Initialize the CAN_SJW member */ + CAN_InitStruct->CAN_SJW = CAN_SJW_1tq; + /* Initialize the CAN_BS1 member */ + CAN_InitStruct->CAN_BS1 = CAN_BS1_4tq; + /* Initialize the CAN_BS2 member */ + CAN_InitStruct->CAN_BS2 = CAN_BS2_3tq; + /* Initialize the CAN_Prescaler member */ + CAN_InitStruct->CAN_Prescaler = 1; +} + +/** + * @brief Select the start bank filter for slave CAN. + * @note This function applies only to STM32 Connectivity line devices. + * @param CAN_BankNumber: Select the start slave bank filter from 1..27. + * @retval None. + */ +void CAN_SlaveStartBank(uint8_t CAN_BankNumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_BANKNUMBER(CAN_BankNumber)); + /* enter Initialisation mode for the filter */ + CAN1->FMR |= FMR_FINIT; + /* Select the start slave bank */ + CAN1->FMR &= (uint32_t)0xFFFFC0F1 ; + CAN1->FMR |= (uint32_t)(CAN_BankNumber)<<8; + /* Leave Initialisation mode for the filter */ + CAN1->FMR &= ~FMR_FINIT; +} + +/** + * @brief Enables or disables the specified CANx interrupts. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the CAN interrupt sources to be enabled or disabled. + * This parameter can be: + * -CAN_IT_TME, + * -CAN_IT_FMP0, + * -CAN_IT_FF0, + * -CAN_IT_FOV0, + * -CAN_IT_FMP1, + * -CAN_IT_FF1, + * -CAN_IT_FOV1, + * -CAN_IT_EWG, + * -CAN_IT_EPV, + * -CAN_IT_LEC, + * -CAN_IT_ERR, + * -CAN_IT_WKU or + * -CAN_IT_SLK. + * @param NewState: new state of the CAN interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IT(CAN_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected CANx interrupt */ + CANx->IER |= CAN_IT; + } + else + { + /* Disable the selected CANx interrupt */ + CANx->IER &= ~CAN_IT; + } +} + +/** + * @brief Initiates the transmission of a message. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param TxMessage: pointer to a structure which contains CAN Id, CAN + * DLC and CAN datas. + * @retval The number of the mailbox that is used for transmission + * or CAN_NO_MB if there is no empty mailbox. + */ +uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage) +{ + uint8_t transmit_mailbox = 0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IDTYPE(TxMessage->IDE)); + assert_param(IS_CAN_RTR(TxMessage->RTR)); + assert_param(IS_CAN_DLC(TxMessage->DLC)); + + /* Select one empty transmit mailbox */ + if ((CANx->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) + { + transmit_mailbox = 0; + } + else if ((CANx->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) + { + transmit_mailbox = 1; + } + else if ((CANx->TSR&CAN_TSR_TME2) == CAN_TSR_TME2) + { + transmit_mailbox = 2; + } + else + { + transmit_mailbox = CAN_NO_MB; + } + + if (transmit_mailbox != CAN_NO_MB) + { + /* Set up the Id */ + CANx->sTxMailBox[transmit_mailbox].TIR &= TMIDxR_TXRQ; + if (TxMessage->IDE == CAN_ID_STD) + { + assert_param(IS_CAN_STDID(TxMessage->StdId)); + CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->StdId << 21) | TxMessage->RTR); + } + else + { + assert_param(IS_CAN_EXTID(TxMessage->ExtId)); + CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->ExtId<<3) | TxMessage->IDE | + TxMessage->RTR); + } + + + /* Set up the DLC */ + TxMessage->DLC &= (uint8_t)0x0000000F; + CANx->sTxMailBox[transmit_mailbox].TDTR &= (uint32_t)0xFFFFFFF0; + CANx->sTxMailBox[transmit_mailbox].TDTR |= TxMessage->DLC; + + /* Set up the data field */ + CANx->sTxMailBox[transmit_mailbox].TDLR = (((uint32_t)TxMessage->Data[3] << 24) | + ((uint32_t)TxMessage->Data[2] << 16) | + ((uint32_t)TxMessage->Data[1] << 8) | + ((uint32_t)TxMessage->Data[0])); + CANx->sTxMailBox[transmit_mailbox].TDHR = (((uint32_t)TxMessage->Data[7] << 24) | + ((uint32_t)TxMessage->Data[6] << 16) | + ((uint32_t)TxMessage->Data[5] << 8) | + ((uint32_t)TxMessage->Data[4])); + /* Request transmission */ + CANx->sTxMailBox[transmit_mailbox].TIR |= TMIDxR_TXRQ; + } + return transmit_mailbox; +} + +/** + * @brief Checks the transmission of a message. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param TransmitMailbox: the number of the mailbox that is used for transmission. + * @retval CANTXOK if the CAN driver transmits the message, CANTXFAILED in an other case. + */ +uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox) +{ + /* RQCP, TXOK and TME bits */ + uint8_t state = 0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_TRANSMITMAILBOX(TransmitMailbox)); + switch (TransmitMailbox) + { + case (0): state |= (uint8_t)((CANx->TSR & CAN_TSR_RQCP0) << 2); + state |= (uint8_t)((CANx->TSR & CAN_TSR_TXOK0) >> 0); + state |= (uint8_t)((CANx->TSR & CAN_TSR_TME0) >> 26); + break; + case (1): state |= (uint8_t)((CANx->TSR & CAN_TSR_RQCP1) >> 6); + state |= (uint8_t)((CANx->TSR & CAN_TSR_TXOK1) >> 8); + state |= (uint8_t)((CANx->TSR & CAN_TSR_TME1) >> 27); + break; + case (2): state |= (uint8_t)((CANx->TSR & CAN_TSR_RQCP2) >> 14); + state |= (uint8_t)((CANx->TSR & CAN_TSR_TXOK2) >> 16); + state |= (uint8_t)((CANx->TSR & CAN_TSR_TME2) >> 28); + break; + default: + state = CANTXFAILED; + break; + } + switch (state) + { + /* transmit pending */ + case (0x0): state = CANTXPENDING; + break; + /* transmit failed */ + case (0x5): state = CANTXFAILED; + break; + /* transmit succedeed */ + case (0x7): state = CANTXOK; + break; + default: + state = CANTXFAILED; + break; + } + return state; +} + +/** + * @brief Cancels a transmit request. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param Mailbox: Mailbox number. + * @retval None. + */ +void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_TRANSMITMAILBOX(Mailbox)); + /* abort transmission */ + switch (Mailbox) + { + case (0): CANx->TSR |= CAN_TSR_ABRQ0; + break; + case (1): CANx->TSR |= CAN_TSR_ABRQ1; + break; + case (2): CANx->TSR |= CAN_TSR_ABRQ2; + break; + default: + break; + } +} + +/** + * @brief Releases a FIFO. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param FIFONumber: FIFO to release, CAN_FIFO0 or CAN_FIFO1. + * @retval None. + */ +void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + /* Release FIFO0 */ + if (FIFONumber == CAN_FIFO0) + { + CANx->RF0R |= CAN_RF0R_RFOM0; + } + /* Release FIFO1 */ + else /* FIFONumber == CAN_FIFO1 */ + { + CANx->RF1R |= CAN_RF1R_RFOM1; + } +} + +/** + * @brief Returns the number of pending messages. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. + * @retval NbMessage which is the number of pending message. + */ +uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber) +{ + uint8_t message_pending=0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + if (FIFONumber == CAN_FIFO0) + { + message_pending = (uint8_t)(CANx->RF0R&(uint32_t)0x03); + } + else if (FIFONumber == CAN_FIFO1) + { + message_pending = (uint8_t)(CANx->RF1R&(uint32_t)0x03); + } + else + { + message_pending = 0; + } + return message_pending; +} + +/** + * @brief Receives a message. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. + * @param RxMessage: pointer to a structure receive message which + * contains CAN Id, CAN DLC, CAN datas and FMI number. + * @retval None. + */ +void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + /* Get the Id */ + RxMessage->IDE = (uint8_t)0x04 & CANx->sFIFOMailBox[FIFONumber].RIR; + if (RxMessage->IDE == CAN_ID_STD) + { + RxMessage->StdId = (uint32_t)0x000007FF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 21); + } + else + { + RxMessage->ExtId = (uint32_t)0x1FFFFFFF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 3); + } + + RxMessage->RTR = (uint8_t)0x02 & CANx->sFIFOMailBox[FIFONumber].RIR; + /* Get the DLC */ + RxMessage->DLC = (uint8_t)0x0F & CANx->sFIFOMailBox[FIFONumber].RDTR; + /* Get the FMI */ + RxMessage->FMI = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDTR >> 8); + /* Get the data field */ + RxMessage->Data[0] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDLR; + RxMessage->Data[1] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 8); + RxMessage->Data[2] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 16); + RxMessage->Data[3] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 24); + RxMessage->Data[4] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDHR; + RxMessage->Data[5] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 8); + RxMessage->Data[6] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 16); + RxMessage->Data[7] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 24); + /* Release the FIFO */ + CAN_FIFORelease(CANx, FIFONumber); +} + +/** + * @brief Enables or disables the DBG Freeze for CAN. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param NewState: new state of the CAN peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable Debug Freeze */ + CANx->MCR |= MCR_DBF; + } + else + { + /* Disable Debug Freeze */ + CANx->MCR &= ~MCR_DBF; + } +} + +/** + * @brief Enters the low power mode. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval CANSLEEPOK if sleep entered, CANSLEEPFAILED in an other case. + */ +uint8_t CAN_Sleep(CAN_TypeDef* CANx) +{ + uint8_t sleepstatus = CANSLEEPFAILED; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Request Sleep mode */ + CANx->MCR = (((CANx->MCR) & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); + + /* Sleep mode status */ + if ((CANx->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) == CAN_MSR_SLAK) + { + /* Sleep mode not entered */ + sleepstatus = CANSLEEPOK; + } + /* At this step, sleep mode status */ + return (uint8_t)sleepstatus; +} + +/** + * @brief Wakes the CAN up. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval CANWAKEUPOK if sleep mode left, CANWAKEUPFAILED in an other case. + */ +uint8_t CAN_WakeUp(CAN_TypeDef* CANx) +{ + uint32_t wait_slak = SLAK_TIMEOUT; + uint8_t wakeupstatus = CANWAKEUPFAILED; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Wake up request */ + CANx->MCR &= ~(uint32_t)CAN_MCR_SLEEP; + + /* Sleep mode status */ + while(((CANx->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK)&&(wait_slak!=0x00)) + { + wait_slak--; + } + if((CANx->MSR & CAN_MSR_SLAK) != CAN_MSR_SLAK) + { + /* Sleep mode exited */ + wakeupstatus = CANWAKEUPOK; + } + /* At this step, sleep mode status */ + return (uint8_t)wakeupstatus; +} + +/** + * @brief Checks whether the specified CAN flag is set or not. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_FLAG: specifies the flag to check. + * This parameter can be one of the following flags: + * - CAN_FLAG_EWG + * - CAN_FLAG_EPV + * - CAN_FLAG_BOF + * - CAN_FLAG_RQCP0 + * - CAN_FLAG_RQCP1 + * - CAN_FLAG_RQCP2 + * - CAN_FLAG_FMP1 + * - CAN_FLAG_FF1 + * - CAN_FLAG_FOV1 + * - CAN_FLAG_FMP0 + * - CAN_FLAG_FF0 + * - CAN_FLAG_FOV0 + * - CAN_FLAG_WKU + * - CAN_FLAG_SLAK + * - CAN_FLAG_LEC + * @retval The new state of CAN_FLAG (SET or RESET). + */ +FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_GET_FLAG(CAN_FLAG)); + + + if((CAN_FLAG & CAN_FLAGS_ESR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->ESR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_MSR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->MSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_TSR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->TSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_RF0R) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->RF0R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else /* If(CAN_FLAG & CAN_FLAGS_RF1R != (uint32_t)RESET) */ + { + /* Check the status of the specified CAN flag */ + if ((uint32_t)(CANx->RF1R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + /* Return the CAN_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the CAN's pending flags. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_FLAG: specifies the flag to clear. + * This parameter can be one of the following flags: + * - CAN_FLAG_RQCP0 + * - CAN_FLAG_RQCP1 + * - CAN_FLAG_RQCP2 + * - CAN_FLAG_FF1 + * - CAN_FLAG_FOV1 + * - CAN_FLAG_FF0 + * - CAN_FLAG_FOV0 + * - CAN_FLAG_WKU + * - CAN_FLAG_SLAK + * - CAN_FLAG_LEC + * @retval None. + */ +void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG) +{ + uint32_t flagtmp=0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_CLEAR_FLAG(CAN_FLAG)); + + if (CAN_FLAG == CAN_FLAG_LEC) /* ESR register */ + { + /* Clear the selected CAN flags */ + CANx->ESR = (uint32_t)RESET; + } + else /* MSR or TSR or RF0R or RF1R */ + { + flagtmp = CAN_FLAG & 0x000FFFFF; + + if ((CAN_FLAG & CAN_FLAGS_RF0R)!=(uint32_t)RESET) + { + /* Receive Flags */ + CANx->RF0R = (uint32_t)(flagtmp); + } + else if ((CAN_FLAG & CAN_FLAGS_RF1R)!=(uint32_t)RESET) + { + /* Receive Flags */ + CANx->RF1R = (uint32_t)(flagtmp); + } + else if ((CAN_FLAG & CAN_FLAGS_TSR)!=(uint32_t)RESET) + { + /* Transmit Flags */ + CANx->TSR = (uint32_t)(flagtmp); + } + else /* If((CAN_FLAG & CAN_FLAGS_MSR)!=(uint32_t)RESET) */ + { + /* Operating mode Flags */ + CANx->MSR = (uint32_t)(flagtmp); + } + } +} + +/** + * @brief Checks whether the specified CANx interrupt has occurred or not. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the CAN interrupt source to check. + * This parameter can be one of the following flags: + * - CAN_IT_TME + * - CAN_IT_FMP0 + * - CAN_IT_FF0 + * - CAN_IT_FOV0 + * - CAN_IT_FMP1 + * - CAN_IT_FF1 + * - CAN_IT_FOV1 + * - CAN_IT_WKU + * - CAN_IT_SLK + * - CAN_IT_EWG + * - CAN_IT_EPV + * - CAN_IT_BOF + * - CAN_IT_LEC + * - CAN_IT_ERR + * @retval The current state of CAN_IT (SET or RESET). + */ +ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT) +{ + ITStatus itstatus = RESET; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IT(CAN_IT)); + + /* check the enable interrupt bit */ + if((CANx->IER & CAN_IT) != RESET) + { + /* in case the Interrupt is enabled, .... */ + switch (CAN_IT) + { + case CAN_IT_TME: + /* Check CAN_TSR_RQCPx bits */ + itstatus = CheckITStatus(CANx->TSR, CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2); + break; + case CAN_IT_FMP0: + /* Check CAN_RF0R_FMP0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FMP0); + break; + case CAN_IT_FF0: + /* Check CAN_RF0R_FULL0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FULL0); + break; + case CAN_IT_FOV0: + /* Check CAN_RF0R_FOVR0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FOVR0); + break; + case CAN_IT_FMP1: + /* Check CAN_RF1R_FMP1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FMP1); + break; + case CAN_IT_FF1: + /* Check CAN_RF1R_FULL1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FULL1); + break; + case CAN_IT_FOV1: + /* Check CAN_RF1R_FOVR1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FOVR1); + break; + case CAN_IT_WKU: + /* Check CAN_MSR_WKUI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_WKUI); + break; + case CAN_IT_SLK: + /* Check CAN_MSR_SLAKI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_SLAKI); + break; + case CAN_IT_EWG: + /* Check CAN_ESR_EWGF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EWGF); + break; + case CAN_IT_EPV: + /* Check CAN_ESR_EPVF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EPVF); + break; + case CAN_IT_BOF: + /* Check CAN_ESR_BOFF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_BOFF); + break; + case CAN_IT_LEC: + /* Check CAN_ESR_LEC bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_LEC); + break; + case CAN_IT_ERR: + /* Check CAN_MSR_ERRI, CAN_ESR_EWGF, CAN_ESR_EPVF, CAN_ESR_BOFF and CAN_ESR_LEC bits */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EWGF|CAN_ESR_EPVF|CAN_ESR_BOFF|CAN_ESR_LEC); + itstatus |= CheckITStatus(CANx->MSR, CAN_MSR_ERRI); + break; + default : + /* in case of error, return RESET */ + itstatus = RESET; + break; + } + } + else + { + /* in case the Interrupt is not enabled, return RESET */ + itstatus = RESET; + } + + /* Return the CAN_IT status */ + return itstatus; +} + +/** + * @brief Clears the CANx’s interrupt pending bits. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the interrupt pending bit to clear. + * - CAN_IT_TME + * - CAN_IT_FF0 + * - CAN_IT_FOV0 + * - CAN_IT_FF1 + * - CAN_IT_FOV1 + * - CAN_IT_WKU + * - CAN_IT_SLK + * - CAN_IT_EWG + * - CAN_IT_EPV + * - CAN_IT_BOF + * - CAN_IT_LEC + * - CAN_IT_ERR + * @retval None. + */ +void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_CLEAR_IT(CAN_IT)); + + switch (CAN_IT) + { + case CAN_IT_TME: + /* Clear CAN_TSR_RQCPx (rc_w1)*/ + CANx->TSR = CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2; + break; + case CAN_IT_FF0: + /* Clear CAN_RF0R_FULL0 (rc_w1)*/ + CANx->RF0R = CAN_RF0R_FULL0; + break; + case CAN_IT_FOV0: + /* Clear CAN_RF0R_FOVR0 (rc_w1)*/ + CANx->RF0R = CAN_RF0R_FOVR0; + break; + case CAN_IT_FF1: + /* Clear CAN_RF1R_FULL1 (rc_w1)*/ + CANx->RF1R = CAN_RF1R_FULL1; + break; + case CAN_IT_FOV1: + /* Clear CAN_RF1R_FOVR1 (rc_w1)*/ + CANx->RF1R = CAN_RF1R_FOVR1; + break; + case CAN_IT_WKU: + /* Clear CAN_MSR_WKUI (rc_w1)*/ + CANx->MSR = CAN_MSR_WKUI; + break; + case CAN_IT_SLK: + /* Clear CAN_MSR_SLAKI (rc_w1)*/ + CANx->MSR = CAN_MSR_SLAKI; + break; + case CAN_IT_EWG: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : the corresponding Flag is cleared by hardware depending of the CAN Bus status*/ + break; + case CAN_IT_EPV: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : the corresponding Flag is cleared by hardware depending of the CAN Bus status*/ + break; + case CAN_IT_BOF: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : the corresponding Flag is cleared by hardware depending of the CAN Bus status*/ + break; + case CAN_IT_LEC: + /* Clear LEC bits */ + CANx->ESR = RESET; + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + break; + case CAN_IT_ERR: + /*Clear LEC bits */ + CANx->ESR = RESET; + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : BOFF, EPVF and EWGF Flags are cleared by hardware depending of the CAN Bus status*/ + break; + default : + break; + } +} + +/** + * @brief Checks whether the CAN interrupt has occurred or not. + * @param CAN_Reg: specifies the CAN interrupt register to check. + * @param It_Bit: specifies the interrupt source bit to check. + * @retval The new state of the CAN Interrupt (SET or RESET). + */ +static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit) +{ + ITStatus pendingbitstatus = RESET; + + if ((CAN_Reg & It_Bit) != (uint32_t)RESET) + { + /* CAN_IT is set */ + pendingbitstatus = SET; + } + else + { + /* CAN_IT is reset */ + pendingbitstatus = RESET; + } + return pendingbitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c index 5b3f9b513..f9ea52cbb 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c @@ -1,432 +1,432 @@ -/** - ****************************************************************************** - * @file stm32f10x_cec.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the CEC firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_cec.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup CEC - * @brief CEC driver modules - * @{ - */ - -/** @defgroup CEC_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - - -/** @defgroup CEC_Private_Defines - * @{ - */ - -/* ------------ CEC registers bit address in the alias region ----------- */ -#define CEC_OFFSET (CEC_BASE - PERIPH_BASE) - -/* --- CFGR Register ---*/ - -/* Alias word address of PE bit */ -#define CFGR_OFFSET (CEC_OFFSET + 0x00) -#define PE_BitNumber 0x00 -#define CFGR_PE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (PE_BitNumber * 4)) - -/* Alias word address of IE bit */ -#define IE_BitNumber 0x01 -#define CFGR_IE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (IE_BitNumber * 4)) - -/* --- CSR Register ---*/ - -/* Alias word address of TSOM bit */ -#define CSR_OFFSET (CEC_OFFSET + 0x10) -#define TSOM_BitNumber 0x00 -#define CSR_TSOM_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TSOM_BitNumber * 4)) - -/* Alias word address of TEOM bit */ -#define TEOM_BitNumber 0x01 -#define CSR_TEOM_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEOM_BitNumber * 4)) - -#define CFGR_CLEAR_Mask (uint8_t)(0xF3) /* CFGR register Mask */ -#define FLAG_Mask ((uint32_t)0x00FFFFFF) /* CEC FLAG mask */ - -/** - * @} - */ - - -/** @defgroup CEC_Private_Macros - * @{ - */ - -/** - * @} - */ - - -/** @defgroup CEC_Private_Variables - * @{ - */ - -/** - * @} - */ - - -/** @defgroup CEC_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - - -/** @defgroup CEC_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the CEC peripheral registers to their default reset - * values. - * @param None - * @retval None - */ -void CEC_DeInit(void) -{ - /* Enable CEC reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_CEC, ENABLE); - /* Release CEC from reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_CEC, DISABLE); -} - - -/** - * @brief Initializes the CEC peripheral according to the specified - * parameters in the CEC_InitStruct. - * @param CEC_InitStruct: pointer to an CEC_InitTypeDef structure that - * contains the configuration information for the specified - * CEC peripheral. - * @retval None - */ -void CEC_Init(CEC_InitTypeDef* CEC_InitStruct) -{ - uint16_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_CEC_BIT_TIMING_ERROR_MODE(CEC_InitStruct->CEC_BitTimingMode)); - assert_param(IS_CEC_BIT_PERIOD_ERROR_MODE(CEC_InitStruct->CEC_BitPeriodMode)); - - /*---------------------------- CEC CFGR Configuration -----------------*/ - /* Get the CEC CFGR value */ - tmpreg = CEC->CFGR; - - /* Clear BTEM and BPEM bits */ - tmpreg &= CFGR_CLEAR_Mask; - - /* Configure CEC: Bit Timing Error and Bit Period Error */ - tmpreg |= (uint16_t)(CEC_InitStruct->CEC_BitTimingMode | CEC_InitStruct->CEC_BitPeriodMode); - - /* Write to CEC CFGR register*/ - CEC->CFGR = tmpreg; - -} - -/** - * @brief Enables or disables the specified CEC peripheral. - * @param NewState: new state of the CEC peripheral. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void CEC_Cmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) CFGR_PE_BB = (uint32_t)NewState; - - if(NewState == DISABLE) - { - /* Wait until the PE bit is cleared by hardware (Idle Line detected) */ - while((CEC->CFGR & CEC_CFGR_PE) != (uint32_t)RESET) - { - } - } -} - -/** - * @brief Enables or disables the CEC interrupt. - * @param NewState: new state of the CEC interrupt. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void CEC_ITConfig(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) CFGR_IE_BB = (uint32_t)NewState; -} - -/** - * @brief Defines the Own Address of the CEC device. - * @param CEC_OwnAddress: The CEC own address - * @retval None - */ -void CEC_OwnAddressConfig(uint8_t CEC_OwnAddress) -{ - /* Check the parameters */ - assert_param(IS_CEC_ADDRESS(CEC_OwnAddress)); - - /* Set the CEC own address */ - CEC->OAR = CEC_OwnAddress; -} - -/** - * @brief Sets the CEC prescaler value. - * @param CEC_Prescaler: CEC prescaler new value - * @retval None - */ -void CEC_SetPrescaler(uint16_t CEC_Prescaler) -{ - /* Check the parameters */ - assert_param(IS_CEC_PRESCALER(CEC_Prescaler)); - - /* Set the Prescaler value*/ - CEC->PRES = CEC_Prescaler; -} - -/** - * @brief Transmits single data through the CEC peripheral. - * @param Data: the data to transmit. - * @retval None - */ -void CEC_SendDataByte(uint8_t Data) -{ - /* Transmit Data */ - CEC->TXD = Data ; -} - - -/** - * @brief Returns the most recent received data by the CEC peripheral. - * @param None - * @retval The received data. - */ -uint8_t CEC_ReceiveDataByte(void) -{ - /* Receive Data */ - return (uint8_t)(CEC->RXD); -} - -/** - * @brief Starts a new message. - * @param None - * @retval None - */ -void CEC_StartOfMessage(void) -{ - /* Starts of new message */ - *(__IO uint32_t *) CSR_TSOM_BB = (uint32_t)0x1; -} - -/** - * @brief Transmits message with or without an EOM bit. - * @param NewState: new state of the CEC Tx End Of Message. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void CEC_EndOfMessageCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - /* The data byte will be transmitted with or without an EOM bit*/ - *(__IO uint32_t *) CSR_TEOM_BB = (uint32_t)NewState; -} - -/** - * @brief Gets the CEC flag status - * @param CEC_FLAG: specifies the CEC flag to check. - * This parameter can be one of the following values: - * @arg CEC_FLAG_BTE: Bit Timing Error - * @arg CEC_FLAG_BPE: Bit Period Error - * @arg CEC_FLAG_RBTFE: Rx Block Transfer Finished Error - * @arg CEC_FLAG_SBE: Start Bit Error - * @arg CEC_FLAG_ACKE: Block Acknowledge Error - * @arg CEC_FLAG_LINE: Line Error - * @arg CEC_FLAG_TBTFE: Tx Block Transfer Finsihed Error - * @arg CEC_FLAG_TEOM: Tx End Of Message - * @arg CEC_FLAG_TERR: Tx Error - * @arg CEC_FLAG_TBTRF: Tx Byte Transfer Request or Block Transfer Finished - * @arg CEC_FLAG_RSOM: Rx Start Of Message - * @arg CEC_FLAG_REOM: Rx End Of Message - * @arg CEC_FLAG_RERR: Rx Error - * @arg CEC_FLAG_RBTF: Rx Byte/Block Transfer Finished - * @retval The new state of CEC_FLAG (SET or RESET) - */ -FlagStatus CEC_GetFlagStatus(uint32_t CEC_FLAG) -{ - FlagStatus bitstatus = RESET; - uint32_t cecreg = 0, cecbase = 0; - - /* Check the parameters */ - assert_param(IS_CEC_GET_FLAG(CEC_FLAG)); - - /* Get the CEC peripheral base address */ - cecbase = (uint32_t)(CEC_BASE); - - /* Read flag register index */ - cecreg = CEC_FLAG >> 28; - - /* Get bit[23:0] of the flag */ - CEC_FLAG &= FLAG_Mask; - - if(cecreg != 0) - { - /* Flag in CEC ESR Register */ - CEC_FLAG = (uint32_t)(CEC_FLAG >> 16); - - /* Get the CEC ESR register address */ - cecbase += 0xC; - } - else - { - /* Get the CEC CSR register address */ - cecbase += 0x10; - } - - if(((*(__IO uint32_t *)cecbase) & CEC_FLAG) != (uint32_t)RESET) - { - /* CEC_FLAG is set */ - bitstatus = SET; - } - else - { - /* CEC_FLAG is reset */ - bitstatus = RESET; - } - - /* Return the CEC_FLAG status */ - return bitstatus; -} - -/** - * @brief Clears the CEC's pending flags. - * @param CEC_FLAG: specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg CEC_FLAG_TERR: Tx Error - * @arg CEC_FLAG_TBTRF: Tx Byte Transfer Request or Block Transfer Finished - * @arg CEC_FLAG_RSOM: Rx Start Of Message - * @arg CEC_FLAG_REOM: Rx End Of Message - * @arg CEC_FLAG_RERR: Rx Error - * @arg CEC_FLAG_RBTF: Rx Byte/Block Transfer Finished - * @retval None - */ -void CEC_ClearFlag(uint32_t CEC_FLAG) -{ - uint32_t tmp = 0x0; - - /* Check the parameters */ - assert_param(IS_CEC_CLEAR_FLAG(CEC_FLAG)); - - tmp = CEC->CSR & 0x2; - - /* Clear the selected CEC flags */ - CEC->CSR &= (uint32_t)(((~(uint32_t)CEC_FLAG) & 0xFFFFFFFC) | tmp); -} - -/** - * @brief Checks whether the specified CEC interrupt has occurred or not. - * @param CEC_IT: specifies the CEC interrupt source to check. - * This parameter can be one of the following values: - * @arg CEC_IT_TERR: Tx Error - * @arg CEC_IT_TBTF: Tx Block Transfer Finished - * @arg CEC_IT_RERR: Rx Error - * @arg CEC_IT_RBTF: Rx Block Transfer Finished - * @retval The new state of CEC_IT (SET or RESET). - */ -ITStatus CEC_GetITStatus(uint8_t CEC_IT) -{ - ITStatus bitstatus = RESET; - uint32_t enablestatus = 0; - - /* Check the parameters */ - assert_param(IS_CEC_GET_IT(CEC_IT)); - - /* Get the CEC IT enable bit status */ - enablestatus = (CEC->CFGR & (uint8_t)CEC_CFGR_IE) ; - - /* Check the status of the specified CEC interrupt */ - if (((CEC->CSR & CEC_IT) != (uint32_t)RESET) && enablestatus) - { - /* CEC_IT is set */ - bitstatus = SET; - } - else - { - /* CEC_IT is reset */ - bitstatus = RESET; - } - /* Return the CEC_IT status */ - return bitstatus; -} - -/** - * @brief Clears the CEC's interrupt pending bits. - * @param CEC_IT: specifies the CEC interrupt pending bit to clear. - * This parameter can be any combination of the following values: - * @arg CEC_IT_TERR: Tx Error - * @arg CEC_IT_TBTF: Tx Block Transfer Finished - * @arg CEC_IT_RERR: Rx Error - * @arg CEC_IT_RBTF: Rx Block Transfer Finished - * @retval None - */ -void CEC_ClearITPendingBit(uint16_t CEC_IT) -{ - uint32_t tmp = 0x0; - - /* Check the parameters */ - assert_param(IS_CEC_GET_IT(CEC_IT)); - - tmp = CEC->CSR & 0x2; - - /* Clear the selected CEC interrupt pending bits */ - CEC->CSR &= (uint32_t)(((~(uint32_t)CEC_IT) & 0xFFFFFFFC) | tmp); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_cec.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the CEC firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_cec.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CEC + * @brief CEC driver modules + * @{ + */ + +/** @defgroup CEC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Defines + * @{ + */ + +/* ------------ CEC registers bit address in the alias region ----------- */ +#define CEC_OFFSET (CEC_BASE - PERIPH_BASE) + +/* --- CFGR Register ---*/ + +/* Alias word address of PE bit */ +#define CFGR_OFFSET (CEC_OFFSET + 0x00) +#define PE_BitNumber 0x00 +#define CFGR_PE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (PE_BitNumber * 4)) + +/* Alias word address of IE bit */ +#define IE_BitNumber 0x01 +#define CFGR_IE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (IE_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of TSOM bit */ +#define CSR_OFFSET (CEC_OFFSET + 0x10) +#define TSOM_BitNumber 0x00 +#define CSR_TSOM_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TSOM_BitNumber * 4)) + +/* Alias word address of TEOM bit */ +#define TEOM_BitNumber 0x01 +#define CSR_TEOM_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEOM_BitNumber * 4)) + +#define CFGR_CLEAR_Mask (uint8_t)(0xF3) /* CFGR register Mask */ +#define FLAG_Mask ((uint32_t)0x00FFFFFF) /* CEC FLAG mask */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Macros + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Variables + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the CEC peripheral registers to their default reset + * values. + * @param None + * @retval None + */ +void CEC_DeInit(void) +{ + /* Enable CEC reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CEC, ENABLE); + /* Release CEC from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CEC, DISABLE); +} + + +/** + * @brief Initializes the CEC peripheral according to the specified + * parameters in the CEC_InitStruct. + * @param CEC_InitStruct: pointer to an CEC_InitTypeDef structure that + * contains the configuration information for the specified + * CEC peripheral. + * @retval None + */ +void CEC_Init(CEC_InitTypeDef* CEC_InitStruct) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_CEC_BIT_TIMING_ERROR_MODE(CEC_InitStruct->CEC_BitTimingMode)); + assert_param(IS_CEC_BIT_PERIOD_ERROR_MODE(CEC_InitStruct->CEC_BitPeriodMode)); + + /*---------------------------- CEC CFGR Configuration -----------------*/ + /* Get the CEC CFGR value */ + tmpreg = CEC->CFGR; + + /* Clear BTEM and BPEM bits */ + tmpreg &= CFGR_CLEAR_Mask; + + /* Configure CEC: Bit Timing Error and Bit Period Error */ + tmpreg |= (uint16_t)(CEC_InitStruct->CEC_BitTimingMode | CEC_InitStruct->CEC_BitPeriodMode); + + /* Write to CEC CFGR register*/ + CEC->CFGR = tmpreg; + +} + +/** + * @brief Enables or disables the specified CEC peripheral. + * @param NewState: new state of the CEC peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CEC_Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CFGR_PE_BB = (uint32_t)NewState; + + if(NewState == DISABLE) + { + /* Wait until the PE bit is cleared by hardware (Idle Line detected) */ + while((CEC->CFGR & CEC_CFGR_PE) != (uint32_t)RESET) + { + } + } +} + +/** + * @brief Enables or disables the CEC interrupt. + * @param NewState: new state of the CEC interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CEC_ITConfig(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CFGR_IE_BB = (uint32_t)NewState; +} + +/** + * @brief Defines the Own Address of the CEC device. + * @param CEC_OwnAddress: The CEC own address + * @retval None + */ +void CEC_OwnAddressConfig(uint8_t CEC_OwnAddress) +{ + /* Check the parameters */ + assert_param(IS_CEC_ADDRESS(CEC_OwnAddress)); + + /* Set the CEC own address */ + CEC->OAR = CEC_OwnAddress; +} + +/** + * @brief Sets the CEC prescaler value. + * @param CEC_Prescaler: CEC prescaler new value + * @retval None + */ +void CEC_SetPrescaler(uint16_t CEC_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_CEC_PRESCALER(CEC_Prescaler)); + + /* Set the Prescaler value*/ + CEC->PRES = CEC_Prescaler; +} + +/** + * @brief Transmits single data through the CEC peripheral. + * @param Data: the data to transmit. + * @retval None + */ +void CEC_SendDataByte(uint8_t Data) +{ + /* Transmit Data */ + CEC->TXD = Data ; +} + + +/** + * @brief Returns the most recent received data by the CEC peripheral. + * @param None + * @retval The received data. + */ +uint8_t CEC_ReceiveDataByte(void) +{ + /* Receive Data */ + return (uint8_t)(CEC->RXD); +} + +/** + * @brief Starts a new message. + * @param None + * @retval None + */ +void CEC_StartOfMessage(void) +{ + /* Starts of new message */ + *(__IO uint32_t *) CSR_TSOM_BB = (uint32_t)0x1; +} + +/** + * @brief Transmits message with or without an EOM bit. + * @param NewState: new state of the CEC Tx End Of Message. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CEC_EndOfMessageCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* The data byte will be transmitted with or without an EOM bit*/ + *(__IO uint32_t *) CSR_TEOM_BB = (uint32_t)NewState; +} + +/** + * @brief Gets the CEC flag status + * @param CEC_FLAG: specifies the CEC flag to check. + * This parameter can be one of the following values: + * @arg CEC_FLAG_BTE: Bit Timing Error + * @arg CEC_FLAG_BPE: Bit Period Error + * @arg CEC_FLAG_RBTFE: Rx Block Transfer Finished Error + * @arg CEC_FLAG_SBE: Start Bit Error + * @arg CEC_FLAG_ACKE: Block Acknowledge Error + * @arg CEC_FLAG_LINE: Line Error + * @arg CEC_FLAG_TBTFE: Tx Block Transfer Finsihed Error + * @arg CEC_FLAG_TEOM: Tx End Of Message + * @arg CEC_FLAG_TERR: Tx Error + * @arg CEC_FLAG_TBTRF: Tx Byte Transfer Request or Block Transfer Finished + * @arg CEC_FLAG_RSOM: Rx Start Of Message + * @arg CEC_FLAG_REOM: Rx End Of Message + * @arg CEC_FLAG_RERR: Rx Error + * @arg CEC_FLAG_RBTF: Rx Byte/Block Transfer Finished + * @retval The new state of CEC_FLAG (SET or RESET) + */ +FlagStatus CEC_GetFlagStatus(uint32_t CEC_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t cecreg = 0, cecbase = 0; + + /* Check the parameters */ + assert_param(IS_CEC_GET_FLAG(CEC_FLAG)); + + /* Get the CEC peripheral base address */ + cecbase = (uint32_t)(CEC_BASE); + + /* Read flag register index */ + cecreg = CEC_FLAG >> 28; + + /* Get bit[23:0] of the flag */ + CEC_FLAG &= FLAG_Mask; + + if(cecreg != 0) + { + /* Flag in CEC ESR Register */ + CEC_FLAG = (uint32_t)(CEC_FLAG >> 16); + + /* Get the CEC ESR register address */ + cecbase += 0xC; + } + else + { + /* Get the CEC CSR register address */ + cecbase += 0x10; + } + + if(((*(__IO uint32_t *)cecbase) & CEC_FLAG) != (uint32_t)RESET) + { + /* CEC_FLAG is set */ + bitstatus = SET; + } + else + { + /* CEC_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the CEC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the CEC's pending flags. + * @param CEC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg CEC_FLAG_TERR: Tx Error + * @arg CEC_FLAG_TBTRF: Tx Byte Transfer Request or Block Transfer Finished + * @arg CEC_FLAG_RSOM: Rx Start Of Message + * @arg CEC_FLAG_REOM: Rx End Of Message + * @arg CEC_FLAG_RERR: Rx Error + * @arg CEC_FLAG_RBTF: Rx Byte/Block Transfer Finished + * @retval None + */ +void CEC_ClearFlag(uint32_t CEC_FLAG) +{ + uint32_t tmp = 0x0; + + /* Check the parameters */ + assert_param(IS_CEC_CLEAR_FLAG(CEC_FLAG)); + + tmp = CEC->CSR & 0x2; + + /* Clear the selected CEC flags */ + CEC->CSR &= (uint32_t)(((~(uint32_t)CEC_FLAG) & 0xFFFFFFFC) | tmp); +} + +/** + * @brief Checks whether the specified CEC interrupt has occurred or not. + * @param CEC_IT: specifies the CEC interrupt source to check. + * This parameter can be one of the following values: + * @arg CEC_IT_TERR: Tx Error + * @arg CEC_IT_TBTF: Tx Block Transfer Finished + * @arg CEC_IT_RERR: Rx Error + * @arg CEC_IT_RBTF: Rx Block Transfer Finished + * @retval The new state of CEC_IT (SET or RESET). + */ +ITStatus CEC_GetITStatus(uint8_t CEC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_CEC_GET_IT(CEC_IT)); + + /* Get the CEC IT enable bit status */ + enablestatus = (CEC->CFGR & (uint8_t)CEC_CFGR_IE) ; + + /* Check the status of the specified CEC interrupt */ + if (((CEC->CSR & CEC_IT) != (uint32_t)RESET) && enablestatus) + { + /* CEC_IT is set */ + bitstatus = SET; + } + else + { + /* CEC_IT is reset */ + bitstatus = RESET; + } + /* Return the CEC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the CEC's interrupt pending bits. + * @param CEC_IT: specifies the CEC interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg CEC_IT_TERR: Tx Error + * @arg CEC_IT_TBTF: Tx Block Transfer Finished + * @arg CEC_IT_RERR: Rx Error + * @arg CEC_IT_RBTF: Rx Block Transfer Finished + * @retval None + */ +void CEC_ClearITPendingBit(uint16_t CEC_IT) +{ + uint32_t tmp = 0x0; + + /* Check the parameters */ + assert_param(IS_CEC_GET_IT(CEC_IT)); + + tmp = CEC->CSR & 0x2; + + /* Clear the selected CEC interrupt pending bits */ + CEC->CSR &= (uint32_t)(((~(uint32_t)CEC_IT) & 0xFFFFFFFC) | tmp); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c index 511a7b90e..9e8e32944 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c @@ -1,159 +1,159 @@ -/** - ****************************************************************************** - * @file stm32f10x_crc.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the CRC firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_crc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup CRC - * @brief CRC driver modules - * @{ - */ - -/** @defgroup CRC_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup CRC_Private_Defines - * @{ - */ - -/** - * @} - */ - -/** @defgroup CRC_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup CRC_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup CRC_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup CRC_Private_Functions - * @{ - */ - -/** - * @brief Resets the CRC Data register (DR). - * @param None - * @retval None - */ -void CRC_ResetDR(void) -{ - /* Reset CRC generator */ - CRC->CR = CRC_CR_RESET; -} - -/** - * @brief Computes the 32-bit CRC of a given data word(32-bit). - * @param Data: data word(32-bit) to compute its CRC - * @retval 32-bit CRC - */ -uint32_t CRC_CalcCRC(uint32_t Data) -{ - CRC->DR = Data; - - return (CRC->DR); -} - -/** - * @brief Computes the 32-bit CRC of a given buffer of data word(32-bit). - * @param pBuffer: pointer to the buffer containing the data to be computed - * @param BufferLength: length of the buffer to be computed - * @retval 32-bit CRC - */ -uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength) -{ - uint32_t index = 0; - - for(index = 0; index < BufferLength; index++) - { - CRC->DR = pBuffer[index]; - } - return (CRC->DR); -} - -/** - * @brief Returns the current CRC value. - * @param None - * @retval 32-bit CRC - */ -uint32_t CRC_GetCRC(void) -{ - return (CRC->DR); -} - -/** - * @brief Stores a 8-bit data in the Independent Data(ID) register. - * @param IDValue: 8-bit value to be stored in the ID register - * @retval None - */ -void CRC_SetIDRegister(uint8_t IDValue) -{ - CRC->IDR = IDValue; -} - -/** - * @brief Returns the 8-bit data stored in the Independent Data(ID) register - * @param None - * @retval 8-bit value of the ID register - */ -uint8_t CRC_GetIDRegister(void) -{ - return (CRC->IDR); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_crc.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the CRC firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_crc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CRC + * @brief CRC driver modules + * @{ + */ + +/** @defgroup CRC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Defines + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Functions + * @{ + */ + +/** + * @brief Resets the CRC Data register (DR). + * @param None + * @retval None + */ +void CRC_ResetDR(void) +{ + /* Reset CRC generator */ + CRC->CR = CRC_CR_RESET; +} + +/** + * @brief Computes the 32-bit CRC of a given data word(32-bit). + * @param Data: data word(32-bit) to compute its CRC + * @retval 32-bit CRC + */ +uint32_t CRC_CalcCRC(uint32_t Data) +{ + CRC->DR = Data; + + return (CRC->DR); +} + +/** + * @brief Computes the 32-bit CRC of a given buffer of data word(32-bit). + * @param pBuffer: pointer to the buffer containing the data to be computed + * @param BufferLength: length of the buffer to be computed + * @retval 32-bit CRC + */ +uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength) +{ + uint32_t index = 0; + + for(index = 0; index < BufferLength; index++) + { + CRC->DR = pBuffer[index]; + } + return (CRC->DR); +} + +/** + * @brief Returns the current CRC value. + * @param None + * @retval 32-bit CRC + */ +uint32_t CRC_GetCRC(void) +{ + return (CRC->DR); +} + +/** + * @brief Stores a 8-bit data in the Independent Data(ID) register. + * @param IDValue: 8-bit value to be stored in the ID register + * @retval None + */ +void CRC_SetIDRegister(uint8_t IDValue) +{ + CRC->IDR = IDValue; +} + +/** + * @brief Returns the 8-bit data stored in the Independent Data(ID) register + * @param None + * @retval 8-bit value of the ID register + */ +uint8_t CRC_GetIDRegister(void) +{ + return (CRC->IDR); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c index 55e91c0a7..613ed6d5d 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c @@ -1,570 +1,570 @@ -/** - ****************************************************************************** - * @file stm32f10x_dac.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the DAC firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_dac.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup DAC - * @brief DAC driver modules - * @{ - */ - -/** @defgroup DAC_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup DAC_Private_Defines - * @{ - */ - -/* CR register Mask */ -#define CR_CLEAR_MASK ((uint32_t)0x00000FFE) - -/* DAC Dual Channels SWTRIG masks */ -#define DUAL_SWTRIG_SET ((uint32_t)0x00000003) -#define DUAL_SWTRIG_RESET ((uint32_t)0xFFFFFFFC) - -/* DHR registers offsets */ -#define DHR12R1_OFFSET ((uint32_t)0x00000008) -#define DHR12R2_OFFSET ((uint32_t)0x00000014) -#define DHR12RD_OFFSET ((uint32_t)0x00000020) - -/* DOR register offset */ -#define DOR_OFFSET ((uint32_t)0x0000002C) -/** - * @} - */ - -/** @defgroup DAC_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup DAC_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup DAC_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup DAC_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the DAC peripheral registers to their default reset values. - * @param None - * @retval None - */ -void DAC_DeInit(void) -{ - /* Enable DAC reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE); - /* Release DAC from reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE); -} - -/** - * @brief Initializes the DAC peripheral according to the specified - * parameters in the DAC_InitStruct. - * @param DAC_Channel: the selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure that - * contains the configuration information for the specified DAC channel. - * @retval None - */ -void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct) -{ - uint32_t tmpreg1 = 0, tmpreg2 = 0; - /* Check the DAC parameters */ - assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger)); - assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration)); - assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude)); - assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer)); -/*---------------------------- DAC CR Configuration --------------------------*/ - /* Get the DAC CR value */ - tmpreg1 = DAC->CR; - /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */ - tmpreg1 &= ~(CR_CLEAR_MASK << DAC_Channel); - /* Configure for the selected DAC channel: buffer output, trigger, wave genration, - mask/amplitude for wave genration */ - /* Set TSELx and TENx bits according to DAC_Trigger value */ - /* Set WAVEx bits according to DAC_WaveGeneration value */ - /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */ - /* Set BOFFx bit according to DAC_OutputBuffer value */ - tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration | - DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_OutputBuffer); - /* Calculate CR register value depending on DAC_Channel */ - tmpreg1 |= tmpreg2 << DAC_Channel; - /* Write to DAC CR */ - DAC->CR = tmpreg1; -} - -/** - * @brief Fills each DAC_InitStruct member with its default value. - * @param DAC_InitStruct : pointer to a DAC_InitTypeDef structure which will - * be initialized. - * @retval None - */ -void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct) -{ -/*--------------- Reset DAC init structure parameters values -----------------*/ - /* Initialize the DAC_Trigger member */ - DAC_InitStruct->DAC_Trigger = DAC_Trigger_None; - /* Initialize the DAC_WaveGeneration member */ - DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None; - /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */ - DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0; - /* Initialize the DAC_OutputBuffer member */ - DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable; -} - -/** - * @brief Enables or disables the specified DAC channel. - * @param DAC_Channel: the selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @param NewState: new state of the DAC channel. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(DAC_Channel)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected DAC channel */ - DAC->CR |= (DAC_CR_EN1 << DAC_Channel); - } - else - { - /* Disable the selected DAC channel */ - DAC->CR &= ~(DAC_CR_EN1 << DAC_Channel); - } -} -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) -/** - * @brief Enables or disables the specified DAC interrupts. - * @param DAC_Channel: the selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @param DAC_IT: specifies the DAC interrupt sources to be enabled or disabled. - * This parameter can be the following values: - * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask - * @param NewState: new state of the specified DAC interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(DAC_Channel)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - assert_param(IS_DAC_IT(DAC_IT)); - - if (NewState != DISABLE) - { - /* Enable the selected DAC interrupts */ - DAC->CR |= (DAC_IT << DAC_Channel); - } - else - { - /* Disable the selected DAC interrupts */ - DAC->CR &= (~(uint32_t)(DAC_IT << DAC_Channel)); - } -} -#endif - -/** - * @brief Enables or disables the specified DAC channel DMA request. - * @param DAC_Channel: the selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @param NewState: new state of the selected DAC channel DMA request. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(DAC_Channel)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected DAC channel DMA request */ - DAC->CR |= (DAC_CR_DMAEN1 << DAC_Channel); - } - else - { - /* Disable the selected DAC channel DMA request */ - DAC->CR &= ~(DAC_CR_DMAEN1 << DAC_Channel); - } -} - -/** - * @brief Enables or disables the selected DAC channel software trigger. - * @param DAC_Channel: the selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @param NewState: new state of the selected DAC channel software trigger. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(DAC_Channel)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable software trigger for the selected DAC channel */ - DAC->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4); - } - else - { - /* Disable software trigger for the selected DAC channel */ - DAC->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4)); - } -} - -/** - * @brief Enables or disables simultaneously the two DAC channels software - * triggers. - * @param NewState: new state of the DAC channels software triggers. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void DAC_DualSoftwareTriggerCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable software trigger for both DAC channels */ - DAC->SWTRIGR |= DUAL_SWTRIG_SET ; - } - else - { - /* Disable software trigger for both DAC channels */ - DAC->SWTRIGR &= DUAL_SWTRIG_RESET; - } -} - -/** - * @brief Enables or disables the selected DAC channel wave generation. - * @param DAC_Channel: the selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @param DAC_Wave: Specifies the wave type to enable or disable. - * This parameter can be one of the following values: - * @arg DAC_Wave_Noise: noise wave generation - * @arg DAC_Wave_Triangle: triangle wave generation - * @param NewState: new state of the selected DAC channel wave generation. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(DAC_Channel)); - assert_param(IS_DAC_WAVE(DAC_Wave)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected wave generation for the selected DAC channel */ - DAC->CR |= DAC_Wave << DAC_Channel; - } - else - { - /* Disable the selected wave generation for the selected DAC channel */ - DAC->CR &= ~(DAC_Wave << DAC_Channel); - } -} - -/** - * @brief Set the specified data holding register value for DAC channel1. - * @param DAC_Align: Specifies the data alignement for DAC channel1. - * This parameter can be one of the following values: - * @arg DAC_Align_8b_R: 8bit right data alignement selected - * @arg DAC_Align_12b_L: 12bit left data alignement selected - * @arg DAC_Align_12b_R: 12bit right data alignement selected - * @param Data : Data to be loaded in the selected data holding register. - * @retval None - */ -void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data) -{ - __IO uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_DAC_ALIGN(DAC_Align)); - assert_param(IS_DAC_DATA(Data)); - - tmp = (uint32_t)DAC_BASE; - tmp += DHR12R1_OFFSET + DAC_Align; - - /* Set the DAC channel1 selected data holding register */ - *(__IO uint32_t *) tmp = Data; -} - -/** - * @brief Set the specified data holding register value for DAC channel2. - * @param DAC_Align: Specifies the data alignement for DAC channel2. - * This parameter can be one of the following values: - * @arg DAC_Align_8b_R: 8bit right data alignement selected - * @arg DAC_Align_12b_L: 12bit left data alignement selected - * @arg DAC_Align_12b_R: 12bit right data alignement selected - * @param Data : Data to be loaded in the selected data holding register. - * @retval None - */ -void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data) -{ - __IO uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_DAC_ALIGN(DAC_Align)); - assert_param(IS_DAC_DATA(Data)); - - tmp = (uint32_t)DAC_BASE; - tmp += DHR12R2_OFFSET + DAC_Align; - - /* Set the DAC channel2 selected data holding register */ - *(__IO uint32_t *)tmp = Data; -} - -/** - * @brief Set the specified data holding register value for dual channel - * DAC. - * @param DAC_Align: Specifies the data alignement for dual channel DAC. - * This parameter can be one of the following values: - * @arg DAC_Align_8b_R: 8bit right data alignement selected - * @arg DAC_Align_12b_L: 12bit left data alignement selected - * @arg DAC_Align_12b_R: 12bit right data alignement selected - * @param Data2: Data for DAC Channel2 to be loaded in the selected data - * holding register. - * @param Data1: Data for DAC Channel1 to be loaded in the selected data - * holding register. - * @retval None - */ -void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1) -{ - uint32_t data = 0, tmp = 0; - - /* Check the parameters */ - assert_param(IS_DAC_ALIGN(DAC_Align)); - assert_param(IS_DAC_DATA(Data1)); - assert_param(IS_DAC_DATA(Data2)); - - /* Calculate and set dual DAC data holding register value */ - if (DAC_Align == DAC_Align_8b_R) - { - data = ((uint32_t)Data2 << 8) | Data1; - } - else - { - data = ((uint32_t)Data2 << 16) | Data1; - } - - tmp = (uint32_t)DAC_BASE; - tmp += DHR12RD_OFFSET + DAC_Align; - - /* Set the dual DAC selected data holding register */ - *(__IO uint32_t *)tmp = data; -} - -/** - * @brief Returns the last data output value of the selected DAC cahnnel. - * @param DAC_Channel: the selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @retval The selected DAC channel data output value. - */ -uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel) -{ - __IO uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(DAC_Channel)); - - tmp = (uint32_t) DAC_BASE ; - tmp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2); - - /* Returns the DAC channel data output register value */ - return (uint16_t) (*(__IO uint32_t*) tmp); -} - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) -/** - * @brief Checks whether the specified DAC flag is set or not. - * @param DAC_Channel: thee selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @param DAC_FLAG: specifies the flag to check. - * This parameter can be only of the following value: - * @arg DAC_FLAG_DMAUDR: DMA underrun flag - * @retval The new state of DAC_FLAG (SET or RESET). - */ -FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(DAC_Channel)); - assert_param(IS_DAC_FLAG(DAC_FLAG)); - - /* Check the status of the specified DAC flag */ - if ((DAC->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)RESET) - { - /* DAC_FLAG is set */ - bitstatus = SET; - } - else - { - /* DAC_FLAG is reset */ - bitstatus = RESET; - } - /* Return the DAC_FLAG status */ - return bitstatus; -} - -/** - * @brief Clears the DAC channelx's pending flags. - * @param DAC_Channel: the selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @param DAC_FLAG: specifies the flag to clear. - * This parameter can be of the following value: - * @arg DAC_FLAG_DMAUDR: DMA underrun flag - * @retval None - */ -void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(DAC_Channel)); - assert_param(IS_DAC_FLAG(DAC_FLAG)); - - /* Clear the selected DAC flags */ - DAC->SR = (DAC_FLAG << DAC_Channel); -} - -/** - * @brief Checks whether the specified DAC interrupt has occurred or not. - * @param DAC_Channel: the selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @param DAC_IT: specifies the DAC interrupt source to check. - * This parameter can be the following values: - * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask - * @retval The new state of DAC_IT (SET or RESET). - */ -ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT) -{ - ITStatus bitstatus = RESET; - uint32_t enablestatus = 0; - - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(DAC_Channel)); - assert_param(IS_DAC_IT(DAC_IT)); - - /* Get the DAC_IT enable bit status */ - enablestatus = (DAC->CR & (DAC_IT << DAC_Channel)) ; - - /* Check the status of the specified DAC interrupt */ - if (((DAC->SR & (DAC_IT << DAC_Channel)) != (uint32_t)RESET) && enablestatus) - { - /* DAC_IT is set */ - bitstatus = SET; - } - else - { - /* DAC_IT is reset */ - bitstatus = RESET; - } - /* Return the DAC_IT status */ - return bitstatus; -} - -/** - * @brief Clears the DAC channelx’s interrupt pending bits. - * @param DAC_Channel: the selected DAC channel. - * This parameter can be one of the following values: - * @arg DAC_Channel_1: DAC Channel1 selected - * @arg DAC_Channel_2: DAC Channel2 selected - * @param DAC_IT: specifies the DAC interrupt pending bit to clear. - * This parameter can be the following values: - * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask - * @retval None - */ -void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT) -{ - /* Check the parameters */ - assert_param(IS_DAC_CHANNEL(DAC_Channel)); - assert_param(IS_DAC_IT(DAC_IT)); - - /* Clear the selected DAC interrupt pending bits */ - DAC->SR = (DAC_IT << DAC_Channel); -} -#endif - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_dac.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the DAC firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_dac.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DAC + * @brief DAC driver modules + * @{ + */ + +/** @defgroup DAC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_Defines + * @{ + */ + +/* CR register Mask */ +#define CR_CLEAR_MASK ((uint32_t)0x00000FFE) + +/* DAC Dual Channels SWTRIG masks */ +#define DUAL_SWTRIG_SET ((uint32_t)0x00000003) +#define DUAL_SWTRIG_RESET ((uint32_t)0xFFFFFFFC) + +/* DHR registers offsets */ +#define DHR12R1_OFFSET ((uint32_t)0x00000008) +#define DHR12R2_OFFSET ((uint32_t)0x00000014) +#define DHR12RD_OFFSET ((uint32_t)0x00000020) + +/* DOR register offset */ +#define DOR_OFFSET ((uint32_t)0x0000002C) +/** + * @} + */ + +/** @defgroup DAC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the DAC peripheral registers to their default reset values. + * @param None + * @retval None + */ +void DAC_DeInit(void) +{ + /* Enable DAC reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE); + /* Release DAC from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE); +} + +/** + * @brief Initializes the DAC peripheral according to the specified + * parameters in the DAC_InitStruct. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure that + * contains the configuration information for the specified DAC channel. + * @retval None + */ +void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0; + /* Check the DAC parameters */ + assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger)); + assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration)); + assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude)); + assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer)); +/*---------------------------- DAC CR Configuration --------------------------*/ + /* Get the DAC CR value */ + tmpreg1 = DAC->CR; + /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */ + tmpreg1 &= ~(CR_CLEAR_MASK << DAC_Channel); + /* Configure for the selected DAC channel: buffer output, trigger, wave genration, + mask/amplitude for wave genration */ + /* Set TSELx and TENx bits according to DAC_Trigger value */ + /* Set WAVEx bits according to DAC_WaveGeneration value */ + /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */ + /* Set BOFFx bit according to DAC_OutputBuffer value */ + tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration | + DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_OutputBuffer); + /* Calculate CR register value depending on DAC_Channel */ + tmpreg1 |= tmpreg2 << DAC_Channel; + /* Write to DAC CR */ + DAC->CR = tmpreg1; +} + +/** + * @brief Fills each DAC_InitStruct member with its default value. + * @param DAC_InitStruct : pointer to a DAC_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct) +{ +/*--------------- Reset DAC init structure parameters values -----------------*/ + /* Initialize the DAC_Trigger member */ + DAC_InitStruct->DAC_Trigger = DAC_Trigger_None; + /* Initialize the DAC_WaveGeneration member */ + DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None; + /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */ + DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0; + /* Initialize the DAC_OutputBuffer member */ + DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable; +} + +/** + * @brief Enables or disables the specified DAC channel. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the DAC channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected DAC channel */ + DAC->CR |= (DAC_CR_EN1 << DAC_Channel); + } + else + { + /* Disable the selected DAC channel */ + DAC->CR &= ~(DAC_CR_EN1 << DAC_Channel); + } +} +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/** + * @brief Enables or disables the specified DAC interrupts. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt sources to be enabled or disabled. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @param NewState: new state of the specified DAC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_DAC_IT(DAC_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected DAC interrupts */ + DAC->CR |= (DAC_IT << DAC_Channel); + } + else + { + /* Disable the selected DAC interrupts */ + DAC->CR &= (~(uint32_t)(DAC_IT << DAC_Channel)); + } +} +#endif + +/** + * @brief Enables or disables the specified DAC channel DMA request. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the selected DAC channel DMA request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected DAC channel DMA request */ + DAC->CR |= (DAC_CR_DMAEN1 << DAC_Channel); + } + else + { + /* Disable the selected DAC channel DMA request */ + DAC->CR &= ~(DAC_CR_DMAEN1 << DAC_Channel); + } +} + +/** + * @brief Enables or disables the selected DAC channel software trigger. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the selected DAC channel software trigger. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable software trigger for the selected DAC channel */ + DAC->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4); + } + else + { + /* Disable software trigger for the selected DAC channel */ + DAC->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4)); + } +} + +/** + * @brief Enables or disables simultaneously the two DAC channels software + * triggers. + * @param NewState: new state of the DAC channels software triggers. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_DualSoftwareTriggerCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable software trigger for both DAC channels */ + DAC->SWTRIGR |= DUAL_SWTRIG_SET ; + } + else + { + /* Disable software trigger for both DAC channels */ + DAC->SWTRIGR &= DUAL_SWTRIG_RESET; + } +} + +/** + * @brief Enables or disables the selected DAC channel wave generation. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_Wave: Specifies the wave type to enable or disable. + * This parameter can be one of the following values: + * @arg DAC_Wave_Noise: noise wave generation + * @arg DAC_Wave_Triangle: triangle wave generation + * @param NewState: new state of the selected DAC channel wave generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_WAVE(DAC_Wave)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected wave generation for the selected DAC channel */ + DAC->CR |= DAC_Wave << DAC_Channel; + } + else + { + /* Disable the selected wave generation for the selected DAC channel */ + DAC->CR &= ~(DAC_Wave << DAC_Channel); + } +} + +/** + * @brief Set the specified data holding register value for DAC channel1. + * @param DAC_Align: Specifies the data alignement for DAC channel1. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignement selected + * @arg DAC_Align_12b_L: 12bit left data alignement selected + * @arg DAC_Align_12b_R: 12bit right data alignement selected + * @param Data : Data to be loaded in the selected data holding register. + * @retval None + */ +void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12R1_OFFSET + DAC_Align; + + /* Set the DAC channel1 selected data holding register */ + *(__IO uint32_t *) tmp = Data; +} + +/** + * @brief Set the specified data holding register value for DAC channel2. + * @param DAC_Align: Specifies the data alignement for DAC channel2. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignement selected + * @arg DAC_Align_12b_L: 12bit left data alignement selected + * @arg DAC_Align_12b_R: 12bit right data alignement selected + * @param Data : Data to be loaded in the selected data holding register. + * @retval None + */ +void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12R2_OFFSET + DAC_Align; + + /* Set the DAC channel2 selected data holding register */ + *(__IO uint32_t *)tmp = Data; +} + +/** + * @brief Set the specified data holding register value for dual channel + * DAC. + * @param DAC_Align: Specifies the data alignement for dual channel DAC. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignement selected + * @arg DAC_Align_12b_L: 12bit left data alignement selected + * @arg DAC_Align_12b_R: 12bit right data alignement selected + * @param Data2: Data for DAC Channel2 to be loaded in the selected data + * holding register. + * @param Data1: Data for DAC Channel1 to be loaded in the selected data + * holding register. + * @retval None + */ +void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1) +{ + uint32_t data = 0, tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data1)); + assert_param(IS_DAC_DATA(Data2)); + + /* Calculate and set dual DAC data holding register value */ + if (DAC_Align == DAC_Align_8b_R) + { + data = ((uint32_t)Data2 << 8) | Data1; + } + else + { + data = ((uint32_t)Data2 << 16) | Data1; + } + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12RD_OFFSET + DAC_Align; + + /* Set the dual DAC selected data holding register */ + *(__IO uint32_t *)tmp = data; +} + +/** + * @brief Returns the last data output value of the selected DAC cahnnel. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @retval The selected DAC channel data output value. + */ +uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + + tmp = (uint32_t) DAC_BASE ; + tmp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2); + + /* Returns the DAC channel data output register value */ + return (uint16_t) (*(__IO uint32_t*) tmp); +} + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/** + * @brief Checks whether the specified DAC flag is set or not. + * @param DAC_Channel: thee selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_FLAG: specifies the flag to check. + * This parameter can be only of the following value: + * @arg DAC_FLAG_DMAUDR: DMA underrun flag + * @retval The new state of DAC_FLAG (SET or RESET). + */ +FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_FLAG(DAC_FLAG)); + + /* Check the status of the specified DAC flag */ + if ((DAC->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)RESET) + { + /* DAC_FLAG is set */ + bitstatus = SET; + } + else + { + /* DAC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the DAC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DAC channelx's pending flags. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_FLAG: specifies the flag to clear. + * This parameter can be of the following value: + * @arg DAC_FLAG_DMAUDR: DMA underrun flag + * @retval None + */ +void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_FLAG(DAC_FLAG)); + + /* Clear the selected DAC flags */ + DAC->SR = (DAC_FLAG << DAC_Channel); +} + +/** + * @brief Checks whether the specified DAC interrupt has occurred or not. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt source to check. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @retval The new state of DAC_IT (SET or RESET). + */ +ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_IT(DAC_IT)); + + /* Get the DAC_IT enable bit status */ + enablestatus = (DAC->CR & (DAC_IT << DAC_Channel)) ; + + /* Check the status of the specified DAC interrupt */ + if (((DAC->SR & (DAC_IT << DAC_Channel)) != (uint32_t)RESET) && enablestatus) + { + /* DAC_IT is set */ + bitstatus = SET; + } + else + { + /* DAC_IT is reset */ + bitstatus = RESET; + } + /* Return the DAC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the DAC channelx’s interrupt pending bits. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt pending bit to clear. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @retval None + */ +void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_IT(DAC_IT)); + + /* Clear the selected DAC interrupt pending bits */ + DAC->SR = (DAC_IT << DAC_Channel); +} +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c index 3f4e62727..3238f8ac2 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c @@ -1,161 +1,161 @@ -/** - ****************************************************************************** - * @file stm32f10x_dbgmcu.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the DBGMCU firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_dbgmcu.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup DBGMCU - * @brief DBGMCU driver modules - * @{ - */ - -/** @defgroup DBGMCU_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup DBGMCU_Private_Defines - * @{ - */ - -#define IDCODE_DEVID_MASK ((uint32_t)0x00000FFF) -/** - * @} - */ - -/** @defgroup DBGMCU_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup DBGMCU_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup DBGMCU_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup DBGMCU_Private_Functions - * @{ - */ - -/** - * @brief Returns the device revision identifier. - * @param None - * @retval Device revision identifier - */ -uint32_t DBGMCU_GetREVID(void) -{ - return(DBGMCU->IDCODE >> 16); -} - -/** - * @brief Returns the device identifier. - * @param None - * @retval Device identifier - */ -uint32_t DBGMCU_GetDEVID(void) -{ - return(DBGMCU->IDCODE & IDCODE_DEVID_MASK); -} - -/** - * @brief Configures the specified peripheral and low power mode behavior - * when the MCU under Debug mode. - * @param DBGMCU_Periph: specifies the peripheral and low power mode. - * This parameter can be any combination of the following values: - * @arg DBGMCU_SLEEP: Keep debugger connection during SLEEP mode - * @arg DBGMCU_STOP: Keep debugger connection during STOP mode - * @arg DBGMCU_STANDBY: Keep debugger connection during STANDBY mode - * @arg DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted - * @arg DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted - * @arg DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted - * @arg DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted - * @arg DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted - * @arg DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted - * @arg DBGMCU_CAN1_STOP: Debug CAN2 stopped when Core is halted - * @arg DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped when Core is halted - * @arg DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped when Core is halted - * @arg DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted - * @arg DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted - * @arg DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted - * @arg DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted - * @arg DBGMCU_CAN2_STOP: Debug CAN2 stopped when Core is halted - * @arg DBGMCU_TIM15_STOP: TIM15 counter stopped when Core is halted - * @arg DBGMCU_TIM16_STOP: TIM16 counter stopped when Core is halted - * @arg DBGMCU_TIM17_STOP: TIM17 counter stopped when Core is halted - * @arg DBGMCU_TIM9_STOP: TIM9 counter stopped when Core is halted - * @arg DBGMCU_TIM10_STOP: TIM10 counter stopped when Core is halted - * @arg DBGMCU_TIM11_STOP: TIM11 counter stopped when Core is halted - * @arg DBGMCU_TIM12_STOP: TIM12 counter stopped when Core is halted - * @arg DBGMCU_TIM13_STOP: TIM13 counter stopped when Core is halted - * @arg DBGMCU_TIM14_STOP: TIM14 counter stopped when Core is halted - * @param NewState: new state of the specified peripheral in Debug mode. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - DBGMCU->CR |= DBGMCU_Periph; - } - else - { - DBGMCU->CR &= ~DBGMCU_Periph; - } -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_dbgmcu.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the DBGMCU firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_dbgmcu.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DBGMCU + * @brief DBGMCU driver modules + * @{ + */ + +/** @defgroup DBGMCU_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Defines + * @{ + */ + +#define IDCODE_DEVID_MASK ((uint32_t)0x00000FFF) +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Functions + * @{ + */ + +/** + * @brief Returns the device revision identifier. + * @param None + * @retval Device revision identifier + */ +uint32_t DBGMCU_GetREVID(void) +{ + return(DBGMCU->IDCODE >> 16); +} + +/** + * @brief Returns the device identifier. + * @param None + * @retval Device identifier + */ +uint32_t DBGMCU_GetDEVID(void) +{ + return(DBGMCU->IDCODE & IDCODE_DEVID_MASK); +} + +/** + * @brief Configures the specified peripheral and low power mode behavior + * when the MCU under Debug mode. + * @param DBGMCU_Periph: specifies the peripheral and low power mode. + * This parameter can be any combination of the following values: + * @arg DBGMCU_SLEEP: Keep debugger connection during SLEEP mode + * @arg DBGMCU_STOP: Keep debugger connection during STOP mode + * @arg DBGMCU_STANDBY: Keep debugger connection during STANDBY mode + * @arg DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted + * @arg DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted + * @arg DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted + * @arg DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted + * @arg DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted + * @arg DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted + * @arg DBGMCU_CAN1_STOP: Debug CAN2 stopped when Core is halted + * @arg DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped when Core is halted + * @arg DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped when Core is halted + * @arg DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted + * @arg DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted + * @arg DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted + * @arg DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted + * @arg DBGMCU_CAN2_STOP: Debug CAN2 stopped when Core is halted + * @arg DBGMCU_TIM15_STOP: TIM15 counter stopped when Core is halted + * @arg DBGMCU_TIM16_STOP: TIM16 counter stopped when Core is halted + * @arg DBGMCU_TIM17_STOP: TIM17 counter stopped when Core is halted + * @arg DBGMCU_TIM9_STOP: TIM9 counter stopped when Core is halted + * @arg DBGMCU_TIM10_STOP: TIM10 counter stopped when Core is halted + * @arg DBGMCU_TIM11_STOP: TIM11 counter stopped when Core is halted + * @arg DBGMCU_TIM12_STOP: TIM12 counter stopped when Core is halted + * @arg DBGMCU_TIM13_STOP: TIM13 counter stopped when Core is halted + * @arg DBGMCU_TIM14_STOP: TIM14 counter stopped when Core is halted + * @param NewState: new state of the specified peripheral in Debug mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + DBGMCU->CR |= DBGMCU_Periph; + } + else + { + DBGMCU->CR &= ~DBGMCU_Periph; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c index 662b4fe64..2fe8349d7 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c @@ -1,711 +1,711 @@ -/** - ****************************************************************************** - * @file stm32f10x_dma.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the DMA firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_dma.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup DMA - * @brief DMA driver modules - * @{ - */ - -/** @defgroup DMA_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - -/** @defgroup DMA_Private_Defines - * @{ - */ - - -/* DMA1 Channelx interrupt pending bit masks */ -#define DMA1_Channel1_IT_Mask ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1)) -#define DMA1_Channel2_IT_Mask ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2)) -#define DMA1_Channel3_IT_Mask ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3)) -#define DMA1_Channel4_IT_Mask ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4)) -#define DMA1_Channel5_IT_Mask ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5)) -#define DMA1_Channel6_IT_Mask ((uint32_t)(DMA_ISR_GIF6 | DMA_ISR_TCIF6 | DMA_ISR_HTIF6 | DMA_ISR_TEIF6)) -#define DMA1_Channel7_IT_Mask ((uint32_t)(DMA_ISR_GIF7 | DMA_ISR_TCIF7 | DMA_ISR_HTIF7 | DMA_ISR_TEIF7)) - -/* DMA2 Channelx interrupt pending bit masks */ -#define DMA2_Channel1_IT_Mask ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1)) -#define DMA2_Channel2_IT_Mask ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2)) -#define DMA2_Channel3_IT_Mask ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3)) -#define DMA2_Channel4_IT_Mask ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4)) -#define DMA2_Channel5_IT_Mask ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5)) - -/* DMA2 FLAG mask */ -#define FLAG_Mask ((uint32_t)0x10000000) - -/* DMA registers Masks */ -#define CCR_CLEAR_Mask ((uint32_t)0xFFFF800F) - -/** - * @} - */ - -/** @defgroup DMA_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup DMA_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup DMA_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup DMA_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the DMAy Channelx registers to their default reset - * values. - * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and - * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. - * @retval None - */ -void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx) -{ - /* Check the parameters */ - assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); - - /* Disable the selected DMAy Channelx */ - DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR1_EN); - - /* Reset DMAy Channelx control register */ - DMAy_Channelx->CCR = 0; - - /* Reset DMAy Channelx remaining bytes register */ - DMAy_Channelx->CNDTR = 0; - - /* Reset DMAy Channelx peripheral address register */ - DMAy_Channelx->CPAR = 0; - - /* Reset DMAy Channelx memory address register */ - DMAy_Channelx->CMAR = 0; - - if (DMAy_Channelx == DMA1_Channel1) - { - /* Reset interrupt pending bits for DMA1 Channel1 */ - DMA1->IFCR |= DMA1_Channel1_IT_Mask; - } - else if (DMAy_Channelx == DMA1_Channel2) - { - /* Reset interrupt pending bits for DMA1 Channel2 */ - DMA1->IFCR |= DMA1_Channel2_IT_Mask; - } - else if (DMAy_Channelx == DMA1_Channel3) - { - /* Reset interrupt pending bits for DMA1 Channel3 */ - DMA1->IFCR |= DMA1_Channel3_IT_Mask; - } - else if (DMAy_Channelx == DMA1_Channel4) - { - /* Reset interrupt pending bits for DMA1 Channel4 */ - DMA1->IFCR |= DMA1_Channel4_IT_Mask; - } - else if (DMAy_Channelx == DMA1_Channel5) - { - /* Reset interrupt pending bits for DMA1 Channel5 */ - DMA1->IFCR |= DMA1_Channel5_IT_Mask; - } - else if (DMAy_Channelx == DMA1_Channel6) - { - /* Reset interrupt pending bits for DMA1 Channel6 */ - DMA1->IFCR |= DMA1_Channel6_IT_Mask; - } - else if (DMAy_Channelx == DMA1_Channel7) - { - /* Reset interrupt pending bits for DMA1 Channel7 */ - DMA1->IFCR |= DMA1_Channel7_IT_Mask; - } - else if (DMAy_Channelx == DMA2_Channel1) - { - /* Reset interrupt pending bits for DMA2 Channel1 */ - DMA2->IFCR |= DMA2_Channel1_IT_Mask; - } - else if (DMAy_Channelx == DMA2_Channel2) - { - /* Reset interrupt pending bits for DMA2 Channel2 */ - DMA2->IFCR |= DMA2_Channel2_IT_Mask; - } - else if (DMAy_Channelx == DMA2_Channel3) - { - /* Reset interrupt pending bits for DMA2 Channel3 */ - DMA2->IFCR |= DMA2_Channel3_IT_Mask; - } - else if (DMAy_Channelx == DMA2_Channel4) - { - /* Reset interrupt pending bits for DMA2 Channel4 */ - DMA2->IFCR |= DMA2_Channel4_IT_Mask; - } - else - { - if (DMAy_Channelx == DMA2_Channel5) - { - /* Reset interrupt pending bits for DMA2 Channel5 */ - DMA2->IFCR |= DMA2_Channel5_IT_Mask; - } - } -} - -/** - * @brief Initializes the DMAy Channelx according to the specified - * parameters in the DMA_InitStruct. - * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and - * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. - * @param DMA_InitStruct: pointer to a DMA_InitTypeDef structure that - * contains the configuration information for the specified DMA Channel. - * @retval None - */ -void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, const DMA_InitTypeDef* DMA_InitStruct) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); - assert_param(IS_DMA_DIR(DMA_InitStruct->DMA_DIR)); - assert_param(IS_DMA_BUFFER_SIZE(DMA_InitStruct->DMA_BufferSize)); - assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc)); - assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc)); - assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize)); - assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize)); - assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode)); - assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority)); - assert_param(IS_DMA_M2M_STATE(DMA_InitStruct->DMA_M2M)); - -/*--------------------------- DMAy Channelx CCR Configuration -----------------*/ - /* Get the DMAy_Channelx CCR value */ - tmpreg = DMAy_Channelx->CCR; - /* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */ - tmpreg &= CCR_CLEAR_Mask; - /* Configure DMAy Channelx: data transfer, data size, priority level and mode */ - /* Set DIR bit according to DMA_DIR value */ - /* Set CIRC bit according to DMA_Mode value */ - /* Set PINC bit according to DMA_PeripheralInc value */ - /* Set MINC bit according to DMA_MemoryInc value */ - /* Set PSIZE bits according to DMA_PeripheralDataSize value */ - /* Set MSIZE bits according to DMA_MemoryDataSize value */ - /* Set PL bits according to DMA_Priority value */ - /* Set the MEM2MEM bit according to DMA_M2M value */ - tmpreg |= DMA_InitStruct->DMA_DIR | DMA_InitStruct->DMA_Mode | - DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc | - DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize | - DMA_InitStruct->DMA_Priority | DMA_InitStruct->DMA_M2M; - - /* Write to DMAy Channelx CCR */ - DMAy_Channelx->CCR = tmpreg; - -/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/ - /* Write to DMAy Channelx CNDTR */ - DMAy_Channelx->CNDTR = DMA_InitStruct->DMA_BufferSize; - -/*--------------------------- DMAy Channelx CPAR Configuration ----------------*/ - /* Write to DMAy Channelx CPAR */ - DMAy_Channelx->CPAR = DMA_InitStruct->DMA_PeripheralBaseAddr; - -/*--------------------------- DMAy Channelx CMAR Configuration ----------------*/ - /* Write to DMAy Channelx CMAR */ - DMAy_Channelx->CMAR = DMA_InitStruct->DMA_MemoryBaseAddr; -} - -/** - * @brief Fills each DMA_InitStruct member with its default value. - * @param DMA_InitStruct : pointer to a DMA_InitTypeDef structure which will - * be initialized. - * @retval None - */ -void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct) -{ -/*-------------- Reset DMA init structure parameters values ------------------*/ - /* Initialize the DMA_PeripheralBaseAddr member */ - DMA_InitStruct->DMA_PeripheralBaseAddr = 0; - /* Initialize the DMA_MemoryBaseAddr member */ - DMA_InitStruct->DMA_MemoryBaseAddr = 0; - /* Initialize the DMA_DIR member */ - DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralSRC; - /* Initialize the DMA_BufferSize member */ - DMA_InitStruct->DMA_BufferSize = 0; - /* Initialize the DMA_PeripheralInc member */ - DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable; - /* Initialize the DMA_MemoryInc member */ - DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable; - /* Initialize the DMA_PeripheralDataSize member */ - DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; - /* Initialize the DMA_MemoryDataSize member */ - DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; - /* Initialize the DMA_Mode member */ - DMA_InitStruct->DMA_Mode = DMA_Mode_Normal; - /* Initialize the DMA_Priority member */ - DMA_InitStruct->DMA_Priority = DMA_Priority_Low; - /* Initialize the DMA_M2M member */ - DMA_InitStruct->DMA_M2M = DMA_M2M_Disable; -} - -/** - * @brief Enables or disables the specified DMAy Channelx. - * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and - * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. - * @param NewState: new state of the DMAy Channelx. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the selected DMAy Channelx */ - DMAy_Channelx->CCR |= DMA_CCR1_EN; - } - else - { - /* Disable the selected DMAy Channelx */ - DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR1_EN); - } -} - -/** - * @brief Enables or disables the specified DMAy Channelx interrupts. - * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and - * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. - * @param DMA_IT: specifies the DMA interrupts sources to be enabled - * or disabled. - * This parameter can be any combination of the following values: - * @arg DMA_IT_TC: Transfer complete interrupt mask - * @arg DMA_IT_HT: Half transfer interrupt mask - * @arg DMA_IT_TE: Transfer error interrupt mask - * @param NewState: new state of the specified DMA interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); - assert_param(IS_DMA_CONFIG_IT(DMA_IT)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected DMA interrupts */ - DMAy_Channelx->CCR |= DMA_IT; - } - else - { - /* Disable the selected DMA interrupts */ - DMAy_Channelx->CCR &= ~DMA_IT; - } -} - -/** - * @brief Sets the number of data units in the current DMAy Channelx transfer. - * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and - * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. - * @param DataNumber: The number of data units in the current DMAy Channelx - * transfer. - * @note This function can only be used when the DMAy_Channelx is disabled. - * @retval None. - */ -void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber) -{ - /* Check the parameters */ - assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); - -/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/ - /* Write to DMAy Channelx CNDTR */ - DMAy_Channelx->CNDTR = DataNumber; -} - -/** - * @brief Returns the number of remaining data units in the current - * DMAy Channelx transfer. - * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and - * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. - * @retval The number of remaining data units in the current DMAy Channelx - * transfer. - */ -uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx) -{ - /* Check the parameters */ - assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); - /* Return the number of remaining data units for DMAy Channelx */ - return ((uint16_t)(DMAy_Channelx->CNDTR)); -} - -/** - * @brief Checks whether the specified DMAy Channelx flag is set or not. - * @param DMA_FLAG: specifies the flag to check. - * This parameter can be one of the following values: - * @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag. - * @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag. - * @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag. - * @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag. - * @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag. - * @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag. - * @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag. - * @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag. - * @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag. - * @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag. - * @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag. - * @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag. - * @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag. - * @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag. - * @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag. - * @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag. - * @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag. - * @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag. - * @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag. - * @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag. - * @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag. - * @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag. - * @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag. - * @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag. - * @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag. - * @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag. - * @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag. - * @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag. - * @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag. - * @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag. - * @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag. - * @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag. - * @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag. - * @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag. - * @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag. - * @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag. - * @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag. - * @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag. - * @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag. - * @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag. - * @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag. - * @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag. - * @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag. - * @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag. - * @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag. - * @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag. - * @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag. - * @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag. - * @retval The new state of DMA_FLAG (SET or RESET). - */ -FlagStatus DMA_GetFlagStatus(uint32_t DMA_FLAG) -{ - FlagStatus bitstatus = RESET; - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_DMA_GET_FLAG(DMA_FLAG)); - - /* Calculate the used DMA */ - if ((DMA_FLAG & FLAG_Mask) != (uint32_t)RESET) - { - /* Get DMA2 ISR register value */ - tmpreg = DMA2->ISR ; - } - else - { - /* Get DMA1 ISR register value */ - tmpreg = DMA1->ISR ; - } - - /* Check the status of the specified DMA flag */ - if ((tmpreg & DMA_FLAG) != (uint32_t)RESET) - { - /* DMA_FLAG is set */ - bitstatus = SET; - } - else - { - /* DMA_FLAG is reset */ - bitstatus = RESET; - } - - /* Return the DMA_FLAG status */ - return bitstatus; -} - -/** - * @brief Clears the DMAy Channelx's pending flags. - * @param DMA_FLAG: specifies the flag to clear. - * This parameter can be any combination (for the same DMA) of the following values: - * @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag. - * @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag. - * @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag. - * @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag. - * @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag. - * @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag. - * @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag. - * @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag. - * @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag. - * @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag. - * @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag. - * @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag. - * @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag. - * @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag. - * @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag. - * @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag. - * @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag. - * @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag. - * @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag. - * @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag. - * @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag. - * @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag. - * @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag. - * @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag. - * @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag. - * @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag. - * @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag. - * @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag. - * @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag. - * @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag. - * @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag. - * @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag. - * @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag. - * @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag. - * @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag. - * @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag. - * @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag. - * @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag. - * @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag. - * @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag. - * @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag. - * @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag. - * @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag. - * @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag. - * @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag. - * @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag. - * @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag. - * @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag. - * @retval None - */ -void DMA_ClearFlag(uint32_t DMA_FLAG) -{ - /* Check the parameters */ - assert_param(IS_DMA_CLEAR_FLAG(DMA_FLAG)); - /* Calculate the used DMA */ - - if ((DMA_FLAG & FLAG_Mask) != (uint32_t)RESET) - { - /* Clear the selected DMA flags */ - DMA2->IFCR = DMA_FLAG; - } - else - { - /* Clear the selected DMA flags */ - DMA1->IFCR = DMA_FLAG; - } -} - -/** - * @brief Checks whether the specified DMAy Channelx interrupt has occurred or not. - * @param DMA_IT: specifies the DMA interrupt source to check. - * This parameter can be one of the following values: - * @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt. - * @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt. - * @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt. - * @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt. - * @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt. - * @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt. - * @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt. - * @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt. - * @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt. - * @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt. - * @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt. - * @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt. - * @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt. - * @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt. - * @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt. - * @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt. - * @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt. - * @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt. - * @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt. - * @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt. - * @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt. - * @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt. - * @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt. - * @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt. - * @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt. - * @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt. - * @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt. - * @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt. - * @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt. - * @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt. - * @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt. - * @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt. - * @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt. - * @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt. - * @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt. - * @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt. - * @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt. - * @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt. - * @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt. - * @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt. - * @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt. - * @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt. - * @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt. - * @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt. - * @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt. - * @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt. - * @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt. - * @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt. - * @retval The new state of DMA_IT (SET or RESET). - */ -ITStatus DMA_GetITStatus(uint32_t DMA_IT) -{ - ITStatus bitstatus = RESET; - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_DMA_GET_IT(DMA_IT)); - - /* Calculate the used DMA */ - if ((DMA_IT & FLAG_Mask) != (uint32_t)RESET) - { - /* Get DMA2 ISR register value */ - tmpreg = DMA2->ISR ; - } - else - { - /* Get DMA1 ISR register value */ - tmpreg = DMA1->ISR ; - } - - /* Check the status of the specified DMA interrupt */ - if ((tmpreg & DMA_IT) != (uint32_t)RESET) - { - /* DMA_IT is set */ - bitstatus = SET; - } - else - { - /* DMA_IT is reset */ - bitstatus = RESET; - } - /* Return the DMA_IT status */ - return bitstatus; -} - -/** - * @brief Clears the DMAy Channelx’s interrupt pending bits. - * @param DMA_IT: specifies the DMA interrupt pending bit to clear. - * This parameter can be any combination (for the same DMA) of the following values: - * @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt. - * @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt. - * @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt. - * @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt. - * @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt. - * @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt. - * @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt. - * @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt. - * @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt. - * @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt. - * @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt. - * @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt. - * @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt. - * @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt. - * @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt. - * @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt. - * @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt. - * @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt. - * @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt. - * @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt. - * @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt. - * @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt. - * @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt. - * @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt. - * @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt. - * @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt. - * @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt. - * @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt. - * @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt. - * @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt. - * @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt. - * @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt. - * @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt. - * @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt. - * @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt. - * @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt. - * @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt. - * @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt. - * @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt. - * @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt. - * @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt. - * @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt. - * @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt. - * @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt. - * @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt. - * @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt. - * @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt. - * @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt. - * @retval None - */ -void DMA_ClearITPendingBit(uint32_t DMA_IT) -{ - /* Check the parameters */ - assert_param(IS_DMA_CLEAR_IT(DMA_IT)); - - /* Calculate the used DMA */ - if ((DMA_IT & FLAG_Mask) != (uint32_t)RESET) - { - /* Clear the selected DMA interrupt pending bits */ - DMA2->IFCR = DMA_IT; - } - else - { - /* Clear the selected DMA interrupt pending bits */ - DMA1->IFCR = DMA_IT; - } -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_dma.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the DMA firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_dma.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DMA + * @brief DMA driver modules + * @{ + */ + +/** @defgroup DMA_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + +/** @defgroup DMA_Private_Defines + * @{ + */ + + +/* DMA1 Channelx interrupt pending bit masks */ +#define DMA1_Channel1_IT_Mask ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1)) +#define DMA1_Channel2_IT_Mask ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2)) +#define DMA1_Channel3_IT_Mask ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3)) +#define DMA1_Channel4_IT_Mask ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4)) +#define DMA1_Channel5_IT_Mask ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5)) +#define DMA1_Channel6_IT_Mask ((uint32_t)(DMA_ISR_GIF6 | DMA_ISR_TCIF6 | DMA_ISR_HTIF6 | DMA_ISR_TEIF6)) +#define DMA1_Channel7_IT_Mask ((uint32_t)(DMA_ISR_GIF7 | DMA_ISR_TCIF7 | DMA_ISR_HTIF7 | DMA_ISR_TEIF7)) + +/* DMA2 Channelx interrupt pending bit masks */ +#define DMA2_Channel1_IT_Mask ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1)) +#define DMA2_Channel2_IT_Mask ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2)) +#define DMA2_Channel3_IT_Mask ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3)) +#define DMA2_Channel4_IT_Mask ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4)) +#define DMA2_Channel5_IT_Mask ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5)) + +/* DMA2 FLAG mask */ +#define FLAG_Mask ((uint32_t)0x10000000) + +/* DMA registers Masks */ +#define CCR_CLEAR_Mask ((uint32_t)0xFFFF800F) + +/** + * @} + */ + +/** @defgroup DMA_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the DMAy Channelx registers to their default reset + * values. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @retval None + */ +void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + + /* Disable the selected DMAy Channelx */ + DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR1_EN); + + /* Reset DMAy Channelx control register */ + DMAy_Channelx->CCR = 0; + + /* Reset DMAy Channelx remaining bytes register */ + DMAy_Channelx->CNDTR = 0; + + /* Reset DMAy Channelx peripheral address register */ + DMAy_Channelx->CPAR = 0; + + /* Reset DMAy Channelx memory address register */ + DMAy_Channelx->CMAR = 0; + + if (DMAy_Channelx == DMA1_Channel1) + { + /* Reset interrupt pending bits for DMA1 Channel1 */ + DMA1->IFCR |= DMA1_Channel1_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel2) + { + /* Reset interrupt pending bits for DMA1 Channel2 */ + DMA1->IFCR |= DMA1_Channel2_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel3) + { + /* Reset interrupt pending bits for DMA1 Channel3 */ + DMA1->IFCR |= DMA1_Channel3_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel4) + { + /* Reset interrupt pending bits for DMA1 Channel4 */ + DMA1->IFCR |= DMA1_Channel4_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel5) + { + /* Reset interrupt pending bits for DMA1 Channel5 */ + DMA1->IFCR |= DMA1_Channel5_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel6) + { + /* Reset interrupt pending bits for DMA1 Channel6 */ + DMA1->IFCR |= DMA1_Channel6_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel7) + { + /* Reset interrupt pending bits for DMA1 Channel7 */ + DMA1->IFCR |= DMA1_Channel7_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel1) + { + /* Reset interrupt pending bits for DMA2 Channel1 */ + DMA2->IFCR |= DMA2_Channel1_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel2) + { + /* Reset interrupt pending bits for DMA2 Channel2 */ + DMA2->IFCR |= DMA2_Channel2_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel3) + { + /* Reset interrupt pending bits for DMA2 Channel3 */ + DMA2->IFCR |= DMA2_Channel3_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel4) + { + /* Reset interrupt pending bits for DMA2 Channel4 */ + DMA2->IFCR |= DMA2_Channel4_IT_Mask; + } + else + { + if (DMAy_Channelx == DMA2_Channel5) + { + /* Reset interrupt pending bits for DMA2 Channel5 */ + DMA2->IFCR |= DMA2_Channel5_IT_Mask; + } + } +} + +/** + * @brief Initializes the DMAy Channelx according to the specified + * parameters in the DMA_InitStruct. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DMA_InitStruct: pointer to a DMA_InitTypeDef structure that + * contains the configuration information for the specified DMA Channel. + * @retval None + */ +void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, const DMA_InitTypeDef* DMA_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_DMA_DIR(DMA_InitStruct->DMA_DIR)); + assert_param(IS_DMA_BUFFER_SIZE(DMA_InitStruct->DMA_BufferSize)); + assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc)); + assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc)); + assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize)); + assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize)); + assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode)); + assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority)); + assert_param(IS_DMA_M2M_STATE(DMA_InitStruct->DMA_M2M)); + +/*--------------------------- DMAy Channelx CCR Configuration -----------------*/ + /* Get the DMAy_Channelx CCR value */ + tmpreg = DMAy_Channelx->CCR; + /* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */ + tmpreg &= CCR_CLEAR_Mask; + /* Configure DMAy Channelx: data transfer, data size, priority level and mode */ + /* Set DIR bit according to DMA_DIR value */ + /* Set CIRC bit according to DMA_Mode value */ + /* Set PINC bit according to DMA_PeripheralInc value */ + /* Set MINC bit according to DMA_MemoryInc value */ + /* Set PSIZE bits according to DMA_PeripheralDataSize value */ + /* Set MSIZE bits according to DMA_MemoryDataSize value */ + /* Set PL bits according to DMA_Priority value */ + /* Set the MEM2MEM bit according to DMA_M2M value */ + tmpreg |= DMA_InitStruct->DMA_DIR | DMA_InitStruct->DMA_Mode | + DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc | + DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize | + DMA_InitStruct->DMA_Priority | DMA_InitStruct->DMA_M2M; + + /* Write to DMAy Channelx CCR */ + DMAy_Channelx->CCR = tmpreg; + +/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/ + /* Write to DMAy Channelx CNDTR */ + DMAy_Channelx->CNDTR = DMA_InitStruct->DMA_BufferSize; + +/*--------------------------- DMAy Channelx CPAR Configuration ----------------*/ + /* Write to DMAy Channelx CPAR */ + DMAy_Channelx->CPAR = DMA_InitStruct->DMA_PeripheralBaseAddr; + +/*--------------------------- DMAy Channelx CMAR Configuration ----------------*/ + /* Write to DMAy Channelx CMAR */ + DMAy_Channelx->CMAR = DMA_InitStruct->DMA_MemoryBaseAddr; +} + +/** + * @brief Fills each DMA_InitStruct member with its default value. + * @param DMA_InitStruct : pointer to a DMA_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct) +{ +/*-------------- Reset DMA init structure parameters values ------------------*/ + /* Initialize the DMA_PeripheralBaseAddr member */ + DMA_InitStruct->DMA_PeripheralBaseAddr = 0; + /* Initialize the DMA_MemoryBaseAddr member */ + DMA_InitStruct->DMA_MemoryBaseAddr = 0; + /* Initialize the DMA_DIR member */ + DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralSRC; + /* Initialize the DMA_BufferSize member */ + DMA_InitStruct->DMA_BufferSize = 0; + /* Initialize the DMA_PeripheralInc member */ + DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable; + /* Initialize the DMA_MemoryInc member */ + DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable; + /* Initialize the DMA_PeripheralDataSize member */ + DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + /* Initialize the DMA_MemoryDataSize member */ + DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + /* Initialize the DMA_Mode member */ + DMA_InitStruct->DMA_Mode = DMA_Mode_Normal; + /* Initialize the DMA_Priority member */ + DMA_InitStruct->DMA_Priority = DMA_Priority_Low; + /* Initialize the DMA_M2M member */ + DMA_InitStruct->DMA_M2M = DMA_M2M_Disable; +} + +/** + * @brief Enables or disables the specified DMAy Channelx. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param NewState: new state of the DMAy Channelx. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected DMAy Channelx */ + DMAy_Channelx->CCR |= DMA_CCR1_EN; + } + else + { + /* Disable the selected DMAy Channelx */ + DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR1_EN); + } +} + +/** + * @brief Enables or disables the specified DMAy Channelx interrupts. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DMA_IT: specifies the DMA interrupts sources to be enabled + * or disabled. + * This parameter can be any combination of the following values: + * @arg DMA_IT_TC: Transfer complete interrupt mask + * @arg DMA_IT_HT: Half transfer interrupt mask + * @arg DMA_IT_TE: Transfer error interrupt mask + * @param NewState: new state of the specified DMA interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_DMA_CONFIG_IT(DMA_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected DMA interrupts */ + DMAy_Channelx->CCR |= DMA_IT; + } + else + { + /* Disable the selected DMA interrupts */ + DMAy_Channelx->CCR &= ~DMA_IT; + } +} + +/** + * @brief Sets the number of data units in the current DMAy Channelx transfer. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DataNumber: The number of data units in the current DMAy Channelx + * transfer. + * @note This function can only be used when the DMAy_Channelx is disabled. + * @retval None. + */ +void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + +/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/ + /* Write to DMAy Channelx CNDTR */ + DMAy_Channelx->CNDTR = DataNumber; +} + +/** + * @brief Returns the number of remaining data units in the current + * DMAy Channelx transfer. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @retval The number of remaining data units in the current DMAy Channelx + * transfer. + */ +uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + /* Return the number of remaining data units for DMAy Channelx */ + return ((uint16_t)(DMAy_Channelx->CNDTR)); +} + +/** + * @brief Checks whether the specified DMAy Channelx flag is set or not. + * @param DMA_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag. + * @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag. + * @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag. + * @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag. + * @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag. + * @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag. + * @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag. + * @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag. + * @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag. + * @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag. + * @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag. + * @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag. + * @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag. + * @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag. + * @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag. + * @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag. + * @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag. + * @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag. + * @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag. + * @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag. + * @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag. + * @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag. + * @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag. + * @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag. + * @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag. + * @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag. + * @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag. + * @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag. + * @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag. + * @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag. + * @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag. + * @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag. + * @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag. + * @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag. + * @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag. + * @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag. + * @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag. + * @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag. + * @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag. + * @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag. + * @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag. + * @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag. + * @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag. + * @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag. + * @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag. + * @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag. + * @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag. + * @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag. + * @retval The new state of DMA_FLAG (SET or RESET). + */ +FlagStatus DMA_GetFlagStatus(uint32_t DMA_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_DMA_GET_FLAG(DMA_FLAG)); + + /* Calculate the used DMA */ + if ((DMA_FLAG & FLAG_Mask) != (uint32_t)RESET) + { + /* Get DMA2 ISR register value */ + tmpreg = DMA2->ISR ; + } + else + { + /* Get DMA1 ISR register value */ + tmpreg = DMA1->ISR ; + } + + /* Check the status of the specified DMA flag */ + if ((tmpreg & DMA_FLAG) != (uint32_t)RESET) + { + /* DMA_FLAG is set */ + bitstatus = SET; + } + else + { + /* DMA_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the DMA_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DMAy Channelx's pending flags. + * @param DMA_FLAG: specifies the flag to clear. + * This parameter can be any combination (for the same DMA) of the following values: + * @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag. + * @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag. + * @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag. + * @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag. + * @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag. + * @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag. + * @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag. + * @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag. + * @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag. + * @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag. + * @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag. + * @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag. + * @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag. + * @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag. + * @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag. + * @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag. + * @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag. + * @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag. + * @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag. + * @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag. + * @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag. + * @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag. + * @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag. + * @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag. + * @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag. + * @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag. + * @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag. + * @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag. + * @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag. + * @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag. + * @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag. + * @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag. + * @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag. + * @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag. + * @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag. + * @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag. + * @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag. + * @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag. + * @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag. + * @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag. + * @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag. + * @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag. + * @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag. + * @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag. + * @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag. + * @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag. + * @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag. + * @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag. + * @retval None + */ +void DMA_ClearFlag(uint32_t DMA_FLAG) +{ + /* Check the parameters */ + assert_param(IS_DMA_CLEAR_FLAG(DMA_FLAG)); + /* Calculate the used DMA */ + + if ((DMA_FLAG & FLAG_Mask) != (uint32_t)RESET) + { + /* Clear the selected DMA flags */ + DMA2->IFCR = DMA_FLAG; + } + else + { + /* Clear the selected DMA flags */ + DMA1->IFCR = DMA_FLAG; + } +} + +/** + * @brief Checks whether the specified DMAy Channelx interrupt has occurred or not. + * @param DMA_IT: specifies the DMA interrupt source to check. + * This parameter can be one of the following values: + * @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt. + * @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt. + * @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt. + * @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt. + * @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt. + * @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt. + * @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt. + * @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt. + * @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt. + * @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt. + * @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt. + * @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt. + * @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt. + * @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt. + * @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt. + * @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt. + * @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt. + * @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt. + * @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt. + * @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt. + * @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt. + * @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt. + * @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt. + * @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt. + * @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt. + * @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt. + * @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt. + * @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt. + * @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt. + * @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt. + * @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt. + * @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt. + * @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt. + * @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt. + * @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt. + * @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt. + * @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt. + * @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt. + * @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt. + * @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt. + * @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt. + * @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt. + * @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt. + * @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt. + * @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt. + * @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt. + * @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt. + * @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt. + * @retval The new state of DMA_IT (SET or RESET). + */ +ITStatus DMA_GetITStatus(uint32_t DMA_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_DMA_GET_IT(DMA_IT)); + + /* Calculate the used DMA */ + if ((DMA_IT & FLAG_Mask) != (uint32_t)RESET) + { + /* Get DMA2 ISR register value */ + tmpreg = DMA2->ISR ; + } + else + { + /* Get DMA1 ISR register value */ + tmpreg = DMA1->ISR ; + } + + /* Check the status of the specified DMA interrupt */ + if ((tmpreg & DMA_IT) != (uint32_t)RESET) + { + /* DMA_IT is set */ + bitstatus = SET; + } + else + { + /* DMA_IT is reset */ + bitstatus = RESET; + } + /* Return the DMA_IT status */ + return bitstatus; +} + +/** + * @brief Clears the DMAy Channelx’s interrupt pending bits. + * @param DMA_IT: specifies the DMA interrupt pending bit to clear. + * This parameter can be any combination (for the same DMA) of the following values: + * @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt. + * @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt. + * @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt. + * @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt. + * @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt. + * @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt. + * @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt. + * @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt. + * @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt. + * @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt. + * @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt. + * @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt. + * @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt. + * @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt. + * @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt. + * @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt. + * @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt. + * @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt. + * @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt. + * @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt. + * @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt. + * @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt. + * @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt. + * @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt. + * @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt. + * @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt. + * @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt. + * @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt. + * @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt. + * @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt. + * @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt. + * @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt. + * @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt. + * @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt. + * @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt. + * @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt. + * @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt. + * @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt. + * @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt. + * @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt. + * @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt. + * @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt. + * @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt. + * @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt. + * @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt. + * @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt. + * @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt. + * @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt. + * @retval None + */ +void DMA_ClearITPendingBit(uint32_t DMA_IT) +{ + /* Check the parameters */ + assert_param(IS_DMA_CLEAR_IT(DMA_IT)); + + /* Calculate the used DMA */ + if ((DMA_IT & FLAG_Mask) != (uint32_t)RESET) + { + /* Clear the selected DMA interrupt pending bits */ + DMA2->IFCR = DMA_IT; + } + else + { + /* Clear the selected DMA interrupt pending bits */ + DMA1->IFCR = DMA_IT; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c index 73de195cb..4e1d1b066 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c @@ -1,268 +1,268 @@ -/** - ****************************************************************************** - * @file stm32f10x_exti.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the EXTI firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_exti.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup EXTI - * @brief EXTI driver modules - * @{ - */ - -/** @defgroup EXTI_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup EXTI_Private_Defines - * @{ - */ - -#define EXTI_LINENONE ((uint32_t)0x00000) /* No interrupt selected */ - -/** - * @} - */ - -/** @defgroup EXTI_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup EXTI_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup EXTI_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup EXTI_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the EXTI peripheral registers to their default reset values. - * @param None - * @retval None - */ -void EXTI_DeInit(void) -{ - EXTI->IMR = 0x00000000; - EXTI->EMR = 0x00000000; - EXTI->RTSR = 0x00000000; - EXTI->FTSR = 0x00000000; - EXTI->PR = 0x000FFFFF; -} - -/** - * @brief Initializes the EXTI peripheral according to the specified - * parameters in the EXTI_InitStruct. - * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure - * that contains the configuration information for the EXTI peripheral. - * @retval None - */ -void EXTI_Init(const EXTI_InitTypeDef* EXTI_InitStruct) -{ - uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode)); - assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger)); - assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line)); - assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd)); - - tmp = (uint32_t)EXTI_BASE; - - if (EXTI_InitStruct->EXTI_LineCmd != DISABLE) - { - /* Clear EXTI line configuration */ - EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line; - EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line; - - tmp += EXTI_InitStruct->EXTI_Mode; - - *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line; - - /* Clear Rising Falling edge configuration */ - EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line; - EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line; - - /* Select the trigger for the selected external interrupts */ - if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling) - { - /* Rising Falling edge */ - EXTI->RTSR |= EXTI_InitStruct->EXTI_Line; - EXTI->FTSR |= EXTI_InitStruct->EXTI_Line; - } - else - { - tmp = (uint32_t)EXTI_BASE; - tmp += EXTI_InitStruct->EXTI_Trigger; - - *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line; - } - } - else - { - tmp += EXTI_InitStruct->EXTI_Mode; - - /* Disable the selected external lines */ - *(__IO uint32_t *) tmp &= ~EXTI_InitStruct->EXTI_Line; - } -} - -/** - * @brief Fills each EXTI_InitStruct member with its reset value. - * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure which will - * be initialized. - * @retval None - */ -void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct) -{ - EXTI_InitStruct->EXTI_Line = EXTI_LINENONE; - EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt; - EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling; - EXTI_InitStruct->EXTI_LineCmd = DISABLE; -} - -/** - * @brief Generates a Software interrupt. - * @param EXTI_Line: specifies the EXTI lines to be enabled or disabled. - * This parameter can be any combination of EXTI_Linex where x can be (0..19). - * @retval None - */ -void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line) -{ - /* Check the parameters */ - assert_param(IS_EXTI_LINE(EXTI_Line)); - - EXTI->SWIER |= EXTI_Line; -} - -/** - * @brief Checks whether the specified EXTI line flag is set or not. - * @param EXTI_Line: specifies the EXTI line flag to check. - * This parameter can be: - * @arg EXTI_Linex: External interrupt line x where x(0..19) - * @retval The new state of EXTI_Line (SET or RESET). - */ -FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_GET_EXTI_LINE(EXTI_Line)); - - if ((EXTI->PR & EXTI_Line) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - return bitstatus; -} - -/** - * @brief Clears the EXTI’s line pending flags. - * @param EXTI_Line: specifies the EXTI lines flags to clear. - * This parameter can be any combination of EXTI_Linex where x can be (0..19). - * @retval None - */ -void EXTI_ClearFlag(uint32_t EXTI_Line) -{ - /* Check the parameters */ - assert_param(IS_EXTI_LINE(EXTI_Line)); - - EXTI->PR = EXTI_Line; -} - -/** - * @brief Checks whether the specified EXTI line is asserted or not. - * @param EXTI_Line: specifies the EXTI line to check. - * This parameter can be: - * @arg EXTI_Linex: External interrupt line x where x(0..19) - * @retval The new state of EXTI_Line (SET or RESET). - */ -ITStatus EXTI_GetITStatus(uint32_t EXTI_Line) -{ - ITStatus bitstatus = RESET; - uint32_t enablestatus = 0; - /* Check the parameters */ - assert_param(IS_GET_EXTI_LINE(EXTI_Line)); - - enablestatus = EXTI->IMR & EXTI_Line; - if (((EXTI->PR & EXTI_Line) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET)) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - return bitstatus; -} - -/** - * @brief Clears the EXTI’s line pending bits. - * @param EXTI_Line: specifies the EXTI lines to clear. - * This parameter can be any combination of EXTI_Linex where x can be (0..19). - * @retval None - */ -void EXTI_ClearITPendingBit(uint32_t EXTI_Line) -{ - /* Check the parameters */ - assert_param(IS_EXTI_LINE(EXTI_Line)); - - EXTI->PR = EXTI_Line; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_exti.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the EXTI firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_exti.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup EXTI + * @brief EXTI driver modules + * @{ + */ + +/** @defgroup EXTI_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Defines + * @{ + */ + +#define EXTI_LINENONE ((uint32_t)0x00000) /* No interrupt selected */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the EXTI peripheral registers to their default reset values. + * @param None + * @retval None + */ +void EXTI_DeInit(void) +{ + EXTI->IMR = 0x00000000; + EXTI->EMR = 0x00000000; + EXTI->RTSR = 0x00000000; + EXTI->FTSR = 0x00000000; + EXTI->PR = 0x000FFFFF; +} + +/** + * @brief Initializes the EXTI peripheral according to the specified + * parameters in the EXTI_InitStruct. + * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure + * that contains the configuration information for the EXTI peripheral. + * @retval None + */ +void EXTI_Init(const EXTI_InitTypeDef* EXTI_InitStruct) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode)); + assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger)); + assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line)); + assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd)); + + tmp = (uint32_t)EXTI_BASE; + + if (EXTI_InitStruct->EXTI_LineCmd != DISABLE) + { + /* Clear EXTI line configuration */ + EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line; + EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line; + + tmp += EXTI_InitStruct->EXTI_Mode; + + *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line; + + /* Clear Rising Falling edge configuration */ + EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line; + EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line; + + /* Select the trigger for the selected external interrupts */ + if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling) + { + /* Rising Falling edge */ + EXTI->RTSR |= EXTI_InitStruct->EXTI_Line; + EXTI->FTSR |= EXTI_InitStruct->EXTI_Line; + } + else + { + tmp = (uint32_t)EXTI_BASE; + tmp += EXTI_InitStruct->EXTI_Trigger; + + *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line; + } + } + else + { + tmp += EXTI_InitStruct->EXTI_Mode; + + /* Disable the selected external lines */ + *(__IO uint32_t *) tmp &= ~EXTI_InitStruct->EXTI_Line; + } +} + +/** + * @brief Fills each EXTI_InitStruct member with its reset value. + * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct) +{ + EXTI_InitStruct->EXTI_Line = EXTI_LINENONE; + EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt; + EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling; + EXTI_InitStruct->EXTI_LineCmd = DISABLE; +} + +/** + * @brief Generates a Software interrupt. + * @param EXTI_Line: specifies the EXTI lines to be enabled or disabled. + * This parameter can be any combination of EXTI_Linex where x can be (0..19). + * @retval None + */ +void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->SWIER |= EXTI_Line; +} + +/** + * @brief Checks whether the specified EXTI line flag is set or not. + * @param EXTI_Line: specifies the EXTI line flag to check. + * This parameter can be: + * @arg EXTI_Linex: External interrupt line x where x(0..19) + * @retval The new state of EXTI_Line (SET or RESET). + */ +FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_GET_EXTI_LINE(EXTI_Line)); + + if ((EXTI->PR & EXTI_Line) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the EXTI’s line pending flags. + * @param EXTI_Line: specifies the EXTI lines flags to clear. + * This parameter can be any combination of EXTI_Linex where x can be (0..19). + * @retval None + */ +void EXTI_ClearFlag(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->PR = EXTI_Line; +} + +/** + * @brief Checks whether the specified EXTI line is asserted or not. + * @param EXTI_Line: specifies the EXTI line to check. + * This parameter can be: + * @arg EXTI_Linex: External interrupt line x where x(0..19) + * @retval The new state of EXTI_Line (SET or RESET). + */ +ITStatus EXTI_GetITStatus(uint32_t EXTI_Line) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + /* Check the parameters */ + assert_param(IS_GET_EXTI_LINE(EXTI_Line)); + + enablestatus = EXTI->IMR & EXTI_Line; + if (((EXTI->PR & EXTI_Line) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the EXTI’s line pending bits. + * @param EXTI_Line: specifies the EXTI lines to clear. + * This parameter can be any combination of EXTI_Linex where x can be (0..19). + * @retval None + */ +void EXTI_ClearITPendingBit(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->PR = EXTI_Line; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c index 57bb715c8..d0091647e 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c @@ -1,1683 +1,1683 @@ -/** - ****************************************************************************** - * @file stm32f10x_flash.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the FLASH firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_flash.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup FLASH - * @brief FLASH driver modules - * @{ - */ - -/** @defgroup FLASH_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup FLASH_Private_Defines - * @{ - */ - -/* Flash Access Control Register bits */ -#define ACR_LATENCY_Mask ((uint32_t)0x00000038) -#define ACR_HLFCYA_Mask ((uint32_t)0xFFFFFFF7) -#define ACR_PRFTBE_Mask ((uint32_t)0xFFFFFFEF) - -/* Flash Access Control Register bits */ -#define ACR_PRFTBS_Mask ((uint32_t)0x00000020) - -/* Flash Control Register bits */ -#define CR_PG_Set ((uint32_t)0x00000001) -#define CR_PG_Reset ((uint32_t)0x00001FFE) -#define CR_PER_Set ((uint32_t)0x00000002) -#define CR_PER_Reset ((uint32_t)0x00001FFD) -#define CR_MER_Set ((uint32_t)0x00000004) -#define CR_MER_Reset ((uint32_t)0x00001FFB) -#define CR_OPTPG_Set ((uint32_t)0x00000010) -#define CR_OPTPG_Reset ((uint32_t)0x00001FEF) -#define CR_OPTER_Set ((uint32_t)0x00000020) -#define CR_OPTER_Reset ((uint32_t)0x00001FDF) -#define CR_STRT_Set ((uint32_t)0x00000040) -#define CR_LOCK_Set ((uint32_t)0x00000080) - -/* FLASH Mask */ -#define RDPRT_Mask ((uint32_t)0x00000002) -#define WRP0_Mask ((uint32_t)0x000000FF) -#define WRP1_Mask ((uint32_t)0x0000FF00) -#define WRP2_Mask ((uint32_t)0x00FF0000) -#define WRP3_Mask ((uint32_t)0xFF000000) -#define OB_USER_BFB2 ((uint16_t)0x0008) - -/* FLASH Keys */ -#define RDP_Key ((uint16_t)0x00A5) -#define FLASH_KEY1 ((uint32_t)0x45670123) -#define FLASH_KEY2 ((uint32_t)0xCDEF89AB) - -/* FLASH BANK address */ -#define FLASH_BANK1_END_ADDRESS ((uint32_t)0x807FFFF) - -/* Delay definition */ -#define EraseTimeout ((uint32_t)0x000B0000) -#define ProgramTimeout ((uint32_t)0x00002000) -/** - * @} - */ - -/** @defgroup FLASH_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup FLASH_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup FLASH_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup FLASH_Private_Functions - * @{ - */ - -/** -@code - - This driver provides functions to configure and program the Flash memory of all STM32F10x devices, - including the latest STM32F10x_XL density devices. - - STM32F10x_XL devices feature up to 1 Mbyte with dual bank architecture for read-while-write (RWW) capability: - - bank1: fixed size of 512 Kbytes (256 pages of 2Kbytes each) - - bank2: up to 512 Kbytes (up to 256 pages of 2Kbytes each) - While other STM32F10x devices features only one bank with memory up to 512 Kbytes. - - In version V3.3.0, some functions were updated and new ones were added to support - STM32F10x_XL devices. Thus some functions manages all devices, while other are - dedicated for XL devices only. - - The table below presents the list of available functions depending on the used STM32F10x devices. - - *************************************************** - * Legacy functions used for all STM32F10x devices * - *************************************************** - +----------------------------------------------------------------------------------------------------------------------------------+ - | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | - | | devices | devices | | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_SetLatency | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_HalfCycleAccessCmd | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_PrefetchBufferCmd | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_Unlock | Yes | Yes | - For STM32F10X_XL devices: unlock Bank1 and Bank2. | - | | | | - For other devices: unlock Bank1 and it is equivalent | - | | | | to FLASH_UnlockBank1 function. | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_Lock | Yes | Yes | - For STM32F10X_XL devices: lock Bank1 and Bank2. | - | | | | - For other devices: lock Bank1 and it is equivalent | - | | | | to FLASH_LockBank1 function. | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_ErasePage | Yes | Yes | - For STM32F10x_XL devices: erase a page in Bank1 and Bank2 | - | | | | - For other devices: erase a page in Bank1 | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_EraseAllPages | Yes | Yes | - For STM32F10x_XL devices: erase all pages in Bank1 and Bank2 | - | | | | - For other devices: erase all pages in Bank1 | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_EraseOptionBytes | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_ProgramWord | Yes | Yes | Updated to program up to 1MByte (depending on the used device) | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_ProgramHalfWord | Yes | Yes | Updated to program up to 1MByte (depending on the used device) | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_ProgramOptionByteData | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_EnableWriteProtection | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_ReadOutProtection | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_UserOptionByteConfig | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_GetUserOptionByte | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_GetWriteProtectionOptionByte | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_GetReadOutProtectionStatus | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_GetPrefetchBufferStatus | Yes | Yes | No change | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_ITConfig | Yes | Yes | - For STM32F10x_XL devices: enable Bank1 and Bank2's interrupts| - | | | | - For other devices: enable Bank1's interrupts | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_GetFlagStatus | Yes | Yes | - For STM32F10x_XL devices: return Bank1 and Bank2's flag status| - | | | | - For other devices: return Bank1's flag status | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_ClearFlag | Yes | Yes | - For STM32F10x_XL devices: clear Bank1 and Bank2's flag | - | | | | - For other devices: clear Bank1's flag | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_GetStatus | Yes | Yes | - Return the status of Bank1 (for all devices) | - | | | | equivalent to FLASH_GetBank1Status function | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_WaitForLastOperation | Yes | Yes | - Wait for Bank1 last operation (for all devices) | - | | | | equivalent to: FLASH_WaitForLastBank1Operation function | - +----------------------------------------------------------------------------------------------------------------------------------+ - - ************************************************************************************************************************ - * New functions used for all STM32F10x devices to manage Bank1: * - * - These functions are mainly useful for STM32F10x_XL density devices, to have separate control for Bank1 and bank2 * - * - For other devices, these functions are optional (covered by functions listed above) * - ************************************************************************************************************************ - +----------------------------------------------------------------------------------------------------------------------------------+ - | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | - | | devices | devices | | - |----------------------------------------------------------------------------------------------------------------------------------| - | FLASH_UnlockBank1 | Yes | Yes | - Unlock Bank1 | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_LockBank1 | Yes | Yes | - Lock Bank1 | - |----------------------------------------------------------------------------------------------------------------------------------| - | FLASH_EraseAllBank1Pages | Yes | Yes | - Erase all pages in Bank1 | - |----------------------------------------------------------------------------------------------------------------------------------| - | FLASH_GetBank1Status | Yes | Yes | - Return the status of Bank1 | - |----------------------------------------------------------------------------------------------------------------------------------| - | FLASH_WaitForLastBank1Operation | Yes | Yes | - Wait for Bank1 last operation | - +----------------------------------------------------------------------------------------------------------------------------------+ - - ***************************************************************************** - * New Functions used only with STM32F10x_XL density devices to manage Bank2 * - ***************************************************************************** - +----------------------------------------------------------------------------------------------------------------------------------+ - | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | - | | devices | devices | | - |----------------------------------------------------------------------------------------------------------------------------------| - | FLASH_UnlockBank2 | Yes | No | - Unlock Bank2 | - |----------------------------------------------------------------------------------------------------------------------------------| - |FLASH_LockBank2 | Yes | No | - Lock Bank2 | - |----------------------------------------------------------------------------------------------------------------------------------| - | FLASH_EraseAllBank2Pages | Yes | No | - Erase all pages in Bank2 | - |----------------------------------------------------------------------------------------------------------------------------------| - | FLASH_GetBank2Status | Yes | No | - Return the status of Bank2 | - |----------------------------------------------------------------------------------------------------------------------------------| - | FLASH_WaitForLastBank2Operation | Yes | No | - Wait for Bank2 last operation | - |----------------------------------------------------------------------------------------------------------------------------------| - | FLASH_BootConfig | Yes | No | - Configure to boot from Bank1 or Bank2 | - +----------------------------------------------------------------------------------------------------------------------------------+ -@endcode -*/ - - -/** - * @brief Sets the code latency value. - * @note This function can be used for all STM32F10x devices. - * @param FLASH_Latency: specifies the FLASH Latency value. - * This parameter can be one of the following values: - * @arg FLASH_Latency_0: FLASH Zero Latency cycle - * @arg FLASH_Latency_1: FLASH One Latency cycle - * @arg FLASH_Latency_2: FLASH Two Latency cycles - * @retval None - */ -void FLASH_SetLatency(uint32_t FLASH_Latency) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_FLASH_LATENCY(FLASH_Latency)); - - /* Read the ACR register */ - tmpreg = FLASH->ACR; - - /* Sets the Latency value */ - tmpreg &= ACR_LATENCY_Mask; - tmpreg |= FLASH_Latency; - - /* Write the ACR register */ - FLASH->ACR = tmpreg; -} - -/** - * @brief Enables or disables the Half cycle flash access. - * @note This function can be used for all STM32F10x devices. - * @param FLASH_HalfCycleAccess: specifies the FLASH Half cycle Access mode. - * This parameter can be one of the following values: - * @arg FLASH_HalfCycleAccess_Enable: FLASH Half Cycle Enable - * @arg FLASH_HalfCycleAccess_Disable: FLASH Half Cycle Disable - * @retval None - */ -void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess) -{ - /* Check the parameters */ - assert_param(IS_FLASH_HALFCYCLEACCESS_STATE(FLASH_HalfCycleAccess)); - - /* Enable or disable the Half cycle access */ - FLASH->ACR &= ACR_HLFCYA_Mask; - FLASH->ACR |= FLASH_HalfCycleAccess; -} - -/** - * @brief Enables or disables the Prefetch Buffer. - * @note This function can be used for all STM32F10x devices. - * @param FLASH_PrefetchBuffer: specifies the Prefetch buffer status. - * This parameter can be one of the following values: - * @arg FLASH_PrefetchBuffer_Enable: FLASH Prefetch Buffer Enable - * @arg FLASH_PrefetchBuffer_Disable: FLASH Prefetch Buffer Disable - * @retval None - */ -void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer) -{ - /* Check the parameters */ - assert_param(IS_FLASH_PREFETCHBUFFER_STATE(FLASH_PrefetchBuffer)); - - /* Enable or disable the Prefetch Buffer */ - FLASH->ACR &= ACR_PRFTBE_Mask; - FLASH->ACR |= FLASH_PrefetchBuffer; -} - -/** - * @brief Unlocks the FLASH Program Erase Controller. - * @note This function can be used for all STM32F10x devices. - * - For STM32F10X_XL devices this function unlocks Bank1 and Bank2. - * - For all other devices it unlocks Bank1 and it is equivalent - * to FLASH_UnlockBank1 function.. - * @param None - * @retval None - */ -void FLASH_Unlock(void) -{ - /* Authorize the FPEC of Bank1 Access */ - FLASH->KEYR = FLASH_KEY1; - FLASH->KEYR = FLASH_KEY2; - -#ifdef STM32F10X_XL - /* Authorize the FPEC of Bank2 Access */ - FLASH->KEYR2 = FLASH_KEY1; - FLASH->KEYR2 = FLASH_KEY2; -#endif /* STM32F10X_XL */ -} -/** - * @brief Unlocks the FLASH Bank1 Program Erase Controller. - * @note This function can be used for all STM32F10x devices. - * - For STM32F10X_XL devices this function unlocks Bank1. - * - For all other devices it unlocks Bank1 and it is - * equivalent to FLASH_Unlock function. - * @param None - * @retval None - */ -void FLASH_UnlockBank1(void) -{ - /* Authorize the FPEC of Bank1 Access */ - FLASH->KEYR = FLASH_KEY1; - FLASH->KEYR = FLASH_KEY2; -} - -#ifdef STM32F10X_XL -/** - * @brief Unlocks the FLASH Bank2 Program Erase Controller. - * @note This function can be used only for STM32F10X_XL density devices. - * @param None - * @retval None - */ -void FLASH_UnlockBank2(void) -{ - /* Authorize the FPEC of Bank2 Access */ - FLASH->KEYR2 = FLASH_KEY1; - FLASH->KEYR2 = FLASH_KEY2; - -} -#endif /* STM32F10X_XL */ - -/** - * @brief Locks the FLASH Program Erase Controller. - * @note This function can be used for all STM32F10x devices. - * - For STM32F10X_XL devices this function Locks Bank1 and Bank2. - * - For all other devices it Locks Bank1 and it is equivalent - * to FLASH_LockBank1 function. - * @param None - * @retval None - */ -void FLASH_Lock(void) -{ - /* Set the Lock Bit to lock the FPEC and the CR of Bank1 */ - FLASH->CR |= CR_LOCK_Set; - -#ifdef STM32F10X_XL - /* Set the Lock Bit to lock the FPEC and the CR of Bank2 */ - FLASH->CR2 |= CR_LOCK_Set; -#endif /* STM32F10X_XL */ -} - -/** - * @brief Locks the FLASH Bank1 Program Erase Controller. - * @note this function can be used for all STM32F10x devices. - * - For STM32F10X_XL devices this function Locks Bank1. - * - For all other devices it Locks Bank1 and it is equivalent - * to FLASH_Lock function. - * @param None - * @retval None - */ -void FLASH_LockBank1(void) -{ - /* Set the Lock Bit to lock the FPEC and the CR of Bank1 */ - FLASH->CR |= CR_LOCK_Set; -} - -#ifdef STM32F10X_XL -/** - * @brief Locks the FLASH Bank2 Program Erase Controller. - * @note This function can be used only for STM32F10X_XL density devices. - * @param None - * @retval None - */ -void FLASH_LockBank2(void) -{ - /* Set the Lock Bit to lock the FPEC and the CR of Bank2 */ - FLASH->CR2 |= CR_LOCK_Set; -} -#endif /* STM32F10X_XL */ - -/** - * @brief Erases a specified FLASH page. - * @note This function can be used for all STM32F10x devices. - * @param Page_Address: The page address to be erased. - * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_ErasePage(uint32_t Page_Address) -{ - FLASH_Status status = FLASH_COMPLETE; - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Page_Address)); - -#ifdef STM32F10X_XL - if(Page_Address < FLASH_BANK1_END_ADDRESS) - { - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank1Operation(EraseTimeout); - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to erase the page */ - FLASH->CR|= CR_PER_Set; - FLASH->AR = Page_Address; - FLASH->CR|= CR_STRT_Set; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank1Operation(EraseTimeout); - - /* Disable the PER Bit */ - FLASH->CR &= CR_PER_Reset; - } - } - else - { - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(EraseTimeout); - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to erase the page */ - FLASH->CR2|= CR_PER_Set; - FLASH->AR2 = Page_Address; - FLASH->CR2|= CR_STRT_Set; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(EraseTimeout); - - /* Disable the PER Bit */ - FLASH->CR2 &= CR_PER_Reset; - } - } -#else - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(EraseTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to erase the page */ - FLASH->CR|= CR_PER_Set; - FLASH->AR = Page_Address; - FLASH->CR|= CR_STRT_Set; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(EraseTimeout); - - /* Disable the PER Bit */ - FLASH->CR &= CR_PER_Reset; - } -#endif /* STM32F10X_XL */ - - /* Return the Erase Status */ - return status; -} - -/** - * @brief Erases all FLASH pages. - * @note This function can be used for all STM32F10x devices. - * @param None - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_EraseAllPages(void) -{ - FLASH_Status status = FLASH_COMPLETE; - -#ifdef STM32F10X_XL - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank1Operation(EraseTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to erase all pages */ - FLASH->CR |= CR_MER_Set; - FLASH->CR |= CR_STRT_Set; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank1Operation(EraseTimeout); - - /* Disable the MER Bit */ - FLASH->CR &= CR_MER_Reset; - } - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to erase all pages */ - FLASH->CR2 |= CR_MER_Set; - FLASH->CR2 |= CR_STRT_Set; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(EraseTimeout); - - /* Disable the MER Bit */ - FLASH->CR2 &= CR_MER_Reset; - } -#else - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(EraseTimeout); - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to erase all pages */ - FLASH->CR |= CR_MER_Set; - FLASH->CR |= CR_STRT_Set; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(EraseTimeout); - - /* Disable the MER Bit */ - FLASH->CR &= CR_MER_Reset; - } -#endif /* STM32F10X_XL */ - - /* Return the Erase Status */ - return status; -} - -/** - * @brief Erases all Bank1 FLASH pages. - * @note This function can be used for all STM32F10x devices. - * - For STM32F10X_XL devices this function erases all Bank1 pages. - * - For all other devices it erases all Bank1 pages and it is equivalent - * to FLASH_EraseAllPages function. - * @param None - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_EraseAllBank1Pages(void) -{ - FLASH_Status status = FLASH_COMPLETE; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank1Operation(EraseTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to erase all pages */ - FLASH->CR |= CR_MER_Set; - FLASH->CR |= CR_STRT_Set; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank1Operation(EraseTimeout); - - /* Disable the MER Bit */ - FLASH->CR &= CR_MER_Reset; - } - /* Return the Erase Status */ - return status; -} - -#ifdef STM32F10X_XL -/** - * @brief Erases all Bank2 FLASH pages. - * @note This function can be used only for STM32F10x_XL density devices. - * @param None - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_EraseAllBank2Pages(void) -{ - FLASH_Status status = FLASH_COMPLETE; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(EraseTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to erase all pages */ - FLASH->CR2 |= CR_MER_Set; - FLASH->CR2 |= CR_STRT_Set; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(EraseTimeout); - - /* Disable the MER Bit */ - FLASH->CR2 &= CR_MER_Reset; - } - /* Return the Erase Status */ - return status; -} -#endif /* STM32F10X_XL */ - -/** - * @brief Erases the FLASH option bytes. - * @note This functions erases all option bytes except the Read protection (RDP). - * @note This function can be used for all STM32F10x devices. - * @param None - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_EraseOptionBytes(void) -{ - uint16_t rdptmp = RDP_Key; - - FLASH_Status status = FLASH_COMPLETE; - - /* Get the actual read protection Option Byte value */ - if(FLASH_GetReadOutProtectionStatus() != RESET) - { - rdptmp = 0x00; - } - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(EraseTimeout); - if(status == FLASH_COMPLETE) - { - /* Authorize the small information block programming */ - FLASH->OPTKEYR = FLASH_KEY1; - FLASH->OPTKEYR = FLASH_KEY2; - - /* if the previous operation is completed, proceed to erase the option bytes */ - FLASH->CR |= CR_OPTER_Set; - FLASH->CR |= CR_STRT_Set; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(EraseTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the erase operation is completed, disable the OPTER Bit */ - FLASH->CR &= CR_OPTER_Reset; - - /* Enable the Option Bytes Programming operation */ - FLASH->CR |= CR_OPTPG_Set; - /* Restore the last read protection Option Byte value */ - OB->RDP = (uint16_t)rdptmp; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - if(status != FLASH_TIMEOUT) - { - /* if the program operation is completed, disable the OPTPG Bit */ - FLASH->CR &= CR_OPTPG_Reset; - } - } - else - { - if (status != FLASH_TIMEOUT) - { - /* Disable the OPTPG Bit */ - FLASH->CR &= CR_OPTPG_Reset; - } - } - } - /* Return the erase status */ - return status; -} - -/** - * @brief Programs a word at a specified address. - * @note This function can be used for all STM32F10x devices. - * @param Address: specifies the address to be programmed. - * @param Data: specifies the data to be programmed. - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data) -{ - FLASH_Status status = FLASH_COMPLETE; - __IO uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Address)); - -#ifdef STM32F10X_XL - if(Address < FLASH_BANK1_END_ADDRESS - 2) - { - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank1Operation(ProgramTimeout); - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new first - half word */ - FLASH->CR |= CR_PG_Set; - - *(__IO uint16_t*)Address = (uint16_t)Data; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new second - half word */ - tmp = Address + 2; - - *(__IO uint16_t*) tmp = Data >> 16; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - /* Disable the PG Bit */ - FLASH->CR &= CR_PG_Reset; - } - else - { - /* Disable the PG Bit */ - FLASH->CR &= CR_PG_Reset; - } - } - } - else if(Address == (FLASH_BANK1_END_ADDRESS - 1)) - { - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank1Operation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new first - half word */ - FLASH->CR |= CR_PG_Set; - - *(__IO uint16_t*)Address = (uint16_t)Data; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank1Operation(ProgramTimeout); - - /* Disable the PG Bit */ - FLASH->CR &= CR_PG_Reset; - } - else - { - /* Disable the PG Bit */ - FLASH->CR &= CR_PG_Reset; - } - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new second - half word */ - FLASH->CR2 |= CR_PG_Set; - tmp = Address + 2; - - *(__IO uint16_t*) tmp = Data >> 16; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(ProgramTimeout); - - /* Disable the PG Bit */ - FLASH->CR2 &= CR_PG_Reset; - } - else - { - /* Disable the PG Bit */ - FLASH->CR2 &= CR_PG_Reset; - } - } - else - { - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new first - half word */ - FLASH->CR2 |= CR_PG_Set; - - *(__IO uint16_t*)Address = (uint16_t)Data; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new second - half word */ - tmp = Address + 2; - - *(__IO uint16_t*) tmp = Data >> 16; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(ProgramTimeout); - - /* Disable the PG Bit */ - FLASH->CR2 &= CR_PG_Reset; - } - else - { - /* Disable the PG Bit */ - FLASH->CR2 &= CR_PG_Reset; - } - } - } -#else - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new first - half word */ - FLASH->CR |= CR_PG_Set; - - *(__IO uint16_t*)Address = (uint16_t)Data; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new second - half word */ - tmp = Address + 2; - - *(__IO uint16_t*) tmp = Data >> 16; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - /* Disable the PG Bit */ - FLASH->CR &= CR_PG_Reset; - } - else - { - /* Disable the PG Bit */ - FLASH->CR &= CR_PG_Reset; - } - } -#endif /* STM32F10X_XL */ - - /* Return the Program Status */ - return status; -} - -/** - * @brief Programs a half word at a specified address. - * @note This function can be used for all STM32F10x devices. - * @param Address: specifies the address to be programmed. - * @param Data: specifies the data to be programmed. - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data) -{ - FLASH_Status status = FLASH_COMPLETE; - /* Check the parameters */ - assert_param(IS_FLASH_ADDRESS(Address)); - -#ifdef STM32F10X_XL - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - if(Address < FLASH_BANK1_END_ADDRESS) - { - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new data */ - FLASH->CR |= CR_PG_Set; - - *(__IO uint16_t*)Address = Data; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank1Operation(ProgramTimeout); - - /* Disable the PG Bit */ - FLASH->CR &= CR_PG_Reset; - } - } - else - { - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new data */ - FLASH->CR2 |= CR_PG_Set; - - *(__IO uint16_t*)Address = Data; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastBank2Operation(ProgramTimeout); - - /* Disable the PG Bit */ - FLASH->CR2 &= CR_PG_Reset; - } - } -#else - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* if the previous operation is completed, proceed to program the new data */ - FLASH->CR |= CR_PG_Set; - - *(__IO uint16_t*)Address = Data; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - /* Disable the PG Bit */ - FLASH->CR &= CR_PG_Reset; - } -#endif /* STM32F10X_XL */ - - /* Return the Program Status */ - return status; -} - -/** - * @brief Programs a half word at a specified Option Byte Data address. - * @note This function can be used for all STM32F10x devices. - * @param Address: specifies the address to be programmed. - * This parameter can be 0x1FFFF804 or 0x1FFFF806. - * @param Data: specifies the data to be programmed. - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data) -{ - FLASH_Status status = FLASH_COMPLETE; - /* Check the parameters */ - assert_param(IS_OB_DATA_ADDRESS(Address)); - status = FLASH_WaitForLastOperation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* Authorize the small information block programming */ - FLASH->OPTKEYR = FLASH_KEY1; - FLASH->OPTKEYR = FLASH_KEY2; - /* Enables the Option Bytes Programming operation */ - FLASH->CR |= CR_OPTPG_Set; - *(__IO uint16_t*)Address = Data; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - if(status != FLASH_TIMEOUT) - { - /* if the program operation is completed, disable the OPTPG Bit */ - FLASH->CR &= CR_OPTPG_Reset; - } - } - /* Return the Option Byte Data Program Status */ - return status; -} - -/** - * @brief Write protects the desired pages - * @note This function can be used for all STM32F10x devices. - * @param FLASH_Pages: specifies the address of the pages to be write protected. - * This parameter can be: - * @arg For @b STM32_Low-density_devices: value between FLASH_WRProt_Pages0to3 and FLASH_WRProt_Pages28to31 - * @arg For @b STM32_Medium-density_devices: value between FLASH_WRProt_Pages0to3 - * and FLASH_WRProt_Pages124to127 - * @arg For @b STM32_High-density_devices: value between FLASH_WRProt_Pages0to1 and - * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to255 - * @arg For @b STM32_Connectivity_line_devices: value between FLASH_WRProt_Pages0to1 and - * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to127 - * @arg For @b STM32_XL-density_devices: value between FLASH_WRProt_Pages0to1 and - * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to511 - * @arg FLASH_WRProt_AllPages - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages) -{ - uint16_t WRP0_Data = 0xFFFF, WRP1_Data = 0xFFFF, WRP2_Data = 0xFFFF, WRP3_Data = 0xFFFF; - - FLASH_Status status = FLASH_COMPLETE; - - /* Check the parameters */ - assert_param(IS_FLASH_WRPROT_PAGE(FLASH_Pages)); - - FLASH_Pages = (uint32_t)(~FLASH_Pages); - WRP0_Data = (uint16_t)(FLASH_Pages & WRP0_Mask); - WRP1_Data = (uint16_t)((FLASH_Pages & WRP1_Mask) >> 8); - WRP2_Data = (uint16_t)((FLASH_Pages & WRP2_Mask) >> 16); - WRP3_Data = (uint16_t)((FLASH_Pages & WRP3_Mask) >> 24); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* Authorizes the small information block programming */ - FLASH->OPTKEYR = FLASH_KEY1; - FLASH->OPTKEYR = FLASH_KEY2; - FLASH->CR |= CR_OPTPG_Set; - if(WRP0_Data != 0xFF) - { - OB->WRP0 = WRP0_Data; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - } - if((status == FLASH_COMPLETE) && (WRP1_Data != 0xFF)) - { - OB->WRP1 = WRP1_Data; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - } - if((status == FLASH_COMPLETE) && (WRP2_Data != 0xFF)) - { - OB->WRP2 = WRP2_Data; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - } - - if((status == FLASH_COMPLETE)&& (WRP3_Data != 0xFF)) - { - OB->WRP3 = WRP3_Data; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - } - - if(status != FLASH_TIMEOUT) - { - /* if the program operation is completed, disable the OPTPG Bit */ - FLASH->CR &= CR_OPTPG_Reset; - } - } - /* Return the write protection operation Status */ - return status; -} - -/** - * @brief Enables or disables the read out protection. - * @note If the user has already programmed the other option bytes before calling - * this function, he must re-program them since this function erases all option bytes. - * @note This function can be used for all STM32F10x devices. - * @param Newstate: new state of the ReadOut Protection. - * This parameter can be: ENABLE or DISABLE. - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState) -{ - FLASH_Status status = FLASH_COMPLETE; - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - status = FLASH_WaitForLastOperation(EraseTimeout); - if(status == FLASH_COMPLETE) - { - /* Authorizes the small information block programming */ - FLASH->OPTKEYR = FLASH_KEY1; - FLASH->OPTKEYR = FLASH_KEY2; - FLASH->CR |= CR_OPTER_Set; - FLASH->CR |= CR_STRT_Set; - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(EraseTimeout); - if(status == FLASH_COMPLETE) - { - /* if the erase operation is completed, disable the OPTER Bit */ - FLASH->CR &= CR_OPTER_Reset; - /* Enable the Option Bytes Programming operation */ - FLASH->CR |= CR_OPTPG_Set; - if(NewState != DISABLE) - { - OB->RDP = 0x00; - } - else - { - OB->RDP = RDP_Key; - } - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(EraseTimeout); - - if(status != FLASH_TIMEOUT) - { - /* if the program operation is completed, disable the OPTPG Bit */ - FLASH->CR &= CR_OPTPG_Reset; - } - } - else - { - if(status != FLASH_TIMEOUT) - { - /* Disable the OPTER Bit */ - FLASH->CR &= CR_OPTER_Reset; - } - } - } - /* Return the protection operation Status */ - return status; -} - -/** - * @brief Programs the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. - * @note This function can be used for all STM32F10x devices. - * @param OB_IWDG: Selects the IWDG mode - * This parameter can be one of the following values: - * @arg OB_IWDG_SW: Software IWDG selected - * @arg OB_IWDG_HW: Hardware IWDG selected - * @param OB_STOP: Reset event when entering STOP mode. - * This parameter can be one of the following values: - * @arg OB_STOP_NoRST: No reset generated when entering in STOP - * @arg OB_STOP_RST: Reset generated when entering in STOP - * @param OB_STDBY: Reset event when entering Standby mode. - * This parameter can be one of the following values: - * @arg OB_STDBY_NoRST: No reset generated when entering in STANDBY - * @arg OB_STDBY_RST: Reset generated when entering in STANDBY - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY) -{ - FLASH_Status status = FLASH_COMPLETE; - - /* Check the parameters */ - assert_param(IS_OB_IWDG_SOURCE(OB_IWDG)); - assert_param(IS_OB_STOP_SOURCE(OB_STOP)); - assert_param(IS_OB_STDBY_SOURCE(OB_STDBY)); - - /* Authorize the small information block programming */ - FLASH->OPTKEYR = FLASH_KEY1; - FLASH->OPTKEYR = FLASH_KEY2; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* Enable the Option Bytes Programming operation */ - FLASH->CR |= CR_OPTPG_Set; - - OB->USER = OB_IWDG | (uint16_t)(OB_STOP | (uint16_t)(OB_STDBY | ((uint16_t)0xF8))); - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - if(status != FLASH_TIMEOUT) - { - /* if the program operation is completed, disable the OPTPG Bit */ - FLASH->CR &= CR_OPTPG_Reset; - } - } - /* Return the Option Byte program Status */ - return status; -} - -#ifdef STM32F10X_XL -/** - * @brief Configures to boot from Bank1 or Bank2. - * @note This function can be used only for STM32F10x_XL density devices. - * @param FLASH_BOOT: select the FLASH Bank to boot from. - * This parameter can be one of the following values: - * @arg FLASH_BOOT_Bank1: At startup, if boot pins are set in boot from user Flash - * position and this parameter is selected the device will boot from Bank1(Default). - * @arg FLASH_BOOT_Bank2: At startup, if boot pins are set in boot from user Flash - * position and this parameter is selected the device will boot from Bank2 or Bank1, - * depending on the activation of the bank. The active banks are checked in - * the following order: Bank2, followed by Bank1. - * The active bank is recognized by the value programmed at the base address - * of the respective bank (corresponding to the initial stack pointer value - * in the interrupt vector table). - * For more information, please refer to AN2606 from www.st.com. - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_BootConfig(uint16_t FLASH_BOOT) -{ - FLASH_Status status = FLASH_COMPLETE; - assert_param(IS_FLASH_BOOT(FLASH_BOOT)); - /* Authorize the small information block programming */ - FLASH->OPTKEYR = FLASH_KEY1; - FLASH->OPTKEYR = FLASH_KEY2; - - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - - if(status == FLASH_COMPLETE) - { - /* Enable the Option Bytes Programming operation */ - FLASH->CR |= CR_OPTPG_Set; - - if(FLASH_BOOT == FLASH_BOOT_Bank1) - { - OB->USER |= OB_USER_BFB2; - } - else - { - OB->USER &= (uint16_t)(~(uint16_t)(OB_USER_BFB2)); - } - /* Wait for last operation to be completed */ - status = FLASH_WaitForLastOperation(ProgramTimeout); - if(status != FLASH_TIMEOUT) - { - /* if the program operation is completed, disable the OPTPG Bit */ - FLASH->CR &= CR_OPTPG_Reset; - } - } - /* Return the Option Byte program Status */ - return status; -} -#endif /* STM32F10X_XL */ - -/** - * @brief Returns the FLASH User Option Bytes values. - * @note This function can be used for all STM32F10x devices. - * @param None - * @retval The FLASH User Option Bytes values:IWDG_SW(Bit0), RST_STOP(Bit1) - * and RST_STDBY(Bit2). - */ -uint32_t FLASH_GetUserOptionByte(void) -{ - /* Return the User Option Byte */ - return (uint32_t)(FLASH->OBR >> 2); -} - -/** - * @brief Returns the FLASH Write Protection Option Bytes Register value. - * @note This function can be used for all STM32F10x devices. - * @param None - * @retval The FLASH Write Protection Option Bytes Register value - */ -uint32_t FLASH_GetWriteProtectionOptionByte(void) -{ - /* Return the Falsh write protection Register value */ - return (uint32_t)(FLASH->WRPR); -} - -/** - * @brief Checks whether the FLASH Read Out Protection Status is set or not. - * @note This function can be used for all STM32F10x devices. - * @param None - * @retval FLASH ReadOut Protection Status(SET or RESET) - */ -FlagStatus FLASH_GetReadOutProtectionStatus(void) -{ - FlagStatus readoutstatus = RESET; - if ((FLASH->OBR & RDPRT_Mask) != (uint32_t)RESET) - { - readoutstatus = SET; - } - else - { - readoutstatus = RESET; - } - return readoutstatus; -} - -/** - * @brief Checks whether the FLASH Prefetch Buffer status is set or not. - * @note This function can be used for all STM32F10x devices. - * @param None - * @retval FLASH Prefetch Buffer Status (SET or RESET). - */ -FlagStatus FLASH_GetPrefetchBufferStatus(void) -{ - FlagStatus bitstatus = RESET; - - if ((FLASH->ACR & ACR_PRFTBS_Mask) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - /* Return the new state of FLASH Prefetch Buffer Status (SET or RESET) */ - return bitstatus; -} - -/** - * @brief Enables or disables the specified FLASH interrupts. - * @note This function can be used for all STM32F10x devices. - * - For STM32F10X_XL devices, enables or disables the specified FLASH interrupts - for Bank1 and Bank2. - * - For other devices it enables or disables the specified FLASH interrupts for Bank1. - * @param FLASH_IT: specifies the FLASH interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg FLASH_IT_ERROR: FLASH Error Interrupt - * @arg FLASH_IT_EOP: FLASH end of operation Interrupt - * @param NewState: new state of the specified Flash interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState) -{ -#ifdef STM32F10X_XL - /* Check the parameters */ - assert_param(IS_FLASH_IT(FLASH_IT)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if((FLASH_IT & 0x80000000) != 0x0) - { - if(NewState != DISABLE) - { - /* Enable the interrupt sources */ - FLASH->CR2 |= (FLASH_IT & 0x7FFFFFFF); - } - else - { - /* Disable the interrupt sources */ - FLASH->CR2 &= ~(uint32_t)(FLASH_IT & 0x7FFFFFFF); - } - } - else - { - if(NewState != DISABLE) - { - /* Enable the interrupt sources */ - FLASH->CR |= FLASH_IT; - } - else - { - /* Disable the interrupt sources */ - FLASH->CR &= ~(uint32_t)FLASH_IT; - } - } -#else - /* Check the parameters */ - assert_param(IS_FLASH_IT(FLASH_IT)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if(NewState != DISABLE) - { - /* Enable the interrupt sources */ - FLASH->CR |= FLASH_IT; - } - else - { - /* Disable the interrupt sources */ - FLASH->CR &= ~(uint32_t)FLASH_IT; - } -#endif /* STM32F10X_XL */ -} - -/** - * @brief Checks whether the specified FLASH flag is set or not. - * @note This function can be used for all STM32F10x devices. - * - For STM32F10X_XL devices, this function checks whether the specified - * Bank1 or Bank2 flag is set or not. - * - For other devices, it checks whether the specified Bank1 flag is - * set or not. - * @param FLASH_FLAG: specifies the FLASH flag to check. - * This parameter can be one of the following values: - * @arg FLASH_FLAG_BSY: FLASH Busy flag - * @arg FLASH_FLAG_PGERR: FLASH Program error flag - * @arg FLASH_FLAG_WRPRTERR: FLASH Write protected error flag - * @arg FLASH_FLAG_EOP: FLASH End of Operation flag - * @arg FLASH_FLAG_OPTERR: FLASH Option Byte error flag - * @retval The new state of FLASH_FLAG (SET or RESET). - */ -FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG) -{ - FlagStatus bitstatus = RESET; - -#ifdef STM32F10X_XL - /* Check the parameters */ - assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ; - if(FLASH_FLAG == FLASH_FLAG_OPTERR) - { - if((FLASH->OBR & FLASH_FLAG_OPTERR) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - } - else - { - if((FLASH_FLAG & 0x80000000) != 0x0) - { - if((FLASH->SR2 & FLASH_FLAG) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - } - else - { - if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - } - } -#else - /* Check the parameters */ - assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ; - if(FLASH_FLAG == FLASH_FLAG_OPTERR) - { - if((FLASH->OBR & FLASH_FLAG_OPTERR) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - } - else - { - if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - } -#endif /* STM32F10X_XL */ - - /* Return the new state of FLASH_FLAG (SET or RESET) */ - return bitstatus; -} - -/** - * @brief Clears the FLASH’s pending flags. - * @note This function can be used for all STM32F10x devices. - * - For STM32F10X_XL devices, this function clears Bank1 or Bank2’s pending flags - * - For other devices, it clears Bank1’s pending flags. - * @param FLASH_FLAG: specifies the FLASH flags to clear. - * This parameter can be any combination of the following values: - * @arg FLASH_FLAG_PGERR: FLASH Program error flag - * @arg FLASH_FLAG_WRPRTERR: FLASH Write protected error flag - * @arg FLASH_FLAG_EOP: FLASH End of Operation flag - * @retval None - */ -void FLASH_ClearFlag(uint32_t FLASH_FLAG) -{ -#ifdef STM32F10X_XL - /* Check the parameters */ - assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ; - - if((FLASH_FLAG & 0x80000000) != 0x0) - { - /* Clear the flags */ - FLASH->SR2 = FLASH_FLAG; - } - else - { - /* Clear the flags */ - FLASH->SR = FLASH_FLAG; - } - -#else - /* Check the parameters */ - assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ; - - /* Clear the flags */ - FLASH->SR = FLASH_FLAG; -#endif /* STM32F10X_XL */ -} - -/** - * @brief Returns the FLASH Status. - * @note This function can be used for all STM32F10x devices, it is equivalent - * to FLASH_GetBank1Status function. - * @param None - * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, - * FLASH_ERROR_WRP or FLASH_COMPLETE - */ -FLASH_Status FLASH_GetStatus(void) -{ - FLASH_Status flashstatus = FLASH_COMPLETE; - - if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY) - { - flashstatus = FLASH_BUSY; - } - else - { - if((FLASH->SR & FLASH_FLAG_PGERR) != 0) - { - flashstatus = FLASH_ERROR_PG; - } - else - { - if((FLASH->SR & FLASH_FLAG_WRPRTERR) != 0 ) - { - flashstatus = FLASH_ERROR_WRP; - } - else - { - flashstatus = FLASH_COMPLETE; - } - } - } - /* Return the Flash Status */ - return flashstatus; -} - -/** - * @brief Returns the FLASH Bank1 Status. - * @note This function can be used for all STM32F10x devices, it is equivalent - * to FLASH_GetStatus function. - * @param None - * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, - * FLASH_ERROR_WRP or FLASH_COMPLETE - */ -FLASH_Status FLASH_GetBank1Status(void) -{ - FLASH_Status flashstatus = FLASH_COMPLETE; - - if((FLASH->SR & FLASH_FLAG_BANK1_BSY) == FLASH_FLAG_BSY) - { - flashstatus = FLASH_BUSY; - } - else - { - if((FLASH->SR & FLASH_FLAG_BANK1_PGERR) != 0) - { - flashstatus = FLASH_ERROR_PG; - } - else - { - if((FLASH->SR & FLASH_FLAG_BANK1_WRPRTERR) != 0 ) - { - flashstatus = FLASH_ERROR_WRP; - } - else - { - flashstatus = FLASH_COMPLETE; - } - } - } - /* Return the Flash Status */ - return flashstatus; -} - -#ifdef STM32F10X_XL -/** - * @brief Returns the FLASH Bank2 Status. - * @note This function can be used for STM32F10x_XL density devices. - * @param None - * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, - * FLASH_ERROR_WRP or FLASH_COMPLETE - */ -FLASH_Status FLASH_GetBank2Status(void) -{ - FLASH_Status flashstatus = FLASH_COMPLETE; - - if((FLASH->SR2 & (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) == (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) - { - flashstatus = FLASH_BUSY; - } - else - { - if((FLASH->SR2 & (FLASH_FLAG_BANK2_PGERR & 0x7FFFFFFF)) != 0) - { - flashstatus = FLASH_ERROR_PG; - } - else - { - if((FLASH->SR2 & (FLASH_FLAG_BANK2_WRPRTERR & 0x7FFFFFFF)) != 0 ) - { - flashstatus = FLASH_ERROR_WRP; - } - else - { - flashstatus = FLASH_COMPLETE; - } - } - } - /* Return the Flash Status */ - return flashstatus; -} -#endif /* STM32F10X_XL */ -/** - * @brief Waits for a Flash operation to complete or a TIMEOUT to occur. - * @note This function can be used for all STM32F10x devices, - * it is equivalent to FLASH_WaitForLastBank1Operation. - * - For STM32F10X_XL devices this function waits for a Bank1 Flash operation - * to complete or a TIMEOUT to occur. - * - For all other devices it waits for a Flash operation to complete - * or a TIMEOUT to occur. - * @param Timeout: FLASH progamming Timeout - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout) -{ - FLASH_Status status = FLASH_COMPLETE; - - /* Check for the Flash Status */ - status = FLASH_GetBank1Status(); - /* Wait for a Flash operation to complete or a TIMEOUT to occur */ - while((status == FLASH_BUSY) && (Timeout != 0x00)) - { - status = FLASH_GetBank1Status(); - Timeout--; - } - if(Timeout == 0x00 ) - { - status = FLASH_TIMEOUT; - } - /* Return the operation status */ - return status; -} - -/** - * @brief Waits for a Flash operation on Bank1 to complete or a TIMEOUT to occur. - * @note This function can be used for all STM32F10x devices, - * it is equivalent to FLASH_WaitForLastOperation. - * @param Timeout: FLASH progamming Timeout - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_WaitForLastBank1Operation(uint32_t Timeout) -{ - FLASH_Status status = FLASH_COMPLETE; - - /* Check for the Flash Status */ - status = FLASH_GetBank1Status(); - /* Wait for a Flash operation to complete or a TIMEOUT to occur */ - while((status == FLASH_FLAG_BANK1_BSY) && (Timeout != 0x00)) - { - status = FLASH_GetBank1Status(); - Timeout--; - } - if(Timeout == 0x00 ) - { - status = FLASH_TIMEOUT; - } - /* Return the operation status */ - return status; -} - -#ifdef STM32F10X_XL -/** - * @brief Waits for a Flash operation on Bank2 to complete or a TIMEOUT to occur. - * @note This function can be used only for STM32F10x_XL density devices. - * @param Timeout: FLASH progamming Timeout - * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, - * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. - */ -FLASH_Status FLASH_WaitForLastBank2Operation(uint32_t Timeout) -{ - FLASH_Status status = FLASH_COMPLETE; - - /* Check for the Flash Status */ - status = FLASH_GetBank2Status(); - /* Wait for a Flash operation to complete or a TIMEOUT to occur */ - while((status == (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) && (Timeout != 0x00)) - { - status = FLASH_GetBank2Status(); - Timeout--; - } - if(Timeout == 0x00 ) - { - status = FLASH_TIMEOUT; - } - /* Return the operation status */ - return status; -} -#endif /* STM32F10X_XL */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_flash.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the FLASH firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_flash.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup FLASH + * @brief FLASH driver modules + * @{ + */ + +/** @defgroup FLASH_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_Defines + * @{ + */ + +/* Flash Access Control Register bits */ +#define ACR_LATENCY_Mask ((uint32_t)0x00000038) +#define ACR_HLFCYA_Mask ((uint32_t)0xFFFFFFF7) +#define ACR_PRFTBE_Mask ((uint32_t)0xFFFFFFEF) + +/* Flash Access Control Register bits */ +#define ACR_PRFTBS_Mask ((uint32_t)0x00000020) + +/* Flash Control Register bits */ +#define CR_PG_Set ((uint32_t)0x00000001) +#define CR_PG_Reset ((uint32_t)0x00001FFE) +#define CR_PER_Set ((uint32_t)0x00000002) +#define CR_PER_Reset ((uint32_t)0x00001FFD) +#define CR_MER_Set ((uint32_t)0x00000004) +#define CR_MER_Reset ((uint32_t)0x00001FFB) +#define CR_OPTPG_Set ((uint32_t)0x00000010) +#define CR_OPTPG_Reset ((uint32_t)0x00001FEF) +#define CR_OPTER_Set ((uint32_t)0x00000020) +#define CR_OPTER_Reset ((uint32_t)0x00001FDF) +#define CR_STRT_Set ((uint32_t)0x00000040) +#define CR_LOCK_Set ((uint32_t)0x00000080) + +/* FLASH Mask */ +#define RDPRT_Mask ((uint32_t)0x00000002) +#define WRP0_Mask ((uint32_t)0x000000FF) +#define WRP1_Mask ((uint32_t)0x0000FF00) +#define WRP2_Mask ((uint32_t)0x00FF0000) +#define WRP3_Mask ((uint32_t)0xFF000000) +#define OB_USER_BFB2 ((uint16_t)0x0008) + +/* FLASH Keys */ +#define RDP_Key ((uint16_t)0x00A5) +#define FLASH_KEY1 ((uint32_t)0x45670123) +#define FLASH_KEY2 ((uint32_t)0xCDEF89AB) + +/* FLASH BANK address */ +#define FLASH_BANK1_END_ADDRESS ((uint32_t)0x807FFFF) + +/* Delay definition */ +#define EraseTimeout ((uint32_t)0x000B0000) +#define ProgramTimeout ((uint32_t)0x00002000) +/** + * @} + */ + +/** @defgroup FLASH_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_Functions + * @{ + */ + +/** +@code + + This driver provides functions to configure and program the Flash memory of all STM32F10x devices, + including the latest STM32F10x_XL density devices. + + STM32F10x_XL devices feature up to 1 Mbyte with dual bank architecture for read-while-write (RWW) capability: + - bank1: fixed size of 512 Kbytes (256 pages of 2Kbytes each) + - bank2: up to 512 Kbytes (up to 256 pages of 2Kbytes each) + While other STM32F10x devices features only one bank with memory up to 512 Kbytes. + + In version V3.3.0, some functions were updated and new ones were added to support + STM32F10x_XL devices. Thus some functions manages all devices, while other are + dedicated for XL devices only. + + The table below presents the list of available functions depending on the used STM32F10x devices. + + *************************************************** + * Legacy functions used for all STM32F10x devices * + *************************************************** + +----------------------------------------------------------------------------------------------------------------------------------+ + | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | + | | devices | devices | | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_SetLatency | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_HalfCycleAccessCmd | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_PrefetchBufferCmd | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_Unlock | Yes | Yes | - For STM32F10X_XL devices: unlock Bank1 and Bank2. | + | | | | - For other devices: unlock Bank1 and it is equivalent | + | | | | to FLASH_UnlockBank1 function. | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_Lock | Yes | Yes | - For STM32F10X_XL devices: lock Bank1 and Bank2. | + | | | | - For other devices: lock Bank1 and it is equivalent | + | | | | to FLASH_LockBank1 function. | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ErasePage | Yes | Yes | - For STM32F10x_XL devices: erase a page in Bank1 and Bank2 | + | | | | - For other devices: erase a page in Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_EraseAllPages | Yes | Yes | - For STM32F10x_XL devices: erase all pages in Bank1 and Bank2 | + | | | | - For other devices: erase all pages in Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_EraseOptionBytes | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ProgramWord | Yes | Yes | Updated to program up to 1MByte (depending on the used device) | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ProgramHalfWord | Yes | Yes | Updated to program up to 1MByte (depending on the used device) | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ProgramOptionByteData | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_EnableWriteProtection | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ReadOutProtection | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_UserOptionByteConfig | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetUserOptionByte | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetWriteProtectionOptionByte | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetReadOutProtectionStatus | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetPrefetchBufferStatus | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ITConfig | Yes | Yes | - For STM32F10x_XL devices: enable Bank1 and Bank2's interrupts| + | | | | - For other devices: enable Bank1's interrupts | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetFlagStatus | Yes | Yes | - For STM32F10x_XL devices: return Bank1 and Bank2's flag status| + | | | | - For other devices: return Bank1's flag status | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ClearFlag | Yes | Yes | - For STM32F10x_XL devices: clear Bank1 and Bank2's flag | + | | | | - For other devices: clear Bank1's flag | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetStatus | Yes | Yes | - Return the status of Bank1 (for all devices) | + | | | | equivalent to FLASH_GetBank1Status function | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_WaitForLastOperation | Yes | Yes | - Wait for Bank1 last operation (for all devices) | + | | | | equivalent to: FLASH_WaitForLastBank1Operation function | + +----------------------------------------------------------------------------------------------------------------------------------+ + + ************************************************************************************************************************ + * New functions used for all STM32F10x devices to manage Bank1: * + * - These functions are mainly useful for STM32F10x_XL density devices, to have separate control for Bank1 and bank2 * + * - For other devices, these functions are optional (covered by functions listed above) * + ************************************************************************************************************************ + +----------------------------------------------------------------------------------------------------------------------------------+ + | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | + | | devices | devices | | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_UnlockBank1 | Yes | Yes | - Unlock Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_LockBank1 | Yes | Yes | - Lock Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_EraseAllBank1Pages | Yes | Yes | - Erase all pages in Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_GetBank1Status | Yes | Yes | - Return the status of Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_WaitForLastBank1Operation | Yes | Yes | - Wait for Bank1 last operation | + +----------------------------------------------------------------------------------------------------------------------------------+ + + ***************************************************************************** + * New Functions used only with STM32F10x_XL density devices to manage Bank2 * + ***************************************************************************** + +----------------------------------------------------------------------------------------------------------------------------------+ + | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | + | | devices | devices | | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_UnlockBank2 | Yes | No | - Unlock Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_LockBank2 | Yes | No | - Lock Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_EraseAllBank2Pages | Yes | No | - Erase all pages in Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_GetBank2Status | Yes | No | - Return the status of Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_WaitForLastBank2Operation | Yes | No | - Wait for Bank2 last operation | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_BootConfig | Yes | No | - Configure to boot from Bank1 or Bank2 | + +----------------------------------------------------------------------------------------------------------------------------------+ +@endcode +*/ + + +/** + * @brief Sets the code latency value. + * @note This function can be used for all STM32F10x devices. + * @param FLASH_Latency: specifies the FLASH Latency value. + * This parameter can be one of the following values: + * @arg FLASH_Latency_0: FLASH Zero Latency cycle + * @arg FLASH_Latency_1: FLASH One Latency cycle + * @arg FLASH_Latency_2: FLASH Two Latency cycles + * @retval None + */ +void FLASH_SetLatency(uint32_t FLASH_Latency) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_FLASH_LATENCY(FLASH_Latency)); + + /* Read the ACR register */ + tmpreg = FLASH->ACR; + + /* Sets the Latency value */ + tmpreg &= ACR_LATENCY_Mask; + tmpreg |= FLASH_Latency; + + /* Write the ACR register */ + FLASH->ACR = tmpreg; +} + +/** + * @brief Enables or disables the Half cycle flash access. + * @note This function can be used for all STM32F10x devices. + * @param FLASH_HalfCycleAccess: specifies the FLASH Half cycle Access mode. + * This parameter can be one of the following values: + * @arg FLASH_HalfCycleAccess_Enable: FLASH Half Cycle Enable + * @arg FLASH_HalfCycleAccess_Disable: FLASH Half Cycle Disable + * @retval None + */ +void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess) +{ + /* Check the parameters */ + assert_param(IS_FLASH_HALFCYCLEACCESS_STATE(FLASH_HalfCycleAccess)); + + /* Enable or disable the Half cycle access */ + FLASH->ACR &= ACR_HLFCYA_Mask; + FLASH->ACR |= FLASH_HalfCycleAccess; +} + +/** + * @brief Enables or disables the Prefetch Buffer. + * @note This function can be used for all STM32F10x devices. + * @param FLASH_PrefetchBuffer: specifies the Prefetch buffer status. + * This parameter can be one of the following values: + * @arg FLASH_PrefetchBuffer_Enable: FLASH Prefetch Buffer Enable + * @arg FLASH_PrefetchBuffer_Disable: FLASH Prefetch Buffer Disable + * @retval None + */ +void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer) +{ + /* Check the parameters */ + assert_param(IS_FLASH_PREFETCHBUFFER_STATE(FLASH_PrefetchBuffer)); + + /* Enable or disable the Prefetch Buffer */ + FLASH->ACR &= ACR_PRFTBE_Mask; + FLASH->ACR |= FLASH_PrefetchBuffer; +} + +/** + * @brief Unlocks the FLASH Program Erase Controller. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function unlocks Bank1 and Bank2. + * - For all other devices it unlocks Bank1 and it is equivalent + * to FLASH_UnlockBank1 function.. + * @param None + * @retval None + */ +void FLASH_Unlock(void) +{ + /* Authorize the FPEC of Bank1 Access */ + FLASH->KEYR = FLASH_KEY1; + FLASH->KEYR = FLASH_KEY2; + +#ifdef STM32F10X_XL + /* Authorize the FPEC of Bank2 Access */ + FLASH->KEYR2 = FLASH_KEY1; + FLASH->KEYR2 = FLASH_KEY2; +#endif /* STM32F10X_XL */ +} +/** + * @brief Unlocks the FLASH Bank1 Program Erase Controller. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function unlocks Bank1. + * - For all other devices it unlocks Bank1 and it is + * equivalent to FLASH_Unlock function. + * @param None + * @retval None + */ +void FLASH_UnlockBank1(void) +{ + /* Authorize the FPEC of Bank1 Access */ + FLASH->KEYR = FLASH_KEY1; + FLASH->KEYR = FLASH_KEY2; +} + +#ifdef STM32F10X_XL +/** + * @brief Unlocks the FLASH Bank2 Program Erase Controller. + * @note This function can be used only for STM32F10X_XL density devices. + * @param None + * @retval None + */ +void FLASH_UnlockBank2(void) +{ + /* Authorize the FPEC of Bank2 Access */ + FLASH->KEYR2 = FLASH_KEY1; + FLASH->KEYR2 = FLASH_KEY2; + +} +#endif /* STM32F10X_XL */ + +/** + * @brief Locks the FLASH Program Erase Controller. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function Locks Bank1 and Bank2. + * - For all other devices it Locks Bank1 and it is equivalent + * to FLASH_LockBank1 function. + * @param None + * @retval None + */ +void FLASH_Lock(void) +{ + /* Set the Lock Bit to lock the FPEC and the CR of Bank1 */ + FLASH->CR |= CR_LOCK_Set; + +#ifdef STM32F10X_XL + /* Set the Lock Bit to lock the FPEC and the CR of Bank2 */ + FLASH->CR2 |= CR_LOCK_Set; +#endif /* STM32F10X_XL */ +} + +/** + * @brief Locks the FLASH Bank1 Program Erase Controller. + * @note this function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function Locks Bank1. + * - For all other devices it Locks Bank1 and it is equivalent + * to FLASH_Lock function. + * @param None + * @retval None + */ +void FLASH_LockBank1(void) +{ + /* Set the Lock Bit to lock the FPEC and the CR of Bank1 */ + FLASH->CR |= CR_LOCK_Set; +} + +#ifdef STM32F10X_XL +/** + * @brief Locks the FLASH Bank2 Program Erase Controller. + * @note This function can be used only for STM32F10X_XL density devices. + * @param None + * @retval None + */ +void FLASH_LockBank2(void) +{ + /* Set the Lock Bit to lock the FPEC and the CR of Bank2 */ + FLASH->CR2 |= CR_LOCK_Set; +} +#endif /* STM32F10X_XL */ + +/** + * @brief Erases a specified FLASH page. + * @note This function can be used for all STM32F10x devices. + * @param Page_Address: The page address to be erased. + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ErasePage(uint32_t Page_Address) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Page_Address)); + +#ifdef STM32F10X_XL + if(Page_Address < FLASH_BANK1_END_ADDRESS) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase the page */ + FLASH->CR|= CR_PER_Set; + FLASH->AR = Page_Address; + FLASH->CR|= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + /* Disable the PER Bit */ + FLASH->CR &= CR_PER_Reset; + } + } + else + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase the page */ + FLASH->CR2|= CR_PER_Set; + FLASH->AR2 = Page_Address; + FLASH->CR2|= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + /* Disable the PER Bit */ + FLASH->CR2 &= CR_PER_Reset; + } + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase the page */ + FLASH->CR|= CR_PER_Set; + FLASH->AR = Page_Address; + FLASH->CR|= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + /* Disable the PER Bit */ + FLASH->CR &= CR_PER_Reset; + } +#endif /* STM32F10X_XL */ + + /* Return the Erase Status */ + return status; +} + +/** + * @brief Erases all FLASH pages. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseAllPages(void) +{ + FLASH_Status status = FLASH_COMPLETE; + +#ifdef STM32F10X_XL + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR |= CR_MER_Set; + FLASH->CR |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR &= CR_MER_Reset; + } + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR2 |= CR_MER_Set; + FLASH->CR2 |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR2 &= CR_MER_Reset; + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR |= CR_MER_Set; + FLASH->CR |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR &= CR_MER_Reset; + } +#endif /* STM32F10X_XL */ + + /* Return the Erase Status */ + return status; +} + +/** + * @brief Erases all Bank1 FLASH pages. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function erases all Bank1 pages. + * - For all other devices it erases all Bank1 pages and it is equivalent + * to FLASH_EraseAllPages function. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseAllBank1Pages(void) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR |= CR_MER_Set; + FLASH->CR |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR &= CR_MER_Reset; + } + /* Return the Erase Status */ + return status; +} + +#ifdef STM32F10X_XL +/** + * @brief Erases all Bank2 FLASH pages. + * @note This function can be used only for STM32F10x_XL density devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseAllBank2Pages(void) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR2 |= CR_MER_Set; + FLASH->CR2 |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR2 &= CR_MER_Reset; + } + /* Return the Erase Status */ + return status; +} +#endif /* STM32F10X_XL */ + +/** + * @brief Erases the FLASH option bytes. + * @note This functions erases all option bytes except the Read protection (RDP). + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseOptionBytes(void) +{ + uint16_t rdptmp = RDP_Key; + + FLASH_Status status = FLASH_COMPLETE; + + /* Get the actual read protection Option Byte value */ + if(FLASH_GetReadOutProtectionStatus() != RESET) + { + rdptmp = 0x00; + } + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* if the previous operation is completed, proceed to erase the option bytes */ + FLASH->CR |= CR_OPTER_Set; + FLASH->CR |= CR_STRT_Set; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the erase operation is completed, disable the OPTER Bit */ + FLASH->CR &= CR_OPTER_Reset; + + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + /* Restore the last read protection Option Byte value */ + OB->RDP = (uint16_t)rdptmp; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + else + { + if (status != FLASH_TIMEOUT) + { + /* Disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + } + /* Return the erase status */ + return status; +} + +/** + * @brief Programs a word at a specified address. + * @note This function can be used for all STM32F10x devices. + * @param Address: specifies the address to be programmed. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + +#ifdef STM32F10X_XL + if(Address < FLASH_BANK1_END_ADDRESS - 2) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + } + } + else if(Address == (FLASH_BANK1_END_ADDRESS - 1)) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + FLASH->CR2 |= CR_PG_Set; + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + } + else + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR2 |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + } + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + } +#endif /* STM32F10X_XL */ + + /* Return the Program Status */ + return status; +} + +/** + * @brief Programs a half word at a specified address. + * @note This function can be used for all STM32F10x devices. + * @param Address: specifies the address to be programmed. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + +#ifdef STM32F10X_XL + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(Address < FLASH_BANK1_END_ADDRESS) + { + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + } + else + { + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR2 |= CR_PG_Set; + + *(__IO uint16_t*)Address = Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } +#endif /* STM32F10X_XL */ + + /* Return the Program Status */ + return status; +} + +/** + * @brief Programs a half word at a specified Option Byte Data address. + * @note This function can be used for all STM32F10x devices. + * @param Address: specifies the address to be programmed. + * This parameter can be 0x1FFFF804 or 0x1FFFF806. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_OB_DATA_ADDRESS(Address)); + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + /* Enables the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + *(__IO uint16_t*)Address = Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the Option Byte Data Program Status */ + return status; +} + +/** + * @brief Write protects the desired pages + * @note This function can be used for all STM32F10x devices. + * @param FLASH_Pages: specifies the address of the pages to be write protected. + * This parameter can be: + * @arg For @b STM32_Low-density_devices: value between FLASH_WRProt_Pages0to3 and FLASH_WRProt_Pages28to31 + * @arg For @b STM32_Medium-density_devices: value between FLASH_WRProt_Pages0to3 + * and FLASH_WRProt_Pages124to127 + * @arg For @b STM32_High-density_devices: value between FLASH_WRProt_Pages0to1 and + * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to255 + * @arg For @b STM32_Connectivity_line_devices: value between FLASH_WRProt_Pages0to1 and + * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to127 + * @arg For @b STM32_XL-density_devices: value between FLASH_WRProt_Pages0to1 and + * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to511 + * @arg FLASH_WRProt_AllPages + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages) +{ + uint16_t WRP0_Data = 0xFFFF, WRP1_Data = 0xFFFF, WRP2_Data = 0xFFFF, WRP3_Data = 0xFFFF; + + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_FLASH_WRPROT_PAGE(FLASH_Pages)); + + FLASH_Pages = (uint32_t)(~FLASH_Pages); + WRP0_Data = (uint16_t)(FLASH_Pages & WRP0_Mask); + WRP1_Data = (uint16_t)((FLASH_Pages & WRP1_Mask) >> 8); + WRP2_Data = (uint16_t)((FLASH_Pages & WRP2_Mask) >> 16); + WRP3_Data = (uint16_t)((FLASH_Pages & WRP3_Mask) >> 24); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Authorizes the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + FLASH->CR |= CR_OPTPG_Set; + if(WRP0_Data != 0xFF) + { + OB->WRP0 = WRP0_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + if((status == FLASH_COMPLETE) && (WRP1_Data != 0xFF)) + { + OB->WRP1 = WRP1_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + if((status == FLASH_COMPLETE) && (WRP2_Data != 0xFF)) + { + OB->WRP2 = WRP2_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + + if((status == FLASH_COMPLETE)&& (WRP3_Data != 0xFF)) + { + OB->WRP3 = WRP3_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the write protection operation Status */ + return status; +} + +/** + * @brief Enables or disables the read out protection. + * @note If the user has already programmed the other option bytes before calling + * this function, he must re-program them since this function erases all option bytes. + * @note This function can be used for all STM32F10x devices. + * @param Newstate: new state of the ReadOut Protection. + * This parameter can be: ENABLE or DISABLE. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* Authorizes the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + FLASH->CR |= CR_OPTER_Set; + FLASH->CR |= CR_STRT_Set; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the erase operation is completed, disable the OPTER Bit */ + FLASH->CR &= CR_OPTER_Reset; + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + if(NewState != DISABLE) + { + OB->RDP = 0x00; + } + else + { + OB->RDP = RDP_Key; + } + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + else + { + if(status != FLASH_TIMEOUT) + { + /* Disable the OPTER Bit */ + FLASH->CR &= CR_OPTER_Reset; + } + } + } + /* Return the protection operation Status */ + return status; +} + +/** + * @brief Programs the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. + * @note This function can be used for all STM32F10x devices. + * @param OB_IWDG: Selects the IWDG mode + * This parameter can be one of the following values: + * @arg OB_IWDG_SW: Software IWDG selected + * @arg OB_IWDG_HW: Hardware IWDG selected + * @param OB_STOP: Reset event when entering STOP mode. + * This parameter can be one of the following values: + * @arg OB_STOP_NoRST: No reset generated when entering in STOP + * @arg OB_STOP_RST: Reset generated when entering in STOP + * @param OB_STDBY: Reset event when entering Standby mode. + * This parameter can be one of the following values: + * @arg OB_STDBY_NoRST: No reset generated when entering in STANDBY + * @arg OB_STDBY_RST: Reset generated when entering in STANDBY + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_IWDG_SOURCE(OB_IWDG)); + assert_param(IS_OB_STOP_SOURCE(OB_STOP)); + assert_param(IS_OB_STDBY_SOURCE(OB_STDBY)); + + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + + OB->USER = OB_IWDG | (uint16_t)(OB_STOP | (uint16_t)(OB_STDBY | ((uint16_t)0xF8))); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the Option Byte program Status */ + return status; +} + +#ifdef STM32F10X_XL +/** + * @brief Configures to boot from Bank1 or Bank2. + * @note This function can be used only for STM32F10x_XL density devices. + * @param FLASH_BOOT: select the FLASH Bank to boot from. + * This parameter can be one of the following values: + * @arg FLASH_BOOT_Bank1: At startup, if boot pins are set in boot from user Flash + * position and this parameter is selected the device will boot from Bank1(Default). + * @arg FLASH_BOOT_Bank2: At startup, if boot pins are set in boot from user Flash + * position and this parameter is selected the device will boot from Bank2 or Bank1, + * depending on the activation of the bank. The active banks are checked in + * the following order: Bank2, followed by Bank1. + * The active bank is recognized by the value programmed at the base address + * of the respective bank (corresponding to the initial stack pointer value + * in the interrupt vector table). + * For more information, please refer to AN2606 from www.st.com. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_BootConfig(uint16_t FLASH_BOOT) +{ + FLASH_Status status = FLASH_COMPLETE; + assert_param(IS_FLASH_BOOT(FLASH_BOOT)); + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + + if(FLASH_BOOT == FLASH_BOOT_Bank1) + { + OB->USER |= OB_USER_BFB2; + } + else + { + OB->USER &= (uint16_t)(~(uint16_t)(OB_USER_BFB2)); + } + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the Option Byte program Status */ + return status; +} +#endif /* STM32F10X_XL */ + +/** + * @brief Returns the FLASH User Option Bytes values. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval The FLASH User Option Bytes values:IWDG_SW(Bit0), RST_STOP(Bit1) + * and RST_STDBY(Bit2). + */ +uint32_t FLASH_GetUserOptionByte(void) +{ + /* Return the User Option Byte */ + return (uint32_t)(FLASH->OBR >> 2); +} + +/** + * @brief Returns the FLASH Write Protection Option Bytes Register value. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval The FLASH Write Protection Option Bytes Register value + */ +uint32_t FLASH_GetWriteProtectionOptionByte(void) +{ + /* Return the Falsh write protection Register value */ + return (uint32_t)(FLASH->WRPR); +} + +/** + * @brief Checks whether the FLASH Read Out Protection Status is set or not. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH ReadOut Protection Status(SET or RESET) + */ +FlagStatus FLASH_GetReadOutProtectionStatus(void) +{ + FlagStatus readoutstatus = RESET; + if ((FLASH->OBR & RDPRT_Mask) != (uint32_t)RESET) + { + readoutstatus = SET; + } + else + { + readoutstatus = RESET; + } + return readoutstatus; +} + +/** + * @brief Checks whether the FLASH Prefetch Buffer status is set or not. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH Prefetch Buffer Status (SET or RESET). + */ +FlagStatus FLASH_GetPrefetchBufferStatus(void) +{ + FlagStatus bitstatus = RESET; + + if ((FLASH->ACR & ACR_PRFTBS_Mask) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the new state of FLASH Prefetch Buffer Status (SET or RESET) */ + return bitstatus; +} + +/** + * @brief Enables or disables the specified FLASH interrupts. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices, enables or disables the specified FLASH interrupts + for Bank1 and Bank2. + * - For other devices it enables or disables the specified FLASH interrupts for Bank1. + * @param FLASH_IT: specifies the FLASH interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg FLASH_IT_ERROR: FLASH Error Interrupt + * @arg FLASH_IT_EOP: FLASH end of operation Interrupt + * @param NewState: new state of the specified Flash interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState) +{ +#ifdef STM32F10X_XL + /* Check the parameters */ + assert_param(IS_FLASH_IT(FLASH_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if((FLASH_IT & 0x80000000) != 0x0) + { + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR2 |= (FLASH_IT & 0x7FFFFFFF); + } + else + { + /* Disable the interrupt sources */ + FLASH->CR2 &= ~(uint32_t)(FLASH_IT & 0x7FFFFFFF); + } + } + else + { + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR |= FLASH_IT; + } + else + { + /* Disable the interrupt sources */ + FLASH->CR &= ~(uint32_t)FLASH_IT; + } + } +#else + /* Check the parameters */ + assert_param(IS_FLASH_IT(FLASH_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR |= FLASH_IT; + } + else + { + /* Disable the interrupt sources */ + FLASH->CR &= ~(uint32_t)FLASH_IT; + } +#endif /* STM32F10X_XL */ +} + +/** + * @brief Checks whether the specified FLASH flag is set or not. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices, this function checks whether the specified + * Bank1 or Bank2 flag is set or not. + * - For other devices, it checks whether the specified Bank1 flag is + * set or not. + * @param FLASH_FLAG: specifies the FLASH flag to check. + * This parameter can be one of the following values: + * @arg FLASH_FLAG_BSY: FLASH Busy flag + * @arg FLASH_FLAG_PGERR: FLASH Program error flag + * @arg FLASH_FLAG_WRPRTERR: FLASH Write protected error flag + * @arg FLASH_FLAG_EOP: FLASH End of Operation flag + * @arg FLASH_FLAG_OPTERR: FLASH Option Byte error flag + * @retval The new state of FLASH_FLAG (SET or RESET). + */ +FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG) +{ + FlagStatus bitstatus = RESET; + +#ifdef STM32F10X_XL + /* Check the parameters */ + assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ; + if(FLASH_FLAG == FLASH_FLAG_OPTERR) + { + if((FLASH->OBR & FLASH_FLAG_OPTERR) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + else + { + if((FLASH_FLAG & 0x80000000) != 0x0) + { + if((FLASH->SR2 & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + else + { + if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + } +#else + /* Check the parameters */ + assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ; + if(FLASH_FLAG == FLASH_FLAG_OPTERR) + { + if((FLASH->OBR & FLASH_FLAG_OPTERR) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + else + { + if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } +#endif /* STM32F10X_XL */ + + /* Return the new state of FLASH_FLAG (SET or RESET) */ + return bitstatus; +} + +/** + * @brief Clears the FLASH’s pending flags. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices, this function clears Bank1 or Bank2’s pending flags + * - For other devices, it clears Bank1’s pending flags. + * @param FLASH_FLAG: specifies the FLASH flags to clear. + * This parameter can be any combination of the following values: + * @arg FLASH_FLAG_PGERR: FLASH Program error flag + * @arg FLASH_FLAG_WRPRTERR: FLASH Write protected error flag + * @arg FLASH_FLAG_EOP: FLASH End of Operation flag + * @retval None + */ +void FLASH_ClearFlag(uint32_t FLASH_FLAG) +{ +#ifdef STM32F10X_XL + /* Check the parameters */ + assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ; + + if((FLASH_FLAG & 0x80000000) != 0x0) + { + /* Clear the flags */ + FLASH->SR2 = FLASH_FLAG; + } + else + { + /* Clear the flags */ + FLASH->SR = FLASH_FLAG; + } + +#else + /* Check the parameters */ + assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ; + + /* Clear the flags */ + FLASH->SR = FLASH_FLAG; +#endif /* STM32F10X_XL */ +} + +/** + * @brief Returns the FLASH Status. + * @note This function can be used for all STM32F10x devices, it is equivalent + * to FLASH_GetBank1Status function. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP or FLASH_COMPLETE + */ +FLASH_Status FLASH_GetStatus(void) +{ + FLASH_Status flashstatus = FLASH_COMPLETE; + + if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY) + { + flashstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR & FLASH_FLAG_PGERR) != 0) + { + flashstatus = FLASH_ERROR_PG; + } + else + { + if((FLASH->SR & FLASH_FLAG_WRPRTERR) != 0 ) + { + flashstatus = FLASH_ERROR_WRP; + } + else + { + flashstatus = FLASH_COMPLETE; + } + } + } + /* Return the Flash Status */ + return flashstatus; +} + +/** + * @brief Returns the FLASH Bank1 Status. + * @note This function can be used for all STM32F10x devices, it is equivalent + * to FLASH_GetStatus function. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP or FLASH_COMPLETE + */ +FLASH_Status FLASH_GetBank1Status(void) +{ + FLASH_Status flashstatus = FLASH_COMPLETE; + + if((FLASH->SR & FLASH_FLAG_BANK1_BSY) == FLASH_FLAG_BSY) + { + flashstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR & FLASH_FLAG_BANK1_PGERR) != 0) + { + flashstatus = FLASH_ERROR_PG; + } + else + { + if((FLASH->SR & FLASH_FLAG_BANK1_WRPRTERR) != 0 ) + { + flashstatus = FLASH_ERROR_WRP; + } + else + { + flashstatus = FLASH_COMPLETE; + } + } + } + /* Return the Flash Status */ + return flashstatus; +} + +#ifdef STM32F10X_XL +/** + * @brief Returns the FLASH Bank2 Status. + * @note This function can be used for STM32F10x_XL density devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP or FLASH_COMPLETE + */ +FLASH_Status FLASH_GetBank2Status(void) +{ + FLASH_Status flashstatus = FLASH_COMPLETE; + + if((FLASH->SR2 & (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) == (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) + { + flashstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR2 & (FLASH_FLAG_BANK2_PGERR & 0x7FFFFFFF)) != 0) + { + flashstatus = FLASH_ERROR_PG; + } + else + { + if((FLASH->SR2 & (FLASH_FLAG_BANK2_WRPRTERR & 0x7FFFFFFF)) != 0 ) + { + flashstatus = FLASH_ERROR_WRP; + } + else + { + flashstatus = FLASH_COMPLETE; + } + } + } + /* Return the Flash Status */ + return flashstatus; +} +#endif /* STM32F10X_XL */ +/** + * @brief Waits for a Flash operation to complete or a TIMEOUT to occur. + * @note This function can be used for all STM32F10x devices, + * it is equivalent to FLASH_WaitForLastBank1Operation. + * - For STM32F10X_XL devices this function waits for a Bank1 Flash operation + * to complete or a TIMEOUT to occur. + * - For all other devices it waits for a Flash operation to complete + * or a TIMEOUT to occur. + * @param Timeout: FLASH progamming Timeout + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check for the Flash Status */ + status = FLASH_GetBank1Status(); + /* Wait for a Flash operation to complete or a TIMEOUT to occur */ + while((status == FLASH_BUSY) && (Timeout != 0x00)) + { + status = FLASH_GetBank1Status(); + Timeout--; + } + if(Timeout == 0x00 ) + { + status = FLASH_TIMEOUT; + } + /* Return the operation status */ + return status; +} + +/** + * @brief Waits for a Flash operation on Bank1 to complete or a TIMEOUT to occur. + * @note This function can be used for all STM32F10x devices, + * it is equivalent to FLASH_WaitForLastOperation. + * @param Timeout: FLASH progamming Timeout + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_WaitForLastBank1Operation(uint32_t Timeout) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check for the Flash Status */ + status = FLASH_GetBank1Status(); + /* Wait for a Flash operation to complete or a TIMEOUT to occur */ + while((status == FLASH_FLAG_BANK1_BSY) && (Timeout != 0x00)) + { + status = FLASH_GetBank1Status(); + Timeout--; + } + if(Timeout == 0x00 ) + { + status = FLASH_TIMEOUT; + } + /* Return the operation status */ + return status; +} + +#ifdef STM32F10X_XL +/** + * @brief Waits for a Flash operation on Bank2 to complete or a TIMEOUT to occur. + * @note This function can be used only for STM32F10x_XL density devices. + * @param Timeout: FLASH progamming Timeout + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_WaitForLastBank2Operation(uint32_t Timeout) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check for the Flash Status */ + status = FLASH_GetBank2Status(); + /* Wait for a Flash operation to complete or a TIMEOUT to occur */ + while((status == (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) && (Timeout != 0x00)) + { + status = FLASH_GetBank2Status(); + Timeout--; + } + if(Timeout == 0x00 ) + { + status = FLASH_TIMEOUT; + } + /* Return the operation status */ + return status; +} +#endif /* STM32F10X_XL */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c index db9a5aad1..b4584aaf7 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c @@ -1,863 +1,863 @@ -/** - ****************************************************************************** - * @file stm32f10x_fsmc.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the FSMC firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_fsmc.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup FSMC - * @brief FSMC driver modules - * @{ - */ - -/** @defgroup FSMC_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - -/** @defgroup FSMC_Private_Defines - * @{ - */ - -/* --------------------- FSMC registers bit mask ---------------------------- */ - -/* FSMC BCRx Mask */ -#define BCR_MBKEN_Set ((uint32_t)0x00000001) -#define BCR_MBKEN_Reset ((uint32_t)0x000FFFFE) -#define BCR_FACCEN_Set ((uint32_t)0x00000040) - -/* FSMC PCRx Mask */ -#define PCR_PBKEN_Set ((uint32_t)0x00000004) -#define PCR_PBKEN_Reset ((uint32_t)0x000FFFFB) -#define PCR_ECCEN_Set ((uint32_t)0x00000040) -#define PCR_ECCEN_Reset ((uint32_t)0x000FFFBF) -#define PCR_MemoryType_NAND ((uint32_t)0x00000008) -/** - * @} - */ - -/** @defgroup FSMC_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup FSMC_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup FSMC_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup FSMC_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the FSMC NOR/SRAM Banks registers to their default - * reset values. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1 - * @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 - * @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 - * @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 - * @retval None - */ -void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank) -{ - /* Check the parameter */ - assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank)); - - /* FSMC_Bank1_NORSRAM1 */ - if(FSMC_Bank == FSMC_Bank1_NORSRAM1) - { - FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030DB; - } - /* FSMC_Bank1_NORSRAM2, FSMC_Bank1_NORSRAM3 or FSMC_Bank1_NORSRAM4 */ - else - { - FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030D2; - } - FSMC_Bank1->BTCR[FSMC_Bank + 1] = 0x0FFFFFFF; - FSMC_Bank1E->BWTR[FSMC_Bank] = 0x0FFFFFFF; -} - -/** - * @brief Deinitializes the FSMC NAND Banks registers to their default reset values. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND - * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND - * @retval None - */ -void FSMC_NANDDeInit(uint32_t FSMC_Bank) -{ - /* Check the parameter */ - assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); - - if(FSMC_Bank == FSMC_Bank2_NAND) - { - /* Set the FSMC_Bank2 registers to their reset values */ - FSMC_Bank2->PCR2 = 0x00000018; - FSMC_Bank2->SR2 = 0x00000040; - FSMC_Bank2->PMEM2 = 0xFCFCFCFC; - FSMC_Bank2->PATT2 = 0xFCFCFCFC; - } - /* FSMC_Bank3_NAND */ - else - { - /* Set the FSMC_Bank3 registers to their reset values */ - FSMC_Bank3->PCR3 = 0x00000018; - FSMC_Bank3->SR3 = 0x00000040; - FSMC_Bank3->PMEM3 = 0xFCFCFCFC; - FSMC_Bank3->PATT3 = 0xFCFCFCFC; - } -} - -/** - * @brief Deinitializes the FSMC PCCARD Bank registers to their default reset values. - * @param None - * @retval None - */ -void FSMC_PCCARDDeInit(void) -{ - /* Set the FSMC_Bank4 registers to their reset values */ - FSMC_Bank4->PCR4 = 0x00000018; - FSMC_Bank4->SR4 = 0x00000000; - FSMC_Bank4->PMEM4 = 0xFCFCFCFC; - FSMC_Bank4->PATT4 = 0xFCFCFCFC; - FSMC_Bank4->PIO4 = 0xFCFCFCFC; -} - -/** - * @brief Initializes the FSMC NOR/SRAM Banks according to the specified - * parameters in the FSMC_NORSRAMInitStruct. - * @param FSMC_NORSRAMInitStruct : pointer to a FSMC_NORSRAMInitTypeDef - * structure that contains the configuration information for - * the FSMC NOR/SRAM specified Banks. - * @retval None - */ -void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct) -{ - /* Check the parameters */ - assert_param(IS_FSMC_NORSRAM_BANK(FSMC_NORSRAMInitStruct->FSMC_Bank)); - assert_param(IS_FSMC_MUX(FSMC_NORSRAMInitStruct->FSMC_DataAddressMux)); - assert_param(IS_FSMC_MEMORY(FSMC_NORSRAMInitStruct->FSMC_MemoryType)); - assert_param(IS_FSMC_MEMORY_WIDTH(FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth)); - assert_param(IS_FSMC_BURSTMODE(FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode)); - assert_param(IS_FSMC_ASYNWAIT(FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait)); - assert_param(IS_FSMC_WAIT_POLARITY(FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity)); - assert_param(IS_FSMC_WRAP_MODE(FSMC_NORSRAMInitStruct->FSMC_WrapMode)); - assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive)); - assert_param(IS_FSMC_WRITE_OPERATION(FSMC_NORSRAMInitStruct->FSMC_WriteOperation)); - assert_param(IS_FSMC_WAITE_SIGNAL(FSMC_NORSRAMInitStruct->FSMC_WaitSignal)); - assert_param(IS_FSMC_EXTENDED_MODE(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode)); - assert_param(IS_FSMC_WRITE_BURST(FSMC_NORSRAMInitStruct->FSMC_WriteBurst)); - assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime)); - assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime)); - assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime)); - assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration)); - assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision)); - assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency)); - assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode)); - - /* Bank1 NOR/SRAM control register configuration */ - FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] = - (uint32_t)FSMC_NORSRAMInitStruct->FSMC_DataAddressMux | - FSMC_NORSRAMInitStruct->FSMC_MemoryType | - FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth | - FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode | - FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait | - FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity | - FSMC_NORSRAMInitStruct->FSMC_WrapMode | - FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive | - FSMC_NORSRAMInitStruct->FSMC_WriteOperation | - FSMC_NORSRAMInitStruct->FSMC_WaitSignal | - FSMC_NORSRAMInitStruct->FSMC_ExtendedMode | - FSMC_NORSRAMInitStruct->FSMC_WriteBurst; - - if(FSMC_NORSRAMInitStruct->FSMC_MemoryType == FSMC_MemoryType_NOR) - { - FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] |= (uint32_t)BCR_FACCEN_Set; - } - - /* Bank1 NOR/SRAM timing register configuration */ - FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank+1] = - (uint32_t)FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime | - (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime << 4) | - (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime << 8) | - (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration << 16) | - (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision << 20) | - (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency << 24) | - FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode; - - - /* Bank1 NOR/SRAM timing register for write configuration, if extended mode is used */ - if(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode == FSMC_ExtendedMode_Enable) - { - assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime)); - assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime)); - assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime)); - assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision)); - assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency)); - assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode)); - FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = - (uint32_t)FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime | - (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime << 4 )| - (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime << 8) | - (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision << 20) | - (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency << 24) | - FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode; - } - else - { - FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 0x0FFFFFFF; - } -} - -/** - * @brief Initializes the FSMC NAND Banks according to the specified - * parameters in the FSMC_NANDInitStruct. - * @param FSMC_NANDInitStruct : pointer to a FSMC_NANDInitTypeDef - * structure that contains the configuration information for the FSMC NAND specified Banks. - * @retval None - */ -void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct) -{ - uint32_t tmppcr = 0x00000000, tmppmem = 0x00000000, tmppatt = 0x00000000; - - /* Check the parameters */ - assert_param( IS_FSMC_NAND_BANK(FSMC_NANDInitStruct->FSMC_Bank)); - assert_param( IS_FSMC_WAIT_FEATURE(FSMC_NANDInitStruct->FSMC_Waitfeature)); - assert_param( IS_FSMC_MEMORY_WIDTH(FSMC_NANDInitStruct->FSMC_MemoryDataWidth)); - assert_param( IS_FSMC_ECC_STATE(FSMC_NANDInitStruct->FSMC_ECC)); - assert_param( IS_FSMC_ECCPAGE_SIZE(FSMC_NANDInitStruct->FSMC_ECCPageSize)); - assert_param( IS_FSMC_TCLR_TIME(FSMC_NANDInitStruct->FSMC_TCLRSetupTime)); - assert_param( IS_FSMC_TAR_TIME(FSMC_NANDInitStruct->FSMC_TARSetupTime)); - assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime)); - assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime)); - assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime)); - assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime)); - assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime)); - assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime)); - assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime)); - assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime)); - - /* Set the tmppcr value according to FSMC_NANDInitStruct parameters */ - tmppcr = (uint32_t)FSMC_NANDInitStruct->FSMC_Waitfeature | - PCR_MemoryType_NAND | - FSMC_NANDInitStruct->FSMC_MemoryDataWidth | - FSMC_NANDInitStruct->FSMC_ECC | - FSMC_NANDInitStruct->FSMC_ECCPageSize | - (FSMC_NANDInitStruct->FSMC_TCLRSetupTime << 9 )| - (FSMC_NANDInitStruct->FSMC_TARSetupTime << 13); - - /* Set tmppmem value according to FSMC_CommonSpaceTimingStructure parameters */ - tmppmem = (uint32_t)FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime | - (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) | - (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)| - (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); - - /* Set tmppatt value according to FSMC_AttributeSpaceTimingStructure parameters */ - tmppatt = (uint32_t)FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime | - (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) | - (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)| - (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24); - - if(FSMC_NANDInitStruct->FSMC_Bank == FSMC_Bank2_NAND) - { - /* FSMC_Bank2_NAND registers configuration */ - FSMC_Bank2->PCR2 = tmppcr; - FSMC_Bank2->PMEM2 = tmppmem; - FSMC_Bank2->PATT2 = tmppatt; - } - else - { - /* FSMC_Bank3_NAND registers configuration */ - FSMC_Bank3->PCR3 = tmppcr; - FSMC_Bank3->PMEM3 = tmppmem; - FSMC_Bank3->PATT3 = tmppatt; - } -} - -/** - * @brief Initializes the FSMC PCCARD Bank according to the specified - * parameters in the FSMC_PCCARDInitStruct. - * @param FSMC_PCCARDInitStruct : pointer to a FSMC_PCCARDInitTypeDef - * structure that contains the configuration information for the FSMC PCCARD Bank. - * @retval None - */ -void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct) -{ - /* Check the parameters */ - assert_param(IS_FSMC_WAIT_FEATURE(FSMC_PCCARDInitStruct->FSMC_Waitfeature)); - assert_param(IS_FSMC_TCLR_TIME(FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime)); - assert_param(IS_FSMC_TAR_TIME(FSMC_PCCARDInitStruct->FSMC_TARSetupTime)); - - assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime)); - assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime)); - assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime)); - assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime)); - - assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime)); - assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime)); - assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime)); - assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime)); - assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime)); - assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime)); - assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime)); - assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime)); - - /* Set the PCR4 register value according to FSMC_PCCARDInitStruct parameters */ - FSMC_Bank4->PCR4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_Waitfeature | - FSMC_MemoryDataWidth_16b | - (FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime << 9) | - (FSMC_PCCARDInitStruct->FSMC_TARSetupTime << 13); - - /* Set PMEM4 register value according to FSMC_CommonSpaceTimingStructure parameters */ - FSMC_Bank4->PMEM4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime | - (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) | - (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)| - (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); - - /* Set PATT4 register value according to FSMC_AttributeSpaceTimingStructure parameters */ - FSMC_Bank4->PATT4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime | - (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) | - (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)| - (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24); - - /* Set PIO4 register value according to FSMC_IOSpaceTimingStructure parameters */ - FSMC_Bank4->PIO4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime | - (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime << 8) | - (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime << 16)| - (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime << 24); -} - -/** - * @brief Fills each FSMC_NORSRAMInitStruct member with its default value. - * @param FSMC_NORSRAMInitStruct: pointer to a FSMC_NORSRAMInitTypeDef - * structure which will be initialized. - * @retval None - */ -void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct) -{ - /* Reset NOR/SRAM Init structure parameters values */ - FSMC_NORSRAMInitStruct->FSMC_Bank = FSMC_Bank1_NORSRAM1; - FSMC_NORSRAMInitStruct->FSMC_DataAddressMux = FSMC_DataAddressMux_Enable; - FSMC_NORSRAMInitStruct->FSMC_MemoryType = FSMC_MemoryType_SRAM; - FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b; - FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; - FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; - FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; - FSMC_NORSRAMInitStruct->FSMC_WrapMode = FSMC_WrapMode_Disable; - FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; - FSMC_NORSRAMInitStruct->FSMC_WriteOperation = FSMC_WriteOperation_Enable; - FSMC_NORSRAMInitStruct->FSMC_WaitSignal = FSMC_WaitSignal_Enable; - FSMC_NORSRAMInitStruct->FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; - FSMC_NORSRAMInitStruct->FSMC_WriteBurst = FSMC_WriteBurst_Disable; - FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime = 0xF; - FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime = 0xF; - FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime = 0xFF; - FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF; - FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision = 0xF; - FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency = 0xF; - FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; - FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime = 0xF; - FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime = 0xF; - FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime = 0xFF; - FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF; - FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision = 0xF; - FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency = 0xF; - FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; -} - -/** - * @brief Fills each FSMC_NANDInitStruct member with its default value. - * @param FSMC_NANDInitStruct: pointer to a FSMC_NANDInitTypeDef - * structure which will be initialized. - * @retval None - */ -void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct) -{ - /* Reset NAND Init structure parameters values */ - FSMC_NANDInitStruct->FSMC_Bank = FSMC_Bank2_NAND; - FSMC_NANDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable; - FSMC_NANDInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b; - FSMC_NANDInitStruct->FSMC_ECC = FSMC_ECC_Disable; - FSMC_NANDInitStruct->FSMC_ECCPageSize = FSMC_ECCPageSize_256Bytes; - FSMC_NANDInitStruct->FSMC_TCLRSetupTime = 0x0; - FSMC_NANDInitStruct->FSMC_TARSetupTime = 0x0; - FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC; - FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; - FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; - FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; - FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC; - FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; - FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; - FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; -} - -/** - * @brief Fills each FSMC_PCCARDInitStruct member with its default value. - * @param FSMC_PCCARDInitStruct: pointer to a FSMC_PCCARDInitTypeDef - * structure which will be initialized. - * @retval None - */ -void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct) -{ - /* Reset PCCARD Init structure parameters values */ - FSMC_PCCARDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable; - FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime = 0x0; - FSMC_PCCARDInitStruct->FSMC_TARSetupTime = 0x0; - FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; - FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; -} - -/** - * @brief Enables or disables the specified NOR/SRAM Memory Bank. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1 - * @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 - * @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 - * @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 - * @param NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState) -{ - assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */ - FSMC_Bank1->BTCR[FSMC_Bank] |= BCR_MBKEN_Set; - } - else - { - /* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */ - FSMC_Bank1->BTCR[FSMC_Bank] &= BCR_MBKEN_Reset; - } -} - -/** - * @brief Enables or disables the specified NAND Memory Bank. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND - * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND - * @param NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState) -{ - assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */ - if(FSMC_Bank == FSMC_Bank2_NAND) - { - FSMC_Bank2->PCR2 |= PCR_PBKEN_Set; - } - else - { - FSMC_Bank3->PCR3 |= PCR_PBKEN_Set; - } - } - else - { - /* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */ - if(FSMC_Bank == FSMC_Bank2_NAND) - { - FSMC_Bank2->PCR2 &= PCR_PBKEN_Reset; - } - else - { - FSMC_Bank3->PCR3 &= PCR_PBKEN_Reset; - } - } -} - -/** - * @brief Enables or disables the PCCARD Memory Bank. - * @param NewState: new state of the PCCARD Memory Bank. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void FSMC_PCCARDCmd(FunctionalState NewState) -{ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the PCCARD Bank by setting the PBKEN bit in the PCR4 register */ - FSMC_Bank4->PCR4 |= PCR_PBKEN_Set; - } - else - { - /* Disable the PCCARD Bank by clearing the PBKEN bit in the PCR4 register */ - FSMC_Bank4->PCR4 &= PCR_PBKEN_Reset; - } -} - -/** - * @brief Enables or disables the FSMC NAND ECC feature. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND - * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND - * @param NewState: new state of the FSMC NAND ECC feature. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState) -{ - assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */ - if(FSMC_Bank == FSMC_Bank2_NAND) - { - FSMC_Bank2->PCR2 |= PCR_ECCEN_Set; - } - else - { - FSMC_Bank3->PCR3 |= PCR_ECCEN_Set; - } - } - else - { - /* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */ - if(FSMC_Bank == FSMC_Bank2_NAND) - { - FSMC_Bank2->PCR2 &= PCR_ECCEN_Reset; - } - else - { - FSMC_Bank3->PCR3 &= PCR_ECCEN_Reset; - } - } -} - -/** - * @brief Returns the error correction code register value. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND - * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND - * @retval The Error Correction Code (ECC) value. - */ -uint32_t FSMC_GetECC(uint32_t FSMC_Bank) -{ - uint32_t eccval = 0x00000000; - - if(FSMC_Bank == FSMC_Bank2_NAND) - { - /* Get the ECCR2 register value */ - eccval = FSMC_Bank2->ECCR2; - } - else - { - /* Get the ECCR3 register value */ - eccval = FSMC_Bank3->ECCR3; - } - /* Return the error correction code value */ - return(eccval); -} - -/** - * @brief Enables or disables the specified FSMC interrupts. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND - * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND - * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD - * @param FSMC_IT: specifies the FSMC interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. - * @arg FSMC_IT_Level: Level edge detection interrupt. - * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. - * @param NewState: new state of the specified FSMC interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState) -{ - assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); - assert_param(IS_FSMC_IT(FSMC_IT)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the selected FSMC_Bank2 interrupts */ - if(FSMC_Bank == FSMC_Bank2_NAND) - { - FSMC_Bank2->SR2 |= FSMC_IT; - } - /* Enable the selected FSMC_Bank3 interrupts */ - else if (FSMC_Bank == FSMC_Bank3_NAND) - { - FSMC_Bank3->SR3 |= FSMC_IT; - } - /* Enable the selected FSMC_Bank4 interrupts */ - else - { - FSMC_Bank4->SR4 |= FSMC_IT; - } - } - else - { - /* Disable the selected FSMC_Bank2 interrupts */ - if(FSMC_Bank == FSMC_Bank2_NAND) - { - - FSMC_Bank2->SR2 &= (uint32_t)~FSMC_IT; - } - /* Disable the selected FSMC_Bank3 interrupts */ - else if (FSMC_Bank == FSMC_Bank3_NAND) - { - FSMC_Bank3->SR3 &= (uint32_t)~FSMC_IT; - } - /* Disable the selected FSMC_Bank4 interrupts */ - else - { - FSMC_Bank4->SR4 &= (uint32_t)~FSMC_IT; - } - } -} - -/** - * @brief Checks whether the specified FSMC flag is set or not. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND - * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND - * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD - * @param FSMC_FLAG: specifies the flag to check. - * This parameter can be one of the following values: - * @arg FSMC_FLAG_RisingEdge: Rising egde detection Flag. - * @arg FSMC_FLAG_Level: Level detection Flag. - * @arg FSMC_FLAG_FallingEdge: Falling egde detection Flag. - * @arg FSMC_FLAG_FEMPT: Fifo empty Flag. - * @retval The new state of FSMC_FLAG (SET or RESET). - */ -FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG) -{ - FlagStatus bitstatus = RESET; - uint32_t tmpsr = 0x00000000; - - /* Check the parameters */ - assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank)); - assert_param(IS_FSMC_GET_FLAG(FSMC_FLAG)); - - if(FSMC_Bank == FSMC_Bank2_NAND) - { - tmpsr = FSMC_Bank2->SR2; - } - else if(FSMC_Bank == FSMC_Bank3_NAND) - { - tmpsr = FSMC_Bank3->SR3; - } - /* FSMC_Bank4_PCCARD*/ - else - { - tmpsr = FSMC_Bank4->SR4; - } - - /* Get the flag status */ - if ((tmpsr & FSMC_FLAG) != (uint16_t)RESET ) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - /* Return the flag status */ - return bitstatus; -} - -/** - * @brief Clears the FSMC’s pending flags. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND - * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND - * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD - * @param FSMC_FLAG: specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg FSMC_FLAG_RisingEdge: Rising egde detection Flag. - * @arg FSMC_FLAG_Level: Level detection Flag. - * @arg FSMC_FLAG_FallingEdge: Falling egde detection Flag. - * @retval None - */ -void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG) -{ - /* Check the parameters */ - assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank)); - assert_param(IS_FSMC_CLEAR_FLAG(FSMC_FLAG)) ; - - if(FSMC_Bank == FSMC_Bank2_NAND) - { - FSMC_Bank2->SR2 &= ~FSMC_FLAG; - } - else if(FSMC_Bank == FSMC_Bank3_NAND) - { - FSMC_Bank3->SR3 &= ~FSMC_FLAG; - } - /* FSMC_Bank4_PCCARD*/ - else - { - FSMC_Bank4->SR4 &= ~FSMC_FLAG; - } -} - -/** - * @brief Checks whether the specified FSMC interrupt has occurred or not. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND - * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND - * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD - * @param FSMC_IT: specifies the FSMC interrupt source to check. - * This parameter can be one of the following values: - * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. - * @arg FSMC_IT_Level: Level edge detection interrupt. - * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. - * @retval The new state of FSMC_IT (SET or RESET). - */ -ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT) -{ - ITStatus bitstatus = RESET; - uint32_t tmpsr = 0x0, itstatus = 0x0, itenable = 0x0; - - /* Check the parameters */ - assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); - assert_param(IS_FSMC_GET_IT(FSMC_IT)); - - if(FSMC_Bank == FSMC_Bank2_NAND) - { - tmpsr = FSMC_Bank2->SR2; - } - else if(FSMC_Bank == FSMC_Bank3_NAND) - { - tmpsr = FSMC_Bank3->SR3; - } - /* FSMC_Bank4_PCCARD*/ - else - { - tmpsr = FSMC_Bank4->SR4; - } - - itstatus = tmpsr & FSMC_IT; - - itenable = tmpsr & (FSMC_IT >> 3); - if ((itstatus != (uint32_t)RESET) && (itenable != (uint32_t)RESET)) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - return bitstatus; -} - -/** - * @brief Clears the FSMC’s interrupt pending bits. - * @param FSMC_Bank: specifies the FSMC Bank to be used - * This parameter can be one of the following values: - * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND - * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND - * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD - * @param FSMC_IT: specifies the interrupt pending bit to clear. - * This parameter can be any combination of the following values: - * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. - * @arg FSMC_IT_Level: Level edge detection interrupt. - * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. - * @retval None - */ -void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT) -{ - /* Check the parameters */ - assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); - assert_param(IS_FSMC_IT(FSMC_IT)); - - if(FSMC_Bank == FSMC_Bank2_NAND) - { - FSMC_Bank2->SR2 &= ~(FSMC_IT >> 3); - } - else if(FSMC_Bank == FSMC_Bank3_NAND) - { - FSMC_Bank3->SR3 &= ~(FSMC_IT >> 3); - } - /* FSMC_Bank4_PCCARD*/ - else - { - FSMC_Bank4->SR4 &= ~(FSMC_IT >> 3); - } -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_fsmc.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the FSMC firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_fsmc.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup FSMC + * @brief FSMC driver modules + * @{ + */ + +/** @defgroup FSMC_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + +/** @defgroup FSMC_Private_Defines + * @{ + */ + +/* --------------------- FSMC registers bit mask ---------------------------- */ + +/* FSMC BCRx Mask */ +#define BCR_MBKEN_Set ((uint32_t)0x00000001) +#define BCR_MBKEN_Reset ((uint32_t)0x000FFFFE) +#define BCR_FACCEN_Set ((uint32_t)0x00000040) + +/* FSMC PCRx Mask */ +#define PCR_PBKEN_Set ((uint32_t)0x00000004) +#define PCR_PBKEN_Reset ((uint32_t)0x000FFFFB) +#define PCR_ECCEN_Set ((uint32_t)0x00000040) +#define PCR_ECCEN_Reset ((uint32_t)0x000FFFBF) +#define PCR_MemoryType_NAND ((uint32_t)0x00000008) +/** + * @} + */ + +/** @defgroup FSMC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the FSMC NOR/SRAM Banks registers to their default + * reset values. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1 + * @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 + * @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 + * @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 + * @retval None + */ +void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank) +{ + /* Check the parameter */ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank)); + + /* FSMC_Bank1_NORSRAM1 */ + if(FSMC_Bank == FSMC_Bank1_NORSRAM1) + { + FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030DB; + } + /* FSMC_Bank1_NORSRAM2, FSMC_Bank1_NORSRAM3 or FSMC_Bank1_NORSRAM4 */ + else + { + FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030D2; + } + FSMC_Bank1->BTCR[FSMC_Bank + 1] = 0x0FFFFFFF; + FSMC_Bank1E->BWTR[FSMC_Bank] = 0x0FFFFFFF; +} + +/** + * @brief Deinitializes the FSMC NAND Banks registers to their default reset values. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @retval None + */ +void FSMC_NANDDeInit(uint32_t FSMC_Bank) +{ + /* Check the parameter */ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + /* Set the FSMC_Bank2 registers to their reset values */ + FSMC_Bank2->PCR2 = 0x00000018; + FSMC_Bank2->SR2 = 0x00000040; + FSMC_Bank2->PMEM2 = 0xFCFCFCFC; + FSMC_Bank2->PATT2 = 0xFCFCFCFC; + } + /* FSMC_Bank3_NAND */ + else + { + /* Set the FSMC_Bank3 registers to their reset values */ + FSMC_Bank3->PCR3 = 0x00000018; + FSMC_Bank3->SR3 = 0x00000040; + FSMC_Bank3->PMEM3 = 0xFCFCFCFC; + FSMC_Bank3->PATT3 = 0xFCFCFCFC; + } +} + +/** + * @brief Deinitializes the FSMC PCCARD Bank registers to their default reset values. + * @param None + * @retval None + */ +void FSMC_PCCARDDeInit(void) +{ + /* Set the FSMC_Bank4 registers to their reset values */ + FSMC_Bank4->PCR4 = 0x00000018; + FSMC_Bank4->SR4 = 0x00000000; + FSMC_Bank4->PMEM4 = 0xFCFCFCFC; + FSMC_Bank4->PATT4 = 0xFCFCFCFC; + FSMC_Bank4->PIO4 = 0xFCFCFCFC; +} + +/** + * @brief Initializes the FSMC NOR/SRAM Banks according to the specified + * parameters in the FSMC_NORSRAMInitStruct. + * @param FSMC_NORSRAMInitStruct : pointer to a FSMC_NORSRAMInitTypeDef + * structure that contains the configuration information for + * the FSMC NOR/SRAM specified Banks. + * @retval None + */ +void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct) +{ + /* Check the parameters */ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_NORSRAMInitStruct->FSMC_Bank)); + assert_param(IS_FSMC_MUX(FSMC_NORSRAMInitStruct->FSMC_DataAddressMux)); + assert_param(IS_FSMC_MEMORY(FSMC_NORSRAMInitStruct->FSMC_MemoryType)); + assert_param(IS_FSMC_MEMORY_WIDTH(FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth)); + assert_param(IS_FSMC_BURSTMODE(FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode)); + assert_param(IS_FSMC_ASYNWAIT(FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait)); + assert_param(IS_FSMC_WAIT_POLARITY(FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity)); + assert_param(IS_FSMC_WRAP_MODE(FSMC_NORSRAMInitStruct->FSMC_WrapMode)); + assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive)); + assert_param(IS_FSMC_WRITE_OPERATION(FSMC_NORSRAMInitStruct->FSMC_WriteOperation)); + assert_param(IS_FSMC_WAITE_SIGNAL(FSMC_NORSRAMInitStruct->FSMC_WaitSignal)); + assert_param(IS_FSMC_EXTENDED_MODE(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode)); + assert_param(IS_FSMC_WRITE_BURST(FSMC_NORSRAMInitStruct->FSMC_WriteBurst)); + assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime)); + assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime)); + assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime)); + assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration)); + assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision)); + assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency)); + assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode)); + + /* Bank1 NOR/SRAM control register configuration */ + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_DataAddressMux | + FSMC_NORSRAMInitStruct->FSMC_MemoryType | + FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth | + FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode | + FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait | + FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity | + FSMC_NORSRAMInitStruct->FSMC_WrapMode | + FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive | + FSMC_NORSRAMInitStruct->FSMC_WriteOperation | + FSMC_NORSRAMInitStruct->FSMC_WaitSignal | + FSMC_NORSRAMInitStruct->FSMC_ExtendedMode | + FSMC_NORSRAMInitStruct->FSMC_WriteBurst; + + if(FSMC_NORSRAMInitStruct->FSMC_MemoryType == FSMC_MemoryType_NOR) + { + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] |= (uint32_t)BCR_FACCEN_Set; + } + + /* Bank1 NOR/SRAM timing register configuration */ + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank+1] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime << 4) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime << 8) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration << 16) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision << 20) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency << 24) | + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode; + + + /* Bank1 NOR/SRAM timing register for write configuration, if extended mode is used */ + if(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode == FSMC_ExtendedMode_Enable) + { + assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime)); + assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime)); + assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime)); + assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision)); + assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency)); + assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode)); + FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime << 4 )| + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime << 8) | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision << 20) | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency << 24) | + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode; + } + else + { + FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 0x0FFFFFFF; + } +} + +/** + * @brief Initializes the FSMC NAND Banks according to the specified + * parameters in the FSMC_NANDInitStruct. + * @param FSMC_NANDInitStruct : pointer to a FSMC_NANDInitTypeDef + * structure that contains the configuration information for the FSMC NAND specified Banks. + * @retval None + */ +void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct) +{ + uint32_t tmppcr = 0x00000000, tmppmem = 0x00000000, tmppatt = 0x00000000; + + /* Check the parameters */ + assert_param( IS_FSMC_NAND_BANK(FSMC_NANDInitStruct->FSMC_Bank)); + assert_param( IS_FSMC_WAIT_FEATURE(FSMC_NANDInitStruct->FSMC_Waitfeature)); + assert_param( IS_FSMC_MEMORY_WIDTH(FSMC_NANDInitStruct->FSMC_MemoryDataWidth)); + assert_param( IS_FSMC_ECC_STATE(FSMC_NANDInitStruct->FSMC_ECC)); + assert_param( IS_FSMC_ECCPAGE_SIZE(FSMC_NANDInitStruct->FSMC_ECCPageSize)); + assert_param( IS_FSMC_TCLR_TIME(FSMC_NANDInitStruct->FSMC_TCLRSetupTime)); + assert_param( IS_FSMC_TAR_TIME(FSMC_NANDInitStruct->FSMC_TARSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime)); + + /* Set the tmppcr value according to FSMC_NANDInitStruct parameters */ + tmppcr = (uint32_t)FSMC_NANDInitStruct->FSMC_Waitfeature | + PCR_MemoryType_NAND | + FSMC_NANDInitStruct->FSMC_MemoryDataWidth | + FSMC_NANDInitStruct->FSMC_ECC | + FSMC_NANDInitStruct->FSMC_ECCPageSize | + (FSMC_NANDInitStruct->FSMC_TCLRSetupTime << 9 )| + (FSMC_NANDInitStruct->FSMC_TARSetupTime << 13); + + /* Set tmppmem value according to FSMC_CommonSpaceTimingStructure parameters */ + tmppmem = (uint32_t)FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime | + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set tmppatt value according to FSMC_AttributeSpaceTimingStructure parameters */ + tmppatt = (uint32_t)FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime | + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + if(FSMC_NANDInitStruct->FSMC_Bank == FSMC_Bank2_NAND) + { + /* FSMC_Bank2_NAND registers configuration */ + FSMC_Bank2->PCR2 = tmppcr; + FSMC_Bank2->PMEM2 = tmppmem; + FSMC_Bank2->PATT2 = tmppatt; + } + else + { + /* FSMC_Bank3_NAND registers configuration */ + FSMC_Bank3->PCR3 = tmppcr; + FSMC_Bank3->PMEM3 = tmppmem; + FSMC_Bank3->PATT3 = tmppatt; + } +} + +/** + * @brief Initializes the FSMC PCCARD Bank according to the specified + * parameters in the FSMC_PCCARDInitStruct. + * @param FSMC_PCCARDInitStruct : pointer to a FSMC_PCCARDInitTypeDef + * structure that contains the configuration information for the FSMC PCCARD Bank. + * @retval None + */ +void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct) +{ + /* Check the parameters */ + assert_param(IS_FSMC_WAIT_FEATURE(FSMC_PCCARDInitStruct->FSMC_Waitfeature)); + assert_param(IS_FSMC_TCLR_TIME(FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime)); + assert_param(IS_FSMC_TAR_TIME(FSMC_PCCARDInitStruct->FSMC_TARSetupTime)); + + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime)); + + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime)); + + /* Set the PCR4 register value according to FSMC_PCCARDInitStruct parameters */ + FSMC_Bank4->PCR4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_Waitfeature | + FSMC_MemoryDataWidth_16b | + (FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime << 9) | + (FSMC_PCCARDInitStruct->FSMC_TARSetupTime << 13); + + /* Set PMEM4 register value according to FSMC_CommonSpaceTimingStructure parameters */ + FSMC_Bank4->PMEM4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set PATT4 register value according to FSMC_AttributeSpaceTimingStructure parameters */ + FSMC_Bank4->PATT4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set PIO4 register value according to FSMC_IOSpaceTimingStructure parameters */ + FSMC_Bank4->PIO4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime << 24); +} + +/** + * @brief Fills each FSMC_NORSRAMInitStruct member with its default value. + * @param FSMC_NORSRAMInitStruct: pointer to a FSMC_NORSRAMInitTypeDef + * structure which will be initialized. + * @retval None + */ +void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct) +{ + /* Reset NOR/SRAM Init structure parameters values */ + FSMC_NORSRAMInitStruct->FSMC_Bank = FSMC_Bank1_NORSRAM1; + FSMC_NORSRAMInitStruct->FSMC_DataAddressMux = FSMC_DataAddressMux_Enable; + FSMC_NORSRAMInitStruct->FSMC_MemoryType = FSMC_MemoryType_SRAM; + FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b; + FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; + FSMC_NORSRAMInitStruct->FSMC_WrapMode = FSMC_WrapMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; + FSMC_NORSRAMInitStruct->FSMC_WriteOperation = FSMC_WriteOperation_Enable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignal = FSMC_WaitSignal_Enable; + FSMC_NORSRAMInitStruct->FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_WriteBurst = FSMC_WriteBurst_Disable; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime = 0xFF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime = 0xFF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; +} + +/** + * @brief Fills each FSMC_NANDInitStruct member with its default value. + * @param FSMC_NANDInitStruct: pointer to a FSMC_NANDInitTypeDef + * structure which will be initialized. + * @retval None + */ +void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct) +{ + /* Reset NAND Init structure parameters values */ + FSMC_NANDInitStruct->FSMC_Bank = FSMC_Bank2_NAND; + FSMC_NANDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable; + FSMC_NANDInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b; + FSMC_NANDInitStruct->FSMC_ECC = FSMC_ECC_Disable; + FSMC_NANDInitStruct->FSMC_ECCPageSize = FSMC_ECCPageSize_256Bytes; + FSMC_NANDInitStruct->FSMC_TCLRSetupTime = 0x0; + FSMC_NANDInitStruct->FSMC_TARSetupTime = 0x0; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; +} + +/** + * @brief Fills each FSMC_PCCARDInitStruct member with its default value. + * @param FSMC_PCCARDInitStruct: pointer to a FSMC_PCCARDInitTypeDef + * structure which will be initialized. + * @retval None + */ +void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct) +{ + /* Reset PCCARD Init structure parameters values */ + FSMC_PCCARDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable; + FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime = 0x0; + FSMC_PCCARDInitStruct->FSMC_TARSetupTime = 0x0; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; +} + +/** + * @brief Enables or disables the specified NOR/SRAM Memory Bank. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1 + * @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 + * @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 + * @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 + * @param NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */ + FSMC_Bank1->BTCR[FSMC_Bank] |= BCR_MBKEN_Set; + } + else + { + /* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */ + FSMC_Bank1->BTCR[FSMC_Bank] &= BCR_MBKEN_Reset; + } +} + +/** + * @brief Enables or disables the specified NAND Memory Bank. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @param NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 |= PCR_PBKEN_Set; + } + else + { + FSMC_Bank3->PCR3 |= PCR_PBKEN_Set; + } + } + else + { + /* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 &= PCR_PBKEN_Reset; + } + else + { + FSMC_Bank3->PCR3 &= PCR_PBKEN_Reset; + } + } +} + +/** + * @brief Enables or disables the PCCARD Memory Bank. + * @param NewState: new state of the PCCARD Memory Bank. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_PCCARDCmd(FunctionalState NewState) +{ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the PCCARD Bank by setting the PBKEN bit in the PCR4 register */ + FSMC_Bank4->PCR4 |= PCR_PBKEN_Set; + } + else + { + /* Disable the PCCARD Bank by clearing the PBKEN bit in the PCR4 register */ + FSMC_Bank4->PCR4 &= PCR_PBKEN_Reset; + } +} + +/** + * @brief Enables or disables the FSMC NAND ECC feature. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @param NewState: new state of the FSMC NAND ECC feature. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 |= PCR_ECCEN_Set; + } + else + { + FSMC_Bank3->PCR3 |= PCR_ECCEN_Set; + } + } + else + { + /* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 &= PCR_ECCEN_Reset; + } + else + { + FSMC_Bank3->PCR3 &= PCR_ECCEN_Reset; + } + } +} + +/** + * @brief Returns the error correction code register value. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @retval The Error Correction Code (ECC) value. + */ +uint32_t FSMC_GetECC(uint32_t FSMC_Bank) +{ + uint32_t eccval = 0x00000000; + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + /* Get the ECCR2 register value */ + eccval = FSMC_Bank2->ECCR2; + } + else + { + /* Get the ECCR3 register value */ + eccval = FSMC_Bank3->ECCR3; + } + /* Return the error correction code value */ + return(eccval); +} + +/** + * @brief Enables or disables the specified FSMC interrupts. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the FSMC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @param NewState: new state of the specified FSMC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState) +{ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_IT(FSMC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected FSMC_Bank2 interrupts */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 |= FSMC_IT; + } + /* Enable the selected FSMC_Bank3 interrupts */ + else if (FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 |= FSMC_IT; + } + /* Enable the selected FSMC_Bank4 interrupts */ + else + { + FSMC_Bank4->SR4 |= FSMC_IT; + } + } + else + { + /* Disable the selected FSMC_Bank2 interrupts */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + + FSMC_Bank2->SR2 &= (uint32_t)~FSMC_IT; + } + /* Disable the selected FSMC_Bank3 interrupts */ + else if (FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= (uint32_t)~FSMC_IT; + } + /* Disable the selected FSMC_Bank4 interrupts */ + else + { + FSMC_Bank4->SR4 &= (uint32_t)~FSMC_IT; + } + } +} + +/** + * @brief Checks whether the specified FSMC flag is set or not. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg FSMC_FLAG_RisingEdge: Rising egde detection Flag. + * @arg FSMC_FLAG_Level: Level detection Flag. + * @arg FSMC_FLAG_FallingEdge: Falling egde detection Flag. + * @arg FSMC_FLAG_FEMPT: Fifo empty Flag. + * @retval The new state of FSMC_FLAG (SET or RESET). + */ +FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tmpsr = 0x00000000; + + /* Check the parameters */ + assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank)); + assert_param(IS_FSMC_GET_FLAG(FSMC_FLAG)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + tmpsr = FSMC_Bank2->SR2; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + tmpsr = FSMC_Bank3->SR3; + } + /* FSMC_Bank4_PCCARD*/ + else + { + tmpsr = FSMC_Bank4->SR4; + } + + /* Get the flag status */ + if ((tmpsr & FSMC_FLAG) != (uint16_t)RESET ) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the FSMC’s pending flags. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg FSMC_FLAG_RisingEdge: Rising egde detection Flag. + * @arg FSMC_FLAG_Level: Level detection Flag. + * @arg FSMC_FLAG_FallingEdge: Falling egde detection Flag. + * @retval None + */ +void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank)); + assert_param(IS_FSMC_CLEAR_FLAG(FSMC_FLAG)) ; + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 &= ~FSMC_FLAG; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= ~FSMC_FLAG; + } + /* FSMC_Bank4_PCCARD*/ + else + { + FSMC_Bank4->SR4 &= ~FSMC_FLAG; + } +} + +/** + * @brief Checks whether the specified FSMC interrupt has occurred or not. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the FSMC interrupt source to check. + * This parameter can be one of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @retval The new state of FSMC_IT (SET or RESET). + */ +ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpsr = 0x0, itstatus = 0x0, itenable = 0x0; + + /* Check the parameters */ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_GET_IT(FSMC_IT)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + tmpsr = FSMC_Bank2->SR2; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + tmpsr = FSMC_Bank3->SR3; + } + /* FSMC_Bank4_PCCARD*/ + else + { + tmpsr = FSMC_Bank4->SR4; + } + + itstatus = tmpsr & FSMC_IT; + + itenable = tmpsr & (FSMC_IT >> 3); + if ((itstatus != (uint32_t)RESET) && (itenable != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the FSMC’s interrupt pending bits. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @retval None + */ +void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT) +{ + /* Check the parameters */ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_IT(FSMC_IT)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 &= ~(FSMC_IT >> 3); + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= ~(FSMC_IT >> 3); + } + /* FSMC_Bank4_PCCARD*/ + else + { + FSMC_Bank4->SR4 &= ~(FSMC_IT >> 3); + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c index 88268473c..265b720e7 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c @@ -1,647 +1,647 @@ -/** - ****************************************************************************** - * @file stm32f10x_gpio.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the GPIO firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_gpio.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup GPIO - * @brief GPIO driver modules - * @{ - */ - -/** @defgroup GPIO_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup GPIO_Private_Defines - * @{ - */ - -/* ------------ RCC registers bit address in the alias region ----------------*/ -#define AFIO_OFFSET (AFIO_BASE - PERIPH_BASE) - -/* --- EVENTCR Register -----*/ - -/* Alias word address of EVOE bit */ -#define EVCR_OFFSET (AFIO_OFFSET + 0x00) -#define EVOE_BitNumber ((uint8_t)0x07) -#define EVCR_EVOE_BB (PERIPH_BB_BASE + (EVCR_OFFSET * 32) + (EVOE_BitNumber * 4)) - - -/* --- MAPR Register ---*/ -/* Alias word address of MII_RMII_SEL bit */ -#define MAPR_OFFSET (AFIO_OFFSET + 0x04) -#define MII_RMII_SEL_BitNumber ((u8)0x17) -#define MAPR_MII_RMII_SEL_BB (PERIPH_BB_BASE + (MAPR_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4)) - - -#define EVCR_PORTPINCONFIG_MASK ((uint16_t)0xFF80) -#define LSB_MASK ((uint16_t)0xFFFF) -#define DBGAFR_POSITION_MASK ((uint32_t)0x000F0000) -#define DBGAFR_SWJCFG_MASK ((uint32_t)0xF0FFFFFF) -#define DBGAFR_LOCATION_MASK ((uint32_t)0x00200000) -#define DBGAFR_NUMBITS_MASK ((uint32_t)0x00100000) -/** - * @} - */ - -/** @defgroup GPIO_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup GPIO_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup GPIO_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup GPIO_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the GPIOx peripheral registers to their default reset values. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @retval None - */ -void GPIO_DeInit(GPIO_TypeDef* GPIOx) -{ - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - - if (GPIOx == GPIOA) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, DISABLE); - } - else if (GPIOx == GPIOB) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, DISABLE); - } - else if (GPIOx == GPIOC) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, DISABLE); - } - else if (GPIOx == GPIOD) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, DISABLE); - } - else if (GPIOx == GPIOE) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, DISABLE); - } - else if (GPIOx == GPIOF) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, DISABLE); - } - else - { - if (GPIOx == GPIOG) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, DISABLE); - } - } -} - -/** - * @brief Deinitializes the Alternate Functions (remap, event control - * and EXTI configuration) registers to their default reset values. - * @param None - * @retval None - */ -void GPIO_AFIODeInit(void) -{ - RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, DISABLE); -} - -/** - * @brief Initializes the GPIOx peripheral according to the specified - * parameters in the GPIO_InitStruct. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that - * contains the configuration information for the specified GPIO peripheral. - * @retval None - */ -void GPIO_Init(GPIO_TypeDef* GPIOx, const GPIO_InitTypeDef* GPIO_InitStruct) -{ - uint32_t currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00; - uint32_t tmpreg = 0x00, pinmask = 0x00; - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode)); - assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin)); - -/*---------------------------- GPIO Mode Configuration -----------------------*/ - currentmode = ((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x0F); - if ((((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x10)) != 0x00) - { - /* Check the parameters */ - assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed)); - /* Output mode */ - currentmode |= (uint32_t)GPIO_InitStruct->GPIO_Speed; - } -/*---------------------------- GPIO CRL Configuration ------------------------*/ - /* Configure the eight low port pins */ - if (((uint32_t)GPIO_InitStruct->GPIO_Pin & ((uint32_t)0x00FF)) != 0x00) - { - tmpreg = GPIOx->CRL; - for (pinpos = 0x00; pinpos < 0x08; pinpos++) - { - pos = ((uint32_t)0x01) << pinpos; - /* Get the port pins position */ - currentpin = (GPIO_InitStruct->GPIO_Pin) & pos; - if (currentpin == pos) - { - pos = pinpos << 2; - /* Clear the corresponding low control register bits */ - pinmask = ((uint32_t)0x0F) << pos; - tmpreg &= ~pinmask; - /* Write the mode configuration in the corresponding bits */ - tmpreg |= (currentmode << pos); - /* Reset the corresponding ODR bit */ - if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD) - { - GPIOx->BRR = (((uint32_t)0x01) << pinpos); - } - else - { - /* Set the corresponding ODR bit */ - if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU) - { - GPIOx->BSRR = (((uint32_t)0x01) << pinpos); - } - } - } - } - GPIOx->CRL = tmpreg; - } -/*---------------------------- GPIO CRH Configuration ------------------------*/ - /* Configure the eight high port pins */ - if (GPIO_InitStruct->GPIO_Pin > 0x00FF) - { - tmpreg = GPIOx->CRH; - for (pinpos = 0x00; pinpos < 0x08; pinpos++) - { - pos = (((uint32_t)0x01) << (pinpos + 0x08)); - /* Get the port pins position */ - currentpin = ((GPIO_InitStruct->GPIO_Pin) & pos); - if (currentpin == pos) - { - pos = pinpos << 2; - /* Clear the corresponding high control register bits */ - pinmask = ((uint32_t)0x0F) << pos; - tmpreg &= ~pinmask; - /* Write the mode configuration in the corresponding bits */ - tmpreg |= (currentmode << pos); - /* Reset the corresponding ODR bit */ - if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD) - { - GPIOx->BRR = (((uint32_t)0x01) << (pinpos + 0x08)); - } - /* Set the corresponding ODR bit */ - if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU) - { - GPIOx->BSRR = (((uint32_t)0x01) << (pinpos + 0x08)); - } - } - } - GPIOx->CRH = tmpreg; - } -} - -/** - * @brief Fills each GPIO_InitStruct member with its default value. - * @param GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure which will - * be initialized. - * @retval None - */ -void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct) -{ - /* Reset GPIO init structure parameters values */ - GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All; - GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz; - GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN_FLOATING; -} - -/** - * @brief Reads the specified input port pin. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @param GPIO_Pin: specifies the port bit to read. - * This parameter can be GPIO_Pin_x where x can be (0..15). - * @retval The input port pin value. - */ -uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - uint8_t bitstatus = 0x00; - - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); - - if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET) - { - bitstatus = (uint8_t)Bit_SET; - } - else - { - bitstatus = (uint8_t)Bit_RESET; - } - return bitstatus; -} - -/** - * @brief Reads the specified GPIO input data port. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @retval GPIO input data port value. - */ -uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx) -{ - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - - return ((uint16_t)GPIOx->IDR); -} - -/** - * @brief Reads the specified output data port bit. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @param GPIO_Pin: specifies the port bit to read. - * This parameter can be GPIO_Pin_x where x can be (0..15). - * @retval The output port pin value. - */ -uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - uint8_t bitstatus = 0x00; - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); - - if ((GPIOx->ODR & GPIO_Pin) != (uint32_t)Bit_RESET) - { - bitstatus = (uint8_t)Bit_SET; - } - else - { - bitstatus = (uint8_t)Bit_RESET; - } - return bitstatus; -} - -/** - * @brief Reads the specified GPIO output data port. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @retval GPIO output data port value. - */ -uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx) -{ - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - - return ((uint16_t)GPIOx->ODR); -} - -/** - * @brief Sets the selected data port bits. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @param GPIO_Pin: specifies the port bits to be written. - * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). - * @retval None - */ -void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - assert_param(IS_GPIO_PIN(GPIO_Pin)); - - GPIOx->BSRR = GPIO_Pin; -} - -/** - * @brief Clears the selected data port bits. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @param GPIO_Pin: specifies the port bits to be written. - * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). - * @retval None - */ -void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - assert_param(IS_GPIO_PIN(GPIO_Pin)); - - GPIOx->BRR = GPIO_Pin; -} - -/** - * @brief Sets or clears the selected data port bit. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @param GPIO_Pin: specifies the port bit to be written. - * This parameter can be one of GPIO_Pin_x where x can be (0..15). - * @param BitVal: specifies the value to be written to the selected bit. - * This parameter can be one of the BitAction enum values: - * @arg Bit_RESET: to clear the port pin - * @arg Bit_SET: to set the port pin - * @retval None - */ -void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal) -{ - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); - assert_param(IS_GPIO_BIT_ACTION(BitVal)); - - if (BitVal != Bit_RESET) - { - GPIOx->BSRR = GPIO_Pin; - } - else - { - GPIOx->BRR = GPIO_Pin; - } -} - -/** - * @brief Writes data to the specified GPIO data port. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @param PortVal: specifies the value to be written to the port output data register. - * @retval None - */ -void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal) -{ - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - - GPIOx->ODR = PortVal; -} - -/** - * @brief Locks GPIO Pins configuration registers. - * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. - * @param GPIO_Pin: specifies the port bit to be written. - * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). - * @retval None - */ -void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) -{ - uint32_t tmp = 0x00010000; - - /* Check the parameters */ - assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); - assert_param(IS_GPIO_PIN(GPIO_Pin)); - - tmp |= GPIO_Pin; - /* Set LCKK bit */ - GPIOx->LCKR = tmp; - /* Reset LCKK bit */ - GPIOx->LCKR = GPIO_Pin; - /* Set LCKK bit */ - GPIOx->LCKR = tmp; - /* Read LCKK bit*/ - tmp = GPIOx->LCKR; - /* Read LCKK bit*/ - tmp = GPIOx->LCKR; -} - -/** - * @brief Selects the GPIO pin used as Event output. - * @param GPIO_PortSource: selects the GPIO port to be used as source - * for Event output. - * This parameter can be GPIO_PortSourceGPIOx where x can be (A..E). - * @param GPIO_PinSource: specifies the pin for the Event output. - * This parameter can be GPIO_PinSourcex where x can be (0..15). - * @retval None - */ -void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource) -{ - uint32_t tmpreg = 0x00; - /* Check the parameters */ - assert_param(IS_GPIO_EVENTOUT_PORT_SOURCE(GPIO_PortSource)); - assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); - - tmpreg = AFIO->EVCR; - /* Clear the PORT[6:4] and PIN[3:0] bits */ - tmpreg &= EVCR_PORTPINCONFIG_MASK; - tmpreg |= (uint32_t)GPIO_PortSource << 0x04; - tmpreg |= GPIO_PinSource; - AFIO->EVCR = tmpreg; -} - -/** - * @brief Enables or disables the Event Output. - * @param NewState: new state of the Event output. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void GPIO_EventOutputCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) EVCR_EVOE_BB = (uint32_t)NewState; -} - -/** - * @brief Changes the mapping of the specified pin. - * @param GPIO_Remap: selects the pin to remap. - * This parameter can be one of the following values: - * @arg GPIO_Remap_SPI1 : SPI1 Alternate Function mapping - * @arg GPIO_Remap_I2C1 : I2C1 Alternate Function mapping - * @arg GPIO_Remap_USART1 : USART1 Alternate Function mapping - * @arg GPIO_Remap_USART2 : USART2 Alternate Function mapping - * @arg GPIO_PartialRemap_USART3 : USART3 Partial Alternate Function mapping - * @arg GPIO_FullRemap_USART3 : USART3 Full Alternate Function mapping - * @arg GPIO_PartialRemap_TIM1 : TIM1 Partial Alternate Function mapping - * @arg GPIO_FullRemap_TIM1 : TIM1 Full Alternate Function mapping - * @arg GPIO_PartialRemap1_TIM2 : TIM2 Partial1 Alternate Function mapping - * @arg GPIO_PartialRemap2_TIM2 : TIM2 Partial2 Alternate Function mapping - * @arg GPIO_FullRemap_TIM2 : TIM2 Full Alternate Function mapping - * @arg GPIO_PartialRemap_TIM3 : TIM3 Partial Alternate Function mapping - * @arg GPIO_FullRemap_TIM3 : TIM3 Full Alternate Function mapping - * @arg GPIO_Remap_TIM4 : TIM4 Alternate Function mapping - * @arg GPIO_Remap1_CAN1 : CAN1 Alternate Function mapping - * @arg GPIO_Remap2_CAN1 : CAN1 Alternate Function mapping - * @arg GPIO_Remap_PD01 : PD01 Alternate Function mapping - * @arg GPIO_Remap_TIM5CH4_LSI : LSI connected to TIM5 Channel4 input capture for calibration - * @arg GPIO_Remap_ADC1_ETRGINJ : ADC1 External Trigger Injected Conversion remapping - * @arg GPIO_Remap_ADC1_ETRGREG : ADC1 External Trigger Regular Conversion remapping - * @arg GPIO_Remap_ADC2_ETRGINJ : ADC2 External Trigger Injected Conversion remapping - * @arg GPIO_Remap_ADC2_ETRGREG : ADC2 External Trigger Regular Conversion remapping - * @arg GPIO_Remap_ETH : Ethernet remapping (only for Connectivity line devices) - * @arg GPIO_Remap_CAN2 : CAN2 remapping (only for Connectivity line devices) - * @arg GPIO_Remap_SWJ_NoJTRST : Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST - * @arg GPIO_Remap_SWJ_JTAGDisable : JTAG-DP Disabled and SW-DP Enabled - * @arg GPIO_Remap_SWJ_Disable : Full SWJ Disabled (JTAG-DP + SW-DP) - * @arg GPIO_Remap_SPI3 : SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices) - * @arg GPIO_Remap_TIM2ITR1_PTP_SOF : Ethernet PTP output or USB OTG SOF (Start of Frame) connected - * to TIM2 Internal Trigger 1 for calibration (only for Connectivity line devices) - * If the GPIO_Remap_TIM2ITR1_PTP_SOF is enabled the TIM2 ITR1 is connected to - * Ethernet PTP output. When Reset TIM2 ITR1 is connected to USB OTG SOF output. - * @arg GPIO_Remap_PTP_PPS : Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) - * @arg GPIO_Remap_TIM15 : TIM15 Alternate Function mapping (only for Value line devices) - * @arg GPIO_Remap_TIM16 : TIM16 Alternate Function mapping (only for Value line devices) - * @arg GPIO_Remap_TIM17 : TIM17 Alternate Function mapping (only for Value line devices) - * @arg GPIO_Remap_CEC : CEC Alternate Function mapping (only for Value line devices) - * @arg GPIO_Remap_TIM1_DMA : TIM1 DMA requests mapping (only for Value line devices) - * @arg GPIO_Remap_TIM9 : TIM9 Alternate Function mapping (only for XL-density devices) - * @arg GPIO_Remap_TIM10 : TIM10 Alternate Function mapping (only for XL-density devices) - * @arg GPIO_Remap_TIM11 : TIM11 Alternate Function mapping (only for XL-density devices) - * @arg GPIO_Remap_TIM13 : TIM13 Alternate Function mapping (only for High density Value line and XL-density devices) - * @arg GPIO_Remap_TIM14 : TIM14 Alternate Function mapping (only for High density Value line and XL-density devices) - * @arg GPIO_Remap_FSMC_NADV : FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices) - * @arg GPIO_Remap_TIM67_DAC_DMA : TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices) - * @arg GPIO_Remap_TIM12 : TIM12 Alternate Function mapping (only for High density Value line devices) - * @arg GPIO_Remap_MISC : Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping, - * only for High density Value line devices) - * @param NewState: new state of the port pin remapping. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState) -{ - uint32_t tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00; - - /* Check the parameters */ - assert_param(IS_GPIO_REMAP(GPIO_Remap)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if((GPIO_Remap & 0x80000000) == 0x80000000) - { - tmpreg = AFIO->MAPR2; - } - else - { - tmpreg = AFIO->MAPR; - } - - tmpmask = (GPIO_Remap & DBGAFR_POSITION_MASK) >> 0x10; - tmp = GPIO_Remap & LSB_MASK; - - if ((GPIO_Remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) - { - tmpreg &= DBGAFR_SWJCFG_MASK; - AFIO->MAPR &= DBGAFR_SWJCFG_MASK; - } - else if ((GPIO_Remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK) - { - tmp1 = ((uint32_t)0x03) << tmpmask; - tmpreg &= ~tmp1; - tmpreg |= ~DBGAFR_SWJCFG_MASK; - } - else - { - tmpreg &= ~(tmp << ((GPIO_Remap >> 0x15)*0x10)); - tmpreg |= ~DBGAFR_SWJCFG_MASK; - } - - if (NewState != DISABLE) - { - tmpreg |= (tmp << ((GPIO_Remap >> 0x15)*0x10)); - } - - if((GPIO_Remap & 0x80000000) == 0x80000000) - { - AFIO->MAPR2 = tmpreg; - } - else - { - AFIO->MAPR = tmpreg; - } -} - -/** - * @brief Selects the GPIO pin used as EXTI Line. - * @param GPIO_PortSource: selects the GPIO port to be used as source for EXTI lines. - * This parameter can be GPIO_PortSourceGPIOx where x can be (A..G). - * @param GPIO_PinSource: specifies the EXTI line to be configured. - * This parameter can be GPIO_PinSourcex where x can be (0..15). - * @retval None - */ -void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource) -{ - uint32_t tmp = 0x00; - /* Check the parameters */ - assert_param(IS_GPIO_EXTI_PORT_SOURCE(GPIO_PortSource)); - assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); - - tmp = ((uint32_t)0x0F) << (0x04 * (GPIO_PinSource & (uint8_t)0x03)); - AFIO->EXTICR[GPIO_PinSource >> 0x02] &= ~tmp; - AFIO->EXTICR[GPIO_PinSource >> 0x02] |= (((uint32_t)GPIO_PortSource) << (0x04 * (GPIO_PinSource & (uint8_t)0x03))); -} - -/** - * @brief Selects the Ethernet media interface. - * @note This function applies only to STM32 Connectivity line devices. - * @param GPIO_ETH_MediaInterface: specifies the Media Interface mode. - * This parameter can be one of the following values: - * @arg GPIO_ETH_MediaInterface_MII: MII mode - * @arg GPIO_ETH_MediaInterface_RMII: RMII mode - * @retval None - */ -void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface) -{ - assert_param(IS_GPIO_ETH_MEDIA_INTERFACE(GPIO_ETH_MediaInterface)); - - /* Configure MII_RMII selection bit */ - *(__IO uint32_t *) MAPR_MII_RMII_SEL_BB = GPIO_ETH_MediaInterface; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_gpio.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the GPIO firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_gpio.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup GPIO + * @brief GPIO driver modules + * @{ + */ + +/** @defgroup GPIO_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_Defines + * @{ + */ + +/* ------------ RCC registers bit address in the alias region ----------------*/ +#define AFIO_OFFSET (AFIO_BASE - PERIPH_BASE) + +/* --- EVENTCR Register -----*/ + +/* Alias word address of EVOE bit */ +#define EVCR_OFFSET (AFIO_OFFSET + 0x00) +#define EVOE_BitNumber ((uint8_t)0x07) +#define EVCR_EVOE_BB (PERIPH_BB_BASE + (EVCR_OFFSET * 32) + (EVOE_BitNumber * 4)) + + +/* --- MAPR Register ---*/ +/* Alias word address of MII_RMII_SEL bit */ +#define MAPR_OFFSET (AFIO_OFFSET + 0x04) +#define MII_RMII_SEL_BitNumber ((u8)0x17) +#define MAPR_MII_RMII_SEL_BB (PERIPH_BB_BASE + (MAPR_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4)) + + +#define EVCR_PORTPINCONFIG_MASK ((uint16_t)0xFF80) +#define LSB_MASK ((uint16_t)0xFFFF) +#define DBGAFR_POSITION_MASK ((uint32_t)0x000F0000) +#define DBGAFR_SWJCFG_MASK ((uint32_t)0xF0FFFFFF) +#define DBGAFR_LOCATION_MASK ((uint32_t)0x00200000) +#define DBGAFR_NUMBITS_MASK ((uint32_t)0x00100000) +/** + * @} + */ + +/** @defgroup GPIO_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the GPIOx peripheral registers to their default reset values. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @retval None + */ +void GPIO_DeInit(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + if (GPIOx == GPIOA) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, DISABLE); + } + else if (GPIOx == GPIOB) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, DISABLE); + } + else if (GPIOx == GPIOC) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, DISABLE); + } + else if (GPIOx == GPIOD) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, DISABLE); + } + else if (GPIOx == GPIOE) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, DISABLE); + } + else if (GPIOx == GPIOF) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, DISABLE); + } + else + { + if (GPIOx == GPIOG) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, DISABLE); + } + } +} + +/** + * @brief Deinitializes the Alternate Functions (remap, event control + * and EXTI configuration) registers to their default reset values. + * @param None + * @retval None + */ +void GPIO_AFIODeInit(void) +{ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, DISABLE); +} + +/** + * @brief Initializes the GPIOx peripheral according to the specified + * parameters in the GPIO_InitStruct. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that + * contains the configuration information for the specified GPIO peripheral. + * @retval None + */ +void GPIO_Init(GPIO_TypeDef* GPIOx, const GPIO_InitTypeDef* GPIO_InitStruct) +{ + uint32_t currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00; + uint32_t tmpreg = 0x00, pinmask = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode)); + assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin)); + +/*---------------------------- GPIO Mode Configuration -----------------------*/ + currentmode = ((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x0F); + if ((((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x10)) != 0x00) + { + /* Check the parameters */ + assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed)); + /* Output mode */ + currentmode |= (uint32_t)GPIO_InitStruct->GPIO_Speed; + } +/*---------------------------- GPIO CRL Configuration ------------------------*/ + /* Configure the eight low port pins */ + if (((uint32_t)GPIO_InitStruct->GPIO_Pin & ((uint32_t)0x00FF)) != 0x00) + { + tmpreg = GPIOx->CRL; + for (pinpos = 0x00; pinpos < 0x08; pinpos++) + { + pos = ((uint32_t)0x01) << pinpos; + /* Get the port pins position */ + currentpin = (GPIO_InitStruct->GPIO_Pin) & pos; + if (currentpin == pos) + { + pos = pinpos << 2; + /* Clear the corresponding low control register bits */ + pinmask = ((uint32_t)0x0F) << pos; + tmpreg &= ~pinmask; + /* Write the mode configuration in the corresponding bits */ + tmpreg |= (currentmode << pos); + /* Reset the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD) + { + GPIOx->BRR = (((uint32_t)0x01) << pinpos); + } + else + { + /* Set the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU) + { + GPIOx->BSRR = (((uint32_t)0x01) << pinpos); + } + } + } + } + GPIOx->CRL = tmpreg; + } +/*---------------------------- GPIO CRH Configuration ------------------------*/ + /* Configure the eight high port pins */ + if (GPIO_InitStruct->GPIO_Pin > 0x00FF) + { + tmpreg = GPIOx->CRH; + for (pinpos = 0x00; pinpos < 0x08; pinpos++) + { + pos = (((uint32_t)0x01) << (pinpos + 0x08)); + /* Get the port pins position */ + currentpin = ((GPIO_InitStruct->GPIO_Pin) & pos); + if (currentpin == pos) + { + pos = pinpos << 2; + /* Clear the corresponding high control register bits */ + pinmask = ((uint32_t)0x0F) << pos; + tmpreg &= ~pinmask; + /* Write the mode configuration in the corresponding bits */ + tmpreg |= (currentmode << pos); + /* Reset the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD) + { + GPIOx->BRR = (((uint32_t)0x01) << (pinpos + 0x08)); + } + /* Set the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU) + { + GPIOx->BSRR = (((uint32_t)0x01) << (pinpos + 0x08)); + } + } + } + GPIOx->CRH = tmpreg; + } +} + +/** + * @brief Fills each GPIO_InitStruct member with its default value. + * @param GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct) +{ + /* Reset GPIO init structure parameters values */ + GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All; + GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN_FLOATING; +} + +/** + * @brief Reads the specified input port pin. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to read. + * This parameter can be GPIO_Pin_x where x can be (0..15). + * @retval The input port pin value. + */ +uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint8_t bitstatus = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + + if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET) + { + bitstatus = (uint8_t)Bit_SET; + } + else + { + bitstatus = (uint8_t)Bit_RESET; + } + return bitstatus; +} + +/** + * @brief Reads the specified GPIO input data port. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @retval GPIO input data port value. + */ +uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + return ((uint16_t)GPIOx->IDR); +} + +/** + * @brief Reads the specified output data port bit. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to read. + * This parameter can be GPIO_Pin_x where x can be (0..15). + * @retval The output port pin value. + */ +uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint8_t bitstatus = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + + if ((GPIOx->ODR & GPIO_Pin) != (uint32_t)Bit_RESET) + { + bitstatus = (uint8_t)Bit_SET; + } + else + { + bitstatus = (uint8_t)Bit_RESET; + } + return bitstatus; +} + +/** + * @brief Reads the specified GPIO output data port. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @retval GPIO output data port value. + */ +uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + return ((uint16_t)GPIOx->ODR); +} + +/** + * @brief Sets the selected data port bits. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bits to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + GPIOx->BSRR = GPIO_Pin; +} + +/** + * @brief Clears the selected data port bits. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bits to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + GPIOx->BRR = GPIO_Pin; +} + +/** + * @brief Sets or clears the selected data port bit. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to be written. + * This parameter can be one of GPIO_Pin_x where x can be (0..15). + * @param BitVal: specifies the value to be written to the selected bit. + * This parameter can be one of the BitAction enum values: + * @arg Bit_RESET: to clear the port pin + * @arg Bit_SET: to set the port pin + * @retval None + */ +void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + assert_param(IS_GPIO_BIT_ACTION(BitVal)); + + if (BitVal != Bit_RESET) + { + GPIOx->BSRR = GPIO_Pin; + } + else + { + GPIOx->BRR = GPIO_Pin; + } +} + +/** + * @brief Writes data to the specified GPIO data port. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param PortVal: specifies the value to be written to the port output data register. + * @retval None + */ +void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + GPIOx->ODR = PortVal; +} + +/** + * @brief Locks GPIO Pins configuration registers. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint32_t tmp = 0x00010000; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + tmp |= GPIO_Pin; + /* Set LCKK bit */ + GPIOx->LCKR = tmp; + /* Reset LCKK bit */ + GPIOx->LCKR = GPIO_Pin; + /* Set LCKK bit */ + GPIOx->LCKR = tmp; + /* Read LCKK bit*/ + tmp = GPIOx->LCKR; + /* Read LCKK bit*/ + tmp = GPIOx->LCKR; +} + +/** + * @brief Selects the GPIO pin used as Event output. + * @param GPIO_PortSource: selects the GPIO port to be used as source + * for Event output. + * This parameter can be GPIO_PortSourceGPIOx where x can be (A..E). + * @param GPIO_PinSource: specifies the pin for the Event output. + * This parameter can be GPIO_PinSourcex where x can be (0..15). + * @retval None + */ +void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource) +{ + uint32_t tmpreg = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_EVENTOUT_PORT_SOURCE(GPIO_PortSource)); + assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); + + tmpreg = AFIO->EVCR; + /* Clear the PORT[6:4] and PIN[3:0] bits */ + tmpreg &= EVCR_PORTPINCONFIG_MASK; + tmpreg |= (uint32_t)GPIO_PortSource << 0x04; + tmpreg |= GPIO_PinSource; + AFIO->EVCR = tmpreg; +} + +/** + * @brief Enables or disables the Event Output. + * @param NewState: new state of the Event output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void GPIO_EventOutputCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) EVCR_EVOE_BB = (uint32_t)NewState; +} + +/** + * @brief Changes the mapping of the specified pin. + * @param GPIO_Remap: selects the pin to remap. + * This parameter can be one of the following values: + * @arg GPIO_Remap_SPI1 : SPI1 Alternate Function mapping + * @arg GPIO_Remap_I2C1 : I2C1 Alternate Function mapping + * @arg GPIO_Remap_USART1 : USART1 Alternate Function mapping + * @arg GPIO_Remap_USART2 : USART2 Alternate Function mapping + * @arg GPIO_PartialRemap_USART3 : USART3 Partial Alternate Function mapping + * @arg GPIO_FullRemap_USART3 : USART3 Full Alternate Function mapping + * @arg GPIO_PartialRemap_TIM1 : TIM1 Partial Alternate Function mapping + * @arg GPIO_FullRemap_TIM1 : TIM1 Full Alternate Function mapping + * @arg GPIO_PartialRemap1_TIM2 : TIM2 Partial1 Alternate Function mapping + * @arg GPIO_PartialRemap2_TIM2 : TIM2 Partial2 Alternate Function mapping + * @arg GPIO_FullRemap_TIM2 : TIM2 Full Alternate Function mapping + * @arg GPIO_PartialRemap_TIM3 : TIM3 Partial Alternate Function mapping + * @arg GPIO_FullRemap_TIM3 : TIM3 Full Alternate Function mapping + * @arg GPIO_Remap_TIM4 : TIM4 Alternate Function mapping + * @arg GPIO_Remap1_CAN1 : CAN1 Alternate Function mapping + * @arg GPIO_Remap2_CAN1 : CAN1 Alternate Function mapping + * @arg GPIO_Remap_PD01 : PD01 Alternate Function mapping + * @arg GPIO_Remap_TIM5CH4_LSI : LSI connected to TIM5 Channel4 input capture for calibration + * @arg GPIO_Remap_ADC1_ETRGINJ : ADC1 External Trigger Injected Conversion remapping + * @arg GPIO_Remap_ADC1_ETRGREG : ADC1 External Trigger Regular Conversion remapping + * @arg GPIO_Remap_ADC2_ETRGINJ : ADC2 External Trigger Injected Conversion remapping + * @arg GPIO_Remap_ADC2_ETRGREG : ADC2 External Trigger Regular Conversion remapping + * @arg GPIO_Remap_ETH : Ethernet remapping (only for Connectivity line devices) + * @arg GPIO_Remap_CAN2 : CAN2 remapping (only for Connectivity line devices) + * @arg GPIO_Remap_SWJ_NoJTRST : Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST + * @arg GPIO_Remap_SWJ_JTAGDisable : JTAG-DP Disabled and SW-DP Enabled + * @arg GPIO_Remap_SWJ_Disable : Full SWJ Disabled (JTAG-DP + SW-DP) + * @arg GPIO_Remap_SPI3 : SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices) + * @arg GPIO_Remap_TIM2ITR1_PTP_SOF : Ethernet PTP output or USB OTG SOF (Start of Frame) connected + * to TIM2 Internal Trigger 1 for calibration (only for Connectivity line devices) + * If the GPIO_Remap_TIM2ITR1_PTP_SOF is enabled the TIM2 ITR1 is connected to + * Ethernet PTP output. When Reset TIM2 ITR1 is connected to USB OTG SOF output. + * @arg GPIO_Remap_PTP_PPS : Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) + * @arg GPIO_Remap_TIM15 : TIM15 Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_TIM16 : TIM16 Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_TIM17 : TIM17 Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_CEC : CEC Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_TIM1_DMA : TIM1 DMA requests mapping (only for Value line devices) + * @arg GPIO_Remap_TIM9 : TIM9 Alternate Function mapping (only for XL-density devices) + * @arg GPIO_Remap_TIM10 : TIM10 Alternate Function mapping (only for XL-density devices) + * @arg GPIO_Remap_TIM11 : TIM11 Alternate Function mapping (only for XL-density devices) + * @arg GPIO_Remap_TIM13 : TIM13 Alternate Function mapping (only for High density Value line and XL-density devices) + * @arg GPIO_Remap_TIM14 : TIM14 Alternate Function mapping (only for High density Value line and XL-density devices) + * @arg GPIO_Remap_FSMC_NADV : FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices) + * @arg GPIO_Remap_TIM67_DAC_DMA : TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices) + * @arg GPIO_Remap_TIM12 : TIM12 Alternate Function mapping (only for High density Value line devices) + * @arg GPIO_Remap_MISC : Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping, + * only for High density Value line devices) + * @param NewState: new state of the port pin remapping. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState) +{ + uint32_t tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_REMAP(GPIO_Remap)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if((GPIO_Remap & 0x80000000) == 0x80000000) + { + tmpreg = AFIO->MAPR2; + } + else + { + tmpreg = AFIO->MAPR; + } + + tmpmask = (GPIO_Remap & DBGAFR_POSITION_MASK) >> 0x10; + tmp = GPIO_Remap & LSB_MASK; + + if ((GPIO_Remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) + { + tmpreg &= DBGAFR_SWJCFG_MASK; + AFIO->MAPR &= DBGAFR_SWJCFG_MASK; + } + else if ((GPIO_Remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK) + { + tmp1 = ((uint32_t)0x03) << tmpmask; + tmpreg &= ~tmp1; + tmpreg |= ~DBGAFR_SWJCFG_MASK; + } + else + { + tmpreg &= ~(tmp << ((GPIO_Remap >> 0x15)*0x10)); + tmpreg |= ~DBGAFR_SWJCFG_MASK; + } + + if (NewState != DISABLE) + { + tmpreg |= (tmp << ((GPIO_Remap >> 0x15)*0x10)); + } + + if((GPIO_Remap & 0x80000000) == 0x80000000) + { + AFIO->MAPR2 = tmpreg; + } + else + { + AFIO->MAPR = tmpreg; + } +} + +/** + * @brief Selects the GPIO pin used as EXTI Line. + * @param GPIO_PortSource: selects the GPIO port to be used as source for EXTI lines. + * This parameter can be GPIO_PortSourceGPIOx where x can be (A..G). + * @param GPIO_PinSource: specifies the EXTI line to be configured. + * This parameter can be GPIO_PinSourcex where x can be (0..15). + * @retval None + */ +void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource) +{ + uint32_t tmp = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_EXTI_PORT_SOURCE(GPIO_PortSource)); + assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); + + tmp = ((uint32_t)0x0F) << (0x04 * (GPIO_PinSource & (uint8_t)0x03)); + AFIO->EXTICR[GPIO_PinSource >> 0x02] &= ~tmp; + AFIO->EXTICR[GPIO_PinSource >> 0x02] |= (((uint32_t)GPIO_PortSource) << (0x04 * (GPIO_PinSource & (uint8_t)0x03))); +} + +/** + * @brief Selects the Ethernet media interface. + * @note This function applies only to STM32 Connectivity line devices. + * @param GPIO_ETH_MediaInterface: specifies the Media Interface mode. + * This parameter can be one of the following values: + * @arg GPIO_ETH_MediaInterface_MII: MII mode + * @arg GPIO_ETH_MediaInterface_RMII: RMII mode + * @retval None + */ +void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface) +{ + assert_param(IS_GPIO_ETH_MEDIA_INTERFACE(GPIO_ETH_MediaInterface)); + + /* Configure MII_RMII selection bit */ + *(__IO uint32_t *) MAPR_MII_RMII_SEL_BB = GPIO_ETH_MediaInterface; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c index ef35d7265..5379a1829 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c @@ -1,1285 +1,1285 @@ -/** - ****************************************************************************** - * @file stm32f10x_i2c.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the I2C firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_i2c.h" -#include "stm32f10x_rcc.h" - - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup I2C - * @brief I2C driver modules - * @{ - */ - -/** @defgroup I2C_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup I2C_Private_Defines - * @{ - */ - -/* I2C SPE mask */ -#define CR1_PE_Set ((uint16_t)0x0001) -#define CR1_PE_Reset ((uint16_t)0xFFFE) - -/* I2C START mask */ -#define CR1_START_Set ((uint16_t)0x0100) -#define CR1_START_Reset ((uint16_t)0xFEFF) - -/* I2C STOP mask */ -#define CR1_STOP_Set ((uint16_t)0x0200) -#define CR1_STOP_Reset ((uint16_t)0xFDFF) - -/* I2C ACK mask */ -#define CR1_ACK_Set ((uint16_t)0x0400) -#define CR1_ACK_Reset ((uint16_t)0xFBFF) - -/* I2C ENGC mask */ -#define CR1_ENGC_Set ((uint16_t)0x0040) -#define CR1_ENGC_Reset ((uint16_t)0xFFBF) - -/* I2C SWRST mask */ -#define CR1_SWRST_Set ((uint16_t)0x8000) -#define CR1_SWRST_Reset ((uint16_t)0x7FFF) - -/* I2C PEC mask */ -#define CR1_PEC_Set ((uint16_t)0x1000) -#define CR1_PEC_Reset ((uint16_t)0xEFFF) - -/* I2C ENPEC mask */ -#define CR1_ENPEC_Set ((uint16_t)0x0020) -#define CR1_ENPEC_Reset ((uint16_t)0xFFDF) - -/* I2C ENARP mask */ -#define CR1_ENARP_Set ((uint16_t)0x0010) -#define CR1_ENARP_Reset ((uint16_t)0xFFEF) - -/* I2C NOSTRETCH mask */ -#define CR1_NOSTRETCH_Set ((uint16_t)0x0080) -#define CR1_NOSTRETCH_Reset ((uint16_t)0xFF7F) - -/* I2C registers Masks */ -#define CR1_CLEAR_Mask ((uint16_t)0xFBF5) - -/* I2C DMAEN mask */ -#define CR2_DMAEN_Set ((uint16_t)0x0800) -#define CR2_DMAEN_Reset ((uint16_t)0xF7FF) - -/* I2C LAST mask */ -#define CR2_LAST_Set ((uint16_t)0x1000) -#define CR2_LAST_Reset ((uint16_t)0xEFFF) - -/* I2C FREQ mask */ -#define CR2_FREQ_Reset ((uint16_t)0xFFC0) - -/* I2C ADD0 mask */ -#define OAR1_ADD0_Set ((uint16_t)0x0001) -#define OAR1_ADD0_Reset ((uint16_t)0xFFFE) - -/* I2C ENDUAL mask */ -#define OAR2_ENDUAL_Set ((uint16_t)0x0001) -#define OAR2_ENDUAL_Reset ((uint16_t)0xFFFE) - -/* I2C ADD2 mask */ -#define OAR2_ADD2_Reset ((uint16_t)0xFF01) - -/* I2C F/S mask */ -#define CCR_FS_Set ((uint16_t)0x8000) - -/* I2C CCR mask */ -#define CCR_CCR_Set ((uint16_t)0x0FFF) - -/* I2C FLAG mask */ -#define FLAG_Mask ((uint32_t)0x00FFFFFF) - -/* I2C Interrupt Enable mask */ -#define ITEN_Mask ((uint32_t)0x07000000) - -/** - * @} - */ - -/** @defgroup I2C_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup I2C_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup I2C_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup I2C_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the I2Cx peripheral registers to their default reset values. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @retval None - */ -void I2C_DeInit(I2C_TypeDef* I2Cx) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - - if (I2Cx == I2C1) - { - /* Enable I2C1 reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, ENABLE); - /* Release I2C1 from reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE); - } - else - { - /* Enable I2C2 reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, ENABLE); - /* Release I2C2 from reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, DISABLE); - } -} - -/** - * @brief Initializes the I2Cx peripheral according to the specified - * parameters in the I2C_InitStruct. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param I2C_InitStruct: pointer to a I2C_InitTypeDef structure that - * contains the configuration information for the specified I2C peripheral. - * @retval None - */ -void I2C_Init(I2C_TypeDef* I2Cx, const I2C_InitTypeDef* I2C_InitStruct) -{ - uint16_t tmpreg = 0, freqrange = 0; - uint16_t result = 0x04; - uint32_t pclk1 = 8000000; - RCC_ClocksTypeDef rcc_clocks; - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_CLOCK_SPEED(I2C_InitStruct->I2C_ClockSpeed)); - assert_param(IS_I2C_MODE(I2C_InitStruct->I2C_Mode)); - assert_param(IS_I2C_DUTY_CYCLE(I2C_InitStruct->I2C_DutyCycle)); - assert_param(IS_I2C_OWN_ADDRESS1(I2C_InitStruct->I2C_OwnAddress1)); - assert_param(IS_I2C_ACK_STATE(I2C_InitStruct->I2C_Ack)); - assert_param(IS_I2C_ACKNOWLEDGE_ADDRESS(I2C_InitStruct->I2C_AcknowledgedAddress)); - -/*---------------------------- I2Cx CR2 Configuration ------------------------*/ - /* Get the I2Cx CR2 value */ - tmpreg = I2Cx->CR2; - /* Clear frequency FREQ[5:0] bits */ - tmpreg &= CR2_FREQ_Reset; - /* Get pclk1 frequency value */ - RCC_GetClocksFreq(&rcc_clocks); - pclk1 = rcc_clocks.PCLK1_Frequency; - /* Set frequency bits depending on pclk1 value */ - freqrange = (uint16_t)(pclk1 / 1000000); - tmpreg |= freqrange; - /* Write to I2Cx CR2 */ - I2Cx->CR2 = tmpreg; - -/*---------------------------- I2Cx CCR Configuration ------------------------*/ - /* Disable the selected I2C peripheral to configure TRISE */ - I2Cx->CR1 &= CR1_PE_Reset; - /* Reset tmpreg value */ - /* Clear F/S, DUTY and CCR[11:0] bits */ - tmpreg = 0; - - /* Configure speed in standard mode */ - if (I2C_InitStruct->I2C_ClockSpeed <= 100000) - { - /* Standard mode speed calculate */ - result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed << 1)); - /* Test if CCR value is under 0x4*/ - if (result < 0x04) - { - /* Set minimum allowed value */ - result = 0x04; - } - /* Set speed value for standard mode */ - tmpreg |= result; - /* Set Maximum Rise Time for standard mode */ - I2Cx->TRISE = freqrange + 1; - } - /* Configure speed in fast mode */ - else /*(I2C_InitStruct->I2C_ClockSpeed <= 400000)*/ - { - if (I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_2) - { - /* Fast mode speed calculate: Tlow/Thigh = 2 */ - result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 3)); - } - else /*I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_16_9*/ - { - /* Fast mode speed calculate: Tlow/Thigh = 16/9 */ - result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 25)); - /* Set DUTY bit */ - result |= I2C_DutyCycle_16_9; - } - - /* Test if CCR value is under 0x1*/ - if ((result & CCR_CCR_Set) == 0) - { - /* Set minimum allowed value */ - result |= (uint16_t)0x0001; - } - /* Set speed value and set F/S bit for fast mode */ - tmpreg |= (uint16_t)(result | CCR_FS_Set); - /* Set Maximum Rise Time for fast mode */ - I2Cx->TRISE = (uint16_t)(((freqrange * (uint16_t)300) / (uint16_t)1000) + (uint16_t)1); - } - - /* Write to I2Cx CCR */ - I2Cx->CCR = tmpreg; - /* Enable the selected I2C peripheral */ - I2Cx->CR1 |= CR1_PE_Set; - -/*---------------------------- I2Cx CR1 Configuration ------------------------*/ - /* Get the I2Cx CR1 value */ - tmpreg = I2Cx->CR1; - /* Clear ACK, SMBTYPE and SMBUS bits */ - tmpreg &= CR1_CLEAR_Mask; - /* Configure I2Cx: mode and acknowledgement */ - /* Set SMBTYPE and SMBUS bits according to I2C_Mode value */ - /* Set ACK bit according to I2C_Ack value */ - tmpreg |= (uint16_t)((uint32_t)I2C_InitStruct->I2C_Mode | I2C_InitStruct->I2C_Ack); - /* Write to I2Cx CR1 */ - I2Cx->CR1 = tmpreg; - -/*---------------------------- I2Cx OAR1 Configuration -----------------------*/ - /* Set I2Cx Own Address1 and acknowledged address */ - I2Cx->OAR1 = (I2C_InitStruct->I2C_AcknowledgedAddress | I2C_InitStruct->I2C_OwnAddress1); -} - -/** - * @brief Fills each I2C_InitStruct member with its default value. - * @param I2C_InitStruct: pointer to an I2C_InitTypeDef structure which will be initialized. - * @retval None - */ -void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct) -{ -/*---------------- Reset I2C init structure parameters values ----------------*/ - /* initialize the I2C_ClockSpeed member */ - I2C_InitStruct->I2C_ClockSpeed = 5000; - /* Initialize the I2C_Mode member */ - I2C_InitStruct->I2C_Mode = I2C_Mode_I2C; - /* Initialize the I2C_DutyCycle member */ - I2C_InitStruct->I2C_DutyCycle = I2C_DutyCycle_2; - /* Initialize the I2C_OwnAddress1 member */ - I2C_InitStruct->I2C_OwnAddress1 = 0; - /* Initialize the I2C_Ack member */ - I2C_InitStruct->I2C_Ack = I2C_Ack_Disable; - /* Initialize the I2C_AcknowledgedAddress member */ - I2C_InitStruct->I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; -} - -/** - * @brief Enables or disables the specified I2C peripheral. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2Cx peripheral. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected I2C peripheral */ - I2Cx->CR1 |= CR1_PE_Set; - } - else - { - /* Disable the selected I2C peripheral */ - I2Cx->CR1 &= CR1_PE_Reset; - } -} - -/** - * @brief Enables or disables the specified I2C DMA requests. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2C DMA transfer. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected I2C DMA requests */ - I2Cx->CR2 |= CR2_DMAEN_Set; - } - else - { - /* Disable the selected I2C DMA requests */ - I2Cx->CR2 &= CR2_DMAEN_Reset; - } -} - -/** - * @brief Specifies if the next DMA transfer will be the last one. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2C DMA last transfer. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Next DMA transfer is the last transfer */ - I2Cx->CR2 |= CR2_LAST_Set; - } - else - { - /* Next DMA transfer is not the last transfer */ - I2Cx->CR2 &= CR2_LAST_Reset; - } -} - -/** - * @brief Generates I2Cx communication START condition. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2C START condition generation. - * This parameter can be: ENABLE or DISABLE. - * @retval None. - */ -void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Generate a START condition */ - I2Cx->CR1 |= CR1_START_Set; - } - else - { - /* Disable the START condition generation */ - I2Cx->CR1 &= CR1_START_Reset; - } -} - -/** - * @brief Generates I2Cx communication STOP condition. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2C STOP condition generation. - * This parameter can be: ENABLE or DISABLE. - * @retval None. - */ -void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Generate a STOP condition */ - I2Cx->CR1 |= CR1_STOP_Set; - } - else - { - /* Disable the STOP condition generation */ - I2Cx->CR1 &= CR1_STOP_Reset; - } -} - -/** - * @brief Enables or disables the specified I2C acknowledge feature. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2C Acknowledgement. - * This parameter can be: ENABLE or DISABLE. - * @retval None. - */ -void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the acknowledgement */ - I2Cx->CR1 |= CR1_ACK_Set; - } - else - { - /* Disable the acknowledgement */ - I2Cx->CR1 &= CR1_ACK_Reset; - } -} - -/** - * @brief Configures the specified I2C own address2. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param Address: specifies the 7bit I2C own address2. - * @retval None. - */ -void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address) -{ - uint16_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - - /* Get the old register value */ - tmpreg = I2Cx->OAR2; - - /* Reset I2Cx Own address2 bit [7:1] */ - tmpreg &= OAR2_ADD2_Reset; - - /* Set I2Cx Own address2 */ - tmpreg |= (uint16_t)((uint16_t)Address & (uint16_t)0x00FE); - - /* Store the new register value */ - I2Cx->OAR2 = tmpreg; -} - -/** - * @brief Enables or disables the specified I2C dual addressing mode. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2C dual addressing mode. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable dual addressing mode */ - I2Cx->OAR2 |= OAR2_ENDUAL_Set; - } - else - { - /* Disable dual addressing mode */ - I2Cx->OAR2 &= OAR2_ENDUAL_Reset; - } -} - -/** - * @brief Enables or disables the specified I2C general call feature. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2C General call. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable generall call */ - I2Cx->CR1 |= CR1_ENGC_Set; - } - else - { - /* Disable generall call */ - I2Cx->CR1 &= CR1_ENGC_Reset; - } -} - -/** - * @brief Enables or disables the specified I2C interrupts. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param I2C_IT: specifies the I2C interrupts sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg I2C_IT_BUF: Buffer interrupt mask - * @arg I2C_IT_EVT: Event interrupt mask - * @arg I2C_IT_ERR: Error interrupt mask - * @param NewState: new state of the specified I2C interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - assert_param(IS_I2C_CONFIG_IT(I2C_IT)); - - if (NewState != DISABLE) - { - /* Enable the selected I2C interrupts */ - I2Cx->CR2 |= I2C_IT; - } - else - { - /* Disable the selected I2C interrupts */ - I2Cx->CR2 &= (uint16_t)~I2C_IT; - } -} - -/** - * @brief Sends a data byte through the I2Cx peripheral. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param Data: Byte to be transmitted.. - * @retval None - */ -void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - /* Write in the DR register the data to be sent */ - I2Cx->DR = Data; -} - -/** - * @brief Returns the most recent received data by the I2Cx peripheral. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @retval The value of the received data. - */ -uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - /* Return the data in the DR register */ - return (uint8_t)I2Cx->DR; -} - -/** - * @brief Transmits the address byte to select the slave device. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param Address: specifies the slave address which will be transmitted - * @param I2C_Direction: specifies whether the I2C device will be a - * Transmitter or a Receiver. This parameter can be one of the following values - * @arg I2C_Direction_Transmitter: Transmitter mode - * @arg I2C_Direction_Receiver: Receiver mode - * @retval None. - */ -void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_DIRECTION(I2C_Direction)); - /* Test on the direction to set/reset the read/write bit */ - if (I2C_Direction != I2C_Direction_Transmitter) - { - /* Set the address bit0 for read */ - Address |= OAR1_ADD0_Set; - } - else - { - /* Reset the address bit0 for write */ - Address &= OAR1_ADD0_Reset; - } - /* Send the address */ - I2Cx->DR = Address; -} - -/** - * @brief Reads the specified I2C register and returns its value. - * @param I2C_Register: specifies the register to read. - * This parameter can be one of the following values: - * @arg I2C_Register_CR1: CR1 register. - * @arg I2C_Register_CR2: CR2 register. - * @arg I2C_Register_OAR1: OAR1 register. - * @arg I2C_Register_OAR2: OAR2 register. - * @arg I2C_Register_DR: DR register. - * @arg I2C_Register_SR1: SR1 register. - * @arg I2C_Register_SR2: SR2 register. - * @arg I2C_Register_CCR: CCR register. - * @arg I2C_Register_TRISE: TRISE register. - * @retval The value of the read register. - */ -uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register) -{ - __IO uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_REGISTER(I2C_Register)); - - tmp = (uint32_t) I2Cx; - tmp += I2C_Register; - - /* Return the selected register value */ - return (*(__IO uint16_t *) tmp); -} - -/** - * @brief Enables or disables the specified I2C software reset. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2C software reset. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Peripheral under reset */ - I2Cx->CR1 |= CR1_SWRST_Set; - } - else - { - /* Peripheral not under reset */ - I2Cx->CR1 &= CR1_SWRST_Reset; - } -} - -/** - * @brief Drives the SMBusAlert pin high or low for the specified I2C. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param I2C_SMBusAlert: specifies SMBAlert pin level. - * This parameter can be one of the following values: - * @arg I2C_SMBusAlert_Low: SMBAlert pin driven low - * @arg I2C_SMBusAlert_High: SMBAlert pin driven high - * @retval None - */ -void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_SMBUS_ALERT(I2C_SMBusAlert)); - if (I2C_SMBusAlert == I2C_SMBusAlert_Low) - { - /* Drive the SMBusAlert pin Low */ - I2Cx->CR1 |= I2C_SMBusAlert_Low; - } - else - { - /* Drive the SMBusAlert pin High */ - I2Cx->CR1 &= I2C_SMBusAlert_High; - } -} - -/** - * @brief Enables or disables the specified I2C PEC transfer. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2C PEC transmission. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected I2C PEC transmission */ - I2Cx->CR1 |= CR1_PEC_Set; - } - else - { - /* Disable the selected I2C PEC transmission */ - I2Cx->CR1 &= CR1_PEC_Reset; - } -} - -/** - * @brief Selects the specified I2C PEC position. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param I2C_PECPosition: specifies the PEC position. - * This parameter can be one of the following values: - * @arg I2C_PECPosition_Next: indicates that the next byte is PEC - * @arg I2C_PECPosition_Current: indicates that current byte is PEC - * @retval None - */ -void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_PEC_POSITION(I2C_PECPosition)); - if (I2C_PECPosition == I2C_PECPosition_Next) - { - /* Next byte in shift register is PEC */ - I2Cx->CR1 |= I2C_PECPosition_Next; - } - else - { - /* Current byte in shift register is PEC */ - I2Cx->CR1 &= I2C_PECPosition_Current; - } -} - -/** - * @brief Enables or disables the PEC value calculation of the transfered bytes. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2Cx PEC value calculation. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected I2C PEC calculation */ - I2Cx->CR1 |= CR1_ENPEC_Set; - } - else - { - /* Disable the selected I2C PEC calculation */ - I2Cx->CR1 &= CR1_ENPEC_Reset; - } -} - -/** - * @brief Returns the PEC value for the specified I2C. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @retval The PEC value. - */ -uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - /* Return the selected I2C PEC value */ - return ((I2Cx->SR2) >> 8); -} - -/** - * @brief Enables or disables the specified I2C ARP. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2Cx ARP. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected I2C ARP */ - I2Cx->CR1 |= CR1_ENARP_Set; - } - else - { - /* Disable the selected I2C ARP */ - I2Cx->CR1 &= CR1_ENARP_Reset; - } -} - -/** - * @brief Enables or disables the specified I2C Clock stretching. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param NewState: new state of the I2Cx Clock stretching. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState == DISABLE) - { - /* Enable the selected I2C Clock stretching */ - I2Cx->CR1 |= CR1_NOSTRETCH_Set; - } - else - { - /* Disable the selected I2C Clock stretching */ - I2Cx->CR1 &= CR1_NOSTRETCH_Reset; - } -} - -/** - * @brief Selects the specified I2C fast mode duty cycle. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param I2C_DutyCycle: specifies the fast mode duty cycle. - * This parameter can be one of the following values: - * @arg I2C_DutyCycle_2: I2C fast mode Tlow/Thigh = 2 - * @arg I2C_DutyCycle_16_9: I2C fast mode Tlow/Thigh = 16/9 - * @retval None - */ -void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle) -{ - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_DUTY_CYCLE(I2C_DutyCycle)); - if (I2C_DutyCycle != I2C_DutyCycle_16_9) - { - /* I2C fast mode Tlow/Thigh=2 */ - I2Cx->CCR &= I2C_DutyCycle_2; - } - else - { - /* I2C fast mode Tlow/Thigh=16/9 */ - I2Cx->CCR |= I2C_DutyCycle_16_9; - } -} - - - -/** - * @brief - **************************************************************************************** - * - * I2C State Monitoring Functions - * - **************************************************************************************** - * This I2C driver provides three different ways for I2C state monitoring - * depending on the application requirements and constraints: - * - * - * 1) Basic state monitoring: - * Using I2C_CheckEvent() function: - * It compares the status registers (SR1 and SR2) content to a given event - * (can be the combination of one or more flags). - * It returns SUCCESS if the current status includes the given flags - * and returns ERROR if one or more flags are missing in the current status. - * - When to use: - * - This function is suitable for most applciations as well as for startup - * activity since the events are fully described in the product reference manual - * (RM0008). - * - It is also suitable for users who need to define their own events. - * - Limitations: - * - If an error occurs (ie. error flags are set besides to the monitored flags), - * the I2C_CheckEvent() function may return SUCCESS despite the communication - * hold or corrupted real state. - * In this case, it is advised to use error interrupts to monitor the error - * events and handle them in the interrupt IRQ handler. - * - * @note - * For error management, it is advised to use the following functions: - * - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR). - * - I2Cx_ER_IRQHandler() which is called when the error interurpt occurs. - * Where x is the peripheral instance (I2C1, I2C2 ...) - * - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into I2Cx_ER_IRQHandler() - * in order to determine which error occured. - * - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() - * and/or I2C_GenerateStop() in order to clear the error flag and source, - * and return to correct communication status. - * - * - * 2) Advanced state monitoring: - * Using the function I2C_GetLastEvent() which returns the image of both status - * registers in a single word (uint32_t) (Status Register 2 value is shifted left - * by 16 bits and concatenated to Status Register 1). - * - When to use: - * - This function is suitable for the same applications above but it allows to - * overcome the mentionned limitation of I2C_GetFlagStatus() function. - * The returned value could be compared to events already defined in the - * library (stm32f10x_i2c.h) or to custom values defiend by user. - * - This function is suitable when multiple flags are monitored at the same time. - * - At the opposite of I2C_CheckEvent() function, this function allows user to - * choose when an event is accepted (when all events flags are set and no - * other flags are set or just when the needed flags are set like - * I2C_CheckEvent() function). - * - Limitations: - * - User may need to define his own events. - * - Same remark concerning the error management is applicable for this - * function if user decides to check only regular communication flags (and - * ignores error flags). - * - * - * 3) Flag-based state monitoring: - * Using the function I2C_GetFlagStatus() which simply returns the status of - * one single flag (ie. I2C_FLAG_RXNE ...). - * - When to use: - * - This function could be used for specific applications or in debug phase. - * - It is suitable when only one flag checking is needed (most I2C events - * are monitored through multiple flags). - * - Limitations: - * - When calling this function, the Status register is accessed. Some flags are - * cleared when the status register is accessed. So checking the status - * of one Flag, may clear other ones. - * - Function may need to be called twice or more in order to monitor one - * single event. - * - * For detailed description of Events, please refer to section I2C_Events in - * stm32f10x_i2c.h file. - * - */ - -/** - * - * 1) Basic state monitoring - ******************************************************************************* - */ - -/** - * @brief Checks whether the last I2Cx Event is equal to the one passed - * as parameter. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param I2C_EVENT: specifies the event to be checked. - * This parameter can be one of the following values: - * @arg I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED : EV1 - * @arg I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED : EV1 - * @arg I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED : EV1 - * @arg I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED : EV1 - * @arg I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED : EV1 - * @arg I2C_EVENT_SLAVE_BYTE_RECEIVED : EV2 - * @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF) : EV2 - * @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL) : EV2 - * @arg I2C_EVENT_SLAVE_BYTE_TRANSMITTED : EV3 - * @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF) : EV3 - * @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL) : EV3 - * @arg I2C_EVENT_SLAVE_ACK_FAILURE : EV3_2 - * @arg I2C_EVENT_SLAVE_STOP_DETECTED : EV4 - * @arg I2C_EVENT_MASTER_MODE_SELECT : EV5 - * @arg I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED : EV6 - * @arg I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED : EV6 - * @arg I2C_EVENT_MASTER_BYTE_RECEIVED : EV7 - * @arg I2C_EVENT_MASTER_BYTE_TRANSMITTING : EV8 - * @arg I2C_EVENT_MASTER_BYTE_TRANSMITTED : EV8_2 - * @arg I2C_EVENT_MASTER_MODE_ADDRESS10 : EV9 - * - * @note: For detailed description of Events, please refer to section - * I2C_Events in stm32f10x_i2c.h file. - * - * @retval An ErrorStatus enumuration value: - * - SUCCESS: Last event is equal to the I2C_EVENT - * - ERROR: Last event is different from the I2C_EVENT - */ -ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT) -{ - uint32_t lastevent = 0; - uint32_t flag1 = 0, flag2 = 0; - ErrorStatus status = ERROR; - - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_EVENT(I2C_EVENT)); - - /* Read the I2Cx status register */ - flag1 = I2Cx->SR1; - flag2 = I2Cx->SR2; - flag2 = flag2 << 16; - - /* Get the last event value from I2C status register */ - lastevent = (flag1 | flag2) & FLAG_Mask; - - /* Check whether the last event contains the I2C_EVENT */ - if ((lastevent & I2C_EVENT) == I2C_EVENT) - { - /* SUCCESS: last event is equal to I2C_EVENT */ - status = SUCCESS; - } - else - { - /* ERROR: last event is different from I2C_EVENT */ - status = ERROR; - } - /* Return status */ - return status; -} - -/** - * - * 2) Advanced state monitoring - ******************************************************************************* - */ - -/** - * @brief Returns the last I2Cx Event. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * - * @note: For detailed description of Events, please refer to section - * I2C_Events in stm32f10x_i2c.h file. - * - * @retval The last event - */ -uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx) -{ - uint32_t lastevent = 0; - uint32_t flag1 = 0, flag2 = 0; - - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - - /* Read the I2Cx status register */ - flag1 = I2Cx->SR1; - flag2 = I2Cx->SR2; - flag2 = flag2 << 16; - - /* Get the last event value from I2C status register */ - lastevent = (flag1 | flag2) & FLAG_Mask; - - /* Return status */ - return lastevent; -} - -/** - * - * 3) Flag-based state monitoring - ******************************************************************************* - */ - -/** - * @brief Checks whether the specified I2C flag is set or not. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param I2C_FLAG: specifies the flag to check. - * This parameter can be one of the following values: - * @arg I2C_FLAG_DUALF: Dual flag (Slave mode) - * @arg I2C_FLAG_SMBHOST: SMBus host header (Slave mode) - * @arg I2C_FLAG_SMBDEFAULT: SMBus default header (Slave mode) - * @arg I2C_FLAG_GENCALL: General call header flag (Slave mode) - * @arg I2C_FLAG_TRA: Transmitter/Receiver flag - * @arg I2C_FLAG_BUSY: Bus busy flag - * @arg I2C_FLAG_MSL: Master/Slave flag - * @arg I2C_FLAG_SMBALERT: SMBus Alert flag - * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag - * @arg I2C_FLAG_PECERR: PEC error in reception flag - * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) - * @arg I2C_FLAG_AF: Acknowledge failure flag - * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) - * @arg I2C_FLAG_BERR: Bus error flag - * @arg I2C_FLAG_TXE: Data register empty flag (Transmitter) - * @arg I2C_FLAG_RXNE: Data register not empty (Receiver) flag - * @arg I2C_FLAG_STOPF: Stop detection flag (Slave mode) - * @arg I2C_FLAG_ADD10: 10-bit header sent flag (Master mode) - * @arg I2C_FLAG_BTF: Byte transfer finished flag - * @arg I2C_FLAG_ADDR: Address sent flag (Master mode) “ADSL” - * Address matched flag (Slave mode)”ENDAD” - * @arg I2C_FLAG_SB: Start bit flag (Master mode) - * @retval The new state of I2C_FLAG (SET or RESET). - */ -FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) -{ - FlagStatus bitstatus = RESET; - __IO uint32_t i2creg = 0, i2cxbase = 0; - - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_GET_FLAG(I2C_FLAG)); - - /* Get the I2Cx peripheral base address */ - i2cxbase = (uint32_t)I2Cx; - - /* Read flag register index */ - i2creg = I2C_FLAG >> 28; - - /* Get bit[23:0] of the flag */ - I2C_FLAG &= FLAG_Mask; - - if(i2creg != 0) - { - /* Get the I2Cx SR1 register address */ - i2cxbase += 0x14; - } - else - { - /* Flag in I2Cx SR2 Register */ - I2C_FLAG = (uint32_t)(I2C_FLAG >> 16); - /* Get the I2Cx SR2 register address */ - i2cxbase += 0x18; - } - - if(((*(__IO uint32_t *)i2cxbase) & I2C_FLAG) != (uint32_t)RESET) - { - /* I2C_FLAG is set */ - bitstatus = SET; - } - else - { - /* I2C_FLAG is reset */ - bitstatus = RESET; - } - - /* Return the I2C_FLAG status */ - return bitstatus; -} - - - -/** - * @brief Clears the I2Cx's pending flags. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param I2C_FLAG: specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg I2C_FLAG_SMBALERT: SMBus Alert flag - * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag - * @arg I2C_FLAG_PECERR: PEC error in reception flag - * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) - * @arg I2C_FLAG_AF: Acknowledge failure flag - * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) - * @arg I2C_FLAG_BERR: Bus error flag - * - * @note - * - STOPF (STOP detection) is cleared by software sequence: a read operation - * to I2C_SR1 register (I2C_GetFlagStatus()) followed by a write operation - * to I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral). - * - ADD10 (10-bit header sent) is cleared by software sequence: a read - * operation to I2C_SR1 (I2C_GetFlagStatus()) followed by writing the - * second byte of the address in DR register. - * - BTF (Byte Transfer Finished) is cleared by software sequence: a read - * operation to I2C_SR1 register (I2C_GetFlagStatus()) followed by a - * read/write to I2C_DR register (I2C_SendData()). - * - ADDR (Address sent) is cleared by software sequence: a read operation to - * I2C_SR1 register (I2C_GetFlagStatus()) followed by a read operation to - * I2C_SR2 register ((void)(I2Cx->SR2)). - * - SB (Start Bit) is cleared software sequence: a read operation to I2C_SR1 - * register (I2C_GetFlagStatus()) followed by a write operation to I2C_DR - * register (I2C_SendData()). - * @retval None - */ -void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) -{ - uint32_t flagpos = 0; - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG)); - /* Get the I2C flag position */ - flagpos = I2C_FLAG & FLAG_Mask; - /* Clear the selected I2C flag */ - I2Cx->SR1 = (uint16_t)~flagpos; -} - -/** - * @brief Checks whether the specified I2C interrupt has occurred or not. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param I2C_IT: specifies the interrupt source to check. - * This parameter can be one of the following values: - * @arg I2C_IT_SMBALERT: SMBus Alert flag - * @arg I2C_IT_TIMEOUT: Timeout or Tlow error flag - * @arg I2C_IT_PECERR: PEC error in reception flag - * @arg I2C_IT_OVR: Overrun/Underrun flag (Slave mode) - * @arg I2C_IT_AF: Acknowledge failure flag - * @arg I2C_IT_ARLO: Arbitration lost flag (Master mode) - * @arg I2C_IT_BERR: Bus error flag - * @arg I2C_IT_TXE: Data register empty flag (Transmitter) - * @arg I2C_IT_RXNE: Data register not empty (Receiver) flag - * @arg I2C_IT_STOPF: Stop detection flag (Slave mode) - * @arg I2C_IT_ADD10: 10-bit header sent flag (Master mode) - * @arg I2C_IT_BTF: Byte transfer finished flag - * @arg I2C_IT_ADDR: Address sent flag (Master mode) “ADSL” - * Address matched flag (Slave mode)”ENDAD” - * @arg I2C_IT_SB: Start bit flag (Master mode) - * @retval The new state of I2C_IT (SET or RESET). - */ -ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT) -{ - ITStatus bitstatus = RESET; - uint32_t enablestatus = 0; - - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_GET_IT(I2C_IT)); - - /* Check if the interrupt source is enabled or not */ - enablestatus = (uint32_t)(((I2C_IT & ITEN_Mask) >> 16) & (I2Cx->CR2)) ; - - /* Get bit[23:0] of the flag */ - I2C_IT &= FLAG_Mask; - - /* Check the status of the specified I2C flag */ - if (((I2Cx->SR1 & I2C_IT) != (uint32_t)RESET) && enablestatus) - { - /* I2C_IT is set */ - bitstatus = SET; - } - else - { - /* I2C_IT is reset */ - bitstatus = RESET; - } - /* Return the I2C_IT status */ - return bitstatus; -} - -/** - * @brief Clears the I2Cx’s interrupt pending bits. - * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. - * @param I2C_IT: specifies the interrupt pending bit to clear. - * This parameter can be any combination of the following values: - * @arg I2C_IT_SMBALERT: SMBus Alert interrupt - * @arg I2C_IT_TIMEOUT: Timeout or Tlow error interrupt - * @arg I2C_IT_PECERR: PEC error in reception interrupt - * @arg I2C_IT_OVR: Overrun/Underrun interrupt (Slave mode) - * @arg I2C_IT_AF: Acknowledge failure interrupt - * @arg I2C_IT_ARLO: Arbitration lost interrupt (Master mode) - * @arg I2C_IT_BERR: Bus error interrupt - * - * @note - * - STOPF (STOP detection) is cleared by software sequence: a read operation - * to I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to - * I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral). - * - ADD10 (10-bit header sent) is cleared by software sequence: a read - * operation to I2C_SR1 (I2C_GetITStatus()) followed by writing the second - * byte of the address in I2C_DR register. - * - BTF (Byte Transfer Finished) is cleared by software sequence: a read - * operation to I2C_SR1 register (I2C_GetITStatus()) followed by a - * read/write to I2C_DR register (I2C_SendData()). - * - ADDR (Address sent) is cleared by software sequence: a read operation to - * I2C_SR1 register (I2C_GetITStatus()) followed by a read operation to - * I2C_SR2 register ((void)(I2Cx->SR2)). - * - SB (Start Bit) is cleared by software sequence: a read operation to - * I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to - * I2C_DR register (I2C_SendData()). - * @retval None - */ -void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT) -{ - uint32_t flagpos = 0; - /* Check the parameters */ - assert_param(IS_I2C_ALL_PERIPH(I2Cx)); - assert_param(IS_I2C_CLEAR_IT(I2C_IT)); - /* Get the I2C flag position */ - flagpos = I2C_IT & FLAG_Mask; - /* Clear the selected I2C flag */ - I2Cx->SR1 = (uint16_t)~flagpos; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_i2c.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the I2C firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_i2c.h" +#include "stm32f10x_rcc.h" + + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup I2C + * @brief I2C driver modules + * @{ + */ + +/** @defgroup I2C_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_Defines + * @{ + */ + +/* I2C SPE mask */ +#define CR1_PE_Set ((uint16_t)0x0001) +#define CR1_PE_Reset ((uint16_t)0xFFFE) + +/* I2C START mask */ +#define CR1_START_Set ((uint16_t)0x0100) +#define CR1_START_Reset ((uint16_t)0xFEFF) + +/* I2C STOP mask */ +#define CR1_STOP_Set ((uint16_t)0x0200) +#define CR1_STOP_Reset ((uint16_t)0xFDFF) + +/* I2C ACK mask */ +#define CR1_ACK_Set ((uint16_t)0x0400) +#define CR1_ACK_Reset ((uint16_t)0xFBFF) + +/* I2C ENGC mask */ +#define CR1_ENGC_Set ((uint16_t)0x0040) +#define CR1_ENGC_Reset ((uint16_t)0xFFBF) + +/* I2C SWRST mask */ +#define CR1_SWRST_Set ((uint16_t)0x8000) +#define CR1_SWRST_Reset ((uint16_t)0x7FFF) + +/* I2C PEC mask */ +#define CR1_PEC_Set ((uint16_t)0x1000) +#define CR1_PEC_Reset ((uint16_t)0xEFFF) + +/* I2C ENPEC mask */ +#define CR1_ENPEC_Set ((uint16_t)0x0020) +#define CR1_ENPEC_Reset ((uint16_t)0xFFDF) + +/* I2C ENARP mask */ +#define CR1_ENARP_Set ((uint16_t)0x0010) +#define CR1_ENARP_Reset ((uint16_t)0xFFEF) + +/* I2C NOSTRETCH mask */ +#define CR1_NOSTRETCH_Set ((uint16_t)0x0080) +#define CR1_NOSTRETCH_Reset ((uint16_t)0xFF7F) + +/* I2C registers Masks */ +#define CR1_CLEAR_Mask ((uint16_t)0xFBF5) + +/* I2C DMAEN mask */ +#define CR2_DMAEN_Set ((uint16_t)0x0800) +#define CR2_DMAEN_Reset ((uint16_t)0xF7FF) + +/* I2C LAST mask */ +#define CR2_LAST_Set ((uint16_t)0x1000) +#define CR2_LAST_Reset ((uint16_t)0xEFFF) + +/* I2C FREQ mask */ +#define CR2_FREQ_Reset ((uint16_t)0xFFC0) + +/* I2C ADD0 mask */ +#define OAR1_ADD0_Set ((uint16_t)0x0001) +#define OAR1_ADD0_Reset ((uint16_t)0xFFFE) + +/* I2C ENDUAL mask */ +#define OAR2_ENDUAL_Set ((uint16_t)0x0001) +#define OAR2_ENDUAL_Reset ((uint16_t)0xFFFE) + +/* I2C ADD2 mask */ +#define OAR2_ADD2_Reset ((uint16_t)0xFF01) + +/* I2C F/S mask */ +#define CCR_FS_Set ((uint16_t)0x8000) + +/* I2C CCR mask */ +#define CCR_CCR_Set ((uint16_t)0x0FFF) + +/* I2C FLAG mask */ +#define FLAG_Mask ((uint32_t)0x00FFFFFF) + +/* I2C Interrupt Enable mask */ +#define ITEN_Mask ((uint32_t)0x07000000) + +/** + * @} + */ + +/** @defgroup I2C_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the I2Cx peripheral registers to their default reset values. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval None + */ +void I2C_DeInit(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + if (I2Cx == I2C1) + { + /* Enable I2C1 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, ENABLE); + /* Release I2C1 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE); + } + else + { + /* Enable I2C2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, ENABLE); + /* Release I2C2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, DISABLE); + } +} + +/** + * @brief Initializes the I2Cx peripheral according to the specified + * parameters in the I2C_InitStruct. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_InitStruct: pointer to a I2C_InitTypeDef structure that + * contains the configuration information for the specified I2C peripheral. + * @retval None + */ +void I2C_Init(I2C_TypeDef* I2Cx, const I2C_InitTypeDef* I2C_InitStruct) +{ + uint16_t tmpreg = 0, freqrange = 0; + uint16_t result = 0x04; + uint32_t pclk1 = 8000000; + RCC_ClocksTypeDef rcc_clocks; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLOCK_SPEED(I2C_InitStruct->I2C_ClockSpeed)); + assert_param(IS_I2C_MODE(I2C_InitStruct->I2C_Mode)); + assert_param(IS_I2C_DUTY_CYCLE(I2C_InitStruct->I2C_DutyCycle)); + assert_param(IS_I2C_OWN_ADDRESS1(I2C_InitStruct->I2C_OwnAddress1)); + assert_param(IS_I2C_ACK_STATE(I2C_InitStruct->I2C_Ack)); + assert_param(IS_I2C_ACKNOWLEDGE_ADDRESS(I2C_InitStruct->I2C_AcknowledgedAddress)); + +/*---------------------------- I2Cx CR2 Configuration ------------------------*/ + /* Get the I2Cx CR2 value */ + tmpreg = I2Cx->CR2; + /* Clear frequency FREQ[5:0] bits */ + tmpreg &= CR2_FREQ_Reset; + /* Get pclk1 frequency value */ + RCC_GetClocksFreq(&rcc_clocks); + pclk1 = rcc_clocks.PCLK1_Frequency; + /* Set frequency bits depending on pclk1 value */ + freqrange = (uint16_t)(pclk1 / 1000000); + tmpreg |= freqrange; + /* Write to I2Cx CR2 */ + I2Cx->CR2 = tmpreg; + +/*---------------------------- I2Cx CCR Configuration ------------------------*/ + /* Disable the selected I2C peripheral to configure TRISE */ + I2Cx->CR1 &= CR1_PE_Reset; + /* Reset tmpreg value */ + /* Clear F/S, DUTY and CCR[11:0] bits */ + tmpreg = 0; + + /* Configure speed in standard mode */ + if (I2C_InitStruct->I2C_ClockSpeed <= 100000) + { + /* Standard mode speed calculate */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed << 1)); + /* Test if CCR value is under 0x4*/ + if (result < 0x04) + { + /* Set minimum allowed value */ + result = 0x04; + } + /* Set speed value for standard mode */ + tmpreg |= result; + /* Set Maximum Rise Time for standard mode */ + I2Cx->TRISE = freqrange + 1; + } + /* Configure speed in fast mode */ + else /*(I2C_InitStruct->I2C_ClockSpeed <= 400000)*/ + { + if (I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_2) + { + /* Fast mode speed calculate: Tlow/Thigh = 2 */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 3)); + } + else /*I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_16_9*/ + { + /* Fast mode speed calculate: Tlow/Thigh = 16/9 */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 25)); + /* Set DUTY bit */ + result |= I2C_DutyCycle_16_9; + } + + /* Test if CCR value is under 0x1*/ + if ((result & CCR_CCR_Set) == 0) + { + /* Set minimum allowed value */ + result |= (uint16_t)0x0001; + } + /* Set speed value and set F/S bit for fast mode */ + tmpreg |= (uint16_t)(result | CCR_FS_Set); + /* Set Maximum Rise Time for fast mode */ + I2Cx->TRISE = (uint16_t)(((freqrange * (uint16_t)300) / (uint16_t)1000) + (uint16_t)1); + } + + /* Write to I2Cx CCR */ + I2Cx->CCR = tmpreg; + /* Enable the selected I2C peripheral */ + I2Cx->CR1 |= CR1_PE_Set; + +/*---------------------------- I2Cx CR1 Configuration ------------------------*/ + /* Get the I2Cx CR1 value */ + tmpreg = I2Cx->CR1; + /* Clear ACK, SMBTYPE and SMBUS bits */ + tmpreg &= CR1_CLEAR_Mask; + /* Configure I2Cx: mode and acknowledgement */ + /* Set SMBTYPE and SMBUS bits according to I2C_Mode value */ + /* Set ACK bit according to I2C_Ack value */ + tmpreg |= (uint16_t)((uint32_t)I2C_InitStruct->I2C_Mode | I2C_InitStruct->I2C_Ack); + /* Write to I2Cx CR1 */ + I2Cx->CR1 = tmpreg; + +/*---------------------------- I2Cx OAR1 Configuration -----------------------*/ + /* Set I2Cx Own Address1 and acknowledged address */ + I2Cx->OAR1 = (I2C_InitStruct->I2C_AcknowledgedAddress | I2C_InitStruct->I2C_OwnAddress1); +} + +/** + * @brief Fills each I2C_InitStruct member with its default value. + * @param I2C_InitStruct: pointer to an I2C_InitTypeDef structure which will be initialized. + * @retval None + */ +void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct) +{ +/*---------------- Reset I2C init structure parameters values ----------------*/ + /* initialize the I2C_ClockSpeed member */ + I2C_InitStruct->I2C_ClockSpeed = 5000; + /* Initialize the I2C_Mode member */ + I2C_InitStruct->I2C_Mode = I2C_Mode_I2C; + /* Initialize the I2C_DutyCycle member */ + I2C_InitStruct->I2C_DutyCycle = I2C_DutyCycle_2; + /* Initialize the I2C_OwnAddress1 member */ + I2C_InitStruct->I2C_OwnAddress1 = 0; + /* Initialize the I2C_Ack member */ + I2C_InitStruct->I2C_Ack = I2C_Ack_Disable; + /* Initialize the I2C_AcknowledgedAddress member */ + I2C_InitStruct->I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; +} + +/** + * @brief Enables or disables the specified I2C peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C peripheral */ + I2Cx->CR1 |= CR1_PE_Set; + } + else + { + /* Disable the selected I2C peripheral */ + I2Cx->CR1 &= CR1_PE_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C DMA requests. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C DMA transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C DMA requests */ + I2Cx->CR2 |= CR2_DMAEN_Set; + } + else + { + /* Disable the selected I2C DMA requests */ + I2Cx->CR2 &= CR2_DMAEN_Reset; + } +} + +/** + * @brief Specifies if the next DMA transfer will be the last one. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C DMA last transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Next DMA transfer is the last transfer */ + I2Cx->CR2 |= CR2_LAST_Set; + } + else + { + /* Next DMA transfer is not the last transfer */ + I2Cx->CR2 &= CR2_LAST_Reset; + } +} + +/** + * @brief Generates I2Cx communication START condition. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C START condition generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Generate a START condition */ + I2Cx->CR1 |= CR1_START_Set; + } + else + { + /* Disable the START condition generation */ + I2Cx->CR1 &= CR1_START_Reset; + } +} + +/** + * @brief Generates I2Cx communication STOP condition. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C STOP condition generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Generate a STOP condition */ + I2Cx->CR1 |= CR1_STOP_Set; + } + else + { + /* Disable the STOP condition generation */ + I2Cx->CR1 &= CR1_STOP_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C acknowledge feature. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C Acknowledgement. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the acknowledgement */ + I2Cx->CR1 |= CR1_ACK_Set; + } + else + { + /* Disable the acknowledgement */ + I2Cx->CR1 &= CR1_ACK_Reset; + } +} + +/** + * @brief Configures the specified I2C own address2. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Address: specifies the 7bit I2C own address2. + * @retval None. + */ +void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Get the old register value */ + tmpreg = I2Cx->OAR2; + + /* Reset I2Cx Own address2 bit [7:1] */ + tmpreg &= OAR2_ADD2_Reset; + + /* Set I2Cx Own address2 */ + tmpreg |= (uint16_t)((uint16_t)Address & (uint16_t)0x00FE); + + /* Store the new register value */ + I2Cx->OAR2 = tmpreg; +} + +/** + * @brief Enables or disables the specified I2C dual addressing mode. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C dual addressing mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable dual addressing mode */ + I2Cx->OAR2 |= OAR2_ENDUAL_Set; + } + else + { + /* Disable dual addressing mode */ + I2Cx->OAR2 &= OAR2_ENDUAL_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C general call feature. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C General call. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable generall call */ + I2Cx->CR1 |= CR1_ENGC_Set; + } + else + { + /* Disable generall call */ + I2Cx->CR1 &= CR1_ENGC_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C interrupts. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the I2C interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg I2C_IT_BUF: Buffer interrupt mask + * @arg I2C_IT_EVT: Event interrupt mask + * @arg I2C_IT_ERR: Error interrupt mask + * @param NewState: new state of the specified I2C interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_I2C_CONFIG_IT(I2C_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected I2C interrupts */ + I2Cx->CR2 |= I2C_IT; + } + else + { + /* Disable the selected I2C interrupts */ + I2Cx->CR2 &= (uint16_t)~I2C_IT; + } +} + +/** + * @brief Sends a data byte through the I2Cx peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Data: Byte to be transmitted.. + * @retval None + */ +void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Write in the DR register the data to be sent */ + I2Cx->DR = Data; +} + +/** + * @brief Returns the most recent received data by the I2Cx peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval The value of the received data. + */ +uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Return the data in the DR register */ + return (uint8_t)I2Cx->DR; +} + +/** + * @brief Transmits the address byte to select the slave device. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Address: specifies the slave address which will be transmitted + * @param I2C_Direction: specifies whether the I2C device will be a + * Transmitter or a Receiver. This parameter can be one of the following values + * @arg I2C_Direction_Transmitter: Transmitter mode + * @arg I2C_Direction_Receiver: Receiver mode + * @retval None. + */ +void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_DIRECTION(I2C_Direction)); + /* Test on the direction to set/reset the read/write bit */ + if (I2C_Direction != I2C_Direction_Transmitter) + { + /* Set the address bit0 for read */ + Address |= OAR1_ADD0_Set; + } + else + { + /* Reset the address bit0 for write */ + Address &= OAR1_ADD0_Reset; + } + /* Send the address */ + I2Cx->DR = Address; +} + +/** + * @brief Reads the specified I2C register and returns its value. + * @param I2C_Register: specifies the register to read. + * This parameter can be one of the following values: + * @arg I2C_Register_CR1: CR1 register. + * @arg I2C_Register_CR2: CR2 register. + * @arg I2C_Register_OAR1: OAR1 register. + * @arg I2C_Register_OAR2: OAR2 register. + * @arg I2C_Register_DR: DR register. + * @arg I2C_Register_SR1: SR1 register. + * @arg I2C_Register_SR2: SR2 register. + * @arg I2C_Register_CCR: CCR register. + * @arg I2C_Register_TRISE: TRISE register. + * @retval The value of the read register. + */ +uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_REGISTER(I2C_Register)); + + tmp = (uint32_t) I2Cx; + tmp += I2C_Register; + + /* Return the selected register value */ + return (*(__IO uint16_t *) tmp); +} + +/** + * @brief Enables or disables the specified I2C software reset. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C software reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Peripheral under reset */ + I2Cx->CR1 |= CR1_SWRST_Set; + } + else + { + /* Peripheral not under reset */ + I2Cx->CR1 &= CR1_SWRST_Reset; + } +} + +/** + * @brief Drives the SMBusAlert pin high or low for the specified I2C. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_SMBusAlert: specifies SMBAlert pin level. + * This parameter can be one of the following values: + * @arg I2C_SMBusAlert_Low: SMBAlert pin driven low + * @arg I2C_SMBusAlert_High: SMBAlert pin driven high + * @retval None + */ +void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_SMBUS_ALERT(I2C_SMBusAlert)); + if (I2C_SMBusAlert == I2C_SMBusAlert_Low) + { + /* Drive the SMBusAlert pin Low */ + I2Cx->CR1 |= I2C_SMBusAlert_Low; + } + else + { + /* Drive the SMBusAlert pin High */ + I2Cx->CR1 &= I2C_SMBusAlert_High; + } +} + +/** + * @brief Enables or disables the specified I2C PEC transfer. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C PEC transmission. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C PEC transmission */ + I2Cx->CR1 |= CR1_PEC_Set; + } + else + { + /* Disable the selected I2C PEC transmission */ + I2Cx->CR1 &= CR1_PEC_Reset; + } +} + +/** + * @brief Selects the specified I2C PEC position. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_PECPosition: specifies the PEC position. + * This parameter can be one of the following values: + * @arg I2C_PECPosition_Next: indicates that the next byte is PEC + * @arg I2C_PECPosition_Current: indicates that current byte is PEC + * @retval None + */ +void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_PEC_POSITION(I2C_PECPosition)); + if (I2C_PECPosition == I2C_PECPosition_Next) + { + /* Next byte in shift register is PEC */ + I2Cx->CR1 |= I2C_PECPosition_Next; + } + else + { + /* Current byte in shift register is PEC */ + I2Cx->CR1 &= I2C_PECPosition_Current; + } +} + +/** + * @brief Enables or disables the PEC value calculation of the transfered bytes. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx PEC value calculation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C PEC calculation */ + I2Cx->CR1 |= CR1_ENPEC_Set; + } + else + { + /* Disable the selected I2C PEC calculation */ + I2Cx->CR1 &= CR1_ENPEC_Reset; + } +} + +/** + * @brief Returns the PEC value for the specified I2C. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval The PEC value. + */ +uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Return the selected I2C PEC value */ + return ((I2Cx->SR2) >> 8); +} + +/** + * @brief Enables or disables the specified I2C ARP. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx ARP. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C ARP */ + I2Cx->CR1 |= CR1_ENARP_Set; + } + else + { + /* Disable the selected I2C ARP */ + I2Cx->CR1 &= CR1_ENARP_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C Clock stretching. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx Clock stretching. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState == DISABLE) + { + /* Enable the selected I2C Clock stretching */ + I2Cx->CR1 |= CR1_NOSTRETCH_Set; + } + else + { + /* Disable the selected I2C Clock stretching */ + I2Cx->CR1 &= CR1_NOSTRETCH_Reset; + } +} + +/** + * @brief Selects the specified I2C fast mode duty cycle. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_DutyCycle: specifies the fast mode duty cycle. + * This parameter can be one of the following values: + * @arg I2C_DutyCycle_2: I2C fast mode Tlow/Thigh = 2 + * @arg I2C_DutyCycle_16_9: I2C fast mode Tlow/Thigh = 16/9 + * @retval None + */ +void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_DUTY_CYCLE(I2C_DutyCycle)); + if (I2C_DutyCycle != I2C_DutyCycle_16_9) + { + /* I2C fast mode Tlow/Thigh=2 */ + I2Cx->CCR &= I2C_DutyCycle_2; + } + else + { + /* I2C fast mode Tlow/Thigh=16/9 */ + I2Cx->CCR |= I2C_DutyCycle_16_9; + } +} + + + +/** + * @brief + **************************************************************************************** + * + * I2C State Monitoring Functions + * + **************************************************************************************** + * This I2C driver provides three different ways for I2C state monitoring + * depending on the application requirements and constraints: + * + * + * 1) Basic state monitoring: + * Using I2C_CheckEvent() function: + * It compares the status registers (SR1 and SR2) content to a given event + * (can be the combination of one or more flags). + * It returns SUCCESS if the current status includes the given flags + * and returns ERROR if one or more flags are missing in the current status. + * - When to use: + * - This function is suitable for most applciations as well as for startup + * activity since the events are fully described in the product reference manual + * (RM0008). + * - It is also suitable for users who need to define their own events. + * - Limitations: + * - If an error occurs (ie. error flags are set besides to the monitored flags), + * the I2C_CheckEvent() function may return SUCCESS despite the communication + * hold or corrupted real state. + * In this case, it is advised to use error interrupts to monitor the error + * events and handle them in the interrupt IRQ handler. + * + * @note + * For error management, it is advised to use the following functions: + * - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR). + * - I2Cx_ER_IRQHandler() which is called when the error interurpt occurs. + * Where x is the peripheral instance (I2C1, I2C2 ...) + * - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into I2Cx_ER_IRQHandler() + * in order to determine which error occured. + * - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() + * and/or I2C_GenerateStop() in order to clear the error flag and source, + * and return to correct communication status. + * + * + * 2) Advanced state monitoring: + * Using the function I2C_GetLastEvent() which returns the image of both status + * registers in a single word (uint32_t) (Status Register 2 value is shifted left + * by 16 bits and concatenated to Status Register 1). + * - When to use: + * - This function is suitable for the same applications above but it allows to + * overcome the mentionned limitation of I2C_GetFlagStatus() function. + * The returned value could be compared to events already defined in the + * library (stm32f10x_i2c.h) or to custom values defiend by user. + * - This function is suitable when multiple flags are monitored at the same time. + * - At the opposite of I2C_CheckEvent() function, this function allows user to + * choose when an event is accepted (when all events flags are set and no + * other flags are set or just when the needed flags are set like + * I2C_CheckEvent() function). + * - Limitations: + * - User may need to define his own events. + * - Same remark concerning the error management is applicable for this + * function if user decides to check only regular communication flags (and + * ignores error flags). + * + * + * 3) Flag-based state monitoring: + * Using the function I2C_GetFlagStatus() which simply returns the status of + * one single flag (ie. I2C_FLAG_RXNE ...). + * - When to use: + * - This function could be used for specific applications or in debug phase. + * - It is suitable when only one flag checking is needed (most I2C events + * are monitored through multiple flags). + * - Limitations: + * - When calling this function, the Status register is accessed. Some flags are + * cleared when the status register is accessed. So checking the status + * of one Flag, may clear other ones. + * - Function may need to be called twice or more in order to monitor one + * single event. + * + * For detailed description of Events, please refer to section I2C_Events in + * stm32f10x_i2c.h file. + * + */ + +/** + * + * 1) Basic state monitoring + ******************************************************************************* + */ + +/** + * @brief Checks whether the last I2Cx Event is equal to the one passed + * as parameter. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_EVENT: specifies the event to be checked. + * This parameter can be one of the following values: + * @arg I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_BYTE_RECEIVED : EV2 + * @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF) : EV2 + * @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL) : EV2 + * @arg I2C_EVENT_SLAVE_BYTE_TRANSMITTED : EV3 + * @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF) : EV3 + * @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL) : EV3 + * @arg I2C_EVENT_SLAVE_ACK_FAILURE : EV3_2 + * @arg I2C_EVENT_SLAVE_STOP_DETECTED : EV4 + * @arg I2C_EVENT_MASTER_MODE_SELECT : EV5 + * @arg I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED : EV6 + * @arg I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED : EV6 + * @arg I2C_EVENT_MASTER_BYTE_RECEIVED : EV7 + * @arg I2C_EVENT_MASTER_BYTE_TRANSMITTING : EV8 + * @arg I2C_EVENT_MASTER_BYTE_TRANSMITTED : EV8_2 + * @arg I2C_EVENT_MASTER_MODE_ADDRESS10 : EV9 + * + * @note: For detailed description of Events, please refer to section + * I2C_Events in stm32f10x_i2c.h file. + * + * @retval An ErrorStatus enumuration value: + * - SUCCESS: Last event is equal to the I2C_EVENT + * - ERROR: Last event is different from the I2C_EVENT + */ +ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT) +{ + uint32_t lastevent = 0; + uint32_t flag1 = 0, flag2 = 0; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_EVENT(I2C_EVENT)); + + /* Read the I2Cx status register */ + flag1 = I2Cx->SR1; + flag2 = I2Cx->SR2; + flag2 = flag2 << 16; + + /* Get the last event value from I2C status register */ + lastevent = (flag1 | flag2) & FLAG_Mask; + + /* Check whether the last event contains the I2C_EVENT */ + if ((lastevent & I2C_EVENT) == I2C_EVENT) + { + /* SUCCESS: last event is equal to I2C_EVENT */ + status = SUCCESS; + } + else + { + /* ERROR: last event is different from I2C_EVENT */ + status = ERROR; + } + /* Return status */ + return status; +} + +/** + * + * 2) Advanced state monitoring + ******************************************************************************* + */ + +/** + * @brief Returns the last I2Cx Event. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * + * @note: For detailed description of Events, please refer to section + * I2C_Events in stm32f10x_i2c.h file. + * + * @retval The last event + */ +uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx) +{ + uint32_t lastevent = 0; + uint32_t flag1 = 0, flag2 = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Read the I2Cx status register */ + flag1 = I2Cx->SR1; + flag2 = I2Cx->SR2; + flag2 = flag2 << 16; + + /* Get the last event value from I2C status register */ + lastevent = (flag1 | flag2) & FLAG_Mask; + + /* Return status */ + return lastevent; +} + +/** + * + * 3) Flag-based state monitoring + ******************************************************************************* + */ + +/** + * @brief Checks whether the specified I2C flag is set or not. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg I2C_FLAG_DUALF: Dual flag (Slave mode) + * @arg I2C_FLAG_SMBHOST: SMBus host header (Slave mode) + * @arg I2C_FLAG_SMBDEFAULT: SMBus default header (Slave mode) + * @arg I2C_FLAG_GENCALL: General call header flag (Slave mode) + * @arg I2C_FLAG_TRA: Transmitter/Receiver flag + * @arg I2C_FLAG_BUSY: Bus busy flag + * @arg I2C_FLAG_MSL: Master/Slave flag + * @arg I2C_FLAG_SMBALERT: SMBus Alert flag + * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_FLAG_PECERR: PEC error in reception flag + * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_FLAG_AF: Acknowledge failure flag + * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_FLAG_BERR: Bus error flag + * @arg I2C_FLAG_TXE: Data register empty flag (Transmitter) + * @arg I2C_FLAG_RXNE: Data register not empty (Receiver) flag + * @arg I2C_FLAG_STOPF: Stop detection flag (Slave mode) + * @arg I2C_FLAG_ADD10: 10-bit header sent flag (Master mode) + * @arg I2C_FLAG_BTF: Byte transfer finished flag + * @arg I2C_FLAG_ADDR: Address sent flag (Master mode) “ADSL” + * Address matched flag (Slave mode)”ENDAD” + * @arg I2C_FLAG_SB: Start bit flag (Master mode) + * @retval The new state of I2C_FLAG (SET or RESET). + */ +FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) +{ + FlagStatus bitstatus = RESET; + __IO uint32_t i2creg = 0, i2cxbase = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_GET_FLAG(I2C_FLAG)); + + /* Get the I2Cx peripheral base address */ + i2cxbase = (uint32_t)I2Cx; + + /* Read flag register index */ + i2creg = I2C_FLAG >> 28; + + /* Get bit[23:0] of the flag */ + I2C_FLAG &= FLAG_Mask; + + if(i2creg != 0) + { + /* Get the I2Cx SR1 register address */ + i2cxbase += 0x14; + } + else + { + /* Flag in I2Cx SR2 Register */ + I2C_FLAG = (uint32_t)(I2C_FLAG >> 16); + /* Get the I2Cx SR2 register address */ + i2cxbase += 0x18; + } + + if(((*(__IO uint32_t *)i2cxbase) & I2C_FLAG) != (uint32_t)RESET) + { + /* I2C_FLAG is set */ + bitstatus = SET; + } + else + { + /* I2C_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the I2C_FLAG status */ + return bitstatus; +} + + + +/** + * @brief Clears the I2Cx's pending flags. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg I2C_FLAG_SMBALERT: SMBus Alert flag + * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_FLAG_PECERR: PEC error in reception flag + * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_FLAG_AF: Acknowledge failure flag + * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_FLAG_BERR: Bus error flag + * + * @note + * - STOPF (STOP detection) is cleared by software sequence: a read operation + * to I2C_SR1 register (I2C_GetFlagStatus()) followed by a write operation + * to I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral). + * - ADD10 (10-bit header sent) is cleared by software sequence: a read + * operation to I2C_SR1 (I2C_GetFlagStatus()) followed by writing the + * second byte of the address in DR register. + * - BTF (Byte Transfer Finished) is cleared by software sequence: a read + * operation to I2C_SR1 register (I2C_GetFlagStatus()) followed by a + * read/write to I2C_DR register (I2C_SendData()). + * - ADDR (Address sent) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetFlagStatus()) followed by a read operation to + * I2C_SR2 register ((void)(I2Cx->SR2)). + * - SB (Start Bit) is cleared software sequence: a read operation to I2C_SR1 + * register (I2C_GetFlagStatus()) followed by a write operation to I2C_DR + * register (I2C_SendData()). + * @retval None + */ +void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) +{ + uint32_t flagpos = 0; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG)); + /* Get the I2C flag position */ + flagpos = I2C_FLAG & FLAG_Mask; + /* Clear the selected I2C flag */ + I2Cx->SR1 = (uint16_t)~flagpos; +} + +/** + * @brief Checks whether the specified I2C interrupt has occurred or not. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the interrupt source to check. + * This parameter can be one of the following values: + * @arg I2C_IT_SMBALERT: SMBus Alert flag + * @arg I2C_IT_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_IT_PECERR: PEC error in reception flag + * @arg I2C_IT_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_IT_AF: Acknowledge failure flag + * @arg I2C_IT_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_IT_BERR: Bus error flag + * @arg I2C_IT_TXE: Data register empty flag (Transmitter) + * @arg I2C_IT_RXNE: Data register not empty (Receiver) flag + * @arg I2C_IT_STOPF: Stop detection flag (Slave mode) + * @arg I2C_IT_ADD10: 10-bit header sent flag (Master mode) + * @arg I2C_IT_BTF: Byte transfer finished flag + * @arg I2C_IT_ADDR: Address sent flag (Master mode) “ADSL” + * Address matched flag (Slave mode)”ENDAD” + * @arg I2C_IT_SB: Start bit flag (Master mode) + * @retval The new state of I2C_IT (SET or RESET). + */ +ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_GET_IT(I2C_IT)); + + /* Check if the interrupt source is enabled or not */ + enablestatus = (uint32_t)(((I2C_IT & ITEN_Mask) >> 16) & (I2Cx->CR2)) ; + + /* Get bit[23:0] of the flag */ + I2C_IT &= FLAG_Mask; + + /* Check the status of the specified I2C flag */ + if (((I2Cx->SR1 & I2C_IT) != (uint32_t)RESET) && enablestatus) + { + /* I2C_IT is set */ + bitstatus = SET; + } + else + { + /* I2C_IT is reset */ + bitstatus = RESET; + } + /* Return the I2C_IT status */ + return bitstatus; +} + +/** + * @brief Clears the I2Cx’s interrupt pending bits. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg I2C_IT_SMBALERT: SMBus Alert interrupt + * @arg I2C_IT_TIMEOUT: Timeout or Tlow error interrupt + * @arg I2C_IT_PECERR: PEC error in reception interrupt + * @arg I2C_IT_OVR: Overrun/Underrun interrupt (Slave mode) + * @arg I2C_IT_AF: Acknowledge failure interrupt + * @arg I2C_IT_ARLO: Arbitration lost interrupt (Master mode) + * @arg I2C_IT_BERR: Bus error interrupt + * + * @note + * - STOPF (STOP detection) is cleared by software sequence: a read operation + * to I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to + * I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral). + * - ADD10 (10-bit header sent) is cleared by software sequence: a read + * operation to I2C_SR1 (I2C_GetITStatus()) followed by writing the second + * byte of the address in I2C_DR register. + * - BTF (Byte Transfer Finished) is cleared by software sequence: a read + * operation to I2C_SR1 register (I2C_GetITStatus()) followed by a + * read/write to I2C_DR register (I2C_SendData()). + * - ADDR (Address sent) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetITStatus()) followed by a read operation to + * I2C_SR2 register ((void)(I2Cx->SR2)). + * - SB (Start Bit) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to + * I2C_DR register (I2C_SendData()). + * @retval None + */ +void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT) +{ + uint32_t flagpos = 0; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLEAR_IT(I2C_IT)); + /* Get the I2C flag position */ + flagpos = I2C_IT & FLAG_Mask; + /* Clear the selected I2C flag */ + I2Cx->SR1 = (uint16_t)~flagpos; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c index 7738cf3c4..d1014c970 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c @@ -1,189 +1,189 @@ -/** - ****************************************************************************** - * @file stm32f10x_iwdg.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the IWDG firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_iwdg.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup IWDG - * @brief IWDG driver modules - * @{ - */ - -/** @defgroup IWDG_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup IWDG_Private_Defines - * @{ - */ - -/* ---------------------- IWDG registers bit mask ----------------------------*/ - -/* KR register bit mask */ -#define KR_KEY_Reload ((uint16_t)0xAAAA) -#define KR_KEY_Enable ((uint16_t)0xCCCC) - -/** - * @} - */ - -/** @defgroup IWDG_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup IWDG_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup IWDG_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup IWDG_Private_Functions - * @{ - */ - -/** - * @brief Enables or disables write access to IWDG_PR and IWDG_RLR registers. - * @param IWDG_WriteAccess: new state of write access to IWDG_PR and IWDG_RLR registers. - * This parameter can be one of the following values: - * @arg IWDG_WriteAccess_Enable: Enable write access to IWDG_PR and IWDG_RLR registers - * @arg IWDG_WriteAccess_Disable: Disable write access to IWDG_PR and IWDG_RLR registers - * @retval None - */ -void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess) -{ - /* Check the parameters */ - assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess)); - IWDG->KR = IWDG_WriteAccess; -} - -/** - * @brief Sets IWDG Prescaler value. - * @param IWDG_Prescaler: specifies the IWDG Prescaler value. - * This parameter can be one of the following values: - * @arg IWDG_Prescaler_4: IWDG prescaler set to 4 - * @arg IWDG_Prescaler_8: IWDG prescaler set to 8 - * @arg IWDG_Prescaler_16: IWDG prescaler set to 16 - * @arg IWDG_Prescaler_32: IWDG prescaler set to 32 - * @arg IWDG_Prescaler_64: IWDG prescaler set to 64 - * @arg IWDG_Prescaler_128: IWDG prescaler set to 128 - * @arg IWDG_Prescaler_256: IWDG prescaler set to 256 - * @retval None - */ -void IWDG_SetPrescaler(uint8_t IWDG_Prescaler) -{ - /* Check the parameters */ - assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler)); - IWDG->PR = IWDG_Prescaler; -} - -/** - * @brief Sets IWDG Reload value. - * @param Reload: specifies the IWDG Reload value. - * This parameter must be a number between 0 and 0x0FFF. - * @retval None - */ -void IWDG_SetReload(uint16_t Reload) -{ - /* Check the parameters */ - assert_param(IS_IWDG_RELOAD(Reload)); - IWDG->RLR = Reload; -} - -/** - * @brief Reloads IWDG counter with value defined in the reload register - * (write access to IWDG_PR and IWDG_RLR registers disabled). - * @param None - * @retval None - */ -void IWDG_ReloadCounter(void) -{ - IWDG->KR = KR_KEY_Reload; -} - -/** - * @brief Enables IWDG (write access to IWDG_PR and IWDG_RLR registers disabled). - * @param None - * @retval None - */ -void IWDG_Enable(void) -{ - IWDG->KR = KR_KEY_Enable; -} - -/** - * @brief Checks whether the specified IWDG flag is set or not. - * @param IWDG_FLAG: specifies the flag to check. - * This parameter can be one of the following values: - * @arg IWDG_FLAG_PVU: Prescaler Value Update on going - * @arg IWDG_FLAG_RVU: Reload Value Update on going - * @retval The new state of IWDG_FLAG (SET or RESET). - */ -FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_IWDG_FLAG(IWDG_FLAG)); - if ((IWDG->SR & IWDG_FLAG) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - /* Return the flag status */ - return bitstatus; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_iwdg.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the IWDG firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_iwdg.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup IWDG + * @brief IWDG driver modules + * @{ + */ + +/** @defgroup IWDG_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_Defines + * @{ + */ + +/* ---------------------- IWDG registers bit mask ----------------------------*/ + +/* KR register bit mask */ +#define KR_KEY_Reload ((uint16_t)0xAAAA) +#define KR_KEY_Enable ((uint16_t)0xCCCC) + +/** + * @} + */ + +/** @defgroup IWDG_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_Functions + * @{ + */ + +/** + * @brief Enables or disables write access to IWDG_PR and IWDG_RLR registers. + * @param IWDG_WriteAccess: new state of write access to IWDG_PR and IWDG_RLR registers. + * This parameter can be one of the following values: + * @arg IWDG_WriteAccess_Enable: Enable write access to IWDG_PR and IWDG_RLR registers + * @arg IWDG_WriteAccess_Disable: Disable write access to IWDG_PR and IWDG_RLR registers + * @retval None + */ +void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess) +{ + /* Check the parameters */ + assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess)); + IWDG->KR = IWDG_WriteAccess; +} + +/** + * @brief Sets IWDG Prescaler value. + * @param IWDG_Prescaler: specifies the IWDG Prescaler value. + * This parameter can be one of the following values: + * @arg IWDG_Prescaler_4: IWDG prescaler set to 4 + * @arg IWDG_Prescaler_8: IWDG prescaler set to 8 + * @arg IWDG_Prescaler_16: IWDG prescaler set to 16 + * @arg IWDG_Prescaler_32: IWDG prescaler set to 32 + * @arg IWDG_Prescaler_64: IWDG prescaler set to 64 + * @arg IWDG_Prescaler_128: IWDG prescaler set to 128 + * @arg IWDG_Prescaler_256: IWDG prescaler set to 256 + * @retval None + */ +void IWDG_SetPrescaler(uint8_t IWDG_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler)); + IWDG->PR = IWDG_Prescaler; +} + +/** + * @brief Sets IWDG Reload value. + * @param Reload: specifies the IWDG Reload value. + * This parameter must be a number between 0 and 0x0FFF. + * @retval None + */ +void IWDG_SetReload(uint16_t Reload) +{ + /* Check the parameters */ + assert_param(IS_IWDG_RELOAD(Reload)); + IWDG->RLR = Reload; +} + +/** + * @brief Reloads IWDG counter with value defined in the reload register + * (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param None + * @retval None + */ +void IWDG_ReloadCounter(void) +{ + IWDG->KR = KR_KEY_Reload; +} + +/** + * @brief Enables IWDG (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param None + * @retval None + */ +void IWDG_Enable(void) +{ + IWDG->KR = KR_KEY_Enable; +} + +/** + * @brief Checks whether the specified IWDG flag is set or not. + * @param IWDG_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg IWDG_FLAG_PVU: Prescaler Value Update on going + * @arg IWDG_FLAG_RVU: Reload Value Update on going + * @retval The new state of IWDG_FLAG (SET or RESET). + */ +FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_IWDG_FLAG(IWDG_FLAG)); + if ((IWDG->SR & IWDG_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c index 8eeeec200..9d7a4b574 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c @@ -1,306 +1,306 @@ -/** - ****************************************************************************** - * @file stm32f10x_pwr.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the PWR firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_pwr.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup PWR - * @brief PWR driver modules - * @{ - */ - -/** @defgroup PWR_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup PWR_Private_Defines - * @{ - */ - -/* --------- PWR registers bit address in the alias region ---------- */ -#define PWR_OFFSET (PWR_BASE - PERIPH_BASE) - -/* --- CR Register ---*/ - -/* Alias word address of DBP bit */ -#define CR_OFFSET (PWR_OFFSET + 0x00) -#define DBP_BitNumber 0x08 -#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4)) - -/* Alias word address of PVDE bit */ -#define PVDE_BitNumber 0x04 -#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4)) - -/* --- CSR Register ---*/ - -/* Alias word address of EWUP bit */ -#define CSR_OFFSET (PWR_OFFSET + 0x04) -#define EWUP_BitNumber 0x08 -#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4)) - -/* ------------------ PWR registers bit mask ------------------------ */ - -/* CR register bit mask */ -#define CR_DS_MASK ((uint32_t)0xFFFFFFFC) -#define CR_PLS_MASK ((uint32_t)0xFFFFFF1F) - - -/** - * @} - */ - -/** @defgroup PWR_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup PWR_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup PWR_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup PWR_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the PWR peripheral registers to their default reset values. - * @param None - * @retval None - */ -void PWR_DeInit(void) -{ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE); -} - -/** - * @brief Enables or disables access to the RTC and backup registers. - * @param NewState: new state of the access to the RTC and backup registers. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void PWR_BackupAccessCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) CR_DBP_BB = (uint32_t)NewState; -} - -/** - * @brief Enables or disables the Power Voltage Detector(PVD). - * @param NewState: new state of the PVD. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void PWR_PVDCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)NewState; -} - -/** - * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD). - * @param PWR_PVDLevel: specifies the PVD detection level - * This parameter can be one of the following values: - * @arg PWR_PVDLevel_2V2: PVD detection level set to 2.2V - * @arg PWR_PVDLevel_2V3: PVD detection level set to 2.3V - * @arg PWR_PVDLevel_2V4: PVD detection level set to 2.4V - * @arg PWR_PVDLevel_2V5: PVD detection level set to 2.5V - * @arg PWR_PVDLevel_2V6: PVD detection level set to 2.6V - * @arg PWR_PVDLevel_2V7: PVD detection level set to 2.7V - * @arg PWR_PVDLevel_2V8: PVD detection level set to 2.8V - * @arg PWR_PVDLevel_2V9: PVD detection level set to 2.9V - * @retval None - */ -void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel)); - tmpreg = PWR->CR; - /* Clear PLS[7:5] bits */ - tmpreg &= CR_PLS_MASK; - /* Set PLS[7:5] bits according to PWR_PVDLevel value */ - tmpreg |= PWR_PVDLevel; - /* Store the new value */ - PWR->CR = tmpreg; -} - -/** - * @brief Enables or disables the WakeUp Pin functionality. - * @param NewState: new state of the WakeUp Pin functionality. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void PWR_WakeUpPinCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) CSR_EWUP_BB = (uint32_t)NewState; -} - -/** - * @brief Enters STOP mode. - * @param PWR_Regulator: specifies the regulator state in STOP mode. - * This parameter can be one of the following values: - * @arg PWR_Regulator_ON: STOP mode with regulator ON - * @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode - * @param PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction. - * This parameter can be one of the following values: - * @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction - * @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction - * @retval None - */ -void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_PWR_REGULATOR(PWR_Regulator)); - assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry)); - - /* Select the regulator state in STOP mode ---------------------------------*/ - tmpreg = PWR->CR; - /* Clear PDDS and LPDS bits */ - tmpreg &= CR_DS_MASK; - /* Set LPDS bit according to PWR_Regulator value */ - tmpreg |= PWR_Regulator; - /* Store the new value */ - PWR->CR = tmpreg; - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SCB->SCR |= SCB_SCR_SLEEPDEEP; - - /* Select STOP mode entry --------------------------------------------------*/ - if(PWR_STOPEntry == PWR_STOPEntry_WFI) - { - /* Request Wait For Interrupt */ - __WFI(); - } - else - { - /* Request Wait For Event */ - __WFE(); - } - - /* Reset SLEEPDEEP bit of Cortex System Control Register */ - SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP); -} - -/** - * @brief Enters STANDBY mode. - * @param None - * @retval None - */ -void PWR_EnterSTANDBYMode(void) -{ - /* Clear Wake-up flag */ - PWR->CR |= PWR_CR_CWUF; - /* Select STANDBY mode */ - PWR->CR |= PWR_CR_PDDS; - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SCB->SCR |= SCB_SCR_SLEEPDEEP; -/* This option is used to ensure that store operations are completed */ -#if defined ( __CC_ARM ) - __force_stores(); -#endif - /* Request Wait For Interrupt */ - __WFI(); -} - -/** - * @brief Checks whether the specified PWR flag is set or not. - * @param PWR_FLAG: specifies the flag to check. - * This parameter can be one of the following values: - * @arg PWR_FLAG_WU: Wake Up flag - * @arg PWR_FLAG_SB: StandBy flag - * @arg PWR_FLAG_PVDO: PVD Output - * @retval The new state of PWR_FLAG (SET or RESET). - */ -FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_PWR_GET_FLAG(PWR_FLAG)); - - if ((PWR->CSR & PWR_FLAG) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - /* Return the flag status */ - return bitstatus; -} - -/** - * @brief Clears the PWR's pending flags. - * @param PWR_FLAG: specifies the flag to clear. - * This parameter can be one of the following values: - * @arg PWR_FLAG_WU: Wake Up flag - * @arg PWR_FLAG_SB: StandBy flag - * @retval None - */ -void PWR_ClearFlag(uint32_t PWR_FLAG) -{ - /* Check the parameters */ - assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG)); - - PWR->CR |= PWR_FLAG << 2; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_pwr.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the PWR firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_pwr.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup PWR + * @brief PWR driver modules + * @{ + */ + +/** @defgroup PWR_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_Defines + * @{ + */ + +/* --------- PWR registers bit address in the alias region ---------- */ +#define PWR_OFFSET (PWR_BASE - PERIPH_BASE) + +/* --- CR Register ---*/ + +/* Alias word address of DBP bit */ +#define CR_OFFSET (PWR_OFFSET + 0x00) +#define DBP_BitNumber 0x08 +#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4)) + +/* Alias word address of PVDE bit */ +#define PVDE_BitNumber 0x04 +#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of EWUP bit */ +#define CSR_OFFSET (PWR_OFFSET + 0x04) +#define EWUP_BitNumber 0x08 +#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4)) + +/* ------------------ PWR registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_DS_MASK ((uint32_t)0xFFFFFFFC) +#define CR_PLS_MASK ((uint32_t)0xFFFFFF1F) + + +/** + * @} + */ + +/** @defgroup PWR_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the PWR peripheral registers to their default reset values. + * @param None + * @retval None + */ +void PWR_DeInit(void) +{ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE); +} + +/** + * @brief Enables or disables access to the RTC and backup registers. + * @param NewState: new state of the access to the RTC and backup registers. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_BackupAccessCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_DBP_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the Power Voltage Detector(PVD). + * @param NewState: new state of the PVD. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_PVDCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD). + * @param PWR_PVDLevel: specifies the PVD detection level + * This parameter can be one of the following values: + * @arg PWR_PVDLevel_2V2: PVD detection level set to 2.2V + * @arg PWR_PVDLevel_2V3: PVD detection level set to 2.3V + * @arg PWR_PVDLevel_2V4: PVD detection level set to 2.4V + * @arg PWR_PVDLevel_2V5: PVD detection level set to 2.5V + * @arg PWR_PVDLevel_2V6: PVD detection level set to 2.6V + * @arg PWR_PVDLevel_2V7: PVD detection level set to 2.7V + * @arg PWR_PVDLevel_2V8: PVD detection level set to 2.8V + * @arg PWR_PVDLevel_2V9: PVD detection level set to 2.9V + * @retval None + */ +void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel)); + tmpreg = PWR->CR; + /* Clear PLS[7:5] bits */ + tmpreg &= CR_PLS_MASK; + /* Set PLS[7:5] bits according to PWR_PVDLevel value */ + tmpreg |= PWR_PVDLevel; + /* Store the new value */ + PWR->CR = tmpreg; +} + +/** + * @brief Enables or disables the WakeUp Pin functionality. + * @param NewState: new state of the WakeUp Pin functionality. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_WakeUpPinCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CSR_EWUP_BB = (uint32_t)NewState; +} + +/** + * @brief Enters STOP mode. + * @param PWR_Regulator: specifies the regulator state in STOP mode. + * This parameter can be one of the following values: + * @arg PWR_Regulator_ON: STOP mode with regulator ON + * @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode + * @param PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction + * @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction + * @retval None + */ +void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR(PWR_Regulator)); + assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry)); + + /* Select the regulator state in STOP mode ---------------------------------*/ + tmpreg = PWR->CR; + /* Clear PDDS and LPDS bits */ + tmpreg &= CR_DS_MASK; + /* Set LPDS bit according to PWR_Regulator value */ + tmpreg |= PWR_Regulator; + /* Store the new value */ + PWR->CR = tmpreg; + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP; + + /* Select STOP mode entry --------------------------------------------------*/ + if(PWR_STOPEntry == PWR_STOPEntry_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __WFE(); + } + + /* Reset SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP); +} + +/** + * @brief Enters STANDBY mode. + * @param None + * @retval None + */ +void PWR_EnterSTANDBYMode(void) +{ + /* Clear Wake-up flag */ + PWR->CR |= PWR_CR_CWUF; + /* Select STANDBY mode */ + PWR->CR |= PWR_CR_PDDS; + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP; +/* This option is used to ensure that store operations are completed */ +#if defined ( __CC_ARM ) + __force_stores(); +#endif + /* Request Wait For Interrupt */ + __WFI(); +} + +/** + * @brief Checks whether the specified PWR flag is set or not. + * @param PWR_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag + * @arg PWR_FLAG_SB: StandBy flag + * @arg PWR_FLAG_PVDO: PVD Output + * @retval The new state of PWR_FLAG (SET or RESET). + */ +FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_PWR_GET_FLAG(PWR_FLAG)); + + if ((PWR->CSR & PWR_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the PWR's pending flags. + * @param PWR_FLAG: specifies the flag to clear. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag + * @arg PWR_FLAG_SB: StandBy flag + * @retval None + */ +void PWR_ClearFlag(uint32_t PWR_FLAG) +{ + /* Check the parameters */ + assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG)); + + PWR->CR |= PWR_FLAG << 2; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c index 9a0b7ca1e..a9e822ce9 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c @@ -1,1469 +1,1469 @@ -/** - ****************************************************************************** - * @file stm32f10x_rcc.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the RCC firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup RCC - * @brief RCC driver modules - * @{ - */ - -/** @defgroup RCC_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup RCC_Private_Defines - * @{ - */ - -/* ------------ RCC registers bit address in the alias region ----------- */ -#define RCC_OFFSET (RCC_BASE - PERIPH_BASE) - -/* --- CR Register ---*/ - -/* Alias word address of HSION bit */ -#define CR_OFFSET (RCC_OFFSET + 0x00) -#define HSION_BitNumber 0x00 -#define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) - -/* Alias word address of PLLON bit */ -#define PLLON_BitNumber 0x18 -#define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) - -#ifdef STM32F10X_CL - /* Alias word address of PLL2ON bit */ - #define PLL2ON_BitNumber 0x1A - #define CR_PLL2ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL2ON_BitNumber * 4)) - - /* Alias word address of PLL3ON bit */ - #define PLL3ON_BitNumber 0x1C - #define CR_PLL3ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL3ON_BitNumber * 4)) -#endif /* STM32F10X_CL */ - -/* Alias word address of CSSON bit */ -#define CSSON_BitNumber 0x13 -#define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) - -/* --- CFGR Register ---*/ - -/* Alias word address of USBPRE bit */ -#define CFGR_OFFSET (RCC_OFFSET + 0x04) - -#ifndef STM32F10X_CL - #define USBPRE_BitNumber 0x16 - #define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4)) -#else - #define OTGFSPRE_BitNumber 0x16 - #define CFGR_OTGFSPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (OTGFSPRE_BitNumber * 4)) -#endif /* STM32F10X_CL */ - -/* --- BDCR Register ---*/ - -/* Alias word address of RTCEN bit */ -#define BDCR_OFFSET (RCC_OFFSET + 0x20) -#define RTCEN_BitNumber 0x0F -#define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) - -/* Alias word address of BDRST bit */ -#define BDRST_BitNumber 0x10 -#define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) - -/* --- CSR Register ---*/ - -/* Alias word address of LSION bit */ -#define CSR_OFFSET (RCC_OFFSET + 0x24) -#define LSION_BitNumber 0x00 -#define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) - -#ifdef STM32F10X_CL -/* --- CFGR2 Register ---*/ - - /* Alias word address of I2S2SRC bit */ - #define CFGR2_OFFSET (RCC_OFFSET + 0x2C) - #define I2S2SRC_BitNumber 0x11 - #define CFGR2_I2S2SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S2SRC_BitNumber * 4)) - - /* Alias word address of I2S3SRC bit */ - #define I2S3SRC_BitNumber 0x12 - #define CFGR2_I2S3SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S3SRC_BitNumber * 4)) -#endif /* STM32F10X_CL */ - -/* ---------------------- RCC registers bit mask ------------------------ */ - -/* CR register bit mask */ -#define CR_HSEBYP_Reset ((uint32_t)0xFFFBFFFF) -#define CR_HSEBYP_Set ((uint32_t)0x00040000) -#define CR_HSEON_Reset ((uint32_t)0xFFFEFFFF) -#define CR_HSEON_Set ((uint32_t)0x00010000) -#define CR_HSITRIM_Mask ((uint32_t)0xFFFFFF07) - -/* CFGR register bit mask */ -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) - #define CFGR_PLL_Mask ((uint32_t)0xFFC2FFFF) -#else - #define CFGR_PLL_Mask ((uint32_t)0xFFC0FFFF) -#endif /* STM32F10X_CL */ - -#define CFGR_PLLMull_Mask ((uint32_t)0x003C0000) -#define CFGR_PLLSRC_Mask ((uint32_t)0x00010000) -#define CFGR_PLLXTPRE_Mask ((uint32_t)0x00020000) -#define CFGR_SWS_Mask ((uint32_t)0x0000000C) -#define CFGR_SW_Mask ((uint32_t)0xFFFFFFFC) -#define CFGR_HPRE_Reset_Mask ((uint32_t)0xFFFFFF0F) -#define CFGR_HPRE_Set_Mask ((uint32_t)0x000000F0) -#define CFGR_PPRE1_Reset_Mask ((uint32_t)0xFFFFF8FF) -#define CFGR_PPRE1_Set_Mask ((uint32_t)0x00000700) -#define CFGR_PPRE2_Reset_Mask ((uint32_t)0xFFFFC7FF) -#define CFGR_PPRE2_Set_Mask ((uint32_t)0x00003800) -#define CFGR_ADCPRE_Reset_Mask ((uint32_t)0xFFFF3FFF) -#define CFGR_ADCPRE_Set_Mask ((uint32_t)0x0000C000) - -/* CSR register bit mask */ -#define CSR_RMVF_Set ((uint32_t)0x01000000) - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) -/* CFGR2 register bit mask */ - #define CFGR2_PREDIV1SRC ((uint32_t)0x00010000) - #define CFGR2_PREDIV1 ((uint32_t)0x0000000F) -#endif -#ifdef STM32F10X_CL - #define CFGR2_PREDIV2 ((uint32_t)0x000000F0) - #define CFGR2_PLL2MUL ((uint32_t)0x00000F00) - #define CFGR2_PLL3MUL ((uint32_t)0x0000F000) -#endif /* STM32F10X_CL */ - -/* RCC Flag Mask */ -#define FLAG_Mask ((uint8_t)0x1F) - -/* CIR register byte 2 (Bits[15:8]) base address */ -#define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009) - -/* CIR register byte 3 (Bits[23:16]) base address */ -#define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A) - -/* CFGR register byte 4 (Bits[31:24]) base address */ -#define CFGR_BYTE4_ADDRESS ((uint32_t)0x40021007) - -/* BDCR register base address */ -#define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET) - -/** - * @} - */ - -/** @defgroup RCC_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup RCC_Private_Variables - * @{ - */ - -static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}; -static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8}; - -/** - * @} - */ - -/** @defgroup RCC_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup RCC_Private_Functions - * @{ - */ - -/** - * @brief Resets the RCC clock configuration to the default reset state. - * @param None - * @retval None - */ -void RCC_DeInit(void) -{ - /* Set HSION bit */ - RCC->CR |= (uint32_t)0x00000001; - - /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ -#ifndef STM32F10X_CL - RCC->CFGR &= (uint32_t)0xF8FF0000; -#else - RCC->CFGR &= (uint32_t)0xF0FF0000; -#endif /* STM32F10X_CL */ - - /* Reset HSEON, CSSON and PLLON bits */ - RCC->CR &= (uint32_t)0xFEF6FFFF; - - /* Reset HSEBYP bit */ - RCC->CR &= (uint32_t)0xFFFBFFFF; - - /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ - RCC->CFGR &= (uint32_t)0xFF80FFFF; - -#ifdef STM32F10X_CL - /* Reset PLL2ON and PLL3ON bits */ - RCC->CR &= (uint32_t)0xEBFFFFFF; - - /* Disable all interrupts and clear pending bits */ - RCC->CIR = 0x00FF0000; - - /* Reset CFGR2 register */ - RCC->CFGR2 = 0x00000000; -#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) - /* Disable all interrupts and clear pending bits */ - RCC->CIR = 0x009F0000; - - /* Reset CFGR2 register */ - RCC->CFGR2 = 0x00000000; -#else - /* Disable all interrupts and clear pending bits */ - RCC->CIR = 0x009F0000; -#endif /* STM32F10X_CL */ - -} - -/** - * @brief Configures the External High Speed oscillator (HSE). - * @note HSE can not be stopped if it is used directly or through the PLL as system clock. - * @param RCC_HSE: specifies the new state of the HSE. - * This parameter can be one of the following values: - * @arg RCC_HSE_OFF: HSE oscillator OFF - * @arg RCC_HSE_ON: HSE oscillator ON - * @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock - * @retval None - */ -void RCC_HSEConfig(uint32_t RCC_HSE) -{ - /* Check the parameters */ - assert_param(IS_RCC_HSE(RCC_HSE)); - /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/ - /* Reset HSEON bit */ - RCC->CR &= CR_HSEON_Reset; - /* Reset HSEBYP bit */ - RCC->CR &= CR_HSEBYP_Reset; - /* Configure HSE (RCC_HSE_OFF is already covered by the code section above) */ - switch(RCC_HSE) - { - case RCC_HSE_ON: - /* Set HSEON bit */ - RCC->CR |= CR_HSEON_Set; - break; - - case RCC_HSE_Bypass: - /* Set HSEBYP and HSEON bits */ - RCC->CR |= CR_HSEBYP_Set | CR_HSEON_Set; - break; - - default: - break; - } -} - -/** - * @brief Waits for HSE start-up. - * @param None - * @retval An ErrorStatus enumuration value: - * - SUCCESS: HSE oscillator is stable and ready to use - * - ERROR: HSE oscillator not yet ready - */ -ErrorStatus RCC_WaitForHSEStartUp(void) -{ - __IO uint32_t StartUpCounter = 0; - ErrorStatus status = ERROR; - FlagStatus HSEStatus = RESET; - - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY); - StartUpCounter++; - } while((StartUpCounter != HSE_STARTUP_TIMEOUT) && (HSEStatus == RESET)); - - if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET) - { - status = SUCCESS; - } - else - { - status = ERROR; - } - return (status); -} - -/** - * @brief Adjusts the Internal High Speed oscillator (HSI) calibration value. - * @param HSICalibrationValue: specifies the calibration trimming value. - * This parameter must be a number between 0 and 0x1F. - * @retval None - */ -void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue)); - tmpreg = RCC->CR; - /* Clear HSITRIM[4:0] bits */ - tmpreg &= CR_HSITRIM_Mask; - /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */ - tmpreg |= (uint32_t)HSICalibrationValue << 3; - /* Store the new value */ - RCC->CR = tmpreg; -} - -/** - * @brief Enables or disables the Internal High Speed oscillator (HSI). - * @note HSI can not be stopped if it is used directly or through the PLL as system clock. - * @param NewState: new state of the HSI. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_HSICmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState; -} - -/** - * @brief Configures the PLL clock source and multiplication factor. - * @note This function must be used only when the PLL is disabled. - * @param RCC_PLLSource: specifies the PLL entry clock source. - * For @b STM32_Connectivity_line_devices or @b STM32_Value_line_devices, - * this parameter can be one of the following values: - * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry - * @arg RCC_PLLSource_PREDIV1: PREDIV1 clock selected as PLL clock entry - * For @b other_STM32_devices, this parameter can be one of the following values: - * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry - * @arg RCC_PLLSource_HSE_Div1: HSE oscillator clock selected as PLL clock entry - * @arg RCC_PLLSource_HSE_Div2: HSE oscillator clock divided by 2 selected as PLL clock entry - * @param RCC_PLLMul: specifies the PLL multiplication factor. - * For @b STM32_Connectivity_line_devices, this parameter can be RCC_PLLMul_x where x:{[4,9], 6_5} - * For @b other_STM32_devices, this parameter can be RCC_PLLMul_x where x:[2,16] - * @retval None - */ -void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource)); - assert_param(IS_RCC_PLL_MUL(RCC_PLLMul)); - - tmpreg = RCC->CFGR; - /* Clear PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */ - tmpreg &= CFGR_PLL_Mask; - /* Set the PLL configuration bits */ - tmpreg |= RCC_PLLSource | RCC_PLLMul; - /* Store the new value */ - RCC->CFGR = tmpreg; -} - -/** - * @brief Enables or disables the PLL. - * @note The PLL can not be disabled if it is used as system clock. - * @param NewState: new state of the PLL. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_PLLCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState; -} - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) -/** - * @brief Configures the PREDIV1 division factor. - * @note - * - This function must be used only when the PLL is disabled. - * - This function applies only to STM32 Connectivity line and Value line - * devices. - * @param RCC_PREDIV1_Source: specifies the PREDIV1 clock source. - * This parameter can be one of the following values: - * @arg RCC_PREDIV1_Source_HSE: HSE selected as PREDIV1 clock - * @arg RCC_PREDIV1_Source_PLL2: PLL2 selected as PREDIV1 clock - * @note - * For @b STM32_Value_line_devices this parameter is always RCC_PREDIV1_Source_HSE - * @param RCC_PREDIV1_Div: specifies the PREDIV1 clock division factor. - * This parameter can be RCC_PREDIV1_Divx where x:[1,16] - * @retval None - */ -void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_RCC_PREDIV1_SOURCE(RCC_PREDIV1_Source)); - assert_param(IS_RCC_PREDIV1(RCC_PREDIV1_Div)); - - tmpreg = RCC->CFGR2; - /* Clear PREDIV1[3:0] and PREDIV1SRC bits */ - tmpreg &= ~(CFGR2_PREDIV1 | CFGR2_PREDIV1SRC); - /* Set the PREDIV1 clock source and division factor */ - tmpreg |= RCC_PREDIV1_Source | RCC_PREDIV1_Div ; - /* Store the new value */ - RCC->CFGR2 = tmpreg; -} -#endif - -#ifdef STM32F10X_CL -/** - * @brief Configures the PREDIV2 division factor. - * @note - * - This function must be used only when both PLL2 and PLL3 are disabled. - * - This function applies only to STM32 Connectivity line devices. - * @param RCC_PREDIV2_Div: specifies the PREDIV2 clock division factor. - * This parameter can be RCC_PREDIV2_Divx where x:[1,16] - * @retval None - */ -void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_RCC_PREDIV2(RCC_PREDIV2_Div)); - - tmpreg = RCC->CFGR2; - /* Clear PREDIV2[3:0] bits */ - tmpreg &= ~CFGR2_PREDIV2; - /* Set the PREDIV2 division factor */ - tmpreg |= RCC_PREDIV2_Div; - /* Store the new value */ - RCC->CFGR2 = tmpreg; -} - -/** - * @brief Configures the PLL2 multiplication factor. - * @note - * - This function must be used only when the PLL2 is disabled. - * - This function applies only to STM32 Connectivity line devices. - * @param RCC_PLL2Mul: specifies the PLL2 multiplication factor. - * This parameter can be RCC_PLL2Mul_x where x:{[8,14], 16, 20} - * @retval None - */ -void RCC_PLL2Config(uint32_t RCC_PLL2Mul) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_RCC_PLL2_MUL(RCC_PLL2Mul)); - - tmpreg = RCC->CFGR2; - /* Clear PLL2Mul[3:0] bits */ - tmpreg &= ~CFGR2_PLL2MUL; - /* Set the PLL2 configuration bits */ - tmpreg |= RCC_PLL2Mul; - /* Store the new value */ - RCC->CFGR2 = tmpreg; -} - - -/** - * @brief Enables or disables the PLL2. - * @note - * - The PLL2 can not be disabled if it is used indirectly as system clock - * (i.e. it is used as PLL clock entry that is used as System clock). - * - This function applies only to STM32 Connectivity line devices. - * @param NewState: new state of the PLL2. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_PLL2Cmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) CR_PLL2ON_BB = (uint32_t)NewState; -} - - -/** - * @brief Configures the PLL3 multiplication factor. - * @note - * - This function must be used only when the PLL3 is disabled. - * - This function applies only to STM32 Connectivity line devices. - * @param RCC_PLL3Mul: specifies the PLL3 multiplication factor. - * This parameter can be RCC_PLL3Mul_x where x:{[8,14], 16, 20} - * @retval None - */ -void RCC_PLL3Config(uint32_t RCC_PLL3Mul) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_RCC_PLL3_MUL(RCC_PLL3Mul)); - - tmpreg = RCC->CFGR2; - /* Clear PLL3Mul[3:0] bits */ - tmpreg &= ~CFGR2_PLL3MUL; - /* Set the PLL3 configuration bits */ - tmpreg |= RCC_PLL3Mul; - /* Store the new value */ - RCC->CFGR2 = tmpreg; -} - - -/** - * @brief Enables or disables the PLL3. - * @note This function applies only to STM32 Connectivity line devices. - * @param NewState: new state of the PLL3. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_PLL3Cmd(FunctionalState NewState) -{ - /* Check the parameters */ - - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) CR_PLL3ON_BB = (uint32_t)NewState; -} -#endif /* STM32F10X_CL */ - -/** - * @brief Configures the system clock (SYSCLK). - * @param RCC_SYSCLKSource: specifies the clock source used as system clock. - * This parameter can be one of the following values: - * @arg RCC_SYSCLKSource_HSI: HSI selected as system clock - * @arg RCC_SYSCLKSource_HSE: HSE selected as system clock - * @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock - * @retval None - */ -void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource)); - tmpreg = RCC->CFGR; - /* Clear SW[1:0] bits */ - tmpreg &= CFGR_SW_Mask; - /* Set SW[1:0] bits according to RCC_SYSCLKSource value */ - tmpreg |= RCC_SYSCLKSource; - /* Store the new value */ - RCC->CFGR = tmpreg; -} - -/** - * @brief Returns the clock source used as system clock. - * @param None - * @retval The clock source used as system clock. The returned value can - * be one of the following: - * - 0x00: HSI used as system clock - * - 0x04: HSE used as system clock - * - 0x08: PLL used as system clock - */ -uint8_t RCC_GetSYSCLKSource(void) -{ - return ((uint8_t)(RCC->CFGR & CFGR_SWS_Mask)); -} - -/** - * @brief Configures the AHB clock (HCLK). - * @param RCC_SYSCLK: defines the AHB clock divider. This clock is derived from - * the system clock (SYSCLK). - * This parameter can be one of the following values: - * @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK - * @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2 - * @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4 - * @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8 - * @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16 - * @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64 - * @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128 - * @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256 - * @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512 - * @retval None - */ -void RCC_HCLKConfig(uint32_t RCC_SYSCLK) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_RCC_HCLK(RCC_SYSCLK)); - tmpreg = RCC->CFGR; - /* Clear HPRE[3:0] bits */ - tmpreg &= CFGR_HPRE_Reset_Mask; - /* Set HPRE[3:0] bits according to RCC_SYSCLK value */ - tmpreg |= RCC_SYSCLK; - /* Store the new value */ - RCC->CFGR = tmpreg; -} - -/** - * @brief Configures the Low Speed APB clock (PCLK1). - * @param RCC_HCLK: defines the APB1 clock divider. This clock is derived from - * the AHB clock (HCLK). - * This parameter can be one of the following values: - * @arg RCC_HCLK_Div1: APB1 clock = HCLK - * @arg RCC_HCLK_Div2: APB1 clock = HCLK/2 - * @arg RCC_HCLK_Div4: APB1 clock = HCLK/4 - * @arg RCC_HCLK_Div8: APB1 clock = HCLK/8 - * @arg RCC_HCLK_Div16: APB1 clock = HCLK/16 - * @retval None - */ -void RCC_PCLK1Config(uint32_t RCC_HCLK) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_RCC_PCLK(RCC_HCLK)); - tmpreg = RCC->CFGR; - /* Clear PPRE1[2:0] bits */ - tmpreg &= CFGR_PPRE1_Reset_Mask; - /* Set PPRE1[2:0] bits according to RCC_HCLK value */ - tmpreg |= RCC_HCLK; - /* Store the new value */ - RCC->CFGR = tmpreg; -} - -/** - * @brief Configures the High Speed APB clock (PCLK2). - * @param RCC_HCLK: defines the APB2 clock divider. This clock is derived from - * the AHB clock (HCLK). - * This parameter can be one of the following values: - * @arg RCC_HCLK_Div1: APB2 clock = HCLK - * @arg RCC_HCLK_Div2: APB2 clock = HCLK/2 - * @arg RCC_HCLK_Div4: APB2 clock = HCLK/4 - * @arg RCC_HCLK_Div8: APB2 clock = HCLK/8 - * @arg RCC_HCLK_Div16: APB2 clock = HCLK/16 - * @retval None - */ -void RCC_PCLK2Config(uint32_t RCC_HCLK) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_RCC_PCLK(RCC_HCLK)); - tmpreg = RCC->CFGR; - /* Clear PPRE2[2:0] bits */ - tmpreg &= CFGR_PPRE2_Reset_Mask; - /* Set PPRE2[2:0] bits according to RCC_HCLK value */ - tmpreg |= RCC_HCLK << 3; - /* Store the new value */ - RCC->CFGR = tmpreg; -} - -/** - * @brief Enables or disables the specified RCC interrupts. - * @param RCC_IT: specifies the RCC interrupt sources to be enabled or disabled. - * - * For @b STM32_Connectivity_line_devices, this parameter can be any combination - * of the following values - * @arg RCC_IT_LSIRDY: LSI ready interrupt - * @arg RCC_IT_LSERDY: LSE ready interrupt - * @arg RCC_IT_HSIRDY: HSI ready interrupt - * @arg RCC_IT_HSERDY: HSE ready interrupt - * @arg RCC_IT_PLLRDY: PLL ready interrupt - * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt - * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt - * - * For @b other_STM32_devices, this parameter can be any combination of the - * following values - * @arg RCC_IT_LSIRDY: LSI ready interrupt - * @arg RCC_IT_LSERDY: LSE ready interrupt - * @arg RCC_IT_HSIRDY: HSI ready interrupt - * @arg RCC_IT_HSERDY: HSE ready interrupt - * @arg RCC_IT_PLLRDY: PLL ready interrupt - * - * @param NewState: new state of the specified RCC interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_RCC_IT(RCC_IT)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Perform Byte access to RCC_CIR bits to enable the selected interrupts */ - *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT; - } - else - { - /* Perform Byte access to RCC_CIR bits to disable the selected interrupts */ - *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT; - } -} - -#ifndef STM32F10X_CL -/** - * @brief Configures the USB clock (USBCLK). - * @param RCC_USBCLKSource: specifies the USB clock source. This clock is - * derived from the PLL output. - * This parameter can be one of the following values: - * @arg RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB - * clock source - * @arg RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB clock source - * @retval None - */ -void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource) -{ - /* Check the parameters */ - assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource)); - - *(__IO uint32_t *) CFGR_USBPRE_BB = RCC_USBCLKSource; -} -#else -/** - * @brief Configures the USB OTG FS clock (OTGFSCLK). - * This function applies only to STM32 Connectivity line devices. - * @param RCC_OTGFSCLKSource: specifies the USB OTG FS clock source. - * This clock is derived from the PLL output. - * This parameter can be one of the following values: - * @arg RCC_OTGFSCLKSource_PLLVCO_Div3: PLL VCO clock divided by 2 selected as USB OTG FS clock source - * @arg RCC_OTGFSCLKSource_PLLVCO_Div2: PLL VCO clock divided by 2 selected as USB OTG FS clock source - * @retval None - */ -void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource) -{ - /* Check the parameters */ - assert_param(IS_RCC_OTGFSCLK_SOURCE(RCC_OTGFSCLKSource)); - - *(__IO uint32_t *) CFGR_OTGFSPRE_BB = RCC_OTGFSCLKSource; -} -#endif /* STM32F10X_CL */ - -/** - * @brief Configures the ADC clock (ADCCLK). - * @param RCC_PCLK2: defines the ADC clock divider. This clock is derived from - * the APB2 clock (PCLK2). - * This parameter can be one of the following values: - * @arg RCC_PCLK2_Div2: ADC clock = PCLK2/2 - * @arg RCC_PCLK2_Div4: ADC clock = PCLK2/4 - * @arg RCC_PCLK2_Div6: ADC clock = PCLK2/6 - * @arg RCC_PCLK2_Div8: ADC clock = PCLK2/8 - * @retval None - */ -void RCC_ADCCLKConfig(uint32_t RCC_PCLK2) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_RCC_ADCCLK(RCC_PCLK2)); - tmpreg = RCC->CFGR; - /* Clear ADCPRE[1:0] bits */ - tmpreg &= CFGR_ADCPRE_Reset_Mask; - /* Set ADCPRE[1:0] bits according to RCC_PCLK2 value */ - tmpreg |= RCC_PCLK2; - /* Store the new value */ - RCC->CFGR = tmpreg; -} - -#ifdef STM32F10X_CL -/** - * @brief Configures the I2S2 clock source(I2S2CLK). - * @note - * - This function must be called before enabling I2S2 APB clock. - * - This function applies only to STM32 Connectivity line devices. - * @param RCC_I2S2CLKSource: specifies the I2S2 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2S2CLKSource_SYSCLK: system clock selected as I2S2 clock entry - * @arg RCC_I2S2CLKSource_PLL3_VCO: PLL3 VCO clock selected as I2S2 clock entry - * @retval None - */ -void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource) -{ - /* Check the parameters */ - assert_param(IS_RCC_I2S2CLK_SOURCE(RCC_I2S2CLKSource)); - - *(__IO uint32_t *) CFGR2_I2S2SRC_BB = RCC_I2S2CLKSource; -} - -/** - * @brief Configures the I2S3 clock source(I2S2CLK). - * @note - * - This function must be called before enabling I2S3 APB clock. - * - This function applies only to STM32 Connectivity line devices. - * @param RCC_I2S3CLKSource: specifies the I2S3 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2S3CLKSource_SYSCLK: system clock selected as I2S3 clock entry - * @arg RCC_I2S3CLKSource_PLL3_VCO: PLL3 VCO clock selected as I2S3 clock entry - * @retval None - */ -void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource) -{ - /* Check the parameters */ - assert_param(IS_RCC_I2S3CLK_SOURCE(RCC_I2S3CLKSource)); - - *(__IO uint32_t *) CFGR2_I2S3SRC_BB = RCC_I2S3CLKSource; -} -#endif /* STM32F10X_CL */ - -/** - * @brief Configures the External Low Speed oscillator (LSE). - * @param RCC_LSE: specifies the new state of the LSE. - * This parameter can be one of the following values: - * @arg RCC_LSE_OFF: LSE oscillator OFF - * @arg RCC_LSE_ON: LSE oscillator ON - * @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock - * @retval None - */ -void RCC_LSEConfig(uint8_t RCC_LSE) -{ - /* Check the parameters */ - assert_param(IS_RCC_LSE(RCC_LSE)); - /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/ - /* Reset LSEON bit */ - *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF; - /* Reset LSEBYP bit */ - *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF; - /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */ - switch(RCC_LSE) - { - case RCC_LSE_ON: - /* Set LSEON bit */ - *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_ON; - break; - - case RCC_LSE_Bypass: - /* Set LSEBYP and LSEON bits */ - *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON; - break; - - default: - break; - } -} - -/** - * @brief Enables or disables the Internal Low Speed oscillator (LSI). - * @note LSI can not be disabled if the IWDG is running. - * @param NewState: new state of the LSI. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_LSICmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState; -} - -/** - * @brief Configures the RTC clock (RTCCLK). - * @note Once the RTC clock is selected it can’t be changed unless the Backup domain is reset. - * @param RCC_RTCCLKSource: specifies the RTC clock source. - * This parameter can be one of the following values: - * @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock - * @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock - * @arg RCC_RTCCLKSource_HSE_Div128: HSE clock divided by 128 selected as RTC clock - * @retval None - */ -void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource) -{ - /* Check the parameters */ - assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource)); - /* Select the RTC clock source */ - RCC->BDCR |= RCC_RTCCLKSource; -} - -/** - * @brief Enables or disables the RTC clock. - * @note This function must be used only after the RTC clock was selected using the RCC_RTCCLKConfig function. - * @param NewState: new state of the RTC clock. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_RTCCLKCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState; -} - -/** - * @brief Returns the frequencies of different on chip clocks. - * @param RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold - * the clocks frequencies. - * @note The result of this function could be not correct when using - * fractional value for HSE crystal. - * @retval None - */ -void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) -{ - uint32_t tmp = 0, pllmull = 0, pllsource = 0, presc = 0; - -#ifdef STM32F10X_CL - uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0; -#endif /* STM32F10X_CL */ - -#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) - uint32_t prediv1factor = 0; -#endif - - /* Get SYSCLK source -------------------------------------------------------*/ - tmp = RCC->CFGR & CFGR_SWS_Mask; - - switch (tmp) - { - case 0x00: /* HSI used as system clock */ - RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; - break; - case 0x04: /* HSE used as system clock */ - RCC_Clocks->SYSCLK_Frequency = HSE_VALUE; - break; - case 0x08: /* PLL used as system clock */ - - /* Get PLL clock source and multiplication factor ----------------------*/ - pllmull = RCC->CFGR & CFGR_PLLMull_Mask; - pllsource = RCC->CFGR & CFGR_PLLSRC_Mask; - -#ifndef STM32F10X_CL - pllmull = ( pllmull >> 18) + 2; - - if (pllsource == 0x00) - {/* HSI oscillator clock divided by 2 selected as PLL clock entry */ - RCC_Clocks->SYSCLK_Frequency = (HSI_VALUE >> 1) * pllmull; - } - else - { - #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) - prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1; - /* HSE oscillator clock selected as PREDIV1 clock entry */ - RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE / prediv1factor) * pllmull; - #else - /* HSE selected as PLL clock entry */ - if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (uint32_t)RESET) - {/* HSE oscillator clock divided by 2 */ - RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE >> 1) * pllmull; - } - else - { - RCC_Clocks->SYSCLK_Frequency = HSE_VALUE * pllmull; - } - #endif - } -#else - pllmull = pllmull >> 18; - - if (pllmull != 0x0D) - { - pllmull += 2; - } - else - { /* PLL multiplication factor = PLL input clock * 6.5 */ - pllmull = 13 / 2; - } - - if (pllsource == 0x00) - {/* HSI oscillator clock divided by 2 selected as PLL clock entry */ - RCC_Clocks->SYSCLK_Frequency = (HSI_VALUE >> 1) * pllmull; - } - else - {/* PREDIV1 selected as PLL clock entry */ - - /* Get PREDIV1 clock source and division factor */ - prediv1source = RCC->CFGR2 & CFGR2_PREDIV1SRC; - prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1; - - if (prediv1source == 0) - { /* HSE oscillator clock selected as PREDIV1 clock entry */ - RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE / prediv1factor) * pllmull; - } - else - {/* PLL2 clock selected as PREDIV1 clock entry */ - - /* Get PREDIV2 division factor and PLL2 multiplication factor */ - prediv2factor = ((RCC->CFGR2 & CFGR2_PREDIV2) >> 4) + 1; - pll2mull = ((RCC->CFGR2 & CFGR2_PLL2MUL) >> 8 ) + 2; - RCC_Clocks->SYSCLK_Frequency = (((HSE_VALUE / prediv2factor) * pll2mull) / prediv1factor) * pllmull; - } - } -#endif /* STM32F10X_CL */ - break; - - default: - RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; - break; - } - - /* Compute HCLK, PCLK1, PCLK2 and ADCCLK clocks frequencies ----------------*/ - /* Get HCLK prescaler */ - tmp = RCC->CFGR & CFGR_HPRE_Set_Mask; - tmp = tmp >> 4; - presc = APBAHBPrescTable[tmp]; - /* HCLK clock frequency */ - RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc; - /* Get PCLK1 prescaler */ - tmp = RCC->CFGR & CFGR_PPRE1_Set_Mask; - tmp = tmp >> 8; - presc = APBAHBPrescTable[tmp]; - /* PCLK1 clock frequency */ - RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc; - /* Get PCLK2 prescaler */ - tmp = RCC->CFGR & CFGR_PPRE2_Set_Mask; - tmp = tmp >> 11; - presc = APBAHBPrescTable[tmp]; - /* PCLK2 clock frequency */ - RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc; - /* Get ADCCLK prescaler */ - tmp = RCC->CFGR & CFGR_ADCPRE_Set_Mask; - tmp = tmp >> 14; - presc = ADCPrescTable[tmp]; - /* ADCCLK clock frequency */ - RCC_Clocks->ADCCLK_Frequency = RCC_Clocks->PCLK2_Frequency / presc; -} - -/** - * @brief Enables or disables the AHB peripheral clock. - * @param RCC_AHBPeriph: specifies the AHB peripheral to gates its clock. - * - * For @b STM32_Connectivity_line_devices, this parameter can be any combination - * of the following values: - * @arg RCC_AHBPeriph_DMA1 - * @arg RCC_AHBPeriph_DMA2 - * @arg RCC_AHBPeriph_SRAM - * @arg RCC_AHBPeriph_FLITF - * @arg RCC_AHBPeriph_CRC - * @arg RCC_AHBPeriph_OTG_FS - * @arg RCC_AHBPeriph_ETH_MAC - * @arg RCC_AHBPeriph_ETH_MAC_Tx - * @arg RCC_AHBPeriph_ETH_MAC_Rx - * - * For @b other_STM32_devices, this parameter can be any combination of the - * following values: - * @arg RCC_AHBPeriph_DMA1 - * @arg RCC_AHBPeriph_DMA2 - * @arg RCC_AHBPeriph_SRAM - * @arg RCC_AHBPeriph_FLITF - * @arg RCC_AHBPeriph_CRC - * @arg RCC_AHBPeriph_FSMC - * @arg RCC_AHBPeriph_SDIO - * - * @note SRAM and FLITF clock can be disabled only during sleep mode. - * @param NewState: new state of the specified peripheral clock. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - RCC->AHBENR |= RCC_AHBPeriph; - } - else - { - RCC->AHBENR &= ~RCC_AHBPeriph; - } -} - -/** - * @brief Enables or disables the High Speed APB (APB2) peripheral clock. - * @param RCC_APB2Periph: specifies the APB2 peripheral to gates its clock. - * This parameter can be any combination of the following values: - * @arg RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, - * RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, - * RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, - * RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, - * RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, - * RCC_APB2Periph_TIM15, RCC_APB2Periph_TIM16, RCC_APB2Periph_TIM17, - * RCC_APB2Periph_TIM9, RCC_APB2Periph_TIM10, RCC_APB2Periph_TIM11 - * @param NewState: new state of the specified peripheral clock. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - RCC->APB2ENR |= RCC_APB2Periph; - } - else - { - RCC->APB2ENR &= ~RCC_APB2Periph; - } -} - -/** - * @brief Enables or disables the Low Speed APB (APB1) peripheral clock. - * @param RCC_APB1Periph: specifies the APB1 peripheral to gates its clock. - * This parameter can be any combination of the following values: - * @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, - * RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, - * RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, - * RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, - * RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, - * RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP, - * RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_CEC, - * RCC_APB1Periph_TIM12, RCC_APB1Periph_TIM13, RCC_APB1Periph_TIM14 - * @param NewState: new state of the specified peripheral clock. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - RCC->APB1ENR |= RCC_APB1Periph; - } - else - { - RCC->APB1ENR &= ~RCC_APB1Periph; - } -} - -#ifdef STM32F10X_CL -/** - * @brief Forces or releases AHB peripheral reset. - * @note This function applies only to STM32 Connectivity line devices. - * @param RCC_AHBPeriph: specifies the AHB peripheral to reset. - * This parameter can be any combination of the following values: - * @arg RCC_AHBPeriph_OTG_FS - * @arg RCC_AHBPeriph_ETH_MAC - * @param NewState: new state of the specified peripheral reset. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_RCC_AHB_PERIPH_RESET(RCC_AHBPeriph)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - RCC->AHBRSTR |= RCC_AHBPeriph; - } - else - { - RCC->AHBRSTR &= ~RCC_AHBPeriph; - } -} -#endif /* STM32F10X_CL */ - -/** - * @brief Forces or releases High Speed APB (APB2) peripheral reset. - * @param RCC_APB2Periph: specifies the APB2 peripheral to reset. - * This parameter can be any combination of the following values: - * @arg RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, - * RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, - * RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, - * RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, - * RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, - * RCC_APB2Periph_TIM15, RCC_APB2Periph_TIM16, RCC_APB2Periph_TIM17, - * RCC_APB2Periph_TIM9, RCC_APB2Periph_TIM10, RCC_APB2Periph_TIM11 - * @param NewState: new state of the specified peripheral reset. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - RCC->APB2RSTR |= RCC_APB2Periph; - } - else - { - RCC->APB2RSTR &= ~RCC_APB2Periph; - } -} - -/** - * @brief Forces or releases Low Speed APB (APB1) peripheral reset. - * @param RCC_APB1Periph: specifies the APB1 peripheral to reset. - * This parameter can be any combination of the following values: - * @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, - * RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, - * RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, - * RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, - * RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, - * RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP, - * RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_CEC, - * RCC_APB1Periph_TIM12, RCC_APB1Periph_TIM13, RCC_APB1Periph_TIM14 - * @param NewState: new state of the specified peripheral clock. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - RCC->APB1RSTR |= RCC_APB1Periph; - } - else - { - RCC->APB1RSTR &= ~RCC_APB1Periph; - } -} - -/** - * @brief Forces or releases the Backup domain reset. - * @param NewState: new state of the Backup domain reset. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_BackupResetCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState; -} - -/** - * @brief Enables or disables the Clock Security System. - * @param NewState: new state of the Clock Security System.. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RCC_ClockSecuritySystemCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState; -} - -/** - * @brief Selects the clock source to output on MCO pin. - * @param RCC_MCO: specifies the clock source to output. - * - * For @b STM32_Connectivity_line_devices, this parameter can be one of the - * following values: - * @arg RCC_MCO_NoClock: No clock selected - * @arg RCC_MCO_SYSCLK: System clock selected - * @arg RCC_MCO_HSI: HSI oscillator clock selected - * @arg RCC_MCO_HSE: HSE oscillator clock selected - * @arg RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected - * @arg RCC_MCO_PLL2CLK: PLL2 clock selected - * @arg RCC_MCO_PLL3CLK_Div2: PLL3 clock divided by 2 selected - * @arg RCC_MCO_XT1: External 3-25 MHz oscillator clock selected - * @arg RCC_MCO_PLL3CLK: PLL3 clock selected - * - * For @b other_STM32_devices, this parameter can be one of the following values: - * @arg RCC_MCO_NoClock: No clock selected - * @arg RCC_MCO_SYSCLK: System clock selected - * @arg RCC_MCO_HSI: HSI oscillator clock selected - * @arg RCC_MCO_HSE: HSE oscillator clock selected - * @arg RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected - * - * @retval None - */ -void RCC_MCOConfig(uint8_t RCC_MCO) -{ - /* Check the parameters */ - assert_param(IS_RCC_MCO(RCC_MCO)); - - /* Perform Byte access to MCO bits to select the MCO source */ - *(__IO uint8_t *) CFGR_BYTE4_ADDRESS = RCC_MCO; -} - -/** - * @brief Checks whether the specified RCC flag is set or not. - * @param RCC_FLAG: specifies the flag to check. - * - * For @b STM32_Connectivity_line_devices, this parameter can be one of the - * following values: - * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready - * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready - * @arg RCC_FLAG_PLLRDY: PLL clock ready - * @arg RCC_FLAG_PLL2RDY: PLL2 clock ready - * @arg RCC_FLAG_PLL3RDY: PLL3 clock ready - * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready - * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready - * @arg RCC_FLAG_PINRST: Pin reset - * @arg RCC_FLAG_PORRST: POR/PDR reset - * @arg RCC_FLAG_SFTRST: Software reset - * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset - * @arg RCC_FLAG_WWDGRST: Window Watchdog reset - * @arg RCC_FLAG_LPWRRST: Low Power reset - * - * For @b other_STM32_devices, this parameter can be one of the following values: - * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready - * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready - * @arg RCC_FLAG_PLLRDY: PLL clock ready - * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready - * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready - * @arg RCC_FLAG_PINRST: Pin reset - * @arg RCC_FLAG_PORRST: POR/PDR reset - * @arg RCC_FLAG_SFTRST: Software reset - * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset - * @arg RCC_FLAG_WWDGRST: Window Watchdog reset - * @arg RCC_FLAG_LPWRRST: Low Power reset - * - * @retval The new state of RCC_FLAG (SET or RESET). - */ -FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG) -{ - uint32_t tmp = 0; - uint32_t statusreg = 0; - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_RCC_FLAG(RCC_FLAG)); - - /* Get the RCC register index */ - tmp = RCC_FLAG >> 5; - if (tmp == 1) /* The flag to check is in CR register */ - { - statusreg = RCC->CR; - } - else if (tmp == 2) /* The flag to check is in BDCR register */ - { - statusreg = RCC->BDCR; - } - else /* The flag to check is in CSR register */ - { - statusreg = RCC->CSR; - } - - /* Get the flag position */ - tmp = RCC_FLAG & FLAG_Mask; - if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - - /* Return the flag status */ - return bitstatus; -} - -/** - * @brief Clears the RCC reset flags. - * @note The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, - * RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST - * @param None - * @retval None - */ -void RCC_ClearFlag(void) -{ - /* Set RMVF bit to clear the reset flags */ - RCC->CSR |= CSR_RMVF_Set; -} - -/** - * @brief Checks whether the specified RCC interrupt has occurred or not. - * @param RCC_IT: specifies the RCC interrupt source to check. - * - * For @b STM32_Connectivity_line_devices, this parameter can be one of the - * following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt - * @arg RCC_IT_LSERDY: LSE ready interrupt - * @arg RCC_IT_HSIRDY: HSI ready interrupt - * @arg RCC_IT_HSERDY: HSE ready interrupt - * @arg RCC_IT_PLLRDY: PLL ready interrupt - * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt - * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt - * @arg RCC_IT_CSS: Clock Security System interrupt - * - * For @b other_STM32_devices, this parameter can be one of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt - * @arg RCC_IT_LSERDY: LSE ready interrupt - * @arg RCC_IT_HSIRDY: HSI ready interrupt - * @arg RCC_IT_HSERDY: HSE ready interrupt - * @arg RCC_IT_PLLRDY: PLL ready interrupt - * @arg RCC_IT_CSS: Clock Security System interrupt - * - * @retval The new state of RCC_IT (SET or RESET). - */ -ITStatus RCC_GetITStatus(uint8_t RCC_IT) -{ - ITStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_RCC_GET_IT(RCC_IT)); - - /* Check the status of the specified RCC interrupt */ - if ((RCC->CIR & RCC_IT) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - - /* Return the RCC_IT status */ - return bitstatus; -} - -/** - * @brief Clears the RCC’s interrupt pending bits. - * @param RCC_IT: specifies the interrupt pending bit to clear. - * - * For @b STM32_Connectivity_line_devices, this parameter can be any combination - * of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt - * @arg RCC_IT_LSERDY: LSE ready interrupt - * @arg RCC_IT_HSIRDY: HSI ready interrupt - * @arg RCC_IT_HSERDY: HSE ready interrupt - * @arg RCC_IT_PLLRDY: PLL ready interrupt - * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt - * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt - * @arg RCC_IT_CSS: Clock Security System interrupt - * - * For @b other_STM32_devices, this parameter can be any combination of the - * following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt - * @arg RCC_IT_LSERDY: LSE ready interrupt - * @arg RCC_IT_HSIRDY: HSI ready interrupt - * @arg RCC_IT_HSERDY: HSE ready interrupt - * @arg RCC_IT_PLLRDY: PLL ready interrupt - * - * @arg RCC_IT_CSS: Clock Security System interrupt - * @retval None - */ -void RCC_ClearITPendingBit(uint8_t RCC_IT) -{ - /* Check the parameters */ - assert_param(IS_RCC_CLEAR_IT(RCC_IT)); - - /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt - pending bits */ - *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_rcc.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the RCC firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup RCC + * @brief RCC driver modules + * @{ + */ + +/** @defgroup RCC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Private_Defines + * @{ + */ + +/* ------------ RCC registers bit address in the alias region ----------- */ +#define RCC_OFFSET (RCC_BASE - PERIPH_BASE) + +/* --- CR Register ---*/ + +/* Alias word address of HSION bit */ +#define CR_OFFSET (RCC_OFFSET + 0x00) +#define HSION_BitNumber 0x00 +#define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) + +/* Alias word address of PLLON bit */ +#define PLLON_BitNumber 0x18 +#define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) + +#ifdef STM32F10X_CL + /* Alias word address of PLL2ON bit */ + #define PLL2ON_BitNumber 0x1A + #define CR_PLL2ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL2ON_BitNumber * 4)) + + /* Alias word address of PLL3ON bit */ + #define PLL3ON_BitNumber 0x1C + #define CR_PLL3ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL3ON_BitNumber * 4)) +#endif /* STM32F10X_CL */ + +/* Alias word address of CSSON bit */ +#define CSSON_BitNumber 0x13 +#define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) + +/* --- CFGR Register ---*/ + +/* Alias word address of USBPRE bit */ +#define CFGR_OFFSET (RCC_OFFSET + 0x04) + +#ifndef STM32F10X_CL + #define USBPRE_BitNumber 0x16 + #define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4)) +#else + #define OTGFSPRE_BitNumber 0x16 + #define CFGR_OTGFSPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (OTGFSPRE_BitNumber * 4)) +#endif /* STM32F10X_CL */ + +/* --- BDCR Register ---*/ + +/* Alias word address of RTCEN bit */ +#define BDCR_OFFSET (RCC_OFFSET + 0x20) +#define RTCEN_BitNumber 0x0F +#define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) + +/* Alias word address of BDRST bit */ +#define BDRST_BitNumber 0x10 +#define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of LSION bit */ +#define CSR_OFFSET (RCC_OFFSET + 0x24) +#define LSION_BitNumber 0x00 +#define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) + +#ifdef STM32F10X_CL +/* --- CFGR2 Register ---*/ + + /* Alias word address of I2S2SRC bit */ + #define CFGR2_OFFSET (RCC_OFFSET + 0x2C) + #define I2S2SRC_BitNumber 0x11 + #define CFGR2_I2S2SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S2SRC_BitNumber * 4)) + + /* Alias word address of I2S3SRC bit */ + #define I2S3SRC_BitNumber 0x12 + #define CFGR2_I2S3SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S3SRC_BitNumber * 4)) +#endif /* STM32F10X_CL */ + +/* ---------------------- RCC registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_HSEBYP_Reset ((uint32_t)0xFFFBFFFF) +#define CR_HSEBYP_Set ((uint32_t)0x00040000) +#define CR_HSEON_Reset ((uint32_t)0xFFFEFFFF) +#define CR_HSEON_Set ((uint32_t)0x00010000) +#define CR_HSITRIM_Mask ((uint32_t)0xFFFFFF07) + +/* CFGR register bit mask */ +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) + #define CFGR_PLL_Mask ((uint32_t)0xFFC2FFFF) +#else + #define CFGR_PLL_Mask ((uint32_t)0xFFC0FFFF) +#endif /* STM32F10X_CL */ + +#define CFGR_PLLMull_Mask ((uint32_t)0x003C0000) +#define CFGR_PLLSRC_Mask ((uint32_t)0x00010000) +#define CFGR_PLLXTPRE_Mask ((uint32_t)0x00020000) +#define CFGR_SWS_Mask ((uint32_t)0x0000000C) +#define CFGR_SW_Mask ((uint32_t)0xFFFFFFFC) +#define CFGR_HPRE_Reset_Mask ((uint32_t)0xFFFFFF0F) +#define CFGR_HPRE_Set_Mask ((uint32_t)0x000000F0) +#define CFGR_PPRE1_Reset_Mask ((uint32_t)0xFFFFF8FF) +#define CFGR_PPRE1_Set_Mask ((uint32_t)0x00000700) +#define CFGR_PPRE2_Reset_Mask ((uint32_t)0xFFFFC7FF) +#define CFGR_PPRE2_Set_Mask ((uint32_t)0x00003800) +#define CFGR_ADCPRE_Reset_Mask ((uint32_t)0xFFFF3FFF) +#define CFGR_ADCPRE_Set_Mask ((uint32_t)0x0000C000) + +/* CSR register bit mask */ +#define CSR_RMVF_Set ((uint32_t)0x01000000) + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) +/* CFGR2 register bit mask */ + #define CFGR2_PREDIV1SRC ((uint32_t)0x00010000) + #define CFGR2_PREDIV1 ((uint32_t)0x0000000F) +#endif +#ifdef STM32F10X_CL + #define CFGR2_PREDIV2 ((uint32_t)0x000000F0) + #define CFGR2_PLL2MUL ((uint32_t)0x00000F00) + #define CFGR2_PLL3MUL ((uint32_t)0x0000F000) +#endif /* STM32F10X_CL */ + +/* RCC Flag Mask */ +#define FLAG_Mask ((uint8_t)0x1F) + +/* CIR register byte 2 (Bits[15:8]) base address */ +#define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009) + +/* CIR register byte 3 (Bits[23:16]) base address */ +#define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A) + +/* CFGR register byte 4 (Bits[31:24]) base address */ +#define CFGR_BYTE4_ADDRESS ((uint32_t)0x40021007) + +/* BDCR register base address */ +#define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET) + +/** + * @} + */ + +/** @defgroup RCC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Private_Variables + * @{ + */ + +static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}; +static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8}; + +/** + * @} + */ + +/** @defgroup RCC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Private_Functions + * @{ + */ + +/** + * @brief Resets the RCC clock configuration to the default reset state. + * @param None + * @retval None + */ +void RCC_DeInit(void) +{ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ +#ifndef STM32F10X_CL + RCC->CFGR &= (uint32_t)0xF8FF0000; +#else + RCC->CFGR &= (uint32_t)0xF0FF0000; +#endif /* STM32F10X_CL */ + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ + RCC->CFGR &= (uint32_t)0xFF80FFFF; + +#ifdef STM32F10X_CL + /* Reset PLL2ON and PLL3ON bits */ + RCC->CR &= (uint32_t)0xEBFFFFFF; + + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x00FF0000; + + /* Reset CFGR2 register */ + RCC->CFGR2 = 0x00000000; +#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; + + /* Reset CFGR2 register */ + RCC->CFGR2 = 0x00000000; +#else + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; +#endif /* STM32F10X_CL */ + +} + +/** + * @brief Configures the External High Speed oscillator (HSE). + * @note HSE can not be stopped if it is used directly or through the PLL as system clock. + * @param RCC_HSE: specifies the new state of the HSE. + * This parameter can be one of the following values: + * @arg RCC_HSE_OFF: HSE oscillator OFF + * @arg RCC_HSE_ON: HSE oscillator ON + * @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock + * @retval None + */ +void RCC_HSEConfig(uint32_t RCC_HSE) +{ + /* Check the parameters */ + assert_param(IS_RCC_HSE(RCC_HSE)); + /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/ + /* Reset HSEON bit */ + RCC->CR &= CR_HSEON_Reset; + /* Reset HSEBYP bit */ + RCC->CR &= CR_HSEBYP_Reset; + /* Configure HSE (RCC_HSE_OFF is already covered by the code section above) */ + switch(RCC_HSE) + { + case RCC_HSE_ON: + /* Set HSEON bit */ + RCC->CR |= CR_HSEON_Set; + break; + + case RCC_HSE_Bypass: + /* Set HSEBYP and HSEON bits */ + RCC->CR |= CR_HSEBYP_Set | CR_HSEON_Set; + break; + + default: + break; + } +} + +/** + * @brief Waits for HSE start-up. + * @param None + * @retval An ErrorStatus enumuration value: + * - SUCCESS: HSE oscillator is stable and ready to use + * - ERROR: HSE oscillator not yet ready + */ +ErrorStatus RCC_WaitForHSEStartUp(void) +{ + __IO uint32_t StartUpCounter = 0; + ErrorStatus status = ERROR; + FlagStatus HSEStatus = RESET; + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY); + StartUpCounter++; + } while((StartUpCounter != HSE_STARTUP_TIMEOUT) && (HSEStatus == RESET)); + + if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET) + { + status = SUCCESS; + } + else + { + status = ERROR; + } + return (status); +} + +/** + * @brief Adjusts the Internal High Speed oscillator (HSI) calibration value. + * @param HSICalibrationValue: specifies the calibration trimming value. + * This parameter must be a number between 0 and 0x1F. + * @retval None + */ +void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue)); + tmpreg = RCC->CR; + /* Clear HSITRIM[4:0] bits */ + tmpreg &= CR_HSITRIM_Mask; + /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */ + tmpreg |= (uint32_t)HSICalibrationValue << 3; + /* Store the new value */ + RCC->CR = tmpreg; +} + +/** + * @brief Enables or disables the Internal High Speed oscillator (HSI). + * @note HSI can not be stopped if it is used directly or through the PLL as system clock. + * @param NewState: new state of the HSI. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_HSICmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the PLL clock source and multiplication factor. + * @note This function must be used only when the PLL is disabled. + * @param RCC_PLLSource: specifies the PLL entry clock source. + * For @b STM32_Connectivity_line_devices or @b STM32_Value_line_devices, + * this parameter can be one of the following values: + * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry + * @arg RCC_PLLSource_PREDIV1: PREDIV1 clock selected as PLL clock entry + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry + * @arg RCC_PLLSource_HSE_Div1: HSE oscillator clock selected as PLL clock entry + * @arg RCC_PLLSource_HSE_Div2: HSE oscillator clock divided by 2 selected as PLL clock entry + * @param RCC_PLLMul: specifies the PLL multiplication factor. + * For @b STM32_Connectivity_line_devices, this parameter can be RCC_PLLMul_x where x:{[4,9], 6_5} + * For @b other_STM32_devices, this parameter can be RCC_PLLMul_x where x:[2,16] + * @retval None + */ +void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource)); + assert_param(IS_RCC_PLL_MUL(RCC_PLLMul)); + + tmpreg = RCC->CFGR; + /* Clear PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */ + tmpreg &= CFGR_PLL_Mask; + /* Set the PLL configuration bits */ + tmpreg |= RCC_PLLSource | RCC_PLLMul; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Enables or disables the PLL. + * @note The PLL can not be disabled if it is used as system clock. + * @param NewState: new state of the PLL. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLLCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState; +} + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) +/** + * @brief Configures the PREDIV1 division factor. + * @note + * - This function must be used only when the PLL is disabled. + * - This function applies only to STM32 Connectivity line and Value line + * devices. + * @param RCC_PREDIV1_Source: specifies the PREDIV1 clock source. + * This parameter can be one of the following values: + * @arg RCC_PREDIV1_Source_HSE: HSE selected as PREDIV1 clock + * @arg RCC_PREDIV1_Source_PLL2: PLL2 selected as PREDIV1 clock + * @note + * For @b STM32_Value_line_devices this parameter is always RCC_PREDIV1_Source_HSE + * @param RCC_PREDIV1_Div: specifies the PREDIV1 clock division factor. + * This parameter can be RCC_PREDIV1_Divx where x:[1,16] + * @retval None + */ +void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PREDIV1_SOURCE(RCC_PREDIV1_Source)); + assert_param(IS_RCC_PREDIV1(RCC_PREDIV1_Div)); + + tmpreg = RCC->CFGR2; + /* Clear PREDIV1[3:0] and PREDIV1SRC bits */ + tmpreg &= ~(CFGR2_PREDIV1 | CFGR2_PREDIV1SRC); + /* Set the PREDIV1 clock source and division factor */ + tmpreg |= RCC_PREDIV1_Source | RCC_PREDIV1_Div ; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} +#endif + +#ifdef STM32F10X_CL +/** + * @brief Configures the PREDIV2 division factor. + * @note + * - This function must be used only when both PLL2 and PLL3 are disabled. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_PREDIV2_Div: specifies the PREDIV2 clock division factor. + * This parameter can be RCC_PREDIV2_Divx where x:[1,16] + * @retval None + */ +void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PREDIV2(RCC_PREDIV2_Div)); + + tmpreg = RCC->CFGR2; + /* Clear PREDIV2[3:0] bits */ + tmpreg &= ~CFGR2_PREDIV2; + /* Set the PREDIV2 division factor */ + tmpreg |= RCC_PREDIV2_Div; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} + +/** + * @brief Configures the PLL2 multiplication factor. + * @note + * - This function must be used only when the PLL2 is disabled. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_PLL2Mul: specifies the PLL2 multiplication factor. + * This parameter can be RCC_PLL2Mul_x where x:{[8,14], 16, 20} + * @retval None + */ +void RCC_PLL2Config(uint32_t RCC_PLL2Mul) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PLL2_MUL(RCC_PLL2Mul)); + + tmpreg = RCC->CFGR2; + /* Clear PLL2Mul[3:0] bits */ + tmpreg &= ~CFGR2_PLL2MUL; + /* Set the PLL2 configuration bits */ + tmpreg |= RCC_PLL2Mul; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} + + +/** + * @brief Enables or disables the PLL2. + * @note + * - The PLL2 can not be disabled if it is used indirectly as system clock + * (i.e. it is used as PLL clock entry that is used as System clock). + * - This function applies only to STM32 Connectivity line devices. + * @param NewState: new state of the PLL2. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLL2Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_PLL2ON_BB = (uint32_t)NewState; +} + + +/** + * @brief Configures the PLL3 multiplication factor. + * @note + * - This function must be used only when the PLL3 is disabled. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_PLL3Mul: specifies the PLL3 multiplication factor. + * This parameter can be RCC_PLL3Mul_x where x:{[8,14], 16, 20} + * @retval None + */ +void RCC_PLL3Config(uint32_t RCC_PLL3Mul) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PLL3_MUL(RCC_PLL3Mul)); + + tmpreg = RCC->CFGR2; + /* Clear PLL3Mul[3:0] bits */ + tmpreg &= ~CFGR2_PLL3MUL; + /* Set the PLL3 configuration bits */ + tmpreg |= RCC_PLL3Mul; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} + + +/** + * @brief Enables or disables the PLL3. + * @note This function applies only to STM32 Connectivity line devices. + * @param NewState: new state of the PLL3. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLL3Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_PLL3ON_BB = (uint32_t)NewState; +} +#endif /* STM32F10X_CL */ + +/** + * @brief Configures the system clock (SYSCLK). + * @param RCC_SYSCLKSource: specifies the clock source used as system clock. + * This parameter can be one of the following values: + * @arg RCC_SYSCLKSource_HSI: HSI selected as system clock + * @arg RCC_SYSCLKSource_HSE: HSE selected as system clock + * @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock + * @retval None + */ +void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource)); + tmpreg = RCC->CFGR; + /* Clear SW[1:0] bits */ + tmpreg &= CFGR_SW_Mask; + /* Set SW[1:0] bits according to RCC_SYSCLKSource value */ + tmpreg |= RCC_SYSCLKSource; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Returns the clock source used as system clock. + * @param None + * @retval The clock source used as system clock. The returned value can + * be one of the following: + * - 0x00: HSI used as system clock + * - 0x04: HSE used as system clock + * - 0x08: PLL used as system clock + */ +uint8_t RCC_GetSYSCLKSource(void) +{ + return ((uint8_t)(RCC->CFGR & CFGR_SWS_Mask)); +} + +/** + * @brief Configures the AHB clock (HCLK). + * @param RCC_SYSCLK: defines the AHB clock divider. This clock is derived from + * the system clock (SYSCLK). + * This parameter can be one of the following values: + * @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK + * @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2 + * @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4 + * @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8 + * @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16 + * @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64 + * @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128 + * @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256 + * @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512 + * @retval None + */ +void RCC_HCLKConfig(uint32_t RCC_SYSCLK) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_HCLK(RCC_SYSCLK)); + tmpreg = RCC->CFGR; + /* Clear HPRE[3:0] bits */ + tmpreg &= CFGR_HPRE_Reset_Mask; + /* Set HPRE[3:0] bits according to RCC_SYSCLK value */ + tmpreg |= RCC_SYSCLK; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Configures the Low Speed APB clock (PCLK1). + * @param RCC_HCLK: defines the APB1 clock divider. This clock is derived from + * the AHB clock (HCLK). + * This parameter can be one of the following values: + * @arg RCC_HCLK_Div1: APB1 clock = HCLK + * @arg RCC_HCLK_Div2: APB1 clock = HCLK/2 + * @arg RCC_HCLK_Div4: APB1 clock = HCLK/4 + * @arg RCC_HCLK_Div8: APB1 clock = HCLK/8 + * @arg RCC_HCLK_Div16: APB1 clock = HCLK/16 + * @retval None + */ +void RCC_PCLK1Config(uint32_t RCC_HCLK) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_PCLK(RCC_HCLK)); + tmpreg = RCC->CFGR; + /* Clear PPRE1[2:0] bits */ + tmpreg &= CFGR_PPRE1_Reset_Mask; + /* Set PPRE1[2:0] bits according to RCC_HCLK value */ + tmpreg |= RCC_HCLK; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Configures the High Speed APB clock (PCLK2). + * @param RCC_HCLK: defines the APB2 clock divider. This clock is derived from + * the AHB clock (HCLK). + * This parameter can be one of the following values: + * @arg RCC_HCLK_Div1: APB2 clock = HCLK + * @arg RCC_HCLK_Div2: APB2 clock = HCLK/2 + * @arg RCC_HCLK_Div4: APB2 clock = HCLK/4 + * @arg RCC_HCLK_Div8: APB2 clock = HCLK/8 + * @arg RCC_HCLK_Div16: APB2 clock = HCLK/16 + * @retval None + */ +void RCC_PCLK2Config(uint32_t RCC_HCLK) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_PCLK(RCC_HCLK)); + tmpreg = RCC->CFGR; + /* Clear PPRE2[2:0] bits */ + tmpreg &= CFGR_PPRE2_Reset_Mask; + /* Set PPRE2[2:0] bits according to RCC_HCLK value */ + tmpreg |= RCC_HCLK << 3; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Enables or disables the specified RCC interrupts. + * @param RCC_IT: specifies the RCC interrupt sources to be enabled or disabled. + * + * For @b STM32_Connectivity_line_devices, this parameter can be any combination + * of the following values + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt + * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt + * + * For @b other_STM32_devices, this parameter can be any combination of the + * following values + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * + * @param NewState: new state of the specified RCC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_IT(RCC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Perform Byte access to RCC_CIR bits to enable the selected interrupts */ + *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT; + } + else + { + /* Perform Byte access to RCC_CIR bits to disable the selected interrupts */ + *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT; + } +} + +#ifndef STM32F10X_CL +/** + * @brief Configures the USB clock (USBCLK). + * @param RCC_USBCLKSource: specifies the USB clock source. This clock is + * derived from the PLL output. + * This parameter can be one of the following values: + * @arg RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB + * clock source + * @arg RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB clock source + * @retval None + */ +void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource)); + + *(__IO uint32_t *) CFGR_USBPRE_BB = RCC_USBCLKSource; +} +#else +/** + * @brief Configures the USB OTG FS clock (OTGFSCLK). + * This function applies only to STM32 Connectivity line devices. + * @param RCC_OTGFSCLKSource: specifies the USB OTG FS clock source. + * This clock is derived from the PLL output. + * This parameter can be one of the following values: + * @arg RCC_OTGFSCLKSource_PLLVCO_Div3: PLL VCO clock divided by 2 selected as USB OTG FS clock source + * @arg RCC_OTGFSCLKSource_PLLVCO_Div2: PLL VCO clock divided by 2 selected as USB OTG FS clock source + * @retval None + */ +void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_OTGFSCLK_SOURCE(RCC_OTGFSCLKSource)); + + *(__IO uint32_t *) CFGR_OTGFSPRE_BB = RCC_OTGFSCLKSource; +} +#endif /* STM32F10X_CL */ + +/** + * @brief Configures the ADC clock (ADCCLK). + * @param RCC_PCLK2: defines the ADC clock divider. This clock is derived from + * the APB2 clock (PCLK2). + * This parameter can be one of the following values: + * @arg RCC_PCLK2_Div2: ADC clock = PCLK2/2 + * @arg RCC_PCLK2_Div4: ADC clock = PCLK2/4 + * @arg RCC_PCLK2_Div6: ADC clock = PCLK2/6 + * @arg RCC_PCLK2_Div8: ADC clock = PCLK2/8 + * @retval None + */ +void RCC_ADCCLKConfig(uint32_t RCC_PCLK2) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_ADCCLK(RCC_PCLK2)); + tmpreg = RCC->CFGR; + /* Clear ADCPRE[1:0] bits */ + tmpreg &= CFGR_ADCPRE_Reset_Mask; + /* Set ADCPRE[1:0] bits according to RCC_PCLK2 value */ + tmpreg |= RCC_PCLK2; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +#ifdef STM32F10X_CL +/** + * @brief Configures the I2S2 clock source(I2S2CLK). + * @note + * - This function must be called before enabling I2S2 APB clock. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_I2S2CLKSource: specifies the I2S2 clock source. + * This parameter can be one of the following values: + * @arg RCC_I2S2CLKSource_SYSCLK: system clock selected as I2S2 clock entry + * @arg RCC_I2S2CLKSource_PLL3_VCO: PLL3 VCO clock selected as I2S2 clock entry + * @retval None + */ +void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_I2S2CLK_SOURCE(RCC_I2S2CLKSource)); + + *(__IO uint32_t *) CFGR2_I2S2SRC_BB = RCC_I2S2CLKSource; +} + +/** + * @brief Configures the I2S3 clock source(I2S2CLK). + * @note + * - This function must be called before enabling I2S3 APB clock. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_I2S3CLKSource: specifies the I2S3 clock source. + * This parameter can be one of the following values: + * @arg RCC_I2S3CLKSource_SYSCLK: system clock selected as I2S3 clock entry + * @arg RCC_I2S3CLKSource_PLL3_VCO: PLL3 VCO clock selected as I2S3 clock entry + * @retval None + */ +void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_I2S3CLK_SOURCE(RCC_I2S3CLKSource)); + + *(__IO uint32_t *) CFGR2_I2S3SRC_BB = RCC_I2S3CLKSource; +} +#endif /* STM32F10X_CL */ + +/** + * @brief Configures the External Low Speed oscillator (LSE). + * @param RCC_LSE: specifies the new state of the LSE. + * This parameter can be one of the following values: + * @arg RCC_LSE_OFF: LSE oscillator OFF + * @arg RCC_LSE_ON: LSE oscillator ON + * @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock + * @retval None + */ +void RCC_LSEConfig(uint8_t RCC_LSE) +{ + /* Check the parameters */ + assert_param(IS_RCC_LSE(RCC_LSE)); + /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/ + /* Reset LSEON bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF; + /* Reset LSEBYP bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF; + /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */ + switch(RCC_LSE) + { + case RCC_LSE_ON: + /* Set LSEON bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_ON; + break; + + case RCC_LSE_Bypass: + /* Set LSEBYP and LSEON bits */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON; + break; + + default: + break; + } +} + +/** + * @brief Enables or disables the Internal Low Speed oscillator (LSI). + * @note LSI can not be disabled if the IWDG is running. + * @param NewState: new state of the LSI. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_LSICmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the RTC clock (RTCCLK). + * @note Once the RTC clock is selected it can’t be changed unless the Backup domain is reset. + * @param RCC_RTCCLKSource: specifies the RTC clock source. + * This parameter can be one of the following values: + * @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock + * @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock + * @arg RCC_RTCCLKSource_HSE_Div128: HSE clock divided by 128 selected as RTC clock + * @retval None + */ +void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource)); + /* Select the RTC clock source */ + RCC->BDCR |= RCC_RTCCLKSource; +} + +/** + * @brief Enables or disables the RTC clock. + * @note This function must be used only after the RTC clock was selected using the RCC_RTCCLKConfig function. + * @param NewState: new state of the RTC clock. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_RTCCLKCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState; +} + +/** + * @brief Returns the frequencies of different on chip clocks. + * @param RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold + * the clocks frequencies. + * @note The result of this function could be not correct when using + * fractional value for HSE crystal. + * @retval None + */ +void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0, presc = 0; + +#ifdef STM32F10X_CL + uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0; +#endif /* STM32F10X_CL */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + uint32_t prediv1factor = 0; +#endif + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & CFGR_SWS_Mask; + + switch (tmp) + { + case 0x00: /* HSI used as system clock */ + RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + RCC_Clocks->SYSCLK_Frequency = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock */ + + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & CFGR_PLLMull_Mask; + pllsource = RCC->CFGR & CFGR_PLLSRC_Mask; + +#ifndef STM32F10X_CL + pllmull = ( pllmull >> 18) + 2; + + if (pllsource == 0x00) + {/* HSI oscillator clock divided by 2 selected as PLL clock entry */ + RCC_Clocks->SYSCLK_Frequency = (HSI_VALUE >> 1) * pllmull; + } + else + { + #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1; + /* HSE oscillator clock selected as PREDIV1 clock entry */ + RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE / prediv1factor) * pllmull; + #else + /* HSE selected as PLL clock entry */ + if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (uint32_t)RESET) + {/* HSE oscillator clock divided by 2 */ + RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE >> 1) * pllmull; + } + else + { + RCC_Clocks->SYSCLK_Frequency = HSE_VALUE * pllmull; + } + #endif + } +#else + pllmull = pllmull >> 18; + + if (pllmull != 0x0D) + { + pllmull += 2; + } + else + { /* PLL multiplication factor = PLL input clock * 6.5 */ + pllmull = 13 / 2; + } + + if (pllsource == 0x00) + {/* HSI oscillator clock divided by 2 selected as PLL clock entry */ + RCC_Clocks->SYSCLK_Frequency = (HSI_VALUE >> 1) * pllmull; + } + else + {/* PREDIV1 selected as PLL clock entry */ + + /* Get PREDIV1 clock source and division factor */ + prediv1source = RCC->CFGR2 & CFGR2_PREDIV1SRC; + prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1; + + if (prediv1source == 0) + { /* HSE oscillator clock selected as PREDIV1 clock entry */ + RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE / prediv1factor) * pllmull; + } + else + {/* PLL2 clock selected as PREDIV1 clock entry */ + + /* Get PREDIV2 division factor and PLL2 multiplication factor */ + prediv2factor = ((RCC->CFGR2 & CFGR2_PREDIV2) >> 4) + 1; + pll2mull = ((RCC->CFGR2 & CFGR2_PLL2MUL) >> 8 ) + 2; + RCC_Clocks->SYSCLK_Frequency = (((HSE_VALUE / prediv2factor) * pll2mull) / prediv1factor) * pllmull; + } + } +#endif /* STM32F10X_CL */ + break; + + default: + RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; + break; + } + + /* Compute HCLK, PCLK1, PCLK2 and ADCCLK clocks frequencies ----------------*/ + /* Get HCLK prescaler */ + tmp = RCC->CFGR & CFGR_HPRE_Set_Mask; + tmp = tmp >> 4; + presc = APBAHBPrescTable[tmp]; + /* HCLK clock frequency */ + RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc; + /* Get PCLK1 prescaler */ + tmp = RCC->CFGR & CFGR_PPRE1_Set_Mask; + tmp = tmp >> 8; + presc = APBAHBPrescTable[tmp]; + /* PCLK1 clock frequency */ + RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc; + /* Get PCLK2 prescaler */ + tmp = RCC->CFGR & CFGR_PPRE2_Set_Mask; + tmp = tmp >> 11; + presc = APBAHBPrescTable[tmp]; + /* PCLK2 clock frequency */ + RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc; + /* Get ADCCLK prescaler */ + tmp = RCC->CFGR & CFGR_ADCPRE_Set_Mask; + tmp = tmp >> 14; + presc = ADCPrescTable[tmp]; + /* ADCCLK clock frequency */ + RCC_Clocks->ADCCLK_Frequency = RCC_Clocks->PCLK2_Frequency / presc; +} + +/** + * @brief Enables or disables the AHB peripheral clock. + * @param RCC_AHBPeriph: specifies the AHB peripheral to gates its clock. + * + * For @b STM32_Connectivity_line_devices, this parameter can be any combination + * of the following values: + * @arg RCC_AHBPeriph_DMA1 + * @arg RCC_AHBPeriph_DMA2 + * @arg RCC_AHBPeriph_SRAM + * @arg RCC_AHBPeriph_FLITF + * @arg RCC_AHBPeriph_CRC + * @arg RCC_AHBPeriph_OTG_FS + * @arg RCC_AHBPeriph_ETH_MAC + * @arg RCC_AHBPeriph_ETH_MAC_Tx + * @arg RCC_AHBPeriph_ETH_MAC_Rx + * + * For @b other_STM32_devices, this parameter can be any combination of the + * following values: + * @arg RCC_AHBPeriph_DMA1 + * @arg RCC_AHBPeriph_DMA2 + * @arg RCC_AHBPeriph_SRAM + * @arg RCC_AHBPeriph_FLITF + * @arg RCC_AHBPeriph_CRC + * @arg RCC_AHBPeriph_FSMC + * @arg RCC_AHBPeriph_SDIO + * + * @note SRAM and FLITF clock can be disabled only during sleep mode. + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHBENR |= RCC_AHBPeriph; + } + else + { + RCC->AHBENR &= ~RCC_AHBPeriph; + } +} + +/** + * @brief Enables or disables the High Speed APB (APB2) peripheral clock. + * @param RCC_APB2Periph: specifies the APB2 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, + * RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, + * RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, + * RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, + * RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, + * RCC_APB2Periph_TIM15, RCC_APB2Periph_TIM16, RCC_APB2Periph_TIM17, + * RCC_APB2Periph_TIM9, RCC_APB2Periph_TIM10, RCC_APB2Periph_TIM11 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB2ENR |= RCC_APB2Periph; + } + else + { + RCC->APB2ENR &= ~RCC_APB2Periph; + } +} + +/** + * @brief Enables or disables the Low Speed APB (APB1) peripheral clock. + * @param RCC_APB1Periph: specifies the APB1 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, + * RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, + * RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, + * RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, + * RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, + * RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP, + * RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_CEC, + * RCC_APB1Periph_TIM12, RCC_APB1Periph_TIM13, RCC_APB1Periph_TIM14 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB1ENR |= RCC_APB1Periph; + } + else + { + RCC->APB1ENR &= ~RCC_APB1Periph; + } +} + +#ifdef STM32F10X_CL +/** + * @brief Forces or releases AHB peripheral reset. + * @note This function applies only to STM32 Connectivity line devices. + * @param RCC_AHBPeriph: specifies the AHB peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_AHBPeriph_OTG_FS + * @arg RCC_AHBPeriph_ETH_MAC + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB_PERIPH_RESET(RCC_AHBPeriph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHBRSTR |= RCC_AHBPeriph; + } + else + { + RCC->AHBRSTR &= ~RCC_AHBPeriph; + } +} +#endif /* STM32F10X_CL */ + +/** + * @brief Forces or releases High Speed APB (APB2) peripheral reset. + * @param RCC_APB2Periph: specifies the APB2 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, + * RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, + * RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, + * RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, + * RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, + * RCC_APB2Periph_TIM15, RCC_APB2Periph_TIM16, RCC_APB2Periph_TIM17, + * RCC_APB2Periph_TIM9, RCC_APB2Periph_TIM10, RCC_APB2Periph_TIM11 + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB2RSTR |= RCC_APB2Periph; + } + else + { + RCC->APB2RSTR &= ~RCC_APB2Periph; + } +} + +/** + * @brief Forces or releases Low Speed APB (APB1) peripheral reset. + * @param RCC_APB1Periph: specifies the APB1 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, + * RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, + * RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, + * RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, + * RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, + * RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP, + * RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_CEC, + * RCC_APB1Periph_TIM12, RCC_APB1Periph_TIM13, RCC_APB1Periph_TIM14 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB1RSTR |= RCC_APB1Periph; + } + else + { + RCC->APB1RSTR &= ~RCC_APB1Periph; + } +} + +/** + * @brief Forces or releases the Backup domain reset. + * @param NewState: new state of the Backup domain reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_BackupResetCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the Clock Security System. + * @param NewState: new state of the Clock Security System.. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_ClockSecuritySystemCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState; +} + +/** + * @brief Selects the clock source to output on MCO pin. + * @param RCC_MCO: specifies the clock source to output. + * + * For @b STM32_Connectivity_line_devices, this parameter can be one of the + * following values: + * @arg RCC_MCO_NoClock: No clock selected + * @arg RCC_MCO_SYSCLK: System clock selected + * @arg RCC_MCO_HSI: HSI oscillator clock selected + * @arg RCC_MCO_HSE: HSE oscillator clock selected + * @arg RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected + * @arg RCC_MCO_PLL2CLK: PLL2 clock selected + * @arg RCC_MCO_PLL3CLK_Div2: PLL3 clock divided by 2 selected + * @arg RCC_MCO_XT1: External 3-25 MHz oscillator clock selected + * @arg RCC_MCO_PLL3CLK: PLL3 clock selected + * + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_MCO_NoClock: No clock selected + * @arg RCC_MCO_SYSCLK: System clock selected + * @arg RCC_MCO_HSI: HSI oscillator clock selected + * @arg RCC_MCO_HSE: HSE oscillator clock selected + * @arg RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected + * + * @retval None + */ +void RCC_MCOConfig(uint8_t RCC_MCO) +{ + /* Check the parameters */ + assert_param(IS_RCC_MCO(RCC_MCO)); + + /* Perform Byte access to MCO bits to select the MCO source */ + *(__IO uint8_t *) CFGR_BYTE4_ADDRESS = RCC_MCO; +} + +/** + * @brief Checks whether the specified RCC flag is set or not. + * @param RCC_FLAG: specifies the flag to check. + * + * For @b STM32_Connectivity_line_devices, this parameter can be one of the + * following values: + * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready + * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready + * @arg RCC_FLAG_PLLRDY: PLL clock ready + * @arg RCC_FLAG_PLL2RDY: PLL2 clock ready + * @arg RCC_FLAG_PLL3RDY: PLL3 clock ready + * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready + * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready + * @arg RCC_FLAG_PINRST: Pin reset + * @arg RCC_FLAG_PORRST: POR/PDR reset + * @arg RCC_FLAG_SFTRST: Software reset + * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset + * @arg RCC_FLAG_WWDGRST: Window Watchdog reset + * @arg RCC_FLAG_LPWRRST: Low Power reset + * + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready + * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready + * @arg RCC_FLAG_PLLRDY: PLL clock ready + * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready + * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready + * @arg RCC_FLAG_PINRST: Pin reset + * @arg RCC_FLAG_PORRST: POR/PDR reset + * @arg RCC_FLAG_SFTRST: Software reset + * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset + * @arg RCC_FLAG_WWDGRST: Window Watchdog reset + * @arg RCC_FLAG_LPWRRST: Low Power reset + * + * @retval The new state of RCC_FLAG (SET or RESET). + */ +FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG) +{ + uint32_t tmp = 0; + uint32_t statusreg = 0; + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RCC_FLAG(RCC_FLAG)); + + /* Get the RCC register index */ + tmp = RCC_FLAG >> 5; + if (tmp == 1) /* The flag to check is in CR register */ + { + statusreg = RCC->CR; + } + else if (tmp == 2) /* The flag to check is in BDCR register */ + { + statusreg = RCC->BDCR; + } + else /* The flag to check is in CSR register */ + { + statusreg = RCC->CSR; + } + + /* Get the flag position */ + tmp = RCC_FLAG & FLAG_Mask; + if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the RCC reset flags. + * @note The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, + * RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST + * @param None + * @retval None + */ +void RCC_ClearFlag(void) +{ + /* Set RMVF bit to clear the reset flags */ + RCC->CSR |= CSR_RMVF_Set; +} + +/** + * @brief Checks whether the specified RCC interrupt has occurred or not. + * @param RCC_IT: specifies the RCC interrupt source to check. + * + * For @b STM32_Connectivity_line_devices, this parameter can be one of the + * following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt + * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * + * @retval The new state of RCC_IT (SET or RESET). + */ +ITStatus RCC_GetITStatus(uint8_t RCC_IT) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RCC_GET_IT(RCC_IT)); + + /* Check the status of the specified RCC interrupt */ + if ((RCC->CIR & RCC_IT) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + /* Return the RCC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the RCC’s interrupt pending bits. + * @param RCC_IT: specifies the interrupt pending bit to clear. + * + * For @b STM32_Connectivity_line_devices, this parameter can be any combination + * of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt + * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * + * For @b other_STM32_devices, this parameter can be any combination of the + * following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * + * @arg RCC_IT_CSS: Clock Security System interrupt + * @retval None + */ +void RCC_ClearITPendingBit(uint8_t RCC_IT) +{ + /* Check the parameters */ + assert_param(IS_RCC_CLEAR_IT(RCC_IT)); + + /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt + pending bits */ + *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c index dc69f64bf..2478e2515 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c @@ -1,338 +1,338 @@ -/** - ****************************************************************************** - * @file stm32f10x_rtc.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the RTC firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_rtc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup RTC - * @brief RTC driver modules - * @{ - */ - -/** @defgroup RTC_Private_TypesDefinitions - * @{ - */ -/** - * @} - */ - -/** @defgroup RTC_Private_Defines - * @{ - */ -#define RTC_LSB_MASK ((uint32_t)0x0000FFFF) /*!< RTC LSB Mask */ -#define PRLH_MSB_MASK ((uint32_t)0x000F0000) /*!< RTC Prescaler MSB Mask */ - -/** - * @} - */ - -/** @defgroup RTC_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup RTC_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup RTC_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup RTC_Private_Functions - * @{ - */ - -/** - * @brief Enables or disables the specified RTC interrupts. - * @param RTC_IT: specifies the RTC interrupts sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg RTC_IT_OW: Overflow interrupt - * @arg RTC_IT_ALR: Alarm interrupt - * @arg RTC_IT_SEC: Second interrupt - * @param NewState: new state of the specified RTC interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_RTC_IT(RTC_IT)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - RTC->CRH |= RTC_IT; - } - else - { - RTC->CRH &= (uint16_t)~RTC_IT; - } -} - -/** - * @brief Enters the RTC configuration mode. - * @param None - * @retval None - */ -void RTC_EnterConfigMode(void) -{ - /* Set the CNF flag to enter in the Configuration Mode */ - RTC->CRL |= RTC_CRL_CNF; -} - -/** - * @brief Exits from the RTC configuration mode. - * @param None - * @retval None - */ -void RTC_ExitConfigMode(void) -{ - /* Reset the CNF flag to exit from the Configuration Mode */ - RTC->CRL &= (uint16_t)~((uint16_t)RTC_CRL_CNF); -} - -/** - * @brief Gets the RTC counter value. - * @param None - * @retval RTC counter value. - */ -uint32_t RTC_GetCounter(void) -{ - uint16_t tmp = 0; - tmp = RTC->CNTL; - return (((uint32_t)RTC->CNTH << 16 ) | tmp) ; -} - -/** - * @brief Sets the RTC counter value. - * @param CounterValue: RTC counter new value. - * @retval None - */ -void RTC_SetCounter(uint32_t CounterValue) -{ - RTC_EnterConfigMode(); - /* Set RTC COUNTER MSB word */ - RTC->CNTH = CounterValue >> 16; - /* Set RTC COUNTER LSB word */ - RTC->CNTL = (CounterValue & RTC_LSB_MASK); - RTC_ExitConfigMode(); -} - -/** - * @brief Sets the RTC prescaler value. - * @param PrescalerValue: RTC prescaler new value. - * @retval None - */ -void RTC_SetPrescaler(uint32_t PrescalerValue) -{ - /* Check the parameters */ - assert_param(IS_RTC_PRESCALER(PrescalerValue)); - - RTC_EnterConfigMode(); - /* Set RTC PRESCALER MSB word */ - RTC->PRLH = (PrescalerValue & PRLH_MSB_MASK) >> 16; - /* Set RTC PRESCALER LSB word */ - RTC->PRLL = (PrescalerValue & RTC_LSB_MASK); - RTC_ExitConfigMode(); -} - -/** - * @brief Sets the RTC alarm value. - * @param AlarmValue: RTC alarm new value. - * @retval None - */ -void RTC_SetAlarm(uint32_t AlarmValue) -{ - RTC_EnterConfigMode(); - /* Set the ALARM MSB word */ - RTC->ALRH = AlarmValue >> 16; - /* Set the ALARM LSB word */ - RTC->ALRL = (AlarmValue & RTC_LSB_MASK); - RTC_ExitConfigMode(); -} - -/** - * @brief Gets the RTC divider value. - * @param None - * @retval RTC Divider value. - */ -uint32_t RTC_GetDivider(void) -{ - uint32_t tmp = 0x00; - tmp = ((uint32_t)RTC->DIVH & (uint32_t)0x000F) << 16; - tmp |= RTC->DIVL; - return tmp; -} - -/** - * @brief Waits until last write operation on RTC registers has finished. - * @note This function must be called before any write to RTC registers. - * @param None - * @retval None - */ -void RTC_WaitForLastTask(void) -{ - /* Loop until RTOFF flag is set */ - while ((RTC->CRL & RTC_FLAG_RTOFF) == (uint16_t)RESET) - { - } -} - -/** - * @brief Waits until the RTC registers (RTC_CNT, RTC_ALR and RTC_PRL) - * are synchronized with RTC APB clock. - * @note This function must be called before any read operation after an APB reset - * or an APB clock stop. - * @param None - * @retval None - */ -void RTC_WaitForSynchro(void) -{ - /* Clear RSF flag */ - RTC->CRL &= (uint16_t)~RTC_FLAG_RSF; - /* Loop until RSF flag is set */ - while ((RTC->CRL & RTC_FLAG_RSF) == (uint16_t)RESET) - { - } -} - -/** - * @brief Checks whether the specified RTC flag is set or not. - * @param RTC_FLAG: specifies the flag to check. - * This parameter can be one the following values: - * @arg RTC_FLAG_RTOFF: RTC Operation OFF flag - * @arg RTC_FLAG_RSF: Registers Synchronized flag - * @arg RTC_FLAG_OW: Overflow flag - * @arg RTC_FLAG_ALR: Alarm flag - * @arg RTC_FLAG_SEC: Second flag - * @retval The new state of RTC_FLAG (SET or RESET). - */ -FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG) -{ - FlagStatus bitstatus = RESET; - - /* Check the parameters */ - assert_param(IS_RTC_GET_FLAG(RTC_FLAG)); - - if ((RTC->CRL & RTC_FLAG) != (uint16_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - return bitstatus; -} - -/** - * @brief Clears the RTC’s pending flags. - * @param RTC_FLAG: specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg RTC_FLAG_RSF: Registers Synchronized flag. This flag is cleared only after - * an APB reset or an APB Clock stop. - * @arg RTC_FLAG_OW: Overflow flag - * @arg RTC_FLAG_ALR: Alarm flag - * @arg RTC_FLAG_SEC: Second flag - * @retval None - */ -void RTC_ClearFlag(uint16_t RTC_FLAG) -{ - /* Check the parameters */ - assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG)); - - /* Clear the coressponding RTC flag */ - RTC->CRL &= (uint16_t)~RTC_FLAG; -} - -/** - * @brief Checks whether the specified RTC interrupt has occured or not. - * @param RTC_IT: specifies the RTC interrupts sources to check. - * This parameter can be one of the following values: - * @arg RTC_IT_OW: Overflow interrupt - * @arg RTC_IT_ALR: Alarm interrupt - * @arg RTC_IT_SEC: Second interrupt - * @retval The new state of the RTC_IT (SET or RESET). - */ -ITStatus RTC_GetITStatus(uint16_t RTC_IT) -{ - ITStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_RTC_GET_IT(RTC_IT)); - - bitstatus = (ITStatus)(RTC->CRL & RTC_IT); - if (((RTC->CRH & RTC_IT) != (uint16_t)RESET) && (bitstatus != (uint16_t)RESET)) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - return bitstatus; -} - -/** - * @brief Clears the RTC’s interrupt pending bits. - * @param RTC_IT: specifies the interrupt pending bit to clear. - * This parameter can be any combination of the following values: - * @arg RTC_IT_OW: Overflow interrupt - * @arg RTC_IT_ALR: Alarm interrupt - * @arg RTC_IT_SEC: Second interrupt - * @retval None - */ -void RTC_ClearITPendingBit(uint16_t RTC_IT) -{ - /* Check the parameters */ - assert_param(IS_RTC_IT(RTC_IT)); - - /* Clear the coressponding RTC pending bit */ - RTC->CRL &= (uint16_t)~RTC_IT; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_rtc.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the RTC firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_rtc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup RTC + * @brief RTC driver modules + * @{ + */ + +/** @defgroup RTC_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + +/** @defgroup RTC_Private_Defines + * @{ + */ +#define RTC_LSB_MASK ((uint32_t)0x0000FFFF) /*!< RTC LSB Mask */ +#define PRLH_MSB_MASK ((uint32_t)0x000F0000) /*!< RTC Prescaler MSB Mask */ + +/** + * @} + */ + +/** @defgroup RTC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Private_Functions + * @{ + */ + +/** + * @brief Enables or disables the specified RTC interrupts. + * @param RTC_IT: specifies the RTC interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg RTC_IT_OW: Overflow interrupt + * @arg RTC_IT_ALR: Alarm interrupt + * @arg RTC_IT_SEC: Second interrupt + * @param NewState: new state of the specified RTC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RTC_IT(RTC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RTC->CRH |= RTC_IT; + } + else + { + RTC->CRH &= (uint16_t)~RTC_IT; + } +} + +/** + * @brief Enters the RTC configuration mode. + * @param None + * @retval None + */ +void RTC_EnterConfigMode(void) +{ + /* Set the CNF flag to enter in the Configuration Mode */ + RTC->CRL |= RTC_CRL_CNF; +} + +/** + * @brief Exits from the RTC configuration mode. + * @param None + * @retval None + */ +void RTC_ExitConfigMode(void) +{ + /* Reset the CNF flag to exit from the Configuration Mode */ + RTC->CRL &= (uint16_t)~((uint16_t)RTC_CRL_CNF); +} + +/** + * @brief Gets the RTC counter value. + * @param None + * @retval RTC counter value. + */ +uint32_t RTC_GetCounter(void) +{ + uint16_t tmp = 0; + tmp = RTC->CNTL; + return (((uint32_t)RTC->CNTH << 16 ) | tmp) ; +} + +/** + * @brief Sets the RTC counter value. + * @param CounterValue: RTC counter new value. + * @retval None + */ +void RTC_SetCounter(uint32_t CounterValue) +{ + RTC_EnterConfigMode(); + /* Set RTC COUNTER MSB word */ + RTC->CNTH = CounterValue >> 16; + /* Set RTC COUNTER LSB word */ + RTC->CNTL = (CounterValue & RTC_LSB_MASK); + RTC_ExitConfigMode(); +} + +/** + * @brief Sets the RTC prescaler value. + * @param PrescalerValue: RTC prescaler new value. + * @retval None + */ +void RTC_SetPrescaler(uint32_t PrescalerValue) +{ + /* Check the parameters */ + assert_param(IS_RTC_PRESCALER(PrescalerValue)); + + RTC_EnterConfigMode(); + /* Set RTC PRESCALER MSB word */ + RTC->PRLH = (PrescalerValue & PRLH_MSB_MASK) >> 16; + /* Set RTC PRESCALER LSB word */ + RTC->PRLL = (PrescalerValue & RTC_LSB_MASK); + RTC_ExitConfigMode(); +} + +/** + * @brief Sets the RTC alarm value. + * @param AlarmValue: RTC alarm new value. + * @retval None + */ +void RTC_SetAlarm(uint32_t AlarmValue) +{ + RTC_EnterConfigMode(); + /* Set the ALARM MSB word */ + RTC->ALRH = AlarmValue >> 16; + /* Set the ALARM LSB word */ + RTC->ALRL = (AlarmValue & RTC_LSB_MASK); + RTC_ExitConfigMode(); +} + +/** + * @brief Gets the RTC divider value. + * @param None + * @retval RTC Divider value. + */ +uint32_t RTC_GetDivider(void) +{ + uint32_t tmp = 0x00; + tmp = ((uint32_t)RTC->DIVH & (uint32_t)0x000F) << 16; + tmp |= RTC->DIVL; + return tmp; +} + +/** + * @brief Waits until last write operation on RTC registers has finished. + * @note This function must be called before any write to RTC registers. + * @param None + * @retval None + */ +void RTC_WaitForLastTask(void) +{ + /* Loop until RTOFF flag is set */ + while ((RTC->CRL & RTC_FLAG_RTOFF) == (uint16_t)RESET) + { + } +} + +/** + * @brief Waits until the RTC registers (RTC_CNT, RTC_ALR and RTC_PRL) + * are synchronized with RTC APB clock. + * @note This function must be called before any read operation after an APB reset + * or an APB clock stop. + * @param None + * @retval None + */ +void RTC_WaitForSynchro(void) +{ + /* Clear RSF flag */ + RTC->CRL &= (uint16_t)~RTC_FLAG_RSF; + /* Loop until RSF flag is set */ + while ((RTC->CRL & RTC_FLAG_RSF) == (uint16_t)RESET) + { + } +} + +/** + * @brief Checks whether the specified RTC flag is set or not. + * @param RTC_FLAG: specifies the flag to check. + * This parameter can be one the following values: + * @arg RTC_FLAG_RTOFF: RTC Operation OFF flag + * @arg RTC_FLAG_RSF: Registers Synchronized flag + * @arg RTC_FLAG_OW: Overflow flag + * @arg RTC_FLAG_ALR: Alarm flag + * @arg RTC_FLAG_SEC: Second flag + * @retval The new state of RTC_FLAG (SET or RESET). + */ +FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_RTC_GET_FLAG(RTC_FLAG)); + + if ((RTC->CRL & RTC_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the RTC’s pending flags. + * @param RTC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg RTC_FLAG_RSF: Registers Synchronized flag. This flag is cleared only after + * an APB reset or an APB Clock stop. + * @arg RTC_FLAG_OW: Overflow flag + * @arg RTC_FLAG_ALR: Alarm flag + * @arg RTC_FLAG_SEC: Second flag + * @retval None + */ +void RTC_ClearFlag(uint16_t RTC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG)); + + /* Clear the coressponding RTC flag */ + RTC->CRL &= (uint16_t)~RTC_FLAG; +} + +/** + * @brief Checks whether the specified RTC interrupt has occured or not. + * @param RTC_IT: specifies the RTC interrupts sources to check. + * This parameter can be one of the following values: + * @arg RTC_IT_OW: Overflow interrupt + * @arg RTC_IT_ALR: Alarm interrupt + * @arg RTC_IT_SEC: Second interrupt + * @retval The new state of the RTC_IT (SET or RESET). + */ +ITStatus RTC_GetITStatus(uint16_t RTC_IT) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RTC_GET_IT(RTC_IT)); + + bitstatus = (ITStatus)(RTC->CRL & RTC_IT); + if (((RTC->CRH & RTC_IT) != (uint16_t)RESET) && (bitstatus != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the RTC’s interrupt pending bits. + * @param RTC_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg RTC_IT_OW: Overflow interrupt + * @arg RTC_IT_ALR: Alarm interrupt + * @arg RTC_IT_SEC: Second interrupt + * @retval None + */ +void RTC_ClearITPendingBit(uint16_t RTC_IT) +{ + /* Check the parameters */ + assert_param(IS_RTC_IT(RTC_IT)); + + /* Clear the coressponding RTC pending bit */ + RTC->CRL &= (uint16_t)~RTC_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c index 732cad53b..75008e1c0 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c @@ -1,798 +1,798 @@ -/** - ****************************************************************************** - * @file stm32f10x_sdio.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the SDIO firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_sdio.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup SDIO - * @brief SDIO driver modules - * @{ - */ - -/** @defgroup SDIO_Private_TypesDefinitions - * @{ - */ - -/* ------------ SDIO registers bit address in the alias region ----------- */ -#define SDIO_OFFSET (SDIO_BASE - PERIPH_BASE) - -/* --- CLKCR Register ---*/ - -/* Alias word address of CLKEN bit */ -#define CLKCR_OFFSET (SDIO_OFFSET + 0x04) -#define CLKEN_BitNumber 0x08 -#define CLKCR_CLKEN_BB (PERIPH_BB_BASE + (CLKCR_OFFSET * 32) + (CLKEN_BitNumber * 4)) - -/* --- CMD Register ---*/ - -/* Alias word address of SDIOSUSPEND bit */ -#define CMD_OFFSET (SDIO_OFFSET + 0x0C) -#define SDIOSUSPEND_BitNumber 0x0B -#define CMD_SDIOSUSPEND_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (SDIOSUSPEND_BitNumber * 4)) - -/* Alias word address of ENCMDCOMPL bit */ -#define ENCMDCOMPL_BitNumber 0x0C -#define CMD_ENCMDCOMPL_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ENCMDCOMPL_BitNumber * 4)) - -/* Alias word address of NIEN bit */ -#define NIEN_BitNumber 0x0D -#define CMD_NIEN_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (NIEN_BitNumber * 4)) - -/* Alias word address of ATACMD bit */ -#define ATACMD_BitNumber 0x0E -#define CMD_ATACMD_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ATACMD_BitNumber * 4)) - -/* --- DCTRL Register ---*/ - -/* Alias word address of DMAEN bit */ -#define DCTRL_OFFSET (SDIO_OFFSET + 0x2C) -#define DMAEN_BitNumber 0x03 -#define DCTRL_DMAEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (DMAEN_BitNumber * 4)) - -/* Alias word address of RWSTART bit */ -#define RWSTART_BitNumber 0x08 -#define DCTRL_RWSTART_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTART_BitNumber * 4)) - -/* Alias word address of RWSTOP bit */ -#define RWSTOP_BitNumber 0x09 -#define DCTRL_RWSTOP_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTOP_BitNumber * 4)) - -/* Alias word address of RWMOD bit */ -#define RWMOD_BitNumber 0x0A -#define DCTRL_RWMOD_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWMOD_BitNumber * 4)) - -/* Alias word address of SDIOEN bit */ -#define SDIOEN_BitNumber 0x0B -#define DCTRL_SDIOEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (SDIOEN_BitNumber * 4)) - -/* ---------------------- SDIO registers bit mask ------------------------ */ - -/* --- CLKCR Register ---*/ - -/* CLKCR register clear mask */ -#define CLKCR_CLEAR_MASK ((uint32_t)0xFFFF8100) - -/* --- PWRCTRL Register ---*/ - -/* SDIO PWRCTRL Mask */ -#define PWR_PWRCTRL_MASK ((uint32_t)0xFFFFFFFC) - -/* --- DCTRL Register ---*/ - -/* SDIO DCTRL Clear Mask */ -#define DCTRL_CLEAR_MASK ((uint32_t)0xFFFFFF08) - -/* --- CMD Register ---*/ - -/* CMD Register clear mask */ -#define CMD_CLEAR_MASK ((uint32_t)0xFFFFF800) - -/* SDIO RESP Registers Address */ -#define SDIO_RESP_ADDR ((uint32_t)(SDIO_BASE + 0x14)) - -/** - * @} - */ - -/** @defgroup SDIO_Private_Defines - * @{ - */ - -/** - * @} - */ - -/** @defgroup SDIO_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup SDIO_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup SDIO_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup SDIO_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the SDIO peripheral registers to their default reset values. - * @param None - * @retval None - */ -void SDIO_DeInit(void) -{ - SDIO->POWER = 0x00000000; - SDIO->CLKCR = 0x00000000; - SDIO->ARG = 0x00000000; - SDIO->CMD = 0x00000000; - SDIO->DTIMER = 0x00000000; - SDIO->DLEN = 0x00000000; - SDIO->DCTRL = 0x00000000; - SDIO->ICR = 0x00C007FF; - SDIO->MASK = 0x00000000; -} - -/** - * @brief Initializes the SDIO peripheral according to the specified - * parameters in the SDIO_InitStruct. - * @param SDIO_InitStruct : pointer to a SDIO_InitTypeDef structure - * that contains the configuration information for the SDIO peripheral. - * @retval None - */ -void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_SDIO_CLOCK_EDGE(SDIO_InitStruct->SDIO_ClockEdge)); - assert_param(IS_SDIO_CLOCK_BYPASS(SDIO_InitStruct->SDIO_ClockBypass)); - assert_param(IS_SDIO_CLOCK_POWER_SAVE(SDIO_InitStruct->SDIO_ClockPowerSave)); - assert_param(IS_SDIO_BUS_WIDE(SDIO_InitStruct->SDIO_BusWide)); - assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(SDIO_InitStruct->SDIO_HardwareFlowControl)); - -/*---------------------------- SDIO CLKCR Configuration ------------------------*/ - /* Get the SDIO CLKCR value */ - tmpreg = SDIO->CLKCR; - - /* Clear CLKDIV, PWRSAV, BYPASS, WIDBUS, NEGEDGE, HWFC_EN bits */ - tmpreg &= CLKCR_CLEAR_MASK; - - /* Set CLKDIV bits according to SDIO_ClockDiv value */ - /* Set PWRSAV bit according to SDIO_ClockPowerSave value */ - /* Set BYPASS bit according to SDIO_ClockBypass value */ - /* Set WIDBUS bits according to SDIO_BusWide value */ - /* Set NEGEDGE bits according to SDIO_ClockEdge value */ - /* Set HWFC_EN bits according to SDIO_HardwareFlowControl value */ - tmpreg |= (SDIO_InitStruct->SDIO_ClockDiv | SDIO_InitStruct->SDIO_ClockPowerSave | - SDIO_InitStruct->SDIO_ClockBypass | SDIO_InitStruct->SDIO_BusWide | - SDIO_InitStruct->SDIO_ClockEdge | SDIO_InitStruct->SDIO_HardwareFlowControl); - - /* Write to SDIO CLKCR */ - SDIO->CLKCR = tmpreg; -} - -/** - * @brief Fills each SDIO_InitStruct member with its default value. - * @param SDIO_InitStruct: pointer to an SDIO_InitTypeDef structure which - * will be initialized. - * @retval None - */ -void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct) -{ - /* SDIO_InitStruct members default value */ - SDIO_InitStruct->SDIO_ClockDiv = 0x00; - SDIO_InitStruct->SDIO_ClockEdge = SDIO_ClockEdge_Rising; - SDIO_InitStruct->SDIO_ClockBypass = SDIO_ClockBypass_Disable; - SDIO_InitStruct->SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable; - SDIO_InitStruct->SDIO_BusWide = SDIO_BusWide_1b; - SDIO_InitStruct->SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable; -} - -/** - * @brief Enables or disables the SDIO Clock. - * @param NewState: new state of the SDIO Clock. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SDIO_ClockCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) CLKCR_CLKEN_BB = (uint32_t)NewState; -} - -/** - * @brief Sets the power status of the controller. - * @param SDIO_PowerState: new state of the Power state. - * This parameter can be one of the following values: - * @arg SDIO_PowerState_OFF - * @arg SDIO_PowerState_ON - * @retval None - */ -void SDIO_SetPowerState(uint32_t SDIO_PowerState) -{ - /* Check the parameters */ - assert_param(IS_SDIO_POWER_STATE(SDIO_PowerState)); - - SDIO->POWER &= PWR_PWRCTRL_MASK; - SDIO->POWER |= SDIO_PowerState; -} - -/** - * @brief Gets the power status of the controller. - * @param None - * @retval Power status of the controller. The returned value can - * be one of the following: - * - 0x00: Power OFF - * - 0x02: Power UP - * - 0x03: Power ON - */ -uint32_t SDIO_GetPowerState(void) -{ - return (SDIO->POWER & (~PWR_PWRCTRL_MASK)); -} - -/** - * @brief Enables or disables the SDIO interrupts. - * @param SDIO_IT: specifies the SDIO interrupt sources to be enabled or disabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt - * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide - * bus mode interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt - * @param NewState: new state of the specified SDIO interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_SDIO_IT(SDIO_IT)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the SDIO interrupts */ - SDIO->MASK |= SDIO_IT; - } - else - { - /* Disable the SDIO interrupts */ - SDIO->MASK &= ~SDIO_IT; - } -} - -/** - * @brief Enables or disables the SDIO DMA request. - * @param NewState: new state of the selected SDIO DMA request. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SDIO_DMACmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) DCTRL_DMAEN_BB = (uint32_t)NewState; -} - -/** - * @brief Initializes the SDIO Command according to the specified - * parameters in the SDIO_CmdInitStruct and send the command. - * @param SDIO_CmdInitStruct : pointer to a SDIO_CmdInitTypeDef - * structure that contains the configuration information for the SDIO command. - * @retval None - */ -void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_SDIO_CMD_INDEX(SDIO_CmdInitStruct->SDIO_CmdIndex)); - assert_param(IS_SDIO_RESPONSE(SDIO_CmdInitStruct->SDIO_Response)); - assert_param(IS_SDIO_WAIT(SDIO_CmdInitStruct->SDIO_Wait)); - assert_param(IS_SDIO_CPSM(SDIO_CmdInitStruct->SDIO_CPSM)); - -/*---------------------------- SDIO ARG Configuration ------------------------*/ - /* Set the SDIO Argument value */ - SDIO->ARG = SDIO_CmdInitStruct->SDIO_Argument; - -/*---------------------------- SDIO CMD Configuration ------------------------*/ - /* Get the SDIO CMD value */ - tmpreg = SDIO->CMD; - /* Clear CMDINDEX, WAITRESP, WAITINT, WAITPEND, CPSMEN bits */ - tmpreg &= CMD_CLEAR_MASK; - /* Set CMDINDEX bits according to SDIO_CmdIndex value */ - /* Set WAITRESP bits according to SDIO_Response value */ - /* Set WAITINT and WAITPEND bits according to SDIO_Wait value */ - /* Set CPSMEN bits according to SDIO_CPSM value */ - tmpreg |= (uint32_t)SDIO_CmdInitStruct->SDIO_CmdIndex | SDIO_CmdInitStruct->SDIO_Response - | SDIO_CmdInitStruct->SDIO_Wait | SDIO_CmdInitStruct->SDIO_CPSM; - - /* Write to SDIO CMD */ - SDIO->CMD = tmpreg; -} - -/** - * @brief Fills each SDIO_CmdInitStruct member with its default value. - * @param SDIO_CmdInitStruct: pointer to an SDIO_CmdInitTypeDef - * structure which will be initialized. - * @retval None - */ -void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct) -{ - /* SDIO_CmdInitStruct members default value */ - SDIO_CmdInitStruct->SDIO_Argument = 0x00; - SDIO_CmdInitStruct->SDIO_CmdIndex = 0x00; - SDIO_CmdInitStruct->SDIO_Response = SDIO_Response_No; - SDIO_CmdInitStruct->SDIO_Wait = SDIO_Wait_No; - SDIO_CmdInitStruct->SDIO_CPSM = SDIO_CPSM_Disable; -} - -/** - * @brief Returns command index of last command for which response received. - * @param None - * @retval Returns the command index of the last command response received. - */ -uint8_t SDIO_GetCommandResponse(void) -{ - return (uint8_t)(SDIO->RESPCMD); -} - -/** - * @brief Returns response received from the card for the last command. - * @param SDIO_RESP: Specifies the SDIO response register. - * This parameter can be one of the following values: - * @arg SDIO_RESP1: Response Register 1 - * @arg SDIO_RESP2: Response Register 2 - * @arg SDIO_RESP3: Response Register 3 - * @arg SDIO_RESP4: Response Register 4 - * @retval The Corresponding response register value. - */ -uint32_t SDIO_GetResponse(uint32_t SDIO_RESP) -{ - __IO uint32_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_SDIO_RESP(SDIO_RESP)); - - tmp = SDIO_RESP_ADDR + SDIO_RESP; - - return (*(__IO uint32_t *) tmp); -} - -/** - * @brief Initializes the SDIO data path according to the specified - * parameters in the SDIO_DataInitStruct. - * @param SDIO_DataInitStruct : pointer to a SDIO_DataInitTypeDef structure that - * contains the configuration information for the SDIO command. - * @retval None - */ -void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct) -{ - uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_SDIO_DATA_LENGTH(SDIO_DataInitStruct->SDIO_DataLength)); - assert_param(IS_SDIO_BLOCK_SIZE(SDIO_DataInitStruct->SDIO_DataBlockSize)); - assert_param(IS_SDIO_TRANSFER_DIR(SDIO_DataInitStruct->SDIO_TransferDir)); - assert_param(IS_SDIO_TRANSFER_MODE(SDIO_DataInitStruct->SDIO_TransferMode)); - assert_param(IS_SDIO_DPSM(SDIO_DataInitStruct->SDIO_DPSM)); - -/*---------------------------- SDIO DTIMER Configuration ---------------------*/ - /* Set the SDIO Data TimeOut value */ - SDIO->DTIMER = SDIO_DataInitStruct->SDIO_DataTimeOut; - -/*---------------------------- SDIO DLEN Configuration -----------------------*/ - /* Set the SDIO DataLength value */ - SDIO->DLEN = SDIO_DataInitStruct->SDIO_DataLength; - -/*---------------------------- SDIO DCTRL Configuration ----------------------*/ - /* Get the SDIO DCTRL value */ - tmpreg = SDIO->DCTRL; - /* Clear DEN, DTMODE, DTDIR and DBCKSIZE bits */ - tmpreg &= DCTRL_CLEAR_MASK; - /* Set DEN bit according to SDIO_DPSM value */ - /* Set DTMODE bit according to SDIO_TransferMode value */ - /* Set DTDIR bit according to SDIO_TransferDir value */ - /* Set DBCKSIZE bits according to SDIO_DataBlockSize value */ - tmpreg |= (uint32_t)SDIO_DataInitStruct->SDIO_DataBlockSize | SDIO_DataInitStruct->SDIO_TransferDir - | SDIO_DataInitStruct->SDIO_TransferMode | SDIO_DataInitStruct->SDIO_DPSM; - - /* Write to SDIO DCTRL */ - SDIO->DCTRL = tmpreg; -} - -/** - * @brief Fills each SDIO_DataInitStruct member with its default value. - * @param SDIO_DataInitStruct: pointer to an SDIO_DataInitTypeDef structure which - * will be initialized. - * @retval None - */ -void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct) -{ - /* SDIO_DataInitStruct members default value */ - SDIO_DataInitStruct->SDIO_DataTimeOut = 0xFFFFFFFF; - SDIO_DataInitStruct->SDIO_DataLength = 0x00; - SDIO_DataInitStruct->SDIO_DataBlockSize = SDIO_DataBlockSize_1b; - SDIO_DataInitStruct->SDIO_TransferDir = SDIO_TransferDir_ToCard; - SDIO_DataInitStruct->SDIO_TransferMode = SDIO_TransferMode_Block; - SDIO_DataInitStruct->SDIO_DPSM = SDIO_DPSM_Disable; -} - -/** - * @brief Returns number of remaining data bytes to be transferred. - * @param None - * @retval Number of remaining data bytes to be transferred - */ -uint32_t SDIO_GetDataCounter(void) -{ - return SDIO->DCOUNT; -} - -/** - * @brief Read one data word from Rx FIFO. - * @param None - * @retval Data received - */ -uint32_t SDIO_ReadData(void) -{ - return SDIO->FIFO; -} - -/** - * @brief Write one data word to Tx FIFO. - * @param Data: 32-bit data word to write. - * @retval None - */ -void SDIO_WriteData(uint32_t Data) -{ - SDIO->FIFO = Data; -} - -/** - * @brief Returns the number of words left to be written to or read from FIFO. - * @param None - * @retval Remaining number of words. - */ -uint32_t SDIO_GetFIFOCount(void) -{ - return SDIO->FIFOCNT; -} - -/** - * @brief Starts the SD I/O Read Wait operation. - * @param NewState: new state of the Start SDIO Read Wait operation. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SDIO_StartSDIOReadWait(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) DCTRL_RWSTART_BB = (uint32_t) NewState; -} - -/** - * @brief Stops the SD I/O Read Wait operation. - * @param NewState: new state of the Stop SDIO Read Wait operation. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SDIO_StopSDIOReadWait(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) DCTRL_RWSTOP_BB = (uint32_t) NewState; -} - -/** - * @brief Sets one of the two options of inserting read wait interval. - * @param SDIO_ReadWaitMode: SD I/O Read Wait operation mode. - * This parametre can be: - * @arg SDIO_ReadWaitMode_CLK: Read Wait control by stopping SDIOCLK - * @arg SDIO_ReadWaitMode_DATA2: Read Wait control using SDIO_DATA2 - * @retval None - */ -void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode) -{ - /* Check the parameters */ - assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode)); - - *(__IO uint32_t *) DCTRL_RWMOD_BB = SDIO_ReadWaitMode; -} - -/** - * @brief Enables or disables the SD I/O Mode Operation. - * @param NewState: new state of SDIO specific operation. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SDIO_SetSDIOOperation(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) DCTRL_SDIOEN_BB = (uint32_t)NewState; -} - -/** - * @brief Enables or disables the SD I/O Mode suspend command sending. - * @param NewState: new state of the SD I/O Mode suspend command. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SDIO_SendSDIOSuspendCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) CMD_SDIOSUSPEND_BB = (uint32_t)NewState; -} - -/** - * @brief Enables or disables the command completion signal. - * @param NewState: new state of command completion signal. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SDIO_CommandCompletionCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) CMD_ENCMDCOMPL_BB = (uint32_t)NewState; -} - -/** - * @brief Enables or disables the CE-ATA interrupt. - * @param NewState: new state of CE-ATA interrupt. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SDIO_CEATAITCmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)((~((uint32_t)NewState)) & ((uint32_t)0x1)); -} - -/** - * @brief Sends CE-ATA command (CMD61). - * @param NewState: new state of CE-ATA command. This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SDIO_SendCEATACmd(FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - *(__IO uint32_t *) CMD_ATACMD_BB = (uint32_t)NewState; -} - -/** - * @brief Checks whether the specified SDIO flag is set or not. - * @param SDIO_FLAG: specifies the flag to check. - * This parameter can be one of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is zero) - * @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide - * bus mode. - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_CMDACT: Command transfer in progress - * @arg SDIO_FLAG_TXACT: Data transmit in progress - * @arg SDIO_FLAG_RXACT: Data receive in progress - * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty - * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full - * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full - * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full - * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty - * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty - * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO - * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO - * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received - * @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61 - * @retval The new state of SDIO_FLAG (SET or RESET). - */ -FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG) -{ - FlagStatus bitstatus = RESET; - - /* Check the parameters */ - assert_param(IS_SDIO_FLAG(SDIO_FLAG)); - - if ((SDIO->STA & SDIO_FLAG) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - return bitstatus; -} - -/** - * @brief Clears the SDIO's pending flags. - * @param SDIO_FLAG: specifies the flag to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is zero) - * @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide - * bus mode - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received - * @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61 - * @retval None - */ -void SDIO_ClearFlag(uint32_t SDIO_FLAG) -{ - /* Check the parameters */ - assert_param(IS_SDIO_CLEAR_FLAG(SDIO_FLAG)); - - SDIO->ICR = SDIO_FLAG; -} - -/** - * @brief Checks whether the specified SDIO interrupt has occurred or not. - * @param SDIO_IT: specifies the SDIO interrupt source to check. - * This parameter can be one of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt - * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide - * bus mode interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt - * @retval The new state of SDIO_IT (SET or RESET). - */ -ITStatus SDIO_GetITStatus(uint32_t SDIO_IT) -{ - ITStatus bitstatus = RESET; - - /* Check the parameters */ - assert_param(IS_SDIO_GET_IT(SDIO_IT)); - if ((SDIO->STA & SDIO_IT) != (uint32_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - return bitstatus; -} - -/** - * @brief Clears the SDIO’s interrupt pending bits. - * @param SDIO_IT: specifies the interrupt pending bit to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt - * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide - * bus mode interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 - * @retval None - */ -void SDIO_ClearITPendingBit(uint32_t SDIO_IT) -{ - /* Check the parameters */ - assert_param(IS_SDIO_CLEAR_IT(SDIO_IT)); - - SDIO->ICR = SDIO_IT; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_sdio.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the SDIO firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_sdio.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup SDIO + * @brief SDIO driver modules + * @{ + */ + +/** @defgroup SDIO_Private_TypesDefinitions + * @{ + */ + +/* ------------ SDIO registers bit address in the alias region ----------- */ +#define SDIO_OFFSET (SDIO_BASE - PERIPH_BASE) + +/* --- CLKCR Register ---*/ + +/* Alias word address of CLKEN bit */ +#define CLKCR_OFFSET (SDIO_OFFSET + 0x04) +#define CLKEN_BitNumber 0x08 +#define CLKCR_CLKEN_BB (PERIPH_BB_BASE + (CLKCR_OFFSET * 32) + (CLKEN_BitNumber * 4)) + +/* --- CMD Register ---*/ + +/* Alias word address of SDIOSUSPEND bit */ +#define CMD_OFFSET (SDIO_OFFSET + 0x0C) +#define SDIOSUSPEND_BitNumber 0x0B +#define CMD_SDIOSUSPEND_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (SDIOSUSPEND_BitNumber * 4)) + +/* Alias word address of ENCMDCOMPL bit */ +#define ENCMDCOMPL_BitNumber 0x0C +#define CMD_ENCMDCOMPL_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ENCMDCOMPL_BitNumber * 4)) + +/* Alias word address of NIEN bit */ +#define NIEN_BitNumber 0x0D +#define CMD_NIEN_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (NIEN_BitNumber * 4)) + +/* Alias word address of ATACMD bit */ +#define ATACMD_BitNumber 0x0E +#define CMD_ATACMD_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ATACMD_BitNumber * 4)) + +/* --- DCTRL Register ---*/ + +/* Alias word address of DMAEN bit */ +#define DCTRL_OFFSET (SDIO_OFFSET + 0x2C) +#define DMAEN_BitNumber 0x03 +#define DCTRL_DMAEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (DMAEN_BitNumber * 4)) + +/* Alias word address of RWSTART bit */ +#define RWSTART_BitNumber 0x08 +#define DCTRL_RWSTART_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTART_BitNumber * 4)) + +/* Alias word address of RWSTOP bit */ +#define RWSTOP_BitNumber 0x09 +#define DCTRL_RWSTOP_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTOP_BitNumber * 4)) + +/* Alias word address of RWMOD bit */ +#define RWMOD_BitNumber 0x0A +#define DCTRL_RWMOD_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWMOD_BitNumber * 4)) + +/* Alias word address of SDIOEN bit */ +#define SDIOEN_BitNumber 0x0B +#define DCTRL_SDIOEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (SDIOEN_BitNumber * 4)) + +/* ---------------------- SDIO registers bit mask ------------------------ */ + +/* --- CLKCR Register ---*/ + +/* CLKCR register clear mask */ +#define CLKCR_CLEAR_MASK ((uint32_t)0xFFFF8100) + +/* --- PWRCTRL Register ---*/ + +/* SDIO PWRCTRL Mask */ +#define PWR_PWRCTRL_MASK ((uint32_t)0xFFFFFFFC) + +/* --- DCTRL Register ---*/ + +/* SDIO DCTRL Clear Mask */ +#define DCTRL_CLEAR_MASK ((uint32_t)0xFFFFFF08) + +/* --- CMD Register ---*/ + +/* CMD Register clear mask */ +#define CMD_CLEAR_MASK ((uint32_t)0xFFFFF800) + +/* SDIO RESP Registers Address */ +#define SDIO_RESP_ADDR ((uint32_t)(SDIO_BASE + 0x14)) + +/** + * @} + */ + +/** @defgroup SDIO_Private_Defines + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the SDIO peripheral registers to their default reset values. + * @param None + * @retval None + */ +void SDIO_DeInit(void) +{ + SDIO->POWER = 0x00000000; + SDIO->CLKCR = 0x00000000; + SDIO->ARG = 0x00000000; + SDIO->CMD = 0x00000000; + SDIO->DTIMER = 0x00000000; + SDIO->DLEN = 0x00000000; + SDIO->DCTRL = 0x00000000; + SDIO->ICR = 0x00C007FF; + SDIO->MASK = 0x00000000; +} + +/** + * @brief Initializes the SDIO peripheral according to the specified + * parameters in the SDIO_InitStruct. + * @param SDIO_InitStruct : pointer to a SDIO_InitTypeDef structure + * that contains the configuration information for the SDIO peripheral. + * @retval None + */ +void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_CLOCK_EDGE(SDIO_InitStruct->SDIO_ClockEdge)); + assert_param(IS_SDIO_CLOCK_BYPASS(SDIO_InitStruct->SDIO_ClockBypass)); + assert_param(IS_SDIO_CLOCK_POWER_SAVE(SDIO_InitStruct->SDIO_ClockPowerSave)); + assert_param(IS_SDIO_BUS_WIDE(SDIO_InitStruct->SDIO_BusWide)); + assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(SDIO_InitStruct->SDIO_HardwareFlowControl)); + +/*---------------------------- SDIO CLKCR Configuration ------------------------*/ + /* Get the SDIO CLKCR value */ + tmpreg = SDIO->CLKCR; + + /* Clear CLKDIV, PWRSAV, BYPASS, WIDBUS, NEGEDGE, HWFC_EN bits */ + tmpreg &= CLKCR_CLEAR_MASK; + + /* Set CLKDIV bits according to SDIO_ClockDiv value */ + /* Set PWRSAV bit according to SDIO_ClockPowerSave value */ + /* Set BYPASS bit according to SDIO_ClockBypass value */ + /* Set WIDBUS bits according to SDIO_BusWide value */ + /* Set NEGEDGE bits according to SDIO_ClockEdge value */ + /* Set HWFC_EN bits according to SDIO_HardwareFlowControl value */ + tmpreg |= (SDIO_InitStruct->SDIO_ClockDiv | SDIO_InitStruct->SDIO_ClockPowerSave | + SDIO_InitStruct->SDIO_ClockBypass | SDIO_InitStruct->SDIO_BusWide | + SDIO_InitStruct->SDIO_ClockEdge | SDIO_InitStruct->SDIO_HardwareFlowControl); + + /* Write to SDIO CLKCR */ + SDIO->CLKCR = tmpreg; +} + +/** + * @brief Fills each SDIO_InitStruct member with its default value. + * @param SDIO_InitStruct: pointer to an SDIO_InitTypeDef structure which + * will be initialized. + * @retval None + */ +void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct) +{ + /* SDIO_InitStruct members default value */ + SDIO_InitStruct->SDIO_ClockDiv = 0x00; + SDIO_InitStruct->SDIO_ClockEdge = SDIO_ClockEdge_Rising; + SDIO_InitStruct->SDIO_ClockBypass = SDIO_ClockBypass_Disable; + SDIO_InitStruct->SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable; + SDIO_InitStruct->SDIO_BusWide = SDIO_BusWide_1b; + SDIO_InitStruct->SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable; +} + +/** + * @brief Enables or disables the SDIO Clock. + * @param NewState: new state of the SDIO Clock. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_ClockCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CLKCR_CLKEN_BB = (uint32_t)NewState; +} + +/** + * @brief Sets the power status of the controller. + * @param SDIO_PowerState: new state of the Power state. + * This parameter can be one of the following values: + * @arg SDIO_PowerState_OFF + * @arg SDIO_PowerState_ON + * @retval None + */ +void SDIO_SetPowerState(uint32_t SDIO_PowerState) +{ + /* Check the parameters */ + assert_param(IS_SDIO_POWER_STATE(SDIO_PowerState)); + + SDIO->POWER &= PWR_PWRCTRL_MASK; + SDIO->POWER |= SDIO_PowerState; +} + +/** + * @brief Gets the power status of the controller. + * @param None + * @retval Power status of the controller. The returned value can + * be one of the following: + * - 0x00: Power OFF + * - 0x02: Power UP + * - 0x03: Power ON + */ +uint32_t SDIO_GetPowerState(void) +{ + return (SDIO->POWER & (~PWR_PWRCTRL_MASK)); +} + +/** + * @brief Enables or disables the SDIO interrupts. + * @param SDIO_IT: specifies the SDIO interrupt sources to be enabled or disabled. + * This parameter can be one or a combination of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt + * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt + * @arg SDIO_IT_TXACT: Data transmit in progress interrupt + * @arg SDIO_IT_RXACT: Data receive in progress interrupt + * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt + * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt + * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt + * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt + * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt + * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt + * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt + * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt + * @param NewState: new state of the specified SDIO interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SDIO_IT(SDIO_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the SDIO interrupts */ + SDIO->MASK |= SDIO_IT; + } + else + { + /* Disable the SDIO interrupts */ + SDIO->MASK &= ~SDIO_IT; + } +} + +/** + * @brief Enables or disables the SDIO DMA request. + * @param NewState: new state of the selected SDIO DMA request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_DMACmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_DMAEN_BB = (uint32_t)NewState; +} + +/** + * @brief Initializes the SDIO Command according to the specified + * parameters in the SDIO_CmdInitStruct and send the command. + * @param SDIO_CmdInitStruct : pointer to a SDIO_CmdInitTypeDef + * structure that contains the configuration information for the SDIO command. + * @retval None + */ +void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_CMD_INDEX(SDIO_CmdInitStruct->SDIO_CmdIndex)); + assert_param(IS_SDIO_RESPONSE(SDIO_CmdInitStruct->SDIO_Response)); + assert_param(IS_SDIO_WAIT(SDIO_CmdInitStruct->SDIO_Wait)); + assert_param(IS_SDIO_CPSM(SDIO_CmdInitStruct->SDIO_CPSM)); + +/*---------------------------- SDIO ARG Configuration ------------------------*/ + /* Set the SDIO Argument value */ + SDIO->ARG = SDIO_CmdInitStruct->SDIO_Argument; + +/*---------------------------- SDIO CMD Configuration ------------------------*/ + /* Get the SDIO CMD value */ + tmpreg = SDIO->CMD; + /* Clear CMDINDEX, WAITRESP, WAITINT, WAITPEND, CPSMEN bits */ + tmpreg &= CMD_CLEAR_MASK; + /* Set CMDINDEX bits according to SDIO_CmdIndex value */ + /* Set WAITRESP bits according to SDIO_Response value */ + /* Set WAITINT and WAITPEND bits according to SDIO_Wait value */ + /* Set CPSMEN bits according to SDIO_CPSM value */ + tmpreg |= (uint32_t)SDIO_CmdInitStruct->SDIO_CmdIndex | SDIO_CmdInitStruct->SDIO_Response + | SDIO_CmdInitStruct->SDIO_Wait | SDIO_CmdInitStruct->SDIO_CPSM; + + /* Write to SDIO CMD */ + SDIO->CMD = tmpreg; +} + +/** + * @brief Fills each SDIO_CmdInitStruct member with its default value. + * @param SDIO_CmdInitStruct: pointer to an SDIO_CmdInitTypeDef + * structure which will be initialized. + * @retval None + */ +void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct) +{ + /* SDIO_CmdInitStruct members default value */ + SDIO_CmdInitStruct->SDIO_Argument = 0x00; + SDIO_CmdInitStruct->SDIO_CmdIndex = 0x00; + SDIO_CmdInitStruct->SDIO_Response = SDIO_Response_No; + SDIO_CmdInitStruct->SDIO_Wait = SDIO_Wait_No; + SDIO_CmdInitStruct->SDIO_CPSM = SDIO_CPSM_Disable; +} + +/** + * @brief Returns command index of last command for which response received. + * @param None + * @retval Returns the command index of the last command response received. + */ +uint8_t SDIO_GetCommandResponse(void) +{ + return (uint8_t)(SDIO->RESPCMD); +} + +/** + * @brief Returns response received from the card for the last command. + * @param SDIO_RESP: Specifies the SDIO response register. + * This parameter can be one of the following values: + * @arg SDIO_RESP1: Response Register 1 + * @arg SDIO_RESP2: Response Register 2 + * @arg SDIO_RESP3: Response Register 3 + * @arg SDIO_RESP4: Response Register 4 + * @retval The Corresponding response register value. + */ +uint32_t SDIO_GetResponse(uint32_t SDIO_RESP) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_RESP(SDIO_RESP)); + + tmp = SDIO_RESP_ADDR + SDIO_RESP; + + return (*(__IO uint32_t *) tmp); +} + +/** + * @brief Initializes the SDIO data path according to the specified + * parameters in the SDIO_DataInitStruct. + * @param SDIO_DataInitStruct : pointer to a SDIO_DataInitTypeDef structure that + * contains the configuration information for the SDIO command. + * @retval None + */ +void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_DATA_LENGTH(SDIO_DataInitStruct->SDIO_DataLength)); + assert_param(IS_SDIO_BLOCK_SIZE(SDIO_DataInitStruct->SDIO_DataBlockSize)); + assert_param(IS_SDIO_TRANSFER_DIR(SDIO_DataInitStruct->SDIO_TransferDir)); + assert_param(IS_SDIO_TRANSFER_MODE(SDIO_DataInitStruct->SDIO_TransferMode)); + assert_param(IS_SDIO_DPSM(SDIO_DataInitStruct->SDIO_DPSM)); + +/*---------------------------- SDIO DTIMER Configuration ---------------------*/ + /* Set the SDIO Data TimeOut value */ + SDIO->DTIMER = SDIO_DataInitStruct->SDIO_DataTimeOut; + +/*---------------------------- SDIO DLEN Configuration -----------------------*/ + /* Set the SDIO DataLength value */ + SDIO->DLEN = SDIO_DataInitStruct->SDIO_DataLength; + +/*---------------------------- SDIO DCTRL Configuration ----------------------*/ + /* Get the SDIO DCTRL value */ + tmpreg = SDIO->DCTRL; + /* Clear DEN, DTMODE, DTDIR and DBCKSIZE bits */ + tmpreg &= DCTRL_CLEAR_MASK; + /* Set DEN bit according to SDIO_DPSM value */ + /* Set DTMODE bit according to SDIO_TransferMode value */ + /* Set DTDIR bit according to SDIO_TransferDir value */ + /* Set DBCKSIZE bits according to SDIO_DataBlockSize value */ + tmpreg |= (uint32_t)SDIO_DataInitStruct->SDIO_DataBlockSize | SDIO_DataInitStruct->SDIO_TransferDir + | SDIO_DataInitStruct->SDIO_TransferMode | SDIO_DataInitStruct->SDIO_DPSM; + + /* Write to SDIO DCTRL */ + SDIO->DCTRL = tmpreg; +} + +/** + * @brief Fills each SDIO_DataInitStruct member with its default value. + * @param SDIO_DataInitStruct: pointer to an SDIO_DataInitTypeDef structure which + * will be initialized. + * @retval None + */ +void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct) +{ + /* SDIO_DataInitStruct members default value */ + SDIO_DataInitStruct->SDIO_DataTimeOut = 0xFFFFFFFF; + SDIO_DataInitStruct->SDIO_DataLength = 0x00; + SDIO_DataInitStruct->SDIO_DataBlockSize = SDIO_DataBlockSize_1b; + SDIO_DataInitStruct->SDIO_TransferDir = SDIO_TransferDir_ToCard; + SDIO_DataInitStruct->SDIO_TransferMode = SDIO_TransferMode_Block; + SDIO_DataInitStruct->SDIO_DPSM = SDIO_DPSM_Disable; +} + +/** + * @brief Returns number of remaining data bytes to be transferred. + * @param None + * @retval Number of remaining data bytes to be transferred + */ +uint32_t SDIO_GetDataCounter(void) +{ + return SDIO->DCOUNT; +} + +/** + * @brief Read one data word from Rx FIFO. + * @param None + * @retval Data received + */ +uint32_t SDIO_ReadData(void) +{ + return SDIO->FIFO; +} + +/** + * @brief Write one data word to Tx FIFO. + * @param Data: 32-bit data word to write. + * @retval None + */ +void SDIO_WriteData(uint32_t Data) +{ + SDIO->FIFO = Data; +} + +/** + * @brief Returns the number of words left to be written to or read from FIFO. + * @param None + * @retval Remaining number of words. + */ +uint32_t SDIO_GetFIFOCount(void) +{ + return SDIO->FIFOCNT; +} + +/** + * @brief Starts the SD I/O Read Wait operation. + * @param NewState: new state of the Start SDIO Read Wait operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_StartSDIOReadWait(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_RWSTART_BB = (uint32_t) NewState; +} + +/** + * @brief Stops the SD I/O Read Wait operation. + * @param NewState: new state of the Stop SDIO Read Wait operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_StopSDIOReadWait(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_RWSTOP_BB = (uint32_t) NewState; +} + +/** + * @brief Sets one of the two options of inserting read wait interval. + * @param SDIO_ReadWaitMode: SD I/O Read Wait operation mode. + * This parametre can be: + * @arg SDIO_ReadWaitMode_CLK: Read Wait control by stopping SDIOCLK + * @arg SDIO_ReadWaitMode_DATA2: Read Wait control using SDIO_DATA2 + * @retval None + */ +void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode) +{ + /* Check the parameters */ + assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode)); + + *(__IO uint32_t *) DCTRL_RWMOD_BB = SDIO_ReadWaitMode; +} + +/** + * @brief Enables or disables the SD I/O Mode Operation. + * @param NewState: new state of SDIO specific operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SetSDIOOperation(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_SDIOEN_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the SD I/O Mode suspend command sending. + * @param NewState: new state of the SD I/O Mode suspend command. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SendSDIOSuspendCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_SDIOSUSPEND_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the command completion signal. + * @param NewState: new state of command completion signal. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_CommandCompletionCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_ENCMDCOMPL_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the CE-ATA interrupt. + * @param NewState: new state of CE-ATA interrupt. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_CEATAITCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)((~((uint32_t)NewState)) & ((uint32_t)0x1)); +} + +/** + * @brief Sends CE-ATA command (CMD61). + * @param NewState: new state of CE-ATA command. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SendCEATACmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_ATACMD_BB = (uint32_t)NewState; +} + +/** + * @brief Checks whether the specified SDIO flag is set or not. + * @param SDIO_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) + * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) + * @arg SDIO_FLAG_CTIMEOUT: Command response timeout + * @arg SDIO_FLAG_DTIMEOUT: Data timeout + * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error + * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error + * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) + * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) + * @arg SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is zero) + * @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide + * bus mode. + * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) + * @arg SDIO_FLAG_CMDACT: Command transfer in progress + * @arg SDIO_FLAG_TXACT: Data transmit in progress + * @arg SDIO_FLAG_RXACT: Data receive in progress + * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty + * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full + * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full + * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full + * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty + * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty + * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO + * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO + * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received + * @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval The new state of SDIO_FLAG (SET or RESET). + */ +FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_SDIO_FLAG(SDIO_FLAG)); + + if ((SDIO->STA & SDIO_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the SDIO's pending flags. + * @param SDIO_FLAG: specifies the flag to clear. + * This parameter can be one or a combination of the following values: + * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) + * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) + * @arg SDIO_FLAG_CTIMEOUT: Command response timeout + * @arg SDIO_FLAG_DTIMEOUT: Data timeout + * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error + * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error + * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) + * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) + * @arg SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is zero) + * @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide + * bus mode + * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) + * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received + * @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval None + */ +void SDIO_ClearFlag(uint32_t SDIO_FLAG) +{ + /* Check the parameters */ + assert_param(IS_SDIO_CLEAR_FLAG(SDIO_FLAG)); + + SDIO->ICR = SDIO_FLAG; +} + +/** + * @brief Checks whether the specified SDIO interrupt has occurred or not. + * @param SDIO_IT: specifies the SDIO interrupt source to check. + * This parameter can be one of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt + * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt + * @arg SDIO_IT_TXACT: Data transmit in progress interrupt + * @arg SDIO_IT_RXACT: Data receive in progress interrupt + * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt + * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt + * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt + * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt + * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt + * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt + * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt + * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt + * @retval The new state of SDIO_IT (SET or RESET). + */ +ITStatus SDIO_GetITStatus(uint32_t SDIO_IT) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_SDIO_GET_IT(SDIO_IT)); + if ((SDIO->STA & SDIO_IT) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the SDIO’s interrupt pending bits. + * @param SDIO_IT: specifies the interrupt pending bit to clear. + * This parameter can be one or a combination of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval None + */ +void SDIO_ClearITPendingBit(uint32_t SDIO_IT) +{ + /* Check the parameters */ + assert_param(IS_SDIO_CLEAR_IT(SDIO_IT)); + + SDIO->ICR = SDIO_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c index d8a335d07..cd8ee0ef2 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c @@ -1,907 +1,907 @@ -/** - ****************************************************************************** - * @file stm32f10x_spi.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the SPI firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_spi.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup SPI - * @brief SPI driver modules - * @{ - */ - -/** @defgroup SPI_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - - -/** @defgroup SPI_Private_Defines - * @{ - */ - -/* SPI SPE mask */ -#define CR1_SPE_Set ((uint16_t)0x0040) -#define CR1_SPE_Reset ((uint16_t)0xFFBF) - -/* I2S I2SE mask */ -#define I2SCFGR_I2SE_Set ((uint16_t)0x0400) -#define I2SCFGR_I2SE_Reset ((uint16_t)0xFBFF) - -/* SPI CRCNext mask */ -#define CR1_CRCNext_Set ((uint16_t)0x1000) - -/* SPI CRCEN mask */ -#define CR1_CRCEN_Set ((uint16_t)0x2000) -#define CR1_CRCEN_Reset ((uint16_t)0xDFFF) - -/* SPI SSOE mask */ -#define CR2_SSOE_Set ((uint16_t)0x0004) -#define CR2_SSOE_Reset ((uint16_t)0xFFFB) - -/* SPI registers Masks */ -#define CR1_CLEAR_Mask ((uint16_t)0x3040) -#define I2SCFGR_CLEAR_Mask ((uint16_t)0xF040) - -/* SPI or I2S mode selection masks */ -#define SPI_Mode_Select ((uint16_t)0xF7FF) -#define I2S_Mode_Select ((uint16_t)0x0800) - -/* I2S clock source selection masks */ -#define I2S2_CLOCK_SRC ((uint32_t)(0x00020000)) -#define I2S3_CLOCK_SRC ((uint32_t)(0x00040000)) -#define I2S_MUL_MASK ((uint32_t)(0x0000F000)) -#define I2S_DIV_MASK ((uint32_t)(0x000000F0)) - -/** - * @} - */ - -/** @defgroup SPI_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup SPI_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup SPI_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup SPI_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the SPIx peripheral registers to their default - * reset values (Affects also the I2Ss). - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @retval None - */ -void SPI_I2S_DeInit(SPI_TypeDef* SPIx) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - - if (SPIx == SPI1) - { - /* Enable SPI1 reset state */ - RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE); - /* Release SPI1 from reset state */ - RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE); - } - else if (SPIx == SPI2) - { - /* Enable SPI2 reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE); - /* Release SPI2 from reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE); - } - else - { - if (SPIx == SPI3) - { - /* Enable SPI3 reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE); - /* Release SPI3 from reset state */ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE); - } - } -} - -/** - * @brief Initializes the SPIx peripheral according to the specified - * parameters in the SPI_InitStruct. - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure that - * contains the configuration information for the specified SPI peripheral. - * @retval None - */ -void SPI_Init(SPI_TypeDef* SPIx, const SPI_InitTypeDef* SPI_InitStruct) -{ - uint16_t tmpreg = 0; - - /* check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - - /* Check the SPI parameters */ - assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction)); - assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode)); - assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize)); - assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL)); - assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA)); - assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS)); - assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler)); - assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit)); - assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial)); - -/*---------------------------- SPIx CR1 Configuration ------------------------*/ - /* Get the SPIx CR1 value */ - tmpreg = SPIx->CR1; - /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */ - tmpreg &= CR1_CLEAR_Mask; - /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler - master/salve mode, CPOL and CPHA */ - /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */ - /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */ - /* Set LSBFirst bit according to SPI_FirstBit value */ - /* Set BR bits according to SPI_BaudRatePrescaler value */ - /* Set CPOL bit according to SPI_CPOL value */ - /* Set CPHA bit according to SPI_CPHA value */ - tmpreg |= (uint16_t)((uint32_t)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode | - SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL | - SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS | - SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit); - /* Write to SPIx CR1 */ - SPIx->CR1 = tmpreg; - - /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */ - SPIx->I2SCFGR &= SPI_Mode_Select; - -/*---------------------------- SPIx CRCPOLY Configuration --------------------*/ - /* Write to SPIx CRCPOLY */ - SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial; -} - -/** - * @brief Initializes the SPIx peripheral according to the specified - * parameters in the I2S_InitStruct. - * @param SPIx: where x can be 2 or 3 to select the SPI peripheral - * (configured in I2S mode). - * @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that - * contains the configuration information for the specified SPI peripheral - * configured in I2S mode. - * @note - * The function calculates the optimal prescaler needed to obtain the most - * accurate audio frequency (depending on the I2S clock source, the PLL values - * and the product configuration). But in case the prescaler value is greater - * than 511, the default value (0x02) will be configured instead. * - * @retval None - */ -void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct) -{ - uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1; - uint32_t tmp = 0; - RCC_ClocksTypeDef RCC_Clocks; - uint32_t sourceclock = 0; - - /* Check the I2S parameters */ - assert_param(IS_SPI_23_PERIPH(SPIx)); - assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode)); - assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard)); - assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat)); - assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput)); - assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq)); - assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL)); - -/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/ - /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ - SPIx->I2SCFGR &= I2SCFGR_CLEAR_Mask; - SPIx->I2SPR = 0x0002; - - /* Get the I2SCFGR register value */ - tmpreg = SPIx->I2SCFGR; - - /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/ - if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default) - { - i2sodd = (uint16_t)0; - i2sdiv = (uint16_t)2; - } - /* If the requested audio frequency is not the default, compute the prescaler */ - else - { - /* Check the frame length (For the Prescaler computing) */ - if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b) - { - /* Packet length is 16 bits */ - packetlength = 1; - } - else - { - /* Packet length is 32 bits */ - packetlength = 2; - } - - /* Get the I2S clock source mask depending on the peripheral number */ - if(((uint32_t)SPIx) == SPI2_BASE) - { - /* The mask is relative to I2S2 */ - tmp = I2S2_CLOCK_SRC; - } - else - { - /* The mask is relative to I2S3 */ - tmp = I2S3_CLOCK_SRC; - } - - /* Check the I2S clock source configuration depending on the Device: - Only Connectivity line devices have the PLL3 VCO clock */ -#ifdef STM32F10X_CL - if((RCC->CFGR2 & tmp) != 0) - { - /* Get the configuration bits of RCC PLL3 multiplier */ - tmp = (uint32_t)((RCC->CFGR2 & I2S_MUL_MASK) >> 12); - - /* Get the value of the PLL3 multiplier */ - if((tmp > 5) && (tmp < 15)) - { - /* Multplier is between 8 and 14 (value 15 is forbidden) */ - tmp += 2; - } - else - { - if (tmp == 15) - { - /* Multiplier is 20 */ - tmp = 20; - } - } - /* Get the PREDIV2 value */ - sourceclock = (uint32_t)(((RCC->CFGR2 & I2S_DIV_MASK) >> 4) + 1); - - /* Calculate the Source Clock frequency based on PLL3 and PREDIV2 values */ - sourceclock = (uint32_t) ((HSE_Value / sourceclock) * tmp * 2); - } - else - { - /* I2S Clock source is System clock: Get System Clock frequency */ - RCC_GetClocksFreq(&RCC_Clocks); - - /* Get the source clock value: based on System Clock value */ - sourceclock = RCC_Clocks.SYSCLK_Frequency; - } -#else /* STM32F10X_HD */ - /* I2S Clock source is System clock: Get System Clock frequency */ - RCC_GetClocksFreq(&RCC_Clocks); - - /* Get the source clock value: based on System Clock value */ - sourceclock = RCC_Clocks.SYSCLK_Frequency; -#endif /* STM32F10X_CL */ - - /* Compute the Real divider depending on the MCLK output state with a flaoting point */ - if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable) - { - /* MCLK output is enabled */ - tmp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5); - } - else - { - /* MCLK output is disabled */ - tmp = (uint16_t)(((((sourceclock / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5); - } - - /* Remove the flaoting point */ - tmp = tmp / 10; - - /* Check the parity of the divider */ - i2sodd = (uint16_t)(tmp & (uint16_t)0x0001); - - /* Compute the i2sdiv prescaler */ - i2sdiv = (uint16_t)((tmp - i2sodd) / 2); - - /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */ - i2sodd = (uint16_t) (i2sodd << 8); - } - - /* Test if the divider is 1 or 0 or greater than 0xFF */ - if ((i2sdiv < 2) || (i2sdiv > 0xFF)) - { - /* Set the default values */ - i2sdiv = 2; - i2sodd = 0; - } - - /* Write to SPIx I2SPR register the computed value */ - SPIx->I2SPR = (uint16_t)(i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput)); - - /* Configure the I2S with the SPI_InitStruct values */ - tmpreg |= (uint16_t)(I2S_Mode_Select | (uint16_t)(I2S_InitStruct->I2S_Mode | \ - (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \ - (uint16_t)I2S_InitStruct->I2S_CPOL)))); - - /* Write to SPIx I2SCFGR */ - SPIx->I2SCFGR = tmpreg; -} - -/** - * @brief Fills each SPI_InitStruct member with its default value. - * @param SPI_InitStruct : pointer to a SPI_InitTypeDef structure which will be initialized. - * @retval None - */ -void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct) -{ -/*--------------- Reset SPI init structure parameters values -----------------*/ - /* Initialize the SPI_Direction member */ - SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex; - /* initialize the SPI_Mode member */ - SPI_InitStruct->SPI_Mode = SPI_Mode_Slave; - /* initialize the SPI_DataSize member */ - SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b; - /* Initialize the SPI_CPOL member */ - SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low; - /* Initialize the SPI_CPHA member */ - SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge; - /* Initialize the SPI_NSS member */ - SPI_InitStruct->SPI_NSS = SPI_NSS_Hard; - /* Initialize the SPI_BaudRatePrescaler member */ - SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2; - /* Initialize the SPI_FirstBit member */ - SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB; - /* Initialize the SPI_CRCPolynomial member */ - SPI_InitStruct->SPI_CRCPolynomial = 7; -} - -/** - * @brief Fills each I2S_InitStruct member with its default value. - * @param I2S_InitStruct : pointer to a I2S_InitTypeDef structure which will be initialized. - * @retval None - */ -void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct) -{ -/*--------------- Reset I2S init structure parameters values -----------------*/ - /* Initialize the I2S_Mode member */ - I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx; - - /* Initialize the I2S_Standard member */ - I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips; - - /* Initialize the I2S_DataFormat member */ - I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b; - - /* Initialize the I2S_MCLKOutput member */ - I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable; - - /* Initialize the I2S_AudioFreq member */ - I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default; - - /* Initialize the I2S_CPOL member */ - I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low; -} - -/** - * @brief Enables or disables the specified SPI peripheral. - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @param NewState: new state of the SPIx peripheral. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected SPI peripheral */ - SPIx->CR1 |= CR1_SPE_Set; - } - else - { - /* Disable the selected SPI peripheral */ - SPIx->CR1 &= CR1_SPE_Reset; - } -} - -/** - * @brief Enables or disables the specified SPI peripheral (in I2S mode). - * @param SPIx: where x can be 2 or 3 to select the SPI peripheral. - * @param NewState: new state of the SPIx peripheral. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_SPI_23_PERIPH(SPIx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected SPI peripheral (in I2S mode) */ - SPIx->I2SCFGR |= I2SCFGR_I2SE_Set; - } - else - { - /* Disable the selected SPI peripheral (in I2S mode) */ - SPIx->I2SCFGR &= I2SCFGR_I2SE_Reset; - } -} - -/** - * @brief Enables or disables the specified SPI/I2S interrupts. - * @param SPIx: where x can be - * - 1, 2 or 3 in SPI mode - * - 2 or 3 in I2S mode - * @param SPI_I2S_IT: specifies the SPI/I2S interrupt source to be enabled or disabled. - * This parameter can be one of the following values: - * @arg SPI_I2S_IT_TXE: Tx buffer empty interrupt mask - * @arg SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask - * @arg SPI_I2S_IT_ERR: Error interrupt mask - * @param NewState: new state of the specified SPI/I2S interrupt. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState) -{ - uint16_t itpos = 0, itmask = 0 ; - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT)); - - /* Get the SPI/I2S IT index */ - itpos = SPI_I2S_IT >> 4; - - /* Set the IT mask */ - itmask = (uint16_t)1 << (uint16_t)itpos; - - if (NewState != DISABLE) - { - /* Enable the selected SPI/I2S interrupt */ - SPIx->CR2 |= itmask; - } - else - { - /* Disable the selected SPI/I2S interrupt */ - SPIx->CR2 &= (uint16_t)~itmask; - } -} - -/** - * @brief Enables or disables the SPIx/I2Sx DMA interface. - * @param SPIx: where x can be - * - 1, 2 or 3 in SPI mode - * - 2 or 3 in I2S mode - * @param SPI_I2S_DMAReq: specifies the SPI/I2S DMA transfer request to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request - * @arg SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request - * @param NewState: new state of the selected SPI/I2S DMA transfer request. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq)); - if (NewState != DISABLE) - { - /* Enable the selected SPI/I2S DMA requests */ - SPIx->CR2 |= SPI_I2S_DMAReq; - } - else - { - /* Disable the selected SPI/I2S DMA requests */ - SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq; - } -} - -/** - * @brief Transmits a Data through the SPIx/I2Sx peripheral. - * @param SPIx: where x can be - * - 1, 2 or 3 in SPI mode - * - 2 or 3 in I2S mode - * @param Data : Data to be transmitted. - * @retval None - */ -void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - - /* Write in the DR register the data to be sent */ - SPIx->DR = Data; -} - -/** - * @brief Returns the most recent received data by the SPIx/I2Sx peripheral. - * @param SPIx: where x can be - * - 1, 2 or 3 in SPI mode - * - 2 or 3 in I2S mode - * @retval The value of the received data. - */ -uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - - /* Return the data in the DR register */ - return SPIx->DR; -} - -/** - * @brief Configures internally by software the NSS pin for the selected SPI. - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @param SPI_NSSInternalSoft: specifies the SPI NSS internal state. - * This parameter can be one of the following values: - * @arg SPI_NSSInternalSoft_Set: Set NSS pin internally - * @arg SPI_NSSInternalSoft_Reset: Reset NSS pin internally - * @retval None - */ -void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft)); - if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset) - { - /* Set NSS pin internally by software */ - SPIx->CR1 |= SPI_NSSInternalSoft_Set; - } - else - { - /* Reset NSS pin internally by software */ - SPIx->CR1 &= SPI_NSSInternalSoft_Reset; - } -} - -/** - * @brief Enables or disables the SS output for the selected SPI. - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @param NewState: new state of the SPIx SS output. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected SPI SS output */ - SPIx->CR2 |= CR2_SSOE_Set; - } - else - { - /* Disable the selected SPI SS output */ - SPIx->CR2 &= CR2_SSOE_Reset; - } -} - -/** - * @brief Configures the data size for the selected SPI. - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @param SPI_DataSize: specifies the SPI data size. - * This parameter can be one of the following values: - * @arg SPI_DataSize_16b: Set data frame format to 16bit - * @arg SPI_DataSize_8b: Set data frame format to 8bit - * @retval None - */ -void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_SPI_DATASIZE(SPI_DataSize)); - /* Clear DFF bit */ - SPIx->CR1 &= (uint16_t)~SPI_DataSize_16b; - /* Set new DFF bit value */ - SPIx->CR1 |= SPI_DataSize; -} - -/** - * @brief Transmit the SPIx CRC value. - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @retval None - */ -void SPI_TransmitCRC(SPI_TypeDef* SPIx) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - - /* Enable the selected SPI CRC transmission */ - SPIx->CR1 |= CR1_CRCNext_Set; -} - -/** - * @brief Enables or disables the CRC value calculation of the transfered bytes. - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @param NewState: new state of the SPIx CRC value calculation. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the selected SPI CRC calculation */ - SPIx->CR1 |= CR1_CRCEN_Set; - } - else - { - /* Disable the selected SPI CRC calculation */ - SPIx->CR1 &= CR1_CRCEN_Reset; - } -} - -/** - * @brief Returns the transmit or the receive CRC register value for the specified SPI. - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @param SPI_CRC: specifies the CRC register to be read. - * This parameter can be one of the following values: - * @arg SPI_CRC_Tx: Selects Tx CRC register - * @arg SPI_CRC_Rx: Selects Rx CRC register - * @retval The selected CRC register value.. - */ -uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC) -{ - uint16_t crcreg = 0; - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_SPI_CRC(SPI_CRC)); - if (SPI_CRC != SPI_CRC_Rx) - { - /* Get the Tx CRC register */ - crcreg = SPIx->TXCRCR; - } - else - { - /* Get the Rx CRC register */ - crcreg = SPIx->RXCRCR; - } - /* Return the selected CRC register */ - return crcreg; -} - -/** - * @brief Returns the CRC Polynomial register value for the specified SPI. - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @retval The CRC Polynomial register value. - */ -uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - - /* Return the CRC polynomial register */ - return SPIx->CRCPR; -} - -/** - * @brief Selects the data transfer direction in bi-directional mode for the specified SPI. - * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. - * @param SPI_Direction: specifies the data transfer direction in bi-directional mode. - * This parameter can be one of the following values: - * @arg SPI_Direction_Tx: Selects Tx transmission direction - * @arg SPI_Direction_Rx: Selects Rx receive direction - * @retval None - */ -void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_SPI_DIRECTION(SPI_Direction)); - if (SPI_Direction == SPI_Direction_Tx) - { - /* Set the Tx only mode */ - SPIx->CR1 |= SPI_Direction_Tx; - } - else - { - /* Set the Rx only mode */ - SPIx->CR1 &= SPI_Direction_Rx; - } -} - -/** - * @brief Checks whether the specified SPI/I2S flag is set or not. - * @param SPIx: where x can be - * - 1, 2 or 3 in SPI mode - * - 2 or 3 in I2S mode - * @param SPI_I2S_FLAG: specifies the SPI/I2S flag to check. - * This parameter can be one of the following values: - * @arg SPI_I2S_FLAG_TXE: Transmit buffer empty flag. - * @arg SPI_I2S_FLAG_RXNE: Receive buffer not empty flag. - * @arg SPI_I2S_FLAG_BSY: Busy flag. - * @arg SPI_I2S_FLAG_OVR: Overrun flag. - * @arg SPI_FLAG_MODF: Mode Fault flag. - * @arg SPI_FLAG_CRCERR: CRC Error flag. - * @arg I2S_FLAG_UDR: Underrun Error flag. - * @arg I2S_FLAG_CHSIDE: Channel Side flag. - * @retval The new state of SPI_I2S_FLAG (SET or RESET). - */ -FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG)); - /* Check the status of the specified SPI/I2S flag */ - if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET) - { - /* SPI_I2S_FLAG is set */ - bitstatus = SET; - } - else - { - /* SPI_I2S_FLAG is reset */ - bitstatus = RESET; - } - /* Return the SPI_I2S_FLAG status */ - return bitstatus; -} - -/** - * @brief Clears the SPIx CRC Error (CRCERR) flag. - * @param SPIx: where x can be - * - 1, 2 or 3 in SPI mode - * @param SPI_I2S_FLAG: specifies the SPI flag to clear. - * This function clears only CRCERR flag. - * @note - * - OVR (OverRun error) flag is cleared by software sequence: a read - * operation to SPI_DR register (SPI_I2S_ReceiveData()) followed by a read - * operation to SPI_SR register (SPI_I2S_GetFlagStatus()). - * - UDR (UnderRun error) flag is cleared by a read operation to - * SPI_SR register (SPI_I2S_GetFlagStatus()). - * - MODF (Mode Fault) flag is cleared by software sequence: a read/write - * operation to SPI_SR register (SPI_I2S_GetFlagStatus()) followed by a - * write operation to SPI_CR1 register (SPI_Cmd() to enable the SPI). - * @retval None - */ -void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) -{ - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG)); - - /* Clear the selected SPI CRC Error (CRCERR) flag */ - SPIx->SR = (uint16_t)~SPI_I2S_FLAG; -} - -/** - * @brief Checks whether the specified SPI/I2S interrupt has occurred or not. - * @param SPIx: where x can be - * - 1, 2 or 3 in SPI mode - * - 2 or 3 in I2S mode - * @param SPI_I2S_IT: specifies the SPI/I2S interrupt source to check. - * This parameter can be one of the following values: - * @arg SPI_I2S_IT_TXE: Transmit buffer empty interrupt. - * @arg SPI_I2S_IT_RXNE: Receive buffer not empty interrupt. - * @arg SPI_I2S_IT_OVR: Overrun interrupt. - * @arg SPI_IT_MODF: Mode Fault interrupt. - * @arg SPI_IT_CRCERR: CRC Error interrupt. - * @arg I2S_IT_UDR: Underrun Error interrupt. - * @retval The new state of SPI_I2S_IT (SET or RESET). - */ -ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) -{ - ITStatus bitstatus = RESET; - uint16_t itpos = 0, itmask = 0, enablestatus = 0; - - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT)); - - /* Get the SPI/I2S IT index */ - itpos = 0x01 << (SPI_I2S_IT & 0x0F); - - /* Get the SPI/I2S IT mask */ - itmask = SPI_I2S_IT >> 4; - - /* Set the IT mask */ - itmask = 0x01 << itmask; - - /* Get the SPI_I2S_IT enable bit status */ - enablestatus = (SPIx->CR2 & itmask) ; - - /* Check the status of the specified SPI/I2S interrupt */ - if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus) - { - /* SPI_I2S_IT is set */ - bitstatus = SET; - } - else - { - /* SPI_I2S_IT is reset */ - bitstatus = RESET; - } - /* Return the SPI_I2S_IT status */ - return bitstatus; -} - -/** - * @brief Clears the SPIx CRC Error (CRCERR) interrupt pending bit. - * @param SPIx: where x can be - * - 1, 2 or 3 in SPI mode - * @param SPI_I2S_IT: specifies the SPI interrupt pending bit to clear. - * This function clears only CRCERR intetrrupt pending bit. - * @note - * - OVR (OverRun Error) interrupt pending bit is cleared by software - * sequence: a read operation to SPI_DR register (SPI_I2S_ReceiveData()) - * followed by a read operation to SPI_SR register (SPI_I2S_GetITStatus()). - * - UDR (UnderRun Error) interrupt pending bit is cleared by a read - * operation to SPI_SR register (SPI_I2S_GetITStatus()). - * - MODF (Mode Fault) interrupt pending bit is cleared by software sequence: - * a read/write operation to SPI_SR register (SPI_I2S_GetITStatus()) - * followed by a write operation to SPI_CR1 register (SPI_Cmd() to enable - * the SPI). - * @retval None - */ -void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) -{ - uint16_t itpos = 0; - /* Check the parameters */ - assert_param(IS_SPI_ALL_PERIPH(SPIx)); - assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT)); - - /* Get the SPI IT index */ - itpos = 0x01 << (SPI_I2S_IT & 0x0F); - - /* Clear the selected SPI CRC Error (CRCERR) interrupt pending bit */ - SPIx->SR = (uint16_t)~itpos; -} -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_spi.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the SPI firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_spi.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup SPI + * @brief SPI driver modules + * @{ + */ + +/** @defgroup SPI_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + + +/** @defgroup SPI_Private_Defines + * @{ + */ + +/* SPI SPE mask */ +#define CR1_SPE_Set ((uint16_t)0x0040) +#define CR1_SPE_Reset ((uint16_t)0xFFBF) + +/* I2S I2SE mask */ +#define I2SCFGR_I2SE_Set ((uint16_t)0x0400) +#define I2SCFGR_I2SE_Reset ((uint16_t)0xFBFF) + +/* SPI CRCNext mask */ +#define CR1_CRCNext_Set ((uint16_t)0x1000) + +/* SPI CRCEN mask */ +#define CR1_CRCEN_Set ((uint16_t)0x2000) +#define CR1_CRCEN_Reset ((uint16_t)0xDFFF) + +/* SPI SSOE mask */ +#define CR2_SSOE_Set ((uint16_t)0x0004) +#define CR2_SSOE_Reset ((uint16_t)0xFFFB) + +/* SPI registers Masks */ +#define CR1_CLEAR_Mask ((uint16_t)0x3040) +#define I2SCFGR_CLEAR_Mask ((uint16_t)0xF040) + +/* SPI or I2S mode selection masks */ +#define SPI_Mode_Select ((uint16_t)0xF7FF) +#define I2S_Mode_Select ((uint16_t)0x0800) + +/* I2S clock source selection masks */ +#define I2S2_CLOCK_SRC ((uint32_t)(0x00020000)) +#define I2S3_CLOCK_SRC ((uint32_t)(0x00040000)) +#define I2S_MUL_MASK ((uint32_t)(0x0000F000)) +#define I2S_DIV_MASK ((uint32_t)(0x000000F0)) + +/** + * @} + */ + +/** @defgroup SPI_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the SPIx peripheral registers to their default + * reset values (Affects also the I2Ss). + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval None + */ +void SPI_I2S_DeInit(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + if (SPIx == SPI1) + { + /* Enable SPI1 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE); + /* Release SPI1 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE); + } + else if (SPIx == SPI2) + { + /* Enable SPI2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE); + /* Release SPI2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE); + } + else + { + if (SPIx == SPI3) + { + /* Enable SPI3 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE); + /* Release SPI3 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE); + } + } +} + +/** + * @brief Initializes the SPIx peripheral according to the specified + * parameters in the SPI_InitStruct. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure that + * contains the configuration information for the specified SPI peripheral. + * @retval None + */ +void SPI_Init(SPI_TypeDef* SPIx, const SPI_InitTypeDef* SPI_InitStruct) +{ + uint16_t tmpreg = 0; + + /* check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Check the SPI parameters */ + assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction)); + assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode)); + assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize)); + assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL)); + assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA)); + assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS)); + assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler)); + assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit)); + assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial)); + +/*---------------------------- SPIx CR1 Configuration ------------------------*/ + /* Get the SPIx CR1 value */ + tmpreg = SPIx->CR1; + /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */ + tmpreg &= CR1_CLEAR_Mask; + /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler + master/salve mode, CPOL and CPHA */ + /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */ + /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */ + /* Set LSBFirst bit according to SPI_FirstBit value */ + /* Set BR bits according to SPI_BaudRatePrescaler value */ + /* Set CPOL bit according to SPI_CPOL value */ + /* Set CPHA bit according to SPI_CPHA value */ + tmpreg |= (uint16_t)((uint32_t)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode | + SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL | + SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS | + SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit); + /* Write to SPIx CR1 */ + SPIx->CR1 = tmpreg; + + /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */ + SPIx->I2SCFGR &= SPI_Mode_Select; + +/*---------------------------- SPIx CRCPOLY Configuration --------------------*/ + /* Write to SPIx CRCPOLY */ + SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial; +} + +/** + * @brief Initializes the SPIx peripheral according to the specified + * parameters in the I2S_InitStruct. + * @param SPIx: where x can be 2 or 3 to select the SPI peripheral + * (configured in I2S mode). + * @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that + * contains the configuration information for the specified SPI peripheral + * configured in I2S mode. + * @note + * The function calculates the optimal prescaler needed to obtain the most + * accurate audio frequency (depending on the I2S clock source, the PLL values + * and the product configuration). But in case the prescaler value is greater + * than 511, the default value (0x02) will be configured instead. * + * @retval None + */ +void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct) +{ + uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1; + uint32_t tmp = 0; + RCC_ClocksTypeDef RCC_Clocks; + uint32_t sourceclock = 0; + + /* Check the I2S parameters */ + assert_param(IS_SPI_23_PERIPH(SPIx)); + assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode)); + assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard)); + assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat)); + assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput)); + assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq)); + assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL)); + +/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/ + /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ + SPIx->I2SCFGR &= I2SCFGR_CLEAR_Mask; + SPIx->I2SPR = 0x0002; + + /* Get the I2SCFGR register value */ + tmpreg = SPIx->I2SCFGR; + + /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/ + if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default) + { + i2sodd = (uint16_t)0; + i2sdiv = (uint16_t)2; + } + /* If the requested audio frequency is not the default, compute the prescaler */ + else + { + /* Check the frame length (For the Prescaler computing) */ + if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b) + { + /* Packet length is 16 bits */ + packetlength = 1; + } + else + { + /* Packet length is 32 bits */ + packetlength = 2; + } + + /* Get the I2S clock source mask depending on the peripheral number */ + if(((uint32_t)SPIx) == SPI2_BASE) + { + /* The mask is relative to I2S2 */ + tmp = I2S2_CLOCK_SRC; + } + else + { + /* The mask is relative to I2S3 */ + tmp = I2S3_CLOCK_SRC; + } + + /* Check the I2S clock source configuration depending on the Device: + Only Connectivity line devices have the PLL3 VCO clock */ +#ifdef STM32F10X_CL + if((RCC->CFGR2 & tmp) != 0) + { + /* Get the configuration bits of RCC PLL3 multiplier */ + tmp = (uint32_t)((RCC->CFGR2 & I2S_MUL_MASK) >> 12); + + /* Get the value of the PLL3 multiplier */ + if((tmp > 5) && (tmp < 15)) + { + /* Multplier is between 8 and 14 (value 15 is forbidden) */ + tmp += 2; + } + else + { + if (tmp == 15) + { + /* Multiplier is 20 */ + tmp = 20; + } + } + /* Get the PREDIV2 value */ + sourceclock = (uint32_t)(((RCC->CFGR2 & I2S_DIV_MASK) >> 4) + 1); + + /* Calculate the Source Clock frequency based on PLL3 and PREDIV2 values */ + sourceclock = (uint32_t) ((HSE_Value / sourceclock) * tmp * 2); + } + else + { + /* I2S Clock source is System clock: Get System Clock frequency */ + RCC_GetClocksFreq(&RCC_Clocks); + + /* Get the source clock value: based on System Clock value */ + sourceclock = RCC_Clocks.SYSCLK_Frequency; + } +#else /* STM32F10X_HD */ + /* I2S Clock source is System clock: Get System Clock frequency */ + RCC_GetClocksFreq(&RCC_Clocks); + + /* Get the source clock value: based on System Clock value */ + sourceclock = RCC_Clocks.SYSCLK_Frequency; +#endif /* STM32F10X_CL */ + + /* Compute the Real divider depending on the MCLK output state with a flaoting point */ + if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable) + { + /* MCLK output is enabled */ + tmp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5); + } + else + { + /* MCLK output is disabled */ + tmp = (uint16_t)(((((sourceclock / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5); + } + + /* Remove the flaoting point */ + tmp = tmp / 10; + + /* Check the parity of the divider */ + i2sodd = (uint16_t)(tmp & (uint16_t)0x0001); + + /* Compute the i2sdiv prescaler */ + i2sdiv = (uint16_t)((tmp - i2sodd) / 2); + + /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */ + i2sodd = (uint16_t) (i2sodd << 8); + } + + /* Test if the divider is 1 or 0 or greater than 0xFF */ + if ((i2sdiv < 2) || (i2sdiv > 0xFF)) + { + /* Set the default values */ + i2sdiv = 2; + i2sodd = 0; + } + + /* Write to SPIx I2SPR register the computed value */ + SPIx->I2SPR = (uint16_t)(i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput)); + + /* Configure the I2S with the SPI_InitStruct values */ + tmpreg |= (uint16_t)(I2S_Mode_Select | (uint16_t)(I2S_InitStruct->I2S_Mode | \ + (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \ + (uint16_t)I2S_InitStruct->I2S_CPOL)))); + + /* Write to SPIx I2SCFGR */ + SPIx->I2SCFGR = tmpreg; +} + +/** + * @brief Fills each SPI_InitStruct member with its default value. + * @param SPI_InitStruct : pointer to a SPI_InitTypeDef structure which will be initialized. + * @retval None + */ +void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct) +{ +/*--------------- Reset SPI init structure parameters values -----------------*/ + /* Initialize the SPI_Direction member */ + SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex; + /* initialize the SPI_Mode member */ + SPI_InitStruct->SPI_Mode = SPI_Mode_Slave; + /* initialize the SPI_DataSize member */ + SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b; + /* Initialize the SPI_CPOL member */ + SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low; + /* Initialize the SPI_CPHA member */ + SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge; + /* Initialize the SPI_NSS member */ + SPI_InitStruct->SPI_NSS = SPI_NSS_Hard; + /* Initialize the SPI_BaudRatePrescaler member */ + SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2; + /* Initialize the SPI_FirstBit member */ + SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB; + /* Initialize the SPI_CRCPolynomial member */ + SPI_InitStruct->SPI_CRCPolynomial = 7; +} + +/** + * @brief Fills each I2S_InitStruct member with its default value. + * @param I2S_InitStruct : pointer to a I2S_InitTypeDef structure which will be initialized. + * @retval None + */ +void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct) +{ +/*--------------- Reset I2S init structure parameters values -----------------*/ + /* Initialize the I2S_Mode member */ + I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx; + + /* Initialize the I2S_Standard member */ + I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips; + + /* Initialize the I2S_DataFormat member */ + I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b; + + /* Initialize the I2S_MCLKOutput member */ + I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable; + + /* Initialize the I2S_AudioFreq member */ + I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default; + + /* Initialize the I2S_CPOL member */ + I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low; +} + +/** + * @brief Enables or disables the specified SPI peripheral. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI peripheral */ + SPIx->CR1 |= CR1_SPE_Set; + } + else + { + /* Disable the selected SPI peripheral */ + SPIx->CR1 &= CR1_SPE_Reset; + } +} + +/** + * @brief Enables or disables the specified SPI peripheral (in I2S mode). + * @param SPIx: where x can be 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_23_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI peripheral (in I2S mode) */ + SPIx->I2SCFGR |= I2SCFGR_I2SE_Set; + } + else + { + /* Disable the selected SPI peripheral (in I2S mode) */ + SPIx->I2SCFGR &= I2SCFGR_I2SE_Reset; + } +} + +/** + * @brief Enables or disables the specified SPI/I2S interrupts. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_IT: specifies the SPI/I2S interrupt source to be enabled or disabled. + * This parameter can be one of the following values: + * @arg SPI_I2S_IT_TXE: Tx buffer empty interrupt mask + * @arg SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask + * @arg SPI_I2S_IT_ERR: Error interrupt mask + * @param NewState: new state of the specified SPI/I2S interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState) +{ + uint16_t itpos = 0, itmask = 0 ; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT)); + + /* Get the SPI/I2S IT index */ + itpos = SPI_I2S_IT >> 4; + + /* Set the IT mask */ + itmask = (uint16_t)1 << (uint16_t)itpos; + + if (NewState != DISABLE) + { + /* Enable the selected SPI/I2S interrupt */ + SPIx->CR2 |= itmask; + } + else + { + /* Disable the selected SPI/I2S interrupt */ + SPIx->CR2 &= (uint16_t)~itmask; + } +} + +/** + * @brief Enables or disables the SPIx/I2Sx DMA interface. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_DMAReq: specifies the SPI/I2S DMA transfer request to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request + * @arg SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request + * @param NewState: new state of the selected SPI/I2S DMA transfer request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq)); + if (NewState != DISABLE) + { + /* Enable the selected SPI/I2S DMA requests */ + SPIx->CR2 |= SPI_I2S_DMAReq; + } + else + { + /* Disable the selected SPI/I2S DMA requests */ + SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq; + } +} + +/** + * @brief Transmits a Data through the SPIx/I2Sx peripheral. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param Data : Data to be transmitted. + * @retval None + */ +void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Write in the DR register the data to be sent */ + SPIx->DR = Data; +} + +/** + * @brief Returns the most recent received data by the SPIx/I2Sx peripheral. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @retval The value of the received data. + */ +uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Return the data in the DR register */ + return SPIx->DR; +} + +/** + * @brief Configures internally by software the NSS pin for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_NSSInternalSoft: specifies the SPI NSS internal state. + * This parameter can be one of the following values: + * @arg SPI_NSSInternalSoft_Set: Set NSS pin internally + * @arg SPI_NSSInternalSoft_Reset: Reset NSS pin internally + * @retval None + */ +void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft)); + if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset) + { + /* Set NSS pin internally by software */ + SPIx->CR1 |= SPI_NSSInternalSoft_Set; + } + else + { + /* Reset NSS pin internally by software */ + SPIx->CR1 &= SPI_NSSInternalSoft_Reset; + } +} + +/** + * @brief Enables or disables the SS output for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx SS output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI SS output */ + SPIx->CR2 |= CR2_SSOE_Set; + } + else + { + /* Disable the selected SPI SS output */ + SPIx->CR2 &= CR2_SSOE_Reset; + } +} + +/** + * @brief Configures the data size for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_DataSize: specifies the SPI data size. + * This parameter can be one of the following values: + * @arg SPI_DataSize_16b: Set data frame format to 16bit + * @arg SPI_DataSize_8b: Set data frame format to 8bit + * @retval None + */ +void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_DATASIZE(SPI_DataSize)); + /* Clear DFF bit */ + SPIx->CR1 &= (uint16_t)~SPI_DataSize_16b; + /* Set new DFF bit value */ + SPIx->CR1 |= SPI_DataSize; +} + +/** + * @brief Transmit the SPIx CRC value. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval None + */ +void SPI_TransmitCRC(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Enable the selected SPI CRC transmission */ + SPIx->CR1 |= CR1_CRCNext_Set; +} + +/** + * @brief Enables or disables the CRC value calculation of the transfered bytes. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx CRC value calculation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI CRC calculation */ + SPIx->CR1 |= CR1_CRCEN_Set; + } + else + { + /* Disable the selected SPI CRC calculation */ + SPIx->CR1 &= CR1_CRCEN_Reset; + } +} + +/** + * @brief Returns the transmit or the receive CRC register value for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_CRC: specifies the CRC register to be read. + * This parameter can be one of the following values: + * @arg SPI_CRC_Tx: Selects Tx CRC register + * @arg SPI_CRC_Rx: Selects Rx CRC register + * @retval The selected CRC register value.. + */ +uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC) +{ + uint16_t crcreg = 0; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_CRC(SPI_CRC)); + if (SPI_CRC != SPI_CRC_Rx) + { + /* Get the Tx CRC register */ + crcreg = SPIx->TXCRCR; + } + else + { + /* Get the Rx CRC register */ + crcreg = SPIx->RXCRCR; + } + /* Return the selected CRC register */ + return crcreg; +} + +/** + * @brief Returns the CRC Polynomial register value for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval The CRC Polynomial register value. + */ +uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Return the CRC polynomial register */ + return SPIx->CRCPR; +} + +/** + * @brief Selects the data transfer direction in bi-directional mode for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_Direction: specifies the data transfer direction in bi-directional mode. + * This parameter can be one of the following values: + * @arg SPI_Direction_Tx: Selects Tx transmission direction + * @arg SPI_Direction_Rx: Selects Rx receive direction + * @retval None + */ +void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_DIRECTION(SPI_Direction)); + if (SPI_Direction == SPI_Direction_Tx) + { + /* Set the Tx only mode */ + SPIx->CR1 |= SPI_Direction_Tx; + } + else + { + /* Set the Rx only mode */ + SPIx->CR1 &= SPI_Direction_Rx; + } +} + +/** + * @brief Checks whether the specified SPI/I2S flag is set or not. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_FLAG: specifies the SPI/I2S flag to check. + * This parameter can be one of the following values: + * @arg SPI_I2S_FLAG_TXE: Transmit buffer empty flag. + * @arg SPI_I2S_FLAG_RXNE: Receive buffer not empty flag. + * @arg SPI_I2S_FLAG_BSY: Busy flag. + * @arg SPI_I2S_FLAG_OVR: Overrun flag. + * @arg SPI_FLAG_MODF: Mode Fault flag. + * @arg SPI_FLAG_CRCERR: CRC Error flag. + * @arg I2S_FLAG_UDR: Underrun Error flag. + * @arg I2S_FLAG_CHSIDE: Channel Side flag. + * @retval The new state of SPI_I2S_FLAG (SET or RESET). + */ +FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG)); + /* Check the status of the specified SPI/I2S flag */ + if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET) + { + /* SPI_I2S_FLAG is set */ + bitstatus = SET; + } + else + { + /* SPI_I2S_FLAG is reset */ + bitstatus = RESET; + } + /* Return the SPI_I2S_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the SPIx CRC Error (CRCERR) flag. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * @param SPI_I2S_FLAG: specifies the SPI flag to clear. + * This function clears only CRCERR flag. + * @note + * - OVR (OverRun error) flag is cleared by software sequence: a read + * operation to SPI_DR register (SPI_I2S_ReceiveData()) followed by a read + * operation to SPI_SR register (SPI_I2S_GetFlagStatus()). + * - UDR (UnderRun error) flag is cleared by a read operation to + * SPI_SR register (SPI_I2S_GetFlagStatus()). + * - MODF (Mode Fault) flag is cleared by software sequence: a read/write + * operation to SPI_SR register (SPI_I2S_GetFlagStatus()) followed by a + * write operation to SPI_CR1 register (SPI_Cmd() to enable the SPI). + * @retval None + */ +void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG)); + + /* Clear the selected SPI CRC Error (CRCERR) flag */ + SPIx->SR = (uint16_t)~SPI_I2S_FLAG; +} + +/** + * @brief Checks whether the specified SPI/I2S interrupt has occurred or not. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_IT: specifies the SPI/I2S interrupt source to check. + * This parameter can be one of the following values: + * @arg SPI_I2S_IT_TXE: Transmit buffer empty interrupt. + * @arg SPI_I2S_IT_RXNE: Receive buffer not empty interrupt. + * @arg SPI_I2S_IT_OVR: Overrun interrupt. + * @arg SPI_IT_MODF: Mode Fault interrupt. + * @arg SPI_IT_CRCERR: CRC Error interrupt. + * @arg I2S_IT_UDR: Underrun Error interrupt. + * @retval The new state of SPI_I2S_IT (SET or RESET). + */ +ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itpos = 0, itmask = 0, enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT)); + + /* Get the SPI/I2S IT index */ + itpos = 0x01 << (SPI_I2S_IT & 0x0F); + + /* Get the SPI/I2S IT mask */ + itmask = SPI_I2S_IT >> 4; + + /* Set the IT mask */ + itmask = 0x01 << itmask; + + /* Get the SPI_I2S_IT enable bit status */ + enablestatus = (SPIx->CR2 & itmask) ; + + /* Check the status of the specified SPI/I2S interrupt */ + if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus) + { + /* SPI_I2S_IT is set */ + bitstatus = SET; + } + else + { + /* SPI_I2S_IT is reset */ + bitstatus = RESET; + } + /* Return the SPI_I2S_IT status */ + return bitstatus; +} + +/** + * @brief Clears the SPIx CRC Error (CRCERR) interrupt pending bit. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * @param SPI_I2S_IT: specifies the SPI interrupt pending bit to clear. + * This function clears only CRCERR intetrrupt pending bit. + * @note + * - OVR (OverRun Error) interrupt pending bit is cleared by software + * sequence: a read operation to SPI_DR register (SPI_I2S_ReceiveData()) + * followed by a read operation to SPI_SR register (SPI_I2S_GetITStatus()). + * - UDR (UnderRun Error) interrupt pending bit is cleared by a read + * operation to SPI_SR register (SPI_I2S_GetITStatus()). + * - MODF (Mode Fault) interrupt pending bit is cleared by software sequence: + * a read/write operation to SPI_SR register (SPI_I2S_GetITStatus()) + * followed by a write operation to SPI_CR1 register (SPI_Cmd() to enable + * the SPI). + * @retval None + */ +void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) +{ + uint16_t itpos = 0; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT)); + + /* Get the SPI IT index */ + itpos = 0x01 << (SPI_I2S_IT & 0x0F); + + /* Clear the selected SPI CRC Error (CRCERR) interrupt pending bit */ + SPIx->SR = (uint16_t)~itpos; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c index 2f31c9a1a..10e33ed72 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c @@ -1,2888 +1,2888 @@ -/** - ****************************************************************************** - * @file stm32f10x_tim.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the TIM firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_tim.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup TIM - * @brief TIM driver modules - * @{ - */ - -/** @defgroup TIM_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup TIM_Private_Defines - * @{ - */ - -/* ---------------------- TIM registers bit mask ------------------------ */ -#define SMCR_ETR_Mask ((uint16_t)0x00FF) -#define CCMR_Offset ((uint16_t)0x0018) -#define CCER_CCE_Set ((uint16_t)0x0001) -#define CCER_CCNE_Set ((uint16_t)0x0004) - -/** - * @} - */ - -/** @defgroup TIM_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup TIM_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup TIM_Private_FunctionPrototypes - * @{ - */ - -static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter); -static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter); -static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter); -static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter); -/** - * @} - */ - -/** @defgroup TIM_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup TIM_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup TIM_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup TIM_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the TIMx peripheral registers to their default reset values. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @retval None - */ -void TIM_DeInit(TIM_TypeDef* TIMx) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - - if (TIMx == TIM1) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, DISABLE); - } - else if (TIMx == TIM2) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE); - } - else if (TIMx == TIM3) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE); - } - else if (TIMx == TIM4) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE); - } - else if (TIMx == TIM5) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, DISABLE); - } - else if (TIMx == TIM6) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, DISABLE); - } - else if (TIMx == TIM7) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, DISABLE); - } - else if (TIMx == TIM8) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, DISABLE); - } - else if (TIMx == TIM9) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, DISABLE); - } - else if (TIMx == TIM10) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, DISABLE); - } - else if (TIMx == TIM11) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, DISABLE); - } - else if (TIMx == TIM12) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, DISABLE); - } - else if (TIMx == TIM13) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, DISABLE); - } - else if (TIMx == TIM14) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, DISABLE); - } - else if (TIMx == TIM15) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, DISABLE); - } - else if (TIMx == TIM16) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM16, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM16, DISABLE); - } - else - { - if (TIMx == TIM17) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM17, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM17, DISABLE); - } - } -} - -/** - * @brief Initializes the TIMx Time Base Unit peripheral according to - * the specified parameters in the TIM_TimeBaseInitStruct. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param TIM_TimeBaseInitStruct: pointer to a TIM_TimeBaseInitTypeDef - * structure that contains the configuration information for the specified TIM peripheral. - * @retval None - */ -void TIM_TimeBaseInit(TIM_TypeDef* TIMx, const TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) -{ - uint16_t tmpcr1 = 0; - - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_TIM_COUNTER_MODE(TIM_TimeBaseInitStruct->TIM_CounterMode)); - assert_param(IS_TIM_CKD_DIV(TIM_TimeBaseInitStruct->TIM_ClockDivision)); - - tmpcr1 = TIMx->CR1; - - if((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM2) || (TIMx == TIM3)|| - (TIMx == TIM4) || (TIMx == TIM5)) - { - /* Select the Counter Mode */ - tmpcr1 &= (uint16_t)(~((uint16_t)(TIM_CR1_DIR | TIM_CR1_CMS))); - tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_CounterMode; - } - - if((TIMx != TIM6) && (TIMx != TIM7)) - { - /* Set the clock division */ - tmpcr1 &= (uint16_t)(~((uint16_t)TIM_CR1_CKD)); - tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_ClockDivision; - } - - TIMx->CR1 = tmpcr1; - - /* Set the Autoreload value */ - TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period ; - - /* Set the Prescaler value */ - TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler; - - if ((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM15)|| (TIMx == TIM16) || (TIMx == TIM17)) - { - /* Set the Repetition Counter value */ - TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter; - } - - /* Generate an update event to reload the Prescaler and the Repetition counter - values immediately */ - TIMx->EGR = TIM_PSCReloadMode_Immediate; -} - -/** - * @brief Initializes the TIMx Channel1 according to the specified - * parameters in the TIM_OCInitStruct. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure - * that contains the configuration information for the specified TIM peripheral. - * @retval None - */ -void TIM_OC1Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) -{ - uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; - - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); - assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); - assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); - /* Disable the Channel 1: Reset the CC1E Bit */ - TIMx->CCER &= (uint16_t)(~(uint16_t)TIM_CCER_CC1E); - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR1 register value */ - tmpccmrx = TIMx->CCMR1; - - /* Reset the Output Compare Mode Bits */ - tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_OC1M)); - tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_CC1S)); - - /* Select the Output Compare Mode */ - tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; - - /* Reset the Output Polarity level */ - tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1P)); - /* Set the Output Compare Polarity */ - tmpccer |= TIM_OCInitStruct->TIM_OCPolarity; - - /* Set the Output State */ - tmpccer |= TIM_OCInitStruct->TIM_OutputState; - - if((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM15)|| - (TIMx == TIM16)|| (TIMx == TIM17)) - { - assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); - assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); - assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); - assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); - - /* Reset the Output N Polarity level */ - tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1NP)); - /* Set the Output N Polarity */ - tmpccer |= TIM_OCInitStruct->TIM_OCNPolarity; - - /* Reset the Output N State */ - tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1NE)); - /* Set the Output N State */ - tmpccer |= TIM_OCInitStruct->TIM_OutputNState; - - /* Reset the Ouput Compare and Output Compare N IDLE State */ - tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS1)); - tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS1N)); - - /* Set the Output Idle state */ - tmpcr2 |= TIM_OCInitStruct->TIM_OCIdleState; - /* Set the Output N Idle state */ - tmpcr2 |= TIM_OCInitStruct->TIM_OCNIdleState; - } - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR1 */ - TIMx->CCMR1 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR1 = TIM_OCInitStruct->TIM_Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Initializes the TIMx Channel2 according to the specified - * parameters in the TIM_OCInitStruct. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select - * the TIM peripheral. - * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure - * that contains the configuration information for the specified TIM peripheral. - * @retval None - */ -void TIM_OC2Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) -{ - uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; - - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); - assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); - assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); - /* Disable the Channel 2: Reset the CC2E Bit */ - TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC2E)); - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR1 register value */ - tmpccmrx = TIMx->CCMR1; - - /* Reset the Output Compare mode and Capture/Compare selection Bits */ - tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_OC2M)); - tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_CC2S)); - - /* Select the Output Compare Mode */ - tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8); - - /* Reset the Output Polarity level */ - tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2P)); - /* Set the Output Compare Polarity */ - tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 4); - - /* Set the Output State */ - tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 4); - - if((TIMx == TIM1) || (TIMx == TIM8)) - { - assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); - assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); - assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); - assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); - - /* Reset the Output N Polarity level */ - tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2NP)); - /* Set the Output N Polarity */ - tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 4); - - /* Reset the Output N State */ - tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2NE)); - /* Set the Output N State */ - tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 4); - - /* Reset the Ouput Compare and Output Compare N IDLE State */ - tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS2)); - tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS2N)); - - /* Set the Output Idle state */ - tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 2); - /* Set the Output N Idle state */ - tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 2); - } - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR1 */ - TIMx->CCMR1 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR2 = TIM_OCInitStruct->TIM_Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Initializes the TIMx Channel3 according to the specified - * parameters in the TIM_OCInitStruct. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure - * that contains the configuration information for the specified TIM peripheral. - * @retval None - */ -void TIM_OC3Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) -{ - uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; - - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); - assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); - assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); - /* Disable the Channel 2: Reset the CC2E Bit */ - TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC3E)); - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR2 register value */ - tmpccmrx = TIMx->CCMR2; - - /* Reset the Output Compare mode and Capture/Compare selection Bits */ - tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_OC3M)); - tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_CC3S)); - /* Select the Output Compare Mode */ - tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; - - /* Reset the Output Polarity level */ - tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3P)); - /* Set the Output Compare Polarity */ - tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 8); - - /* Set the Output State */ - tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 8); - - if((TIMx == TIM1) || (TIMx == TIM8)) - { - assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); - assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); - assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); - assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); - - /* Reset the Output N Polarity level */ - tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3NP)); - /* Set the Output N Polarity */ - tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 8); - /* Reset the Output N State */ - tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3NE)); - - /* Set the Output N State */ - tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 8); - /* Reset the Ouput Compare and Output Compare N IDLE State */ - tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS3)); - tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS3N)); - /* Set the Output Idle state */ - tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 4); - /* Set the Output N Idle state */ - tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 4); - } - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR2 */ - TIMx->CCMR2 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR3 = TIM_OCInitStruct->TIM_Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Initializes the TIMx Channel4 according to the specified - * parameters in the TIM_OCInitStruct. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure - * that contains the configuration information for the specified TIM peripheral. - * @retval None - */ -void TIM_OC4Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) -{ - uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; - - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); - assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); - assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); - /* Disable the Channel 2: Reset the CC4E Bit */ - TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC4E)); - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - /* Get the TIMx CR2 register value */ - tmpcr2 = TIMx->CR2; - - /* Get the TIMx CCMR2 register value */ - tmpccmrx = TIMx->CCMR2; - - /* Reset the Output Compare mode and Capture/Compare selection Bits */ - tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_OC4M)); - tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_CC4S)); - - /* Select the Output Compare Mode */ - tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8); - - /* Reset the Output Polarity level */ - tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC4P)); - /* Set the Output Compare Polarity */ - tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 12); - - /* Set the Output State */ - tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 12); - - if((TIMx == TIM1) || (TIMx == TIM8)) - { - assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); - /* Reset the Ouput Compare IDLE State */ - tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS4)); - /* Set the Output Idle state */ - tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 6); - } - /* Write to TIMx CR2 */ - TIMx->CR2 = tmpcr2; - - /* Write to TIMx CCMR2 */ - TIMx->CCMR2 = tmpccmrx; - - /* Set the Capture Compare Register value */ - TIMx->CCR4 = TIM_OCInitStruct->TIM_Pulse; - - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Initializes the TIM peripheral according to the specified - * parameters in the TIM_ICInitStruct. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure - * that contains the configuration information for the specified TIM peripheral. - * @retval None - */ -void TIM_ICInit(TIM_TypeDef* TIMx, const TIM_ICInitTypeDef* TIM_ICInitStruct) -{ - /* Check the parameters */ - assert_param(IS_TIM_CHANNEL(TIM_ICInitStruct->TIM_Channel)); - assert_param(IS_TIM_IC_SELECTION(TIM_ICInitStruct->TIM_ICSelection)); - assert_param(IS_TIM_IC_PRESCALER(TIM_ICInitStruct->TIM_ICPrescaler)); - assert_param(IS_TIM_IC_FILTER(TIM_ICInitStruct->TIM_ICFilter)); - - if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || - (TIMx == TIM4) ||(TIMx == TIM5)) - { - assert_param(IS_TIM_IC_POLARITY(TIM_ICInitStruct->TIM_ICPolarity)); - } - else - { - assert_param(IS_TIM_IC_POLARITY_LITE(TIM_ICInitStruct->TIM_ICPolarity)); - } - if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) - { - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - /* TI1 Configuration */ - TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, - TIM_ICInitStruct->TIM_ICSelection, - TIM_ICInitStruct->TIM_ICFilter); - /* Set the Input Capture Prescaler value */ - TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); - } - else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_2) - { - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - /* TI2 Configuration */ - TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, - TIM_ICInitStruct->TIM_ICSelection, - TIM_ICInitStruct->TIM_ICFilter); - /* Set the Input Capture Prescaler value */ - TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); - } - else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_3) - { - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - /* TI3 Configuration */ - TI3_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, - TIM_ICInitStruct->TIM_ICSelection, - TIM_ICInitStruct->TIM_ICFilter); - /* Set the Input Capture Prescaler value */ - TIM_SetIC3Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); - } - else - { - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - /* TI4 Configuration */ - TI4_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, - TIM_ICInitStruct->TIM_ICSelection, - TIM_ICInitStruct->TIM_ICFilter); - /* Set the Input Capture Prescaler value */ - TIM_SetIC4Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); - } -} - -/** - * @brief Configures the TIM peripheral according to the specified - * parameters in the TIM_ICInitStruct to measure an external PWM signal. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure - * that contains the configuration information for the specified TIM peripheral. - * @retval None - */ -void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) -{ - uint16_t icoppositepolarity = TIM_ICPolarity_Rising; - uint16_t icoppositeselection = TIM_ICSelection_DirectTI; - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - /* Select the Opposite Input Polarity */ - if (TIM_ICInitStruct->TIM_ICPolarity == TIM_ICPolarity_Rising) - { - icoppositepolarity = TIM_ICPolarity_Falling; - } - else - { - icoppositepolarity = TIM_ICPolarity_Rising; - } - /* Select the Opposite Input */ - if (TIM_ICInitStruct->TIM_ICSelection == TIM_ICSelection_DirectTI) - { - icoppositeselection = TIM_ICSelection_IndirectTI; - } - else - { - icoppositeselection = TIM_ICSelection_DirectTI; - } - if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) - { - /* TI1 Configuration */ - TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, - TIM_ICInitStruct->TIM_ICFilter); - /* Set the Input Capture Prescaler value */ - TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); - /* TI2 Configuration */ - TI2_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); - /* Set the Input Capture Prescaler value */ - TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); - } - else - { - /* TI2 Configuration */ - TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, - TIM_ICInitStruct->TIM_ICFilter); - /* Set the Input Capture Prescaler value */ - TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); - /* TI1 Configuration */ - TI1_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); - /* Set the Input Capture Prescaler value */ - TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); - } -} - -/** - * @brief Configures the: Break feature, dead time, Lock level, the OSSI, - * the OSSR State and the AOE(automatic output enable). - * @param TIMx: where x can be 1 or 8 to select the TIM - * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure that - * contains the BDTR Register configuration information for the TIM peripheral. - * @retval None - */ -void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST2_PERIPH(TIMx)); - assert_param(IS_TIM_OSSR_STATE(TIM_BDTRInitStruct->TIM_OSSRState)); - assert_param(IS_TIM_OSSI_STATE(TIM_BDTRInitStruct->TIM_OSSIState)); - assert_param(IS_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->TIM_LOCKLevel)); - assert_param(IS_TIM_BREAK_STATE(TIM_BDTRInitStruct->TIM_Break)); - assert_param(IS_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->TIM_BreakPolarity)); - assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->TIM_AutomaticOutput)); - /* Set the Lock level, the Break enable Bit and the Ploarity, the OSSR State, - the OSSI State, the dead time value and the Automatic Output Enable Bit */ - TIMx->BDTR = (uint32_t)TIM_BDTRInitStruct->TIM_OSSRState | TIM_BDTRInitStruct->TIM_OSSIState | - TIM_BDTRInitStruct->TIM_LOCKLevel | TIM_BDTRInitStruct->TIM_DeadTime | - TIM_BDTRInitStruct->TIM_Break | TIM_BDTRInitStruct->TIM_BreakPolarity | - TIM_BDTRInitStruct->TIM_AutomaticOutput; -} - -/** - * @brief Fills each TIM_TimeBaseInitStruct member with its default value. - * @param TIM_TimeBaseInitStruct : pointer to a TIM_TimeBaseInitTypeDef - * structure which will be initialized. - * @retval None - */ -void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) -{ - /* Set the default configuration */ - TIM_TimeBaseInitStruct->TIM_Period = 0xFFFF; - TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000; - TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1; - TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000; -} - -/** - * @brief Fills each TIM_OCInitStruct member with its default value. - * @param TIM_OCInitStruct : pointer to a TIM_OCInitTypeDef structure which will - * be initialized. - * @retval None - */ -void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct) -{ - /* Set the default configuration */ - TIM_OCInitStruct->TIM_OCMode = TIM_OCMode_Timing; - TIM_OCInitStruct->TIM_OutputState = TIM_OutputState_Disable; - TIM_OCInitStruct->TIM_OutputNState = TIM_OutputNState_Disable; - TIM_OCInitStruct->TIM_Pulse = 0x0000; - TIM_OCInitStruct->TIM_OCPolarity = TIM_OCPolarity_High; - TIM_OCInitStruct->TIM_OCNPolarity = TIM_OCPolarity_High; - TIM_OCInitStruct->TIM_OCIdleState = TIM_OCIdleState_Reset; - TIM_OCInitStruct->TIM_OCNIdleState = TIM_OCNIdleState_Reset; -} - -/** - * @brief Fills each TIM_ICInitStruct member with its default value. - * @param TIM_ICInitStruct : pointer to a TIM_ICInitTypeDef structure which will - * be initialized. - * @retval None - */ -void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct) -{ - /* Set the default configuration */ - TIM_ICInitStruct->TIM_Channel = TIM_Channel_1; - TIM_ICInitStruct->TIM_ICPolarity = TIM_ICPolarity_Rising; - TIM_ICInitStruct->TIM_ICSelection = TIM_ICSelection_DirectTI; - TIM_ICInitStruct->TIM_ICPrescaler = TIM_ICPSC_DIV1; - TIM_ICInitStruct->TIM_ICFilter = 0x00; -} - -/** - * @brief Fills each TIM_BDTRInitStruct member with its default value. - * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure which - * will be initialized. - * @retval None - */ -void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct) -{ - /* Set the default configuration */ - TIM_BDTRInitStruct->TIM_OSSRState = TIM_OSSRState_Disable; - TIM_BDTRInitStruct->TIM_OSSIState = TIM_OSSIState_Disable; - TIM_BDTRInitStruct->TIM_LOCKLevel = TIM_LOCKLevel_OFF; - TIM_BDTRInitStruct->TIM_DeadTime = 0x00; - TIM_BDTRInitStruct->TIM_Break = TIM_Break_Disable; - TIM_BDTRInitStruct->TIM_BreakPolarity = TIM_BreakPolarity_Low; - TIM_BDTRInitStruct->TIM_AutomaticOutput = TIM_AutomaticOutput_Disable; -} - -/** - * @brief Enables or disables the specified TIM peripheral. - * @param TIMx: where x can be 1 to 17 to select the TIMx peripheral. - * @param NewState: new state of the TIMx peripheral. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the TIM Counter */ - TIMx->CR1 |= TIM_CR1_CEN; - } - else - { - /* Disable the TIM Counter */ - TIMx->CR1 &= (uint16_t)(~((uint16_t)TIM_CR1_CEN)); - } -} - -/** - * @brief Enables or disables the TIM peripheral Main Outputs. - * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIMx peripheral. - * @param NewState: new state of the TIM peripheral Main Outputs. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST2_PERIPH(TIMx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the TIM Main Output */ - TIMx->BDTR |= TIM_BDTR_MOE; - } - else - { - /* Disable the TIM Main Output */ - TIMx->BDTR &= (uint16_t)(~((uint16_t)TIM_BDTR_MOE)); - } -} - -/** - * @brief Enables or disables the specified TIM interrupts. - * @param TIMx: where x can be 1 to 17 to select the TIMx peripheral. - * @param TIM_IT: specifies the TIM interrupts sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg TIM_IT_Update: TIM update Interrupt source - * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source - * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source - * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source - * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source - * @arg TIM_IT_COM: TIM Commutation Interrupt source - * @arg TIM_IT_Trigger: TIM Trigger Interrupt source - * @arg TIM_IT_Break: TIM Break Interrupt source - * @note - * - TIM6 and TIM7 can only generate an update interrupt. - * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, - * TIM_IT_CC2 or TIM_IT_Trigger. - * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. - * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. - * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. - * @param NewState: new state of the TIM interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_TIM_IT(TIM_IT)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the Interrupt sources */ - TIMx->DIER |= TIM_IT; - } - else - { - /* Disable the Interrupt sources */ - TIMx->DIER &= (uint16_t)~TIM_IT; - } -} - -/** - * @brief Configures the TIMx event to be generate by software. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param TIM_EventSource: specifies the event source. - * This parameter can be one or more of the following values: - * @arg TIM_EventSource_Update: Timer update Event source - * @arg TIM_EventSource_CC1: Timer Capture Compare 1 Event source - * @arg TIM_EventSource_CC2: Timer Capture Compare 2 Event source - * @arg TIM_EventSource_CC3: Timer Capture Compare 3 Event source - * @arg TIM_EventSource_CC4: Timer Capture Compare 4 Event source - * @arg TIM_EventSource_COM: Timer COM event source - * @arg TIM_EventSource_Trigger: Timer Trigger Event source - * @arg TIM_EventSource_Break: Timer Break event source - * @note - * - TIM6 and TIM7 can only generate an update event. - * - TIM_EventSource_COM and TIM_EventSource_Break are used only with TIM1 and TIM8. - * @retval None - */ -void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_TIM_EVENT_SOURCE(TIM_EventSource)); - - /* Set the event sources */ - TIMx->EGR = TIM_EventSource; -} - -/** - * @brief Configures the TIMx’s DMA interface. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 15, 16 or 17 to select - * the TIM peripheral. - * @param TIM_DMABase: DMA Base address. - * This parameter can be one of the following values: - * @arg TIM_DMABase_CR, TIM_DMABase_CR2, TIM_DMABase_SMCR, - * TIM_DMABase_DIER, TIM1_DMABase_SR, TIM_DMABase_EGR, - * TIM_DMABase_CCMR1, TIM_DMABase_CCMR2, TIM_DMABase_CCER, - * TIM_DMABase_CNT, TIM_DMABase_PSC, TIM_DMABase_ARR, - * TIM_DMABase_RCR, TIM_DMABase_CCR1, TIM_DMABase_CCR2, - * TIM_DMABase_CCR3, TIM_DMABase_CCR4, TIM_DMABase_BDTR, - * TIM_DMABase_DCR. - * @param TIM_DMABurstLength: DMA Burst length. - * This parameter can be one value between: - * TIM_DMABurstLength_1Byte and TIM_DMABurstLength_18Bytes. - * @retval None - */ -void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST4_PERIPH(TIMx)); - assert_param(IS_TIM_DMA_BASE(TIM_DMABase)); - assert_param(IS_TIM_DMA_LENGTH(TIM_DMABurstLength)); - /* Set the DMA Base and the DMA Burst Length */ - TIMx->DCR = TIM_DMABase | TIM_DMABurstLength; -} - -/** - * @brief Enables or disables the TIMx’s DMA Requests. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7, 8, 15, 16 or 17 - * to select the TIM peripheral. - * @param TIM_DMASource: specifies the DMA Request sources. - * This parameter can be any combination of the following values: - * @arg TIM_DMA_Update: TIM update Interrupt source - * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source - * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source - * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source - * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source - * @arg TIM_DMA_COM: TIM Commutation DMA source - * @arg TIM_DMA_Trigger: TIM Trigger DMA source - * @param NewState: new state of the DMA Request sources. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST9_PERIPH(TIMx)); - assert_param(IS_TIM_DMA_SOURCE(TIM_DMASource)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the DMA sources */ - TIMx->DIER |= TIM_DMASource; - } - else - { - /* Disable the DMA sources */ - TIMx->DIER &= (uint16_t)~TIM_DMASource; - } -} - -/** - * @brief Configures the TIMx interrnal Clock - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 - * to select the TIM peripheral. - * @retval None - */ -void TIM_InternalClockConfig(TIM_TypeDef* TIMx) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - /* Disable slave mode to clock the prescaler directly with the internal clock */ - TIMx->SMCR &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); -} - -/** - * @brief Configures the TIMx Internal Trigger as External Clock - * @param TIMx: where x can be 1, 2, 3, 4, 5, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_ITRSource: Trigger source. - * This parameter can be one of the following values: - * @param TIM_TS_ITR0: Internal Trigger 0 - * @param TIM_TS_ITR1: Internal Trigger 1 - * @param TIM_TS_ITR2: Internal Trigger 2 - * @param TIM_TS_ITR3: Internal Trigger 3 - * @retval None - */ -void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_INTERNAL_TRIGGER_SELECTION(TIM_InputTriggerSource)); - /* Select the Internal Trigger */ - TIM_SelectInputTrigger(TIMx, TIM_InputTriggerSource); - /* Select the External clock mode1 */ - TIMx->SMCR |= TIM_SlaveMode_External1; -} - -/** - * @brief Configures the TIMx Trigger as External Clock - * @param TIMx: where x can be 1, 2, 3, 4, 5, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_TIxExternalCLKSource: Trigger source. - * This parameter can be one of the following values: - * @arg TIM_TIxExternalCLK1Source_TI1ED: TI1 Edge Detector - * @arg TIM_TIxExternalCLK1Source_TI1: Filtered Timer Input 1 - * @arg TIM_TIxExternalCLK1Source_TI2: Filtered Timer Input 2 - * @param TIM_ICPolarity: specifies the TIx Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPolarity_Rising - * @arg TIM_ICPolarity_Falling - * @param ICFilter : specifies the filter value. - * This parameter must be a value between 0x0 and 0xF. - * @retval None - */ -void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, - uint16_t TIM_ICPolarity, uint16_t ICFilter) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_TIXCLK_SOURCE(TIM_TIxExternalCLKSource)); - assert_param(IS_TIM_IC_POLARITY(TIM_ICPolarity)); - assert_param(IS_TIM_IC_FILTER(ICFilter)); - /* Configure the Timer Input Clock Source */ - if (TIM_TIxExternalCLKSource == TIM_TIxExternalCLK1Source_TI2) - { - TI2_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); - } - else - { - TI1_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); - } - /* Select the Trigger source */ - TIM_SelectInputTrigger(TIMx, TIM_TIxExternalCLKSource); - /* Select the External clock mode1 */ - TIMx->SMCR |= TIM_SlaveMode_External1; -} - -/** - * @brief Configures the External clock Mode1 - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. - * This parameter can be one of the following values: - * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. - * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. - * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. - * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. - * @param TIM_ExtTRGPolarity: The external Trigger Polarity. - * This parameter can be one of the following values: - * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. - * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. - * @param ExtTRGFilter: External Trigger Filter. - * This parameter must be a value between 0x00 and 0x0F - * @retval None - */ -void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, - uint16_t ExtTRGFilter) -{ - uint16_t tmpsmcr = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); - assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); - assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); - /* Configure the ETR Clock source */ - TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); - - /* Get the TIMx SMCR register value */ - tmpsmcr = TIMx->SMCR; - /* Reset the SMS Bits */ - tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); - /* Select the External clock mode1 */ - tmpsmcr |= TIM_SlaveMode_External1; - /* Select the Trigger selection : ETRF */ - tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_TS)); - tmpsmcr |= TIM_TS_ETRF; - /* Write to TIMx SMCR */ - TIMx->SMCR = tmpsmcr; -} - -/** - * @brief Configures the External clock Mode2 - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. - * This parameter can be one of the following values: - * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. - * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. - * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. - * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. - * @param TIM_ExtTRGPolarity: The external Trigger Polarity. - * This parameter can be one of the following values: - * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. - * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. - * @param ExtTRGFilter: External Trigger Filter. - * This parameter must be a value between 0x00 and 0x0F - * @retval None - */ -void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, - uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); - assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); - assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); - /* Configure the ETR Clock source */ - TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); - /* Enable the External clock mode2 */ - TIMx->SMCR |= TIM_SMCR_ECE; -} - -/** - * @brief Configures the TIMx External Trigger (ETR). - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. - * This parameter can be one of the following values: - * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. - * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. - * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. - * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. - * @param TIM_ExtTRGPolarity: The external Trigger Polarity. - * This parameter can be one of the following values: - * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. - * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. - * @param ExtTRGFilter: External Trigger Filter. - * This parameter must be a value between 0x00 and 0x0F - * @retval None - */ -void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, - uint16_t ExtTRGFilter) -{ - uint16_t tmpsmcr = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); - assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); - assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); - tmpsmcr = TIMx->SMCR; - /* Reset the ETR Bits */ - tmpsmcr &= SMCR_ETR_Mask; - /* Set the Prescaler, the Filter value and the Polarity */ - tmpsmcr |= (uint16_t)(TIM_ExtTRGPrescaler | (uint16_t)(TIM_ExtTRGPolarity | (uint16_t)(ExtTRGFilter << (uint16_t)8))); - /* Write to TIMx SMCR */ - TIMx->SMCR = tmpsmcr; -} - -/** - * @brief Configures the TIMx Prescaler. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param Prescaler: specifies the Prescaler Register value - * @param TIM_PSCReloadMode: specifies the TIM Prescaler Reload mode - * This parameter can be one of the following values: - * @arg TIM_PSCReloadMode_Update: The Prescaler is loaded at the update event. - * @arg TIM_PSCReloadMode_Immediate: The Prescaler is loaded immediately. - * @retval None - */ -void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_TIM_PRESCALER_RELOAD(TIM_PSCReloadMode)); - /* Set the Prescaler value */ - TIMx->PSC = Prescaler; - /* Set or reset the UG Bit */ - TIMx->EGR = TIM_PSCReloadMode; -} - -/** - * @brief Specifies the TIMx Counter Mode to be used. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_CounterMode: specifies the Counter Mode to be used - * This parameter can be one of the following values: - * @arg TIM_CounterMode_Up: TIM Up Counting Mode - * @arg TIM_CounterMode_Down: TIM Down Counting Mode - * @arg TIM_CounterMode_CenterAligned1: TIM Center Aligned Mode1 - * @arg TIM_CounterMode_CenterAligned2: TIM Center Aligned Mode2 - * @arg TIM_CounterMode_CenterAligned3: TIM Center Aligned Mode3 - * @retval None - */ -void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode) -{ - uint16_t tmpcr1 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_COUNTER_MODE(TIM_CounterMode)); - tmpcr1 = TIMx->CR1; - /* Reset the CMS and DIR Bits */ - tmpcr1 &= (uint16_t)(~((uint16_t)(TIM_CR1_DIR | TIM_CR1_CMS))); - /* Set the Counter Mode */ - tmpcr1 |= TIM_CounterMode; - /* Write to TIMx CR1 register */ - TIMx->CR1 = tmpcr1; -} - -/** - * @brief Selects the Input Trigger source - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_InputTriggerSource: The Input Trigger source. - * This parameter can be one of the following values: - * @arg TIM_TS_ITR0: Internal Trigger 0 - * @arg TIM_TS_ITR1: Internal Trigger 1 - * @arg TIM_TS_ITR2: Internal Trigger 2 - * @arg TIM_TS_ITR3: Internal Trigger 3 - * @arg TIM_TS_TI1F_ED: TI1 Edge Detector - * @arg TIM_TS_TI1FP1: Filtered Timer Input 1 - * @arg TIM_TS_TI2FP2: Filtered Timer Input 2 - * @arg TIM_TS_ETRF: External Trigger input - * @retval None - */ -void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) -{ - uint16_t tmpsmcr = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_TRIGGER_SELECTION(TIM_InputTriggerSource)); - /* Get the TIMx SMCR register value */ - tmpsmcr = TIMx->SMCR; - /* Reset the TS Bits */ - tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_TS)); - /* Set the Input Trigger source */ - tmpsmcr |= TIM_InputTriggerSource; - /* Write to TIMx SMCR */ - TIMx->SMCR = tmpsmcr; -} - -/** - * @brief Configures the TIMx Encoder Interface. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_EncoderMode: specifies the TIMx Encoder Mode. - * This parameter can be one of the following values: - * @arg TIM_EncoderMode_TI1: Counter counts on TI1FP1 edge depending on TI2FP2 level. - * @arg TIM_EncoderMode_TI2: Counter counts on TI2FP2 edge depending on TI1FP1 level. - * @arg TIM_EncoderMode_TI12: Counter counts on both TI1FP1 and TI2FP2 edges depending - * on the level of the other input. - * @param TIM_IC1Polarity: specifies the IC1 Polarity - * This parmeter can be one of the following values: - * @arg TIM_ICPolarity_Falling: IC Falling edge. - * @arg TIM_ICPolarity_Rising: IC Rising edge. - * @param TIM_IC2Polarity: specifies the IC2 Polarity - * This parmeter can be one of the following values: - * @arg TIM_ICPolarity_Falling: IC Falling edge. - * @arg TIM_ICPolarity_Rising: IC Rising edge. - * @retval None - */ -void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, - uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity) -{ - uint16_t tmpsmcr = 0; - uint16_t tmpccmr1 = 0; - uint16_t tmpccer = 0; - - /* Check the parameters */ - assert_param(IS_TIM_LIST5_PERIPH(TIMx)); - assert_param(IS_TIM_ENCODER_MODE(TIM_EncoderMode)); - assert_param(IS_TIM_IC_POLARITY(TIM_IC1Polarity)); - assert_param(IS_TIM_IC_POLARITY(TIM_IC2Polarity)); - - /* Get the TIMx SMCR register value */ - tmpsmcr = TIMx->SMCR; - - /* Get the TIMx CCMR1 register value */ - tmpccmr1 = TIMx->CCMR1; - - /* Get the TIMx CCER register value */ - tmpccer = TIMx->CCER; - - /* Set the encoder Mode */ - tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); - tmpsmcr |= TIM_EncoderMode; - - /* Select the Capture Compare 1 and the Capture Compare 2 as input */ - tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC1S)) & (uint16_t)(~((uint16_t)TIM_CCMR1_CC2S))); - tmpccmr1 |= TIM_CCMR1_CC1S_0 | TIM_CCMR1_CC2S_0; - - /* Set the TI1 and the TI2 Polarities */ - tmpccer &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCER_CC1P)) & ((uint16_t)~((uint16_t)TIM_CCER_CC2P))); - tmpccer |= (uint16_t)(TIM_IC1Polarity | (uint16_t)(TIM_IC2Polarity << (uint16_t)4)); - - /* Write to TIMx SMCR */ - TIMx->SMCR = tmpsmcr; - /* Write to TIMx CCMR1 */ - TIMx->CCMR1 = tmpccmr1; - /* Write to TIMx CCER */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Forces the TIMx output 1 waveform to active or inactive level. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. - * This parameter can be one of the following values: - * @arg TIM_ForcedAction_Active: Force active level on OC1REF - * @arg TIM_ForcedAction_InActive: Force inactive level on OC1REF. - * @retval None - */ -void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) -{ - uint16_t tmpccmr1 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); - tmpccmr1 = TIMx->CCMR1; - /* Reset the OC1M Bits */ - tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1M); - /* Configure The Forced output Mode */ - tmpccmr1 |= TIM_ForcedAction; - /* Write to TIMx CCMR1 register */ - TIMx->CCMR1 = tmpccmr1; -} - -/** - * @brief Forces the TIMx output 2 waveform to active or inactive level. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. - * This parameter can be one of the following values: - * @arg TIM_ForcedAction_Active: Force active level on OC2REF - * @arg TIM_ForcedAction_InActive: Force inactive level on OC2REF. - * @retval None - */ -void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) -{ - uint16_t tmpccmr1 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); - tmpccmr1 = TIMx->CCMR1; - /* Reset the OC2M Bits */ - tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2M); - /* Configure The Forced output Mode */ - tmpccmr1 |= (uint16_t)(TIM_ForcedAction << 8); - /* Write to TIMx CCMR1 register */ - TIMx->CCMR1 = tmpccmr1; -} - -/** - * @brief Forces the TIMx output 3 waveform to active or inactive level. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. - * This parameter can be one of the following values: - * @arg TIM_ForcedAction_Active: Force active level on OC3REF - * @arg TIM_ForcedAction_InActive: Force inactive level on OC3REF. - * @retval None - */ -void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) -{ - uint16_t tmpccmr2 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); - tmpccmr2 = TIMx->CCMR2; - /* Reset the OC1M Bits */ - tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3M); - /* Configure The Forced output Mode */ - tmpccmr2 |= TIM_ForcedAction; - /* Write to TIMx CCMR2 register */ - TIMx->CCMR2 = tmpccmr2; -} - -/** - * @brief Forces the TIMx output 4 waveform to active or inactive level. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. - * This parameter can be one of the following values: - * @arg TIM_ForcedAction_Active: Force active level on OC4REF - * @arg TIM_ForcedAction_InActive: Force inactive level on OC4REF. - * @retval None - */ -void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) -{ - uint16_t tmpccmr2 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); - tmpccmr2 = TIMx->CCMR2; - /* Reset the OC2M Bits */ - tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4M); - /* Configure The Forced output Mode */ - tmpccmr2 |= (uint16_t)(TIM_ForcedAction << 8); - /* Write to TIMx CCMR2 register */ - TIMx->CCMR2 = tmpccmr2; -} - -/** - * @brief Enables or disables TIMx peripheral Preload register on ARR. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param NewState: new state of the TIMx peripheral Preload register - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Set the ARR Preload Bit */ - TIMx->CR1 |= TIM_CR1_ARPE; - } - else - { - /* Reset the ARR Preload Bit */ - TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_ARPE); - } -} - -/** - * @brief Selects the TIM peripheral Commutation event. - * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIMx peripheral - * @param NewState: new state of the Commutation event. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST2_PERIPH(TIMx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Set the COM Bit */ - TIMx->CR2 |= TIM_CR2_CCUS; - } - else - { - /* Reset the COM Bit */ - TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCUS); - } -} - -/** - * @brief Selects the TIMx peripheral Capture Compare DMA source. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 15, 16 or 17 to select - * the TIM peripheral. - * @param NewState: new state of the Capture Compare DMA source - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST4_PERIPH(TIMx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Set the CCDS Bit */ - TIMx->CR2 |= TIM_CR2_CCDS; - } - else - { - /* Reset the CCDS Bit */ - TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCDS); - } -} - -/** - * @brief Sets or Resets the TIM peripheral Capture Compare Preload Control bit. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8 or 15 - * to select the TIMx peripheral - * @param NewState: new state of the Capture Compare Preload Control bit - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST5_PERIPH(TIMx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Set the CCPC Bit */ - TIMx->CR2 |= TIM_CR2_CCPC; - } - else - { - /* Reset the CCPC Bit */ - TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCPC); - } -} - -/** - * @brief Enables or disables the TIMx peripheral Preload register on CCR1. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param TIM_OCPreload: new state of the TIMx peripheral Preload register - * This parameter can be one of the following values: - * @arg TIM_OCPreload_Enable - * @arg TIM_OCPreload_Disable - * @retval None - */ -void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) -{ - uint16_t tmpccmr1 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); - tmpccmr1 = TIMx->CCMR1; - /* Reset the OC1PE Bit */ - tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1PE); - /* Enable or Disable the Output Compare Preload feature */ - tmpccmr1 |= TIM_OCPreload; - /* Write to TIMx CCMR1 register */ - TIMx->CCMR1 = tmpccmr1; -} - -/** - * @brief Enables or disables the TIMx peripheral Preload register on CCR2. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select - * the TIM peripheral. - * @param TIM_OCPreload: new state of the TIMx peripheral Preload register - * This parameter can be one of the following values: - * @arg TIM_OCPreload_Enable - * @arg TIM_OCPreload_Disable - * @retval None - */ -void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) -{ - uint16_t tmpccmr1 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); - tmpccmr1 = TIMx->CCMR1; - /* Reset the OC2PE Bit */ - tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2PE); - /* Enable or Disable the Output Compare Preload feature */ - tmpccmr1 |= (uint16_t)(TIM_OCPreload << 8); - /* Write to TIMx CCMR1 register */ - TIMx->CCMR1 = tmpccmr1; -} - -/** - * @brief Enables or disables the TIMx peripheral Preload register on CCR3. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCPreload: new state of the TIMx peripheral Preload register - * This parameter can be one of the following values: - * @arg TIM_OCPreload_Enable - * @arg TIM_OCPreload_Disable - * @retval None - */ -void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) -{ - uint16_t tmpccmr2 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); - tmpccmr2 = TIMx->CCMR2; - /* Reset the OC3PE Bit */ - tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3PE); - /* Enable or Disable the Output Compare Preload feature */ - tmpccmr2 |= TIM_OCPreload; - /* Write to TIMx CCMR2 register */ - TIMx->CCMR2 = tmpccmr2; -} - -/** - * @brief Enables or disables the TIMx peripheral Preload register on CCR4. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCPreload: new state of the TIMx peripheral Preload register - * This parameter can be one of the following values: - * @arg TIM_OCPreload_Enable - * @arg TIM_OCPreload_Disable - * @retval None - */ -void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) -{ - uint16_t tmpccmr2 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); - tmpccmr2 = TIMx->CCMR2; - /* Reset the OC4PE Bit */ - tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4PE); - /* Enable or Disable the Output Compare Preload feature */ - tmpccmr2 |= (uint16_t)(TIM_OCPreload << 8); - /* Write to TIMx CCMR2 register */ - TIMx->CCMR2 = tmpccmr2; -} - -/** - * @brief Configures the TIMx Output Compare 1 Fast feature. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. - * This parameter can be one of the following values: - * @arg TIM_OCFast_Enable: TIM output compare fast enable - * @arg TIM_OCFast_Disable: TIM output compare fast disable - * @retval None - */ -void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) -{ - uint16_t tmpccmr1 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); - /* Get the TIMx CCMR1 register value */ - tmpccmr1 = TIMx->CCMR1; - /* Reset the OC1FE Bit */ - tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1FE); - /* Enable or Disable the Output Compare Fast Bit */ - tmpccmr1 |= TIM_OCFast; - /* Write to TIMx CCMR1 */ - TIMx->CCMR1 = tmpccmr1; -} - -/** - * @brief Configures the TIMx Output Compare 2 Fast feature. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select - * the TIM peripheral. - * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. - * This parameter can be one of the following values: - * @arg TIM_OCFast_Enable: TIM output compare fast enable - * @arg TIM_OCFast_Disable: TIM output compare fast disable - * @retval None - */ -void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) -{ - uint16_t tmpccmr1 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); - /* Get the TIMx CCMR1 register value */ - tmpccmr1 = TIMx->CCMR1; - /* Reset the OC2FE Bit */ - tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2FE); - /* Enable or Disable the Output Compare Fast Bit */ - tmpccmr1 |= (uint16_t)(TIM_OCFast << 8); - /* Write to TIMx CCMR1 */ - TIMx->CCMR1 = tmpccmr1; -} - -/** - * @brief Configures the TIMx Output Compare 3 Fast feature. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. - * This parameter can be one of the following values: - * @arg TIM_OCFast_Enable: TIM output compare fast enable - * @arg TIM_OCFast_Disable: TIM output compare fast disable - * @retval None - */ -void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) -{ - uint16_t tmpccmr2 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); - /* Get the TIMx CCMR2 register value */ - tmpccmr2 = TIMx->CCMR2; - /* Reset the OC3FE Bit */ - tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3FE); - /* Enable or Disable the Output Compare Fast Bit */ - tmpccmr2 |= TIM_OCFast; - /* Write to TIMx CCMR2 */ - TIMx->CCMR2 = tmpccmr2; -} - -/** - * @brief Configures the TIMx Output Compare 4 Fast feature. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. - * This parameter can be one of the following values: - * @arg TIM_OCFast_Enable: TIM output compare fast enable - * @arg TIM_OCFast_Disable: TIM output compare fast disable - * @retval None - */ -void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) -{ - uint16_t tmpccmr2 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); - /* Get the TIMx CCMR2 register value */ - tmpccmr2 = TIMx->CCMR2; - /* Reset the OC4FE Bit */ - tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4FE); - /* Enable or Disable the Output Compare Fast Bit */ - tmpccmr2 |= (uint16_t)(TIM_OCFast << 8); - /* Write to TIMx CCMR2 */ - TIMx->CCMR2 = tmpccmr2; -} - -/** - * @brief Clears or safeguards the OCREF1 signal on an external event - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. - * This parameter can be one of the following values: - * @arg TIM_OCClear_Enable: TIM Output clear enable - * @arg TIM_OCClear_Disable: TIM Output clear disable - * @retval None - */ -void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) -{ - uint16_t tmpccmr1 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); - - tmpccmr1 = TIMx->CCMR1; - - /* Reset the OC1CE Bit */ - tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1CE); - /* Enable or Disable the Output Compare Clear Bit */ - tmpccmr1 |= TIM_OCClear; - /* Write to TIMx CCMR1 register */ - TIMx->CCMR1 = tmpccmr1; -} - -/** - * @brief Clears or safeguards the OCREF2 signal on an external event - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. - * This parameter can be one of the following values: - * @arg TIM_OCClear_Enable: TIM Output clear enable - * @arg TIM_OCClear_Disable: TIM Output clear disable - * @retval None - */ -void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) -{ - uint16_t tmpccmr1 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); - tmpccmr1 = TIMx->CCMR1; - /* Reset the OC2CE Bit */ - tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2CE); - /* Enable or Disable the Output Compare Clear Bit */ - tmpccmr1 |= (uint16_t)(TIM_OCClear << 8); - /* Write to TIMx CCMR1 register */ - TIMx->CCMR1 = tmpccmr1; -} - -/** - * @brief Clears or safeguards the OCREF3 signal on an external event - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. - * This parameter can be one of the following values: - * @arg TIM_OCClear_Enable: TIM Output clear enable - * @arg TIM_OCClear_Disable: TIM Output clear disable - * @retval None - */ -void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) -{ - uint16_t tmpccmr2 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); - tmpccmr2 = TIMx->CCMR2; - /* Reset the OC3CE Bit */ - tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3CE); - /* Enable or Disable the Output Compare Clear Bit */ - tmpccmr2 |= TIM_OCClear; - /* Write to TIMx CCMR2 register */ - TIMx->CCMR2 = tmpccmr2; -} - -/** - * @brief Clears or safeguards the OCREF4 signal on an external event - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. - * This parameter can be one of the following values: - * @arg TIM_OCClear_Enable: TIM Output clear enable - * @arg TIM_OCClear_Disable: TIM Output clear disable - * @retval None - */ -void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) -{ - uint16_t tmpccmr2 = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); - tmpccmr2 = TIMx->CCMR2; - /* Reset the OC4CE Bit */ - tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4CE); - /* Enable or Disable the Output Compare Clear Bit */ - tmpccmr2 |= (uint16_t)(TIM_OCClear << 8); - /* Write to TIMx CCMR2 register */ - TIMx->CCMR2 = tmpccmr2; -} - -/** - * @brief Configures the TIMx channel 1 polarity. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param TIM_OCPolarity: specifies the OC1 Polarity - * This parmeter can be one of the following values: - * @arg TIM_OCPolarity_High: Output Compare active high - * @arg TIM_OCPolarity_Low: Output Compare active low - * @retval None - */ -void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) -{ - uint16_t tmpccer = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); - tmpccer = TIMx->CCER; - /* Set or Reset the CC1P Bit */ - tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC1P); - tmpccer |= TIM_OCPolarity; - /* Write to TIMx CCER register */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Configures the TIMx Channel 1N polarity. - * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM peripheral. - * @param TIM_OCNPolarity: specifies the OC1N Polarity - * This parmeter can be one of the following values: - * @arg TIM_OCNPolarity_High: Output Compare active high - * @arg TIM_OCNPolarity_Low: Output Compare active low - * @retval None - */ -void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) -{ - uint16_t tmpccer = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST2_PERIPH(TIMx)); - assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); - - tmpccer = TIMx->CCER; - /* Set or Reset the CC1NP Bit */ - tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC1NP); - tmpccer |= TIM_OCNPolarity; - /* Write to TIMx CCER register */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Configures the TIMx channel 2 polarity. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_OCPolarity: specifies the OC2 Polarity - * This parmeter can be one of the following values: - * @arg TIM_OCPolarity_High: Output Compare active high - * @arg TIM_OCPolarity_Low: Output Compare active low - * @retval None - */ -void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) -{ - uint16_t tmpccer = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); - tmpccer = TIMx->CCER; - /* Set or Reset the CC2P Bit */ - tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC2P); - tmpccer |= (uint16_t)(TIM_OCPolarity << 4); - /* Write to TIMx CCER register */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Configures the TIMx Channel 2N polarity. - * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. - * @param TIM_OCNPolarity: specifies the OC2N Polarity - * This parmeter can be one of the following values: - * @arg TIM_OCNPolarity_High: Output Compare active high - * @arg TIM_OCNPolarity_Low: Output Compare active low - * @retval None - */ -void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) -{ - uint16_t tmpccer = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST1_PERIPH(TIMx)); - assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); - - tmpccer = TIMx->CCER; - /* Set or Reset the CC2NP Bit */ - tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC2NP); - tmpccer |= (uint16_t)(TIM_OCNPolarity << 4); - /* Write to TIMx CCER register */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Configures the TIMx channel 3 polarity. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCPolarity: specifies the OC3 Polarity - * This parmeter can be one of the following values: - * @arg TIM_OCPolarity_High: Output Compare active high - * @arg TIM_OCPolarity_Low: Output Compare active low - * @retval None - */ -void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) -{ - uint16_t tmpccer = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); - tmpccer = TIMx->CCER; - /* Set or Reset the CC3P Bit */ - tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC3P); - tmpccer |= (uint16_t)(TIM_OCPolarity << 8); - /* Write to TIMx CCER register */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Configures the TIMx Channel 3N polarity. - * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. - * @param TIM_OCNPolarity: specifies the OC3N Polarity - * This parmeter can be one of the following values: - * @arg TIM_OCNPolarity_High: Output Compare active high - * @arg TIM_OCNPolarity_Low: Output Compare active low - * @retval None - */ -void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) -{ - uint16_t tmpccer = 0; - - /* Check the parameters */ - assert_param(IS_TIM_LIST1_PERIPH(TIMx)); - assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); - - tmpccer = TIMx->CCER; - /* Set or Reset the CC3NP Bit */ - tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC3NP); - tmpccer |= (uint16_t)(TIM_OCNPolarity << 8); - /* Write to TIMx CCER register */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Configures the TIMx channel 4 polarity. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_OCPolarity: specifies the OC4 Polarity - * This parmeter can be one of the following values: - * @arg TIM_OCPolarity_High: Output Compare active high - * @arg TIM_OCPolarity_Low: Output Compare active low - * @retval None - */ -void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) -{ - uint16_t tmpccer = 0; - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); - tmpccer = TIMx->CCER; - /* Set or Reset the CC4P Bit */ - tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC4P); - tmpccer |= (uint16_t)(TIM_OCPolarity << 12); - /* Write to TIMx CCER register */ - TIMx->CCER = tmpccer; -} - -/** - * @brief Enables or disables the TIM Capture Compare Channel x. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param TIM_Channel: specifies the TIM Channel - * This parmeter can be one of the following values: - * @arg TIM_Channel_1: TIM Channel 1 - * @arg TIM_Channel_2: TIM Channel 2 - * @arg TIM_Channel_3: TIM Channel 3 - * @arg TIM_Channel_4: TIM Channel 4 - * @param TIM_CCx: specifies the TIM Channel CCxE bit new state. - * This parameter can be: TIM_CCx_Enable or TIM_CCx_Disable. - * @retval None - */ -void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx) -{ - uint16_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_CHANNEL(TIM_Channel)); - assert_param(IS_TIM_CCX(TIM_CCx)); - - tmp = CCER_CCE_Set << TIM_Channel; - - /* Reset the CCxE Bit */ - TIMx->CCER &= (uint16_t)~ tmp; - - /* Set or reset the CCxE Bit */ - TIMx->CCER |= (uint16_t)(TIM_CCx << TIM_Channel); -} - -/** - * @brief Enables or disables the TIM Capture Compare Channel xN. - * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM peripheral. - * @param TIM_Channel: specifies the TIM Channel - * This parmeter can be one of the following values: - * @arg TIM_Channel_1: TIM Channel 1 - * @arg TIM_Channel_2: TIM Channel 2 - * @arg TIM_Channel_3: TIM Channel 3 - * @param TIM_CCxN: specifies the TIM Channel CCxNE bit new state. - * This parameter can be: TIM_CCxN_Enable or TIM_CCxN_Disable. - * @retval None - */ -void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN) -{ - uint16_t tmp = 0; - - /* Check the parameters */ - assert_param(IS_TIM_LIST2_PERIPH(TIMx)); - assert_param(IS_TIM_COMPLEMENTARY_CHANNEL(TIM_Channel)); - assert_param(IS_TIM_CCXN(TIM_CCxN)); - - tmp = CCER_CCNE_Set << TIM_Channel; - - /* Reset the CCxNE Bit */ - TIMx->CCER &= (uint16_t) ~tmp; - - /* Set or reset the CCxNE Bit */ - TIMx->CCER |= (uint16_t)(TIM_CCxN << TIM_Channel); -} - -/** - * @brief Selects the TIM Ouput Compare Mode. - * @note This function disables the selected channel before changing the Ouput - * Compare Mode. - * User has to enable this channel using TIM_CCxCmd and TIM_CCxNCmd functions. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param TIM_Channel: specifies the TIM Channel - * This parmeter can be one of the following values: - * @arg TIM_Channel_1: TIM Channel 1 - * @arg TIM_Channel_2: TIM Channel 2 - * @arg TIM_Channel_3: TIM Channel 3 - * @arg TIM_Channel_4: TIM Channel 4 - * @param TIM_OCMode: specifies the TIM Output Compare Mode. - * This paramter can be one of the following values: - * @arg TIM_OCMode_Timing - * @arg TIM_OCMode_Active - * @arg TIM_OCMode_Toggle - * @arg TIM_OCMode_PWM1 - * @arg TIM_OCMode_PWM2 - * @arg TIM_ForcedAction_Active - * @arg TIM_ForcedAction_InActive - * @retval None - */ -void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode) -{ - uint32_t tmp = 0; - uint16_t tmp1 = 0; - - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_CHANNEL(TIM_Channel)); - assert_param(IS_TIM_OCM(TIM_OCMode)); - - tmp = (uint32_t) TIMx; - tmp += CCMR_Offset; - - tmp1 = CCER_CCE_Set << (uint16_t)TIM_Channel; - - /* Disable the Channel: Reset the CCxE Bit */ - TIMx->CCER &= (uint16_t) ~tmp1; - - if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) - { - tmp += (TIM_Channel>>1); - - /* Reset the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC1M); - - /* Configure the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp |= TIM_OCMode; - } - else - { - tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1; - - /* Reset the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M); - - /* Configure the OCxM bits in the CCMRx register */ - *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8); - } -} - -/** - * @brief Enables or Disables the TIMx Update event. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param NewState: new state of the TIMx UDIS bit - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Set the Update Disable Bit */ - TIMx->CR1 |= TIM_CR1_UDIS; - } - else - { - /* Reset the Update Disable Bit */ - TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_UDIS); - } -} - -/** - * @brief Configures the TIMx Update Request Interrupt source. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param TIM_UpdateSource: specifies the Update source. - * This parameter can be one of the following values: - * @arg TIM_UpdateSource_Regular: Source of update is the counter overflow/underflow - or the setting of UG bit, or an update generation - through the slave mode controller. - * @arg TIM_UpdateSource_Global: Source of update is counter overflow/underflow. - * @retval None - */ -void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_TIM_UPDATE_SOURCE(TIM_UpdateSource)); - if (TIM_UpdateSource != TIM_UpdateSource_Global) - { - /* Set the URS Bit */ - TIMx->CR1 |= TIM_CR1_URS; - } - else - { - /* Reset the URS Bit */ - TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_URS); - } -} - -/** - * @brief Enables or disables the TIMx’s Hall sensor interface. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param NewState: new state of the TIMx Hall sensor interface. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Set the TI1S Bit */ - TIMx->CR2 |= TIM_CR2_TI1S; - } - else - { - /* Reset the TI1S Bit */ - TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_TI1S); - } -} - -/** - * @brief Selects the TIMx’s One Pulse Mode. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param TIM_OPMode: specifies the OPM Mode to be used. - * This parameter can be one of the following values: - * @arg TIM_OPMode_Single - * @arg TIM_OPMode_Repetitive - * @retval None - */ -void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_TIM_OPM_MODE(TIM_OPMode)); - /* Reset the OPM Bit */ - TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_OPM); - /* Configure the OPM Mode */ - TIMx->CR1 |= TIM_OPMode; -} - -/** - * @brief Selects the TIMx Trigger Output Mode. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7, 8, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_TRGOSource: specifies the Trigger Output source. - * This paramter can be one of the following values: - * - * - For all TIMx - * @arg TIM_TRGOSource_Reset: The UG bit in the TIM_EGR register is used as the trigger output (TRGO). - * @arg TIM_TRGOSource_Enable: The Counter Enable CEN is used as the trigger output (TRGO). - * @arg TIM_TRGOSource_Update: The update event is selected as the trigger output (TRGO). - * - * - For all TIMx except TIM6 and TIM7 - * @arg TIM_TRGOSource_OC1: The trigger output sends a positive pulse when the CC1IF flag - * is to be set, as soon as a capture or compare match occurs (TRGO). - * @arg TIM_TRGOSource_OC1Ref: OC1REF signal is used as the trigger output (TRGO). - * @arg TIM_TRGOSource_OC2Ref: OC2REF signal is used as the trigger output (TRGO). - * @arg TIM_TRGOSource_OC3Ref: OC3REF signal is used as the trigger output (TRGO). - * @arg TIM_TRGOSource_OC4Ref: OC4REF signal is used as the trigger output (TRGO). - * - * @retval None - */ -void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST7_PERIPH(TIMx)); - assert_param(IS_TIM_TRGO_SOURCE(TIM_TRGOSource)); - /* Reset the MMS Bits */ - TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_MMS); - /* Select the TRGO source */ - TIMx->CR2 |= TIM_TRGOSource; -} - -/** - * @brief Selects the TIMx Slave Mode. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_SlaveMode: specifies the Timer Slave Mode. - * This paramter can be one of the following values: - * @arg TIM_SlaveMode_Reset: Rising edge of the selected trigger signal (TRGI) re-initializes - * the counter and triggers an update of the registers. - * @arg TIM_SlaveMode_Gated: The counter clock is enabled when the trigger signal (TRGI) is high. - * @arg TIM_SlaveMode_Trigger: The counter starts at a rising edge of the trigger TRGI. - * @arg TIM_SlaveMode_External1: Rising edges of the selected trigger (TRGI) clock the counter. - * @retval None - */ -void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_SLAVE_MODE(TIM_SlaveMode)); - /* Reset the SMS Bits */ - TIMx->SMCR &= (uint16_t)~((uint16_t)TIM_SMCR_SMS); - /* Select the Slave Mode */ - TIMx->SMCR |= TIM_SlaveMode; -} - -/** - * @brief Sets or Resets the TIMx Master/Slave Mode. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_MasterSlaveMode: specifies the Timer Master Slave Mode. - * This paramter can be one of the following values: - * @arg TIM_MasterSlaveMode_Enable: synchronization between the current timer - * and its slaves (through TRGO). - * @arg TIM_MasterSlaveMode_Disable: No action - * @retval None - */ -void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_MSM_STATE(TIM_MasterSlaveMode)); - /* Reset the MSM Bit */ - TIMx->SMCR &= (uint16_t)~((uint16_t)TIM_SMCR_MSM); - - /* Set or Reset the MSM Bit */ - TIMx->SMCR |= TIM_MasterSlaveMode; -} - -/** - * @brief Sets the TIMx Counter Register value - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param Counter: specifies the Counter register new value. - * @retval None - */ -void TIM_SetCounter(TIM_TypeDef* TIMx, uint16_t Counter) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - /* Set the Counter Register value */ - TIMx->CNT = Counter; -} - -/** - * @brief Sets the TIMx Autoreload Register value - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param Autoreload: specifies the Autoreload register new value. - * @retval None - */ -void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint16_t Autoreload) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - /* Set the Autoreload Register value */ - TIMx->ARR = Autoreload; -} - -/** - * @brief Sets the TIMx Capture Compare1 Register value - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param Compare1: specifies the Capture Compare1 register new value. - * @retval None - */ -void TIM_SetCompare1(TIM_TypeDef* TIMx, uint16_t Compare1) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - /* Set the Capture Compare1 Register value */ - TIMx->CCR1 = Compare1; -} - -/** - * @brief Sets the TIMx Capture Compare2 Register value - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. - * @param Compare2: specifies the Capture Compare2 register new value. - * @retval None - */ -void TIM_SetCompare2(TIM_TypeDef* TIMx, uint16_t Compare2) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - /* Set the Capture Compare2 Register value */ - TIMx->CCR2 = Compare2; -} - -/** - * @brief Sets the TIMx Capture Compare3 Register value - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param Compare3: specifies the Capture Compare3 register new value. - * @retval None - */ -void TIM_SetCompare3(TIM_TypeDef* TIMx, uint16_t Compare3) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - /* Set the Capture Compare3 Register value */ - TIMx->CCR3 = Compare3; -} - -/** - * @brief Sets the TIMx Capture Compare4 Register value - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param Compare4: specifies the Capture Compare4 register new value. - * @retval None - */ -void TIM_SetCompare4(TIM_TypeDef* TIMx, uint16_t Compare4) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - /* Set the Capture Compare4 Register value */ - TIMx->CCR4 = Compare4; -} - -/** - * @brief Sets the TIMx Input Capture 1 prescaler. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param TIM_ICPSC: specifies the Input Capture1 prescaler new value. - * This parameter can be one of the following values: - * @arg TIM_ICPSC_DIV1: no prescaler - * @arg TIM_ICPSC_DIV2: capture is done once every 2 events - * @arg TIM_ICPSC_DIV4: capture is done once every 4 events - * @arg TIM_ICPSC_DIV8: capture is done once every 8 events - * @retval None - */ -void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); - /* Reset the IC1PSC Bits */ - TIMx->CCMR1 &= (uint16_t)~((uint16_t)TIM_CCMR1_IC1PSC); - /* Set the IC1PSC value */ - TIMx->CCMR1 |= TIM_ICPSC; -} - -/** - * @brief Sets the TIMx Input Capture 2 prescaler. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_ICPSC: specifies the Input Capture2 prescaler new value. - * This parameter can be one of the following values: - * @arg TIM_ICPSC_DIV1: no prescaler - * @arg TIM_ICPSC_DIV2: capture is done once every 2 events - * @arg TIM_ICPSC_DIV4: capture is done once every 4 events - * @arg TIM_ICPSC_DIV8: capture is done once every 8 events - * @retval None - */ -void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); - /* Reset the IC2PSC Bits */ - TIMx->CCMR1 &= (uint16_t)~((uint16_t)TIM_CCMR1_IC2PSC); - /* Set the IC2PSC value */ - TIMx->CCMR1 |= (uint16_t)(TIM_ICPSC << 8); -} - -/** - * @brief Sets the TIMx Input Capture 3 prescaler. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_ICPSC: specifies the Input Capture3 prescaler new value. - * This parameter can be one of the following values: - * @arg TIM_ICPSC_DIV1: no prescaler - * @arg TIM_ICPSC_DIV2: capture is done once every 2 events - * @arg TIM_ICPSC_DIV4: capture is done once every 4 events - * @arg TIM_ICPSC_DIV8: capture is done once every 8 events - * @retval None - */ -void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); - /* Reset the IC3PSC Bits */ - TIMx->CCMR2 &= (uint16_t)~((uint16_t)TIM_CCMR2_IC3PSC); - /* Set the IC3PSC value */ - TIMx->CCMR2 |= TIM_ICPSC; -} - -/** - * @brief Sets the TIMx Input Capture 4 prescaler. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_ICPSC: specifies the Input Capture4 prescaler new value. - * This parameter can be one of the following values: - * @arg TIM_ICPSC_DIV1: no prescaler - * @arg TIM_ICPSC_DIV2: capture is done once every 2 events - * @arg TIM_ICPSC_DIV4: capture is done once every 4 events - * @arg TIM_ICPSC_DIV8: capture is done once every 8 events - * @retval None - */ -void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); - /* Reset the IC4PSC Bits */ - TIMx->CCMR2 &= (uint16_t)~((uint16_t)TIM_CCMR2_IC4PSC); - /* Set the IC4PSC value */ - TIMx->CCMR2 |= (uint16_t)(TIM_ICPSC << 8); -} - -/** - * @brief Sets the TIMx Clock Division value. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select - * the TIM peripheral. - * @param TIM_CKD: specifies the clock division value. - * This parameter can be one of the following value: - * @arg TIM_CKD_DIV1: TDTS = Tck_tim - * @arg TIM_CKD_DIV2: TDTS = 2*Tck_tim - * @arg TIM_CKD_DIV4: TDTS = 4*Tck_tim - * @retval None - */ -void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - assert_param(IS_TIM_CKD_DIV(TIM_CKD)); - /* Reset the CKD Bits */ - TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_CKD); - /* Set the CKD value */ - TIMx->CR1 |= TIM_CKD; -} - -/** - * @brief Gets the TIMx Input Capture 1 value. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @retval Capture Compare 1 Register value. - */ -uint16_t TIM_GetCapture1(TIM_TypeDef* TIMx) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST8_PERIPH(TIMx)); - /* Get the Capture 1 Register value */ - return TIMx->CCR1; -} - -/** - * @brief Gets the TIMx Input Capture 2 value. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. - * @retval Capture Compare 2 Register value. - */ -uint16_t TIM_GetCapture2(TIM_TypeDef* TIMx) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST6_PERIPH(TIMx)); - /* Get the Capture 2 Register value */ - return TIMx->CCR2; -} - -/** - * @brief Gets the TIMx Input Capture 3 value. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @retval Capture Compare 3 Register value. - */ -uint16_t TIM_GetCapture3(TIM_TypeDef* TIMx) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - /* Get the Capture 3 Register value */ - return TIMx->CCR3; -} - -/** - * @brief Gets the TIMx Input Capture 4 value. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @retval Capture Compare 4 Register value. - */ -uint16_t TIM_GetCapture4(TIM_TypeDef* TIMx) -{ - /* Check the parameters */ - assert_param(IS_TIM_LIST3_PERIPH(TIMx)); - /* Get the Capture 4 Register value */ - return TIMx->CCR4; -} - -/** - * @brief Gets the TIMx Counter value. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @retval Counter Register value. - */ -uint16_t TIM_GetCounter(TIM_TypeDef* TIMx) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - /* Get the Counter Register value */ - return TIMx->CNT; -} - -/** - * @brief Gets the TIMx Prescaler value. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @retval Prescaler Register value. - */ -uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - /* Get the Prescaler Register value */ - return TIMx->PSC; -} - -/** - * @brief Checks whether the specified TIM flag is set or not. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param TIM_FLAG: specifies the flag to check. - * This parameter can be one of the following values: - * @arg TIM_FLAG_Update: TIM update Flag - * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag - * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag - * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag - * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag - * @arg TIM_FLAG_COM: TIM Commutation Flag - * @arg TIM_FLAG_Trigger: TIM Trigger Flag - * @arg TIM_FLAG_Break: TIM Break Flag - * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag - * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag - * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag - * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag - * @note - * - TIM6 and TIM7 can have only one update flag. - * - TIM9, TIM12 and TIM15 can have only TIM_FLAG_Update, TIM_FLAG_CC1, - * TIM_FLAG_CC2 or TIM_FLAG_Trigger. - * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_FLAG_Update or TIM_FLAG_CC1. - * - TIM_FLAG_Break is used only with TIM1, TIM8 and TIM15. - * - TIM_FLAG_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. - * @retval The new state of TIM_FLAG (SET or RESET). - */ -FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) -{ - ITStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_TIM_GET_FLAG(TIM_FLAG)); - - if ((TIMx->SR & TIM_FLAG) != (uint16_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - return bitstatus; -} - -/** - * @brief Clears the TIMx's pending flags. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param TIM_FLAG: specifies the flag bit to clear. - * This parameter can be any combination of the following values: - * @arg TIM_FLAG_Update: TIM update Flag - * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag - * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag - * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag - * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag - * @arg TIM_FLAG_COM: TIM Commutation Flag - * @arg TIM_FLAG_Trigger: TIM Trigger Flag - * @arg TIM_FLAG_Break: TIM Break Flag - * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag - * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag - * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag - * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag - * @note - * - TIM6 and TIM7 can have only one update flag. - * - TIM9, TIM12 and TIM15 can have only TIM_FLAG_Update, TIM_FLAG_CC1, - * TIM_FLAG_CC2 or TIM_FLAG_Trigger. - * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_FLAG_Update or TIM_FLAG_CC1. - * - TIM_FLAG_Break is used only with TIM1, TIM8 and TIM15. - * - TIM_FLAG_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. - * @retval None - */ -void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_TIM_CLEAR_FLAG(TIM_FLAG)); - - /* Clear the flags */ - TIMx->SR = (uint16_t)~TIM_FLAG; -} - -/** - * @brief Checks whether the TIM interrupt has occurred or not. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param TIM_IT: specifies the TIM interrupt source to check. - * This parameter can be one of the following values: - * @arg TIM_IT_Update: TIM update Interrupt source - * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source - * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source - * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source - * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source - * @arg TIM_IT_COM: TIM Commutation Interrupt source - * @arg TIM_IT_Trigger: TIM Trigger Interrupt source - * @arg TIM_IT_Break: TIM Break Interrupt source - * @note - * - TIM6 and TIM7 can generate only an update interrupt. - * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, - * TIM_IT_CC2 or TIM_IT_Trigger. - * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. - * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. - * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. - * @retval The new state of the TIM_IT(SET or RESET). - */ -ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT) -{ - ITStatus bitstatus = RESET; - uint16_t itstatus = 0x0, itenable = 0x0; - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_TIM_GET_IT(TIM_IT)); - - itstatus = TIMx->SR & TIM_IT; - - itenable = TIMx->DIER & TIM_IT; - if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET)) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - return bitstatus; -} - -/** - * @brief Clears the TIMx's interrupt pending bits. - * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. - * @param TIM_IT: specifies the pending bit to clear. - * This parameter can be any combination of the following values: - * @arg TIM_IT_Update: TIM1 update Interrupt source - * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source - * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source - * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source - * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source - * @arg TIM_IT_COM: TIM Commutation Interrupt source - * @arg TIM_IT_Trigger: TIM Trigger Interrupt source - * @arg TIM_IT_Break: TIM Break Interrupt source - * @note - * - TIM6 and TIM7 can generate only an update interrupt. - * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, - * TIM_IT_CC2 or TIM_IT_Trigger. - * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. - * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. - * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. - * @retval None - */ -void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT) -{ - /* Check the parameters */ - assert_param(IS_TIM_ALL_PERIPH(TIMx)); - assert_param(IS_TIM_IT(TIM_IT)); - /* Clear the IT pending Bit */ - TIMx->SR = (uint16_t)~TIM_IT; -} - -/** - * @brief Configure the TI1 as Input. - * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. - * @param TIM_ICPolarity : The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPolarity_Rising - * @arg TIM_ICPolarity_Falling - * @param TIM_ICSelection: specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSelection_DirectTI: TIM Input 1 is selected to be connected to IC1. - * @arg TIM_ICSelection_IndirectTI: TIM Input 1 is selected to be connected to IC2. - * @arg TIM_ICSelection_TRC: TIM Input 1 is selected to be connected to TRC. - * @param TIM_ICFilter: Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - */ -static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter) -{ - uint16_t tmpccmr1 = 0, tmpccer = 0; - /* Disable the Channel 1: Reset the CC1E Bit */ - TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC1E); - tmpccmr1 = TIMx->CCMR1; - tmpccer = TIMx->CCER; - /* Select the Input and set the filter */ - tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC1S)) & ((uint16_t)~((uint16_t)TIM_CCMR1_IC1F))); - tmpccmr1 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); - - if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || - (TIMx == TIM4) ||(TIMx == TIM5)) - { - /* Select the Polarity and set the CC1E Bit */ - tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC1P)); - tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC1E); - } - else - { - /* Select the Polarity and set the CC1E Bit */ - tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC1P | TIM_CCER_CC1NP)); - tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC1E); - } - - /* Write to TIMx CCMR1 and CCER registers */ - TIMx->CCMR1 = tmpccmr1; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the TI2 as Input. - * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. - * @param TIM_ICPolarity : The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPolarity_Rising - * @arg TIM_ICPolarity_Falling - * @param TIM_ICSelection: specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSelection_DirectTI: TIM Input 2 is selected to be connected to IC2. - * @arg TIM_ICSelection_IndirectTI: TIM Input 2 is selected to be connected to IC1. - * @arg TIM_ICSelection_TRC: TIM Input 2 is selected to be connected to TRC. - * @param TIM_ICFilter: Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - */ -static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter) -{ - uint16_t tmpccmr1 = 0, tmpccer = 0, tmp = 0; - /* Disable the Channel 2: Reset the CC2E Bit */ - TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC2E); - tmpccmr1 = TIMx->CCMR1; - tmpccer = TIMx->CCER; - tmp = (uint16_t)(TIM_ICPolarity << 4); - /* Select the Input and set the filter */ - tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC2S)) & ((uint16_t)~((uint16_t)TIM_CCMR1_IC2F))); - tmpccmr1 |= (uint16_t)(TIM_ICFilter << 12); - tmpccmr1 |= (uint16_t)(TIM_ICSelection << 8); - - if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || - (TIMx == TIM4) ||(TIMx == TIM5)) - { - /* Select the Polarity and set the CC2E Bit */ - tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC2P)); - tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC2E); - } - else - { - /* Select the Polarity and set the CC2E Bit */ - tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC2P | TIM_CCER_CC2NP)); - tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC2E); - } - - /* Write to TIMx CCMR1 and CCER registers */ - TIMx->CCMR1 = tmpccmr1 ; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the TI3 as Input. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_ICPolarity : The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPolarity_Rising - * @arg TIM_ICPolarity_Falling - * @param TIM_ICSelection: specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSelection_DirectTI: TIM Input 3 is selected to be connected to IC3. - * @arg TIM_ICSelection_IndirectTI: TIM Input 3 is selected to be connected to IC4. - * @arg TIM_ICSelection_TRC: TIM Input 3 is selected to be connected to TRC. - * @param TIM_ICFilter: Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - */ -static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter) -{ - uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; - /* Disable the Channel 3: Reset the CC3E Bit */ - TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC3E); - tmpccmr2 = TIMx->CCMR2; - tmpccer = TIMx->CCER; - tmp = (uint16_t)(TIM_ICPolarity << 8); - /* Select the Input and set the filter */ - tmpccmr2 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR2_CC3S)) & ((uint16_t)~((uint16_t)TIM_CCMR2_IC3F))); - tmpccmr2 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); - - if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || - (TIMx == TIM4) ||(TIMx == TIM5)) - { - /* Select the Polarity and set the CC3E Bit */ - tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P)); - tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC3E); - } - else - { - /* Select the Polarity and set the CC3E Bit */ - tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P | TIM_CCER_CC3NP)); - tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC3E); - } - - /* Write to TIMx CCMR2 and CCER registers */ - TIMx->CCMR2 = tmpccmr2; - TIMx->CCER = tmpccer; -} - -/** - * @brief Configure the TI4 as Input. - * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. - * @param TIM_ICPolarity : The Input Polarity. - * This parameter can be one of the following values: - * @arg TIM_ICPolarity_Rising - * @arg TIM_ICPolarity_Falling - * @param TIM_ICSelection: specifies the input to be used. - * This parameter can be one of the following values: - * @arg TIM_ICSelection_DirectTI: TIM Input 4 is selected to be connected to IC4. - * @arg TIM_ICSelection_IndirectTI: TIM Input 4 is selected to be connected to IC3. - * @arg TIM_ICSelection_TRC: TIM Input 4 is selected to be connected to TRC. - * @param TIM_ICFilter: Specifies the Input Capture Filter. - * This parameter must be a value between 0x00 and 0x0F. - * @retval None - */ -static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, - uint16_t TIM_ICFilter) -{ - uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; - - /* Disable the Channel 4: Reset the CC4E Bit */ - TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC4E); - tmpccmr2 = TIMx->CCMR2; - tmpccer = TIMx->CCER; - tmp = (uint16_t)(TIM_ICPolarity << 12); - /* Select the Input and set the filter */ - tmpccmr2 &= (uint16_t)((uint16_t)(~(uint16_t)TIM_CCMR2_CC4S) & ((uint16_t)~((uint16_t)TIM_CCMR2_IC4F))); - tmpccmr2 |= (uint16_t)(TIM_ICSelection << 8); - tmpccmr2 |= (uint16_t)(TIM_ICFilter << 12); - - if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || - (TIMx == TIM4) ||(TIMx == TIM5)) - { - /* Select the Polarity and set the CC4E Bit */ - tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC4P)); - tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC4E); - } - else - { - /* Select the Polarity and set the CC4E Bit */ - tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P | TIM_CCER_CC4NP)); - tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC4E); - } - /* Write to TIMx CCMR2 and CCER registers */ - TIMx->CCMR2 = tmpccmr2; - TIMx->CCER = tmpccer; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_tim.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the TIM firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_tim.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup TIM + * @brief TIM driver modules + * @{ + */ + +/** @defgroup TIM_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Defines + * @{ + */ + +/* ---------------------- TIM registers bit mask ------------------------ */ +#define SMCR_ETR_Mask ((uint16_t)0x00FF) +#define CCMR_Offset ((uint16_t)0x0018) +#define CCER_CCE_Set ((uint16_t)0x0001) +#define CCER_CCNE_Set ((uint16_t)0x0004) + +/** + * @} + */ + +/** @defgroup TIM_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_FunctionPrototypes + * @{ + */ + +static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +/** + * @} + */ + +/** @defgroup TIM_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the TIMx peripheral registers to their default reset values. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @retval None + */ +void TIM_DeInit(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + if (TIMx == TIM1) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, DISABLE); + } + else if (TIMx == TIM2) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE); + } + else if (TIMx == TIM3) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE); + } + else if (TIMx == TIM4) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE); + } + else if (TIMx == TIM5) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, DISABLE); + } + else if (TIMx == TIM6) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, DISABLE); + } + else if (TIMx == TIM7) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, DISABLE); + } + else if (TIMx == TIM8) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, DISABLE); + } + else if (TIMx == TIM9) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, DISABLE); + } + else if (TIMx == TIM10) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, DISABLE); + } + else if (TIMx == TIM11) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, DISABLE); + } + else if (TIMx == TIM12) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, DISABLE); + } + else if (TIMx == TIM13) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, DISABLE); + } + else if (TIMx == TIM14) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, DISABLE); + } + else if (TIMx == TIM15) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, DISABLE); + } + else if (TIMx == TIM16) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM16, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM16, DISABLE); + } + else + { + if (TIMx == TIM17) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM17, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM17, DISABLE); + } + } +} + +/** + * @brief Initializes the TIMx Time Base Unit peripheral according to + * the specified parameters in the TIM_TimeBaseInitStruct. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_TimeBaseInitStruct: pointer to a TIM_TimeBaseInitTypeDef + * structure that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, const TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +{ + uint16_t tmpcr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_COUNTER_MODE(TIM_TimeBaseInitStruct->TIM_CounterMode)); + assert_param(IS_TIM_CKD_DIV(TIM_TimeBaseInitStruct->TIM_ClockDivision)); + + tmpcr1 = TIMx->CR1; + + if((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM2) || (TIMx == TIM3)|| + (TIMx == TIM4) || (TIMx == TIM5)) + { + /* Select the Counter Mode */ + tmpcr1 &= (uint16_t)(~((uint16_t)(TIM_CR1_DIR | TIM_CR1_CMS))); + tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_CounterMode; + } + + if((TIMx != TIM6) && (TIMx != TIM7)) + { + /* Set the clock division */ + tmpcr1 &= (uint16_t)(~((uint16_t)TIM_CR1_CKD)); + tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_ClockDivision; + } + + TIMx->CR1 = tmpcr1; + + /* Set the Autoreload value */ + TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period ; + + /* Set the Prescaler value */ + TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler; + + if ((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM15)|| (TIMx == TIM16) || (TIMx == TIM17)) + { + /* Set the Repetition Counter value */ + TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter; + } + + /* Generate an update event to reload the Prescaler and the Repetition counter + values immediately */ + TIMx->EGR = TIM_PSCReloadMode_Immediate; +} + +/** + * @brief Initializes the TIMx Channel1 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC1Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint16_t)(~(uint16_t)TIM_CCER_CC1E); + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare Mode Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_OC1M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_CC1S)); + + /* Select the Output Compare Mode */ + tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1P)); + /* Set the Output Compare Polarity */ + tmpccer |= TIM_OCInitStruct->TIM_OCPolarity; + + /* Set the Output State */ + tmpccer |= TIM_OCInitStruct->TIM_OutputState; + + if((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM15)|| + (TIMx == TIM16)|| (TIMx == TIM17)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1NP)); + /* Set the Output N Polarity */ + tmpccer |= TIM_OCInitStruct->TIM_OCNPolarity; + + /* Reset the Output N State */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1NE)); + /* Set the Output N State */ + tmpccer |= TIM_OCInitStruct->TIM_OutputNState; + + /* Reset the Ouput Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS1)); + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS1N)); + + /* Set the Output Idle state */ + tmpcr2 |= TIM_OCInitStruct->TIM_OCIdleState; + /* Set the Output N Idle state */ + tmpcr2 |= TIM_OCInitStruct->TIM_OCNIdleState; + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR1 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel2 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select + * the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC2Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC2E)); + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_OC2M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_CC2S)); + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2P)); + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 4); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 4); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2NP)); + /* Set the Output N Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 4); + + /* Reset the Output N State */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2NE)); + /* Set the Output N State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 4); + + /* Reset the Ouput Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS2)); + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS2N)); + + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 2); + /* Set the Output N Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 2); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR2 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel3 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC3Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC3E)); + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_OC3M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_CC3S)); + /* Select the Output Compare Mode */ + tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3P)); + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 8); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 8); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3NP)); + /* Set the Output N Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 8); + /* Reset the Output N State */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3NE)); + + /* Set the Output N State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 8); + /* Reset the Ouput Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS3)); + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS3N)); + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 4); + /* Set the Output N Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 4); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR3 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel4 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC4Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 2: Reset the CC4E Bit */ + TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC4E)); + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_OC4M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_CC4S)); + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC4P)); + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 12); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 12); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + /* Reset the Ouput Compare IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS4)); + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 6); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR4 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIM peripheral according to the specified + * parameters in the TIM_ICInitStruct. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_ICInit(TIM_TypeDef* TIMx, const TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_CHANNEL(TIM_ICInitStruct->TIM_Channel)); + assert_param(IS_TIM_IC_SELECTION(TIM_ICInitStruct->TIM_ICSelection)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICInitStruct->TIM_ICPrescaler)); + assert_param(IS_TIM_IC_FILTER(TIM_ICInitStruct->TIM_ICFilter)); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + assert_param(IS_TIM_IC_POLARITY(TIM_ICInitStruct->TIM_ICPolarity)); + } + else + { + assert_param(IS_TIM_IC_POLARITY_LITE(TIM_ICInitStruct->TIM_ICPolarity)); + } + if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) + { + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + /* TI1 Configuration */ + TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_2) + { + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* TI2 Configuration */ + TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_3) + { + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* TI3 Configuration */ + TI3_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC3Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else + { + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* TI4 Configuration */ + TI4_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC4Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } +} + +/** + * @brief Configures the TIM peripheral according to the specified + * parameters in the TIM_ICInitStruct to measure an external PWM signal. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + uint16_t icoppositepolarity = TIM_ICPolarity_Rising; + uint16_t icoppositeselection = TIM_ICSelection_DirectTI; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Select the Opposite Input Polarity */ + if (TIM_ICInitStruct->TIM_ICPolarity == TIM_ICPolarity_Rising) + { + icoppositepolarity = TIM_ICPolarity_Falling; + } + else + { + icoppositepolarity = TIM_ICPolarity_Rising; + } + /* Select the Opposite Input */ + if (TIM_ICInitStruct->TIM_ICSelection == TIM_ICSelection_DirectTI) + { + icoppositeselection = TIM_ICSelection_IndirectTI; + } + else + { + icoppositeselection = TIM_ICSelection_DirectTI; + } + if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) + { + /* TI1 Configuration */ + TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + /* TI2 Configuration */ + TI2_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else + { + /* TI2 Configuration */ + TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + /* TI1 Configuration */ + TI1_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } +} + +/** + * @brief Configures the: Break feature, dead time, Lock level, the OSSI, + * the OSSR State and the AOE(automatic output enable). + * @param TIMx: where x can be 1 or 8 to select the TIM + * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure that + * contains the BDTR Register configuration information for the TIM peripheral. + * @retval None + */ +void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OSSR_STATE(TIM_BDTRInitStruct->TIM_OSSRState)); + assert_param(IS_TIM_OSSI_STATE(TIM_BDTRInitStruct->TIM_OSSIState)); + assert_param(IS_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->TIM_LOCKLevel)); + assert_param(IS_TIM_BREAK_STATE(TIM_BDTRInitStruct->TIM_Break)); + assert_param(IS_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->TIM_BreakPolarity)); + assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->TIM_AutomaticOutput)); + /* Set the Lock level, the Break enable Bit and the Ploarity, the OSSR State, + the OSSI State, the dead time value and the Automatic Output Enable Bit */ + TIMx->BDTR = (uint32_t)TIM_BDTRInitStruct->TIM_OSSRState | TIM_BDTRInitStruct->TIM_OSSIState | + TIM_BDTRInitStruct->TIM_LOCKLevel | TIM_BDTRInitStruct->TIM_DeadTime | + TIM_BDTRInitStruct->TIM_Break | TIM_BDTRInitStruct->TIM_BreakPolarity | + TIM_BDTRInitStruct->TIM_AutomaticOutput; +} + +/** + * @brief Fills each TIM_TimeBaseInitStruct member with its default value. + * @param TIM_TimeBaseInitStruct : pointer to a TIM_TimeBaseInitTypeDef + * structure which will be initialized. + * @retval None + */ +void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +{ + /* Set the default configuration */ + TIM_TimeBaseInitStruct->TIM_Period = 0xFFFF; + TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000; + TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1; + TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000; +} + +/** + * @brief Fills each TIM_OCInitStruct member with its default value. + * @param TIM_OCInitStruct : pointer to a TIM_OCInitTypeDef structure which will + * be initialized. + * @retval None + */ +void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + /* Set the default configuration */ + TIM_OCInitStruct->TIM_OCMode = TIM_OCMode_Timing; + TIM_OCInitStruct->TIM_OutputState = TIM_OutputState_Disable; + TIM_OCInitStruct->TIM_OutputNState = TIM_OutputNState_Disable; + TIM_OCInitStruct->TIM_Pulse = 0x0000; + TIM_OCInitStruct->TIM_OCPolarity = TIM_OCPolarity_High; + TIM_OCInitStruct->TIM_OCNPolarity = TIM_OCPolarity_High; + TIM_OCInitStruct->TIM_OCIdleState = TIM_OCIdleState_Reset; + TIM_OCInitStruct->TIM_OCNIdleState = TIM_OCNIdleState_Reset; +} + +/** + * @brief Fills each TIM_ICInitStruct member with its default value. + * @param TIM_ICInitStruct : pointer to a TIM_ICInitTypeDef structure which will + * be initialized. + * @retval None + */ +void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + /* Set the default configuration */ + TIM_ICInitStruct->TIM_Channel = TIM_Channel_1; + TIM_ICInitStruct->TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStruct->TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStruct->TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStruct->TIM_ICFilter = 0x00; +} + +/** + * @brief Fills each TIM_BDTRInitStruct member with its default value. + * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure which + * will be initialized. + * @retval None + */ +void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct) +{ + /* Set the default configuration */ + TIM_BDTRInitStruct->TIM_OSSRState = TIM_OSSRState_Disable; + TIM_BDTRInitStruct->TIM_OSSIState = TIM_OSSIState_Disable; + TIM_BDTRInitStruct->TIM_LOCKLevel = TIM_LOCKLevel_OFF; + TIM_BDTRInitStruct->TIM_DeadTime = 0x00; + TIM_BDTRInitStruct->TIM_Break = TIM_Break_Disable; + TIM_BDTRInitStruct->TIM_BreakPolarity = TIM_BreakPolarity_Low; + TIM_BDTRInitStruct->TIM_AutomaticOutput = TIM_AutomaticOutput_Disable; +} + +/** + * @brief Enables or disables the specified TIM peripheral. + * @param TIMx: where x can be 1 to 17 to select the TIMx peripheral. + * @param NewState: new state of the TIMx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the TIM Counter */ + TIMx->CR1 |= TIM_CR1_CEN; + } + else + { + /* Disable the TIM Counter */ + TIMx->CR1 &= (uint16_t)(~((uint16_t)TIM_CR1_CEN)); + } +} + +/** + * @brief Enables or disables the TIM peripheral Main Outputs. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIMx peripheral. + * @param NewState: new state of the TIM peripheral Main Outputs. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the TIM Main Output */ + TIMx->BDTR |= TIM_BDTR_MOE; + } + else + { + /* Disable the TIM Main Output */ + TIMx->BDTR &= (uint16_t)(~((uint16_t)TIM_BDTR_MOE)); + } +} + +/** + * @brief Enables or disables the specified TIM interrupts. + * @param TIMx: where x can be 1 to 17 to select the TIMx peripheral. + * @param TIM_IT: specifies the TIM interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg TIM_IT_Update: TIM update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * @note + * - TIM6 and TIM7 can only generate an update interrupt. + * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, + * TIM_IT_CC2 or TIM_IT_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. + * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @param NewState: new state of the TIM interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_IT(TIM_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Interrupt sources */ + TIMx->DIER |= TIM_IT; + } + else + { + /* Disable the Interrupt sources */ + TIMx->DIER &= (uint16_t)~TIM_IT; + } +} + +/** + * @brief Configures the TIMx event to be generate by software. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_EventSource: specifies the event source. + * This parameter can be one or more of the following values: + * @arg TIM_EventSource_Update: Timer update Event source + * @arg TIM_EventSource_CC1: Timer Capture Compare 1 Event source + * @arg TIM_EventSource_CC2: Timer Capture Compare 2 Event source + * @arg TIM_EventSource_CC3: Timer Capture Compare 3 Event source + * @arg TIM_EventSource_CC4: Timer Capture Compare 4 Event source + * @arg TIM_EventSource_COM: Timer COM event source + * @arg TIM_EventSource_Trigger: Timer Trigger Event source + * @arg TIM_EventSource_Break: Timer Break event source + * @note + * - TIM6 and TIM7 can only generate an update event. + * - TIM_EventSource_COM and TIM_EventSource_Break are used only with TIM1 and TIM8. + * @retval None + */ +void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_EVENT_SOURCE(TIM_EventSource)); + + /* Set the event sources */ + TIMx->EGR = TIM_EventSource; +} + +/** + * @brief Configures the TIMx’s DMA interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 15, 16 or 17 to select + * the TIM peripheral. + * @param TIM_DMABase: DMA Base address. + * This parameter can be one of the following values: + * @arg TIM_DMABase_CR, TIM_DMABase_CR2, TIM_DMABase_SMCR, + * TIM_DMABase_DIER, TIM1_DMABase_SR, TIM_DMABase_EGR, + * TIM_DMABase_CCMR1, TIM_DMABase_CCMR2, TIM_DMABase_CCER, + * TIM_DMABase_CNT, TIM_DMABase_PSC, TIM_DMABase_ARR, + * TIM_DMABase_RCR, TIM_DMABase_CCR1, TIM_DMABase_CCR2, + * TIM_DMABase_CCR3, TIM_DMABase_CCR4, TIM_DMABase_BDTR, + * TIM_DMABase_DCR. + * @param TIM_DMABurstLength: DMA Burst length. + * This parameter can be one value between: + * TIM_DMABurstLength_1Byte and TIM_DMABurstLength_18Bytes. + * @retval None + */ +void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_DMA_BASE(TIM_DMABase)); + assert_param(IS_TIM_DMA_LENGTH(TIM_DMABurstLength)); + /* Set the DMA Base and the DMA Burst Length */ + TIMx->DCR = TIM_DMABase | TIM_DMABurstLength; +} + +/** + * @brief Enables or disables the TIMx’s DMA Requests. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7, 8, 15, 16 or 17 + * to select the TIM peripheral. + * @param TIM_DMASource: specifies the DMA Request sources. + * This parameter can be any combination of the following values: + * @arg TIM_DMA_Update: TIM update Interrupt source + * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source + * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source + * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source + * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source + * @arg TIM_DMA_COM: TIM Commutation DMA source + * @arg TIM_DMA_Trigger: TIM Trigger DMA source + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST9_PERIPH(TIMx)); + assert_param(IS_TIM_DMA_SOURCE(TIM_DMASource)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DMA sources */ + TIMx->DIER |= TIM_DMASource; + } + else + { + /* Disable the DMA sources */ + TIMx->DIER &= (uint16_t)~TIM_DMASource; + } +} + +/** + * @brief Configures the TIMx interrnal Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 + * to select the TIM peripheral. + * @retval None + */ +void TIM_InternalClockConfig(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Disable slave mode to clock the prescaler directly with the internal clock */ + TIMx->SMCR &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); +} + +/** + * @brief Configures the TIMx Internal Trigger as External Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ITRSource: Trigger source. + * This parameter can be one of the following values: + * @param TIM_TS_ITR0: Internal Trigger 0 + * @param TIM_TS_ITR1: Internal Trigger 1 + * @param TIM_TS_ITR2: Internal Trigger 2 + * @param TIM_TS_ITR3: Internal Trigger 3 + * @retval None + */ +void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_INTERNAL_TRIGGER_SELECTION(TIM_InputTriggerSource)); + /* Select the Internal Trigger */ + TIM_SelectInputTrigger(TIMx, TIM_InputTriggerSource); + /* Select the External clock mode1 */ + TIMx->SMCR |= TIM_SlaveMode_External1; +} + +/** + * @brief Configures the TIMx Trigger as External Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_TIxExternalCLKSource: Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TIxExternalCLK1Source_TI1ED: TI1 Edge Detector + * @arg TIM_TIxExternalCLK1Source_TI1: Filtered Timer Input 1 + * @arg TIM_TIxExternalCLK1Source_TI2: Filtered Timer Input 2 + * @param TIM_ICPolarity: specifies the TIx Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param ICFilter : specifies the filter value. + * This parameter must be a value between 0x0 and 0xF. + * @retval None + */ +void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, + uint16_t TIM_ICPolarity, uint16_t ICFilter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_TIXCLK_SOURCE(TIM_TIxExternalCLKSource)); + assert_param(IS_TIM_IC_POLARITY(TIM_ICPolarity)); + assert_param(IS_TIM_IC_FILTER(ICFilter)); + /* Configure the Timer Input Clock Source */ + if (TIM_TIxExternalCLKSource == TIM_TIxExternalCLK1Source_TI2) + { + TI2_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); + } + else + { + TI1_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); + } + /* Select the Trigger source */ + TIM_SelectInputTrigger(TIMx, TIM_TIxExternalCLKSource); + /* Select the External clock mode1 */ + TIMx->SMCR |= TIM_SlaveMode_External1; +} + +/** + * @brief Configures the External clock Mode1 + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter) +{ + uint16_t tmpsmcr = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + /* Configure the ETR Clock source */ + TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + /* Reset the SMS Bits */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); + /* Select the External clock mode1 */ + tmpsmcr |= TIM_SlaveMode_External1; + /* Select the Trigger selection : ETRF */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_TS)); + tmpsmcr |= TIM_TS_ETRF; + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the External clock Mode2 + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + /* Configure the ETR Clock source */ + TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); + /* Enable the External clock mode2 */ + TIMx->SMCR |= TIM_SMCR_ECE; +} + +/** + * @brief Configures the TIMx External Trigger (ETR). + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter) +{ + uint16_t tmpsmcr = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + tmpsmcr = TIMx->SMCR; + /* Reset the ETR Bits */ + tmpsmcr &= SMCR_ETR_Mask; + /* Set the Prescaler, the Filter value and the Polarity */ + tmpsmcr |= (uint16_t)(TIM_ExtTRGPrescaler | (uint16_t)(TIM_ExtTRGPolarity | (uint16_t)(ExtTRGFilter << (uint16_t)8))); + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the TIMx Prescaler. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param Prescaler: specifies the Prescaler Register value + * @param TIM_PSCReloadMode: specifies the TIM Prescaler Reload mode + * This parameter can be one of the following values: + * @arg TIM_PSCReloadMode_Update: The Prescaler is loaded at the update event. + * @arg TIM_PSCReloadMode_Immediate: The Prescaler is loaded immediately. + * @retval None + */ +void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_PRESCALER_RELOAD(TIM_PSCReloadMode)); + /* Set the Prescaler value */ + TIMx->PSC = Prescaler; + /* Set or reset the UG Bit */ + TIMx->EGR = TIM_PSCReloadMode; +} + +/** + * @brief Specifies the TIMx Counter Mode to be used. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_CounterMode: specifies the Counter Mode to be used + * This parameter can be one of the following values: + * @arg TIM_CounterMode_Up: TIM Up Counting Mode + * @arg TIM_CounterMode_Down: TIM Down Counting Mode + * @arg TIM_CounterMode_CenterAligned1: TIM Center Aligned Mode1 + * @arg TIM_CounterMode_CenterAligned2: TIM Center Aligned Mode2 + * @arg TIM_CounterMode_CenterAligned3: TIM Center Aligned Mode3 + * @retval None + */ +void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode) +{ + uint16_t tmpcr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_COUNTER_MODE(TIM_CounterMode)); + tmpcr1 = TIMx->CR1; + /* Reset the CMS and DIR Bits */ + tmpcr1 &= (uint16_t)(~((uint16_t)(TIM_CR1_DIR | TIM_CR1_CMS))); + /* Set the Counter Mode */ + tmpcr1 |= TIM_CounterMode; + /* Write to TIMx CR1 register */ + TIMx->CR1 = tmpcr1; +} + +/** + * @brief Selects the Input Trigger source + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_InputTriggerSource: The Input Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal Trigger 0 + * @arg TIM_TS_ITR1: Internal Trigger 1 + * @arg TIM_TS_ITR2: Internal Trigger 2 + * @arg TIM_TS_ITR3: Internal Trigger 3 + * @arg TIM_TS_TI1F_ED: TI1 Edge Detector + * @arg TIM_TS_TI1FP1: Filtered Timer Input 1 + * @arg TIM_TS_TI2FP2: Filtered Timer Input 2 + * @arg TIM_TS_ETRF: External Trigger input + * @retval None + */ +void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) +{ + uint16_t tmpsmcr = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_TRIGGER_SELECTION(TIM_InputTriggerSource)); + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + /* Reset the TS Bits */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_TS)); + /* Set the Input Trigger source */ + tmpsmcr |= TIM_InputTriggerSource; + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the TIMx Encoder Interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_EncoderMode: specifies the TIMx Encoder Mode. + * This parameter can be one of the following values: + * @arg TIM_EncoderMode_TI1: Counter counts on TI1FP1 edge depending on TI2FP2 level. + * @arg TIM_EncoderMode_TI2: Counter counts on TI2FP2 edge depending on TI1FP1 level. + * @arg TIM_EncoderMode_TI12: Counter counts on both TI1FP1 and TI2FP2 edges depending + * on the level of the other input. + * @param TIM_IC1Polarity: specifies the IC1 Polarity + * This parmeter can be one of the following values: + * @arg TIM_ICPolarity_Falling: IC Falling edge. + * @arg TIM_ICPolarity_Rising: IC Rising edge. + * @param TIM_IC2Polarity: specifies the IC2 Polarity + * This parmeter can be one of the following values: + * @arg TIM_ICPolarity_Falling: IC Falling edge. + * @arg TIM_ICPolarity_Rising: IC Rising edge. + * @retval None + */ +void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, + uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity) +{ + uint16_t tmpsmcr = 0; + uint16_t tmpccmr1 = 0; + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST5_PERIPH(TIMx)); + assert_param(IS_TIM_ENCODER_MODE(TIM_EncoderMode)); + assert_param(IS_TIM_IC_POLARITY(TIM_IC1Polarity)); + assert_param(IS_TIM_IC_POLARITY(TIM_IC2Polarity)); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + + /* Set the encoder Mode */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); + tmpsmcr |= TIM_EncoderMode; + + /* Select the Capture Compare 1 and the Capture Compare 2 as input */ + tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC1S)) & (uint16_t)(~((uint16_t)TIM_CCMR1_CC2S))); + tmpccmr1 |= TIM_CCMR1_CC1S_0 | TIM_CCMR1_CC2S_0; + + /* Set the TI1 and the TI2 Polarities */ + tmpccer &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCER_CC1P)) & ((uint16_t)~((uint16_t)TIM_CCER_CC2P))); + tmpccer |= (uint16_t)(TIM_IC1Polarity | (uint16_t)(TIM_IC2Polarity << (uint16_t)4)); + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Forces the TIMx output 1 waveform to active or inactive level. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC1REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC1REF. + * @retval None + */ +void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC1M Bits */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1M); + /* Configure The Forced output Mode */ + tmpccmr1 |= TIM_ForcedAction; + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Forces the TIMx output 2 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC2REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC2REF. + * @retval None + */ +void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2M Bits */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2M); + /* Configure The Forced output Mode */ + tmpccmr1 |= (uint16_t)(TIM_ForcedAction << 8); + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Forces the TIMx output 3 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC3REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC3REF. + * @retval None + */ +void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC1M Bits */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3M); + /* Configure The Forced output Mode */ + tmpccmr2 |= TIM_ForcedAction; + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Forces the TIMx output 4 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC4REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC4REF. + * @retval None + */ +void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC2M Bits */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4M); + /* Configure The Forced output Mode */ + tmpccmr2 |= (uint16_t)(TIM_ForcedAction << 8); + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Enables or disables TIMx peripheral Preload register on ARR. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param NewState: new state of the TIMx peripheral Preload register + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the ARR Preload Bit */ + TIMx->CR1 |= TIM_CR1_ARPE; + } + else + { + /* Reset the ARR Preload Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_ARPE); + } +} + +/** + * @brief Selects the TIM peripheral Commutation event. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIMx peripheral + * @param NewState: new state of the Commutation event. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the COM Bit */ + TIMx->CR2 |= TIM_CR2_CCUS; + } + else + { + /* Reset the COM Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCUS); + } +} + +/** + * @brief Selects the TIMx peripheral Capture Compare DMA source. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 15, 16 or 17 to select + * the TIM peripheral. + * @param NewState: new state of the Capture Compare DMA source + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the CCDS Bit */ + TIMx->CR2 |= TIM_CR2_CCDS; + } + else + { + /* Reset the CCDS Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCDS); + } +} + +/** + * @brief Sets or Resets the TIM peripheral Capture Compare Preload Control bit. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8 or 15 + * to select the TIMx peripheral + * @param NewState: new state of the Capture Compare Preload Control bit + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST5_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the CCPC Bit */ + TIMx->CR2 |= TIM_CR2_CCPC; + } + else + { + /* Reset the CCPC Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCPC); + } +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR1. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC1PE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr1 |= TIM_OCPreload; + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR2. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select + * the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2PE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr1 |= (uint16_t)(TIM_OCPreload << 8); + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR3. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC3PE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr2 |= TIM_OCPreload; + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR4. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC4PE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr2 |= (uint16_t)(TIM_OCPreload << 8); + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx Output Compare 1 Fast feature. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC1FE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr1 |= TIM_OCFast; + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Configures the TIMx Output Compare 2 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select + * the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2FE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr1 |= (uint16_t)(TIM_OCFast << 8); + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Configures the TIMx Output Compare 3 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC3FE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr2 |= TIM_OCFast; + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx Output Compare 4 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC4FE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr2 |= (uint16_t)(TIM_OCFast << 8); + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF1 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1CE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr1 |= TIM_OCClear; + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Clears or safeguards the OCREF2 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2CE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr1 |= (uint16_t)(TIM_OCClear << 8); + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Clears or safeguards the OCREF3 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC3CE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr2 |= TIM_OCClear; + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF4 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC4CE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr2 |= (uint16_t)(TIM_OCClear << 8); + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx channel 1 polarity. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC1 Polarity + * This parmeter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC1P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC1P); + tmpccer |= TIM_OCPolarity; + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 1N polarity. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC1N Polarity + * This parmeter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + /* Set or Reset the CC1NP Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC1NP); + tmpccer |= TIM_OCNPolarity; + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 2 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC2 Polarity + * This parmeter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC2P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC2P); + tmpccer |= (uint16_t)(TIM_OCPolarity << 4); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 2N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC2N Polarity + * This parmeter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + /* Set or Reset the CC2NP Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC2NP); + tmpccer |= (uint16_t)(TIM_OCNPolarity << 4); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 3 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC3 Polarity + * This parmeter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC3P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC3P); + tmpccer |= (uint16_t)(TIM_OCPolarity << 8); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 3N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC3N Polarity + * This parmeter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + /* Set or Reset the CC3NP Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC3NP); + tmpccer |= (uint16_t)(TIM_OCNPolarity << 8); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 4 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC4 Polarity + * This parmeter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC4P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC4P); + tmpccer |= (uint16_t)(TIM_OCPolarity << 12); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel x. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parmeter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @arg TIM_Channel_4: TIM Channel 4 + * @param TIM_CCx: specifies the TIM Channel CCxE bit new state. + * This parameter can be: TIM_CCx_Enable or TIM_CCx_Disable. + * @retval None + */ +void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx) +{ + uint16_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_CCX(TIM_CCx)); + + tmp = CCER_CCE_Set << TIM_Channel; + + /* Reset the CCxE Bit */ + TIMx->CCER &= (uint16_t)~ tmp; + + /* Set or reset the CCxE Bit */ + TIMx->CCER |= (uint16_t)(TIM_CCx << TIM_Channel); +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel xN. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parmeter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @param TIM_CCxN: specifies the TIM Channel CCxNE bit new state. + * This parameter can be: TIM_CCxN_Enable or TIM_CCxN_Disable. + * @retval None + */ +void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN) +{ + uint16_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_COMPLEMENTARY_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_CCXN(TIM_CCxN)); + + tmp = CCER_CCNE_Set << TIM_Channel; + + /* Reset the CCxNE Bit */ + TIMx->CCER &= (uint16_t) ~tmp; + + /* Set or reset the CCxNE Bit */ + TIMx->CCER |= (uint16_t)(TIM_CCxN << TIM_Channel); +} + +/** + * @brief Selects the TIM Ouput Compare Mode. + * @note This function disables the selected channel before changing the Ouput + * Compare Mode. + * User has to enable this channel using TIM_CCxCmd and TIM_CCxNCmd functions. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parmeter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @arg TIM_Channel_4: TIM Channel 4 + * @param TIM_OCMode: specifies the TIM Output Compare Mode. + * This paramter can be one of the following values: + * @arg TIM_OCMode_Timing + * @arg TIM_OCMode_Active + * @arg TIM_OCMode_Toggle + * @arg TIM_OCMode_PWM1 + * @arg TIM_OCMode_PWM2 + * @arg TIM_ForcedAction_Active + * @arg TIM_ForcedAction_InActive + * @retval None + */ +void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode) +{ + uint32_t tmp = 0; + uint16_t tmp1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_OCM(TIM_OCMode)); + + tmp = (uint32_t) TIMx; + tmp += CCMR_Offset; + + tmp1 = CCER_CCE_Set << (uint16_t)TIM_Channel; + + /* Disable the Channel: Reset the CCxE Bit */ + TIMx->CCER &= (uint16_t) ~tmp1; + + if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) + { + tmp += (TIM_Channel>>1); + + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC1M); + + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= TIM_OCMode; + } + else + { + tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1; + + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M); + + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8); + } +} + +/** + * @brief Enables or Disables the TIMx Update event. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param NewState: new state of the TIMx UDIS bit + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the Update Disable Bit */ + TIMx->CR1 |= TIM_CR1_UDIS; + } + else + { + /* Reset the Update Disable Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_UDIS); + } +} + +/** + * @brief Configures the TIMx Update Request Interrupt source. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_UpdateSource: specifies the Update source. + * This parameter can be one of the following values: + * @arg TIM_UpdateSource_Regular: Source of update is the counter overflow/underflow + or the setting of UG bit, or an update generation + through the slave mode controller. + * @arg TIM_UpdateSource_Global: Source of update is counter overflow/underflow. + * @retval None + */ +void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_UPDATE_SOURCE(TIM_UpdateSource)); + if (TIM_UpdateSource != TIM_UpdateSource_Global) + { + /* Set the URS Bit */ + TIMx->CR1 |= TIM_CR1_URS; + } + else + { + /* Reset the URS Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_URS); + } +} + +/** + * @brief Enables or disables the TIMx’s Hall sensor interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param NewState: new state of the TIMx Hall sensor interface. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the TI1S Bit */ + TIMx->CR2 |= TIM_CR2_TI1S; + } + else + { + /* Reset the TI1S Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_TI1S); + } +} + +/** + * @brief Selects the TIMx’s One Pulse Mode. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_OPMode: specifies the OPM Mode to be used. + * This parameter can be one of the following values: + * @arg TIM_OPMode_Single + * @arg TIM_OPMode_Repetitive + * @retval None + */ +void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_OPM_MODE(TIM_OPMode)); + /* Reset the OPM Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_OPM); + /* Configure the OPM Mode */ + TIMx->CR1 |= TIM_OPMode; +} + +/** + * @brief Selects the TIMx Trigger Output Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_TRGOSource: specifies the Trigger Output source. + * This paramter can be one of the following values: + * + * - For all TIMx + * @arg TIM_TRGOSource_Reset: The UG bit in the TIM_EGR register is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_Enable: The Counter Enable CEN is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_Update: The update event is selected as the trigger output (TRGO). + * + * - For all TIMx except TIM6 and TIM7 + * @arg TIM_TRGOSource_OC1: The trigger output sends a positive pulse when the CC1IF flag + * is to be set, as soon as a capture or compare match occurs (TRGO). + * @arg TIM_TRGOSource_OC1Ref: OC1REF signal is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_OC2Ref: OC2REF signal is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_OC3Ref: OC3REF signal is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_OC4Ref: OC4REF signal is used as the trigger output (TRGO). + * + * @retval None + */ +void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST7_PERIPH(TIMx)); + assert_param(IS_TIM_TRGO_SOURCE(TIM_TRGOSource)); + /* Reset the MMS Bits */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_MMS); + /* Select the TRGO source */ + TIMx->CR2 |= TIM_TRGOSource; +} + +/** + * @brief Selects the TIMx Slave Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_SlaveMode: specifies the Timer Slave Mode. + * This paramter can be one of the following values: + * @arg TIM_SlaveMode_Reset: Rising edge of the selected trigger signal (TRGI) re-initializes + * the counter and triggers an update of the registers. + * @arg TIM_SlaveMode_Gated: The counter clock is enabled when the trigger signal (TRGI) is high. + * @arg TIM_SlaveMode_Trigger: The counter starts at a rising edge of the trigger TRGI. + * @arg TIM_SlaveMode_External1: Rising edges of the selected trigger (TRGI) clock the counter. + * @retval None + */ +void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_SLAVE_MODE(TIM_SlaveMode)); + /* Reset the SMS Bits */ + TIMx->SMCR &= (uint16_t)~((uint16_t)TIM_SMCR_SMS); + /* Select the Slave Mode */ + TIMx->SMCR |= TIM_SlaveMode; +} + +/** + * @brief Sets or Resets the TIMx Master/Slave Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_MasterSlaveMode: specifies the Timer Master Slave Mode. + * This paramter can be one of the following values: + * @arg TIM_MasterSlaveMode_Enable: synchronization between the current timer + * and its slaves (through TRGO). + * @arg TIM_MasterSlaveMode_Disable: No action + * @retval None + */ +void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_MSM_STATE(TIM_MasterSlaveMode)); + /* Reset the MSM Bit */ + TIMx->SMCR &= (uint16_t)~((uint16_t)TIM_SMCR_MSM); + + /* Set or Reset the MSM Bit */ + TIMx->SMCR |= TIM_MasterSlaveMode; +} + +/** + * @brief Sets the TIMx Counter Register value + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param Counter: specifies the Counter register new value. + * @retval None + */ +void TIM_SetCounter(TIM_TypeDef* TIMx, uint16_t Counter) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Set the Counter Register value */ + TIMx->CNT = Counter; +} + +/** + * @brief Sets the TIMx Autoreload Register value + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param Autoreload: specifies the Autoreload register new value. + * @retval None + */ +void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint16_t Autoreload) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Set the Autoreload Register value */ + TIMx->ARR = Autoreload; +} + +/** + * @brief Sets the TIMx Capture Compare1 Register value + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param Compare1: specifies the Capture Compare1 register new value. + * @retval None + */ +void TIM_SetCompare1(TIM_TypeDef* TIMx, uint16_t Compare1) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + /* Set the Capture Compare1 Register value */ + TIMx->CCR1 = Compare1; +} + +/** + * @brief Sets the TIMx Capture Compare2 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param Compare2: specifies the Capture Compare2 register new value. + * @retval None + */ +void TIM_SetCompare2(TIM_TypeDef* TIMx, uint16_t Compare2) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Set the Capture Compare2 Register value */ + TIMx->CCR2 = Compare2; +} + +/** + * @brief Sets the TIMx Capture Compare3 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param Compare3: specifies the Capture Compare3 register new value. + * @retval None + */ +void TIM_SetCompare3(TIM_TypeDef* TIMx, uint16_t Compare3) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Set the Capture Compare3 Register value */ + TIMx->CCR3 = Compare3; +} + +/** + * @brief Sets the TIMx Capture Compare4 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param Compare4: specifies the Capture Compare4 register new value. + * @retval None + */ +void TIM_SetCompare4(TIM_TypeDef* TIMx, uint16_t Compare4) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Set the Capture Compare4 Register value */ + TIMx->CCR4 = Compare4; +} + +/** + * @brief Sets the TIMx Input Capture 1 prescaler. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture1 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC1PSC Bits */ + TIMx->CCMR1 &= (uint16_t)~((uint16_t)TIM_CCMR1_IC1PSC); + /* Set the IC1PSC value */ + TIMx->CCMR1 |= TIM_ICPSC; +} + +/** + * @brief Sets the TIMx Input Capture 2 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture2 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC2PSC Bits */ + TIMx->CCMR1 &= (uint16_t)~((uint16_t)TIM_CCMR1_IC2PSC); + /* Set the IC2PSC value */ + TIMx->CCMR1 |= (uint16_t)(TIM_ICPSC << 8); +} + +/** + * @brief Sets the TIMx Input Capture 3 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture3 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC3PSC Bits */ + TIMx->CCMR2 &= (uint16_t)~((uint16_t)TIM_CCMR2_IC3PSC); + /* Set the IC3PSC value */ + TIMx->CCMR2 |= TIM_ICPSC; +} + +/** + * @brief Sets the TIMx Input Capture 4 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture4 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC4PSC Bits */ + TIMx->CCMR2 &= (uint16_t)~((uint16_t)TIM_CCMR2_IC4PSC); + /* Set the IC4PSC value */ + TIMx->CCMR2 |= (uint16_t)(TIM_ICPSC << 8); +} + +/** + * @brief Sets the TIMx Clock Division value. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select + * the TIM peripheral. + * @param TIM_CKD: specifies the clock division value. + * This parameter can be one of the following value: + * @arg TIM_CKD_DIV1: TDTS = Tck_tim + * @arg TIM_CKD_DIV2: TDTS = 2*Tck_tim + * @arg TIM_CKD_DIV4: TDTS = 4*Tck_tim + * @retval None + */ +void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CKD_DIV(TIM_CKD)); + /* Reset the CKD Bits */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_CKD); + /* Set the CKD value */ + TIMx->CR1 |= TIM_CKD; +} + +/** + * @brief Gets the TIMx Input Capture 1 value. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @retval Capture Compare 1 Register value. + */ +uint16_t TIM_GetCapture1(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + /* Get the Capture 1 Register value */ + return TIMx->CCR1; +} + +/** + * @brief Gets the TIMx Input Capture 2 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @retval Capture Compare 2 Register value. + */ +uint16_t TIM_GetCapture2(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Get the Capture 2 Register value */ + return TIMx->CCR2; +} + +/** + * @brief Gets the TIMx Input Capture 3 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @retval Capture Compare 3 Register value. + */ +uint16_t TIM_GetCapture3(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Get the Capture 3 Register value */ + return TIMx->CCR3; +} + +/** + * @brief Gets the TIMx Input Capture 4 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @retval Capture Compare 4 Register value. + */ +uint16_t TIM_GetCapture4(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Get the Capture 4 Register value */ + return TIMx->CCR4; +} + +/** + * @brief Gets the TIMx Counter value. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @retval Counter Register value. + */ +uint16_t TIM_GetCounter(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Get the Counter Register value */ + return TIMx->CNT; +} + +/** + * @brief Gets the TIMx Prescaler value. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @retval Prescaler Register value. + */ +uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Get the Prescaler Register value */ + return TIMx->PSC; +} + +/** + * @brief Checks whether the specified TIM flag is set or not. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg TIM_FLAG_Update: TIM update Flag + * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag + * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag + * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag + * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag + * @arg TIM_FLAG_COM: TIM Commutation Flag + * @arg TIM_FLAG_Trigger: TIM Trigger Flag + * @arg TIM_FLAG_Break: TIM Break Flag + * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag + * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag + * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag + * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag + * @note + * - TIM6 and TIM7 can have only one update flag. + * - TIM9, TIM12 and TIM15 can have only TIM_FLAG_Update, TIM_FLAG_CC1, + * TIM_FLAG_CC2 or TIM_FLAG_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_FLAG_Update or TIM_FLAG_CC1. + * - TIM_FLAG_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_FLAG_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval The new state of TIM_FLAG (SET or RESET). + */ +FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_GET_FLAG(TIM_FLAG)); + + if ((TIMx->SR & TIM_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the TIMx's pending flags. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_FLAG: specifies the flag bit to clear. + * This parameter can be any combination of the following values: + * @arg TIM_FLAG_Update: TIM update Flag + * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag + * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag + * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag + * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag + * @arg TIM_FLAG_COM: TIM Commutation Flag + * @arg TIM_FLAG_Trigger: TIM Trigger Flag + * @arg TIM_FLAG_Break: TIM Break Flag + * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag + * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag + * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag + * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag + * @note + * - TIM6 and TIM7 can have only one update flag. + * - TIM9, TIM12 and TIM15 can have only TIM_FLAG_Update, TIM_FLAG_CC1, + * TIM_FLAG_CC2 or TIM_FLAG_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_FLAG_Update or TIM_FLAG_CC1. + * - TIM_FLAG_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_FLAG_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval None + */ +void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_CLEAR_FLAG(TIM_FLAG)); + + /* Clear the flags */ + TIMx->SR = (uint16_t)~TIM_FLAG; +} + +/** + * @brief Checks whether the TIM interrupt has occurred or not. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_IT: specifies the TIM interrupt source to check. + * This parameter can be one of the following values: + * @arg TIM_IT_Update: TIM update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * @note + * - TIM6 and TIM7 can generate only an update interrupt. + * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, + * TIM_IT_CC2 or TIM_IT_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. + * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval The new state of the TIM_IT(SET or RESET). + */ +ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itstatus = 0x0, itenable = 0x0; + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_GET_IT(TIM_IT)); + + itstatus = TIMx->SR & TIM_IT; + + itenable = TIMx->DIER & TIM_IT; + if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the TIMx's interrupt pending bits. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_IT: specifies the pending bit to clear. + * This parameter can be any combination of the following values: + * @arg TIM_IT_Update: TIM1 update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * @note + * - TIM6 and TIM7 can generate only an update interrupt. + * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, + * TIM_IT_CC2 or TIM_IT_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. + * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval None + */ +void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_IT(TIM_IT)); + /* Clear the IT pending Bit */ + TIMx->SR = (uint16_t)~TIM_IT; +} + +/** + * @brief Configure the TI1 as Input. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 1 is selected to be connected to IC1. + * @arg TIM_ICSelection_IndirectTI: TIM Input 1 is selected to be connected to IC2. + * @arg TIM_ICSelection_TRC: TIM Input 1 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr1 = 0, tmpccer = 0; + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC1E); + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + /* Select the Input and set the filter */ + tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC1S)) & ((uint16_t)~((uint16_t)TIM_CCMR1_IC1F))); + tmpccmr1 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC1P)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC1E); + } + else + { + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC1P | TIM_CCER_CC1NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC1E); + } + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI2 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 2 is selected to be connected to IC2. + * @arg TIM_ICSelection_IndirectTI: TIM Input 2 is selected to be connected to IC1. + * @arg TIM_ICSelection_TRC: TIM Input 2 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr1 = 0, tmpccer = 0, tmp = 0; + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC2E); + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 4); + /* Select the Input and set the filter */ + tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC2S)) & ((uint16_t)~((uint16_t)TIM_CCMR1_IC2F))); + tmpccmr1 |= (uint16_t)(TIM_ICFilter << 12); + tmpccmr1 |= (uint16_t)(TIM_ICSelection << 8); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC2P)); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC2E); + } + else + { + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC2P | TIM_CCER_CC2NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC2E); + } + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1 ; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI3 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 3 is selected to be connected to IC3. + * @arg TIM_ICSelection_IndirectTI: TIM Input 3 is selected to be connected to IC4. + * @arg TIM_ICSelection_TRC: TIM Input 3 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; + /* Disable the Channel 3: Reset the CC3E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC3E); + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 8); + /* Select the Input and set the filter */ + tmpccmr2 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR2_CC3S)) & ((uint16_t)~((uint16_t)TIM_CCMR2_IC3F))); + tmpccmr2 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC3E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P)); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC3E); + } + else + { + /* Select the Polarity and set the CC3E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P | TIM_CCER_CC3NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC3E); + } + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI4 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 4 is selected to be connected to IC4. + * @arg TIM_ICSelection_IndirectTI: TIM Input 4 is selected to be connected to IC3. + * @arg TIM_ICSelection_TRC: TIM Input 4 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC4E); + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 12); + /* Select the Input and set the filter */ + tmpccmr2 &= (uint16_t)((uint16_t)(~(uint16_t)TIM_CCMR2_CC4S) & ((uint16_t)~((uint16_t)TIM_CCMR2_IC4F))); + tmpccmr2 |= (uint16_t)(TIM_ICSelection << 8); + tmpccmr2 |= (uint16_t)(TIM_ICFilter << 12); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC4E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC4P)); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC4E); + } + else + { + /* Select the Polarity and set the CC4E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P | TIM_CCER_CC4NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC4E); + } + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c index 65a8062c6..90157e5a6 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c @@ -1,1055 +1,1055 @@ -/** - ****************************************************************************** - * @file stm32f10x_usart.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the USART firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_usart.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup USART - * @brief USART driver modules - * @{ - */ - -/** @defgroup USART_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup USART_Private_Defines - * @{ - */ - -#define CR1_UE_Set ((uint16_t)0x2000) /*!< USART Enable Mask */ -#define CR1_UE_Reset ((uint16_t)0xDFFF) /*!< USART Disable Mask */ - -#define CR1_WAKE_Mask ((uint16_t)0xF7FF) /*!< USART WakeUp Method Mask */ - -#define CR1_RWU_Set ((uint16_t)0x0002) /*!< USART mute mode Enable Mask */ -#define CR1_RWU_Reset ((uint16_t)0xFFFD) /*!< USART mute mode Enable Mask */ -#define CR1_SBK_Set ((uint16_t)0x0001) /*!< USART Break Character send Mask */ -#define CR1_CLEAR_Mask ((uint16_t)0xE9F3) /*!< USART CR1 Mask */ -#define CR2_Address_Mask ((uint16_t)0xFFF0) /*!< USART address Mask */ - -#define CR2_LINEN_Set ((uint16_t)0x4000) /*!< USART LIN Enable Mask */ -#define CR2_LINEN_Reset ((uint16_t)0xBFFF) /*!< USART LIN Disable Mask */ - -#define CR2_LBDL_Mask ((uint16_t)0xFFDF) /*!< USART LIN Break detection Mask */ -#define CR2_STOP_CLEAR_Mask ((uint16_t)0xCFFF) /*!< USART CR2 STOP Bits Mask */ -#define CR2_CLOCK_CLEAR_Mask ((uint16_t)0xF0FF) /*!< USART CR2 Clock Mask */ - -#define CR3_SCEN_Set ((uint16_t)0x0020) /*!< USART SC Enable Mask */ -#define CR3_SCEN_Reset ((uint16_t)0xFFDF) /*!< USART SC Disable Mask */ - -#define CR3_NACK_Set ((uint16_t)0x0010) /*!< USART SC NACK Enable Mask */ -#define CR3_NACK_Reset ((uint16_t)0xFFEF) /*!< USART SC NACK Disable Mask */ - -#define CR3_HDSEL_Set ((uint16_t)0x0008) /*!< USART Half-Duplex Enable Mask */ -#define CR3_HDSEL_Reset ((uint16_t)0xFFF7) /*!< USART Half-Duplex Disable Mask */ - -#define CR3_IRLP_Mask ((uint16_t)0xFFFB) /*!< USART IrDA LowPower mode Mask */ -#define CR3_CLEAR_Mask ((uint16_t)0xFCFF) /*!< USART CR3 Mask */ - -#define CR3_IREN_Set ((uint16_t)0x0002) /*!< USART IrDA Enable Mask */ -#define CR3_IREN_Reset ((uint16_t)0xFFFD) /*!< USART IrDA Disable Mask */ -#define GTPR_LSB_Mask ((uint16_t)0x00FF) /*!< Guard Time Register LSB Mask */ -#define GTPR_MSB_Mask ((uint16_t)0xFF00) /*!< Guard Time Register MSB Mask */ -#define IT_Mask ((uint16_t)0x001F) /*!< USART Interrupt Mask */ - -/* USART OverSampling-8 Mask */ -#define CR1_OVER8_Set ((u16)0x8000) /* USART OVER8 mode Enable Mask */ -#define CR1_OVER8_Reset ((u16)0x7FFF) /* USART OVER8 mode Disable Mask */ - -/* USART One Bit Sampling Mask */ -#define CR3_ONEBITE_Set ((u16)0x0800) /* USART ONEBITE mode Enable Mask */ -#define CR3_ONEBITE_Reset ((u16)0xF7FF) /* USART ONEBITE mode Disable Mask */ - -/** - * @} - */ - -/** @defgroup USART_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup USART_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup USART_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup USART_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the USARTx peripheral registers to their default reset values. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: USART1, USART2, USART3, UART4 or UART5. - * @retval None - */ -void USART_DeInit(USART_TypeDef* USARTx) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - - if (USARTx == USART1) - { - RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE); - RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE); - } - else if (USARTx == USART2) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE); - } - else if (USARTx == USART3) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE); - } - else if (USARTx == UART4) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE); - } - else - { - if (USARTx == UART5) - { - RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE); - } - } -} - -/** - * @brief Initializes the USARTx peripheral according to the specified - * parameters in the USART_InitStruct . - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_InitStruct: pointer to a USART_InitTypeDef structure - * that contains the configuration information for the specified USART peripheral. - * @retval None - */ -void USART_Init(USART_TypeDef* USARTx, const USART_InitTypeDef* USART_InitStruct) -{ - uint32_t tmpreg = 0x00, apbclock = 0x00; - uint32_t integerdivider = 0x00; - uint32_t fractionaldivider = 0x00; - uint32_t usartxbase = 0; - RCC_ClocksTypeDef RCC_ClocksStatus; - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate)); - assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength)); - assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits)); - assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity)); - assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode)); - assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl)); - /* The hardware flow control is available only for USART1, USART2 and USART3 */ - if (USART_InitStruct->USART_HardwareFlowControl != USART_HardwareFlowControl_None) - { - assert_param(IS_USART_123_PERIPH(USARTx)); - } - - usartxbase = (uint32_t)USARTx; - -/*---------------------------- USART CR2 Configuration -----------------------*/ - tmpreg = USARTx->CR2; - /* Clear STOP[13:12] bits */ - tmpreg &= CR2_STOP_CLEAR_Mask; - /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit ------------*/ - /* Set STOP[13:12] bits according to USART_StopBits value */ - tmpreg |= (uint32_t)USART_InitStruct->USART_StopBits; - - /* Write to USART CR2 */ - USARTx->CR2 = (uint16_t)tmpreg; - -/*---------------------------- USART CR1 Configuration -----------------------*/ - tmpreg = USARTx->CR1; - /* Clear M, PCE, PS, TE and RE bits */ - tmpreg &= CR1_CLEAR_Mask; - /* Configure the USART Word Length, Parity and mode ----------------------- */ - /* Set the M bits according to USART_WordLength value */ - /* Set PCE and PS bits according to USART_Parity value */ - /* Set TE and RE bits according to USART_Mode value */ - tmpreg |= (uint32_t)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity | - USART_InitStruct->USART_Mode; - /* Write to USART CR1 */ - USARTx->CR1 = (uint16_t)tmpreg; - -/*---------------------------- USART CR3 Configuration -----------------------*/ - tmpreg = USARTx->CR3; - /* Clear CTSE and RTSE bits */ - tmpreg &= CR3_CLEAR_Mask; - /* Configure the USART HFC -------------------------------------------------*/ - /* Set CTSE and RTSE bits according to USART_HardwareFlowControl value */ - tmpreg |= USART_InitStruct->USART_HardwareFlowControl; - /* Write to USART CR3 */ - USARTx->CR3 = (uint16_t)tmpreg; - -/*---------------------------- USART BRR Configuration -----------------------*/ - /* Configure the USART Baud Rate -------------------------------------------*/ - RCC_GetClocksFreq(&RCC_ClocksStatus); - if (usartxbase == USART1_BASE) - { - apbclock = RCC_ClocksStatus.PCLK2_Frequency; - } - else - { - apbclock = RCC_ClocksStatus.PCLK1_Frequency; - } - - /* Determine the integer part */ - if ((USARTx->CR1 & CR1_OVER8_Set) != 0) - { - /* Integer part computing in case Oversampling mode is 8 Samples */ - integerdivider = ((25 * apbclock) / (2 * (USART_InitStruct->USART_BaudRate))); - } - else /* if ((USARTx->CR1 & CR1_OVER8_Set) == 0) */ - { - /* Integer part computing in case Oversampling mode is 16 Samples */ - integerdivider = ((25 * apbclock) / (4 * (USART_InitStruct->USART_BaudRate))); - } - tmpreg = (integerdivider / 100) << 4; - - /* Determine the fractional part */ - fractionaldivider = integerdivider - (100 * (tmpreg >> 4)); - - /* Implement the fractional part in the register */ - if ((USARTx->CR1 & CR1_OVER8_Set) != 0) - { - tmpreg |= ((((fractionaldivider * 8) + 50) / 100)) & ((uint8_t)0x07); - } - else /* if ((USARTx->CR1 & CR1_OVER8_Set) == 0) */ - { - tmpreg |= ((((fractionaldivider * 16) + 50) / 100)) & ((uint8_t)0x0F); - } - - /* Write to USART BRR */ - USARTx->BRR = (uint16_t)tmpreg; -} - -/** - * @brief Fills each USART_InitStruct member with its default value. - * @param USART_InitStruct: pointer to a USART_InitTypeDef structure - * which will be initialized. - * @retval None - */ -void USART_StructInit(USART_InitTypeDef* USART_InitStruct) -{ - /* USART_InitStruct members default value */ - USART_InitStruct->USART_BaudRate = 9600; - USART_InitStruct->USART_WordLength = USART_WordLength_8b; - USART_InitStruct->USART_StopBits = USART_StopBits_1; - USART_InitStruct->USART_Parity = USART_Parity_No ; - USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx; - USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None; -} - -/** - * @brief Initializes the USARTx peripheral Clock according to the - * specified parameters in the USART_ClockInitStruct . - * @param USARTx: where x can be 1, 2, 3 to select the USART peripheral. - * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef - * structure that contains the configuration information for the specified - * USART peripheral. - * @note The Smart Card mode is not available for UART4 and UART5. - * @retval None - */ -void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct) -{ - uint32_t tmpreg = 0x00; - /* Check the parameters */ - assert_param(IS_USART_123_PERIPH(USARTx)); - assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock)); - assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL)); - assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA)); - assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit)); - -/*---------------------------- USART CR2 Configuration -----------------------*/ - tmpreg = USARTx->CR2; - /* Clear CLKEN, CPOL, CPHA and LBCL bits */ - tmpreg &= CR2_CLOCK_CLEAR_Mask; - /* Configure the USART Clock, CPOL, CPHA and LastBit ------------*/ - /* Set CLKEN bit according to USART_Clock value */ - /* Set CPOL bit according to USART_CPOL value */ - /* Set CPHA bit according to USART_CPHA value */ - /* Set LBCL bit according to USART_LastBit value */ - tmpreg |= (uint32_t)USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL | - USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit; - /* Write to USART CR2 */ - USARTx->CR2 = (uint16_t)tmpreg; -} - -/** - * @brief Fills each USART_ClockInitStruct member with its default value. - * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef - * structure which will be initialized. - * @retval None - */ -void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct) -{ - /* USART_ClockInitStruct members default value */ - USART_ClockInitStruct->USART_Clock = USART_Clock_Disable; - USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low; - USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge; - USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable; -} - -/** - * @brief Enables or disables the specified USART peripheral. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param NewState: new state of the USARTx peripheral. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the selected USART by setting the UE bit in the CR1 register */ - USARTx->CR1 |= CR1_UE_Set; - } - else - { - /* Disable the selected USART by clearing the UE bit in the CR1 register */ - USARTx->CR1 &= CR1_UE_Reset; - } -} - -/** - * @brief Enables or disables the specified USART interrupts. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_IT: specifies the USART interrupt sources to be enabled or disabled. - * This parameter can be one of the following values: - * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) - * @arg USART_IT_LBD: LIN Break detection interrupt - * @arg USART_IT_TXE: Tansmit Data Register empty interrupt - * @arg USART_IT_TC: Transmission complete interrupt - * @arg USART_IT_RXNE: Receive Data register not empty interrupt - * @arg USART_IT_IDLE: Idle line detection interrupt - * @arg USART_IT_PE: Parity Error interrupt - * @arg USART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @param NewState: new state of the specified USARTx interrupts. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState) -{ - uint32_t usartreg = 0x00, itpos = 0x00, itmask = 0x00; - uint32_t usartxbase = 0x00; - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_CONFIG_IT(USART_IT)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - /* The CTS interrupt is not available for UART4 and UART5 */ - if (USART_IT == USART_IT_CTS) - { - assert_param(IS_USART_123_PERIPH(USARTx)); - } - - usartxbase = (uint32_t)USARTx; - - /* Get the USART register index */ - usartreg = (((uint8_t)USART_IT) >> 0x05); - - /* Get the interrupt position */ - itpos = USART_IT & IT_Mask; - itmask = (((uint32_t)0x01) << itpos); - - if (usartreg == 0x01) /* The IT is in CR1 register */ - { - usartxbase += 0x0C; - } - else if (usartreg == 0x02) /* The IT is in CR2 register */ - { - usartxbase += 0x10; - } - else /* The IT is in CR3 register */ - { - usartxbase += 0x14; - } - if (NewState != DISABLE) - { - *(__IO uint32_t*)usartxbase |= itmask; - } - else - { - *(__IO uint32_t*)usartxbase &= ~itmask; - } -} - -/** - * @brief Enables or disables the USART’s DMA interface. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_DMAReq: specifies the DMA request. - * This parameter can be any combination of the following values: - * @arg USART_DMAReq_Tx: USART DMA transmit request - * @arg USART_DMAReq_Rx: USART DMA receive request - * @param NewState: new state of the DMA Request sources. - * This parameter can be: ENABLE or DISABLE. - * @note The DMA mode is not available for UART5 except in the STM32 - * High density value line devices(STM32F10X_HD_VL). - * @retval None - */ -void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_DMAREQ(USART_DMAReq)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the DMA transfer for selected requests by setting the DMAT and/or - DMAR bits in the USART CR3 register */ - USARTx->CR3 |= USART_DMAReq; - } - else - { - /* Disable the DMA transfer for selected requests by clearing the DMAT and/or - DMAR bits in the USART CR3 register */ - USARTx->CR3 &= (uint16_t)~USART_DMAReq; - } -} - -/** - * @brief Sets the address of the USART node. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_Address: Indicates the address of the USART node. - * @retval None - */ -void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_ADDRESS(USART_Address)); - - /* Clear the USART address */ - USARTx->CR2 &= CR2_Address_Mask; - /* Set the USART address node */ - USARTx->CR2 |= USART_Address; -} - -/** - * @brief Selects the USART WakeUp method. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_WakeUp: specifies the USART wakeup method. - * This parameter can be one of the following values: - * @arg USART_WakeUp_IdleLine: WakeUp by an idle line detection - * @arg USART_WakeUp_AddressMark: WakeUp by an address mark - * @retval None - */ -void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_WAKEUP(USART_WakeUp)); - - USARTx->CR1 &= CR1_WAKE_Mask; - USARTx->CR1 |= USART_WakeUp; -} - -/** - * @brief Determines if the USART is in mute mode or not. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param NewState: new state of the USART mute mode. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the USART mute mode by setting the RWU bit in the CR1 register */ - USARTx->CR1 |= CR1_RWU_Set; - } - else - { - /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */ - USARTx->CR1 &= CR1_RWU_Reset; - } -} - -/** - * @brief Sets the USART LIN Break detection length. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_LINBreakDetectLength: specifies the LIN break detection length. - * This parameter can be one of the following values: - * @arg USART_LINBreakDetectLength_10b: 10-bit break detection - * @arg USART_LINBreakDetectLength_11b: 11-bit break detection - * @retval None - */ -void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength)); - - USARTx->CR2 &= CR2_LBDL_Mask; - USARTx->CR2 |= USART_LINBreakDetectLength; -} - -/** - * @brief Enables or disables the USART’s LIN mode. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param NewState: new state of the USART LIN mode. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ - USARTx->CR2 |= CR2_LINEN_Set; - } - else - { - /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */ - USARTx->CR2 &= CR2_LINEN_Reset; - } -} - -/** - * @brief Transmits single data through the USARTx peripheral. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param Data: the data to transmit. - * @retval None - */ -void USART_SendData(USART_TypeDef* USARTx, uint16_t Data) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_DATA(Data)); - - /* Transmit Data */ - USARTx->DR = (Data & (uint16_t)0x01FF); -} - -/** - * @brief Returns the most recent received data by the USARTx peripheral. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @retval The received data. - */ -uint16_t USART_ReceiveData(USART_TypeDef* USARTx) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - - /* Receive Data */ - return (uint16_t)(USARTx->DR & (uint16_t)0x01FF); -} - -/** - * @brief Transmits break characters. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @retval None - */ -void USART_SendBreak(USART_TypeDef* USARTx) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - - /* Send break characters */ - USARTx->CR1 |= CR1_SBK_Set; -} - -/** - * @brief Sets the specified USART guard time. - * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. - * @param USART_GuardTime: specifies the guard time. - * @note The guard time bits are not available for UART4 and UART5. - * @retval None - */ -void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime) -{ - /* Check the parameters */ - assert_param(IS_USART_123_PERIPH(USARTx)); - - /* Clear the USART Guard time */ - USARTx->GTPR &= GTPR_LSB_Mask; - /* Set the USART guard time */ - USARTx->GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08); -} - -/** - * @brief Sets the system clock prescaler. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_Prescaler: specifies the prescaler clock. - * @note The function is used for IrDA mode with UART4 and UART5. - * @retval None - */ -void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - - /* Clear the USART prescaler */ - USARTx->GTPR &= GTPR_MSB_Mask; - /* Set the USART prescaler */ - USARTx->GTPR |= USART_Prescaler; -} - -/** - * @brief Enables or disables the USART’s Smart Card mode. - * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. - * @param NewState: new state of the Smart Card mode. - * This parameter can be: ENABLE or DISABLE. - * @note The Smart Card mode is not available for UART4 and UART5. - * @retval None - */ -void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_USART_123_PERIPH(USARTx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the SC mode by setting the SCEN bit in the CR3 register */ - USARTx->CR3 |= CR3_SCEN_Set; - } - else - { - /* Disable the SC mode by clearing the SCEN bit in the CR3 register */ - USARTx->CR3 &= CR3_SCEN_Reset; - } -} - -/** - * @brief Enables or disables NACK transmission. - * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. - * @param NewState: new state of the NACK transmission. - * This parameter can be: ENABLE or DISABLE. - * @note The Smart Card mode is not available for UART4 and UART5. - * @retval None - */ -void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_USART_123_PERIPH(USARTx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - if (NewState != DISABLE) - { - /* Enable the NACK transmission by setting the NACK bit in the CR3 register */ - USARTx->CR3 |= CR3_NACK_Set; - } - else - { - /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */ - USARTx->CR3 &= CR3_NACK_Reset; - } -} - -/** - * @brief Enables or disables the USART’s Half Duplex communication. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param NewState: new state of the USART Communication. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ - USARTx->CR3 |= CR3_HDSEL_Set; - } - else - { - /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */ - USARTx->CR3 &= CR3_HDSEL_Reset; - } -} - - -/** - * @brief Enables or disables the USART's 8x oversampling mode. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param NewState: new state of the USART one bit sampling methode. - * This parameter can be: ENABLE or DISABLE. - * @note - * This function has to be called before calling USART_Init() - * function in order to have correct baudrate Divider value. - * @retval None - */ -void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the 8x Oversampling mode by setting the OVER8 bit in the CR1 register */ - USARTx->CR1 |= CR1_OVER8_Set; - } - else - { - /* Disable the 8x Oversampling mode by clearing the OVER8 bit in the CR1 register */ - USARTx->CR1 &= CR1_OVER8_Reset; - } -} - -/** - * @brief Enables or disables the USART's one bit sampling methode. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param NewState: new state of the USART one bit sampling methode. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the one bit method by setting the ONEBITE bit in the CR3 register */ - USARTx->CR3 |= CR3_ONEBITE_Set; - } - else - { - /* Disable tthe one bit method by clearing the ONEBITE bit in the CR3 register */ - USARTx->CR3 &= CR3_ONEBITE_Reset; - } -} - -/** - * @brief Configures the USART’s IrDA interface. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_IrDAMode: specifies the IrDA mode. - * This parameter can be one of the following values: - * @arg USART_IrDAMode_LowPower - * @arg USART_IrDAMode_Normal - * @retval None - */ -void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_IRDA_MODE(USART_IrDAMode)); - - USARTx->CR3 &= CR3_IRLP_Mask; - USARTx->CR3 |= USART_IrDAMode; -} - -/** - * @brief Enables or disables the USART’s IrDA interface. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param NewState: new state of the IrDA mode. - * This parameter can be: ENABLE or DISABLE. - * @retval None - */ -void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_FUNCTIONAL_STATE(NewState)); - - if (NewState != DISABLE) - { - /* Enable the IrDA mode by setting the IREN bit in the CR3 register */ - USARTx->CR3 |= CR3_IREN_Set; - } - else - { - /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */ - USARTx->CR3 &= CR3_IREN_Reset; - } -} - -/** - * @brief Checks whether the specified USART flag is set or not. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_FLAG: specifies the flag to check. - * This parameter can be one of the following values: - * @arg USART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5) - * @arg USART_FLAG_LBD: LIN Break detection flag - * @arg USART_FLAG_TXE: Transmit data register empty flag - * @arg USART_FLAG_TC: Transmission Complete flag - * @arg USART_FLAG_RXNE: Receive data register not empty flag - * @arg USART_FLAG_IDLE: Idle Line detection flag - * @arg USART_FLAG_ORE: OverRun Error flag - * @arg USART_FLAG_NE: Noise Error flag - * @arg USART_FLAG_FE: Framing Error flag - * @arg USART_FLAG_PE: Parity Error flag - * @retval The new state of USART_FLAG (SET or RESET). - */ -FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG) -{ - FlagStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_FLAG(USART_FLAG)); - /* The CTS flag is not available for UART4 and UART5 */ - if (USART_FLAG == USART_FLAG_CTS) - { - assert_param(IS_USART_123_PERIPH(USARTx)); - } - - if ((USARTx->SR & USART_FLAG) != (uint16_t)RESET) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - return bitstatus; -} - -/** - * @brief Clears the USARTx's pending flags. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_FLAG: specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg USART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5). - * @arg USART_FLAG_LBD: LIN Break detection flag. - * @arg USART_FLAG_TC: Transmission Complete flag. - * @arg USART_FLAG_RXNE: Receive data register not empty flag. - * - * @note - * - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun - * error) and IDLE (Idle line detected) flags are cleared by software - * sequence: a read operation to USART_SR register (USART_GetFlagStatus()) - * followed by a read operation to USART_DR register (USART_ReceiveData()). - * - RXNE flag can be also cleared by a read to the USART_DR register - * (USART_ReceiveData()). - * - TC flag can be also cleared by software sequence: a read operation to - * USART_SR register (USART_GetFlagStatus()) followed by a write operation - * to USART_DR register (USART_SendData()). - * - TXE flag is cleared only by a write to the USART_DR register - * (USART_SendData()). - * @retval None - */ -void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG) -{ - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_CLEAR_FLAG(USART_FLAG)); - /* The CTS flag is not available for UART4 and UART5 */ - if ((USART_FLAG & USART_FLAG_CTS) == USART_FLAG_CTS) - { - assert_param(IS_USART_123_PERIPH(USARTx)); - } - - USARTx->SR = (uint16_t)~USART_FLAG; -} - -/** - * @brief Checks whether the specified USART interrupt has occurred or not. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_IT: specifies the USART interrupt source to check. - * This parameter can be one of the following values: - * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) - * @arg USART_IT_LBD: LIN Break detection interrupt - * @arg USART_IT_TXE: Tansmit Data Register empty interrupt - * @arg USART_IT_TC: Transmission complete interrupt - * @arg USART_IT_RXNE: Receive Data register not empty interrupt - * @arg USART_IT_IDLE: Idle line detection interrupt - * @arg USART_IT_ORE: OverRun Error interrupt - * @arg USART_IT_NE: Noise Error interrupt - * @arg USART_IT_FE: Framing Error interrupt - * @arg USART_IT_PE: Parity Error interrupt - * @retval The new state of USART_IT (SET or RESET). - */ -ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT) -{ - uint32_t bitpos = 0x00, itmask = 0x00, usartreg = 0x00; - ITStatus bitstatus = RESET; - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_GET_IT(USART_IT)); - /* The CTS interrupt is not available for UART4 and UART5 */ - if (USART_IT == USART_IT_CTS) - { - assert_param(IS_USART_123_PERIPH(USARTx)); - } - - /* Get the USART register index */ - usartreg = (((uint8_t)USART_IT) >> 0x05); - /* Get the interrupt position */ - itmask = USART_IT & IT_Mask; - itmask = (uint32_t)0x01 << itmask; - - if (usartreg == 0x01) /* The IT is in CR1 register */ - { - itmask &= USARTx->CR1; - } - else if (usartreg == 0x02) /* The IT is in CR2 register */ - { - itmask &= USARTx->CR2; - } - else /* The IT is in CR3 register */ - { - itmask &= USARTx->CR3; - } - - bitpos = USART_IT >> 0x08; - bitpos = (uint32_t)0x01 << bitpos; - bitpos &= USARTx->SR; - if ((itmask != (uint16_t)RESET)&&(bitpos != (uint16_t)RESET)) - { - bitstatus = SET; - } - else - { - bitstatus = RESET; - } - - return bitstatus; -} - -/** - * @brief Clears the USARTx’s interrupt pending bits. - * @param USARTx: Select the USART or the UART peripheral. - * This parameter can be one of the following values: - * USART1, USART2, USART3, UART4 or UART5. - * @param USART_IT: specifies the interrupt pending bit to clear. - * This parameter can be one of the following values: - * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) - * @arg USART_IT_LBD: LIN Break detection interrupt - * @arg USART_IT_TC: Transmission complete interrupt. - * @arg USART_IT_RXNE: Receive Data register not empty interrupt. - * - * @note - * - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun - * error) and IDLE (Idle line detected) pending bits are cleared by - * software sequence: a read operation to USART_SR register - * (USART_GetITStatus()) followed by a read operation to USART_DR register - * (USART_ReceiveData()). - * - RXNE pending bit can be also cleared by a read to the USART_DR register - * (USART_ReceiveData()). - * - TC pending bit can be also cleared by software sequence: a read - * operation to USART_SR register (USART_GetITStatus()) followed by a write - * operation to USART_DR register (USART_SendData()). - * - TXE pending bit is cleared only by a write to the USART_DR register - * (USART_SendData()). - * @retval None - */ -void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT) -{ - uint16_t bitpos = 0x00, itmask = 0x00; - /* Check the parameters */ - assert_param(IS_USART_ALL_PERIPH(USARTx)); - assert_param(IS_USART_CLEAR_IT(USART_IT)); - /* The CTS interrupt is not available for UART4 and UART5 */ - if (USART_IT == USART_IT_CTS) - { - assert_param(IS_USART_123_PERIPH(USARTx)); - } - - bitpos = USART_IT >> 0x08; - itmask = ((uint16_t)0x01 << (uint16_t)bitpos); - USARTx->SR = (uint16_t)~itmask; -} -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_usart.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the USART firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_usart.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup USART + * @brief USART driver modules + * @{ + */ + +/** @defgroup USART_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_Defines + * @{ + */ + +#define CR1_UE_Set ((uint16_t)0x2000) /*!< USART Enable Mask */ +#define CR1_UE_Reset ((uint16_t)0xDFFF) /*!< USART Disable Mask */ + +#define CR1_WAKE_Mask ((uint16_t)0xF7FF) /*!< USART WakeUp Method Mask */ + +#define CR1_RWU_Set ((uint16_t)0x0002) /*!< USART mute mode Enable Mask */ +#define CR1_RWU_Reset ((uint16_t)0xFFFD) /*!< USART mute mode Enable Mask */ +#define CR1_SBK_Set ((uint16_t)0x0001) /*!< USART Break Character send Mask */ +#define CR1_CLEAR_Mask ((uint16_t)0xE9F3) /*!< USART CR1 Mask */ +#define CR2_Address_Mask ((uint16_t)0xFFF0) /*!< USART address Mask */ + +#define CR2_LINEN_Set ((uint16_t)0x4000) /*!< USART LIN Enable Mask */ +#define CR2_LINEN_Reset ((uint16_t)0xBFFF) /*!< USART LIN Disable Mask */ + +#define CR2_LBDL_Mask ((uint16_t)0xFFDF) /*!< USART LIN Break detection Mask */ +#define CR2_STOP_CLEAR_Mask ((uint16_t)0xCFFF) /*!< USART CR2 STOP Bits Mask */ +#define CR2_CLOCK_CLEAR_Mask ((uint16_t)0xF0FF) /*!< USART CR2 Clock Mask */ + +#define CR3_SCEN_Set ((uint16_t)0x0020) /*!< USART SC Enable Mask */ +#define CR3_SCEN_Reset ((uint16_t)0xFFDF) /*!< USART SC Disable Mask */ + +#define CR3_NACK_Set ((uint16_t)0x0010) /*!< USART SC NACK Enable Mask */ +#define CR3_NACK_Reset ((uint16_t)0xFFEF) /*!< USART SC NACK Disable Mask */ + +#define CR3_HDSEL_Set ((uint16_t)0x0008) /*!< USART Half-Duplex Enable Mask */ +#define CR3_HDSEL_Reset ((uint16_t)0xFFF7) /*!< USART Half-Duplex Disable Mask */ + +#define CR3_IRLP_Mask ((uint16_t)0xFFFB) /*!< USART IrDA LowPower mode Mask */ +#define CR3_CLEAR_Mask ((uint16_t)0xFCFF) /*!< USART CR3 Mask */ + +#define CR3_IREN_Set ((uint16_t)0x0002) /*!< USART IrDA Enable Mask */ +#define CR3_IREN_Reset ((uint16_t)0xFFFD) /*!< USART IrDA Disable Mask */ +#define GTPR_LSB_Mask ((uint16_t)0x00FF) /*!< Guard Time Register LSB Mask */ +#define GTPR_MSB_Mask ((uint16_t)0xFF00) /*!< Guard Time Register MSB Mask */ +#define IT_Mask ((uint16_t)0x001F) /*!< USART Interrupt Mask */ + +/* USART OverSampling-8 Mask */ +#define CR1_OVER8_Set ((u16)0x8000) /* USART OVER8 mode Enable Mask */ +#define CR1_OVER8_Reset ((u16)0x7FFF) /* USART OVER8 mode Disable Mask */ + +/* USART One Bit Sampling Mask */ +#define CR3_ONEBITE_Set ((u16)0x0800) /* USART ONEBITE mode Enable Mask */ +#define CR3_ONEBITE_Reset ((u16)0xF7FF) /* USART ONEBITE mode Disable Mask */ + +/** + * @} + */ + +/** @defgroup USART_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the USARTx peripheral registers to their default reset values. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: USART1, USART2, USART3, UART4 or UART5. + * @retval None + */ +void USART_DeInit(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + if (USARTx == USART1) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE); + } + else if (USARTx == USART2) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE); + } + else if (USARTx == USART3) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE); + } + else if (USARTx == UART4) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE); + } + else + { + if (USARTx == UART5) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE); + } + } +} + +/** + * @brief Initializes the USARTx peripheral according to the specified + * parameters in the USART_InitStruct . + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_InitStruct: pointer to a USART_InitTypeDef structure + * that contains the configuration information for the specified USART peripheral. + * @retval None + */ +void USART_Init(USART_TypeDef* USARTx, const USART_InitTypeDef* USART_InitStruct) +{ + uint32_t tmpreg = 0x00, apbclock = 0x00; + uint32_t integerdivider = 0x00; + uint32_t fractionaldivider = 0x00; + uint32_t usartxbase = 0; + RCC_ClocksTypeDef RCC_ClocksStatus; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate)); + assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength)); + assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits)); + assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity)); + assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode)); + assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl)); + /* The hardware flow control is available only for USART1, USART2 and USART3 */ + if (USART_InitStruct->USART_HardwareFlowControl != USART_HardwareFlowControl_None) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + usartxbase = (uint32_t)USARTx; + +/*---------------------------- USART CR2 Configuration -----------------------*/ + tmpreg = USARTx->CR2; + /* Clear STOP[13:12] bits */ + tmpreg &= CR2_STOP_CLEAR_Mask; + /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit ------------*/ + /* Set STOP[13:12] bits according to USART_StopBits value */ + tmpreg |= (uint32_t)USART_InitStruct->USART_StopBits; + + /* Write to USART CR2 */ + USARTx->CR2 = (uint16_t)tmpreg; + +/*---------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = USARTx->CR1; + /* Clear M, PCE, PS, TE and RE bits */ + tmpreg &= CR1_CLEAR_Mask; + /* Configure the USART Word Length, Parity and mode ----------------------- */ + /* Set the M bits according to USART_WordLength value */ + /* Set PCE and PS bits according to USART_Parity value */ + /* Set TE and RE bits according to USART_Mode value */ + tmpreg |= (uint32_t)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity | + USART_InitStruct->USART_Mode; + /* Write to USART CR1 */ + USARTx->CR1 = (uint16_t)tmpreg; + +/*---------------------------- USART CR3 Configuration -----------------------*/ + tmpreg = USARTx->CR3; + /* Clear CTSE and RTSE bits */ + tmpreg &= CR3_CLEAR_Mask; + /* Configure the USART HFC -------------------------------------------------*/ + /* Set CTSE and RTSE bits according to USART_HardwareFlowControl value */ + tmpreg |= USART_InitStruct->USART_HardwareFlowControl; + /* Write to USART CR3 */ + USARTx->CR3 = (uint16_t)tmpreg; + +/*---------------------------- USART BRR Configuration -----------------------*/ + /* Configure the USART Baud Rate -------------------------------------------*/ + RCC_GetClocksFreq(&RCC_ClocksStatus); + if (usartxbase == USART1_BASE) + { + apbclock = RCC_ClocksStatus.PCLK2_Frequency; + } + else + { + apbclock = RCC_ClocksStatus.PCLK1_Frequency; + } + + /* Determine the integer part */ + if ((USARTx->CR1 & CR1_OVER8_Set) != 0) + { + /* Integer part computing in case Oversampling mode is 8 Samples */ + integerdivider = ((25 * apbclock) / (2 * (USART_InitStruct->USART_BaudRate))); + } + else /* if ((USARTx->CR1 & CR1_OVER8_Set) == 0) */ + { + /* Integer part computing in case Oversampling mode is 16 Samples */ + integerdivider = ((25 * apbclock) / (4 * (USART_InitStruct->USART_BaudRate))); + } + tmpreg = (integerdivider / 100) << 4; + + /* Determine the fractional part */ + fractionaldivider = integerdivider - (100 * (tmpreg >> 4)); + + /* Implement the fractional part in the register */ + if ((USARTx->CR1 & CR1_OVER8_Set) != 0) + { + tmpreg |= ((((fractionaldivider * 8) + 50) / 100)) & ((uint8_t)0x07); + } + else /* if ((USARTx->CR1 & CR1_OVER8_Set) == 0) */ + { + tmpreg |= ((((fractionaldivider * 16) + 50) / 100)) & ((uint8_t)0x0F); + } + + /* Write to USART BRR */ + USARTx->BRR = (uint16_t)tmpreg; +} + +/** + * @brief Fills each USART_InitStruct member with its default value. + * @param USART_InitStruct: pointer to a USART_InitTypeDef structure + * which will be initialized. + * @retval None + */ +void USART_StructInit(USART_InitTypeDef* USART_InitStruct) +{ + /* USART_InitStruct members default value */ + USART_InitStruct->USART_BaudRate = 9600; + USART_InitStruct->USART_WordLength = USART_WordLength_8b; + USART_InitStruct->USART_StopBits = USART_StopBits_1; + USART_InitStruct->USART_Parity = USART_Parity_No ; + USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None; +} + +/** + * @brief Initializes the USARTx peripheral Clock according to the + * specified parameters in the USART_ClockInitStruct . + * @param USARTx: where x can be 1, 2, 3 to select the USART peripheral. + * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef + * structure that contains the configuration information for the specified + * USART peripheral. + * @note The Smart Card mode is not available for UART4 and UART5. + * @retval None + */ +void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct) +{ + uint32_t tmpreg = 0x00; + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock)); + assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL)); + assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA)); + assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit)); + +/*---------------------------- USART CR2 Configuration -----------------------*/ + tmpreg = USARTx->CR2; + /* Clear CLKEN, CPOL, CPHA and LBCL bits */ + tmpreg &= CR2_CLOCK_CLEAR_Mask; + /* Configure the USART Clock, CPOL, CPHA and LastBit ------------*/ + /* Set CLKEN bit according to USART_Clock value */ + /* Set CPOL bit according to USART_CPOL value */ + /* Set CPHA bit according to USART_CPHA value */ + /* Set LBCL bit according to USART_LastBit value */ + tmpreg |= (uint32_t)USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL | + USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit; + /* Write to USART CR2 */ + USARTx->CR2 = (uint16_t)tmpreg; +} + +/** + * @brief Fills each USART_ClockInitStruct member with its default value. + * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef + * structure which will be initialized. + * @retval None + */ +void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct) +{ + /* USART_ClockInitStruct members default value */ + USART_ClockInitStruct->USART_Clock = USART_Clock_Disable; + USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low; + USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge; + USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable; +} + +/** + * @brief Enables or disables the specified USART peripheral. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USARTx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected USART by setting the UE bit in the CR1 register */ + USARTx->CR1 |= CR1_UE_Set; + } + else + { + /* Disable the selected USART by clearing the UE bit in the CR1 register */ + USARTx->CR1 &= CR1_UE_Reset; + } +} + +/** + * @brief Enables or disables the specified USART interrupts. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IT: specifies the USART interrupt sources to be enabled or disabled. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TXE: Tansmit Data Register empty interrupt + * @arg USART_IT_TC: Transmission complete interrupt + * @arg USART_IT_RXNE: Receive Data register not empty interrupt + * @arg USART_IT_IDLE: Idle line detection interrupt + * @arg USART_IT_PE: Parity Error interrupt + * @arg USART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) + * @param NewState: new state of the specified USARTx interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState) +{ + uint32_t usartreg = 0x00, itpos = 0x00, itmask = 0x00; + uint32_t usartxbase = 0x00; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CONFIG_IT(USART_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + usartxbase = (uint32_t)USARTx; + + /* Get the USART register index */ + usartreg = (((uint8_t)USART_IT) >> 0x05); + + /* Get the interrupt position */ + itpos = USART_IT & IT_Mask; + itmask = (((uint32_t)0x01) << itpos); + + if (usartreg == 0x01) /* The IT is in CR1 register */ + { + usartxbase += 0x0C; + } + else if (usartreg == 0x02) /* The IT is in CR2 register */ + { + usartxbase += 0x10; + } + else /* The IT is in CR3 register */ + { + usartxbase += 0x14; + } + if (NewState != DISABLE) + { + *(__IO uint32_t*)usartxbase |= itmask; + } + else + { + *(__IO uint32_t*)usartxbase &= ~itmask; + } +} + +/** + * @brief Enables or disables the USART’s DMA interface. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_DMAReq: specifies the DMA request. + * This parameter can be any combination of the following values: + * @arg USART_DMAReq_Tx: USART DMA transmit request + * @arg USART_DMAReq_Rx: USART DMA receive request + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @note The DMA mode is not available for UART5 except in the STM32 + * High density value line devices(STM32F10X_HD_VL). + * @retval None + */ +void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DMAREQ(USART_DMAReq)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the DMA transfer for selected requests by setting the DMAT and/or + DMAR bits in the USART CR3 register */ + USARTx->CR3 |= USART_DMAReq; + } + else + { + /* Disable the DMA transfer for selected requests by clearing the DMAT and/or + DMAR bits in the USART CR3 register */ + USARTx->CR3 &= (uint16_t)~USART_DMAReq; + } +} + +/** + * @brief Sets the address of the USART node. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_Address: Indicates the address of the USART node. + * @retval None + */ +void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_ADDRESS(USART_Address)); + + /* Clear the USART address */ + USARTx->CR2 &= CR2_Address_Mask; + /* Set the USART address node */ + USARTx->CR2 |= USART_Address; +} + +/** + * @brief Selects the USART WakeUp method. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_WakeUp: specifies the USART wakeup method. + * This parameter can be one of the following values: + * @arg USART_WakeUp_IdleLine: WakeUp by an idle line detection + * @arg USART_WakeUp_AddressMark: WakeUp by an address mark + * @retval None + */ +void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_WAKEUP(USART_WakeUp)); + + USARTx->CR1 &= CR1_WAKE_Mask; + USARTx->CR1 |= USART_WakeUp; +} + +/** + * @brief Determines if the USART is in mute mode or not. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART mute mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the USART mute mode by setting the RWU bit in the CR1 register */ + USARTx->CR1 |= CR1_RWU_Set; + } + else + { + /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */ + USARTx->CR1 &= CR1_RWU_Reset; + } +} + +/** + * @brief Sets the USART LIN Break detection length. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_LINBreakDetectLength: specifies the LIN break detection length. + * This parameter can be one of the following values: + * @arg USART_LINBreakDetectLength_10b: 10-bit break detection + * @arg USART_LINBreakDetectLength_11b: 11-bit break detection + * @retval None + */ +void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength)); + + USARTx->CR2 &= CR2_LBDL_Mask; + USARTx->CR2 |= USART_LINBreakDetectLength; +} + +/** + * @brief Enables or disables the USART’s LIN mode. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART LIN mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ + USARTx->CR2 |= CR2_LINEN_Set; + } + else + { + /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */ + USARTx->CR2 &= CR2_LINEN_Reset; + } +} + +/** + * @brief Transmits single data through the USARTx peripheral. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param Data: the data to transmit. + * @retval None + */ +void USART_SendData(USART_TypeDef* USARTx, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DATA(Data)); + + /* Transmit Data */ + USARTx->DR = (Data & (uint16_t)0x01FF); +} + +/** + * @brief Returns the most recent received data by the USARTx peripheral. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @retval The received data. + */ +uint16_t USART_ReceiveData(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Receive Data */ + return (uint16_t)(USARTx->DR & (uint16_t)0x01FF); +} + +/** + * @brief Transmits break characters. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @retval None + */ +void USART_SendBreak(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Send break characters */ + USARTx->CR1 |= CR1_SBK_Set; +} + +/** + * @brief Sets the specified USART guard time. + * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. + * @param USART_GuardTime: specifies the guard time. + * @note The guard time bits are not available for UART4 and UART5. + * @retval None + */ +void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + + /* Clear the USART Guard time */ + USARTx->GTPR &= GTPR_LSB_Mask; + /* Set the USART guard time */ + USARTx->GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08); +} + +/** + * @brief Sets the system clock prescaler. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_Prescaler: specifies the prescaler clock. + * @note The function is used for IrDA mode with UART4 and UART5. + * @retval None + */ +void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Clear the USART prescaler */ + USARTx->GTPR &= GTPR_MSB_Mask; + /* Set the USART prescaler */ + USARTx->GTPR |= USART_Prescaler; +} + +/** + * @brief Enables or disables the USART’s Smart Card mode. + * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. + * @param NewState: new state of the Smart Card mode. + * This parameter can be: ENABLE or DISABLE. + * @note The Smart Card mode is not available for UART4 and UART5. + * @retval None + */ +void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the SC mode by setting the SCEN bit in the CR3 register */ + USARTx->CR3 |= CR3_SCEN_Set; + } + else + { + /* Disable the SC mode by clearing the SCEN bit in the CR3 register */ + USARTx->CR3 &= CR3_SCEN_Reset; + } +} + +/** + * @brief Enables or disables NACK transmission. + * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. + * @param NewState: new state of the NACK transmission. + * This parameter can be: ENABLE or DISABLE. + * @note The Smart Card mode is not available for UART4 and UART5. + * @retval None + */ +void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the NACK transmission by setting the NACK bit in the CR3 register */ + USARTx->CR3 |= CR3_NACK_Set; + } + else + { + /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */ + USARTx->CR3 &= CR3_NACK_Reset; + } +} + +/** + * @brief Enables or disables the USART’s Half Duplex communication. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART Communication. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ + USARTx->CR3 |= CR3_HDSEL_Set; + } + else + { + /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */ + USARTx->CR3 &= CR3_HDSEL_Reset; + } +} + + +/** + * @brief Enables or disables the USART's 8x oversampling mode. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART one bit sampling methode. + * This parameter can be: ENABLE or DISABLE. + * @note + * This function has to be called before calling USART_Init() + * function in order to have correct baudrate Divider value. + * @retval None + */ +void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the 8x Oversampling mode by setting the OVER8 bit in the CR1 register */ + USARTx->CR1 |= CR1_OVER8_Set; + } + else + { + /* Disable the 8x Oversampling mode by clearing the OVER8 bit in the CR1 register */ + USARTx->CR1 &= CR1_OVER8_Reset; + } +} + +/** + * @brief Enables or disables the USART's one bit sampling methode. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART one bit sampling methode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the one bit method by setting the ONEBITE bit in the CR3 register */ + USARTx->CR3 |= CR3_ONEBITE_Set; + } + else + { + /* Disable tthe one bit method by clearing the ONEBITE bit in the CR3 register */ + USARTx->CR3 &= CR3_ONEBITE_Reset; + } +} + +/** + * @brief Configures the USART’s IrDA interface. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IrDAMode: specifies the IrDA mode. + * This parameter can be one of the following values: + * @arg USART_IrDAMode_LowPower + * @arg USART_IrDAMode_Normal + * @retval None + */ +void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_IRDA_MODE(USART_IrDAMode)); + + USARTx->CR3 &= CR3_IRLP_Mask; + USARTx->CR3 |= USART_IrDAMode; +} + +/** + * @brief Enables or disables the USART’s IrDA interface. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the IrDA mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the IrDA mode by setting the IREN bit in the CR3 register */ + USARTx->CR3 |= CR3_IREN_Set; + } + else + { + /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */ + USARTx->CR3 &= CR3_IREN_Reset; + } +} + +/** + * @brief Checks whether the specified USART flag is set or not. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg USART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5) + * @arg USART_FLAG_LBD: LIN Break detection flag + * @arg USART_FLAG_TXE: Transmit data register empty flag + * @arg USART_FLAG_TC: Transmission Complete flag + * @arg USART_FLAG_RXNE: Receive data register not empty flag + * @arg USART_FLAG_IDLE: Idle Line detection flag + * @arg USART_FLAG_ORE: OverRun Error flag + * @arg USART_FLAG_NE: Noise Error flag + * @arg USART_FLAG_FE: Framing Error flag + * @arg USART_FLAG_PE: Parity Error flag + * @retval The new state of USART_FLAG (SET or RESET). + */ +FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_FLAG(USART_FLAG)); + /* The CTS flag is not available for UART4 and UART5 */ + if (USART_FLAG == USART_FLAG_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + if ((USARTx->SR & USART_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the USARTx's pending flags. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg USART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5). + * @arg USART_FLAG_LBD: LIN Break detection flag. + * @arg USART_FLAG_TC: Transmission Complete flag. + * @arg USART_FLAG_RXNE: Receive data register not empty flag. + * + * @note + * - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun + * error) and IDLE (Idle line detected) flags are cleared by software + * sequence: a read operation to USART_SR register (USART_GetFlagStatus()) + * followed by a read operation to USART_DR register (USART_ReceiveData()). + * - RXNE flag can be also cleared by a read to the USART_DR register + * (USART_ReceiveData()). + * - TC flag can be also cleared by software sequence: a read operation to + * USART_SR register (USART_GetFlagStatus()) followed by a write operation + * to USART_DR register (USART_SendData()). + * - TXE flag is cleared only by a write to the USART_DR register + * (USART_SendData()). + * @retval None + */ +void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CLEAR_FLAG(USART_FLAG)); + /* The CTS flag is not available for UART4 and UART5 */ + if ((USART_FLAG & USART_FLAG_CTS) == USART_FLAG_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + USARTx->SR = (uint16_t)~USART_FLAG; +} + +/** + * @brief Checks whether the specified USART interrupt has occurred or not. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IT: specifies the USART interrupt source to check. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TXE: Tansmit Data Register empty interrupt + * @arg USART_IT_TC: Transmission complete interrupt + * @arg USART_IT_RXNE: Receive Data register not empty interrupt + * @arg USART_IT_IDLE: Idle line detection interrupt + * @arg USART_IT_ORE: OverRun Error interrupt + * @arg USART_IT_NE: Noise Error interrupt + * @arg USART_IT_FE: Framing Error interrupt + * @arg USART_IT_PE: Parity Error interrupt + * @retval The new state of USART_IT (SET or RESET). + */ +ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT) +{ + uint32_t bitpos = 0x00, itmask = 0x00, usartreg = 0x00; + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_GET_IT(USART_IT)); + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + /* Get the USART register index */ + usartreg = (((uint8_t)USART_IT) >> 0x05); + /* Get the interrupt position */ + itmask = USART_IT & IT_Mask; + itmask = (uint32_t)0x01 << itmask; + + if (usartreg == 0x01) /* The IT is in CR1 register */ + { + itmask &= USARTx->CR1; + } + else if (usartreg == 0x02) /* The IT is in CR2 register */ + { + itmask &= USARTx->CR2; + } + else /* The IT is in CR3 register */ + { + itmask &= USARTx->CR3; + } + + bitpos = USART_IT >> 0x08; + bitpos = (uint32_t)0x01 << bitpos; + bitpos &= USARTx->SR; + if ((itmask != (uint16_t)RESET)&&(bitpos != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + return bitstatus; +} + +/** + * @brief Clears the USARTx’s interrupt pending bits. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IT: specifies the interrupt pending bit to clear. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TC: Transmission complete interrupt. + * @arg USART_IT_RXNE: Receive Data register not empty interrupt. + * + * @note + * - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun + * error) and IDLE (Idle line detected) pending bits are cleared by + * software sequence: a read operation to USART_SR register + * (USART_GetITStatus()) followed by a read operation to USART_DR register + * (USART_ReceiveData()). + * - RXNE pending bit can be also cleared by a read to the USART_DR register + * (USART_ReceiveData()). + * - TC pending bit can be also cleared by software sequence: a read + * operation to USART_SR register (USART_GetITStatus()) followed by a write + * operation to USART_DR register (USART_SendData()). + * - TXE pending bit is cleared only by a write to the USART_DR register + * (USART_SendData()). + * @retval None + */ +void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT) +{ + uint16_t bitpos = 0x00, itmask = 0x00; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CLEAR_IT(USART_IT)); + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + bitpos = USART_IT >> 0x08; + itmask = ((uint16_t)0x01 << (uint16_t)bitpos); + USARTx->SR = (uint16_t)~itmask; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c index 753a710cd..7d44b0945 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c @@ -1,223 +1,223 @@ -/** - ****************************************************************************** - * @file stm32f10x_wwdg.c - * @author MCD Application Team - * @version V3.4.0 - * @date 10/15/2010 - * @brief This file provides all the WWDG firmware functions. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2010 STMicroelectronics

- */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x_wwdg.h" -#include "stm32f10x_rcc.h" - -/** @addtogroup STM32F10x_StdPeriph_Driver - * @{ - */ - -/** @defgroup WWDG - * @brief WWDG driver modules - * @{ - */ - -/** @defgroup WWDG_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @defgroup WWDG_Private_Defines - * @{ - */ - -/* ----------- WWDG registers bit address in the alias region ----------- */ -#define WWDG_OFFSET (WWDG_BASE - PERIPH_BASE) - -/* Alias word address of EWI bit */ -#define CFR_OFFSET (WWDG_OFFSET + 0x04) -#define EWI_BitNumber 0x09 -#define CFR_EWI_BB (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4)) - -/* --------------------- WWDG registers bit mask ------------------------ */ - -/* CR register bit mask */ -#define CR_WDGA_Set ((uint32_t)0x00000080) - -/* CFR register bit mask */ -#define CFR_WDGTB_Mask ((uint32_t)0xFFFFFE7F) -#define CFR_W_Mask ((uint32_t)0xFFFFFF80) -#define BIT_Mask ((uint8_t)0x7F) - -/** - * @} - */ - -/** @defgroup WWDG_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @defgroup WWDG_Private_Variables - * @{ - */ - -/** - * @} - */ - -/** @defgroup WWDG_Private_FunctionPrototypes - * @{ - */ - -/** - * @} - */ - -/** @defgroup WWDG_Private_Functions - * @{ - */ - -/** - * @brief Deinitializes the WWDG peripheral registers to their default reset values. - * @param None - * @retval None - */ -void WWDG_DeInit(void) -{ - RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE); - RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE); -} - -/** - * @brief Sets the WWDG Prescaler. - * @param WWDG_Prescaler: specifies the WWDG Prescaler. - * This parameter can be one of the following values: - * @arg WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1 - * @arg WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2 - * @arg WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4 - * @arg WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8 - * @retval None - */ -void WWDG_SetPrescaler(uint32_t WWDG_Prescaler) -{ - uint32_t tmpreg = 0; - /* Check the parameters */ - assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler)); - /* Clear WDGTB[1:0] bits */ - tmpreg = WWDG->CFR & CFR_WDGTB_Mask; - /* Set WDGTB[1:0] bits according to WWDG_Prescaler value */ - tmpreg |= WWDG_Prescaler; - /* Store the new value */ - WWDG->CFR = tmpreg; -} - -/** - * @brief Sets the WWDG window value. - * @param WindowValue: specifies the window value to be compared to the downcounter. - * This parameter value must be lower than 0x80. - * @retval None - */ -void WWDG_SetWindowValue(uint8_t WindowValue) -{ - __IO uint32_t tmpreg = 0; - - /* Check the parameters */ - assert_param(IS_WWDG_WINDOW_VALUE(WindowValue)); - /* Clear W[6:0] bits */ - - tmpreg = WWDG->CFR & CFR_W_Mask; - - /* Set W[6:0] bits according to WindowValue value */ - tmpreg |= WindowValue & (uint32_t) BIT_Mask; - - /* Store the new value */ - WWDG->CFR = tmpreg; -} - -/** - * @brief Enables the WWDG Early Wakeup interrupt(EWI). - * @param None - * @retval None - */ -void WWDG_EnableIT(void) -{ - *(__IO uint32_t *) CFR_EWI_BB = (uint32_t)ENABLE; -} - -/** - * @brief Sets the WWDG counter value. - * @param Counter: specifies the watchdog counter value. - * This parameter must be a number between 0x40 and 0x7F. - * @retval None - */ -void WWDG_SetCounter(uint8_t Counter) -{ - /* Check the parameters */ - assert_param(IS_WWDG_COUNTER(Counter)); - /* Write to T[6:0] bits to configure the counter value, no need to do - a read-modify-write; writing a 0 to WDGA bit does nothing */ - WWDG->CR = Counter & BIT_Mask; -} - -/** - * @brief Enables WWDG and load the counter value. - * @param Counter: specifies the watchdog counter value. - * This parameter must be a number between 0x40 and 0x7F. - * @retval None - */ -void WWDG_Enable(uint8_t Counter) -{ - /* Check the parameters */ - assert_param(IS_WWDG_COUNTER(Counter)); - WWDG->CR = CR_WDGA_Set | Counter; -} - -/** - * @brief Checks whether the Early Wakeup interrupt flag is set or not. - * @param None - * @retval The new state of the Early Wakeup interrupt flag (SET or RESET) - */ -FlagStatus WWDG_GetFlagStatus(void) -{ - return (FlagStatus)(WWDG->SR); -} - -/** - * @brief Clears Early Wakeup interrupt flag. - * @param None - * @retval None - */ -void WWDG_ClearFlag(void) -{ - WWDG->SR = (uint32_t)RESET; -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file stm32f10x_wwdg.c + * @author MCD Application Team + * @version V3.4.0 + * @date 10/15/2010 + * @brief This file provides all the WWDG firmware functions. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2010 STMicroelectronics

+ */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_wwdg.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup WWDG + * @brief WWDG driver modules + * @{ + */ + +/** @defgroup WWDG_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_Defines + * @{ + */ + +/* ----------- WWDG registers bit address in the alias region ----------- */ +#define WWDG_OFFSET (WWDG_BASE - PERIPH_BASE) + +/* Alias word address of EWI bit */ +#define CFR_OFFSET (WWDG_OFFSET + 0x04) +#define EWI_BitNumber 0x09 +#define CFR_EWI_BB (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4)) + +/* --------------------- WWDG registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_WDGA_Set ((uint32_t)0x00000080) + +/* CFR register bit mask */ +#define CFR_WDGTB_Mask ((uint32_t)0xFFFFFE7F) +#define CFR_W_Mask ((uint32_t)0xFFFFFF80) +#define BIT_Mask ((uint8_t)0x7F) + +/** + * @} + */ + +/** @defgroup WWDG_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the WWDG peripheral registers to their default reset values. + * @param None + * @retval None + */ +void WWDG_DeInit(void) +{ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE); +} + +/** + * @brief Sets the WWDG Prescaler. + * @param WWDG_Prescaler: specifies the WWDG Prescaler. + * This parameter can be one of the following values: + * @arg WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1 + * @arg WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2 + * @arg WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4 + * @arg WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8 + * @retval None + */ +void WWDG_SetPrescaler(uint32_t WWDG_Prescaler) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler)); + /* Clear WDGTB[1:0] bits */ + tmpreg = WWDG->CFR & CFR_WDGTB_Mask; + /* Set WDGTB[1:0] bits according to WWDG_Prescaler value */ + tmpreg |= WWDG_Prescaler; + /* Store the new value */ + WWDG->CFR = tmpreg; +} + +/** + * @brief Sets the WWDG window value. + * @param WindowValue: specifies the window value to be compared to the downcounter. + * This parameter value must be lower than 0x80. + * @retval None + */ +void WWDG_SetWindowValue(uint8_t WindowValue) +{ + __IO uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_WWDG_WINDOW_VALUE(WindowValue)); + /* Clear W[6:0] bits */ + + tmpreg = WWDG->CFR & CFR_W_Mask; + + /* Set W[6:0] bits according to WindowValue value */ + tmpreg |= WindowValue & (uint32_t) BIT_Mask; + + /* Store the new value */ + WWDG->CFR = tmpreg; +} + +/** + * @brief Enables the WWDG Early Wakeup interrupt(EWI). + * @param None + * @retval None + */ +void WWDG_EnableIT(void) +{ + *(__IO uint32_t *) CFR_EWI_BB = (uint32_t)ENABLE; +} + +/** + * @brief Sets the WWDG counter value. + * @param Counter: specifies the watchdog counter value. + * This parameter must be a number between 0x40 and 0x7F. + * @retval None + */ +void WWDG_SetCounter(uint8_t Counter) +{ + /* Check the parameters */ + assert_param(IS_WWDG_COUNTER(Counter)); + /* Write to T[6:0] bits to configure the counter value, no need to do + a read-modify-write; writing a 0 to WDGA bit does nothing */ + WWDG->CR = Counter & BIT_Mask; +} + +/** + * @brief Enables WWDG and load the counter value. + * @param Counter: specifies the watchdog counter value. + * This parameter must be a number between 0x40 and 0x7F. + * @retval None + */ +void WWDG_Enable(uint8_t Counter) +{ + /* Check the parameters */ + assert_param(IS_WWDG_COUNTER(Counter)); + WWDG->CR = CR_WDGA_Set | Counter; +} + +/** + * @brief Checks whether the Early Wakeup interrupt flag is set or not. + * @param None + * @retval The new state of the Early Wakeup interrupt flag (SET or RESET) + */ +FlagStatus WWDG_GetFlagStatus(void) +{ + return (FlagStatus)(WWDG->SR); +} + +/** + * @brief Clears Early Wakeup interrupt flag. + * @param None + * @retval None + */ +void WWDG_ClearFlag(void) +{ + WWDG->SR = (uint32_t)RESET; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_core.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_core.h index 7e606e44b..ec814e411 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_core.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_core.h @@ -1,247 +1,247 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_core.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Standard protocol processing functions prototypes -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_CORE_H -#define __USB_CORE_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -typedef enum _CONTROL_STATE -{ - WAIT_SETUP, /* 0 */ - SETTING_UP, /* 1 */ - IN_DATA, /* 2 */ - OUT_DATA, /* 3 */ - LAST_IN_DATA, /* 4 */ - LAST_OUT_DATA, /* 5 */ - WAIT_STATUS_IN, /* 7 */ - WAIT_STATUS_OUT, /* 8 */ - STALLED, /* 9 */ - PAUSE /* 10 */ -} CONTROL_STATE; /* The state machine states of a control pipe */ - -typedef struct OneDescriptor -{ - const uint8_t *Descriptor; - uint16_t Descriptor_Size; -} -ONE_DESCRIPTOR, *PONE_DESCRIPTOR; -/* All the request process routines return a value of this type - If the return value is not SUCCESS or NOT_READY, - the software will STALL the correspond endpoint */ -typedef enum _RESULT -{ - USB_SUCCESS = 0, /* Process sucessfully */ - USB_ERROR, - USB_UNSUPPORT, - USB_NOT_READY /* The process has not been finished, endpoint will be - NAK to further rquest */ -} RESULT; - - -/*-*-*-*-*-*-*-*-*-*-* Definitions for endpoint level -*-*-*-*-*-*-*-*-*-*-*-*/ -typedef struct _ENDPOINT_INFO -{ - /* When send data out of the device, - CopyData() is used to get data buffer 'Length' bytes data - if Length is 0, - CopyData() returns the total length of the data - if the request is not supported, returns 0 - (NEW Feature ) - if CopyData() returns -1, the calling routine should not proceed - further and will resume the SETUP process by the class device - if Length is not 0, - CopyData() returns a pointer to indicate the data location - Usb_wLength is the data remain to be sent, - Usb_wOffset is the Offset of original data - When receive data from the host, - CopyData() is used to get user data buffer which is capable - of Length bytes data to copy data from the endpoint buffer. - if Length is 0, - CopyData() returns the available data length, - if Length is not 0, - CopyData() returns user buffer address - Usb_rLength is the data remain to be received, - Usb_rPointer is the Offset of data buffer - */ - uint16_t Usb_wLength; - uint16_t Usb_wOffset; - uint16_t PacketSize; - const uint8_t *(*CopyDataIn)(uint16_t Length); - uint8_t *(*CopyDataOut)(uint16_t Length); -}ENDPOINT_INFO; - -/*-*-*-*-*-*-*-*-*-*-*-* Definitions for device level -*-*-*-*-*-*-*-*-*-*-*-*/ - -typedef struct _DEVICE -{ - uint8_t Total_Endpoint; /* Number of endpoints that are used */ - uint8_t Total_Configuration;/* Number of configuration available */ -} -DEVICE; - -typedef union -{ - uint16_t w; - struct BW - { - uint8_t bb1; - uint8_t bb0; - } - bw; -} uint16_t_uint8_t; - -typedef struct _DEVICE_INFO -{ - uint8_t USBbmRequestType; /* bmRequestType */ - uint8_t USBbRequest; /* bRequest */ - uint16_t_uint8_t USBwValues; /* wValue */ - uint16_t_uint8_t USBwIndexs; /* wIndex */ - uint16_t_uint8_t USBwLengths; /* wLength */ - - uint8_t ControlState; /* of type CONTROL_STATE */ - uint8_t Current_Feature; - uint8_t Current_Configuration; /* Selected configuration */ - uint8_t Current_Interface; /* Selected interface of current configuration */ - uint8_t Current_AlternateSetting;/* Selected Alternate Setting of current - interface*/ - - ENDPOINT_INFO Ctrl_Info; -}DEVICE_INFO; - -typedef struct _DEVICE_PROP -{ - void (*Init)(void); /* Initialize the device */ - void (*Reset)(void); /* Reset routine of this device */ - - /* Device dependent process after the status stage */ - void (*Process_Status_IN)(void); - void (*Process_Status_OUT)(void); - - /* Procedure of process on setup stage of a class specified request with data stage */ - /* All class specified requests with data stage are processed in Class_Data_Setup - Class_Data_Setup() - responses to check all special requests and fills ENDPOINT_INFO - according to the request - If IN tokens are expected, then wLength & wOffset will be filled - with the total transferring bytes and the starting position - If OUT tokens are expected, then rLength & rOffset will be filled - with the total expected bytes and the starting position in the buffer - - If the request is valid, Class_Data_Setup returns SUCCESS, else UNSUPPORT - - CAUTION: - Since GET_CONFIGURATION & GET_INTERFACE are highly related to - the individual classes, they will be checked and processed here. - */ - RESULT (*Class_Data_Setup)(uint8_t RequestNo); - - /* Procedure of process on setup stage of a class specified request without data stage */ - /* All class specified requests without data stage are processed in Class_NoData_Setup - Class_NoData_Setup - responses to check all special requests and perform the request - - CAUTION: - Since SET_CONFIGURATION & SET_INTERFACE are highly related to - the individual classes, they will be checked and processed here. - */ - RESULT (*Class_NoData_Setup)(uint8_t RequestNo); - - /*Class_Get_Interface_Setting - This function is used by the file usb_core.c to test if the selected Interface - and Alternate Setting (uint8_t Interface, uint8_t AlternateSetting) are supported by - the application. - This function is writing by user. It should return "SUCCESS" if the Interface - and Alternate Setting are supported by the application or "UNSUPPORT" if they - are not supported. */ - - RESULT (*Class_Get_Interface_Setting)(uint8_t Interface, uint8_t AlternateSetting); - - const uint8_t* (*GetDeviceDescriptor)(uint16_t Length); - const uint8_t* (*GetConfigDescriptor)(uint16_t Length); - const uint8_t* (*GetStringDescriptor)(uint16_t Length); - - /* This field is not used in current library version. It is kept only for - compatibility with previous versions */ - void* RxEP_buffer; - - uint8_t MaxPacketSize; - -}DEVICE_PROP; - -typedef struct _USER_STANDARD_REQUESTS -{ - void (*User_GetConfiguration)(void); /* Get Configuration */ - void (*User_SetConfiguration)(void); /* Set Configuration */ - void (*User_GetInterface)(void); /* Get Interface */ - void (*User_SetInterface)(void); /* Set Interface */ - void (*User_GetStatus)(void); /* Get Status */ - void (*User_ClearFeature)(void); /* Clear Feature */ - void (*User_SetEndPointFeature)(void); /* Set Endpoint Feature */ - void (*User_SetDeviceFeature)(void); /* Set Device Feature */ - void (*User_SetDeviceAddress)(void); /* Set Device Address */ -} -USER_STANDARD_REQUESTS; - -/* Exported constants --------------------------------------------------------*/ -#define Type_Recipient (pInformation->USBbmRequestType & (REQUEST_TYPE | RECIPIENT)) - -#define Usb_rLength Usb_wLength -#define Usb_rOffset Usb_wOffset - -#define USBwValue USBwValues.w -#define USBwValue0 USBwValues.bw.bb0 -#define USBwValue1 USBwValues.bw.bb1 -#define USBwIndex USBwIndexs.w -#define USBwIndex0 USBwIndexs.bw.bb0 -#define USBwIndex1 USBwIndexs.bw.bb1 -#define USBwLength USBwLengths.w -#define USBwLength0 USBwLengths.bw.bb0 -#define USBwLength1 USBwLengths.bw.bb1 - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -uint8_t Setup0_Process(void); -uint8_t Post0_Process(void); -uint8_t Out0_Process(void); -uint8_t In0_Process(void); - -RESULT Standard_SetEndPointFeature(void); -RESULT Standard_SetDeviceFeature(void); - -const uint8_t *Standard_GetConfiguration(uint16_t Length); -RESULT Standard_SetConfiguration(void); -const uint8_t *Standard_GetInterface(uint16_t Length); -RESULT Standard_SetInterface(void); -const uint8_t *Standard_GetDescriptorData(uint16_t Length, ONE_DESCRIPTOR *pDesc); - -const uint8_t *Standard_GetStatus(uint16_t Length); -RESULT Standard_ClearFeature(void); -void SetDeviceAddress(uint8_t); -void NOP_Process(void); - -extern DEVICE_PROP Device_Property; -extern USER_STANDARD_REQUESTS User_Standard_Requests; -extern DEVICE Device_Table; -extern DEVICE_INFO Device_Info; - -/* cells saving status during interrupt servicing */ -extern __IO uint16_t SaveRState; -extern __IO uint16_t SaveTState; - -#endif /* __USB_CORE_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_core.h +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Standard protocol processing functions prototypes +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_CORE_H +#define __USB_CORE_H + +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef enum _CONTROL_STATE +{ + WAIT_SETUP, /* 0 */ + SETTING_UP, /* 1 */ + IN_DATA, /* 2 */ + OUT_DATA, /* 3 */ + LAST_IN_DATA, /* 4 */ + LAST_OUT_DATA, /* 5 */ + WAIT_STATUS_IN, /* 7 */ + WAIT_STATUS_OUT, /* 8 */ + STALLED, /* 9 */ + PAUSE /* 10 */ +} CONTROL_STATE; /* The state machine states of a control pipe */ + +typedef struct OneDescriptor +{ + const uint8_t *Descriptor; + uint16_t Descriptor_Size; +} +ONE_DESCRIPTOR, *PONE_DESCRIPTOR; +/* All the request process routines return a value of this type + If the return value is not SUCCESS or NOT_READY, + the software will STALL the correspond endpoint */ +typedef enum _RESULT +{ + USB_SUCCESS = 0, /* Process sucessfully */ + USB_ERROR, + USB_UNSUPPORT, + USB_NOT_READY /* The process has not been finished, endpoint will be + NAK to further rquest */ +} RESULT; + + +/*-*-*-*-*-*-*-*-*-*-* Definitions for endpoint level -*-*-*-*-*-*-*-*-*-*-*-*/ +typedef struct _ENDPOINT_INFO +{ + /* When send data out of the device, + CopyData() is used to get data buffer 'Length' bytes data + if Length is 0, + CopyData() returns the total length of the data + if the request is not supported, returns 0 + (NEW Feature ) + if CopyData() returns -1, the calling routine should not proceed + further and will resume the SETUP process by the class device + if Length is not 0, + CopyData() returns a pointer to indicate the data location + Usb_wLength is the data remain to be sent, + Usb_wOffset is the Offset of original data + When receive data from the host, + CopyData() is used to get user data buffer which is capable + of Length bytes data to copy data from the endpoint buffer. + if Length is 0, + CopyData() returns the available data length, + if Length is not 0, + CopyData() returns user buffer address + Usb_rLength is the data remain to be received, + Usb_rPointer is the Offset of data buffer + */ + uint16_t Usb_wLength; + uint16_t Usb_wOffset; + uint16_t PacketSize; + const uint8_t *(*CopyDataIn)(uint16_t Length); + uint8_t *(*CopyDataOut)(uint16_t Length); +}ENDPOINT_INFO; + +/*-*-*-*-*-*-*-*-*-*-*-* Definitions for device level -*-*-*-*-*-*-*-*-*-*-*-*/ + +typedef struct _DEVICE +{ + uint8_t Total_Endpoint; /* Number of endpoints that are used */ + uint8_t Total_Configuration;/* Number of configuration available */ +} +DEVICE; + +typedef union +{ + uint16_t w; + struct BW + { + uint8_t bb1; + uint8_t bb0; + } + bw; +} uint16_t_uint8_t; + +typedef struct _DEVICE_INFO +{ + uint8_t USBbmRequestType; /* bmRequestType */ + uint8_t USBbRequest; /* bRequest */ + uint16_t_uint8_t USBwValues; /* wValue */ + uint16_t_uint8_t USBwIndexs; /* wIndex */ + uint16_t_uint8_t USBwLengths; /* wLength */ + + uint8_t ControlState; /* of type CONTROL_STATE */ + uint8_t Current_Feature; + uint8_t Current_Configuration; /* Selected configuration */ + uint8_t Current_Interface; /* Selected interface of current configuration */ + uint8_t Current_AlternateSetting;/* Selected Alternate Setting of current + interface*/ + + ENDPOINT_INFO Ctrl_Info; +}DEVICE_INFO; + +typedef struct _DEVICE_PROP +{ + void (*Init)(void); /* Initialize the device */ + void (*Reset)(void); /* Reset routine of this device */ + + /* Device dependent process after the status stage */ + void (*Process_Status_IN)(void); + void (*Process_Status_OUT)(void); + + /* Procedure of process on setup stage of a class specified request with data stage */ + /* All class specified requests with data stage are processed in Class_Data_Setup + Class_Data_Setup() + responses to check all special requests and fills ENDPOINT_INFO + according to the request + If IN tokens are expected, then wLength & wOffset will be filled + with the total transferring bytes and the starting position + If OUT tokens are expected, then rLength & rOffset will be filled + with the total expected bytes and the starting position in the buffer + + If the request is valid, Class_Data_Setup returns SUCCESS, else UNSUPPORT + + CAUTION: + Since GET_CONFIGURATION & GET_INTERFACE are highly related to + the individual classes, they will be checked and processed here. + */ + RESULT (*Class_Data_Setup)(uint8_t RequestNo); + + /* Procedure of process on setup stage of a class specified request without data stage */ + /* All class specified requests without data stage are processed in Class_NoData_Setup + Class_NoData_Setup + responses to check all special requests and perform the request + + CAUTION: + Since SET_CONFIGURATION & SET_INTERFACE are highly related to + the individual classes, they will be checked and processed here. + */ + RESULT (*Class_NoData_Setup)(uint8_t RequestNo); + + /*Class_Get_Interface_Setting + This function is used by the file usb_core.c to test if the selected Interface + and Alternate Setting (uint8_t Interface, uint8_t AlternateSetting) are supported by + the application. + This function is writing by user. It should return "SUCCESS" if the Interface + and Alternate Setting are supported by the application or "UNSUPPORT" if they + are not supported. */ + + RESULT (*Class_Get_Interface_Setting)(uint8_t Interface, uint8_t AlternateSetting); + + const uint8_t* (*GetDeviceDescriptor)(uint16_t Length); + const uint8_t* (*GetConfigDescriptor)(uint16_t Length); + const uint8_t* (*GetStringDescriptor)(uint16_t Length); + + /* This field is not used in current library version. It is kept only for + compatibility with previous versions */ + void* RxEP_buffer; + + uint8_t MaxPacketSize; + +}DEVICE_PROP; + +typedef struct _USER_STANDARD_REQUESTS +{ + void (*User_GetConfiguration)(void); /* Get Configuration */ + void (*User_SetConfiguration)(void); /* Set Configuration */ + void (*User_GetInterface)(void); /* Get Interface */ + void (*User_SetInterface)(void); /* Set Interface */ + void (*User_GetStatus)(void); /* Get Status */ + void (*User_ClearFeature)(void); /* Clear Feature */ + void (*User_SetEndPointFeature)(void); /* Set Endpoint Feature */ + void (*User_SetDeviceFeature)(void); /* Set Device Feature */ + void (*User_SetDeviceAddress)(void); /* Set Device Address */ +} +USER_STANDARD_REQUESTS; + +/* Exported constants --------------------------------------------------------*/ +#define Type_Recipient (pInformation->USBbmRequestType & (REQUEST_TYPE | RECIPIENT)) + +#define Usb_rLength Usb_wLength +#define Usb_rOffset Usb_wOffset + +#define USBwValue USBwValues.w +#define USBwValue0 USBwValues.bw.bb0 +#define USBwValue1 USBwValues.bw.bb1 +#define USBwIndex USBwIndexs.w +#define USBwIndex0 USBwIndexs.bw.bb0 +#define USBwIndex1 USBwIndexs.bw.bb1 +#define USBwLength USBwLengths.w +#define USBwLength0 USBwLengths.bw.bb0 +#define USBwLength1 USBwLengths.bw.bb1 + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +uint8_t Setup0_Process(void); +uint8_t Post0_Process(void); +uint8_t Out0_Process(void); +uint8_t In0_Process(void); + +RESULT Standard_SetEndPointFeature(void); +RESULT Standard_SetDeviceFeature(void); + +const uint8_t *Standard_GetConfiguration(uint16_t Length); +RESULT Standard_SetConfiguration(void); +const uint8_t *Standard_GetInterface(uint16_t Length); +RESULT Standard_SetInterface(void); +const uint8_t *Standard_GetDescriptorData(uint16_t Length, ONE_DESCRIPTOR *pDesc); + +const uint8_t *Standard_GetStatus(uint16_t Length); +RESULT Standard_ClearFeature(void); +void SetDeviceAddress(uint8_t); +void NOP_Process(void); + +extern DEVICE_PROP Device_Property; +extern USER_STANDARD_REQUESTS User_Standard_Requests; +extern DEVICE Device_Table; +extern DEVICE_INFO Device_Info; + +/* cells saving status during interrupt servicing */ +extern __IO uint16_t SaveRState; +extern __IO uint16_t SaveTState; + +#endif /* __USB_CORE_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_def.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_def.h index dfaf22905..abc1eff18 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_def.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_def.h @@ -1,80 +1,80 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_def.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Definitions related to USB Core -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_DEF_H -#define __USB_DEF_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -typedef enum _RECIPIENT_TYPE -{ - DEVICE_RECIPIENT, /* Recipient device */ - INTERFACE_RECIPIENT, /* Recipient interface */ - ENDPOINT_RECIPIENT, /* Recipient endpoint */ - OTHER_RECIPIENT -} RECIPIENT_TYPE; - - -typedef enum _STANDARD_REQUESTS -{ - GET_STATUS = 0, - CLEAR_FEATURE, - RESERVED1, - SET_FEATURE, - RESERVED2, - SET_ADDRESS, - GET_DESCRIPTOR, - SET_DESCRIPTOR, - GET_CONFIGURATION, - SET_CONFIGURATION, - GET_INTERFACE, - SET_INTERFACE, - TOTAL_sREQUEST, /* Total number of Standard request */ - SYNCH_FRAME = 12 -} STANDARD_REQUESTS; - -/* Definition of "USBwValue" */ -typedef enum _DESCRIPTOR_TYPE -{ - DEVICE_DESCRIPTOR = 1, - CONFIG_DESCRIPTOR, - STRING_DESCRIPTOR, - INTERFACE_DESCRIPTOR, - ENDPOINT_DESCRIPTOR -} DESCRIPTOR_TYPE; - -/* Feature selector of a SET_FEATURE or CLEAR_FEATURE */ -typedef enum _FEATURE_SELECTOR -{ - ENDPOINT_STALL, - DEVICE_REMOTE_WAKEUP -} FEATURE_SELECTOR; - -/* Exported constants --------------------------------------------------------*/ -/* Definition of "USBbmRequestType" */ -#define REQUEST_TYPE 0x60 /* Mask to get request type */ -#define STANDARD_REQUEST 0x00 /* Standard request */ -#define CLASS_REQUEST 0x20 /* Class request */ -#define VENDOR_REQUEST 0x40 /* Vendor request */ - -#define RECIPIENT 0x1F /* Mask to get recipient */ - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ - -#endif /* __USB_DEF_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_def.h +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Definitions related to USB Core +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_DEF_H +#define __USB_DEF_H + +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef enum _RECIPIENT_TYPE +{ + DEVICE_RECIPIENT, /* Recipient device */ + INTERFACE_RECIPIENT, /* Recipient interface */ + ENDPOINT_RECIPIENT, /* Recipient endpoint */ + OTHER_RECIPIENT +} RECIPIENT_TYPE; + + +typedef enum _STANDARD_REQUESTS +{ + GET_STATUS = 0, + CLEAR_FEATURE, + RESERVED1, + SET_FEATURE, + RESERVED2, + SET_ADDRESS, + GET_DESCRIPTOR, + SET_DESCRIPTOR, + GET_CONFIGURATION, + SET_CONFIGURATION, + GET_INTERFACE, + SET_INTERFACE, + TOTAL_sREQUEST, /* Total number of Standard request */ + SYNCH_FRAME = 12 +} STANDARD_REQUESTS; + +/* Definition of "USBwValue" */ +typedef enum _DESCRIPTOR_TYPE +{ + DEVICE_DESCRIPTOR = 1, + CONFIG_DESCRIPTOR, + STRING_DESCRIPTOR, + INTERFACE_DESCRIPTOR, + ENDPOINT_DESCRIPTOR +} DESCRIPTOR_TYPE; + +/* Feature selector of a SET_FEATURE or CLEAR_FEATURE */ +typedef enum _FEATURE_SELECTOR +{ + ENDPOINT_STALL, + DEVICE_REMOTE_WAKEUP +} FEATURE_SELECTOR; + +/* Exported constants --------------------------------------------------------*/ +/* Definition of "USBbmRequestType" */ +#define REQUEST_TYPE 0x60 /* Mask to get request type */ +#define STANDARD_REQUEST 0x00 /* Standard request */ +#define CLASS_REQUEST 0x20 /* Class request */ +#define VENDOR_REQUEST 0x40 /* Vendor request */ + +#define RECIPIENT 0x1F /* Mask to get recipient */ + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +#endif /* __USB_DEF_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_init.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_init.h index 9e27a6e42..1a4297e53 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_init.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_init.h @@ -1,49 +1,49 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_init.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Initialization routines & global variables -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_INIT_H -#define __USB_INIT_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -void USB_Init(void); - -/* External variables --------------------------------------------------------*/ -/* The number of current endpoint, it will be used to specify an endpoint */ -extern uint8_t EPindex; -/* The number of current device, it is an index to the Device_Table */ -/*extern uint8_t Device_no; */ -/* Points to the DEVICE_INFO structure of current device */ -/* The purpose of this register is to speed up the execution */ -extern DEVICE_INFO* pInformation; -/* Points to the DEVICE_PROP structure of current device */ -/* The purpose of this register is to speed up the execution */ -extern DEVICE_PROP* pProperty; -/* Temporary save the state of Rx & Tx status. */ -/* Whenever the Rx or Tx state is changed, its value is saved */ -/* in this variable first and will be set to the EPRB or EPRA */ -/* at the end of interrupt process */ -extern USER_STANDARD_REQUESTS *pUser_Standard_Requests; - -extern uint16_t SaveState ; -extern uint16_t wInterrupt_Mask; - -#endif /* __USB_INIT_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_init.h +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Initialization routines & global variables +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_INIT_H +#define __USB_INIT_H + +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +void USB_Init(void); + +/* External variables --------------------------------------------------------*/ +/* The number of current endpoint, it will be used to specify an endpoint */ +extern uint8_t EPindex; +/* The number of current device, it is an index to the Device_Table */ +/*extern uint8_t Device_no; */ +/* Points to the DEVICE_INFO structure of current device */ +/* The purpose of this register is to speed up the execution */ +extern DEVICE_INFO* pInformation; +/* Points to the DEVICE_PROP structure of current device */ +/* The purpose of this register is to speed up the execution */ +extern DEVICE_PROP* pProperty; +/* Temporary save the state of Rx & Tx status. */ +/* Whenever the Rx or Tx state is changed, its value is saved */ +/* in this variable first and will be set to the EPRB or EPRA */ +/* at the end of interrupt process */ +extern USER_STANDARD_REQUESTS *pUser_Standard_Requests; + +extern uint16_t SaveState ; +extern uint16_t wInterrupt_Mask; + +#endif /* __USB_INIT_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_int.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_int.h index 9934b1169..7c0ce7732 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_int.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_int.h @@ -1,33 +1,33 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_int.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Endpoint CTR (Low and High) interrupt's service routines -* prototypes -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_INT_H -#define __USB_INT_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -void CTR_LP(void); -void CTR_HP(void); - -/* External variables --------------------------------------------------------*/ - -#endif /* __USB_INT_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_int.h +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Endpoint CTR (Low and High) interrupt's service routines +* prototypes +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_INT_H +#define __USB_INT_H + +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +void CTR_LP(void); +void CTR_HP(void); + +/* External variables --------------------------------------------------------*/ + +#endif /* __USB_INT_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_lib.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_lib.h index 23d7294da..27fa8d06e 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_lib.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_lib.h @@ -1,50 +1,50 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_lib.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : USB library include files -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_LIB_H -#define __USB_LIB_H - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" -#include "usb_type.h" -#include "usb_regs.h" -#include "usb_def.h" -#include "usb_core.h" -#include "usb_init.h" -#ifndef STM32F10X_CL - #include "usb_mem.h" - #include "usb_int.h" -#endif /* STM32F10X_CL */ - -#include "usb_sil.h" - -#ifdef STM32F10X_CL - #include "otgd_fs_cal.h" - #include "otgd_fs_pcd.h" - #include "otgd_fs_dev.h" - #include "otgd_fs_int.h" -#endif /* STM32F10X_CL */ - - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -/* External variables --------------------------------------------------------*/ - -#endif /* __USB_LIB_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_lib.h +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : USB library include files +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_LIB_H +#define __USB_LIB_H + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" +#include "usb_type.h" +#include "usb_regs.h" +#include "usb_def.h" +#include "usb_core.h" +#include "usb_init.h" +#ifndef STM32F10X_CL + #include "usb_mem.h" + #include "usb_int.h" +#endif /* STM32F10X_CL */ + +#include "usb_sil.h" + +#ifdef STM32F10X_CL + #include "otgd_fs_cal.h" + #include "otgd_fs_pcd.h" + #include "otgd_fs_dev.h" + #include "otgd_fs_int.h" +#endif /* STM32F10X_CL */ + + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +/* External variables --------------------------------------------------------*/ + +#endif /* __USB_LIB_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_mem.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_mem.h index f7f0ace12..0c8b21863 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_mem.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_mem.h @@ -1,32 +1,32 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_mem.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Utility prototypes functions for memory/PMA transfers -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_MEM_H -#define __USB_MEM_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -void UserToPMABufferCopy(const uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes); -void PMAToUserBufferCopy(uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes); - -/* External variables --------------------------------------------------------*/ - -#endif /*__USB_MEM_H*/ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_mem.h +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Utility prototypes functions for memory/PMA transfers +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_MEM_H +#define __USB_MEM_H + +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +void UserToPMABufferCopy(const uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes); +void PMAToUserBufferCopy(uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes); + +/* External variables --------------------------------------------------------*/ + +#endif /*__USB_MEM_H*/ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_regs.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_regs.h index d11395205..0eba0e9a4 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_regs.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_regs.h @@ -1,671 +1,671 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_regs.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Interface prototype functions to USB cell registers -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_REGS_H -#define __USB_REGS_H - -#ifndef STM32F10X_CL - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -typedef enum _EP_DBUF_DIR -{ - /* double buffered endpoint direction */ - EP_DBUF_ERR, - EP_DBUF_OUT, - EP_DBUF_IN -}EP_DBUF_DIR; - -/* endpoint buffer number */ -enum EP_BUF_NUM -{ - EP_NOBUF, - EP_BUF0, - EP_BUF1 -}; - -/* Exported constants --------------------------------------------------------*/ -#define RegBase (0x40005C00L) /* USB_IP Peripheral Registers base address */ -#define PMAAddr (0x40006000L) /* USB_IP Packet Memory Area base address */ - -/******************************************************************************/ -/* General registers */ -/******************************************************************************/ - -/* Control register */ -#define CNTR ((__IO unsigned *)(RegBase + 0x40)) -/* Interrupt status register */ -#define ISTR ((__IO unsigned *)(RegBase + 0x44)) -/* Frame number register */ -#define FNR ((__IO unsigned *)(RegBase + 0x48)) -/* Device address register */ -#define DADDR ((__IO unsigned *)(RegBase + 0x4C)) -/* Buffer Table address register */ -#define BTABLE ((__IO unsigned *)(RegBase + 0x50)) -/******************************************************************************/ -/* Endpoint registers */ -/******************************************************************************/ -#define EP0REG ((__IO unsigned *)(RegBase)) /* endpoint 0 register address */ - -/* Endpoint Addresses (w/direction) */ -#define EP0_OUT ((uint8_t)0x00) -#define EP0_IN ((uint8_t)0x80) -#define EP1_OUT ((uint8_t)0x01) -#define EP1_IN ((uint8_t)0x81) -#define EP2_OUT ((uint8_t)0x02) -#define EP2_IN ((uint8_t)0x82) -#define EP3_OUT ((uint8_t)0x03) -#define EP3_IN ((uint8_t)0x83) -#define EP4_OUT ((uint8_t)0x04) -#define EP4_IN ((uint8_t)0x84) -#define EP5_OUT ((uint8_t)0x05) -#define EP5_IN ((uint8_t)0x85) -#define EP6_OUT ((uint8_t)0x06) -#define EP6_IN ((uint8_t)0x86) -#define EP7_OUT ((uint8_t)0x07) -#define EP7_IN ((uint8_t)0x87) - -/* endpoints enumeration */ -#define ENDP0 ((uint8_t)0) -#define ENDP1 ((uint8_t)1) -#define ENDP2 ((uint8_t)2) -#define ENDP3 ((uint8_t)3) -#define ENDP4 ((uint8_t)4) -#define ENDP5 ((uint8_t)5) -#define ENDP6 ((uint8_t)6) -#define ENDP7 ((uint8_t)7) - -/******************************************************************************/ -/* ISTR interrupt events */ -/******************************************************************************/ -#define ISTR_CTR (0x8000) /* Correct TRansfer (clear-only bit) */ -#define ISTR_DOVR (0x4000) /* DMA OVeR/underrun (clear-only bit) */ -#define ISTR_ERR (0x2000) /* ERRor (clear-only bit) */ -#define ISTR_WKUP (0x1000) /* WaKe UP (clear-only bit) */ -#define ISTR_SUSP (0x0800) /* SUSPend (clear-only bit) */ -#define ISTR_RESET (0x0400) /* RESET (clear-only bit) */ -#define ISTR_SOF (0x0200) /* Start Of Frame (clear-only bit) */ -#define ISTR_ESOF (0x0100) /* Expected Start Of Frame (clear-only bit) */ - - -#define ISTR_DIR (0x0010) /* DIRection of transaction (read-only bit) */ -#define ISTR_EP_ID (0x000F) /* EndPoint IDentifier (read-only bit) */ - -#define CLR_CTR (~ISTR_CTR) /* clear Correct TRansfer bit */ -#define CLR_DOVR (~ISTR_DOVR) /* clear DMA OVeR/underrun bit*/ -#define CLR_ERR (~ISTR_ERR) /* clear ERRor bit */ -#define CLR_WKUP (~ISTR_WKUP) /* clear WaKe UP bit */ -#define CLR_SUSP (~ISTR_SUSP) /* clear SUSPend bit */ -#define CLR_RESET (~ISTR_RESET) /* clear RESET bit */ -#define CLR_SOF (~ISTR_SOF) /* clear Start Of Frame bit */ -#define CLR_ESOF (~ISTR_ESOF) /* clear Expected Start Of Frame bit */ - -/******************************************************************************/ -/* CNTR control register bits definitions */ -/******************************************************************************/ -#define CNTR_CTRM (0x8000) /* Correct TRansfer Mask */ -#define CNTR_DOVRM (0x4000) /* DMA OVeR/underrun Mask */ -#define CNTR_ERRM (0x2000) /* ERRor Mask */ -#define CNTR_WKUPM (0x1000) /* WaKe UP Mask */ -#define CNTR_SUSPM (0x0800) /* SUSPend Mask */ -#define CNTR_RESETM (0x0400) /* RESET Mask */ -#define CNTR_SOFM (0x0200) /* Start Of Frame Mask */ -#define CNTR_ESOFM (0x0100) /* Expected Start Of Frame Mask */ - - -#define CNTR_RESUME (0x0010) /* RESUME request */ -#define CNTR_FSUSP (0x0008) /* Force SUSPend */ -#define CNTR_LPMODE (0x0004) /* Low-power MODE */ -#define CNTR_PDWN (0x0002) /* Power DoWN */ -#define CNTR_FRES (0x0001) /* Force USB RESet */ - -/******************************************************************************/ -/* FNR Frame Number Register bit definitions */ -/******************************************************************************/ -#define FNR_RXDP (0x8000) /* status of D+ data line */ -#define FNR_RXDM (0x4000) /* status of D- data line */ -#define FNR_LCK (0x2000) /* LoCKed */ -#define FNR_LSOF (0x1800) /* Lost SOF */ -#define FNR_FN (0x07FF) /* Frame Number */ -/******************************************************************************/ -/* DADDR Device ADDRess bit definitions */ -/******************************************************************************/ -#define DADDR_EF (0x80) -#define DADDR_ADD (0x7F) -/******************************************************************************/ -/* Endpoint register */ -/******************************************************************************/ -/* bit positions */ -#define EP_CTR_RX (0x8000) /* EndPoint Correct TRansfer RX */ -#define EP_DTOG_RX (0x4000) /* EndPoint Data TOGGLE RX */ -#define EPRX_STAT (0x3000) /* EndPoint RX STATus bit field */ -#define EP_SETUP (0x0800) /* EndPoint SETUP */ -#define EP_T_FIELD (0x0600) /* EndPoint TYPE */ -#define EP_KIND (0x0100) /* EndPoint KIND */ -#define EP_CTR_TX (0x0080) /* EndPoint Correct TRansfer TX */ -#define EP_DTOG_TX (0x0040) /* EndPoint Data TOGGLE TX */ -#define EPTX_STAT (0x0030) /* EndPoint TX STATus bit field */ -#define EPADDR_FIELD (0x000F) /* EndPoint ADDRess FIELD */ - -/* EndPoint REGister MASK (no toggle fields) */ -#define EPREG_MASK (EP_CTR_RX|EP_SETUP|EP_T_FIELD|EP_KIND|EP_CTR_TX|EPADDR_FIELD) - -/* EP_TYPE[1:0] EndPoint TYPE */ -#define EP_TYPE_MASK (0x0600) /* EndPoint TYPE Mask */ -#define EP_BULK (0x0000) /* EndPoint BULK */ -#define EP_CONTROL (0x0200) /* EndPoint CONTROL */ -#define EP_ISOCHRONOUS (0x0400) /* EndPoint ISOCHRONOUS */ -#define EP_INTERRUPT (0x0600) /* EndPoint INTERRUPT */ -#define EP_T_MASK (~EP_T_FIELD & EPREG_MASK) - - -/* EP_KIND EndPoint KIND */ -#define EPKIND_MASK (~EP_KIND & EPREG_MASK) - -/* STAT_TX[1:0] STATus for TX transfer */ -#define EP_TX_DIS (0x0000) /* EndPoint TX DISabled */ -#define EP_TX_STALL (0x0010) /* EndPoint TX STALLed */ -#define EP_TX_NAK (0x0020) /* EndPoint TX NAKed */ -#define EP_TX_VALID (0x0030) /* EndPoint TX VALID */ -#define EPTX_DTOG1 (0x0010) /* EndPoint TX Data TOGgle bit1 */ -#define EPTX_DTOG2 (0x0020) /* EndPoint TX Data TOGgle bit2 */ -#define EPTX_DTOGMASK (EPTX_STAT|EPREG_MASK) - -/* STAT_RX[1:0] STATus for RX transfer */ -#define EP_RX_DIS (0x0000) /* EndPoint RX DISabled */ -#define EP_RX_STALL (0x1000) /* EndPoint RX STALLed */ -#define EP_RX_NAK (0x2000) /* EndPoint RX NAKed */ -#define EP_RX_VALID (0x3000) /* EndPoint RX VALID */ -#define EPRX_DTOG1 (0x1000) /* EndPoint RX Data TOGgle bit1 */ -#define EPRX_DTOG2 (0x2000) /* EndPoint RX Data TOGgle bit1 */ -#define EPRX_DTOGMASK (EPRX_STAT|EPREG_MASK) -/* Exported macro ------------------------------------------------------------*/ -/* SetCNTR */ -#define _SetCNTR(wRegValue) (*CNTR = (uint16_t)wRegValue) - -/* SetISTR */ -#define _SetISTR(wRegValue) (*ISTR = (uint16_t)wRegValue) - -/* SetDADDR */ -#define _SetDADDR(wRegValue) (*DADDR = (uint16_t)wRegValue) - -/* SetBTABLE */ -#define _SetBTABLE(wRegValue)(*BTABLE = (uint16_t)(wRegValue & 0xFFF8)) - -/* GetCNTR */ -#define _GetCNTR() ((uint16_t) *CNTR) - -/* GetISTR */ -#define _GetISTR() ((uint16_t) *ISTR) - -/* GetFNR */ -#define _GetFNR() ((uint16_t) *FNR) - -/* GetDADDR */ -#define _GetDADDR() ((uint16_t) *DADDR) - -/* GetBTABLE */ -#define _GetBTABLE() ((uint16_t) *BTABLE) - -/* SetENDPOINT */ -#define _SetENDPOINT(bEpNum,wRegValue) (*(EP0REG + bEpNum)= \ - (uint16_t)wRegValue) - -/* GetENDPOINT */ -#define _GetENDPOINT(bEpNum) ((uint16_t)(*(EP0REG + bEpNum))) - -/******************************************************************************* -* Macro Name : SetEPType -* Description : sets the type in the endpoint register(bits EP_TYPE[1:0]) -* Input : bEpNum: Endpoint Number. -* wType -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPType(bEpNum,wType) (_SetENDPOINT(bEpNum,\ - ((_GetENDPOINT(bEpNum) & EP_T_MASK) | wType ))) - -/******************************************************************************* -* Macro Name : GetEPType -* Description : gets the type in the endpoint register(bits EP_TYPE[1:0]) -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Endpoint Type -*******************************************************************************/ -#define _GetEPType(bEpNum) (_GetENDPOINT(bEpNum) & EP_T_FIELD) - -/******************************************************************************* -* Macro Name : SetEPTxStatus -* Description : sets the status for tx transfer (bits STAT_TX[1:0]). -* Input : bEpNum: Endpoint Number. -* wState: new state -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPTxStatus(bEpNum,wState) {\ - register uint16_t _wRegVal; \ - _wRegVal = _GetENDPOINT(bEpNum) & EPTX_DTOGMASK;\ - /* toggle first bit ? */ \ - if((EPTX_DTOG1 & wState)!= 0) \ - _wRegVal ^= EPTX_DTOG1; \ - /* toggle second bit ? */ \ - if((EPTX_DTOG2 & wState)!= 0) \ - _wRegVal ^= EPTX_DTOG2; \ - _SetENDPOINT(bEpNum, (_wRegVal | EP_CTR_RX|EP_CTR_TX)); \ - } /* _SetEPTxStatus */ - -/******************************************************************************* -* Macro Name : SetEPRxStatus -* Description : sets the status for rx transfer (bits STAT_TX[1:0]) -* Input : bEpNum: Endpoint Number. -* wState: new state. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPRxStatus(bEpNum,wState) {\ - register uint16_t _wRegVal; \ - \ - _wRegVal = _GetENDPOINT(bEpNum) & EPRX_DTOGMASK;\ - /* toggle first bit ? */ \ - if((EPRX_DTOG1 & wState)!= 0) \ - _wRegVal ^= EPRX_DTOG1; \ - /* toggle second bit ? */ \ - if((EPRX_DTOG2 & wState)!= 0) \ - _wRegVal ^= EPRX_DTOG2; \ - _SetENDPOINT(bEpNum, (_wRegVal | EP_CTR_RX|EP_CTR_TX)); \ - } /* _SetEPRxStatus */ - -/******************************************************************************* -* Macro Name : SetEPRxTxStatus -* Description : sets the status for rx & tx (bits STAT_TX[1:0] & STAT_RX[1:0]) -* Input : bEpNum: Endpoint Number. -* wStaterx: new state. -* wStatetx: new state. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPRxTxStatus(bEpNum,wStaterx,wStatetx) {\ - register uint32_t _wRegVal; \ - \ - _wRegVal = _GetENDPOINT(bEpNum) & (EPRX_DTOGMASK |EPTX_STAT) ;\ - /* toggle first bit ? */ \ - if((EPRX_DTOG1 & wStaterx)!= 0) \ - _wRegVal ^= EPRX_DTOG1; \ - /* toggle second bit ? */ \ - if((EPRX_DTOG2 & wStaterx)!= 0) \ - _wRegVal ^= EPRX_DTOG2; \ - /* toggle first bit ? */ \ - if((EPTX_DTOG1 & wStatetx)!= 0) \ - _wRegVal ^= EPTX_DTOG1; \ - /* toggle second bit ? */ \ - if((EPTX_DTOG2 & wStatetx)!= 0) \ - _wRegVal ^= EPTX_DTOG2; \ - _SetENDPOINT(bEpNum, _wRegVal | EP_CTR_RX|EP_CTR_TX); \ - } /* _SetEPRxTxStatus */ -/******************************************************************************* -* Macro Name : GetEPTxStatus / GetEPRxStatus -* Description : gets the status for tx/rx transfer (bits STAT_TX[1:0] -* /STAT_RX[1:0]) -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : status . -*******************************************************************************/ -#define _GetEPTxStatus(bEpNum) ((uint16_t)_GetENDPOINT(bEpNum) & EPTX_STAT) - -#define _GetEPRxStatus(bEpNum) ((uint16_t)_GetENDPOINT(bEpNum) & EPRX_STAT) - -/******************************************************************************* -* Macro Name : SetEPTxValid / SetEPRxValid -* Description : sets directly the VALID tx/rx-status into the enpoint register -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPTxValid(bEpNum) (_SetEPTxStatus(bEpNum, EP_TX_VALID)) - -#define _SetEPRxValid(bEpNum) (_SetEPRxStatus(bEpNum, EP_RX_VALID)) - -/******************************************************************************* -* Macro Name : GetTxStallStatus / GetRxStallStatus. -* Description : checks stall condition in an endpoint. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : TRUE = endpoint in stall condition. -*******************************************************************************/ -#define _GetTxStallStatus(bEpNum) (_GetEPTxStatus(bEpNum) \ - == EP_TX_STALL) -#define _GetRxStallStatus(bEpNum) (_GetEPRxStatus(bEpNum) \ - == EP_RX_STALL) - -/******************************************************************************* -* Macro Name : SetEP_KIND / ClearEP_KIND. -* Description : set & clear EP_KIND bit. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEP_KIND(bEpNum) (_SetENDPOINT(bEpNum, \ - (EP_CTR_RX|EP_CTR_TX|((_GetENDPOINT(bEpNum) | EP_KIND) & EPREG_MASK)))) -#define _ClearEP_KIND(bEpNum) (_SetENDPOINT(bEpNum, \ - (EP_CTR_RX|EP_CTR_TX|(_GetENDPOINT(bEpNum) & EPKIND_MASK)))) - -/******************************************************************************* -* Macro Name : Set_Status_Out / Clear_Status_Out. -* Description : Sets/clears directly STATUS_OUT bit in the endpoint register. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _Set_Status_Out(bEpNum) _SetEP_KIND(bEpNum) -#define _Clear_Status_Out(bEpNum) _ClearEP_KIND(bEpNum) - -/******************************************************************************* -* Macro Name : SetEPDoubleBuff / ClearEPDoubleBuff. -* Description : Sets/clears directly EP_KIND bit in the endpoint register. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPDoubleBuff(bEpNum) _SetEP_KIND(bEpNum) -#define _ClearEPDoubleBuff(bEpNum) _ClearEP_KIND(bEpNum) - -/******************************************************************************* -* Macro Name : ClearEP_CTR_RX / ClearEP_CTR_TX. -* Description : Clears bit CTR_RX / CTR_TX in the endpoint register. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _ClearEP_CTR_RX(bEpNum) (_SetENDPOINT(bEpNum,\ - _GetENDPOINT(bEpNum) & 0x7FFF & EPREG_MASK)) -#define _ClearEP_CTR_TX(bEpNum) (_SetENDPOINT(bEpNum,\ - _GetENDPOINT(bEpNum) & 0xFF7F & EPREG_MASK)) - -/******************************************************************************* -* Macro Name : ToggleDTOG_RX / ToggleDTOG_TX . -* Description : Toggles DTOG_RX / DTOG_TX bit in the endpoint register. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _ToggleDTOG_RX(bEpNum) (_SetENDPOINT(bEpNum, \ - EP_CTR_RX|EP_CTR_TX|EP_DTOG_RX | (_GetENDPOINT(bEpNum) & EPREG_MASK))) -#define _ToggleDTOG_TX(bEpNum) (_SetENDPOINT(bEpNum, \ - EP_CTR_RX|EP_CTR_TX|EP_DTOG_TX | (_GetENDPOINT(bEpNum) & EPREG_MASK))) - -/******************************************************************************* -* Macro Name : ClearDTOG_RX / ClearDTOG_TX. -* Description : Clears DTOG_RX / DTOG_TX bit in the endpoint register. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _ClearDTOG_RX(bEpNum) if((_GetENDPOINT(bEpNum) & EP_DTOG_RX) != 0)\ - _ToggleDTOG_RX(bEpNum) -#define _ClearDTOG_TX(bEpNum) if((_GetENDPOINT(bEpNum) & EP_DTOG_TX) != 0)\ - _ToggleDTOG_TX(bEpNum) -/******************************************************************************* -* Macro Name : SetEPAddress. -* Description : Sets address in an endpoint register. -* Input : bEpNum: Endpoint Number. -* bAddr: Address. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPAddress(bEpNum,bAddr) _SetENDPOINT(bEpNum,\ - EP_CTR_RX|EP_CTR_TX|(_GetENDPOINT(bEpNum) & EPREG_MASK) | bAddr) - -/******************************************************************************* -* Macro Name : GetEPAddress. -* Description : Gets address in an endpoint register. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _GetEPAddress(bEpNum) ((uint8_t)(_GetENDPOINT(bEpNum) & EPADDR_FIELD)) - -#define _pEPTxAddr(bEpNum) ((uint32_t *)((_GetBTABLE()+bEpNum*8 )*2 + PMAAddr)) -#define _pEPTxCount(bEpNum) ((uint32_t *)((_GetBTABLE()+bEpNum*8+2)*2 + PMAAddr)) -#define _pEPRxAddr(bEpNum) ((uint32_t *)((_GetBTABLE()+bEpNum*8+4)*2 + PMAAddr)) -#define _pEPRxCount(bEpNum) ((uint32_t *)((_GetBTABLE()+bEpNum*8+6)*2 + PMAAddr)) - -/******************************************************************************* -* Macro Name : SetEPTxAddr / SetEPRxAddr. -* Description : sets address of the tx/rx buffer. -* Input : bEpNum: Endpoint Number. -* wAddr: address to be set (must be word aligned). -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPTxAddr(bEpNum,wAddr) (*_pEPTxAddr(bEpNum) = ((wAddr >> 1) << 1)) -#define _SetEPRxAddr(bEpNum,wAddr) (*_pEPRxAddr(bEpNum) = ((wAddr >> 1) << 1)) - -/******************************************************************************* -* Macro Name : GetEPTxAddr / GetEPRxAddr. -* Description : Gets address of the tx/rx buffer. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : address of the buffer. -*******************************************************************************/ -#define _GetEPTxAddr(bEpNum) ((uint16_t)*_pEPTxAddr(bEpNum)) -#define _GetEPRxAddr(bEpNum) ((uint16_t)*_pEPRxAddr(bEpNum)) - -/******************************************************************************* -* Macro Name : SetEPCountRxReg. -* Description : Sets counter of rx buffer with no. of blocks. -* Input : pdwReg: pointer to counter. -* wCount: Counter. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _BlocksOf32(dwReg,wCount,wNBlocks) {\ - wNBlocks = wCount >> 5;\ - if((wCount & 0x1f) == 0)\ - wNBlocks--;\ - *pdwReg = (uint32_t)((wNBlocks << 10) | 0x8000);\ - }/* _BlocksOf32 */ - -#define _BlocksOf2(dwReg,wCount,wNBlocks) {\ - wNBlocks = wCount >> 1;\ - if((wCount & 0x1) != 0)\ - wNBlocks++;\ - *pdwReg = (uint32_t)(wNBlocks << 10);\ - }/* _BlocksOf2 */ - -#define _SetEPCountRxReg(dwReg,wCount) {\ - uint16_t wNBlocks;\ - if(wCount > 62){_BlocksOf32(dwReg,wCount,wNBlocks);}\ - else {_BlocksOf2(dwReg,wCount,wNBlocks);}\ - }/* _SetEPCountRxReg */ - - - -#define _SetEPRxDblBuf0Count(bEpNum,wCount) {\ - uint32_t *pdwReg = _pEPTxCount(bEpNum); \ - _SetEPCountRxReg(pdwReg, wCount);\ - } -/******************************************************************************* -* Macro Name : SetEPTxCount / SetEPRxCount. -* Description : sets counter for the tx/rx buffer. -* Input : bEpNum: endpoint number. -* wCount: Counter value. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPTxCount(bEpNum,wCount) (*_pEPTxCount(bEpNum) = wCount) -#define _SetEPRxCount(bEpNum,wCount) {\ - uint32_t *pdwReg = _pEPRxCount(bEpNum); \ - _SetEPCountRxReg(pdwReg, wCount);\ - } -/******************************************************************************* -* Macro Name : GetEPTxCount / GetEPRxCount. -* Description : gets counter of the tx buffer. -* Input : bEpNum: endpoint number. -* Output : None. -* Return : Counter value. -*******************************************************************************/ -#define _GetEPTxCount(bEpNum)((uint16_t)(*_pEPTxCount(bEpNum)) & 0x3ff) -#define _GetEPRxCount(bEpNum)((uint16_t)(*_pEPRxCount(bEpNum)) & 0x3ff) - -/******************************************************************************* -* Macro Name : SetEPDblBuf0Addr / SetEPDblBuf1Addr. -* Description : Sets buffer 0/1 address in a double buffer endpoint. -* Input : bEpNum: endpoint number. -* : wBuf0Addr: buffer 0 address. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPDblBuf0Addr(bEpNum,wBuf0Addr) {_SetEPTxAddr(bEpNum, wBuf0Addr);} -#define _SetEPDblBuf1Addr(bEpNum,wBuf1Addr) {_SetEPRxAddr(bEpNum, wBuf1Addr);} - -/******************************************************************************* -* Macro Name : SetEPDblBuffAddr. -* Description : Sets addresses in a double buffer endpoint. -* Input : bEpNum: endpoint number. -* : wBuf0Addr: buffer 0 address. -* : wBuf1Addr = buffer 1 address. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPDblBuffAddr(bEpNum,wBuf0Addr,wBuf1Addr) { \ - _SetEPDblBuf0Addr(bEpNum, wBuf0Addr);\ - _SetEPDblBuf1Addr(bEpNum, wBuf1Addr);\ - } /* _SetEPDblBuffAddr */ - -/******************************************************************************* -* Macro Name : GetEPDblBuf0Addr / GetEPDblBuf1Addr. -* Description : Gets buffer 0/1 address of a double buffer endpoint. -* Input : bEpNum: endpoint number. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _GetEPDblBuf0Addr(bEpNum) (_GetEPTxAddr(bEpNum)) -#define _GetEPDblBuf1Addr(bEpNum) (_GetEPRxAddr(bEpNum)) - -/******************************************************************************* -* Macro Name : SetEPDblBuffCount / SetEPDblBuf0Count / SetEPDblBuf1Count. -* Description : Gets buffer 0/1 address of a double buffer endpoint. -* Input : bEpNum: endpoint number. -* : bDir: endpoint dir EP_DBUF_OUT = OUT -* EP_DBUF_IN = IN -* : wCount: Counter value -* Output : None. -* Return : None. -*******************************************************************************/ -#define _SetEPDblBuf0Count(bEpNum, bDir, wCount) { \ - if(bDir == EP_DBUF_OUT)\ - /* OUT endpoint */ \ - {_SetEPRxDblBuf0Count(bEpNum,wCount);} \ - else if(bDir == EP_DBUF_IN)\ - /* IN endpoint */ \ - *_pEPTxCount(bEpNum) = (uint32_t)wCount; \ - } /* SetEPDblBuf0Count*/ - -#define _SetEPDblBuf1Count(bEpNum, bDir, wCount) { \ - if(bDir == EP_DBUF_OUT)\ - /* OUT endpoint */ \ - {_SetEPRxCount(bEpNum,wCount);}\ - else if(bDir == EP_DBUF_IN)\ - /* IN endpoint */\ - *_pEPRxCount(bEpNum) = (uint32_t)wCount; \ - } /* SetEPDblBuf1Count */ - -#define _SetEPDblBuffCount(bEpNum, bDir, wCount) {\ - _SetEPDblBuf0Count(bEpNum, bDir, wCount); \ - _SetEPDblBuf1Count(bEpNum, bDir, wCount); \ - } /* _SetEPDblBuffCount */ - -/******************************************************************************* -* Macro Name : GetEPDblBuf0Count / GetEPDblBuf1Count. -* Description : Gets buffer 0/1 rx/tx counter for double buffering. -* Input : bEpNum: endpoint number. -* Output : None. -* Return : None. -*******************************************************************************/ -#define _GetEPDblBuf0Count(bEpNum) (_GetEPTxCount(bEpNum)) -#define _GetEPDblBuf1Count(bEpNum) (_GetEPRxCount(bEpNum)) - - -/* External variables --------------------------------------------------------*/ -extern __IO uint16_t wIstr; /* ISTR register last read value */ - -/* Exported functions ------------------------------------------------------- */ -void SetCNTR(uint16_t /*wRegValue*/); -void SetISTR(uint16_t /*wRegValue*/); -void SetDADDR(uint16_t /*wRegValue*/); -void SetBTABLE(uint16_t /*wRegValue*/); -void SetBTABLE(uint16_t /*wRegValue*/); -uint16_t GetCNTR(void); -uint16_t GetISTR(void); -uint16_t GetFNR(void); -uint16_t GetDADDR(void); -uint16_t GetBTABLE(void); -void SetENDPOINT(uint8_t /*bEpNum*/, uint16_t /*wRegValue*/); -uint16_t GetENDPOINT(uint8_t /*bEpNum*/); -void SetEPType(uint8_t /*bEpNum*/, uint16_t /*wType*/); -uint16_t GetEPType(uint8_t /*bEpNum*/); -void SetEPTxStatus(uint8_t /*bEpNum*/, uint16_t /*wState*/); -void SetEPRxStatus(uint8_t /*bEpNum*/, uint16_t /*wState*/); -void SetDouBleBuffEPStall(uint8_t /*bEpNum*/, uint8_t bDir); -uint16_t GetEPTxStatus(uint8_t /*bEpNum*/); -uint16_t GetEPRxStatus(uint8_t /*bEpNum*/); -void SetEPTxValid(uint8_t /*bEpNum*/); -void SetEPRxValid(uint8_t /*bEpNum*/); -uint16_t GetTxStallStatus(uint8_t /*bEpNum*/); -uint16_t GetRxStallStatus(uint8_t /*bEpNum*/); -void SetEP_KIND(uint8_t /*bEpNum*/); -void ClearEP_KIND(uint8_t /*bEpNum*/); -void Set_Status_Out(uint8_t /*bEpNum*/); -void Clear_Status_Out(uint8_t /*bEpNum*/); -void SetEPDoubleBuff(uint8_t /*bEpNum*/); -void ClearEPDoubleBuff(uint8_t /*bEpNum*/); -void ClearEP_CTR_RX(uint8_t /*bEpNum*/); -void ClearEP_CTR_TX(uint8_t /*bEpNum*/); -void ToggleDTOG_RX(uint8_t /*bEpNum*/); -void ToggleDTOG_TX(uint8_t /*bEpNum*/); -void ClearDTOG_RX(uint8_t /*bEpNum*/); -void ClearDTOG_TX(uint8_t /*bEpNum*/); -void SetEPAddress(uint8_t /*bEpNum*/, uint8_t /*bAddr*/); -uint8_t GetEPAddress(uint8_t /*bEpNum*/); -void SetEPTxAddr(uint8_t /*bEpNum*/, uint16_t /*wAddr*/); -void SetEPRxAddr(uint8_t /*bEpNum*/, uint16_t /*wAddr*/); -uint16_t GetEPTxAddr(uint8_t /*bEpNum*/); -uint16_t GetEPRxAddr(uint8_t /*bEpNum*/); -void SetEPCountRxReg(uint32_t * /*pdwReg*/, uint16_t /*wCount*/); -void SetEPTxCount(uint8_t /*bEpNum*/, uint16_t /*wCount*/); -void SetEPRxCount(uint8_t /*bEpNum*/, uint16_t /*wCount*/); -uint16_t GetEPTxCount(uint8_t /*bEpNum*/); -uint16_t GetEPRxCount(uint8_t /*bEpNum*/); -void SetEPDblBuf0Addr(uint8_t /*bEpNum*/, uint16_t /*wBuf0Addr*/); -void SetEPDblBuf1Addr(uint8_t /*bEpNum*/, uint16_t /*wBuf1Addr*/); -void SetEPDblBuffAddr(uint8_t /*bEpNum*/, uint16_t /*wBuf0Addr*/, uint16_t /*wBuf1Addr*/); -uint16_t GetEPDblBuf0Addr(uint8_t /*bEpNum*/); -uint16_t GetEPDblBuf1Addr(uint8_t /*bEpNum*/); -void SetEPDblBuffCount(uint8_t /*bEpNum*/, uint8_t /*bDir*/, uint16_t /*wCount*/); -void SetEPDblBuf0Count(uint8_t /*bEpNum*/, uint8_t /*bDir*/, uint16_t /*wCount*/); -void SetEPDblBuf1Count(uint8_t /*bEpNum*/, uint8_t /*bDir*/, uint16_t /*wCount*/); -uint16_t GetEPDblBuf0Count(uint8_t /*bEpNum*/); -uint16_t GetEPDblBuf1Count(uint8_t /*bEpNum*/); -EP_DBUF_DIR GetEPDblBufDir(uint8_t /*bEpNum*/); -void FreeUserBuffer(uint8_t bEpNum/*bEpNum*/, uint8_t bDir); -uint16_t ToWord(uint8_t, uint8_t); -uint16_t ByteSwap(uint16_t); - -#endif /* STM32F10X_CL */ - -#endif /* __USB_REGS_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_regs.h +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Interface prototype functions to USB cell registers +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_REGS_H +#define __USB_REGS_H + +#ifndef STM32F10X_CL + +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef enum _EP_DBUF_DIR +{ + /* double buffered endpoint direction */ + EP_DBUF_ERR, + EP_DBUF_OUT, + EP_DBUF_IN +}EP_DBUF_DIR; + +/* endpoint buffer number */ +enum EP_BUF_NUM +{ + EP_NOBUF, + EP_BUF0, + EP_BUF1 +}; + +/* Exported constants --------------------------------------------------------*/ +#define RegBase (0x40005C00L) /* USB_IP Peripheral Registers base address */ +#define PMAAddr (0x40006000L) /* USB_IP Packet Memory Area base address */ + +/******************************************************************************/ +/* General registers */ +/******************************************************************************/ + +/* Control register */ +#define CNTR ((__IO unsigned *)(RegBase + 0x40)) +/* Interrupt status register */ +#define ISTR ((__IO unsigned *)(RegBase + 0x44)) +/* Frame number register */ +#define FNR ((__IO unsigned *)(RegBase + 0x48)) +/* Device address register */ +#define DADDR ((__IO unsigned *)(RegBase + 0x4C)) +/* Buffer Table address register */ +#define BTABLE ((__IO unsigned *)(RegBase + 0x50)) +/******************************************************************************/ +/* Endpoint registers */ +/******************************************************************************/ +#define EP0REG ((__IO unsigned *)(RegBase)) /* endpoint 0 register address */ + +/* Endpoint Addresses (w/direction) */ +#define EP0_OUT ((uint8_t)0x00) +#define EP0_IN ((uint8_t)0x80) +#define EP1_OUT ((uint8_t)0x01) +#define EP1_IN ((uint8_t)0x81) +#define EP2_OUT ((uint8_t)0x02) +#define EP2_IN ((uint8_t)0x82) +#define EP3_OUT ((uint8_t)0x03) +#define EP3_IN ((uint8_t)0x83) +#define EP4_OUT ((uint8_t)0x04) +#define EP4_IN ((uint8_t)0x84) +#define EP5_OUT ((uint8_t)0x05) +#define EP5_IN ((uint8_t)0x85) +#define EP6_OUT ((uint8_t)0x06) +#define EP6_IN ((uint8_t)0x86) +#define EP7_OUT ((uint8_t)0x07) +#define EP7_IN ((uint8_t)0x87) + +/* endpoints enumeration */ +#define ENDP0 ((uint8_t)0) +#define ENDP1 ((uint8_t)1) +#define ENDP2 ((uint8_t)2) +#define ENDP3 ((uint8_t)3) +#define ENDP4 ((uint8_t)4) +#define ENDP5 ((uint8_t)5) +#define ENDP6 ((uint8_t)6) +#define ENDP7 ((uint8_t)7) + +/******************************************************************************/ +/* ISTR interrupt events */ +/******************************************************************************/ +#define ISTR_CTR (0x8000) /* Correct TRansfer (clear-only bit) */ +#define ISTR_DOVR (0x4000) /* DMA OVeR/underrun (clear-only bit) */ +#define ISTR_ERR (0x2000) /* ERRor (clear-only bit) */ +#define ISTR_WKUP (0x1000) /* WaKe UP (clear-only bit) */ +#define ISTR_SUSP (0x0800) /* SUSPend (clear-only bit) */ +#define ISTR_RESET (0x0400) /* RESET (clear-only bit) */ +#define ISTR_SOF (0x0200) /* Start Of Frame (clear-only bit) */ +#define ISTR_ESOF (0x0100) /* Expected Start Of Frame (clear-only bit) */ + + +#define ISTR_DIR (0x0010) /* DIRection of transaction (read-only bit) */ +#define ISTR_EP_ID (0x000F) /* EndPoint IDentifier (read-only bit) */ + +#define CLR_CTR (~ISTR_CTR) /* clear Correct TRansfer bit */ +#define CLR_DOVR (~ISTR_DOVR) /* clear DMA OVeR/underrun bit*/ +#define CLR_ERR (~ISTR_ERR) /* clear ERRor bit */ +#define CLR_WKUP (~ISTR_WKUP) /* clear WaKe UP bit */ +#define CLR_SUSP (~ISTR_SUSP) /* clear SUSPend bit */ +#define CLR_RESET (~ISTR_RESET) /* clear RESET bit */ +#define CLR_SOF (~ISTR_SOF) /* clear Start Of Frame bit */ +#define CLR_ESOF (~ISTR_ESOF) /* clear Expected Start Of Frame bit */ + +/******************************************************************************/ +/* CNTR control register bits definitions */ +/******************************************************************************/ +#define CNTR_CTRM (0x8000) /* Correct TRansfer Mask */ +#define CNTR_DOVRM (0x4000) /* DMA OVeR/underrun Mask */ +#define CNTR_ERRM (0x2000) /* ERRor Mask */ +#define CNTR_WKUPM (0x1000) /* WaKe UP Mask */ +#define CNTR_SUSPM (0x0800) /* SUSPend Mask */ +#define CNTR_RESETM (0x0400) /* RESET Mask */ +#define CNTR_SOFM (0x0200) /* Start Of Frame Mask */ +#define CNTR_ESOFM (0x0100) /* Expected Start Of Frame Mask */ + + +#define CNTR_RESUME (0x0010) /* RESUME request */ +#define CNTR_FSUSP (0x0008) /* Force SUSPend */ +#define CNTR_LPMODE (0x0004) /* Low-power MODE */ +#define CNTR_PDWN (0x0002) /* Power DoWN */ +#define CNTR_FRES (0x0001) /* Force USB RESet */ + +/******************************************************************************/ +/* FNR Frame Number Register bit definitions */ +/******************************************************************************/ +#define FNR_RXDP (0x8000) /* status of D+ data line */ +#define FNR_RXDM (0x4000) /* status of D- data line */ +#define FNR_LCK (0x2000) /* LoCKed */ +#define FNR_LSOF (0x1800) /* Lost SOF */ +#define FNR_FN (0x07FF) /* Frame Number */ +/******************************************************************************/ +/* DADDR Device ADDRess bit definitions */ +/******************************************************************************/ +#define DADDR_EF (0x80) +#define DADDR_ADD (0x7F) +/******************************************************************************/ +/* Endpoint register */ +/******************************************************************************/ +/* bit positions */ +#define EP_CTR_RX (0x8000) /* EndPoint Correct TRansfer RX */ +#define EP_DTOG_RX (0x4000) /* EndPoint Data TOGGLE RX */ +#define EPRX_STAT (0x3000) /* EndPoint RX STATus bit field */ +#define EP_SETUP (0x0800) /* EndPoint SETUP */ +#define EP_T_FIELD (0x0600) /* EndPoint TYPE */ +#define EP_KIND (0x0100) /* EndPoint KIND */ +#define EP_CTR_TX (0x0080) /* EndPoint Correct TRansfer TX */ +#define EP_DTOG_TX (0x0040) /* EndPoint Data TOGGLE TX */ +#define EPTX_STAT (0x0030) /* EndPoint TX STATus bit field */ +#define EPADDR_FIELD (0x000F) /* EndPoint ADDRess FIELD */ + +/* EndPoint REGister MASK (no toggle fields) */ +#define EPREG_MASK (EP_CTR_RX|EP_SETUP|EP_T_FIELD|EP_KIND|EP_CTR_TX|EPADDR_FIELD) + +/* EP_TYPE[1:0] EndPoint TYPE */ +#define EP_TYPE_MASK (0x0600) /* EndPoint TYPE Mask */ +#define EP_BULK (0x0000) /* EndPoint BULK */ +#define EP_CONTROL (0x0200) /* EndPoint CONTROL */ +#define EP_ISOCHRONOUS (0x0400) /* EndPoint ISOCHRONOUS */ +#define EP_INTERRUPT (0x0600) /* EndPoint INTERRUPT */ +#define EP_T_MASK (~EP_T_FIELD & EPREG_MASK) + + +/* EP_KIND EndPoint KIND */ +#define EPKIND_MASK (~EP_KIND & EPREG_MASK) + +/* STAT_TX[1:0] STATus for TX transfer */ +#define EP_TX_DIS (0x0000) /* EndPoint TX DISabled */ +#define EP_TX_STALL (0x0010) /* EndPoint TX STALLed */ +#define EP_TX_NAK (0x0020) /* EndPoint TX NAKed */ +#define EP_TX_VALID (0x0030) /* EndPoint TX VALID */ +#define EPTX_DTOG1 (0x0010) /* EndPoint TX Data TOGgle bit1 */ +#define EPTX_DTOG2 (0x0020) /* EndPoint TX Data TOGgle bit2 */ +#define EPTX_DTOGMASK (EPTX_STAT|EPREG_MASK) + +/* STAT_RX[1:0] STATus for RX transfer */ +#define EP_RX_DIS (0x0000) /* EndPoint RX DISabled */ +#define EP_RX_STALL (0x1000) /* EndPoint RX STALLed */ +#define EP_RX_NAK (0x2000) /* EndPoint RX NAKed */ +#define EP_RX_VALID (0x3000) /* EndPoint RX VALID */ +#define EPRX_DTOG1 (0x1000) /* EndPoint RX Data TOGgle bit1 */ +#define EPRX_DTOG2 (0x2000) /* EndPoint RX Data TOGgle bit1 */ +#define EPRX_DTOGMASK (EPRX_STAT|EPREG_MASK) +/* Exported macro ------------------------------------------------------------*/ +/* SetCNTR */ +#define _SetCNTR(wRegValue) (*CNTR = (uint16_t)wRegValue) + +/* SetISTR */ +#define _SetISTR(wRegValue) (*ISTR = (uint16_t)wRegValue) + +/* SetDADDR */ +#define _SetDADDR(wRegValue) (*DADDR = (uint16_t)wRegValue) + +/* SetBTABLE */ +#define _SetBTABLE(wRegValue)(*BTABLE = (uint16_t)(wRegValue & 0xFFF8)) + +/* GetCNTR */ +#define _GetCNTR() ((uint16_t) *CNTR) + +/* GetISTR */ +#define _GetISTR() ((uint16_t) *ISTR) + +/* GetFNR */ +#define _GetFNR() ((uint16_t) *FNR) + +/* GetDADDR */ +#define _GetDADDR() ((uint16_t) *DADDR) + +/* GetBTABLE */ +#define _GetBTABLE() ((uint16_t) *BTABLE) + +/* SetENDPOINT */ +#define _SetENDPOINT(bEpNum,wRegValue) (*(EP0REG + bEpNum)= \ + (uint16_t)wRegValue) + +/* GetENDPOINT */ +#define _GetENDPOINT(bEpNum) ((uint16_t)(*(EP0REG + bEpNum))) + +/******************************************************************************* +* Macro Name : SetEPType +* Description : sets the type in the endpoint register(bits EP_TYPE[1:0]) +* Input : bEpNum: Endpoint Number. +* wType +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPType(bEpNum,wType) (_SetENDPOINT(bEpNum,\ + ((_GetENDPOINT(bEpNum) & EP_T_MASK) | wType ))) + +/******************************************************************************* +* Macro Name : GetEPType +* Description : gets the type in the endpoint register(bits EP_TYPE[1:0]) +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Endpoint Type +*******************************************************************************/ +#define _GetEPType(bEpNum) (_GetENDPOINT(bEpNum) & EP_T_FIELD) + +/******************************************************************************* +* Macro Name : SetEPTxStatus +* Description : sets the status for tx transfer (bits STAT_TX[1:0]). +* Input : bEpNum: Endpoint Number. +* wState: new state +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPTxStatus(bEpNum,wState) {\ + register uint16_t _wRegVal; \ + _wRegVal = _GetENDPOINT(bEpNum) & EPTX_DTOGMASK;\ + /* toggle first bit ? */ \ + if((EPTX_DTOG1 & wState)!= 0) \ + _wRegVal ^= EPTX_DTOG1; \ + /* toggle second bit ? */ \ + if((EPTX_DTOG2 & wState)!= 0) \ + _wRegVal ^= EPTX_DTOG2; \ + _SetENDPOINT(bEpNum, (_wRegVal | EP_CTR_RX|EP_CTR_TX)); \ + } /* _SetEPTxStatus */ + +/******************************************************************************* +* Macro Name : SetEPRxStatus +* Description : sets the status for rx transfer (bits STAT_TX[1:0]) +* Input : bEpNum: Endpoint Number. +* wState: new state. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPRxStatus(bEpNum,wState) {\ + register uint16_t _wRegVal; \ + \ + _wRegVal = _GetENDPOINT(bEpNum) & EPRX_DTOGMASK;\ + /* toggle first bit ? */ \ + if((EPRX_DTOG1 & wState)!= 0) \ + _wRegVal ^= EPRX_DTOG1; \ + /* toggle second bit ? */ \ + if((EPRX_DTOG2 & wState)!= 0) \ + _wRegVal ^= EPRX_DTOG2; \ + _SetENDPOINT(bEpNum, (_wRegVal | EP_CTR_RX|EP_CTR_TX)); \ + } /* _SetEPRxStatus */ + +/******************************************************************************* +* Macro Name : SetEPRxTxStatus +* Description : sets the status for rx & tx (bits STAT_TX[1:0] & STAT_RX[1:0]) +* Input : bEpNum: Endpoint Number. +* wStaterx: new state. +* wStatetx: new state. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPRxTxStatus(bEpNum,wStaterx,wStatetx) {\ + register uint32_t _wRegVal; \ + \ + _wRegVal = _GetENDPOINT(bEpNum) & (EPRX_DTOGMASK |EPTX_STAT) ;\ + /* toggle first bit ? */ \ + if((EPRX_DTOG1 & wStaterx)!= 0) \ + _wRegVal ^= EPRX_DTOG1; \ + /* toggle second bit ? */ \ + if((EPRX_DTOG2 & wStaterx)!= 0) \ + _wRegVal ^= EPRX_DTOG2; \ + /* toggle first bit ? */ \ + if((EPTX_DTOG1 & wStatetx)!= 0) \ + _wRegVal ^= EPTX_DTOG1; \ + /* toggle second bit ? */ \ + if((EPTX_DTOG2 & wStatetx)!= 0) \ + _wRegVal ^= EPTX_DTOG2; \ + _SetENDPOINT(bEpNum, _wRegVal | EP_CTR_RX|EP_CTR_TX); \ + } /* _SetEPRxTxStatus */ +/******************************************************************************* +* Macro Name : GetEPTxStatus / GetEPRxStatus +* Description : gets the status for tx/rx transfer (bits STAT_TX[1:0] +* /STAT_RX[1:0]) +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : status . +*******************************************************************************/ +#define _GetEPTxStatus(bEpNum) ((uint16_t)_GetENDPOINT(bEpNum) & EPTX_STAT) + +#define _GetEPRxStatus(bEpNum) ((uint16_t)_GetENDPOINT(bEpNum) & EPRX_STAT) + +/******************************************************************************* +* Macro Name : SetEPTxValid / SetEPRxValid +* Description : sets directly the VALID tx/rx-status into the enpoint register +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPTxValid(bEpNum) (_SetEPTxStatus(bEpNum, EP_TX_VALID)) + +#define _SetEPRxValid(bEpNum) (_SetEPRxStatus(bEpNum, EP_RX_VALID)) + +/******************************************************************************* +* Macro Name : GetTxStallStatus / GetRxStallStatus. +* Description : checks stall condition in an endpoint. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : TRUE = endpoint in stall condition. +*******************************************************************************/ +#define _GetTxStallStatus(bEpNum) (_GetEPTxStatus(bEpNum) \ + == EP_TX_STALL) +#define _GetRxStallStatus(bEpNum) (_GetEPRxStatus(bEpNum) \ + == EP_RX_STALL) + +/******************************************************************************* +* Macro Name : SetEP_KIND / ClearEP_KIND. +* Description : set & clear EP_KIND bit. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEP_KIND(bEpNum) (_SetENDPOINT(bEpNum, \ + (EP_CTR_RX|EP_CTR_TX|((_GetENDPOINT(bEpNum) | EP_KIND) & EPREG_MASK)))) +#define _ClearEP_KIND(bEpNum) (_SetENDPOINT(bEpNum, \ + (EP_CTR_RX|EP_CTR_TX|(_GetENDPOINT(bEpNum) & EPKIND_MASK)))) + +/******************************************************************************* +* Macro Name : Set_Status_Out / Clear_Status_Out. +* Description : Sets/clears directly STATUS_OUT bit in the endpoint register. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _Set_Status_Out(bEpNum) _SetEP_KIND(bEpNum) +#define _Clear_Status_Out(bEpNum) _ClearEP_KIND(bEpNum) + +/******************************************************************************* +* Macro Name : SetEPDoubleBuff / ClearEPDoubleBuff. +* Description : Sets/clears directly EP_KIND bit in the endpoint register. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPDoubleBuff(bEpNum) _SetEP_KIND(bEpNum) +#define _ClearEPDoubleBuff(bEpNum) _ClearEP_KIND(bEpNum) + +/******************************************************************************* +* Macro Name : ClearEP_CTR_RX / ClearEP_CTR_TX. +* Description : Clears bit CTR_RX / CTR_TX in the endpoint register. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _ClearEP_CTR_RX(bEpNum) (_SetENDPOINT(bEpNum,\ + _GetENDPOINT(bEpNum) & 0x7FFF & EPREG_MASK)) +#define _ClearEP_CTR_TX(bEpNum) (_SetENDPOINT(bEpNum,\ + _GetENDPOINT(bEpNum) & 0xFF7F & EPREG_MASK)) + +/******************************************************************************* +* Macro Name : ToggleDTOG_RX / ToggleDTOG_TX . +* Description : Toggles DTOG_RX / DTOG_TX bit in the endpoint register. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _ToggleDTOG_RX(bEpNum) (_SetENDPOINT(bEpNum, \ + EP_CTR_RX|EP_CTR_TX|EP_DTOG_RX | (_GetENDPOINT(bEpNum) & EPREG_MASK))) +#define _ToggleDTOG_TX(bEpNum) (_SetENDPOINT(bEpNum, \ + EP_CTR_RX|EP_CTR_TX|EP_DTOG_TX | (_GetENDPOINT(bEpNum) & EPREG_MASK))) + +/******************************************************************************* +* Macro Name : ClearDTOG_RX / ClearDTOG_TX. +* Description : Clears DTOG_RX / DTOG_TX bit in the endpoint register. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _ClearDTOG_RX(bEpNum) if((_GetENDPOINT(bEpNum) & EP_DTOG_RX) != 0)\ + _ToggleDTOG_RX(bEpNum) +#define _ClearDTOG_TX(bEpNum) if((_GetENDPOINT(bEpNum) & EP_DTOG_TX) != 0)\ + _ToggleDTOG_TX(bEpNum) +/******************************************************************************* +* Macro Name : SetEPAddress. +* Description : Sets address in an endpoint register. +* Input : bEpNum: Endpoint Number. +* bAddr: Address. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPAddress(bEpNum,bAddr) _SetENDPOINT(bEpNum,\ + EP_CTR_RX|EP_CTR_TX|(_GetENDPOINT(bEpNum) & EPREG_MASK) | bAddr) + +/******************************************************************************* +* Macro Name : GetEPAddress. +* Description : Gets address in an endpoint register. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _GetEPAddress(bEpNum) ((uint8_t)(_GetENDPOINT(bEpNum) & EPADDR_FIELD)) + +#define _pEPTxAddr(bEpNum) ((uint32_t *)((_GetBTABLE()+bEpNum*8 )*2 + PMAAddr)) +#define _pEPTxCount(bEpNum) ((uint32_t *)((_GetBTABLE()+bEpNum*8+2)*2 + PMAAddr)) +#define _pEPRxAddr(bEpNum) ((uint32_t *)((_GetBTABLE()+bEpNum*8+4)*2 + PMAAddr)) +#define _pEPRxCount(bEpNum) ((uint32_t *)((_GetBTABLE()+bEpNum*8+6)*2 + PMAAddr)) + +/******************************************************************************* +* Macro Name : SetEPTxAddr / SetEPRxAddr. +* Description : sets address of the tx/rx buffer. +* Input : bEpNum: Endpoint Number. +* wAddr: address to be set (must be word aligned). +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPTxAddr(bEpNum,wAddr) (*_pEPTxAddr(bEpNum) = ((wAddr >> 1) << 1)) +#define _SetEPRxAddr(bEpNum,wAddr) (*_pEPRxAddr(bEpNum) = ((wAddr >> 1) << 1)) + +/******************************************************************************* +* Macro Name : GetEPTxAddr / GetEPRxAddr. +* Description : Gets address of the tx/rx buffer. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : address of the buffer. +*******************************************************************************/ +#define _GetEPTxAddr(bEpNum) ((uint16_t)*_pEPTxAddr(bEpNum)) +#define _GetEPRxAddr(bEpNum) ((uint16_t)*_pEPRxAddr(bEpNum)) + +/******************************************************************************* +* Macro Name : SetEPCountRxReg. +* Description : Sets counter of rx buffer with no. of blocks. +* Input : pdwReg: pointer to counter. +* wCount: Counter. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _BlocksOf32(dwReg,wCount,wNBlocks) {\ + wNBlocks = wCount >> 5;\ + if((wCount & 0x1f) == 0)\ + wNBlocks--;\ + *pdwReg = (uint32_t)((wNBlocks << 10) | 0x8000);\ + }/* _BlocksOf32 */ + +#define _BlocksOf2(dwReg,wCount,wNBlocks) {\ + wNBlocks = wCount >> 1;\ + if((wCount & 0x1) != 0)\ + wNBlocks++;\ + *pdwReg = (uint32_t)(wNBlocks << 10);\ + }/* _BlocksOf2 */ + +#define _SetEPCountRxReg(dwReg,wCount) {\ + uint16_t wNBlocks;\ + if(wCount > 62){_BlocksOf32(dwReg,wCount,wNBlocks);}\ + else {_BlocksOf2(dwReg,wCount,wNBlocks);}\ + }/* _SetEPCountRxReg */ + + + +#define _SetEPRxDblBuf0Count(bEpNum,wCount) {\ + uint32_t *pdwReg = _pEPTxCount(bEpNum); \ + _SetEPCountRxReg(pdwReg, wCount);\ + } +/******************************************************************************* +* Macro Name : SetEPTxCount / SetEPRxCount. +* Description : sets counter for the tx/rx buffer. +* Input : bEpNum: endpoint number. +* wCount: Counter value. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPTxCount(bEpNum,wCount) (*_pEPTxCount(bEpNum) = wCount) +#define _SetEPRxCount(bEpNum,wCount) {\ + uint32_t *pdwReg = _pEPRxCount(bEpNum); \ + _SetEPCountRxReg(pdwReg, wCount);\ + } +/******************************************************************************* +* Macro Name : GetEPTxCount / GetEPRxCount. +* Description : gets counter of the tx buffer. +* Input : bEpNum: endpoint number. +* Output : None. +* Return : Counter value. +*******************************************************************************/ +#define _GetEPTxCount(bEpNum)((uint16_t)(*_pEPTxCount(bEpNum)) & 0x3ff) +#define _GetEPRxCount(bEpNum)((uint16_t)(*_pEPRxCount(bEpNum)) & 0x3ff) + +/******************************************************************************* +* Macro Name : SetEPDblBuf0Addr / SetEPDblBuf1Addr. +* Description : Sets buffer 0/1 address in a double buffer endpoint. +* Input : bEpNum: endpoint number. +* : wBuf0Addr: buffer 0 address. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPDblBuf0Addr(bEpNum,wBuf0Addr) {_SetEPTxAddr(bEpNum, wBuf0Addr);} +#define _SetEPDblBuf1Addr(bEpNum,wBuf1Addr) {_SetEPRxAddr(bEpNum, wBuf1Addr);} + +/******************************************************************************* +* Macro Name : SetEPDblBuffAddr. +* Description : Sets addresses in a double buffer endpoint. +* Input : bEpNum: endpoint number. +* : wBuf0Addr: buffer 0 address. +* : wBuf1Addr = buffer 1 address. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPDblBuffAddr(bEpNum,wBuf0Addr,wBuf1Addr) { \ + _SetEPDblBuf0Addr(bEpNum, wBuf0Addr);\ + _SetEPDblBuf1Addr(bEpNum, wBuf1Addr);\ + } /* _SetEPDblBuffAddr */ + +/******************************************************************************* +* Macro Name : GetEPDblBuf0Addr / GetEPDblBuf1Addr. +* Description : Gets buffer 0/1 address of a double buffer endpoint. +* Input : bEpNum: endpoint number. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _GetEPDblBuf0Addr(bEpNum) (_GetEPTxAddr(bEpNum)) +#define _GetEPDblBuf1Addr(bEpNum) (_GetEPRxAddr(bEpNum)) + +/******************************************************************************* +* Macro Name : SetEPDblBuffCount / SetEPDblBuf0Count / SetEPDblBuf1Count. +* Description : Gets buffer 0/1 address of a double buffer endpoint. +* Input : bEpNum: endpoint number. +* : bDir: endpoint dir EP_DBUF_OUT = OUT +* EP_DBUF_IN = IN +* : wCount: Counter value +* Output : None. +* Return : None. +*******************************************************************************/ +#define _SetEPDblBuf0Count(bEpNum, bDir, wCount) { \ + if(bDir == EP_DBUF_OUT)\ + /* OUT endpoint */ \ + {_SetEPRxDblBuf0Count(bEpNum,wCount);} \ + else if(bDir == EP_DBUF_IN)\ + /* IN endpoint */ \ + *_pEPTxCount(bEpNum) = (uint32_t)wCount; \ + } /* SetEPDblBuf0Count*/ + +#define _SetEPDblBuf1Count(bEpNum, bDir, wCount) { \ + if(bDir == EP_DBUF_OUT)\ + /* OUT endpoint */ \ + {_SetEPRxCount(bEpNum,wCount);}\ + else if(bDir == EP_DBUF_IN)\ + /* IN endpoint */\ + *_pEPRxCount(bEpNum) = (uint32_t)wCount; \ + } /* SetEPDblBuf1Count */ + +#define _SetEPDblBuffCount(bEpNum, bDir, wCount) {\ + _SetEPDblBuf0Count(bEpNum, bDir, wCount); \ + _SetEPDblBuf1Count(bEpNum, bDir, wCount); \ + } /* _SetEPDblBuffCount */ + +/******************************************************************************* +* Macro Name : GetEPDblBuf0Count / GetEPDblBuf1Count. +* Description : Gets buffer 0/1 rx/tx counter for double buffering. +* Input : bEpNum: endpoint number. +* Output : None. +* Return : None. +*******************************************************************************/ +#define _GetEPDblBuf0Count(bEpNum) (_GetEPTxCount(bEpNum)) +#define _GetEPDblBuf1Count(bEpNum) (_GetEPRxCount(bEpNum)) + + +/* External variables --------------------------------------------------------*/ +extern __IO uint16_t wIstr; /* ISTR register last read value */ + +/* Exported functions ------------------------------------------------------- */ +void SetCNTR(uint16_t /*wRegValue*/); +void SetISTR(uint16_t /*wRegValue*/); +void SetDADDR(uint16_t /*wRegValue*/); +void SetBTABLE(uint16_t /*wRegValue*/); +void SetBTABLE(uint16_t /*wRegValue*/); +uint16_t GetCNTR(void); +uint16_t GetISTR(void); +uint16_t GetFNR(void); +uint16_t GetDADDR(void); +uint16_t GetBTABLE(void); +void SetENDPOINT(uint8_t /*bEpNum*/, uint16_t /*wRegValue*/); +uint16_t GetENDPOINT(uint8_t /*bEpNum*/); +void SetEPType(uint8_t /*bEpNum*/, uint16_t /*wType*/); +uint16_t GetEPType(uint8_t /*bEpNum*/); +void SetEPTxStatus(uint8_t /*bEpNum*/, uint16_t /*wState*/); +void SetEPRxStatus(uint8_t /*bEpNum*/, uint16_t /*wState*/); +void SetDouBleBuffEPStall(uint8_t /*bEpNum*/, uint8_t bDir); +uint16_t GetEPTxStatus(uint8_t /*bEpNum*/); +uint16_t GetEPRxStatus(uint8_t /*bEpNum*/); +void SetEPTxValid(uint8_t /*bEpNum*/); +void SetEPRxValid(uint8_t /*bEpNum*/); +uint16_t GetTxStallStatus(uint8_t /*bEpNum*/); +uint16_t GetRxStallStatus(uint8_t /*bEpNum*/); +void SetEP_KIND(uint8_t /*bEpNum*/); +void ClearEP_KIND(uint8_t /*bEpNum*/); +void Set_Status_Out(uint8_t /*bEpNum*/); +void Clear_Status_Out(uint8_t /*bEpNum*/); +void SetEPDoubleBuff(uint8_t /*bEpNum*/); +void ClearEPDoubleBuff(uint8_t /*bEpNum*/); +void ClearEP_CTR_RX(uint8_t /*bEpNum*/); +void ClearEP_CTR_TX(uint8_t /*bEpNum*/); +void ToggleDTOG_RX(uint8_t /*bEpNum*/); +void ToggleDTOG_TX(uint8_t /*bEpNum*/); +void ClearDTOG_RX(uint8_t /*bEpNum*/); +void ClearDTOG_TX(uint8_t /*bEpNum*/); +void SetEPAddress(uint8_t /*bEpNum*/, uint8_t /*bAddr*/); +uint8_t GetEPAddress(uint8_t /*bEpNum*/); +void SetEPTxAddr(uint8_t /*bEpNum*/, uint16_t /*wAddr*/); +void SetEPRxAddr(uint8_t /*bEpNum*/, uint16_t /*wAddr*/); +uint16_t GetEPTxAddr(uint8_t /*bEpNum*/); +uint16_t GetEPRxAddr(uint8_t /*bEpNum*/); +void SetEPCountRxReg(uint32_t * /*pdwReg*/, uint16_t /*wCount*/); +void SetEPTxCount(uint8_t /*bEpNum*/, uint16_t /*wCount*/); +void SetEPRxCount(uint8_t /*bEpNum*/, uint16_t /*wCount*/); +uint16_t GetEPTxCount(uint8_t /*bEpNum*/); +uint16_t GetEPRxCount(uint8_t /*bEpNum*/); +void SetEPDblBuf0Addr(uint8_t /*bEpNum*/, uint16_t /*wBuf0Addr*/); +void SetEPDblBuf1Addr(uint8_t /*bEpNum*/, uint16_t /*wBuf1Addr*/); +void SetEPDblBuffAddr(uint8_t /*bEpNum*/, uint16_t /*wBuf0Addr*/, uint16_t /*wBuf1Addr*/); +uint16_t GetEPDblBuf0Addr(uint8_t /*bEpNum*/); +uint16_t GetEPDblBuf1Addr(uint8_t /*bEpNum*/); +void SetEPDblBuffCount(uint8_t /*bEpNum*/, uint8_t /*bDir*/, uint16_t /*wCount*/); +void SetEPDblBuf0Count(uint8_t /*bEpNum*/, uint8_t /*bDir*/, uint16_t /*wCount*/); +void SetEPDblBuf1Count(uint8_t /*bEpNum*/, uint8_t /*bDir*/, uint16_t /*wCount*/); +uint16_t GetEPDblBuf0Count(uint8_t /*bEpNum*/); +uint16_t GetEPDblBuf1Count(uint8_t /*bEpNum*/); +EP_DBUF_DIR GetEPDblBufDir(uint8_t /*bEpNum*/); +void FreeUserBuffer(uint8_t bEpNum/*bEpNum*/, uint8_t bDir); +uint16_t ToWord(uint8_t, uint8_t); +uint16_t ByteSwap(uint16_t); + +#endif /* STM32F10X_CL */ + +#endif /* __USB_REGS_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_sil.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_sil.h index f55e3a027..107d44f2f 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_sil.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_sil.h @@ -1,34 +1,34 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_sil.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Simplified Interface Layer function prototypes. -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_SIL_H -#define __USB_SIL_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ - -uint32_t USB_SIL_Init(void); -uint32_t USB_SIL_Write(uint8_t bEpAddr, uint8_t* pBufferPointer, uint32_t wBufferSize); -uint32_t USB_SIL_Read(uint8_t bEpAddr, uint8_t* pBufferPointer); - -/* External variables --------------------------------------------------------*/ - -#endif /* __USB_SIL_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_sil.h +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Simplified Interface Layer function prototypes. +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_SIL_H +#define __USB_SIL_H + +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +uint32_t USB_SIL_Init(void); +uint32_t USB_SIL_Write(uint8_t bEpAddr, uint8_t* pBufferPointer, uint32_t wBufferSize); +uint32_t USB_SIL_Read(uint8_t bEpAddr, uint8_t* pBufferPointer); + +/* External variables --------------------------------------------------------*/ + +#endif /* __USB_SIL_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_type.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_type.h index f76ef3b6b..472aca3e4 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_type.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_type.h @@ -1,74 +1,74 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_type.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Type definitions used by the USB Library -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_TYPE_H -#define __USB_TYPE_H - -/* Includes ------------------------------------------------------------------*/ -#include "usb_conf.h" - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -#ifndef NULL -#define NULL ((void *)0) -#endif - -#ifndef __STM32F10x_H - -typedef signed long s32; -typedef signed short s16; -typedef signed char s8; - -typedef volatile signed long vs32; -typedef volatile signed short vs16; -typedef volatile signed char vs8; - -typedef unsigned long u32; -typedef unsigned short u16; -typedef unsigned char u8; - -typedef unsigned long const uc32; /* Read Only */ -typedef unsigned short const uc16; /* Read Only */ -typedef unsigned char const uc8; /* Read Only */ - -typedef volatile unsigned long vu32; -typedef volatile unsigned short vu16; -typedef volatile unsigned char vu8; - -typedef volatile unsigned long const vuc32; /* Read Only */ -typedef volatile unsigned short const vuc16; /* Read Only */ -typedef volatile unsigned char const vuc8; /* Read Only */ - - -typedef enum -{ - FALSE = 0, TRUE = !FALSE -} -bool; - -typedef enum { RESET = 0, SET = !RESET } FlagStatus, ITStatus; - -typedef enum { DISABLE = 0, ENABLE = !DISABLE} FunctionalState; - -typedef enum { ERROR = 0, SUCCESS = !ERROR} ErrorStatus; -#endif -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -/* External variables --------------------------------------------------------*/ - -#endif /* __USB_TYPE_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_type.h +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Type definitions used by the USB Library +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_TYPE_H +#define __USB_TYPE_H + +/* Includes ------------------------------------------------------------------*/ +#include "usb_conf.h" + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +#ifndef NULL +#define NULL ((void *)0) +#endif + +#ifndef __STM32F10x_H + +typedef signed long s32; +typedef signed short s16; +typedef signed char s8; + +typedef volatile signed long vs32; +typedef volatile signed short vs16; +typedef volatile signed char vs8; + +typedef unsigned long u32; +typedef unsigned short u16; +typedef unsigned char u8; + +typedef unsigned long const uc32; /* Read Only */ +typedef unsigned short const uc16; /* Read Only */ +typedef unsigned char const uc8; /* Read Only */ + +typedef volatile unsigned long vu32; +typedef volatile unsigned short vu16; +typedef volatile unsigned char vu8; + +typedef volatile unsigned long const vuc32; /* Read Only */ +typedef volatile unsigned short const vuc16; /* Read Only */ +typedef volatile unsigned char const vuc8; /* Read Only */ + + +typedef enum +{ + FALSE = 0, TRUE = !FALSE +} +bool; + +typedef enum { RESET = 0, SET = !RESET } FlagStatus, ITStatus; + +typedef enum { DISABLE = 0, ENABLE = !DISABLE} FunctionalState; + +typedef enum { ERROR = 0, SUCCESS = !ERROR} ErrorStatus; +#endif +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +/* External variables --------------------------------------------------------*/ + +#endif /* __USB_TYPE_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_core.c b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_core.c index 75ddaa42e..7ce85b3e2 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_core.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_core.c @@ -1,1086 +1,1086 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_core.c -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Standard protocol processing (USB v2.0) -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Includes ------------------------------------------------------------------*/ -#include "usb_lib.h" -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -#define ValBit(VAR,Place) (VAR & (1 << Place)) -#define SetBit(VAR,Place) (VAR |= (1 << Place)) -#define ClrBit(VAR,Place) (VAR &= ((1 << Place) ^ 255)) - -#ifdef STM32F10X_CL - #define Send0LengthData() {PCD_EP_Write (0, 0, 0) ; vSetEPTxStatus(EP_TX_VALID);} -#else -#define Send0LengthData() { _SetEPTxCount(ENDP0, 0); \ - vSetEPTxStatus(EP_TX_VALID); \ - } -#endif /* STM32F10X_CL */ - -#define vSetEPRxStatus(st) (SaveRState = st) -#define vSetEPTxStatus(st) (SaveTState = st) - -#define USB_StatusIn() Send0LengthData() -#define USB_StatusOut() vSetEPRxStatus(EP_RX_VALID) - -#define StatusInfo0 StatusInfo.bw.bb1 /* Reverse bb0 & bb1 */ -#define StatusInfo1 StatusInfo.bw.bb0 - -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -uint16_t_uint8_t StatusInfo; - -bool Data_Mul_MaxPacketSize = FALSE; -/* Private function prototypes -----------------------------------------------*/ -static void DataStageOut(void); -static void DataStageIn(void); -static void NoData_Setup0(void); -static void Data_Setup0(void); -/* Private functions ---------------------------------------------------------*/ - -/******************************************************************************* -* Function Name : Standard_GetConfiguration. -* Description : Return the current configuration variable address. -* Input : Length - How many bytes are needed. -* Output : None. -* Return : Return 1 , if the request is invalid when "Length" is 0. -* Return "Buffer" if the "Length" is not 0. -*******************************************************************************/ -const uint8_t *Standard_GetConfiguration(uint16_t Length) -{ - if (Length == 0) - { - pInformation->Ctrl_Info.Usb_wLength = - sizeof(pInformation->Current_Configuration); - return 0; - } - pUser_Standard_Requests->User_GetConfiguration(); - return (uint8_t *)&pInformation->Current_Configuration; -} - -/******************************************************************************* -* Function Name : Standard_SetConfiguration. -* Description : This routine is called to set the configuration value -* Then each class should configure device themself. -* Input : None. -* Output : None. -* Return : Return USB_SUCCESS, if the request is performed. -* Return USB_UNSUPPORT, if the request is invalid. -*******************************************************************************/ -RESULT Standard_SetConfiguration(void) -{ - - if ((pInformation->USBwValue0 <= - Device_Table.Total_Configuration) && (pInformation->USBwValue1 == 0) - && (pInformation->USBwIndex == 0)) /*call Back usb spec 2.0*/ - { - pInformation->Current_Configuration = pInformation->USBwValue0; - pUser_Standard_Requests->User_SetConfiguration(); - return USB_SUCCESS; - } - else - { - return USB_UNSUPPORT; - } -} - -/******************************************************************************* -* Function Name : Standard_GetInterface. -* Description : Return the Alternate Setting of the current interface. -* Input : Length - How many bytes are needed. -* Output : None. -* Return : Return 0, if the request is invalid when "Length" is 0. -* Return "Buffer" if the "Length" is not 0. -*******************************************************************************/ -const uint8_t *Standard_GetInterface(uint16_t Length) -{ - if (Length == 0) - { - pInformation->Ctrl_Info.Usb_wLength = - sizeof(pInformation->Current_AlternateSetting); - return 0; - } - pUser_Standard_Requests->User_GetInterface(); - return (uint8_t *)&pInformation->Current_AlternateSetting; -} - -/******************************************************************************* -* Function Name : Standard_SetInterface. -* Description : This routine is called to set the interface. -* Then each class should configure the interface them self. -* Input : None. -* Output : None. -* Return : - Return USB_SUCCESS, if the request is performed. -* - Return USB_UNSUPPORT, if the request is invalid. -*******************************************************************************/ -RESULT Standard_SetInterface(void) -{ - RESULT Re; - /*Test if the specified Interface and Alternate Setting are supported by - the application Firmware*/ - Re = (*pProperty->Class_Get_Interface_Setting)(pInformation->USBwIndex0, pInformation->USBwValue0); - - if (pInformation->Current_Configuration != 0) - { - if ((Re != USB_SUCCESS) || (pInformation->USBwIndex1 != 0) - || (pInformation->USBwValue1 != 0)) - { - return USB_UNSUPPORT; - } - else if (Re == USB_SUCCESS) - { - pUser_Standard_Requests->User_SetInterface(); - pInformation->Current_Interface = pInformation->USBwIndex0; - pInformation->Current_AlternateSetting = pInformation->USBwValue0; - return USB_SUCCESS; - } - - } - - return USB_UNSUPPORT; -} - -/******************************************************************************* -* Function Name : Standard_GetStatus. -* Description : Copy the device request data to "StatusInfo buffer". -* Input : - Length - How many bytes are needed. -* Output : None. -* Return : Return 0, if the request is at end of data block, -* or is invalid when "Length" is 0. -*******************************************************************************/ -const uint8_t *Standard_GetStatus(uint16_t Length) -{ - if (Length == 0) - { - pInformation->Ctrl_Info.Usb_wLength = 2; - return 0; - } - - /* Reset Status Information */ - StatusInfo.w = 0; - - if (Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT)) - { - /*Get Device Status */ - uint8_t Feature = pInformation->Current_Feature; - - /* Remote Wakeup enabled */ - if (ValBit(Feature, 5)) - { - SetBit(StatusInfo0, 1); - } - else - { - ClrBit(StatusInfo0, 1); - } - - /* Bus-powered */ - if (ValBit(Feature, 6)) - { - SetBit(StatusInfo0, 0); - } - else /* Self-powered */ - { - ClrBit(StatusInfo0, 0); - } - } - /*Interface Status*/ - else if (Type_Recipient == (STANDARD_REQUEST | INTERFACE_RECIPIENT)) - { - return (uint8_t *)&StatusInfo; - } - /*Get EndPoint Status*/ - else if (Type_Recipient == (STANDARD_REQUEST | ENDPOINT_RECIPIENT)) - { - uint8_t Related_Endpoint; - uint8_t wIndex0 = pInformation->USBwIndex0; - - Related_Endpoint = (wIndex0 & 0x0f); - if (ValBit(wIndex0, 7)) - { - /* IN endpoint */ - if (_GetTxStallStatus(Related_Endpoint)) - { - SetBit(StatusInfo0, 0); /* IN Endpoint stalled */ - } - } - else - { - /* OUT endpoint */ - if (_GetRxStallStatus(Related_Endpoint)) - { - SetBit(StatusInfo0, 0); /* OUT Endpoint stalled */ - } - } - - } - else - { - return NULL; - } - pUser_Standard_Requests->User_GetStatus(); - return (uint8_t *)&StatusInfo; -} - -/******************************************************************************* -* Function Name : Standard_ClearFeature. -* Description : Clear or disable a specific feature. -* Input : None. -* Output : None. -* Return : - Return USB_SUCCESS, if the request is performed. -* - Return USB_UNSUPPORT, if the request is invalid. -*******************************************************************************/ -RESULT Standard_ClearFeature(void) -{ - uint32_t Type_Rec = Type_Recipient; - uint32_t Status; - - - if (Type_Rec == (STANDARD_REQUEST | DEVICE_RECIPIENT)) - {/*Device Clear Feature*/ - ClrBit(pInformation->Current_Feature, 5); - return USB_SUCCESS; - } - else if (Type_Rec == (STANDARD_REQUEST | ENDPOINT_RECIPIENT)) - {/*EndPoint Clear Feature*/ - DEVICE* pDev; - uint32_t Related_Endpoint; - uint32_t wIndex0; - uint32_t rEP; - - if ((pInformation->USBwValue != ENDPOINT_STALL) - || (pInformation->USBwIndex1 != 0)) - { - return USB_UNSUPPORT; - } - - pDev = &Device_Table; - wIndex0 = pInformation->USBwIndex0; - rEP = wIndex0 & ~0x80; - Related_Endpoint = ENDP0 + rEP; - - if (ValBit(pInformation->USBwIndex0, 7)) - { - /*Get Status of endpoint & stall the request if the related_ENdpoint - is Disabled*/ - Status = _GetEPTxStatus(Related_Endpoint); - } - else - { - Status = _GetEPRxStatus(Related_Endpoint); - } - - if ((rEP >= pDev->Total_Endpoint) || (Status == 0) - || (pInformation->Current_Configuration == 0)) - { - return USB_UNSUPPORT; - } - - - if (wIndex0 & 0x80) - { - /* IN endpoint */ - if (_GetTxStallStatus(Related_Endpoint )) - { - #ifndef STM32F10X_CL - ClearDTOG_TX(Related_Endpoint); - #endif /* STM32F10X_CL */ - SetEPTxStatus(Related_Endpoint, EP_TX_VALID); - } - } - else - { - /* OUT endpoint */ - if (_GetRxStallStatus(Related_Endpoint)) - { - if (Related_Endpoint == ENDP0) - { - /* After clear the STALL, enable the default endpoint receiver */ - SetEPRxCount(Related_Endpoint, Device_Property.MaxPacketSize); - _SetEPRxStatus(Related_Endpoint, EP_RX_VALID); - } - else - { - #ifndef STM32F10X_CL - ClearDTOG_RX(Related_Endpoint); - #endif /* STM32F10X_CL */ - _SetEPRxStatus(Related_Endpoint, EP_RX_VALID); - } - } - } - pUser_Standard_Requests->User_ClearFeature(); - return USB_SUCCESS; - } - - return USB_UNSUPPORT; -} - -/******************************************************************************* -* Function Name : Standard_SetEndPointFeature -* Description : Set or enable a specific feature of EndPoint -* Input : None. -* Output : None. -* Return : - Return USB_SUCCESS, if the request is performed. -* - Return USB_UNSUPPORT, if the request is invalid. -*******************************************************************************/ -RESULT Standard_SetEndPointFeature(void) -{ - uint32_t wIndex0; - uint32_t Related_Endpoint; - uint32_t rEP; - uint32_t Status; - - wIndex0 = pInformation->USBwIndex0; - rEP = wIndex0 & ~0x80; - Related_Endpoint = ENDP0 + rEP; - - if (ValBit(pInformation->USBwIndex0, 7)) - { - /* get Status of endpoint & stall the request if the related_ENdpoint - is Disabled*/ - Status = _GetEPTxStatus(Related_Endpoint); - } - else - { - Status = _GetEPRxStatus(Related_Endpoint); - } - - if (Related_Endpoint >= Device_Table.Total_Endpoint - || pInformation->USBwValue != 0 || Status == 0 - || pInformation->Current_Configuration == 0) - { - return USB_UNSUPPORT; - } - else - { - if (wIndex0 & 0x80) - { - /* IN endpoint */ - _SetEPTxStatus(Related_Endpoint, EP_TX_STALL); - } - - else - { - /* OUT endpoint */ - _SetEPRxStatus(Related_Endpoint, EP_RX_STALL); - } - } - pUser_Standard_Requests->User_SetEndPointFeature(); - return USB_SUCCESS; -} - -/******************************************************************************* -* Function Name : Standard_SetDeviceFeature. -* Description : Set or enable a specific feature of Device. -* Input : None. -* Output : None. -* Return : - Return USB_SUCCESS, if the request is performed. -* - Return USB_UNSUPPORT, if the request is invalid. -*******************************************************************************/ -RESULT Standard_SetDeviceFeature(void) -{ - SetBit(pInformation->Current_Feature, 5); - pUser_Standard_Requests->User_SetDeviceFeature(); - return USB_SUCCESS; -} - -/******************************************************************************* -* Function Name : Standard_GetDescriptorData. -* Description : Standard_GetDescriptorData is used for descriptors transfer. -* : This routine is used for the descriptors resident in Flash -* or RAM -* pDesc can be in either Flash or RAM -* The purpose of this routine is to have a versatile way to -* response descriptors request. It allows user to generate -* certain descriptors with software or read descriptors from -* external storage part by part. -* Input : - Length - Length of the data in this transfer. -* - pDesc - A pointer points to descriptor struct. -* The structure gives the initial address of the descriptor and -* its original size. -* Output : None. -* Return : Address of a part of the descriptor pointed by the Usb_ -* wOffset The buffer pointed by this address contains at least -* Length bytes. -*******************************************************************************/ -const uint8_t *Standard_GetDescriptorData(uint16_t Length, PONE_DESCRIPTOR pDesc) -{ - uint32_t wOffset; - - wOffset = pInformation->Ctrl_Info.Usb_wOffset; - if (Length == 0) - { - pInformation->Ctrl_Info.Usb_wLength = pDesc->Descriptor_Size - wOffset; - return 0; - } - - return pDesc->Descriptor + wOffset; -} - -/******************************************************************************* -* Function Name : DataStageOut. -* Description : Data stage of a Control Write Transfer. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void DataStageOut(void) -{ - ENDPOINT_INFO *pEPinfo = &pInformation->Ctrl_Info; - uint32_t save_rLength; - - save_rLength = pEPinfo->Usb_rLength; - - if (pEPinfo->CopyDataOut && save_rLength) - { - uint8_t *Buffer; - uint32_t Length; - - Length = pEPinfo->PacketSize; - if (Length > save_rLength) - { - Length = save_rLength; - } - - Buffer = (*pEPinfo->CopyDataOut)(Length); - pEPinfo->Usb_rLength -= Length; - pEPinfo->Usb_rOffset += Length; - - #ifdef STM32F10X_CL - PCD_EP_Read(ENDP0, Buffer, Length); - #else - PMAToUserBufferCopy(Buffer, GetEPRxAddr(ENDP0), Length); - #endif /* STM32F10X_CL */ - } - - if (pEPinfo->Usb_rLength != 0) - { - vSetEPRxStatus(EP_RX_VALID);/* re-enable for next data reception */ - SetEPTxCount(ENDP0, 0); - vSetEPTxStatus(EP_TX_VALID);/* Expect the host to abort the data OUT stage */ - } - /* Set the next State*/ - if (pEPinfo->Usb_rLength >= pEPinfo->PacketSize) - { - pInformation->ControlState = OUT_DATA; - } - else - { - if (pEPinfo->Usb_rLength > 0) - { - pInformation->ControlState = LAST_OUT_DATA; - } - else if (pEPinfo->Usb_rLength == 0) - { - pInformation->ControlState = WAIT_STATUS_IN; - USB_StatusIn(); - } - } -} - -/******************************************************************************* -* Function Name : DataStageIn. -* Description : Data stage of a Control Read Transfer. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void DataStageIn(void) -{ - ENDPOINT_INFO *pEPinfo = &pInformation->Ctrl_Info; - uint32_t save_wLength = pEPinfo->Usb_wLength; - uint32_t ControlState = pInformation->ControlState; - - const uint8_t *DataBuffer; - uint32_t Length; - - if ((save_wLength == 0) && (ControlState == LAST_IN_DATA)) - { - if(Data_Mul_MaxPacketSize == TRUE) - { - /* No more data to send and empty packet */ - Send0LengthData(); - ControlState = LAST_IN_DATA; - Data_Mul_MaxPacketSize = FALSE; - } - else - { - /* No more data to send so STALL the TX Status*/ - ControlState = WAIT_STATUS_OUT; - - #ifdef STM32F10X_CL - PCD_EP_Read (ENDP0, 0, 0); - #endif /* STM32F10X_CL */ - - #ifndef STM32F10X_CL - vSetEPTxStatus(EP_TX_STALL); - #endif /* STM32F10X_CL */ - } - - goto Expect_Status_Out; - } - - Length = pEPinfo->PacketSize; - ControlState = (save_wLength <= Length) ? LAST_IN_DATA : IN_DATA; - - if (Length > save_wLength) - { - Length = save_wLength; - } - - DataBuffer = (*pEPinfo->CopyDataIn)(Length); - -#ifdef STM32F10X_CL - PCD_EP_Write (ENDP0, DataBuffer, Length); -#else - UserToPMABufferCopy(DataBuffer, GetEPTxAddr(ENDP0), Length); -#endif /* STM32F10X_CL */ - - SetEPTxCount(ENDP0, Length); - - pEPinfo->Usb_wLength -= Length; - pEPinfo->Usb_wOffset += Length; - vSetEPTxStatus(EP_TX_VALID); - - USB_StatusOut();/* Expect the host to abort the data IN stage */ - -Expect_Status_Out: - pInformation->ControlState = ControlState; -} - -/******************************************************************************* -* Function Name : NoData_Setup0. -* Description : Proceed the processing of setup request without data stage. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void NoData_Setup0(void) -{ - RESULT Result = USB_UNSUPPORT; - uint32_t RequestNo = pInformation->USBbRequest; - uint32_t ControlState; - - if (Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT)) - { - /* Device Request*/ - /* SET_CONFIGURATION*/ - if (RequestNo == SET_CONFIGURATION) - { - Result = Standard_SetConfiguration(); - } - - /*SET ADDRESS*/ - else if (RequestNo == SET_ADDRESS) - { - if ((pInformation->USBwValue0 > 127) || (pInformation->USBwValue1 != 0) - || (pInformation->USBwIndex != 0) - || (pInformation->Current_Configuration != 0)) - /* Device Address should be 127 or less*/ - { - ControlState = STALLED; - goto exit_NoData_Setup0; - } - else - { - Result = USB_SUCCESS; - - #ifdef STM32F10X_CL - SetDeviceAddress(pInformation->USBwValue0); - #endif /* STM32F10X_CL */ - } - } - /*SET FEATURE for Device*/ - else if (RequestNo == SET_FEATURE) - { - if ((pInformation->USBwValue0 == DEVICE_REMOTE_WAKEUP) - && (pInformation->USBwIndex == 0) - && (ValBit(pInformation->Current_Feature, 5))) - { - Result = Standard_SetDeviceFeature(); - } - else - { - Result = USB_UNSUPPORT; - } - } - /*Clear FEATURE for Device */ - else if (RequestNo == CLEAR_FEATURE) - { - if (pInformation->USBwValue0 == DEVICE_REMOTE_WAKEUP - && pInformation->USBwIndex == 0 - && ValBit(pInformation->Current_Feature, 5)) - { - Result = Standard_ClearFeature(); - } - else - { - Result = USB_UNSUPPORT; - } - } - - } - - /* Interface Request*/ - else if (Type_Recipient == (STANDARD_REQUEST | INTERFACE_RECIPIENT)) - { - /*SET INTERFACE*/ - if (RequestNo == SET_INTERFACE) - { - Result = Standard_SetInterface(); - } - } - - /* EndPoint Request*/ - else if (Type_Recipient == (STANDARD_REQUEST | ENDPOINT_RECIPIENT)) - { - /*CLEAR FEATURE for EndPoint*/ - if (RequestNo == CLEAR_FEATURE) - { - Result = Standard_ClearFeature(); - } - /* SET FEATURE for EndPoint*/ - else if (RequestNo == SET_FEATURE) - { - Result = Standard_SetEndPointFeature(); - } - } - else - { - Result = USB_UNSUPPORT; - } - - - if (Result != USB_SUCCESS) - { - Result = (*pProperty->Class_NoData_Setup)(RequestNo); - if (Result == USB_NOT_READY) - { - ControlState = PAUSE; - goto exit_NoData_Setup0; - } - } - - if (Result != USB_SUCCESS) - { - ControlState = STALLED; - goto exit_NoData_Setup0; - } - - ControlState = WAIT_STATUS_IN;/* After no data stage SETUP */ - - USB_StatusIn(); - -exit_NoData_Setup0: - pInformation->ControlState = ControlState; - return; -} - -/******************************************************************************* -* Function Name : Data_Setup0. -* Description : Proceed the processing of setup request with data stage. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void Data_Setup0(void) -{ - const uint8_t *(*CopyRoutine)(uint16_t); - RESULT Result; - uint32_t Request_No = pInformation->USBbRequest; - - uint32_t Related_Endpoint, Reserved; - uint32_t wOffset, Status; - - - - CopyRoutine = NULL; - wOffset = 0; - - /*GET DESCRIPTOR*/ - if (Request_No == GET_DESCRIPTOR) - { - if (Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT)) - { - uint8_t wValue1 = pInformation->USBwValue1; - if (wValue1 == DEVICE_DESCRIPTOR) - { - CopyRoutine = pProperty->GetDeviceDescriptor; - } - else if (wValue1 == CONFIG_DESCRIPTOR) - { - CopyRoutine = pProperty->GetConfigDescriptor; - } - else if (wValue1 == STRING_DESCRIPTOR) - { - CopyRoutine = pProperty->GetStringDescriptor; - } /* End of GET_DESCRIPTOR */ - } - } - - /*GET STATUS*/ - else if ((Request_No == GET_STATUS) && (pInformation->USBwValue == 0) - && (pInformation->USBwLength == 0x0002) - && (pInformation->USBwIndex1 == 0)) - { - /* GET STATUS for Device*/ - if ((Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT)) - && (pInformation->USBwIndex == 0)) - { - CopyRoutine = Standard_GetStatus; - } - - /* GET STATUS for Interface*/ - else if (Type_Recipient == (STANDARD_REQUEST | INTERFACE_RECIPIENT)) - { - if (((*pProperty->Class_Get_Interface_Setting)(pInformation->USBwIndex0, 0) == USB_SUCCESS) - && (pInformation->Current_Configuration != 0)) - { - CopyRoutine = Standard_GetStatus; - } - } - - /* GET STATUS for EndPoint*/ - else if (Type_Recipient == (STANDARD_REQUEST | ENDPOINT_RECIPIENT)) - { - Related_Endpoint = (pInformation->USBwIndex0 & 0x0f); - Reserved = pInformation->USBwIndex0 & 0x70; - - if (ValBit(pInformation->USBwIndex0, 7)) - { - /*Get Status of endpoint & stall the request if the related_ENdpoint - is Disabled*/ - Status = _GetEPTxStatus(Related_Endpoint); - } - else - { - Status = _GetEPRxStatus(Related_Endpoint); - } - - if ((Related_Endpoint < Device_Table.Total_Endpoint) && (Reserved == 0) - && (Status != 0)) - { - CopyRoutine = Standard_GetStatus; - } - } - - } - - /*GET CONFIGURATION*/ - else if (Request_No == GET_CONFIGURATION) - { - if (Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT)) - { - CopyRoutine = Standard_GetConfiguration; - } - } - /*GET INTERFACE*/ - else if (Request_No == GET_INTERFACE) - { - if ((Type_Recipient == (STANDARD_REQUEST | INTERFACE_RECIPIENT)) - && (pInformation->Current_Configuration != 0) && (pInformation->USBwValue == 0) - && (pInformation->USBwIndex1 == 0) && (pInformation->USBwLength == 0x0001) - && ((*pProperty->Class_Get_Interface_Setting)(pInformation->USBwIndex0, 0) == USB_SUCCESS)) - { - CopyRoutine = Standard_GetInterface; - } - - } - - if (CopyRoutine) - { - pInformation->Ctrl_Info.Usb_wOffset = wOffset; - pInformation->Ctrl_Info.CopyDataIn = CopyRoutine; - /* sb in the original the cast to word was directly */ - /* now the cast is made step by step */ - (*CopyRoutine)(0); - Result = USB_SUCCESS; - } - else - { - Result = (*pProperty->Class_Data_Setup)(pInformation->USBbRequest); - if (Result == USB_NOT_READY) - { - pInformation->ControlState = PAUSE; - return; - } - } - - if (pInformation->Ctrl_Info.Usb_wLength == 0xFFFF) - { - /* Data is not ready, wait it */ - pInformation->ControlState = PAUSE; - return; - } - if ((Result == USB_UNSUPPORT) || (pInformation->Ctrl_Info.Usb_wLength == 0)) - { - /* Unsupported request */ - pInformation->ControlState = STALLED; - return; - } - - - if (ValBit(pInformation->USBbmRequestType, 7)) - { - /* Device ==> Host */ - __IO uint32_t wLength = pInformation->USBwLength; - - /* Restrict the data length to be the one host asks for */ - if (pInformation->Ctrl_Info.Usb_wLength > wLength) - { - pInformation->Ctrl_Info.Usb_wLength = wLength; - } - - else if (pInformation->Ctrl_Info.Usb_wLength < pInformation->USBwLength) - { - if (pInformation->Ctrl_Info.Usb_wLength < pProperty->MaxPacketSize) - { - Data_Mul_MaxPacketSize = FALSE; - } - else if ((pInformation->Ctrl_Info.Usb_wLength % pProperty->MaxPacketSize) == 0) - { - Data_Mul_MaxPacketSize = TRUE; - } - } - - pInformation->Ctrl_Info.PacketSize = pProperty->MaxPacketSize; - DataStageIn(); - } - else - { - pInformation->ControlState = OUT_DATA; - vSetEPRxStatus(EP_RX_VALID); /* enable for next data reception */ - } - - return; -} - -/******************************************************************************* -* Function Name : Setup0_Process -* Description : Get the device request data and dispatch to individual process. -* Input : None. -* Output : None. -* Return : Post0_Process. -*******************************************************************************/ -uint8_t Setup0_Process(void) -{ - - union - { - uint8_t* b; - uint16_t* w; - } pBuf; - -#ifdef STM32F10X_CL - USB_OTG_EP *ep; - uint16_t offset = 0; - - ep = PCD_GetOutEP(ENDP0); - pBuf.b = ep->xfer_buff; -#else - uint16_t offset = 1; - - pBuf.b = PMAAddr + (uint8_t *)(_GetEPRxAddr(ENDP0) * 2); /* *2 for 32 bits addr */ -#endif /* STM32F10X_CL */ - - if (pInformation->ControlState != PAUSE) - { - pInformation->USBbmRequestType = *pBuf.b++; /* bmRequestType */ - pInformation->USBbRequest = *pBuf.b++; /* bRequest */ - pBuf.w += offset; /* word not accessed because of 32 bits addressing */ - pInformation->USBwValue = ByteSwap(*pBuf.w++); /* wValue */ - pBuf.w += offset; /* word not accessed because of 32 bits addressing */ - pInformation->USBwIndex = ByteSwap(*pBuf.w++); /* wIndex */ - pBuf.w += offset; /* word not accessed because of 32 bits addressing */ - pInformation->USBwLength = *pBuf.w; /* wLength */ - } - - pInformation->ControlState = SETTING_UP; - if (pInformation->USBwLength == 0) - { - /* Setup with no data stage */ - NoData_Setup0(); - } - else - { - /* Setup with data stage */ - Data_Setup0(); - } - return Post0_Process(); -} - -/******************************************************************************* -* Function Name : In0_Process -* Description : Process the IN token on all default endpoint. -* Input : None. -* Output : None. -* Return : Post0_Process. -*******************************************************************************/ -uint8_t In0_Process(void) -{ - uint32_t ControlState = pInformation->ControlState; - - if ((ControlState == IN_DATA) || (ControlState == LAST_IN_DATA)) - { - DataStageIn(); - /* ControlState may be changed outside the function */ - ControlState = pInformation->ControlState; - } - - else if (ControlState == WAIT_STATUS_IN) - { - if ((pInformation->USBbRequest == SET_ADDRESS) && - (Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT))) - { - SetDeviceAddress(pInformation->USBwValue0); - pUser_Standard_Requests->User_SetDeviceAddress(); - } - (*pProperty->Process_Status_IN)(); - ControlState = STALLED; - } - - else - { - ControlState = STALLED; - } - - pInformation->ControlState = ControlState; - - return Post0_Process(); -} - -/******************************************************************************* -* Function Name : Out0_Process -* Description : Process the OUT token on all default endpoint. -* Input : None. -* Output : None. -* Return : Post0_Process. -*******************************************************************************/ -uint8_t Out0_Process(void) -{ - uint32_t ControlState = pInformation->ControlState; - - if ((ControlState == IN_DATA) || (ControlState == LAST_IN_DATA)) - { - /* host aborts the transfer before finish */ - ControlState = STALLED; - } - else if ((ControlState == OUT_DATA) || (ControlState == LAST_OUT_DATA)) - { - DataStageOut(); - ControlState = pInformation->ControlState; /* may be changed outside the function */ - } - - else if (ControlState == WAIT_STATUS_OUT) - { - (*pProperty->Process_Status_OUT)(); - #ifndef STM32F10X_CL - ControlState = STALLED; - #endif /* STM32F10X_CL */ - } - - - /* Unexpect state, STALL the endpoint */ - else - { - ControlState = STALLED; - } - - pInformation->ControlState = ControlState; - - return Post0_Process(); -} - -/******************************************************************************* -* Function Name : Post0_Process -* Description : Stall the Endpoint 0 in case of error. -* Input : None. -* Output : None. -* Return : - 0 if the control State is in PAUSE -* - 1 if not. -*******************************************************************************/ -uint8_t Post0_Process(void) -{ -#ifdef STM32F10X_CL - USB_OTG_EP *ep; -#endif /* STM32F10X_CL */ - - SetEPRxCount(ENDP0, Device_Property.MaxPacketSize); - - if (pInformation->ControlState == STALLED) - { - vSetEPRxStatus(EP_RX_STALL); - vSetEPTxStatus(EP_TX_STALL); - } - -#ifdef STM32F10X_CL - else if ((pInformation->ControlState == OUT_DATA) || - (pInformation->ControlState == WAIT_STATUS_OUT)) - { - ep = PCD_GetInEP(0); - ep->is_in = 0; - OTGD_FS_EP0StartXfer(ep); - - vSetEPTxStatus(EP_TX_VALID); - } - - else if ((pInformation->ControlState == IN_DATA) || - (pInformation->ControlState == WAIT_STATUS_IN)) - { - ep = PCD_GetInEP(0); - ep->is_in = 1; - OTGD_FS_EP0StartXfer(ep); - } -#endif /* STM32F10X_CL */ - - return (pInformation->ControlState == PAUSE); -} - -/******************************************************************************* -* Function Name : SetDeviceAddress. -* Description : Set the device and all the used Endpoints addresses. -* Input : - Val: device adress. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetDeviceAddress(uint8_t Val) -{ -#ifdef STM32F10X_CL - PCD_EP_SetAddress ((uint8_t)Val); -#else - uint32_t i; - uint32_t nEP = Device_Table.Total_Endpoint; - - /* set address in every used endpoint */ - for (i = 0; i < nEP; i++) - { - _SetEPAddress((uint8_t)i, (uint8_t)i); - } /* for */ - _SetDADDR(Val | DADDR_EF); /* set device address and enable function */ -#endif /* STM32F10X_CL */ -} - -/******************************************************************************* -* Function Name : NOP_Process -* Description : No operation function. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void NOP_Process(void) -{ -} - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_core.c +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Standard protocol processing (USB v2.0) +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_lib.h" +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +#define ValBit(VAR,Place) (VAR & (1 << Place)) +#define SetBit(VAR,Place) (VAR |= (1 << Place)) +#define ClrBit(VAR,Place) (VAR &= ((1 << Place) ^ 255)) + +#ifdef STM32F10X_CL + #define Send0LengthData() {PCD_EP_Write (0, 0, 0) ; vSetEPTxStatus(EP_TX_VALID);} +#else +#define Send0LengthData() { _SetEPTxCount(ENDP0, 0); \ + vSetEPTxStatus(EP_TX_VALID); \ + } +#endif /* STM32F10X_CL */ + +#define vSetEPRxStatus(st) (SaveRState = st) +#define vSetEPTxStatus(st) (SaveTState = st) + +#define USB_StatusIn() Send0LengthData() +#define USB_StatusOut() vSetEPRxStatus(EP_RX_VALID) + +#define StatusInfo0 StatusInfo.bw.bb1 /* Reverse bb0 & bb1 */ +#define StatusInfo1 StatusInfo.bw.bb0 + +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +uint16_t_uint8_t StatusInfo; + +bool Data_Mul_MaxPacketSize = FALSE; +/* Private function prototypes -----------------------------------------------*/ +static void DataStageOut(void); +static void DataStageIn(void); +static void NoData_Setup0(void); +static void Data_Setup0(void); +/* Private functions ---------------------------------------------------------*/ + +/******************************************************************************* +* Function Name : Standard_GetConfiguration. +* Description : Return the current configuration variable address. +* Input : Length - How many bytes are needed. +* Output : None. +* Return : Return 1 , if the request is invalid when "Length" is 0. +* Return "Buffer" if the "Length" is not 0. +*******************************************************************************/ +const uint8_t *Standard_GetConfiguration(uint16_t Length) +{ + if (Length == 0) + { + pInformation->Ctrl_Info.Usb_wLength = + sizeof(pInformation->Current_Configuration); + return 0; + } + pUser_Standard_Requests->User_GetConfiguration(); + return (uint8_t *)&pInformation->Current_Configuration; +} + +/******************************************************************************* +* Function Name : Standard_SetConfiguration. +* Description : This routine is called to set the configuration value +* Then each class should configure device themself. +* Input : None. +* Output : None. +* Return : Return USB_SUCCESS, if the request is performed. +* Return USB_UNSUPPORT, if the request is invalid. +*******************************************************************************/ +RESULT Standard_SetConfiguration(void) +{ + + if ((pInformation->USBwValue0 <= + Device_Table.Total_Configuration) && (pInformation->USBwValue1 == 0) + && (pInformation->USBwIndex == 0)) /*call Back usb spec 2.0*/ + { + pInformation->Current_Configuration = pInformation->USBwValue0; + pUser_Standard_Requests->User_SetConfiguration(); + return USB_SUCCESS; + } + else + { + return USB_UNSUPPORT; + } +} + +/******************************************************************************* +* Function Name : Standard_GetInterface. +* Description : Return the Alternate Setting of the current interface. +* Input : Length - How many bytes are needed. +* Output : None. +* Return : Return 0, if the request is invalid when "Length" is 0. +* Return "Buffer" if the "Length" is not 0. +*******************************************************************************/ +const uint8_t *Standard_GetInterface(uint16_t Length) +{ + if (Length == 0) + { + pInformation->Ctrl_Info.Usb_wLength = + sizeof(pInformation->Current_AlternateSetting); + return 0; + } + pUser_Standard_Requests->User_GetInterface(); + return (uint8_t *)&pInformation->Current_AlternateSetting; +} + +/******************************************************************************* +* Function Name : Standard_SetInterface. +* Description : This routine is called to set the interface. +* Then each class should configure the interface them self. +* Input : None. +* Output : None. +* Return : - Return USB_SUCCESS, if the request is performed. +* - Return USB_UNSUPPORT, if the request is invalid. +*******************************************************************************/ +RESULT Standard_SetInterface(void) +{ + RESULT Re; + /*Test if the specified Interface and Alternate Setting are supported by + the application Firmware*/ + Re = (*pProperty->Class_Get_Interface_Setting)(pInformation->USBwIndex0, pInformation->USBwValue0); + + if (pInformation->Current_Configuration != 0) + { + if ((Re != USB_SUCCESS) || (pInformation->USBwIndex1 != 0) + || (pInformation->USBwValue1 != 0)) + { + return USB_UNSUPPORT; + } + else if (Re == USB_SUCCESS) + { + pUser_Standard_Requests->User_SetInterface(); + pInformation->Current_Interface = pInformation->USBwIndex0; + pInformation->Current_AlternateSetting = pInformation->USBwValue0; + return USB_SUCCESS; + } + + } + + return USB_UNSUPPORT; +} + +/******************************************************************************* +* Function Name : Standard_GetStatus. +* Description : Copy the device request data to "StatusInfo buffer". +* Input : - Length - How many bytes are needed. +* Output : None. +* Return : Return 0, if the request is at end of data block, +* or is invalid when "Length" is 0. +*******************************************************************************/ +const uint8_t *Standard_GetStatus(uint16_t Length) +{ + if (Length == 0) + { + pInformation->Ctrl_Info.Usb_wLength = 2; + return 0; + } + + /* Reset Status Information */ + StatusInfo.w = 0; + + if (Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT)) + { + /*Get Device Status */ + uint8_t Feature = pInformation->Current_Feature; + + /* Remote Wakeup enabled */ + if (ValBit(Feature, 5)) + { + SetBit(StatusInfo0, 1); + } + else + { + ClrBit(StatusInfo0, 1); + } + + /* Bus-powered */ + if (ValBit(Feature, 6)) + { + SetBit(StatusInfo0, 0); + } + else /* Self-powered */ + { + ClrBit(StatusInfo0, 0); + } + } + /*Interface Status*/ + else if (Type_Recipient == (STANDARD_REQUEST | INTERFACE_RECIPIENT)) + { + return (uint8_t *)&StatusInfo; + } + /*Get EndPoint Status*/ + else if (Type_Recipient == (STANDARD_REQUEST | ENDPOINT_RECIPIENT)) + { + uint8_t Related_Endpoint; + uint8_t wIndex0 = pInformation->USBwIndex0; + + Related_Endpoint = (wIndex0 & 0x0f); + if (ValBit(wIndex0, 7)) + { + /* IN endpoint */ + if (_GetTxStallStatus(Related_Endpoint)) + { + SetBit(StatusInfo0, 0); /* IN Endpoint stalled */ + } + } + else + { + /* OUT endpoint */ + if (_GetRxStallStatus(Related_Endpoint)) + { + SetBit(StatusInfo0, 0); /* OUT Endpoint stalled */ + } + } + + } + else + { + return NULL; + } + pUser_Standard_Requests->User_GetStatus(); + return (uint8_t *)&StatusInfo; +} + +/******************************************************************************* +* Function Name : Standard_ClearFeature. +* Description : Clear or disable a specific feature. +* Input : None. +* Output : None. +* Return : - Return USB_SUCCESS, if the request is performed. +* - Return USB_UNSUPPORT, if the request is invalid. +*******************************************************************************/ +RESULT Standard_ClearFeature(void) +{ + uint32_t Type_Rec = Type_Recipient; + uint32_t Status; + + + if (Type_Rec == (STANDARD_REQUEST | DEVICE_RECIPIENT)) + {/*Device Clear Feature*/ + ClrBit(pInformation->Current_Feature, 5); + return USB_SUCCESS; + } + else if (Type_Rec == (STANDARD_REQUEST | ENDPOINT_RECIPIENT)) + {/*EndPoint Clear Feature*/ + DEVICE* pDev; + uint32_t Related_Endpoint; + uint32_t wIndex0; + uint32_t rEP; + + if ((pInformation->USBwValue != ENDPOINT_STALL) + || (pInformation->USBwIndex1 != 0)) + { + return USB_UNSUPPORT; + } + + pDev = &Device_Table; + wIndex0 = pInformation->USBwIndex0; + rEP = wIndex0 & ~0x80; + Related_Endpoint = ENDP0 + rEP; + + if (ValBit(pInformation->USBwIndex0, 7)) + { + /*Get Status of endpoint & stall the request if the related_ENdpoint + is Disabled*/ + Status = _GetEPTxStatus(Related_Endpoint); + } + else + { + Status = _GetEPRxStatus(Related_Endpoint); + } + + if ((rEP >= pDev->Total_Endpoint) || (Status == 0) + || (pInformation->Current_Configuration == 0)) + { + return USB_UNSUPPORT; + } + + + if (wIndex0 & 0x80) + { + /* IN endpoint */ + if (_GetTxStallStatus(Related_Endpoint )) + { + #ifndef STM32F10X_CL + ClearDTOG_TX(Related_Endpoint); + #endif /* STM32F10X_CL */ + SetEPTxStatus(Related_Endpoint, EP_TX_VALID); + } + } + else + { + /* OUT endpoint */ + if (_GetRxStallStatus(Related_Endpoint)) + { + if (Related_Endpoint == ENDP0) + { + /* After clear the STALL, enable the default endpoint receiver */ + SetEPRxCount(Related_Endpoint, Device_Property.MaxPacketSize); + _SetEPRxStatus(Related_Endpoint, EP_RX_VALID); + } + else + { + #ifndef STM32F10X_CL + ClearDTOG_RX(Related_Endpoint); + #endif /* STM32F10X_CL */ + _SetEPRxStatus(Related_Endpoint, EP_RX_VALID); + } + } + } + pUser_Standard_Requests->User_ClearFeature(); + return USB_SUCCESS; + } + + return USB_UNSUPPORT; +} + +/******************************************************************************* +* Function Name : Standard_SetEndPointFeature +* Description : Set or enable a specific feature of EndPoint +* Input : None. +* Output : None. +* Return : - Return USB_SUCCESS, if the request is performed. +* - Return USB_UNSUPPORT, if the request is invalid. +*******************************************************************************/ +RESULT Standard_SetEndPointFeature(void) +{ + uint32_t wIndex0; + uint32_t Related_Endpoint; + uint32_t rEP; + uint32_t Status; + + wIndex0 = pInformation->USBwIndex0; + rEP = wIndex0 & ~0x80; + Related_Endpoint = ENDP0 + rEP; + + if (ValBit(pInformation->USBwIndex0, 7)) + { + /* get Status of endpoint & stall the request if the related_ENdpoint + is Disabled*/ + Status = _GetEPTxStatus(Related_Endpoint); + } + else + { + Status = _GetEPRxStatus(Related_Endpoint); + } + + if (Related_Endpoint >= Device_Table.Total_Endpoint + || pInformation->USBwValue != 0 || Status == 0 + || pInformation->Current_Configuration == 0) + { + return USB_UNSUPPORT; + } + else + { + if (wIndex0 & 0x80) + { + /* IN endpoint */ + _SetEPTxStatus(Related_Endpoint, EP_TX_STALL); + } + + else + { + /* OUT endpoint */ + _SetEPRxStatus(Related_Endpoint, EP_RX_STALL); + } + } + pUser_Standard_Requests->User_SetEndPointFeature(); + return USB_SUCCESS; +} + +/******************************************************************************* +* Function Name : Standard_SetDeviceFeature. +* Description : Set or enable a specific feature of Device. +* Input : None. +* Output : None. +* Return : - Return USB_SUCCESS, if the request is performed. +* - Return USB_UNSUPPORT, if the request is invalid. +*******************************************************************************/ +RESULT Standard_SetDeviceFeature(void) +{ + SetBit(pInformation->Current_Feature, 5); + pUser_Standard_Requests->User_SetDeviceFeature(); + return USB_SUCCESS; +} + +/******************************************************************************* +* Function Name : Standard_GetDescriptorData. +* Description : Standard_GetDescriptorData is used for descriptors transfer. +* : This routine is used for the descriptors resident in Flash +* or RAM +* pDesc can be in either Flash or RAM +* The purpose of this routine is to have a versatile way to +* response descriptors request. It allows user to generate +* certain descriptors with software or read descriptors from +* external storage part by part. +* Input : - Length - Length of the data in this transfer. +* - pDesc - A pointer points to descriptor struct. +* The structure gives the initial address of the descriptor and +* its original size. +* Output : None. +* Return : Address of a part of the descriptor pointed by the Usb_ +* wOffset The buffer pointed by this address contains at least +* Length bytes. +*******************************************************************************/ +const uint8_t *Standard_GetDescriptorData(uint16_t Length, PONE_DESCRIPTOR pDesc) +{ + uint32_t wOffset; + + wOffset = pInformation->Ctrl_Info.Usb_wOffset; + if (Length == 0) + { + pInformation->Ctrl_Info.Usb_wLength = pDesc->Descriptor_Size - wOffset; + return 0; + } + + return pDesc->Descriptor + wOffset; +} + +/******************************************************************************* +* Function Name : DataStageOut. +* Description : Data stage of a Control Write Transfer. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void DataStageOut(void) +{ + ENDPOINT_INFO *pEPinfo = &pInformation->Ctrl_Info; + uint32_t save_rLength; + + save_rLength = pEPinfo->Usb_rLength; + + if (pEPinfo->CopyDataOut && save_rLength) + { + uint8_t *Buffer; + uint32_t Length; + + Length = pEPinfo->PacketSize; + if (Length > save_rLength) + { + Length = save_rLength; + } + + Buffer = (*pEPinfo->CopyDataOut)(Length); + pEPinfo->Usb_rLength -= Length; + pEPinfo->Usb_rOffset += Length; + + #ifdef STM32F10X_CL + PCD_EP_Read(ENDP0, Buffer, Length); + #else + PMAToUserBufferCopy(Buffer, GetEPRxAddr(ENDP0), Length); + #endif /* STM32F10X_CL */ + } + + if (pEPinfo->Usb_rLength != 0) + { + vSetEPRxStatus(EP_RX_VALID);/* re-enable for next data reception */ + SetEPTxCount(ENDP0, 0); + vSetEPTxStatus(EP_TX_VALID);/* Expect the host to abort the data OUT stage */ + } + /* Set the next State*/ + if (pEPinfo->Usb_rLength >= pEPinfo->PacketSize) + { + pInformation->ControlState = OUT_DATA; + } + else + { + if (pEPinfo->Usb_rLength > 0) + { + pInformation->ControlState = LAST_OUT_DATA; + } + else if (pEPinfo->Usb_rLength == 0) + { + pInformation->ControlState = WAIT_STATUS_IN; + USB_StatusIn(); + } + } +} + +/******************************************************************************* +* Function Name : DataStageIn. +* Description : Data stage of a Control Read Transfer. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void DataStageIn(void) +{ + ENDPOINT_INFO *pEPinfo = &pInformation->Ctrl_Info; + uint32_t save_wLength = pEPinfo->Usb_wLength; + uint32_t ControlState = pInformation->ControlState; + + const uint8_t *DataBuffer; + uint32_t Length; + + if ((save_wLength == 0) && (ControlState == LAST_IN_DATA)) + { + if(Data_Mul_MaxPacketSize == TRUE) + { + /* No more data to send and empty packet */ + Send0LengthData(); + ControlState = LAST_IN_DATA; + Data_Mul_MaxPacketSize = FALSE; + } + else + { + /* No more data to send so STALL the TX Status*/ + ControlState = WAIT_STATUS_OUT; + + #ifdef STM32F10X_CL + PCD_EP_Read (ENDP0, 0, 0); + #endif /* STM32F10X_CL */ + + #ifndef STM32F10X_CL + vSetEPTxStatus(EP_TX_STALL); + #endif /* STM32F10X_CL */ + } + + goto Expect_Status_Out; + } + + Length = pEPinfo->PacketSize; + ControlState = (save_wLength <= Length) ? LAST_IN_DATA : IN_DATA; + + if (Length > save_wLength) + { + Length = save_wLength; + } + + DataBuffer = (*pEPinfo->CopyDataIn)(Length); + +#ifdef STM32F10X_CL + PCD_EP_Write (ENDP0, DataBuffer, Length); +#else + UserToPMABufferCopy(DataBuffer, GetEPTxAddr(ENDP0), Length); +#endif /* STM32F10X_CL */ + + SetEPTxCount(ENDP0, Length); + + pEPinfo->Usb_wLength -= Length; + pEPinfo->Usb_wOffset += Length; + vSetEPTxStatus(EP_TX_VALID); + + USB_StatusOut();/* Expect the host to abort the data IN stage */ + +Expect_Status_Out: + pInformation->ControlState = ControlState; +} + +/******************************************************************************* +* Function Name : NoData_Setup0. +* Description : Proceed the processing of setup request without data stage. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void NoData_Setup0(void) +{ + RESULT Result = USB_UNSUPPORT; + uint32_t RequestNo = pInformation->USBbRequest; + uint32_t ControlState; + + if (Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT)) + { + /* Device Request*/ + /* SET_CONFIGURATION*/ + if (RequestNo == SET_CONFIGURATION) + { + Result = Standard_SetConfiguration(); + } + + /*SET ADDRESS*/ + else if (RequestNo == SET_ADDRESS) + { + if ((pInformation->USBwValue0 > 127) || (pInformation->USBwValue1 != 0) + || (pInformation->USBwIndex != 0) + || (pInformation->Current_Configuration != 0)) + /* Device Address should be 127 or less*/ + { + ControlState = STALLED; + goto exit_NoData_Setup0; + } + else + { + Result = USB_SUCCESS; + + #ifdef STM32F10X_CL + SetDeviceAddress(pInformation->USBwValue0); + #endif /* STM32F10X_CL */ + } + } + /*SET FEATURE for Device*/ + else if (RequestNo == SET_FEATURE) + { + if ((pInformation->USBwValue0 == DEVICE_REMOTE_WAKEUP) + && (pInformation->USBwIndex == 0) + && (ValBit(pInformation->Current_Feature, 5))) + { + Result = Standard_SetDeviceFeature(); + } + else + { + Result = USB_UNSUPPORT; + } + } + /*Clear FEATURE for Device */ + else if (RequestNo == CLEAR_FEATURE) + { + if (pInformation->USBwValue0 == DEVICE_REMOTE_WAKEUP + && pInformation->USBwIndex == 0 + && ValBit(pInformation->Current_Feature, 5)) + { + Result = Standard_ClearFeature(); + } + else + { + Result = USB_UNSUPPORT; + } + } + + } + + /* Interface Request*/ + else if (Type_Recipient == (STANDARD_REQUEST | INTERFACE_RECIPIENT)) + { + /*SET INTERFACE*/ + if (RequestNo == SET_INTERFACE) + { + Result = Standard_SetInterface(); + } + } + + /* EndPoint Request*/ + else if (Type_Recipient == (STANDARD_REQUEST | ENDPOINT_RECIPIENT)) + { + /*CLEAR FEATURE for EndPoint*/ + if (RequestNo == CLEAR_FEATURE) + { + Result = Standard_ClearFeature(); + } + /* SET FEATURE for EndPoint*/ + else if (RequestNo == SET_FEATURE) + { + Result = Standard_SetEndPointFeature(); + } + } + else + { + Result = USB_UNSUPPORT; + } + + + if (Result != USB_SUCCESS) + { + Result = (*pProperty->Class_NoData_Setup)(RequestNo); + if (Result == USB_NOT_READY) + { + ControlState = PAUSE; + goto exit_NoData_Setup0; + } + } + + if (Result != USB_SUCCESS) + { + ControlState = STALLED; + goto exit_NoData_Setup0; + } + + ControlState = WAIT_STATUS_IN;/* After no data stage SETUP */ + + USB_StatusIn(); + +exit_NoData_Setup0: + pInformation->ControlState = ControlState; + return; +} + +/******************************************************************************* +* Function Name : Data_Setup0. +* Description : Proceed the processing of setup request with data stage. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void Data_Setup0(void) +{ + const uint8_t *(*CopyRoutine)(uint16_t); + RESULT Result; + uint32_t Request_No = pInformation->USBbRequest; + + uint32_t Related_Endpoint, Reserved; + uint32_t wOffset, Status; + + + + CopyRoutine = NULL; + wOffset = 0; + + /*GET DESCRIPTOR*/ + if (Request_No == GET_DESCRIPTOR) + { + if (Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT)) + { + uint8_t wValue1 = pInformation->USBwValue1; + if (wValue1 == DEVICE_DESCRIPTOR) + { + CopyRoutine = pProperty->GetDeviceDescriptor; + } + else if (wValue1 == CONFIG_DESCRIPTOR) + { + CopyRoutine = pProperty->GetConfigDescriptor; + } + else if (wValue1 == STRING_DESCRIPTOR) + { + CopyRoutine = pProperty->GetStringDescriptor; + } /* End of GET_DESCRIPTOR */ + } + } + + /*GET STATUS*/ + else if ((Request_No == GET_STATUS) && (pInformation->USBwValue == 0) + && (pInformation->USBwLength == 0x0002) + && (pInformation->USBwIndex1 == 0)) + { + /* GET STATUS for Device*/ + if ((Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT)) + && (pInformation->USBwIndex == 0)) + { + CopyRoutine = Standard_GetStatus; + } + + /* GET STATUS for Interface*/ + else if (Type_Recipient == (STANDARD_REQUEST | INTERFACE_RECIPIENT)) + { + if (((*pProperty->Class_Get_Interface_Setting)(pInformation->USBwIndex0, 0) == USB_SUCCESS) + && (pInformation->Current_Configuration != 0)) + { + CopyRoutine = Standard_GetStatus; + } + } + + /* GET STATUS for EndPoint*/ + else if (Type_Recipient == (STANDARD_REQUEST | ENDPOINT_RECIPIENT)) + { + Related_Endpoint = (pInformation->USBwIndex0 & 0x0f); + Reserved = pInformation->USBwIndex0 & 0x70; + + if (ValBit(pInformation->USBwIndex0, 7)) + { + /*Get Status of endpoint & stall the request if the related_ENdpoint + is Disabled*/ + Status = _GetEPTxStatus(Related_Endpoint); + } + else + { + Status = _GetEPRxStatus(Related_Endpoint); + } + + if ((Related_Endpoint < Device_Table.Total_Endpoint) && (Reserved == 0) + && (Status != 0)) + { + CopyRoutine = Standard_GetStatus; + } + } + + } + + /*GET CONFIGURATION*/ + else if (Request_No == GET_CONFIGURATION) + { + if (Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT)) + { + CopyRoutine = Standard_GetConfiguration; + } + } + /*GET INTERFACE*/ + else if (Request_No == GET_INTERFACE) + { + if ((Type_Recipient == (STANDARD_REQUEST | INTERFACE_RECIPIENT)) + && (pInformation->Current_Configuration != 0) && (pInformation->USBwValue == 0) + && (pInformation->USBwIndex1 == 0) && (pInformation->USBwLength == 0x0001) + && ((*pProperty->Class_Get_Interface_Setting)(pInformation->USBwIndex0, 0) == USB_SUCCESS)) + { + CopyRoutine = Standard_GetInterface; + } + + } + + if (CopyRoutine) + { + pInformation->Ctrl_Info.Usb_wOffset = wOffset; + pInformation->Ctrl_Info.CopyDataIn = CopyRoutine; + /* sb in the original the cast to word was directly */ + /* now the cast is made step by step */ + (*CopyRoutine)(0); + Result = USB_SUCCESS; + } + else + { + Result = (*pProperty->Class_Data_Setup)(pInformation->USBbRequest); + if (Result == USB_NOT_READY) + { + pInformation->ControlState = PAUSE; + return; + } + } + + if (pInformation->Ctrl_Info.Usb_wLength == 0xFFFF) + { + /* Data is not ready, wait it */ + pInformation->ControlState = PAUSE; + return; + } + if ((Result == USB_UNSUPPORT) || (pInformation->Ctrl_Info.Usb_wLength == 0)) + { + /* Unsupported request */ + pInformation->ControlState = STALLED; + return; + } + + + if (ValBit(pInformation->USBbmRequestType, 7)) + { + /* Device ==> Host */ + __IO uint32_t wLength = pInformation->USBwLength; + + /* Restrict the data length to be the one host asks for */ + if (pInformation->Ctrl_Info.Usb_wLength > wLength) + { + pInformation->Ctrl_Info.Usb_wLength = wLength; + } + + else if (pInformation->Ctrl_Info.Usb_wLength < pInformation->USBwLength) + { + if (pInformation->Ctrl_Info.Usb_wLength < pProperty->MaxPacketSize) + { + Data_Mul_MaxPacketSize = FALSE; + } + else if ((pInformation->Ctrl_Info.Usb_wLength % pProperty->MaxPacketSize) == 0) + { + Data_Mul_MaxPacketSize = TRUE; + } + } + + pInformation->Ctrl_Info.PacketSize = pProperty->MaxPacketSize; + DataStageIn(); + } + else + { + pInformation->ControlState = OUT_DATA; + vSetEPRxStatus(EP_RX_VALID); /* enable for next data reception */ + } + + return; +} + +/******************************************************************************* +* Function Name : Setup0_Process +* Description : Get the device request data and dispatch to individual process. +* Input : None. +* Output : None. +* Return : Post0_Process. +*******************************************************************************/ +uint8_t Setup0_Process(void) +{ + + union + { + uint8_t* b; + uint16_t* w; + } pBuf; + +#ifdef STM32F10X_CL + USB_OTG_EP *ep; + uint16_t offset = 0; + + ep = PCD_GetOutEP(ENDP0); + pBuf.b = ep->xfer_buff; +#else + uint16_t offset = 1; + + pBuf.b = PMAAddr + (uint8_t *)(_GetEPRxAddr(ENDP0) * 2); /* *2 for 32 bits addr */ +#endif /* STM32F10X_CL */ + + if (pInformation->ControlState != PAUSE) + { + pInformation->USBbmRequestType = *pBuf.b++; /* bmRequestType */ + pInformation->USBbRequest = *pBuf.b++; /* bRequest */ + pBuf.w += offset; /* word not accessed because of 32 bits addressing */ + pInformation->USBwValue = ByteSwap(*pBuf.w++); /* wValue */ + pBuf.w += offset; /* word not accessed because of 32 bits addressing */ + pInformation->USBwIndex = ByteSwap(*pBuf.w++); /* wIndex */ + pBuf.w += offset; /* word not accessed because of 32 bits addressing */ + pInformation->USBwLength = *pBuf.w; /* wLength */ + } + + pInformation->ControlState = SETTING_UP; + if (pInformation->USBwLength == 0) + { + /* Setup with no data stage */ + NoData_Setup0(); + } + else + { + /* Setup with data stage */ + Data_Setup0(); + } + return Post0_Process(); +} + +/******************************************************************************* +* Function Name : In0_Process +* Description : Process the IN token on all default endpoint. +* Input : None. +* Output : None. +* Return : Post0_Process. +*******************************************************************************/ +uint8_t In0_Process(void) +{ + uint32_t ControlState = pInformation->ControlState; + + if ((ControlState == IN_DATA) || (ControlState == LAST_IN_DATA)) + { + DataStageIn(); + /* ControlState may be changed outside the function */ + ControlState = pInformation->ControlState; + } + + else if (ControlState == WAIT_STATUS_IN) + { + if ((pInformation->USBbRequest == SET_ADDRESS) && + (Type_Recipient == (STANDARD_REQUEST | DEVICE_RECIPIENT))) + { + SetDeviceAddress(pInformation->USBwValue0); + pUser_Standard_Requests->User_SetDeviceAddress(); + } + (*pProperty->Process_Status_IN)(); + ControlState = STALLED; + } + + else + { + ControlState = STALLED; + } + + pInformation->ControlState = ControlState; + + return Post0_Process(); +} + +/******************************************************************************* +* Function Name : Out0_Process +* Description : Process the OUT token on all default endpoint. +* Input : None. +* Output : None. +* Return : Post0_Process. +*******************************************************************************/ +uint8_t Out0_Process(void) +{ + uint32_t ControlState = pInformation->ControlState; + + if ((ControlState == IN_DATA) || (ControlState == LAST_IN_DATA)) + { + /* host aborts the transfer before finish */ + ControlState = STALLED; + } + else if ((ControlState == OUT_DATA) || (ControlState == LAST_OUT_DATA)) + { + DataStageOut(); + ControlState = pInformation->ControlState; /* may be changed outside the function */ + } + + else if (ControlState == WAIT_STATUS_OUT) + { + (*pProperty->Process_Status_OUT)(); + #ifndef STM32F10X_CL + ControlState = STALLED; + #endif /* STM32F10X_CL */ + } + + + /* Unexpect state, STALL the endpoint */ + else + { + ControlState = STALLED; + } + + pInformation->ControlState = ControlState; + + return Post0_Process(); +} + +/******************************************************************************* +* Function Name : Post0_Process +* Description : Stall the Endpoint 0 in case of error. +* Input : None. +* Output : None. +* Return : - 0 if the control State is in PAUSE +* - 1 if not. +*******************************************************************************/ +uint8_t Post0_Process(void) +{ +#ifdef STM32F10X_CL + USB_OTG_EP *ep; +#endif /* STM32F10X_CL */ + + SetEPRxCount(ENDP0, Device_Property.MaxPacketSize); + + if (pInformation->ControlState == STALLED) + { + vSetEPRxStatus(EP_RX_STALL); + vSetEPTxStatus(EP_TX_STALL); + } + +#ifdef STM32F10X_CL + else if ((pInformation->ControlState == OUT_DATA) || + (pInformation->ControlState == WAIT_STATUS_OUT)) + { + ep = PCD_GetInEP(0); + ep->is_in = 0; + OTGD_FS_EP0StartXfer(ep); + + vSetEPTxStatus(EP_TX_VALID); + } + + else if ((pInformation->ControlState == IN_DATA) || + (pInformation->ControlState == WAIT_STATUS_IN)) + { + ep = PCD_GetInEP(0); + ep->is_in = 1; + OTGD_FS_EP0StartXfer(ep); + } +#endif /* STM32F10X_CL */ + + return (pInformation->ControlState == PAUSE); +} + +/******************************************************************************* +* Function Name : SetDeviceAddress. +* Description : Set the device and all the used Endpoints addresses. +* Input : - Val: device adress. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetDeviceAddress(uint8_t Val) +{ +#ifdef STM32F10X_CL + PCD_EP_SetAddress ((uint8_t)Val); +#else + uint32_t i; + uint32_t nEP = Device_Table.Total_Endpoint; + + /* set address in every used endpoint */ + for (i = 0; i < nEP; i++) + { + _SetEPAddress((uint8_t)i, (uint8_t)i); + } /* for */ + _SetDADDR(Val | DADDR_EF); /* set device address and enable function */ +#endif /* STM32F10X_CL */ +} + +/******************************************************************************* +* Function Name : NOP_Process +* Description : No operation function. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void NOP_Process(void) +{ +} + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_init.c b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_init.c index 2abc3cebe..1b2e562b9 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_init.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_init.c @@ -1,63 +1,63 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_init.c -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Initialization routines & global variables -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Includes ------------------------------------------------------------------*/ -#include "usb_lib.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* The number of current endpoint, it will be used to specify an endpoint */ - uint8_t EPindex; -/* The number of current device, it is an index to the Device_Table */ -/* uint8_t Device_no; */ -/* Points to the DEVICE_INFO structure of current device */ -/* The purpose of this register is to speed up the execution */ -DEVICE_INFO *pInformation; -/* Points to the DEVICE_PROP structure of current device */ -/* The purpose of this register is to speed up the execution */ -DEVICE_PROP *pProperty; -/* Temporary save the state of Rx & Tx status. */ -/* Whenever the Rx or Tx state is changed, its value is saved */ -/* in this variable first and will be set to the EPRB or EPRA */ -/* at the end of interrupt process */ -uint16_t SaveState ; -uint16_t wInterrupt_Mask; -DEVICE_INFO Device_Info; -USER_STANDARD_REQUESTS *pUser_Standard_Requests; - -/* Extern variables ----------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/******************************************************************************* -* Function Name : USB_Init -* Description : USB system initialization -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void USB_Init(void) -{ - pInformation = &Device_Info; - pInformation->ControlState = 2; - pProperty = &Device_Property; - pUser_Standard_Requests = &User_Standard_Requests; - /* Initialize devices one by one */ - pProperty->Init(); -} - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_init.c +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Initialization routines & global variables +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_lib.h" + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* The number of current endpoint, it will be used to specify an endpoint */ + uint8_t EPindex; +/* The number of current device, it is an index to the Device_Table */ +/* uint8_t Device_no; */ +/* Points to the DEVICE_INFO structure of current device */ +/* The purpose of this register is to speed up the execution */ +DEVICE_INFO *pInformation; +/* Points to the DEVICE_PROP structure of current device */ +/* The purpose of this register is to speed up the execution */ +DEVICE_PROP *pProperty; +/* Temporary save the state of Rx & Tx status. */ +/* Whenever the Rx or Tx state is changed, its value is saved */ +/* in this variable first and will be set to the EPRB or EPRA */ +/* at the end of interrupt process */ +uint16_t SaveState ; +uint16_t wInterrupt_Mask; +DEVICE_INFO Device_Info; +USER_STANDARD_REQUESTS *pUser_Standard_Requests; + +/* Extern variables ----------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/******************************************************************************* +* Function Name : USB_Init +* Description : USB system initialization +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void USB_Init(void) +{ + pInformation = &Device_Info; + pInformation->ControlState = 2; + pProperty = &Device_Property; + pUser_Standard_Requests = &User_Standard_Requests; + /* Initialize devices one by one */ + pProperty->Init(); +} + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_int.c b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_int.c index f99c1b042..c60553b19 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_int.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_int.c @@ -1,188 +1,188 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_int.c -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Endpoint CTR (Low and High) interrupt's service routines -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ -#ifndef STM32F10X_CL - -/* Includes ------------------------------------------------------------------*/ -#include "usb_lib.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -__IO uint16_t SaveRState; -__IO uint16_t SaveTState; - -/* Extern variables ----------------------------------------------------------*/ -extern void (*pEpInt_IN[7])(void); /* Handles IN interrupts */ -extern void (*pEpInt_OUT[7])(void); /* Handles OUT interrupts */ - -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/******************************************************************************* -* Function Name : CTR_LP. -* Description : Low priority Endpoint Correct Transfer interrupt's service -* routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void CTR_LP(void) -{ - __IO uint16_t wEPVal = 0; - /* stay in loop while pending ints */ - while (((wIstr = _GetISTR()) & ISTR_CTR) != 0) - { - /* extract highest priority endpoint number */ - EPindex = (uint8_t)(wIstr & ISTR_EP_ID); - if (EPindex == 0) - { - /* Decode and service control endpoint interrupt */ - /* calling related service routine */ - /* (Setup0_Process, In0_Process, Out0_Process) */ - - /* save RX & TX status */ - /* and set both to NAK */ - - - SaveRState = _GetENDPOINT(ENDP0); - SaveTState = SaveRState & EPTX_STAT; - SaveRState &= EPRX_STAT; - - _SetEPRxTxStatus(ENDP0,EP_RX_NAK,EP_TX_NAK); - - /* DIR bit = origin of the interrupt */ - - if ((wIstr & ISTR_DIR) == 0) - { - /* DIR = 0 */ - - /* DIR = 0 => IN int */ - /* DIR = 0 implies that (EP_CTR_TX = 1) always */ - - - _ClearEP_CTR_TX(ENDP0); - In0_Process(); - - /* before terminate set Tx & Rx status */ - - _SetEPRxTxStatus(ENDP0,SaveRState,SaveTState); - return; - } - else - { - /* DIR = 1 */ - - /* DIR = 1 & CTR_RX => SETUP or OUT int */ - /* DIR = 1 & (CTR_TX | CTR_RX) => 2 int pending */ - - wEPVal = _GetENDPOINT(ENDP0); - - if ((wEPVal &EP_SETUP) != 0) - { - _ClearEP_CTR_RX(ENDP0); /* SETUP bit kept frozen while CTR_RX = 1 */ - Setup0_Process(); - /* before terminate set Tx & Rx status */ - - _SetEPRxTxStatus(ENDP0,SaveRState,SaveTState); - return; - } - - else if ((wEPVal & EP_CTR_RX) != 0) - { - _ClearEP_CTR_RX(ENDP0); - Out0_Process(); - /* before terminate set Tx & Rx status */ - - _SetEPRxTxStatus(ENDP0,SaveRState,SaveTState); - return; - } - } - }/* if(EPindex == 0) */ - else - { - /* Decode and service non control endpoints interrupt */ - - /* process related endpoint register */ - wEPVal = _GetENDPOINT(EPindex); - if ((wEPVal & EP_CTR_RX) != 0) - { - /* clear int flag */ - _ClearEP_CTR_RX(EPindex); - - /* call OUT service function */ - (*pEpInt_OUT[EPindex-1])(); - - } /* if((wEPVal & EP_CTR_RX) */ - - if ((wEPVal & EP_CTR_TX) != 0) - { - /* clear int flag */ - _ClearEP_CTR_TX(EPindex); - - /* call IN service function */ - (*pEpInt_IN[EPindex-1])(); - } /* if((wEPVal & EP_CTR_TX) != 0) */ - - }/* if(EPindex == 0) else */ - - }/* while(...) */ -} - -/******************************************************************************* -* Function Name : CTR_HP. -* Description : High Priority Endpoint Correct Transfer interrupt's service -* routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void CTR_HP(void) -{ - uint32_t wEPVal = 0; - - while (((wIstr = _GetISTR()) & ISTR_CTR) != 0) - { - _SetISTR((uint16_t)CLR_CTR); /* clear CTR flag */ - /* extract highest priority endpoint number */ - EPindex = (uint8_t)(wIstr & ISTR_EP_ID); - /* process related endpoint register */ - wEPVal = _GetENDPOINT(EPindex); - if ((wEPVal & EP_CTR_RX) != 0) - { - /* clear int flag */ - _ClearEP_CTR_RX(EPindex); - - /* call OUT service function */ - (*pEpInt_OUT[EPindex-1])(); - - } /* if((wEPVal & EP_CTR_RX) */ - else if ((wEPVal & EP_CTR_TX) != 0) - { - /* clear int flag */ - _ClearEP_CTR_TX(EPindex); - - /* call IN service function */ - (*pEpInt_IN[EPindex-1])(); - - - } /* if((wEPVal & EP_CTR_TX) != 0) */ - - }/* while(...) */ -} - -#endif /* STM32F10X_CL */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_int.c +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Endpoint CTR (Low and High) interrupt's service routines +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ +#ifndef STM32F10X_CL + +/* Includes ------------------------------------------------------------------*/ +#include "usb_lib.h" + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +__IO uint16_t SaveRState; +__IO uint16_t SaveTState; + +/* Extern variables ----------------------------------------------------------*/ +extern void (*pEpInt_IN[7])(void); /* Handles IN interrupts */ +extern void (*pEpInt_OUT[7])(void); /* Handles OUT interrupts */ + +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/******************************************************************************* +* Function Name : CTR_LP. +* Description : Low priority Endpoint Correct Transfer interrupt's service +* routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void CTR_LP(void) +{ + __IO uint16_t wEPVal = 0; + /* stay in loop while pending ints */ + while (((wIstr = _GetISTR()) & ISTR_CTR) != 0) + { + /* extract highest priority endpoint number */ + EPindex = (uint8_t)(wIstr & ISTR_EP_ID); + if (EPindex == 0) + { + /* Decode and service control endpoint interrupt */ + /* calling related service routine */ + /* (Setup0_Process, In0_Process, Out0_Process) */ + + /* save RX & TX status */ + /* and set both to NAK */ + + + SaveRState = _GetENDPOINT(ENDP0); + SaveTState = SaveRState & EPTX_STAT; + SaveRState &= EPRX_STAT; + + _SetEPRxTxStatus(ENDP0,EP_RX_NAK,EP_TX_NAK); + + /* DIR bit = origin of the interrupt */ + + if ((wIstr & ISTR_DIR) == 0) + { + /* DIR = 0 */ + + /* DIR = 0 => IN int */ + /* DIR = 0 implies that (EP_CTR_TX = 1) always */ + + + _ClearEP_CTR_TX(ENDP0); + In0_Process(); + + /* before terminate set Tx & Rx status */ + + _SetEPRxTxStatus(ENDP0,SaveRState,SaveTState); + return; + } + else + { + /* DIR = 1 */ + + /* DIR = 1 & CTR_RX => SETUP or OUT int */ + /* DIR = 1 & (CTR_TX | CTR_RX) => 2 int pending */ + + wEPVal = _GetENDPOINT(ENDP0); + + if ((wEPVal &EP_SETUP) != 0) + { + _ClearEP_CTR_RX(ENDP0); /* SETUP bit kept frozen while CTR_RX = 1 */ + Setup0_Process(); + /* before terminate set Tx & Rx status */ + + _SetEPRxTxStatus(ENDP0,SaveRState,SaveTState); + return; + } + + else if ((wEPVal & EP_CTR_RX) != 0) + { + _ClearEP_CTR_RX(ENDP0); + Out0_Process(); + /* before terminate set Tx & Rx status */ + + _SetEPRxTxStatus(ENDP0,SaveRState,SaveTState); + return; + } + } + }/* if(EPindex == 0) */ + else + { + /* Decode and service non control endpoints interrupt */ + + /* process related endpoint register */ + wEPVal = _GetENDPOINT(EPindex); + if ((wEPVal & EP_CTR_RX) != 0) + { + /* clear int flag */ + _ClearEP_CTR_RX(EPindex); + + /* call OUT service function */ + (*pEpInt_OUT[EPindex-1])(); + + } /* if((wEPVal & EP_CTR_RX) */ + + if ((wEPVal & EP_CTR_TX) != 0) + { + /* clear int flag */ + _ClearEP_CTR_TX(EPindex); + + /* call IN service function */ + (*pEpInt_IN[EPindex-1])(); + } /* if((wEPVal & EP_CTR_TX) != 0) */ + + }/* if(EPindex == 0) else */ + + }/* while(...) */ +} + +/******************************************************************************* +* Function Name : CTR_HP. +* Description : High Priority Endpoint Correct Transfer interrupt's service +* routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void CTR_HP(void) +{ + uint32_t wEPVal = 0; + + while (((wIstr = _GetISTR()) & ISTR_CTR) != 0) + { + _SetISTR((uint16_t)CLR_CTR); /* clear CTR flag */ + /* extract highest priority endpoint number */ + EPindex = (uint8_t)(wIstr & ISTR_EP_ID); + /* process related endpoint register */ + wEPVal = _GetENDPOINT(EPindex); + if ((wEPVal & EP_CTR_RX) != 0) + { + /* clear int flag */ + _ClearEP_CTR_RX(EPindex); + + /* call OUT service function */ + (*pEpInt_OUT[EPindex-1])(); + + } /* if((wEPVal & EP_CTR_RX) */ + else if ((wEPVal & EP_CTR_TX) != 0) + { + /* clear int flag */ + _ClearEP_CTR_TX(EPindex); + + /* call IN service function */ + (*pEpInt_IN[EPindex-1])(); + + + } /* if((wEPVal & EP_CTR_TX) != 0) */ + + }/* while(...) */ +} + +#endif /* STM32F10X_CL */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_mem.c b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_mem.c index ca50a23c4..5b12a2038 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_mem.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_mem.c @@ -1,75 +1,75 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_mem.c -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Utility functions for memory transfers to/from PMA -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ -#ifndef STM32F10X_CL - -/* Includes ------------------------------------------------------------------*/ -#include "usb_lib.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Extern variables ----------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/******************************************************************************* -* Function Name : UserToPMABufferCopy -* Description : Copy a buffer from user memory area to packet memory area (PMA) -* Input : - pbUsrBuf: pointer to user memory area. -* - wPMABufAddr: address into PMA. -* - wNBytes: no. of bytes to be copied. -* Output : None. -* Return : None . -*******************************************************************************/ -void UserToPMABufferCopy(const uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes) -{ - uint32_t n = (wNBytes + 1) >> 1; /* n = (wNBytes + 1) / 2 */ - uint32_t i, temp1, temp2; - uint16_t *pdwVal; - pdwVal = (uint16_t *)(wPMABufAddr * 2 + PMAAddr); - for (i = n; i != 0; i--) - { - temp1 = (uint16_t) * pbUsrBuf; - pbUsrBuf++; - temp2 = temp1 | (uint16_t) * pbUsrBuf << 8; - *pdwVal++ = temp2; - pdwVal++; - pbUsrBuf++; - } -} -/******************************************************************************* -* Function Name : PMAToUserBufferCopy -* Description : Copy a buffer from user memory area to packet memory area (PMA) -* Input : - pbUsrBuf = pointer to user memory area. -* - wPMABufAddr = address into PMA. -* - wNBytes = no. of bytes to be copied. -* Output : None. -* Return : None. -*******************************************************************************/ -void PMAToUserBufferCopy(uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes) -{ - uint32_t n = (wNBytes + 1) >> 1;/* /2*/ - uint32_t i; - uint32_t *pdwVal; - pdwVal = (uint32_t *)(wPMABufAddr * 2 + PMAAddr); - for (i = n; i != 0; i--) - { - *(uint16_t*)pbUsrBuf++ = *pdwVal++; - pbUsrBuf++; - } -} - -#endif /* STM32F10X_CL */ -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_mem.c +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Utility functions for memory transfers to/from PMA +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ +#ifndef STM32F10X_CL + +/* Includes ------------------------------------------------------------------*/ +#include "usb_lib.h" + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Extern variables ----------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +/******************************************************************************* +* Function Name : UserToPMABufferCopy +* Description : Copy a buffer from user memory area to packet memory area (PMA) +* Input : - pbUsrBuf: pointer to user memory area. +* - wPMABufAddr: address into PMA. +* - wNBytes: no. of bytes to be copied. +* Output : None. +* Return : None . +*******************************************************************************/ +void UserToPMABufferCopy(const uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes) +{ + uint32_t n = (wNBytes + 1) >> 1; /* n = (wNBytes + 1) / 2 */ + uint32_t i, temp1, temp2; + uint16_t *pdwVal; + pdwVal = (uint16_t *)(wPMABufAddr * 2 + PMAAddr); + for (i = n; i != 0; i--) + { + temp1 = (uint16_t) * pbUsrBuf; + pbUsrBuf++; + temp2 = temp1 | (uint16_t) * pbUsrBuf << 8; + *pdwVal++ = temp2; + pdwVal++; + pbUsrBuf++; + } +} +/******************************************************************************* +* Function Name : PMAToUserBufferCopy +* Description : Copy a buffer from user memory area to packet memory area (PMA) +* Input : - pbUsrBuf = pointer to user memory area. +* - wPMABufAddr = address into PMA. +* - wNBytes = no. of bytes to be copied. +* Output : None. +* Return : None. +*******************************************************************************/ +void PMAToUserBufferCopy(uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes) +{ + uint32_t n = (wNBytes + 1) >> 1;/* /2*/ + uint32_t i; + uint32_t *pdwVal; + pdwVal = (uint32_t *)(wPMABufAddr * 2 + PMAAddr); + for (i = n; i != 0; i--) + { + *(uint16_t*)pbUsrBuf++ = *pdwVal++; + pbUsrBuf++; + } +} + +#endif /* STM32F10X_CL */ +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_regs.c b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_regs.c index 3bba77012..e2742c0d5 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_regs.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_regs.c @@ -1,750 +1,750 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_regs.c -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Interface functions to USB cell registers -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ -#ifndef STM32F10X_CL - -/* Includes ------------------------------------------------------------------*/ -#include "usb_lib.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Extern variables ----------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/******************************************************************************* -* Function Name : SetCNTR. -* Description : Set the CNTR register value. -* Input : wRegValue: new register value. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetCNTR(uint16_t wRegValue) -{ - _SetCNTR(wRegValue); -} - -/******************************************************************************* -* Function Name : GetCNTR. -* Description : returns the CNTR register value. -* Input : None. -* Output : None. -* Return : CNTR register Value. -*******************************************************************************/ -uint16_t GetCNTR(void) -{ - return(_GetCNTR()); -} - -/******************************************************************************* -* Function Name : SetISTR. -* Description : Set the ISTR register value. -* Input : wRegValue: new register value. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetISTR(uint16_t wRegValue) -{ - _SetISTR(wRegValue); -} - -/******************************************************************************* -* Function Name : GetISTR -* Description : Returns the ISTR register value. -* Input : None. -* Output : None. -* Return : ISTR register Value -*******************************************************************************/ -uint16_t GetISTR(void) -{ - return(_GetISTR()); -} - -/******************************************************************************* -* Function Name : GetFNR -* Description : Returns the FNR register value. -* Input : None. -* Output : None. -* Return : FNR register Value -*******************************************************************************/ -uint16_t GetFNR(void) -{ - return(_GetFNR()); -} - -/******************************************************************************* -* Function Name : SetDADDR -* Description : Set the DADDR register value. -* Input : wRegValue: new register value. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetDADDR(uint16_t wRegValue) -{ - _SetDADDR(wRegValue); -} - -/******************************************************************************* -* Function Name : GetDADDR -* Description : Returns the DADDR register value. -* Input : None. -* Output : None. -* Return : DADDR register Value -*******************************************************************************/ -uint16_t GetDADDR(void) -{ - return(_GetDADDR()); -} - -/******************************************************************************* -* Function Name : SetBTABLE -* Description : Set the BTABLE. -* Input : wRegValue: New register value. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetBTABLE(uint16_t wRegValue) -{ - _SetBTABLE(wRegValue); -} - -/******************************************************************************* -* Function Name : GetBTABLE. -* Description : Returns the BTABLE register value. -* Input : None. -* Output : None. -* Return : BTABLE address. -*******************************************************************************/ -uint16_t GetBTABLE(void) -{ - return(_GetBTABLE()); -} - -/******************************************************************************* -* Function Name : SetENDPOINT -* Description : Setthe Endpoint register value. -* Input : bEpNum: Endpoint Number. -* wRegValue. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetENDPOINT(uint8_t bEpNum, uint16_t wRegValue) -{ - _SetENDPOINT(bEpNum, wRegValue); -} - -/******************************************************************************* -* Function Name : GetENDPOINT -* Description : Return the Endpoint register value. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Endpoint register value. -*******************************************************************************/ -uint16_t GetENDPOINT(uint8_t bEpNum) -{ - return(_GetENDPOINT(bEpNum)); -} - -/******************************************************************************* -* Function Name : SetEPType -* Description : sets the type in the endpoint register. -* Input : bEpNum: Endpoint Number. -* wType: type definition. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPType(uint8_t bEpNum, uint16_t wType) -{ - _SetEPType(bEpNum, wType); -} - -/******************************************************************************* -* Function Name : GetEPType -* Description : Returns the endpoint type. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Endpoint Type -*******************************************************************************/ -uint16_t GetEPType(uint8_t bEpNum) -{ - return(_GetEPType(bEpNum)); -} - -/******************************************************************************* -* Function Name : SetEPTxStatus -* Description : Set the status of Tx endpoint. -* Input : bEpNum: Endpoint Number. -* wState: new state. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPTxStatus(uint8_t bEpNum, uint16_t wState) -{ - _SetEPTxStatus(bEpNum, wState); -} - -/******************************************************************************* -* Function Name : SetEPRxStatus -* Description : Set the status of Rx endpoint. -* Input : bEpNum: Endpoint Number. -* wState: new state. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPRxStatus(uint8_t bEpNum, uint16_t wState) -{ - _SetEPRxStatus(bEpNum, wState); -} - -/******************************************************************************* -* Function Name : SetDouBleBuffEPStall -* Description : sets the status for Double Buffer Endpoint to STALL -* Input : bEpNum: Endpoint Number. -* bDir: Endpoint direction. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetDouBleBuffEPStall(uint8_t bEpNum, uint8_t bDir) -{ - uint16_t Endpoint_DTOG_Status; - Endpoint_DTOG_Status = GetENDPOINT(bEpNum); - if (bDir == EP_DBUF_OUT) - { /* OUT double buffered endpoint */ - _SetENDPOINT(bEpNum, Endpoint_DTOG_Status & ~EPRX_DTOG1); - } - else if (bDir == EP_DBUF_IN) - { /* IN double buffered endpoint */ - _SetENDPOINT(bEpNum, Endpoint_DTOG_Status & ~EPTX_DTOG1); - } -} - -/******************************************************************************* -* Function Name : GetEPTxStatus -* Description : Returns the endpoint Tx status. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Endpoint TX Status -*******************************************************************************/ -uint16_t GetEPTxStatus(uint8_t bEpNum) -{ - return(_GetEPTxStatus(bEpNum)); -} - -/******************************************************************************* -* Function Name : GetEPRxStatus -* Description : Returns the endpoint Rx status. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Endpoint RX Status -*******************************************************************************/ -uint16_t GetEPRxStatus(uint8_t bEpNum) -{ - return(_GetEPRxStatus(bEpNum)); -} - -/******************************************************************************* -* Function Name : SetEPTxValid -* Description : Valid the endpoint Tx Status. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPTxValid(uint8_t bEpNum) -{ - _SetEPTxStatus(bEpNum, EP_TX_VALID); -} - -/******************************************************************************* -* Function Name : SetEPRxValid -* Description : Valid the endpoint Rx Status. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPRxValid(uint8_t bEpNum) -{ - _SetEPRxStatus(bEpNum, EP_RX_VALID); -} - -/******************************************************************************* -* Function Name : SetEP_KIND -* Description : Clear the EP_KIND bit. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEP_KIND(uint8_t bEpNum) -{ - _SetEP_KIND(bEpNum); -} - -/******************************************************************************* -* Function Name : ClearEP_KIND -* Description : set the EP_KIND bit. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void ClearEP_KIND(uint8_t bEpNum) -{ - _ClearEP_KIND(bEpNum); -} -/******************************************************************************* -* Function Name : Clear_Status_Out -* Description : Clear the Status Out of the related Endpoint -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void Clear_Status_Out(uint8_t bEpNum) -{ - _ClearEP_KIND(bEpNum); -} -/******************************************************************************* -* Function Name : Set_Status_Out -* Description : Set the Status Out of the related Endpoint -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void Set_Status_Out(uint8_t bEpNum) -{ - _SetEP_KIND(bEpNum); -} -/******************************************************************************* -* Function Name : SetEPDoubleBuff -* Description : Enable the double buffer feature for the endpoint. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPDoubleBuff(uint8_t bEpNum) -{ - _SetEP_KIND(bEpNum); -} -/******************************************************************************* -* Function Name : ClearEPDoubleBuff -* Description : Disable the double buffer feature for the endpoint. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void ClearEPDoubleBuff(uint8_t bEpNum) -{ - _ClearEP_KIND(bEpNum); -} -/******************************************************************************* -* Function Name : GetTxStallStatus -* Description : Returns the Stall status of the Tx endpoint. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Tx Stall status. -*******************************************************************************/ -uint16_t GetTxStallStatus(uint8_t bEpNum) -{ - return(_GetTxStallStatus(bEpNum)); -} -/******************************************************************************* -* Function Name : GetRxStallStatus -* Description : Returns the Stall status of the Rx endpoint. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Rx Stall status. -*******************************************************************************/ -uint16_t GetRxStallStatus(uint8_t bEpNum) -{ - return(_GetRxStallStatus(bEpNum)); -} -/******************************************************************************* -* Function Name : ClearEP_CTR_RX -* Description : Clear the CTR_RX bit. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void ClearEP_CTR_RX(uint8_t bEpNum) -{ - _ClearEP_CTR_RX(bEpNum); -} -/******************************************************************************* -* Function Name : ClearEP_CTR_TX -* Description : Clear the CTR_TX bit. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void ClearEP_CTR_TX(uint8_t bEpNum) -{ - _ClearEP_CTR_TX(bEpNum); -} -/******************************************************************************* -* Function Name : ToggleDTOG_RX -* Description : Toggle the DTOG_RX bit. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void ToggleDTOG_RX(uint8_t bEpNum) -{ - _ToggleDTOG_RX(bEpNum); -} -/******************************************************************************* -* Function Name : ToggleDTOG_TX -* Description : Toggle the DTOG_TX bit. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void ToggleDTOG_TX(uint8_t bEpNum) -{ - _ToggleDTOG_TX(bEpNum); -} -/******************************************************************************* -* Function Name : ClearDTOG_RX. -* Description : Clear the DTOG_RX bit. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void ClearDTOG_RX(uint8_t bEpNum) -{ - _ClearDTOG_RX(bEpNum); -} -/******************************************************************************* -* Function Name : ClearDTOG_TX. -* Description : Clear the DTOG_TX bit. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -void ClearDTOG_TX(uint8_t bEpNum) -{ - _ClearDTOG_TX(bEpNum); -} -/******************************************************************************* -* Function Name : SetEPAddress -* Description : Set the endpoint address. -* Input : bEpNum: Endpoint Number. -* bAddr: New endpoint address. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPAddress(uint8_t bEpNum, uint8_t bAddr) -{ - _SetEPAddress(bEpNum, bAddr); -} -/******************************************************************************* -* Function Name : GetEPAddress -* Description : Get the endpoint address. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Endpoint address. -*******************************************************************************/ -uint8_t GetEPAddress(uint8_t bEpNum) -{ - return(_GetEPAddress(bEpNum)); -} -/******************************************************************************* -* Function Name : SetEPTxAddr -* Description : Set the endpoint Tx buffer address. -* Input : bEpNum: Endpoint Number. -* wAddr: new address. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPTxAddr(uint8_t bEpNum, uint16_t wAddr) -{ - _SetEPTxAddr(bEpNum, wAddr); -} -/******************************************************************************* -* Function Name : SetEPRxAddr -* Description : Set the endpoint Rx buffer address. -* Input : bEpNum: Endpoint Number. -* wAddr: new address. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPRxAddr(uint8_t bEpNum, uint16_t wAddr) -{ - _SetEPRxAddr(bEpNum, wAddr); -} -/******************************************************************************* -* Function Name : GetEPTxAddr -* Description : Returns the endpoint Tx buffer address. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Rx buffer address. -*******************************************************************************/ -uint16_t GetEPTxAddr(uint8_t bEpNum) -{ - return(_GetEPTxAddr(bEpNum)); -} -/******************************************************************************* -* Function Name : GetEPRxAddr. -* Description : Returns the endpoint Rx buffer address. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Rx buffer address. -*******************************************************************************/ -uint16_t GetEPRxAddr(uint8_t bEpNum) -{ - return(_GetEPRxAddr(bEpNum)); -} -/******************************************************************************* -* Function Name : SetEPTxCount. -* Description : Set the Tx count. -* Input : bEpNum: Endpoint Number. -* wCount: new count value. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPTxCount(uint8_t bEpNum, uint16_t wCount) -{ - _SetEPTxCount(bEpNum, wCount); -} -/******************************************************************************* -* Function Name : SetEPCountRxReg. -* Description : Set the Count Rx Register value. -* Input : *pdwReg: point to the register. -* wCount: the new register value. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPCountRxReg(uint32_t *pdwReg, uint16_t wCount) -{ - _SetEPCountRxReg(dwReg, wCount); -} -/******************************************************************************* -* Function Name : SetEPRxCount -* Description : Set the Rx count. -* Input : bEpNum: Endpoint Number. -* wCount: the new count value. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPRxCount(uint8_t bEpNum, uint16_t wCount) -{ - _SetEPRxCount(bEpNum, wCount); -} -/******************************************************************************* -* Function Name : GetEPTxCount -* Description : Get the Tx count. -* Input : bEpNum: Endpoint Number. -* Output : None -* Return : Tx count value. -*******************************************************************************/ -uint16_t GetEPTxCount(uint8_t bEpNum) -{ - return(_GetEPTxCount(bEpNum)); -} -/******************************************************************************* -* Function Name : GetEPRxCount -* Description : Get the Rx count. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Rx count value. -*******************************************************************************/ -uint16_t GetEPRxCount(uint8_t bEpNum) -{ - return(_GetEPRxCount(bEpNum)); -} -/******************************************************************************* -* Function Name : SetEPDblBuffAddr -* Description : Set the addresses of the buffer 0 and 1. -* Input : bEpNum: Endpoint Number. -* wBuf0Addr: new address of buffer 0. -* wBuf1Addr: new address of buffer 1. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPDblBuffAddr(uint8_t bEpNum, uint16_t wBuf0Addr, uint16_t wBuf1Addr) -{ - _SetEPDblBuffAddr(bEpNum, wBuf0Addr, wBuf1Addr); -} -/******************************************************************************* -* Function Name : SetEPDblBuf0Addr -* Description : Set the Buffer 1 address. -* Input : bEpNum: Endpoint Number -* wBuf0Addr: new address. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPDblBuf0Addr(uint8_t bEpNum, uint16_t wBuf0Addr) -{ - _SetEPDblBuf0Addr(bEpNum, wBuf0Addr); -} -/******************************************************************************* -* Function Name : SetEPDblBuf1Addr -* Description : Set the Buffer 1 address. -* Input : bEpNum: Endpoint Number -* wBuf1Addr: new address. -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPDblBuf1Addr(uint8_t bEpNum, uint16_t wBuf1Addr) -{ - _SetEPDblBuf1Addr(bEpNum, wBuf1Addr); -} -/******************************************************************************* -* Function Name : GetEPDblBuf0Addr -* Description : Returns the address of the Buffer 0. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : None. -*******************************************************************************/ -uint16_t GetEPDblBuf0Addr(uint8_t bEpNum) -{ - return(_GetEPDblBuf0Addr(bEpNum)); -} -/******************************************************************************* -* Function Name : GetEPDblBuf1Addr -* Description : Returns the address of the Buffer 1. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Address of the Buffer 1. -*******************************************************************************/ -uint16_t GetEPDblBuf1Addr(uint8_t bEpNum) -{ - return(_GetEPDblBuf1Addr(bEpNum)); -} -/******************************************************************************* -* Function Name : SetEPDblBuffCount -* Description : Set the number of bytes for a double Buffer -* endpoint. -* Input : bEpNum,bDir, wCount -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPDblBuffCount(uint8_t bEpNum, uint8_t bDir, uint16_t wCount) -{ - _SetEPDblBuffCount(bEpNum, bDir, wCount); -} -/******************************************************************************* -* Function Name : SetEPDblBuf0Count -* Description : Set the number of bytes in the buffer 0 of a double Buffer -* endpoint. -* Input : bEpNum, bDir, wCount -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPDblBuf0Count(uint8_t bEpNum, uint8_t bDir, uint16_t wCount) -{ - _SetEPDblBuf0Count(bEpNum, bDir, wCount); -} -/******************************************************************************* -* Function Name : SetEPDblBuf1Count -* Description : Set the number of bytes in the buffer 0 of a double Buffer -* endpoint. -* Input : bEpNum, bDir, wCount -* Output : None. -* Return : None. -*******************************************************************************/ -void SetEPDblBuf1Count(uint8_t bEpNum, uint8_t bDir, uint16_t wCount) -{ - _SetEPDblBuf1Count(bEpNum, bDir, wCount); -} -/******************************************************************************* -* Function Name : GetEPDblBuf0Count -* Description : Returns the number of byte received in the buffer 0 of a double -* Buffer endpoint. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Endpoint Buffer 0 count -*******************************************************************************/ -uint16_t GetEPDblBuf0Count(uint8_t bEpNum) -{ - return(_GetEPDblBuf0Count(bEpNum)); -} -/******************************************************************************* -* Function Name : GetEPDblBuf1Count -* Description : Returns the number of data received in the buffer 1 of a double -* Buffer endpoint. -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : Endpoint Buffer 1 count. -*******************************************************************************/ -uint16_t GetEPDblBuf1Count(uint8_t bEpNum) -{ - return(_GetEPDblBuf1Count(bEpNum)); -} -/******************************************************************************* -* Function Name : GetEPDblBufDir -* Description : gets direction of the double buffered endpoint -* Input : bEpNum: Endpoint Number. -* Output : None. -* Return : EP_DBUF_OUT, EP_DBUF_IN, -* EP_DBUF_ERR if the endpoint counter not yet programmed. -*******************************************************************************/ -EP_DBUF_DIR GetEPDblBufDir(uint8_t bEpNum) -{ - if ((uint16_t)(*_pEPRxCount(bEpNum) & 0xFC00) != 0) - return(EP_DBUF_OUT); - else if (((uint16_t)(*_pEPTxCount(bEpNum)) & 0x03FF) != 0) - return(EP_DBUF_IN); - else - return(EP_DBUF_ERR); -} -/******************************************************************************* -* Function Name : FreeUserBuffer -* Description : free buffer used from the application realizing it to the line - toggles bit SW_BUF in the double buffered endpoint register -* Input : bEpNum, bDir -* Output : None. -* Return : None. -*******************************************************************************/ -void FreeUserBuffer(uint8_t bEpNum, uint8_t bDir) -{ - if (bDir == EP_DBUF_OUT) - { /* OUT double buffered endpoint */ - _ToggleDTOG_TX(bEpNum); - } - else if (bDir == EP_DBUF_IN) - { /* IN double buffered endpoint */ - _ToggleDTOG_RX(bEpNum); - } -} - -/******************************************************************************* -* Function Name : ToWord -* Description : merge two byte in a word. -* Input : bh: byte high, bl: bytes low. -* Output : None. -* Return : resulted word. -*******************************************************************************/ -uint16_t ToWord(uint8_t bh, uint8_t bl) -{ - uint16_t wRet; - wRet = (uint16_t)bl | ((uint16_t)bh << 8); - return(wRet); -} -/******************************************************************************* -* Function Name : ByteSwap -* Description : Swap two byte in a word. -* Input : wSwW: word to Swap. -* Output : None. -* Return : resulted word. -*******************************************************************************/ -uint16_t ByteSwap(uint16_t wSwW) -{ - uint8_t bTemp; - uint16_t wRet; - bTemp = (uint8_t)(wSwW & 0xff); - wRet = (wSwW >> 8) | ((uint16_t)bTemp << 8); - return(wRet); -} - -#endif /* STM32F10X_CL */ -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_regs.c +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Interface functions to USB cell registers +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ +#ifndef STM32F10X_CL + +/* Includes ------------------------------------------------------------------*/ +#include "usb_lib.h" + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Extern variables ----------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/******************************************************************************* +* Function Name : SetCNTR. +* Description : Set the CNTR register value. +* Input : wRegValue: new register value. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetCNTR(uint16_t wRegValue) +{ + _SetCNTR(wRegValue); +} + +/******************************************************************************* +* Function Name : GetCNTR. +* Description : returns the CNTR register value. +* Input : None. +* Output : None. +* Return : CNTR register Value. +*******************************************************************************/ +uint16_t GetCNTR(void) +{ + return(_GetCNTR()); +} + +/******************************************************************************* +* Function Name : SetISTR. +* Description : Set the ISTR register value. +* Input : wRegValue: new register value. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetISTR(uint16_t wRegValue) +{ + _SetISTR(wRegValue); +} + +/******************************************************************************* +* Function Name : GetISTR +* Description : Returns the ISTR register value. +* Input : None. +* Output : None. +* Return : ISTR register Value +*******************************************************************************/ +uint16_t GetISTR(void) +{ + return(_GetISTR()); +} + +/******************************************************************************* +* Function Name : GetFNR +* Description : Returns the FNR register value. +* Input : None. +* Output : None. +* Return : FNR register Value +*******************************************************************************/ +uint16_t GetFNR(void) +{ + return(_GetFNR()); +} + +/******************************************************************************* +* Function Name : SetDADDR +* Description : Set the DADDR register value. +* Input : wRegValue: new register value. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetDADDR(uint16_t wRegValue) +{ + _SetDADDR(wRegValue); +} + +/******************************************************************************* +* Function Name : GetDADDR +* Description : Returns the DADDR register value. +* Input : None. +* Output : None. +* Return : DADDR register Value +*******************************************************************************/ +uint16_t GetDADDR(void) +{ + return(_GetDADDR()); +} + +/******************************************************************************* +* Function Name : SetBTABLE +* Description : Set the BTABLE. +* Input : wRegValue: New register value. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetBTABLE(uint16_t wRegValue) +{ + _SetBTABLE(wRegValue); +} + +/******************************************************************************* +* Function Name : GetBTABLE. +* Description : Returns the BTABLE register value. +* Input : None. +* Output : None. +* Return : BTABLE address. +*******************************************************************************/ +uint16_t GetBTABLE(void) +{ + return(_GetBTABLE()); +} + +/******************************************************************************* +* Function Name : SetENDPOINT +* Description : Setthe Endpoint register value. +* Input : bEpNum: Endpoint Number. +* wRegValue. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetENDPOINT(uint8_t bEpNum, uint16_t wRegValue) +{ + _SetENDPOINT(bEpNum, wRegValue); +} + +/******************************************************************************* +* Function Name : GetENDPOINT +* Description : Return the Endpoint register value. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Endpoint register value. +*******************************************************************************/ +uint16_t GetENDPOINT(uint8_t bEpNum) +{ + return(_GetENDPOINT(bEpNum)); +} + +/******************************************************************************* +* Function Name : SetEPType +* Description : sets the type in the endpoint register. +* Input : bEpNum: Endpoint Number. +* wType: type definition. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPType(uint8_t bEpNum, uint16_t wType) +{ + _SetEPType(bEpNum, wType); +} + +/******************************************************************************* +* Function Name : GetEPType +* Description : Returns the endpoint type. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Endpoint Type +*******************************************************************************/ +uint16_t GetEPType(uint8_t bEpNum) +{ + return(_GetEPType(bEpNum)); +} + +/******************************************************************************* +* Function Name : SetEPTxStatus +* Description : Set the status of Tx endpoint. +* Input : bEpNum: Endpoint Number. +* wState: new state. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPTxStatus(uint8_t bEpNum, uint16_t wState) +{ + _SetEPTxStatus(bEpNum, wState); +} + +/******************************************************************************* +* Function Name : SetEPRxStatus +* Description : Set the status of Rx endpoint. +* Input : bEpNum: Endpoint Number. +* wState: new state. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPRxStatus(uint8_t bEpNum, uint16_t wState) +{ + _SetEPRxStatus(bEpNum, wState); +} + +/******************************************************************************* +* Function Name : SetDouBleBuffEPStall +* Description : sets the status for Double Buffer Endpoint to STALL +* Input : bEpNum: Endpoint Number. +* bDir: Endpoint direction. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetDouBleBuffEPStall(uint8_t bEpNum, uint8_t bDir) +{ + uint16_t Endpoint_DTOG_Status; + Endpoint_DTOG_Status = GetENDPOINT(bEpNum); + if (bDir == EP_DBUF_OUT) + { /* OUT double buffered endpoint */ + _SetENDPOINT(bEpNum, Endpoint_DTOG_Status & ~EPRX_DTOG1); + } + else if (bDir == EP_DBUF_IN) + { /* IN double buffered endpoint */ + _SetENDPOINT(bEpNum, Endpoint_DTOG_Status & ~EPTX_DTOG1); + } +} + +/******************************************************************************* +* Function Name : GetEPTxStatus +* Description : Returns the endpoint Tx status. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Endpoint TX Status +*******************************************************************************/ +uint16_t GetEPTxStatus(uint8_t bEpNum) +{ + return(_GetEPTxStatus(bEpNum)); +} + +/******************************************************************************* +* Function Name : GetEPRxStatus +* Description : Returns the endpoint Rx status. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Endpoint RX Status +*******************************************************************************/ +uint16_t GetEPRxStatus(uint8_t bEpNum) +{ + return(_GetEPRxStatus(bEpNum)); +} + +/******************************************************************************* +* Function Name : SetEPTxValid +* Description : Valid the endpoint Tx Status. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPTxValid(uint8_t bEpNum) +{ + _SetEPTxStatus(bEpNum, EP_TX_VALID); +} + +/******************************************************************************* +* Function Name : SetEPRxValid +* Description : Valid the endpoint Rx Status. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPRxValid(uint8_t bEpNum) +{ + _SetEPRxStatus(bEpNum, EP_RX_VALID); +} + +/******************************************************************************* +* Function Name : SetEP_KIND +* Description : Clear the EP_KIND bit. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEP_KIND(uint8_t bEpNum) +{ + _SetEP_KIND(bEpNum); +} + +/******************************************************************************* +* Function Name : ClearEP_KIND +* Description : set the EP_KIND bit. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void ClearEP_KIND(uint8_t bEpNum) +{ + _ClearEP_KIND(bEpNum); +} +/******************************************************************************* +* Function Name : Clear_Status_Out +* Description : Clear the Status Out of the related Endpoint +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void Clear_Status_Out(uint8_t bEpNum) +{ + _ClearEP_KIND(bEpNum); +} +/******************************************************************************* +* Function Name : Set_Status_Out +* Description : Set the Status Out of the related Endpoint +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void Set_Status_Out(uint8_t bEpNum) +{ + _SetEP_KIND(bEpNum); +} +/******************************************************************************* +* Function Name : SetEPDoubleBuff +* Description : Enable the double buffer feature for the endpoint. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPDoubleBuff(uint8_t bEpNum) +{ + _SetEP_KIND(bEpNum); +} +/******************************************************************************* +* Function Name : ClearEPDoubleBuff +* Description : Disable the double buffer feature for the endpoint. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void ClearEPDoubleBuff(uint8_t bEpNum) +{ + _ClearEP_KIND(bEpNum); +} +/******************************************************************************* +* Function Name : GetTxStallStatus +* Description : Returns the Stall status of the Tx endpoint. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Tx Stall status. +*******************************************************************************/ +uint16_t GetTxStallStatus(uint8_t bEpNum) +{ + return(_GetTxStallStatus(bEpNum)); +} +/******************************************************************************* +* Function Name : GetRxStallStatus +* Description : Returns the Stall status of the Rx endpoint. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Rx Stall status. +*******************************************************************************/ +uint16_t GetRxStallStatus(uint8_t bEpNum) +{ + return(_GetRxStallStatus(bEpNum)); +} +/******************************************************************************* +* Function Name : ClearEP_CTR_RX +* Description : Clear the CTR_RX bit. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void ClearEP_CTR_RX(uint8_t bEpNum) +{ + _ClearEP_CTR_RX(bEpNum); +} +/******************************************************************************* +* Function Name : ClearEP_CTR_TX +* Description : Clear the CTR_TX bit. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void ClearEP_CTR_TX(uint8_t bEpNum) +{ + _ClearEP_CTR_TX(bEpNum); +} +/******************************************************************************* +* Function Name : ToggleDTOG_RX +* Description : Toggle the DTOG_RX bit. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void ToggleDTOG_RX(uint8_t bEpNum) +{ + _ToggleDTOG_RX(bEpNum); +} +/******************************************************************************* +* Function Name : ToggleDTOG_TX +* Description : Toggle the DTOG_TX bit. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void ToggleDTOG_TX(uint8_t bEpNum) +{ + _ToggleDTOG_TX(bEpNum); +} +/******************************************************************************* +* Function Name : ClearDTOG_RX. +* Description : Clear the DTOG_RX bit. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void ClearDTOG_RX(uint8_t bEpNum) +{ + _ClearDTOG_RX(bEpNum); +} +/******************************************************************************* +* Function Name : ClearDTOG_TX. +* Description : Clear the DTOG_TX bit. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +void ClearDTOG_TX(uint8_t bEpNum) +{ + _ClearDTOG_TX(bEpNum); +} +/******************************************************************************* +* Function Name : SetEPAddress +* Description : Set the endpoint address. +* Input : bEpNum: Endpoint Number. +* bAddr: New endpoint address. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPAddress(uint8_t bEpNum, uint8_t bAddr) +{ + _SetEPAddress(bEpNum, bAddr); +} +/******************************************************************************* +* Function Name : GetEPAddress +* Description : Get the endpoint address. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Endpoint address. +*******************************************************************************/ +uint8_t GetEPAddress(uint8_t bEpNum) +{ + return(_GetEPAddress(bEpNum)); +} +/******************************************************************************* +* Function Name : SetEPTxAddr +* Description : Set the endpoint Tx buffer address. +* Input : bEpNum: Endpoint Number. +* wAddr: new address. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPTxAddr(uint8_t bEpNum, uint16_t wAddr) +{ + _SetEPTxAddr(bEpNum, wAddr); +} +/******************************************************************************* +* Function Name : SetEPRxAddr +* Description : Set the endpoint Rx buffer address. +* Input : bEpNum: Endpoint Number. +* wAddr: new address. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPRxAddr(uint8_t bEpNum, uint16_t wAddr) +{ + _SetEPRxAddr(bEpNum, wAddr); +} +/******************************************************************************* +* Function Name : GetEPTxAddr +* Description : Returns the endpoint Tx buffer address. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Rx buffer address. +*******************************************************************************/ +uint16_t GetEPTxAddr(uint8_t bEpNum) +{ + return(_GetEPTxAddr(bEpNum)); +} +/******************************************************************************* +* Function Name : GetEPRxAddr. +* Description : Returns the endpoint Rx buffer address. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Rx buffer address. +*******************************************************************************/ +uint16_t GetEPRxAddr(uint8_t bEpNum) +{ + return(_GetEPRxAddr(bEpNum)); +} +/******************************************************************************* +* Function Name : SetEPTxCount. +* Description : Set the Tx count. +* Input : bEpNum: Endpoint Number. +* wCount: new count value. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPTxCount(uint8_t bEpNum, uint16_t wCount) +{ + _SetEPTxCount(bEpNum, wCount); +} +/******************************************************************************* +* Function Name : SetEPCountRxReg. +* Description : Set the Count Rx Register value. +* Input : *pdwReg: point to the register. +* wCount: the new register value. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPCountRxReg(uint32_t *pdwReg, uint16_t wCount) +{ + _SetEPCountRxReg(dwReg, wCount); +} +/******************************************************************************* +* Function Name : SetEPRxCount +* Description : Set the Rx count. +* Input : bEpNum: Endpoint Number. +* wCount: the new count value. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPRxCount(uint8_t bEpNum, uint16_t wCount) +{ + _SetEPRxCount(bEpNum, wCount); +} +/******************************************************************************* +* Function Name : GetEPTxCount +* Description : Get the Tx count. +* Input : bEpNum: Endpoint Number. +* Output : None +* Return : Tx count value. +*******************************************************************************/ +uint16_t GetEPTxCount(uint8_t bEpNum) +{ + return(_GetEPTxCount(bEpNum)); +} +/******************************************************************************* +* Function Name : GetEPRxCount +* Description : Get the Rx count. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Rx count value. +*******************************************************************************/ +uint16_t GetEPRxCount(uint8_t bEpNum) +{ + return(_GetEPRxCount(bEpNum)); +} +/******************************************************************************* +* Function Name : SetEPDblBuffAddr +* Description : Set the addresses of the buffer 0 and 1. +* Input : bEpNum: Endpoint Number. +* wBuf0Addr: new address of buffer 0. +* wBuf1Addr: new address of buffer 1. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPDblBuffAddr(uint8_t bEpNum, uint16_t wBuf0Addr, uint16_t wBuf1Addr) +{ + _SetEPDblBuffAddr(bEpNum, wBuf0Addr, wBuf1Addr); +} +/******************************************************************************* +* Function Name : SetEPDblBuf0Addr +* Description : Set the Buffer 1 address. +* Input : bEpNum: Endpoint Number +* wBuf0Addr: new address. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPDblBuf0Addr(uint8_t bEpNum, uint16_t wBuf0Addr) +{ + _SetEPDblBuf0Addr(bEpNum, wBuf0Addr); +} +/******************************************************************************* +* Function Name : SetEPDblBuf1Addr +* Description : Set the Buffer 1 address. +* Input : bEpNum: Endpoint Number +* wBuf1Addr: new address. +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPDblBuf1Addr(uint8_t bEpNum, uint16_t wBuf1Addr) +{ + _SetEPDblBuf1Addr(bEpNum, wBuf1Addr); +} +/******************************************************************************* +* Function Name : GetEPDblBuf0Addr +* Description : Returns the address of the Buffer 0. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : None. +*******************************************************************************/ +uint16_t GetEPDblBuf0Addr(uint8_t bEpNum) +{ + return(_GetEPDblBuf0Addr(bEpNum)); +} +/******************************************************************************* +* Function Name : GetEPDblBuf1Addr +* Description : Returns the address of the Buffer 1. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Address of the Buffer 1. +*******************************************************************************/ +uint16_t GetEPDblBuf1Addr(uint8_t bEpNum) +{ + return(_GetEPDblBuf1Addr(bEpNum)); +} +/******************************************************************************* +* Function Name : SetEPDblBuffCount +* Description : Set the number of bytes for a double Buffer +* endpoint. +* Input : bEpNum,bDir, wCount +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPDblBuffCount(uint8_t bEpNum, uint8_t bDir, uint16_t wCount) +{ + _SetEPDblBuffCount(bEpNum, bDir, wCount); +} +/******************************************************************************* +* Function Name : SetEPDblBuf0Count +* Description : Set the number of bytes in the buffer 0 of a double Buffer +* endpoint. +* Input : bEpNum, bDir, wCount +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPDblBuf0Count(uint8_t bEpNum, uint8_t bDir, uint16_t wCount) +{ + _SetEPDblBuf0Count(bEpNum, bDir, wCount); +} +/******************************************************************************* +* Function Name : SetEPDblBuf1Count +* Description : Set the number of bytes in the buffer 0 of a double Buffer +* endpoint. +* Input : bEpNum, bDir, wCount +* Output : None. +* Return : None. +*******************************************************************************/ +void SetEPDblBuf1Count(uint8_t bEpNum, uint8_t bDir, uint16_t wCount) +{ + _SetEPDblBuf1Count(bEpNum, bDir, wCount); +} +/******************************************************************************* +* Function Name : GetEPDblBuf0Count +* Description : Returns the number of byte received in the buffer 0 of a double +* Buffer endpoint. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Endpoint Buffer 0 count +*******************************************************************************/ +uint16_t GetEPDblBuf0Count(uint8_t bEpNum) +{ + return(_GetEPDblBuf0Count(bEpNum)); +} +/******************************************************************************* +* Function Name : GetEPDblBuf1Count +* Description : Returns the number of data received in the buffer 1 of a double +* Buffer endpoint. +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : Endpoint Buffer 1 count. +*******************************************************************************/ +uint16_t GetEPDblBuf1Count(uint8_t bEpNum) +{ + return(_GetEPDblBuf1Count(bEpNum)); +} +/******************************************************************************* +* Function Name : GetEPDblBufDir +* Description : gets direction of the double buffered endpoint +* Input : bEpNum: Endpoint Number. +* Output : None. +* Return : EP_DBUF_OUT, EP_DBUF_IN, +* EP_DBUF_ERR if the endpoint counter not yet programmed. +*******************************************************************************/ +EP_DBUF_DIR GetEPDblBufDir(uint8_t bEpNum) +{ + if ((uint16_t)(*_pEPRxCount(bEpNum) & 0xFC00) != 0) + return(EP_DBUF_OUT); + else if (((uint16_t)(*_pEPTxCount(bEpNum)) & 0x03FF) != 0) + return(EP_DBUF_IN); + else + return(EP_DBUF_ERR); +} +/******************************************************************************* +* Function Name : FreeUserBuffer +* Description : free buffer used from the application realizing it to the line + toggles bit SW_BUF in the double buffered endpoint register +* Input : bEpNum, bDir +* Output : None. +* Return : None. +*******************************************************************************/ +void FreeUserBuffer(uint8_t bEpNum, uint8_t bDir) +{ + if (bDir == EP_DBUF_OUT) + { /* OUT double buffered endpoint */ + _ToggleDTOG_TX(bEpNum); + } + else if (bDir == EP_DBUF_IN) + { /* IN double buffered endpoint */ + _ToggleDTOG_RX(bEpNum); + } +} + +/******************************************************************************* +* Function Name : ToWord +* Description : merge two byte in a word. +* Input : bh: byte high, bl: bytes low. +* Output : None. +* Return : resulted word. +*******************************************************************************/ +uint16_t ToWord(uint8_t bh, uint8_t bl) +{ + uint16_t wRet; + wRet = (uint16_t)bl | ((uint16_t)bh << 8); + return(wRet); +} +/******************************************************************************* +* Function Name : ByteSwap +* Description : Swap two byte in a word. +* Input : wSwW: word to Swap. +* Output : None. +* Return : resulted word. +*******************************************************************************/ +uint16_t ByteSwap(uint16_t wSwW) +{ + uint8_t bTemp; + uint16_t wRet; + bTemp = (uint8_t)(wSwW & 0xff); + wRet = (wSwW >> 8) | ((uint16_t)bTemp << 8); + return(wRet); +} + +#endif /* STM32F10X_CL */ +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_sil.c b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_sil.c index 524ba75cb..e50d076ff 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_sil.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_sil.c @@ -1,126 +1,126 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_sil.c -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Simplified Interface Layer for Global Initialization and -* Endpoint Rea/Write operations. -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Includes ------------------------------------------------------------------*/ -#include "usb_lib.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Extern variables ----------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/******************************************************************************* -* Function Name : USB_SIL_Init -* Description : Initialize the USB Device IP and the Endpoint 0. -* Input : None. -* Output : None. -* Return : Status. -*******************************************************************************/ -uint32_t USB_SIL_Init(void) -{ -#ifndef STM32F10X_CL - - /* USB interrupts initialization */ - /* clear pending interrupts */ - _SetISTR(0); - wInterrupt_Mask = IMR_MSK; - /* set interrupts mask */ - _SetCNTR(wInterrupt_Mask); - -#else - - /* Perform OTG Device initialization procedure (including EP0 init) */ - OTG_DEV_Init(); - -#endif /* STM32F10X_CL */ - - return 0; -} - -/******************************************************************************* -* Function Name : USB_SIL_Write -* Description : Write a buffer of data to a selected endpoint. -* Input : - bEpAddr: The address of the non control endpoint. -* - pBufferPointer: The pointer to the buffer of data to be written -* to the endpoint. -* - wBufferSize: Number of data to be written (in bytes). -* Output : None. -* Return : Status. -*******************************************************************************/ -uint32_t USB_SIL_Write(uint8_t bEpAddr, uint8_t* pBufferPointer, uint32_t wBufferSize) -{ -#ifndef STM32F10X_CL - - /* Use the memory interface function to write to the selected endpoint */ - UserToPMABufferCopy(pBufferPointer, GetEPTxAddr(bEpAddr & 0x7F), wBufferSize); - - /* Update the data length in the control register */ - SetEPTxCount((bEpAddr & 0x7F), wBufferSize); - -#else - - /* Use the PCD interface layer function to write to the selected endpoint */ - PCD_EP_Write (bEpAddr, pBufferPointer, wBufferSize); - -#endif /* STM32F10X_CL */ - - return 0; -} - -/******************************************************************************* -* Function Name : USB_SIL_Read -* Description : Write a buffer of data to a selected endpoint. -* Input : - bEpAddr: The address of the non control endpoint. -* - pBufferPointer: The pointer to which will be saved the -* received data buffer. -* Output : None. -* Return : Number of received data (in Bytes). -*******************************************************************************/ -uint32_t USB_SIL_Read(uint8_t bEpAddr, uint8_t* pBufferPointer) -{ - uint32_t DataLength = 0; - -#ifndef STM32F10X_CL - - /* Get the number of received data on the selected Endpoint */ - DataLength = GetEPRxCount(bEpAddr & 0x7F); - - /* Use the memory interface function to write to the selected endpoint */ - PMAToUserBufferCopy(pBufferPointer, GetEPRxAddr(bEpAddr & 0x7F), DataLength); - -#else - - USB_OTG_EP *ep; - - /* Get the structure pointer of the selected Endpoint */ - ep = PCD_GetOutEP(bEpAddr); - - /* Get the number of received data */ - DataLength = ep->xfer_len; - - /* Use the PCD interface layer function to read the selected endpoint */ - PCD_EP_Read (bEpAddr, pBufferPointer, DataLength); - -#endif /* STM32F10X_CL */ - - /* Return the number of received data */ - return DataLength; -} - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** +* File Name : usb_sil.c +* Author : MCD Application Team +* Version : V3.2.1 +* Date : 07/05/2010 +* Description : Simplified Interface Layer for Global Initialization and +* Endpoint Rea/Write operations. +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Includes ------------------------------------------------------------------*/ +#include "usb_lib.h" + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Extern variables ----------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/******************************************************************************* +* Function Name : USB_SIL_Init +* Description : Initialize the USB Device IP and the Endpoint 0. +* Input : None. +* Output : None. +* Return : Status. +*******************************************************************************/ +uint32_t USB_SIL_Init(void) +{ +#ifndef STM32F10X_CL + + /* USB interrupts initialization */ + /* clear pending interrupts */ + _SetISTR(0); + wInterrupt_Mask = IMR_MSK; + /* set interrupts mask */ + _SetCNTR(wInterrupt_Mask); + +#else + + /* Perform OTG Device initialization procedure (including EP0 init) */ + OTG_DEV_Init(); + +#endif /* STM32F10X_CL */ + + return 0; +} + +/******************************************************************************* +* Function Name : USB_SIL_Write +* Description : Write a buffer of data to a selected endpoint. +* Input : - bEpAddr: The address of the non control endpoint. +* - pBufferPointer: The pointer to the buffer of data to be written +* to the endpoint. +* - wBufferSize: Number of data to be written (in bytes). +* Output : None. +* Return : Status. +*******************************************************************************/ +uint32_t USB_SIL_Write(uint8_t bEpAddr, uint8_t* pBufferPointer, uint32_t wBufferSize) +{ +#ifndef STM32F10X_CL + + /* Use the memory interface function to write to the selected endpoint */ + UserToPMABufferCopy(pBufferPointer, GetEPTxAddr(bEpAddr & 0x7F), wBufferSize); + + /* Update the data length in the control register */ + SetEPTxCount((bEpAddr & 0x7F), wBufferSize); + +#else + + /* Use the PCD interface layer function to write to the selected endpoint */ + PCD_EP_Write (bEpAddr, pBufferPointer, wBufferSize); + +#endif /* STM32F10X_CL */ + + return 0; +} + +/******************************************************************************* +* Function Name : USB_SIL_Read +* Description : Write a buffer of data to a selected endpoint. +* Input : - bEpAddr: The address of the non control endpoint. +* - pBufferPointer: The pointer to which will be saved the +* received data buffer. +* Output : None. +* Return : Number of received data (in Bytes). +*******************************************************************************/ +uint32_t USB_SIL_Read(uint8_t bEpAddr, uint8_t* pBufferPointer) +{ + uint32_t DataLength = 0; + +#ifndef STM32F10X_CL + + /* Get the number of received data on the selected Endpoint */ + DataLength = GetEPRxCount(bEpAddr & 0x7F); + + /* Use the memory interface function to write to the selected endpoint */ + PMAToUserBufferCopy(pBufferPointer, GetEPRxAddr(bEpAddr & 0x7F), DataLength); + +#else + + USB_OTG_EP *ep; + + /* Get the structure pointer of the selected Endpoint */ + ep = PCD_GetOutEP(bEpAddr); + + /* Get the number of received data */ + DataLength = ep->xfer_len; + + /* Use the PCD interface layer function to read the selected endpoint */ + PCD_EP_Read (bEpAddr, pBufferPointer, DataLength); + +#endif /* STM32F10X_CL */ + + /* Return the number of received data */ + return DataLength; +} + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd.c b/flight/PiOS/STM32F10x/Libraries/msd/msd.c index 5355f1aee..264edca9a 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd.c +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd.c @@ -1,441 +1,441 @@ -/** - ****************************************************************************** - * - * @file msd.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief USB Mass Storage Device Driver - * @see The GNU Public License (GPL) Version 3 - * @defgroup MSD MSD Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Include files */ -#include -#include - -#include - -#include "msd.h" -#include "msd_desc.h" -#include "msd_bot.h" -#include "msd_memory.h" - -/* Local definitions */ - -/* MASS Storage Requests */ -#define GET_MAX_LUN 0xFE -#define MASS_STORAGE_RESET 0xFF -#define LUN_DATA_LENGTH 1 - -/* ISTR events */ -/* IMR_MSK */ -/* mask defining which events has to be handled */ -/* by the device application software */ -#define MSD_IMR_MSK (CNTR_RESETM) - -/* Local prototypes */ -static void MSD_MASS_Reset(void); -static void MSD_Mass_Storage_SetConfiguration(void); -static void MSD_Mass_Storage_ClearFeature(void); -static void MSD_Mass_Storage_SetDeviceAddress(void); -static void MSD_MASS_Status_In(void); -static void MSD_MASS_Status_Out(void); -static RESULT MSD_MASS_Data_Setup(uint8_t); -static RESULT MSD_MASS_NoData_Setup(uint8_t); -static RESULT MSD_MASS_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting); -static uint8_t *MSD_MASS_GetDeviceDescriptor(uint16_t); -static uint8_t *MSD_MASS_GetConfigDescriptor(uint16_t); -static uint8_t *MSD_MASS_GetStringDescriptor(uint16_t); -static uint8_t *Get_Max_Lun(uint16_t Length); - -/* Local variables */ -static const DEVICE My_Device_Table = {MSD_EP_NUM, 1}; -static const DEVICE_PROP My_Device_Property = { - 0, // Init hook not used, done by PIOS_USB module! - MSD_MASS_Reset, MSD_MASS_Status_In, MSD_MASS_Status_Out, MSD_MASS_Data_Setup, MSD_MASS_NoData_Setup, MSD_MASS_Get_Interface_Setting, - MSD_MASS_GetDeviceDescriptor, MSD_MASS_GetConfigDescriptor, MSD_MASS_GetStringDescriptor, 0, 0x40 /*MAX PACKET SIZE*/ -}; -static const USER_STANDARD_REQUESTS My_User_Standard_Requests = { - NOP_Process, - MSD_Mass_Storage_SetConfiguration, - NOP_Process, - NOP_Process, - NOP_Process, - MSD_Mass_Storage_ClearFeature, - NOP_Process, NOP_Process, - MSD_Mass_Storage_SetDeviceAddress -}; -static ONE_DESCRIPTOR Device_Descriptor = {(uint8_t *) MSD_MASS_DeviceDescriptor, MSD_MASS_SIZ_DEVICE_DESC}; -static ONE_DESCRIPTOR Config_Descriptor = {(uint8_t *) MSD_MASS_ConfigDescriptor, MSD_MASS_SIZ_CONFIG_DESC}; -static ONE_DESCRIPTOR String_Descriptor[5] = { - {(uint8_t *) MSD_MASS_StringLangID, MSD_MASS_SIZ_STRING_LANGID}, - {(uint8_t *) MSD_MASS_StringVendor, MSD_MASS_SIZ_STRING_VENDOR}, - {(uint8_t *) MSD_MASS_StringProduct, MSD_MASS_SIZ_STRING_PRODUCT}, - {(uint8_t *) MSD_MASS_StringSerial, MSD_MASS_SIZ_STRING_SERIAL}, - {(uint8_t *) MSD_MASS_StringInterface, MSD_MASS_SIZ_STRING_INTERFACE}, -}; -static uint8_t lun_available; - -/** -* Initialises the USB Device Driver for a Mass Storage Device -* -* Should be called during runtime once a SD Card has been connected.
-* It is possible to switch back to the original device driver provided -* by calling PIOS_USB_Init(1) -* -* \param[in] mode currently only mode 0 supported -* \return < 0 if initialisation failed -*/ -int32_t MSD_Init(uint32_t mode) -{ - /* Update the serial number string descriptor with the data from the unique ID*/ - uint8_t serial_number_str[40]; - int i, len; - PIOS_SYS_SerialNumberGet((char *) serial_number_str); - for(i = 0, len = 0; serial_number_str[i] != '\0' && len < 25; ++i) { - MSD_MASS_StringSerial[len++] = serial_number_str[i]; - MSD_MASS_StringSerial[len++] = 0; - } - - lun_available = 0; - - /* All LUNs available after USB init */ - for(i = 0; i < MSD_NUM_LUN; ++i) { - MSD_LUN_AvailableSet(i, 1); - } - - PIOS_IRQ_Disable(); - - /* Clear all USB interrupt requests */ - _SetCNTR(0); /* Interrupt Mask */ - _SetISTR(0); /* clear pending requests */ - - /* Switch to MSD driver hooks */ - memcpy(&Device_Table, (DEVICE *) &My_Device_Table, sizeof(Device_Table)); - pProperty = (DEVICE_PROP *) &My_Device_Property; - pUser_Standard_Requests = (USER_STANDARD_REQUESTS *) &My_User_Standard_Requests; - - /* Change endpoints */ - pEpInt_IN[0] = MSD_Mass_Storage_In; - pEpInt_OUT[1] = MSD_Mass_Storage_Out; - - /* Force re-enumeration w/o overwriting PIOS hooks */ - PIOS_USB_Init(2); - - /* Clear pending interrupts (again) */ - _SetISTR(0); - - /* Set interrupts mask */ - _SetCNTR(MSD_IMR_MSK); - - PIOS_IRQ_Enable(); - - /* No error */ - return 0; -} - -/** -* Should be called periodically each millisecond so long this driver is -* active (and only then!) to handle USBtransfers. -* -* Take care that no other task accesses SD Card while this function is -* processed! -* -* Ensure that this function isn't called when a PIOS USB driver is running! -* -* \return < 0 on errors -*/ -int32_t MSD_Periodic_mS(void) -{ - /* Call endpoint handler of STM32 USB driver */ - CTR_LP(); - - /* No error */ - return 0; -} - -/** -* This function returns the connection status of the USB HID interface -* \return 1: interface available -* \return 0: interface not available -*/ -int32_t MSD_CheckAvailable(void) -{ - return pInformation->Current_Configuration ? 1 : 0; -} - -/** -* The logical unit is available whenever MSD_Init() is called, or the USB -* cable has been reconnected. -* -* It will be disabled when the host unmounts the file system (like if the -* SD Card would be removed. -* -* When this happens, the application can either call PIOS_USB_Init(1) -* again, e.g. to switch to USB HID, or it can make the LUN available -* again by calling MSD_LUN_AvailableSet(0, 1) -* \param[in] lun Logical Unit number (0) -* \param[in] available 0 or 1 -* \return < 0 on errors -*/ -int32_t MSD_LUN_AvailableSet(uint8_t lun, uint8_t available) -{ - if(lun >= MSD_NUM_LUN) { - return -1; - } - - if(available) { - lun_available |= (1 << lun); - } else { - lun_available &= ~(1 << lun); - } - - /* No error */ - return 0; -} - -/** -* \return 1 if device is mounted by host -* \return 0 if device is not mounted by host -*/ -int32_t MSD_LUN_AvailableGet(uint8_t lun) -{ - if(lun >= MSD_NUM_LUN) - return 0; - - return (lun_available & (1 << lun)) ? 1 : 0; -} - -/** -* Mass Storage reset routine. -*/ -static void MSD_MASS_Reset() -{ - /* Set the device as not configured */ - pInformation->Current_Configuration = 0; - - /* Current Feature initialization */ - pInformation->Current_Feature = MSD_MASS_ConfigDescriptor[7]; - - SetBTABLE(MSD_BTABLE_ADDRESS); - - /* Initialize Endpoint 0 */ - SetEPType(ENDP0, EP_CONTROL); - SetEPTxStatus(ENDP0, EP_TX_NAK); - SetEPRxAddr(ENDP0, MSD_ENDP0_RXADDR); - SetEPRxCount(ENDP0, pProperty->MaxPacketSize); - SetEPTxAddr(ENDP0, MSD_ENDP0_TXADDR); - Clear_Status_Out(ENDP0); - SetEPRxValid(ENDP0); - - /* Initialize Endpoint 1 */ - SetEPType(ENDP1, EP_BULK); - SetEPTxAddr(ENDP1, MSD_ENDP1_TXADDR); - SetEPTxStatus(ENDP1, EP_TX_NAK); - SetEPRxStatus(ENDP1, EP_RX_DIS); - - /* Initialize Endpoint 2 */ - SetEPType(ENDP2, EP_BULK); - SetEPRxAddr(ENDP2, MSD_ENDP2_RXADDR); - SetEPRxCount(ENDP2, pProperty->MaxPacketSize); - SetEPRxStatus(ENDP2, EP_RX_VALID); - SetEPTxStatus(ENDP2, EP_TX_DIS); - - SetEPRxCount(ENDP0, pProperty->MaxPacketSize); - SetEPRxValid(ENDP0); - - /* Set the device to response on default address */ - SetDeviceAddress(0); - - MSD_CBW.dSignature = BOT_CBW_SIGNATURE; - MSD_Bot_State = BOT_IDLE; -} - -/** -* Handle the SetConfiguration request. -*/ -static void MSD_Mass_Storage_SetConfiguration(void) -{ - if(pInformation->Current_Configuration != 0) { - ClearDTOG_TX(ENDP1); - ClearDTOG_RX(ENDP2); - MSD_Bot_State = BOT_IDLE; /* Set the Bot state machine to the IDLE state */ - - /* All LUNs available after USB (re-)connection */ - for(int i = 0; i < MSD_NUM_LUN; ++i) { - MSD_LUN_AvailableSet(i, 1); - } - } -} - -/** -* Handle the ClearFeature request. -*/ -static void MSD_Mass_Storage_ClearFeature(void) -{ - /* When the host send a CBW with invalid signature or invalid length the two */ - /* Endpoints (IN & OUT) shall stall until receiving a Mass Storage Reset */ - if(MSD_CBW.dSignature != BOT_CBW_SIGNATURE) { - MSD_Bot_Abort(BOTH_DIR); - } -} - -/** -* Udpade the device state to addressed. -*/ -static void MSD_Mass_Storage_SetDeviceAddress(void) -{ - -} - -/** -* Mass Storage Status IN routine. -*/ -static void MSD_MASS_Status_In(void) -{ - return; -} - -/******************************************************************************* -* Mass Storage Status OUT routine. -*/ -static void MSD_MASS_Status_Out(void) -{ - return; -} - -/******************************************************************************* -* Handle the data class specific requests.. -* \param[in] RequestNo -* \return RESULT -*/ -static RESULT MSD_MASS_Data_Setup(uint8_t RequestNo) -{ - uint8_t *(*CopyRoutine)( uint16_t); - - CopyRoutine = NULL; - if((Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) && (RequestNo == GET_MAX_LUN) && (pInformation->USBwValue == 0) - && (pInformation->USBwIndex == 0) && (pInformation->USBwLength == 0x01)) { - CopyRoutine = Get_Max_Lun; - } else { - return USB_UNSUPPORT; - } - - if(CopyRoutine == NULL) { - return USB_UNSUPPORT; - } - - pInformation->Ctrl_Info.CopyData = CopyRoutine; - pInformation->Ctrl_Info.Usb_wOffset = 0; - (*CopyRoutine)(0); - - return USB_SUCCESS; -} - -/** -* Handle the no data class specific requests. -* \param[in] RequestNo -* \return RESULT -*/ -static RESULT MSD_MASS_NoData_Setup(uint8_t RequestNo) -{ - if((Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) && (RequestNo == MASS_STORAGE_RESET) && (pInformation->USBwValue == 0) - && (pInformation->USBwIndex == 0) && (pInformation->USBwLength == 0x00)) { - /* Initialise Endpoint 1 */ - ClearDTOG_TX(ENDP1); - - /* Initialise Endpoint 2 */ - ClearDTOG_RX(ENDP2); - - /* Initialise the CBW signature to enable the clear feature*/ - MSD_CBW.dSignature = BOT_CBW_SIGNATURE; - MSD_Bot_State = BOT_IDLE; - - return USB_SUCCESS; - } - return USB_UNSUPPORT; -} - -/** -* Test the interface and the alternate setting according to the supported one. -* \param[in] Interface -* \param[in] AlternateSetting -* \return RESULT -*/ -static RESULT MSD_MASS_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting) -{ - if(AlternateSetting > 0) { - return USB_UNSUPPORT;/* In this application we don't have AlternateSetting*/ - } else if(Interface > 0) { - return USB_UNSUPPORT;/* In this application we have only 1 interfaces*/ - } - return USB_SUCCESS; -} - -/** -* Get the device descriptor. -* \param[in] Length -*/ -static uint8_t *MSD_MASS_GetDeviceDescriptor(uint16_t Length) -{ - return Standard_GetDescriptorData(Length, &Device_Descriptor); -} - -/** -* Get the configuration descriptor. -* \param[in] Length -*/ -static uint8_t *MSD_MASS_GetConfigDescriptor(uint16_t Length) -{ - return Standard_GetDescriptorData(Length, &Config_Descriptor); -} - -/** -* Get the string descriptors according to the needed index. -* \param[in] Length -*/ -static uint8_t *MSD_MASS_GetStringDescriptor(uint16_t Length) -{ - uint8_t wValue0 = pInformation->USBwValue0; - - if(wValue0 > 5) { - return NULL; - } else { - return Standard_GetDescriptorData(Length, &String_Descriptor[wValue0]); - } -} - -/** -* Handle the Get Max Lun request. -* \param[in] Length -*/ -static uint8_t *Get_Max_Lun(uint16_t Length) -{ - static uint32_t Max_Lun = MSD_NUM_LUN - 1; - - if(Length == 0) { - pInformation->Ctrl_Info.Usb_wLength = LUN_DATA_LENGTH; - return 0; - } else { - /* This copy concept requires statically allocated data... grr! */ - return ((uint8_t*) (&Max_Lun)); - } -} - +/** + ****************************************************************************** + * + * @file msd.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief USB Mass Storage Device Driver + * @see The GNU Public License (GPL) Version 3 + * @defgroup MSD MSD Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Include files */ +#include +#include + +#include + +#include "msd.h" +#include "msd_desc.h" +#include "msd_bot.h" +#include "msd_memory.h" + +/* Local definitions */ + +/* MASS Storage Requests */ +#define GET_MAX_LUN 0xFE +#define MASS_STORAGE_RESET 0xFF +#define LUN_DATA_LENGTH 1 + +/* ISTR events */ +/* IMR_MSK */ +/* mask defining which events has to be handled */ +/* by the device application software */ +#define MSD_IMR_MSK (CNTR_RESETM) + +/* Local prototypes */ +static void MSD_MASS_Reset(void); +static void MSD_Mass_Storage_SetConfiguration(void); +static void MSD_Mass_Storage_ClearFeature(void); +static void MSD_Mass_Storage_SetDeviceAddress(void); +static void MSD_MASS_Status_In(void); +static void MSD_MASS_Status_Out(void); +static RESULT MSD_MASS_Data_Setup(uint8_t); +static RESULT MSD_MASS_NoData_Setup(uint8_t); +static RESULT MSD_MASS_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting); +static uint8_t *MSD_MASS_GetDeviceDescriptor(uint16_t); +static uint8_t *MSD_MASS_GetConfigDescriptor(uint16_t); +static uint8_t *MSD_MASS_GetStringDescriptor(uint16_t); +static uint8_t *Get_Max_Lun(uint16_t Length); + +/* Local variables */ +static const DEVICE My_Device_Table = {MSD_EP_NUM, 1}; +static const DEVICE_PROP My_Device_Property = { + 0, // Init hook not used, done by PIOS_USB module! + MSD_MASS_Reset, MSD_MASS_Status_In, MSD_MASS_Status_Out, MSD_MASS_Data_Setup, MSD_MASS_NoData_Setup, MSD_MASS_Get_Interface_Setting, + MSD_MASS_GetDeviceDescriptor, MSD_MASS_GetConfigDescriptor, MSD_MASS_GetStringDescriptor, 0, 0x40 /*MAX PACKET SIZE*/ +}; +static const USER_STANDARD_REQUESTS My_User_Standard_Requests = { + NOP_Process, + MSD_Mass_Storage_SetConfiguration, + NOP_Process, + NOP_Process, + NOP_Process, + MSD_Mass_Storage_ClearFeature, + NOP_Process, NOP_Process, + MSD_Mass_Storage_SetDeviceAddress +}; +static ONE_DESCRIPTOR Device_Descriptor = {(uint8_t *) MSD_MASS_DeviceDescriptor, MSD_MASS_SIZ_DEVICE_DESC}; +static ONE_DESCRIPTOR Config_Descriptor = {(uint8_t *) MSD_MASS_ConfigDescriptor, MSD_MASS_SIZ_CONFIG_DESC}; +static ONE_DESCRIPTOR String_Descriptor[5] = { + {(uint8_t *) MSD_MASS_StringLangID, MSD_MASS_SIZ_STRING_LANGID}, + {(uint8_t *) MSD_MASS_StringVendor, MSD_MASS_SIZ_STRING_VENDOR}, + {(uint8_t *) MSD_MASS_StringProduct, MSD_MASS_SIZ_STRING_PRODUCT}, + {(uint8_t *) MSD_MASS_StringSerial, MSD_MASS_SIZ_STRING_SERIAL}, + {(uint8_t *) MSD_MASS_StringInterface, MSD_MASS_SIZ_STRING_INTERFACE}, +}; +static uint8_t lun_available; + +/** +* Initialises the USB Device Driver for a Mass Storage Device +* +* Should be called during runtime once a SD Card has been connected.
+* It is possible to switch back to the original device driver provided +* by calling PIOS_USB_Init(1) +* +* \param[in] mode currently only mode 0 supported +* \return < 0 if initialisation failed +*/ +int32_t MSD_Init(uint32_t mode) +{ + /* Update the serial number string descriptor with the data from the unique ID*/ + uint8_t serial_number_str[40]; + int i, len; + PIOS_SYS_SerialNumberGet((char *) serial_number_str); + for(i = 0, len = 0; serial_number_str[i] != '\0' && len < 25; ++i) { + MSD_MASS_StringSerial[len++] = serial_number_str[i]; + MSD_MASS_StringSerial[len++] = 0; + } + + lun_available = 0; + + /* All LUNs available after USB init */ + for(i = 0; i < MSD_NUM_LUN; ++i) { + MSD_LUN_AvailableSet(i, 1); + } + + PIOS_IRQ_Disable(); + + /* Clear all USB interrupt requests */ + _SetCNTR(0); /* Interrupt Mask */ + _SetISTR(0); /* clear pending requests */ + + /* Switch to MSD driver hooks */ + memcpy(&Device_Table, (DEVICE *) &My_Device_Table, sizeof(Device_Table)); + pProperty = (DEVICE_PROP *) &My_Device_Property; + pUser_Standard_Requests = (USER_STANDARD_REQUESTS *) &My_User_Standard_Requests; + + /* Change endpoints */ + pEpInt_IN[0] = MSD_Mass_Storage_In; + pEpInt_OUT[1] = MSD_Mass_Storage_Out; + + /* Force re-enumeration w/o overwriting PIOS hooks */ + PIOS_USB_Init(2); + + /* Clear pending interrupts (again) */ + _SetISTR(0); + + /* Set interrupts mask */ + _SetCNTR(MSD_IMR_MSK); + + PIOS_IRQ_Enable(); + + /* No error */ + return 0; +} + +/** +* Should be called periodically each millisecond so long this driver is +* active (and only then!) to handle USBtransfers. +* +* Take care that no other task accesses SD Card while this function is +* processed! +* +* Ensure that this function isn't called when a PIOS USB driver is running! +* +* \return < 0 on errors +*/ +int32_t MSD_Periodic_mS(void) +{ + /* Call endpoint handler of STM32 USB driver */ + CTR_LP(); + + /* No error */ + return 0; +} + +/** +* This function returns the connection status of the USB HID interface +* \return 1: interface available +* \return 0: interface not available +*/ +int32_t MSD_CheckAvailable(void) +{ + return pInformation->Current_Configuration ? 1 : 0; +} + +/** +* The logical unit is available whenever MSD_Init() is called, or the USB +* cable has been reconnected. +* +* It will be disabled when the host unmounts the file system (like if the +* SD Card would be removed. +* +* When this happens, the application can either call PIOS_USB_Init(1) +* again, e.g. to switch to USB HID, or it can make the LUN available +* again by calling MSD_LUN_AvailableSet(0, 1) +* \param[in] lun Logical Unit number (0) +* \param[in] available 0 or 1 +* \return < 0 on errors +*/ +int32_t MSD_LUN_AvailableSet(uint8_t lun, uint8_t available) +{ + if(lun >= MSD_NUM_LUN) { + return -1; + } + + if(available) { + lun_available |= (1 << lun); + } else { + lun_available &= ~(1 << lun); + } + + /* No error */ + return 0; +} + +/** +* \return 1 if device is mounted by host +* \return 0 if device is not mounted by host +*/ +int32_t MSD_LUN_AvailableGet(uint8_t lun) +{ + if(lun >= MSD_NUM_LUN) + return 0; + + return (lun_available & (1 << lun)) ? 1 : 0; +} + +/** +* Mass Storage reset routine. +*/ +static void MSD_MASS_Reset() +{ + /* Set the device as not configured */ + pInformation->Current_Configuration = 0; + + /* Current Feature initialization */ + pInformation->Current_Feature = MSD_MASS_ConfigDescriptor[7]; + + SetBTABLE(MSD_BTABLE_ADDRESS); + + /* Initialize Endpoint 0 */ + SetEPType(ENDP0, EP_CONTROL); + SetEPTxStatus(ENDP0, EP_TX_NAK); + SetEPRxAddr(ENDP0, MSD_ENDP0_RXADDR); + SetEPRxCount(ENDP0, pProperty->MaxPacketSize); + SetEPTxAddr(ENDP0, MSD_ENDP0_TXADDR); + Clear_Status_Out(ENDP0); + SetEPRxValid(ENDP0); + + /* Initialize Endpoint 1 */ + SetEPType(ENDP1, EP_BULK); + SetEPTxAddr(ENDP1, MSD_ENDP1_TXADDR); + SetEPTxStatus(ENDP1, EP_TX_NAK); + SetEPRxStatus(ENDP1, EP_RX_DIS); + + /* Initialize Endpoint 2 */ + SetEPType(ENDP2, EP_BULK); + SetEPRxAddr(ENDP2, MSD_ENDP2_RXADDR); + SetEPRxCount(ENDP2, pProperty->MaxPacketSize); + SetEPRxStatus(ENDP2, EP_RX_VALID); + SetEPTxStatus(ENDP2, EP_TX_DIS); + + SetEPRxCount(ENDP0, pProperty->MaxPacketSize); + SetEPRxValid(ENDP0); + + /* Set the device to response on default address */ + SetDeviceAddress(0); + + MSD_CBW.dSignature = BOT_CBW_SIGNATURE; + MSD_Bot_State = BOT_IDLE; +} + +/** +* Handle the SetConfiguration request. +*/ +static void MSD_Mass_Storage_SetConfiguration(void) +{ + if(pInformation->Current_Configuration != 0) { + ClearDTOG_TX(ENDP1); + ClearDTOG_RX(ENDP2); + MSD_Bot_State = BOT_IDLE; /* Set the Bot state machine to the IDLE state */ + + /* All LUNs available after USB (re-)connection */ + for(int i = 0; i < MSD_NUM_LUN; ++i) { + MSD_LUN_AvailableSet(i, 1); + } + } +} + +/** +* Handle the ClearFeature request. +*/ +static void MSD_Mass_Storage_ClearFeature(void) +{ + /* When the host send a CBW with invalid signature or invalid length the two */ + /* Endpoints (IN & OUT) shall stall until receiving a Mass Storage Reset */ + if(MSD_CBW.dSignature != BOT_CBW_SIGNATURE) { + MSD_Bot_Abort(BOTH_DIR); + } +} + +/** +* Udpade the device state to addressed. +*/ +static void MSD_Mass_Storage_SetDeviceAddress(void) +{ + +} + +/** +* Mass Storage Status IN routine. +*/ +static void MSD_MASS_Status_In(void) +{ + return; +} + +/******************************************************************************* +* Mass Storage Status OUT routine. +*/ +static void MSD_MASS_Status_Out(void) +{ + return; +} + +/******************************************************************************* +* Handle the data class specific requests.. +* \param[in] RequestNo +* \return RESULT +*/ +static RESULT MSD_MASS_Data_Setup(uint8_t RequestNo) +{ + uint8_t *(*CopyRoutine)( uint16_t); + + CopyRoutine = NULL; + if((Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) && (RequestNo == GET_MAX_LUN) && (pInformation->USBwValue == 0) + && (pInformation->USBwIndex == 0) && (pInformation->USBwLength == 0x01)) { + CopyRoutine = Get_Max_Lun; + } else { + return USB_UNSUPPORT; + } + + if(CopyRoutine == NULL) { + return USB_UNSUPPORT; + } + + pInformation->Ctrl_Info.CopyData = CopyRoutine; + pInformation->Ctrl_Info.Usb_wOffset = 0; + (*CopyRoutine)(0); + + return USB_SUCCESS; +} + +/** +* Handle the no data class specific requests. +* \param[in] RequestNo +* \return RESULT +*/ +static RESULT MSD_MASS_NoData_Setup(uint8_t RequestNo) +{ + if((Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) && (RequestNo == MASS_STORAGE_RESET) && (pInformation->USBwValue == 0) + && (pInformation->USBwIndex == 0) && (pInformation->USBwLength == 0x00)) { + /* Initialise Endpoint 1 */ + ClearDTOG_TX(ENDP1); + + /* Initialise Endpoint 2 */ + ClearDTOG_RX(ENDP2); + + /* Initialise the CBW signature to enable the clear feature*/ + MSD_CBW.dSignature = BOT_CBW_SIGNATURE; + MSD_Bot_State = BOT_IDLE; + + return USB_SUCCESS; + } + return USB_UNSUPPORT; +} + +/** +* Test the interface and the alternate setting according to the supported one. +* \param[in] Interface +* \param[in] AlternateSetting +* \return RESULT +*/ +static RESULT MSD_MASS_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting) +{ + if(AlternateSetting > 0) { + return USB_UNSUPPORT;/* In this application we don't have AlternateSetting*/ + } else if(Interface > 0) { + return USB_UNSUPPORT;/* In this application we have only 1 interfaces*/ + } + return USB_SUCCESS; +} + +/** +* Get the device descriptor. +* \param[in] Length +*/ +static uint8_t *MSD_MASS_GetDeviceDescriptor(uint16_t Length) +{ + return Standard_GetDescriptorData(Length, &Device_Descriptor); +} + +/** +* Get the configuration descriptor. +* \param[in] Length +*/ +static uint8_t *MSD_MASS_GetConfigDescriptor(uint16_t Length) +{ + return Standard_GetDescriptorData(Length, &Config_Descriptor); +} + +/** +* Get the string descriptors according to the needed index. +* \param[in] Length +*/ +static uint8_t *MSD_MASS_GetStringDescriptor(uint16_t Length) +{ + uint8_t wValue0 = pInformation->USBwValue0; + + if(wValue0 > 5) { + return NULL; + } else { + return Standard_GetDescriptorData(Length, &String_Descriptor[wValue0]); + } +} + +/** +* Handle the Get Max Lun request. +* \param[in] Length +*/ +static uint8_t *Get_Max_Lun(uint16_t Length) +{ + static uint32_t Max_Lun = MSD_NUM_LUN - 1; + + if(Length == 0) { + pInformation->Ctrl_Info.Usb_wLength = LUN_DATA_LENGTH; + return 0; + } else { + /* This copy concept requires statically allocated data... grr! */ + return ((uint8_t*) (&Max_Lun)); + } +} + diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd.h b/flight/PiOS/STM32F10x/Libraries/msd/msd.h index 38c0339bb..5f74c4e24 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd.h +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd.h @@ -1,78 +1,78 @@ -/** - ****************************************************************************** - * - * @file msd.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief MSD functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef _MSD_H -#define _MSD_H - -///////////////////////////////////////////////////////////////////////////// -// Global definitions -///////////////////////////////////////////////////////////////////////////// - -/* defines how many bytes are sent per packet */ -#define MSD_BULK_MAX_PACKET_SIZE 0x40 - -/* max. number of supported logical units */ -#define MSD_NUM_LUN 1 - -/* defines how many endpoints are used by the device */ -#define MSD_EP_NUM 3 - -/* buffer table base address */ - -#define MSD_BTABLE_ADDRESS (0x00) - -/* EP0 */ -/* rx/tx buffer base address */ -#define MSD_ENDP0_RXADDR (0x18) -#define MSD_ENDP0_TXADDR (0x58) - -/* EP1 */ -/* tx buffer base address */ -#define MSD_ENDP1_TXADDR (0x98) - -/* EP2 */ -/* Rx buffer base address */ -#define MSD_ENDP2_RXADDR (0xD8) - - - -///////////////////////////////////////////////////////////////////////////// -// Prototypes -///////////////////////////////////////////////////////////////////////////// - -extern s32 MSD_Init(u32 mode); -extern s32 MSD_Periodic_mS(void); - -extern s32 MSD_CheckAvailable(void); - -extern s32 MSD_LUN_AvailableSet(u8 lun, u8 available); -extern s32 MSD_LUN_AvailableGet(u8 lun); - -///////////////////////////////////////////////////////////////////////////// -// Export global variables -///////////////////////////////////////////////////////////////////////////// - - -#endif /* _MSD_H */ +/** + ****************************************************************************** + * + * @file msd.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief MSD functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef _MSD_H +#define _MSD_H + +///////////////////////////////////////////////////////////////////////////// +// Global definitions +///////////////////////////////////////////////////////////////////////////// + +/* defines how many bytes are sent per packet */ +#define MSD_BULK_MAX_PACKET_SIZE 0x40 + +/* max. number of supported logical units */ +#define MSD_NUM_LUN 1 + +/* defines how many endpoints are used by the device */ +#define MSD_EP_NUM 3 + +/* buffer table base address */ + +#define MSD_BTABLE_ADDRESS (0x00) + +/* EP0 */ +/* rx/tx buffer base address */ +#define MSD_ENDP0_RXADDR (0x18) +#define MSD_ENDP0_TXADDR (0x58) + +/* EP1 */ +/* tx buffer base address */ +#define MSD_ENDP1_TXADDR (0x98) + +/* EP2 */ +/* Rx buffer base address */ +#define MSD_ENDP2_RXADDR (0xD8) + + + +///////////////////////////////////////////////////////////////////////////// +// Prototypes +///////////////////////////////////////////////////////////////////////////// + +extern s32 MSD_Init(u32 mode); +extern s32 MSD_Periodic_mS(void); + +extern s32 MSD_CheckAvailable(void); + +extern s32 MSD_LUN_AvailableSet(u8 lun, u8 available); +extern s32 MSD_LUN_AvailableGet(u8 lun); + +///////////////////////////////////////////////////////////////////////////// +// Export global variables +///////////////////////////////////////////////////////////////////////////// + + +#endif /* _MSD_H */ diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd_bot.c b/flight/PiOS/STM32F10x/Libraries/msd/msd_bot.c index 2ee50cf87..8e1655381 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd_bot.c +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd_bot.c @@ -1,334 +1,334 @@ -/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** -* File Name : usb_bot.c -* Author : MCD Application Team -* Version : V3.0.1 -* Date : 04/27/2009 -* Description : BOT State Machine management -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Includes ------------------------------------------------------------------*/ -#include -#include - -#include "msd.h" -#include "msd_scsi.h" -#include "msd_bot.h" -#include "msd_memory.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ - -/* Global variables ----------------------------------------------------------*/ -uint8_t MSD_Bot_State; -uint8_t MSD_Bulk_Data_Buff[MSD_BULK_MAX_PACKET_SIZE]; /* data buffer*/ -uint16_t MSD_Data_Len; -Bulk_Only_CBW MSD_CBW; -Bulk_Only_CSW MSD_CSW; - -/* Private variables ---------------------------------------------------------*/ -static uint32_t SCSI_LBA , SCSI_BlkLen; - -/* Extern variables ----------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Extern function prototypes ------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/******************************************************************************* -* Function Name : MSD_Mass_Storage_In -* Description : Mass Storage IN transfer. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_Mass_Storage_In (void) -{ - switch (MSD_Bot_State) - { - case BOT_CSW_Send: - case BOT_ERROR: - MSD_Bot_State = BOT_IDLE; - SetEPRxStatus(ENDP2, EP_RX_VALID);/* enable the Endpoint to recive the next cmd*/ - break; - case BOT_DATA_IN: - switch (MSD_CBW.CB[0]) - { - case SCSI_READ10: - MSD_SCSI_Read10_Cmd(MSD_CBW.bLUN , SCSI_LBA , SCSI_BlkLen); - break; - } - break; - case BOT_DATA_IN_LAST: - MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); - SetEPRxStatus(ENDP2, EP_RX_VALID); - break; - - default: - break; - } -} - -/******************************************************************************* -* Function Name : MSD_Mass_Storage_Out -* Description : Mass Storage OUT transfer. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_Mass_Storage_Out (void) -{ - uint8_t CMD; - CMD = MSD_CBW.CB[0]; - MSD_Data_Len = GetEPRxCount(ENDP2); - - PMAToUserBufferCopy(MSD_Bulk_Data_Buff, MSD_ENDP2_RXADDR, MSD_Data_Len); - - switch (MSD_Bot_State) - { - case BOT_IDLE: - MSD_CBW_Decode(); - break; - case BOT_DATA_OUT: - if (CMD == SCSI_WRITE10) - { - MSD_SCSI_Write10_Cmd(MSD_CBW.bLUN , SCSI_LBA , SCSI_BlkLen); - break; - } - MSD_Bot_Abort(DIR_OUT); - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); - MSD_Set_CSW (CSW_PHASE_ERROR, SEND_CSW_DISABLE); - break; - default: - MSD_Bot_Abort(BOTH_DIR); - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); - MSD_Set_CSW (CSW_PHASE_ERROR, SEND_CSW_DISABLE); - break; - } -} - -/******************************************************************************* -* Function Name : MSD_CBW_Decode -* Description : Decode the received CBW and call the related SCSI command -* routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_CBW_Decode(void) -{ - uint32_t Counter; - - for (Counter = 0; Counter < MSD_Data_Len; Counter++) - { - *((uint8_t *)&MSD_CBW + Counter) = MSD_Bulk_Data_Buff[Counter]; - } - MSD_CSW.dTag = MSD_CBW.dTag; - MSD_CSW.dDataResidue = MSD_CBW.dDataLength; - if (MSD_Data_Len != BOT_CBW_PACKET_LENGTH) - { - MSD_Bot_Abort(BOTH_DIR); - /* reset the MSD_CBW.dSignature to desible the clear feature until receiving a Mass storage reset*/ - MSD_CBW.dSignature = 0; - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, PARAMETER_LIST_LENGTH_ERROR); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); - return; - } - - if ((MSD_CBW.CB[0] == SCSI_READ10 ) || (MSD_CBW.CB[0] == SCSI_WRITE10 )) - { - /* Calculate Logical Block Address */ - SCSI_LBA = (MSD_CBW.CB[2] << 24) | (MSD_CBW.CB[3] << 16) | (MSD_CBW.CB[4] << 8) | MSD_CBW.CB[5]; - /* Calculate the Number of Blocks to transfer */ - SCSI_BlkLen = (MSD_CBW.CB[7] << 8) | MSD_CBW.CB[8]; - } - - if (MSD_CBW.dSignature == BOT_CBW_SIGNATURE) - { - /* Valid CBW */ - if ((MSD_CBW.bLUN >= MSD_NUM_LUN) || (MSD_CBW.bCBLength < 1) || (MSD_CBW.bCBLength > 16)) - { - MSD_Bot_Abort(BOTH_DIR); - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); - } - else - { - switch (MSD_CBW.CB[0]) - { - case SCSI_REQUEST_SENSE: - MSD_SCSI_RequestSense_Cmd (MSD_CBW.bLUN); - break; - case SCSI_INQUIRY: - MSD_SCSI_Inquiry_Cmd(MSD_CBW.bLUN); - break; - case SCSI_START_STOP_UNIT: - MSD_SCSI_Start_Stop_Unit_Cmd(MSD_CBW.bLUN); - MSD_LUN_AvailableSet(MSD_CBW.bLUN, 0); - break; - case SCSI_ALLOW_MEDIUM_REMOVAL: - MSD_SCSI_Start_Stop_Unit_Cmd(MSD_CBW.bLUN); - break; - case SCSI_MODE_SENSE6: - MSD_SCSI_ModeSense6_Cmd (MSD_CBW.bLUN); - break; - case SCSI_MODE_SENSE10: - MSD_SCSI_ModeSense10_Cmd (MSD_CBW.bLUN); - break; - case SCSI_READ_FORMAT_CAPACITIES: - MSD_SCSI_ReadFormatCapacity_Cmd(MSD_CBW.bLUN); - break; - case SCSI_READ_CAPACITY10: - MSD_SCSI_ReadCapacity10_Cmd(MSD_CBW.bLUN); - break; - case SCSI_TEST_UNIT_READY: - MSD_SCSI_TestUnitReady_Cmd(MSD_CBW.bLUN); - break; - case SCSI_READ10: - MSD_SCSI_Read10_Cmd(MSD_CBW.bLUN, SCSI_LBA , SCSI_BlkLen); - break; - case SCSI_WRITE10: - MSD_SCSI_Write10_Cmd(MSD_CBW.bLUN, SCSI_LBA , SCSI_BlkLen); - break; - case SCSI_VERIFY10: - MSD_SCSI_Verify10_Cmd(MSD_CBW.bLUN); - break; - case SCSI_FORMAT_UNIT: - MSD_SCSI_Format_Cmd(MSD_CBW.bLUN); - break; - /*Unsupported command*/ - - case SCSI_MODE_SELECT10: - MSD_SCSI_Mode_Select10_Cmd(MSD_CBW.bLUN); - break; - case SCSI_MODE_SELECT6: - MSD_SCSI_Mode_Select6_Cmd(MSD_CBW.bLUN); - break; - - case SCSI_SEND_DIAGNOSTIC: - MSD_SCSI_Send_Diagnostic_Cmd(MSD_CBW.bLUN); - break; - case SCSI_READ6: - MSD_SCSI_Read6_Cmd(MSD_CBW.bLUN); - break; - case SCSI_READ12: - MSD_SCSI_Read12_Cmd(MSD_CBW.bLUN); - break; - case SCSI_READ16: - MSD_SCSI_Read16_Cmd(MSD_CBW.bLUN); - break; - case SCSI_READ_CAPACITY16: - MSD_SCSI_READ_CAPACITY16_Cmd(MSD_CBW.bLUN); - break; - case SCSI_WRITE6: - MSD_SCSI_Write6_Cmd(MSD_CBW.bLUN); - break; - case SCSI_WRITE12: - MSD_SCSI_Write12_Cmd(MSD_CBW.bLUN); - break; - case SCSI_WRITE16: - MSD_SCSI_Write16_Cmd(MSD_CBW.bLUN); - break; - case SCSI_VERIFY12: - MSD_SCSI_Verify12_Cmd(MSD_CBW.bLUN); - break; - case SCSI_VERIFY16: - MSD_SCSI_Verify16_Cmd(MSD_CBW.bLUN); - break; - - default: - { - MSD_Bot_Abort(BOTH_DIR); - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_COMMAND); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); - } - } - } - } - else - { - /* Invalid CBW */ - MSD_Bot_Abort(BOTH_DIR); - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_COMMAND); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); - } -} - -/******************************************************************************* -* Function Name : MSD_Transfer_Data_Request -* Description : Send the request response to the PC HOST. -* Input : uint8_t* Data_Address : point to the data to transfer. -* uint16_t Data_Length : the nember of Bytes to transfer. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_Transfer_Data_Request(uint8_t* Data_Pointer, uint16_t Data_Len) -{ - UserToPMABufferCopy(Data_Pointer, MSD_ENDP1_TXADDR, Data_Len); - - SetEPTxCount(ENDP1, Data_Len); - SetEPTxStatus(ENDP1, EP_TX_VALID); - MSD_Bot_State = BOT_DATA_IN_LAST; - MSD_CSW.dDataResidue -= Data_Len; - MSD_CSW.bStatus = CSW_CMD_PASSED; -} - -/******************************************************************************* -* Function Name : MSD_Set_CSW -* Description : Set the SCW with the needed fields. -* Input : uint8_t CSW_Status this filed can be CSW_CMD_PASSED,CSW_CMD_FAILED, -* or CSW_PHASE_ERROR. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_Set_CSW (uint8_t CSW_Status, uint8_t Send_Permission) -{ - MSD_CSW.dSignature = BOT_CSW_SIGNATURE; - MSD_CSW.bStatus = CSW_Status; - - UserToPMABufferCopy(((uint8_t *)& MSD_CSW), MSD_ENDP1_TXADDR, CSW_DATA_LENGTH); - - SetEPTxCount(ENDP1, CSW_DATA_LENGTH); - MSD_Bot_State = BOT_ERROR; - if (Send_Permission) - { - MSD_Bot_State = BOT_CSW_Send; - SetEPTxStatus(ENDP1, EP_TX_VALID); - } - -} - -/******************************************************************************* -* Function Name : MSD_Bot_Abort -* Description : Stall the needed Endpoint according to the selected direction. -* Input : Endpoint direction IN, OUT or both directions -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_Bot_Abort(uint8_t Direction) -{ - switch (Direction) - { - case DIR_IN : - SetEPTxStatus(ENDP1, EP_TX_STALL); - break; - case DIR_OUT : - SetEPRxStatus(ENDP2, EP_RX_STALL); - break; - case BOTH_DIR : - SetEPTxStatus(ENDP1, EP_TX_STALL); - SetEPRxStatus(ENDP2, EP_RX_STALL); - break; - default: - break; - } -} - -/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ - +/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** +* File Name : usb_bot.c +* Author : MCD Application Team +* Version : V3.0.1 +* Date : 04/27/2009 +* Description : BOT State Machine management +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Includes ------------------------------------------------------------------*/ +#include +#include + +#include "msd.h" +#include "msd_scsi.h" +#include "msd_bot.h" +#include "msd_memory.h" + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ + +/* Global variables ----------------------------------------------------------*/ +uint8_t MSD_Bot_State; +uint8_t MSD_Bulk_Data_Buff[MSD_BULK_MAX_PACKET_SIZE]; /* data buffer*/ +uint16_t MSD_Data_Len; +Bulk_Only_CBW MSD_CBW; +Bulk_Only_CSW MSD_CSW; + +/* Private variables ---------------------------------------------------------*/ +static uint32_t SCSI_LBA , SCSI_BlkLen; + +/* Extern variables ----------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Extern function prototypes ------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/******************************************************************************* +* Function Name : MSD_Mass_Storage_In +* Description : Mass Storage IN transfer. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_Mass_Storage_In (void) +{ + switch (MSD_Bot_State) + { + case BOT_CSW_Send: + case BOT_ERROR: + MSD_Bot_State = BOT_IDLE; + SetEPRxStatus(ENDP2, EP_RX_VALID);/* enable the Endpoint to recive the next cmd*/ + break; + case BOT_DATA_IN: + switch (MSD_CBW.CB[0]) + { + case SCSI_READ10: + MSD_SCSI_Read10_Cmd(MSD_CBW.bLUN , SCSI_LBA , SCSI_BlkLen); + break; + } + break; + case BOT_DATA_IN_LAST: + MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); + SetEPRxStatus(ENDP2, EP_RX_VALID); + break; + + default: + break; + } +} + +/******************************************************************************* +* Function Name : MSD_Mass_Storage_Out +* Description : Mass Storage OUT transfer. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_Mass_Storage_Out (void) +{ + uint8_t CMD; + CMD = MSD_CBW.CB[0]; + MSD_Data_Len = GetEPRxCount(ENDP2); + + PMAToUserBufferCopy(MSD_Bulk_Data_Buff, MSD_ENDP2_RXADDR, MSD_Data_Len); + + switch (MSD_Bot_State) + { + case BOT_IDLE: + MSD_CBW_Decode(); + break; + case BOT_DATA_OUT: + if (CMD == SCSI_WRITE10) + { + MSD_SCSI_Write10_Cmd(MSD_CBW.bLUN , SCSI_LBA , SCSI_BlkLen); + break; + } + MSD_Bot_Abort(DIR_OUT); + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); + MSD_Set_CSW (CSW_PHASE_ERROR, SEND_CSW_DISABLE); + break; + default: + MSD_Bot_Abort(BOTH_DIR); + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); + MSD_Set_CSW (CSW_PHASE_ERROR, SEND_CSW_DISABLE); + break; + } +} + +/******************************************************************************* +* Function Name : MSD_CBW_Decode +* Description : Decode the received CBW and call the related SCSI command +* routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_CBW_Decode(void) +{ + uint32_t Counter; + + for (Counter = 0; Counter < MSD_Data_Len; Counter++) + { + *((uint8_t *)&MSD_CBW + Counter) = MSD_Bulk_Data_Buff[Counter]; + } + MSD_CSW.dTag = MSD_CBW.dTag; + MSD_CSW.dDataResidue = MSD_CBW.dDataLength; + if (MSD_Data_Len != BOT_CBW_PACKET_LENGTH) + { + MSD_Bot_Abort(BOTH_DIR); + /* reset the MSD_CBW.dSignature to desible the clear feature until receiving a Mass storage reset*/ + MSD_CBW.dSignature = 0; + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, PARAMETER_LIST_LENGTH_ERROR); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); + return; + } + + if ((MSD_CBW.CB[0] == SCSI_READ10 ) || (MSD_CBW.CB[0] == SCSI_WRITE10 )) + { + /* Calculate Logical Block Address */ + SCSI_LBA = (MSD_CBW.CB[2] << 24) | (MSD_CBW.CB[3] << 16) | (MSD_CBW.CB[4] << 8) | MSD_CBW.CB[5]; + /* Calculate the Number of Blocks to transfer */ + SCSI_BlkLen = (MSD_CBW.CB[7] << 8) | MSD_CBW.CB[8]; + } + + if (MSD_CBW.dSignature == BOT_CBW_SIGNATURE) + { + /* Valid CBW */ + if ((MSD_CBW.bLUN >= MSD_NUM_LUN) || (MSD_CBW.bCBLength < 1) || (MSD_CBW.bCBLength > 16)) + { + MSD_Bot_Abort(BOTH_DIR); + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); + } + else + { + switch (MSD_CBW.CB[0]) + { + case SCSI_REQUEST_SENSE: + MSD_SCSI_RequestSense_Cmd (MSD_CBW.bLUN); + break; + case SCSI_INQUIRY: + MSD_SCSI_Inquiry_Cmd(MSD_CBW.bLUN); + break; + case SCSI_START_STOP_UNIT: + MSD_SCSI_Start_Stop_Unit_Cmd(MSD_CBW.bLUN); + MSD_LUN_AvailableSet(MSD_CBW.bLUN, 0); + break; + case SCSI_ALLOW_MEDIUM_REMOVAL: + MSD_SCSI_Start_Stop_Unit_Cmd(MSD_CBW.bLUN); + break; + case SCSI_MODE_SENSE6: + MSD_SCSI_ModeSense6_Cmd (MSD_CBW.bLUN); + break; + case SCSI_MODE_SENSE10: + MSD_SCSI_ModeSense10_Cmd (MSD_CBW.bLUN); + break; + case SCSI_READ_FORMAT_CAPACITIES: + MSD_SCSI_ReadFormatCapacity_Cmd(MSD_CBW.bLUN); + break; + case SCSI_READ_CAPACITY10: + MSD_SCSI_ReadCapacity10_Cmd(MSD_CBW.bLUN); + break; + case SCSI_TEST_UNIT_READY: + MSD_SCSI_TestUnitReady_Cmd(MSD_CBW.bLUN); + break; + case SCSI_READ10: + MSD_SCSI_Read10_Cmd(MSD_CBW.bLUN, SCSI_LBA , SCSI_BlkLen); + break; + case SCSI_WRITE10: + MSD_SCSI_Write10_Cmd(MSD_CBW.bLUN, SCSI_LBA , SCSI_BlkLen); + break; + case SCSI_VERIFY10: + MSD_SCSI_Verify10_Cmd(MSD_CBW.bLUN); + break; + case SCSI_FORMAT_UNIT: + MSD_SCSI_Format_Cmd(MSD_CBW.bLUN); + break; + /*Unsupported command*/ + + case SCSI_MODE_SELECT10: + MSD_SCSI_Mode_Select10_Cmd(MSD_CBW.bLUN); + break; + case SCSI_MODE_SELECT6: + MSD_SCSI_Mode_Select6_Cmd(MSD_CBW.bLUN); + break; + + case SCSI_SEND_DIAGNOSTIC: + MSD_SCSI_Send_Diagnostic_Cmd(MSD_CBW.bLUN); + break; + case SCSI_READ6: + MSD_SCSI_Read6_Cmd(MSD_CBW.bLUN); + break; + case SCSI_READ12: + MSD_SCSI_Read12_Cmd(MSD_CBW.bLUN); + break; + case SCSI_READ16: + MSD_SCSI_Read16_Cmd(MSD_CBW.bLUN); + break; + case SCSI_READ_CAPACITY16: + MSD_SCSI_READ_CAPACITY16_Cmd(MSD_CBW.bLUN); + break; + case SCSI_WRITE6: + MSD_SCSI_Write6_Cmd(MSD_CBW.bLUN); + break; + case SCSI_WRITE12: + MSD_SCSI_Write12_Cmd(MSD_CBW.bLUN); + break; + case SCSI_WRITE16: + MSD_SCSI_Write16_Cmd(MSD_CBW.bLUN); + break; + case SCSI_VERIFY12: + MSD_SCSI_Verify12_Cmd(MSD_CBW.bLUN); + break; + case SCSI_VERIFY16: + MSD_SCSI_Verify16_Cmd(MSD_CBW.bLUN); + break; + + default: + { + MSD_Bot_Abort(BOTH_DIR); + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_COMMAND); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); + } + } + } + } + else + { + /* Invalid CBW */ + MSD_Bot_Abort(BOTH_DIR); + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_COMMAND); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); + } +} + +/******************************************************************************* +* Function Name : MSD_Transfer_Data_Request +* Description : Send the request response to the PC HOST. +* Input : uint8_t* Data_Address : point to the data to transfer. +* uint16_t Data_Length : the nember of Bytes to transfer. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_Transfer_Data_Request(uint8_t* Data_Pointer, uint16_t Data_Len) +{ + UserToPMABufferCopy(Data_Pointer, MSD_ENDP1_TXADDR, Data_Len); + + SetEPTxCount(ENDP1, Data_Len); + SetEPTxStatus(ENDP1, EP_TX_VALID); + MSD_Bot_State = BOT_DATA_IN_LAST; + MSD_CSW.dDataResidue -= Data_Len; + MSD_CSW.bStatus = CSW_CMD_PASSED; +} + +/******************************************************************************* +* Function Name : MSD_Set_CSW +* Description : Set the SCW with the needed fields. +* Input : uint8_t CSW_Status this filed can be CSW_CMD_PASSED,CSW_CMD_FAILED, +* or CSW_PHASE_ERROR. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_Set_CSW (uint8_t CSW_Status, uint8_t Send_Permission) +{ + MSD_CSW.dSignature = BOT_CSW_SIGNATURE; + MSD_CSW.bStatus = CSW_Status; + + UserToPMABufferCopy(((uint8_t *)& MSD_CSW), MSD_ENDP1_TXADDR, CSW_DATA_LENGTH); + + SetEPTxCount(ENDP1, CSW_DATA_LENGTH); + MSD_Bot_State = BOT_ERROR; + if (Send_Permission) + { + MSD_Bot_State = BOT_CSW_Send; + SetEPTxStatus(ENDP1, EP_TX_VALID); + } + +} + +/******************************************************************************* +* Function Name : MSD_Bot_Abort +* Description : Stall the needed Endpoint according to the selected direction. +* Input : Endpoint direction IN, OUT or both directions +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_Bot_Abort(uint8_t Direction) +{ + switch (Direction) + { + case DIR_IN : + SetEPTxStatus(ENDP1, EP_TX_STALL); + break; + case DIR_OUT : + SetEPRxStatus(ENDP2, EP_RX_STALL); + break; + case BOTH_DIR : + SetEPTxStatus(ENDP1, EP_TX_STALL); + SetEPRxStatus(ENDP2, EP_RX_STALL); + break; + default: + break; + } +} + +/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd_bot.h b/flight/PiOS/STM32F10x/Libraries/msd/msd_bot.h index 4324c21b1..f68c78e57 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd_bot.h +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd_bot.h @@ -1,95 +1,95 @@ -/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** -* File Name : usb_bot.h -* Author : MCD Application Team -* Version : V3.0.1 -* Date : 04/27/2009 -* Description : BOT State Machine management -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_BOT_H -#define __USB_BOT_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Bulk-only Command Block Wrapper */ - -typedef struct _Bulk_Only_CBW -{ - uint32_t dSignature; - uint32_t dTag; - uint32_t dDataLength; - uint8_t bmFlags; - uint8_t bLUN; - uint8_t bCBLength; - uint8_t CB[16]; -} -Bulk_Only_CBW; - -/* Bulk-only Command Status Wrapper */ -typedef struct _Bulk_Only_CSW -{ - uint32_t dSignature; - uint32_t dTag; - uint32_t dDataResidue; - uint8_t bStatus; -} -Bulk_Only_CSW; -/* Exported constants --------------------------------------------------------*/ - -/*****************************************************************************/ -/*********************** Bulk-Only Transfer State machine ********************/ -/*****************************************************************************/ -#define BOT_IDLE 0 /* Idle state */ -#define BOT_DATA_OUT 1 /* Data Out state */ -#define BOT_DATA_IN 2 /* Data In state */ -#define BOT_DATA_IN_LAST 3 /* Last Data In Last */ -#define BOT_CSW_Send 4 /* Command Status Wrapper */ -#define BOT_ERROR 5 /* error state */ - -#define BOT_CBW_SIGNATURE 0x43425355 -#define BOT_CSW_SIGNATURE 0x53425355 -#define BOT_CBW_PACKET_LENGTH 31 - -#define CSW_DATA_LENGTH 0x000D - -/* CSW Status Definitions */ -#define CSW_CMD_PASSED 0x00 -#define CSW_CMD_FAILED 0x01 -#define CSW_PHASE_ERROR 0x02 - -#define SEND_CSW_DISABLE 0 -#define SEND_CSW_ENABLE 1 - -#define DIR_IN 0 -#define DIR_OUT 1 -#define BOTH_DIR 2 - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -extern void MSD_Mass_Storage_In (void); -extern void MSD_Mass_Storage_Out (void); -extern void MSD_CBW_Decode(void); -extern void MSD_Transfer_Data_Request(uint8_t* Data_Pointer, uint16_t Data_Len); -extern void MSD_Set_CSW (uint8_t CSW_Status, uint8_t Send_Permission); -extern void MSD_Bot_Abort(uint8_t Direction); - - -/* Exported variables ------------------------------------------------------- */ -extern uint8_t MSD_Bot_State; -extern uint8_t MSD_Bulk_Data_Buff[MSD_BULK_MAX_PACKET_SIZE]; /* data buffer*/ -extern uint16_t MSD_Data_Len; -extern Bulk_Only_CBW MSD_CBW; -extern Bulk_Only_CSW MSD_CSW; - -#endif /* __USB_BOT_H */ - -/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ - +/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** +* File Name : usb_bot.h +* Author : MCD Application Team +* Version : V3.0.1 +* Date : 04/27/2009 +* Description : BOT State Machine management +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_BOT_H +#define __USB_BOT_H + +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +/* Bulk-only Command Block Wrapper */ + +typedef struct _Bulk_Only_CBW +{ + uint32_t dSignature; + uint32_t dTag; + uint32_t dDataLength; + uint8_t bmFlags; + uint8_t bLUN; + uint8_t bCBLength; + uint8_t CB[16]; +} +Bulk_Only_CBW; + +/* Bulk-only Command Status Wrapper */ +typedef struct _Bulk_Only_CSW +{ + uint32_t dSignature; + uint32_t dTag; + uint32_t dDataResidue; + uint8_t bStatus; +} +Bulk_Only_CSW; +/* Exported constants --------------------------------------------------------*/ + +/*****************************************************************************/ +/*********************** Bulk-Only Transfer State machine ********************/ +/*****************************************************************************/ +#define BOT_IDLE 0 /* Idle state */ +#define BOT_DATA_OUT 1 /* Data Out state */ +#define BOT_DATA_IN 2 /* Data In state */ +#define BOT_DATA_IN_LAST 3 /* Last Data In Last */ +#define BOT_CSW_Send 4 /* Command Status Wrapper */ +#define BOT_ERROR 5 /* error state */ + +#define BOT_CBW_SIGNATURE 0x43425355 +#define BOT_CSW_SIGNATURE 0x53425355 +#define BOT_CBW_PACKET_LENGTH 31 + +#define CSW_DATA_LENGTH 0x000D + +/* CSW Status Definitions */ +#define CSW_CMD_PASSED 0x00 +#define CSW_CMD_FAILED 0x01 +#define CSW_PHASE_ERROR 0x02 + +#define SEND_CSW_DISABLE 0 +#define SEND_CSW_ENABLE 1 + +#define DIR_IN 0 +#define DIR_OUT 1 +#define BOTH_DIR 2 + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +extern void MSD_Mass_Storage_In (void); +extern void MSD_Mass_Storage_Out (void); +extern void MSD_CBW_Decode(void); +extern void MSD_Transfer_Data_Request(uint8_t* Data_Pointer, uint16_t Data_Len); +extern void MSD_Set_CSW (uint8_t CSW_Status, uint8_t Send_Permission); +extern void MSD_Bot_Abort(uint8_t Direction); + + +/* Exported variables ------------------------------------------------------- */ +extern uint8_t MSD_Bot_State; +extern uint8_t MSD_Bulk_Data_Buff[MSD_BULK_MAX_PACKET_SIZE]; /* data buffer*/ +extern uint16_t MSD_Data_Len; +extern Bulk_Only_CBW MSD_CBW; +extern Bulk_Only_CSW MSD_CSW; + +#endif /* __USB_BOT_H */ + +/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd_desc.c b/flight/PiOS/STM32F10x/Libraries/msd/msd_desc.c index fe1c422c3..16ee79bbd 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd_desc.c +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd_desc.c @@ -1,135 +1,135 @@ -/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** -* File Name : usb_desc.c -* Author : MCD Application Team -* Version : V3.0.1 -* Date : 04/27/2009 -* Description : Descriptors for Mass Storage Device -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Includes ------------------------------------------------------------------*/ -#include "msd_desc.h" - -const uint8_t MSD_MASS_DeviceDescriptor[MSD_MASS_SIZ_DEVICE_DESC] = - { - 0x12, /* bLength */ - 0x01, /* bDescriptorType */ - 0x00, /* bcdUSB, version 2.00 */ - 0x02, - 0x00, /* bDeviceClass : each interface define the device class */ - 0x00, /* bDeviceSubClass */ - 0x00, /* bDeviceProtocol */ - 0x40, /* bMaxPacketSize0 0x40 = 64 */ - 0x83, /* idVendor (0483) */ - 0x04, - 0x20, /* idProduct */ - 0x57, - 0x00, /* bcdDevice 2.00*/ - 0x02, - 1, /* index of string Manufacturer */ - /**/ - 2, /* index of string descriptor of product*/ - /* */ - 3, /* */ - /* */ - /* */ - 0x01 /*bNumConfigurations */ - }; -const uint8_t MSD_MASS_ConfigDescriptor[MSD_MASS_SIZ_CONFIG_DESC] = - { - - 0x09, /* bLength: Configuation Descriptor size */ - 0x02, /* bDescriptorType: Configuration */ - MSD_MASS_SIZ_CONFIG_DESC, - - 0x00, - 0x01, /* bNumInterfaces: 1 interface */ - 0x01, /* bConfigurationValue: */ - /* Configuration value */ - 0x00, /* iConfiguration: */ - /* Index of string descriptor */ - /* describing the configuration */ - 0xC0, /* bmAttributes: */ - /* bus powered */ - 0x32, /* MaxPower 100 mA */ - - /******************** Descriptor of Mass Storage interface ********************/ - /* 09 */ - 0x09, /* bLength: Interface Descriptor size */ - 0x04, /* bDescriptorType: */ - /* Interface descriptor type */ - 0x00, /* bInterfaceNumber: Number of Interface */ - 0x00, /* bAlternateSetting: Alternate setting */ - 0x02, /* bNumEndpoints*/ - 0x08, /* bInterfaceClass: MASS STORAGE Class */ - 0x06, /* bInterfaceSubClass : SCSI transparent*/ - 0x50, /* nInterfaceProtocol */ - 4, /* iInterface: */ - /* 18 */ - 0x07, /*Endpoint descriptor length = 7*/ - 0x05, /*Endpoint descriptor type */ - 0x81, /*Endpoint address (IN, address 1) */ - 0x02, /*Bulk endpoint type */ - 0x40, /*Maximum packet size (64 bytes) */ - 0x00, - 0x00, /*Polling interval in milliseconds */ - /* 25 */ - 0x07, /*Endpoint descriptor length = 7 */ - 0x05, /*Endpoint descriptor type */ - 0x02, /*Endpoint address (OUT, address 2) */ - 0x02, /*Bulk endpoint type */ - 0x40, /*Maximum packet size (64 bytes) */ - 0x00, - 0x00 /*Polling interval in milliseconds*/ - /*32*/ - }; -const uint8_t MSD_MASS_StringLangID[MSD_MASS_SIZ_STRING_LANGID] = - { - MSD_MASS_SIZ_STRING_LANGID, - 0x03, - 0x09, - 0x04 - } - ; /* LangID = 0x0409: U.S. English */ -const uint8_t MSD_MASS_StringVendor[MSD_MASS_SIZ_STRING_VENDOR] = - { - MSD_MASS_SIZ_STRING_VENDOR, /* Size of manufaturer string */ - 0x03, /* bDescriptorType = String descriptor */ - /* Manufacturer */ - 'O', 0, 'p', 0, 'e', 0, 'n', 0, 'p', 0, 'i', 0, 'l', 0, 'o', 0, - 't', 0, - }; -const uint8_t MSD_MASS_StringProduct[MSD_MASS_SIZ_STRING_PRODUCT] = - { - MSD_MASS_SIZ_STRING_PRODUCT, - 0x03, - /* Product name */ - 'O', 0, 'p', 0, 'e', 0, 'n', 0, 'P', 0, 'i', 0, 'l', 0, 'o', 0, 't', 0, - ' ', 0, 'M', 0, 'a', 0, 's', 0, 's', 0, ' ', 0, 'S', 0, 't', 0, 'o', 0, - 'r', 0, 'a', 0, 'g', 0, 'e', 0 - - }; - -uint8_t MSD_MASS_StringSerial[MSD_MASS_SIZ_STRING_SERIAL] = - { - MSD_MASS_SIZ_STRING_SERIAL, - 0x03, - /* Serial number */ - '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0 - }; -const uint8_t MSD_MASS_StringInterface[MSD_MASS_SIZ_STRING_INTERFACE] = - { - MSD_MASS_SIZ_STRING_INTERFACE, - 0x03, - /* Interface 0: */ - 'S', 0, 'D', 0, ' ', 0, 'C', 0, 'a', 0, 'r', 0, 'd', 0 - }; - -/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ - +/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** +* File Name : usb_desc.c +* Author : MCD Application Team +* Version : V3.0.1 +* Date : 04/27/2009 +* Description : Descriptors for Mass Storage Device +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Includes ------------------------------------------------------------------*/ +#include "msd_desc.h" + +const uint8_t MSD_MASS_DeviceDescriptor[MSD_MASS_SIZ_DEVICE_DESC] = + { + 0x12, /* bLength */ + 0x01, /* bDescriptorType */ + 0x00, /* bcdUSB, version 2.00 */ + 0x02, + 0x00, /* bDeviceClass : each interface define the device class */ + 0x00, /* bDeviceSubClass */ + 0x00, /* bDeviceProtocol */ + 0x40, /* bMaxPacketSize0 0x40 = 64 */ + 0x83, /* idVendor (0483) */ + 0x04, + 0x20, /* idProduct */ + 0x57, + 0x00, /* bcdDevice 2.00*/ + 0x02, + 1, /* index of string Manufacturer */ + /**/ + 2, /* index of string descriptor of product*/ + /* */ + 3, /* */ + /* */ + /* */ + 0x01 /*bNumConfigurations */ + }; +const uint8_t MSD_MASS_ConfigDescriptor[MSD_MASS_SIZ_CONFIG_DESC] = + { + + 0x09, /* bLength: Configuation Descriptor size */ + 0x02, /* bDescriptorType: Configuration */ + MSD_MASS_SIZ_CONFIG_DESC, + + 0x00, + 0x01, /* bNumInterfaces: 1 interface */ + 0x01, /* bConfigurationValue: */ + /* Configuration value */ + 0x00, /* iConfiguration: */ + /* Index of string descriptor */ + /* describing the configuration */ + 0xC0, /* bmAttributes: */ + /* bus powered */ + 0x32, /* MaxPower 100 mA */ + + /******************** Descriptor of Mass Storage interface ********************/ + /* 09 */ + 0x09, /* bLength: Interface Descriptor size */ + 0x04, /* bDescriptorType: */ + /* Interface descriptor type */ + 0x00, /* bInterfaceNumber: Number of Interface */ + 0x00, /* bAlternateSetting: Alternate setting */ + 0x02, /* bNumEndpoints*/ + 0x08, /* bInterfaceClass: MASS STORAGE Class */ + 0x06, /* bInterfaceSubClass : SCSI transparent*/ + 0x50, /* nInterfaceProtocol */ + 4, /* iInterface: */ + /* 18 */ + 0x07, /*Endpoint descriptor length = 7*/ + 0x05, /*Endpoint descriptor type */ + 0x81, /*Endpoint address (IN, address 1) */ + 0x02, /*Bulk endpoint type */ + 0x40, /*Maximum packet size (64 bytes) */ + 0x00, + 0x00, /*Polling interval in milliseconds */ + /* 25 */ + 0x07, /*Endpoint descriptor length = 7 */ + 0x05, /*Endpoint descriptor type */ + 0x02, /*Endpoint address (OUT, address 2) */ + 0x02, /*Bulk endpoint type */ + 0x40, /*Maximum packet size (64 bytes) */ + 0x00, + 0x00 /*Polling interval in milliseconds*/ + /*32*/ + }; +const uint8_t MSD_MASS_StringLangID[MSD_MASS_SIZ_STRING_LANGID] = + { + MSD_MASS_SIZ_STRING_LANGID, + 0x03, + 0x09, + 0x04 + } + ; /* LangID = 0x0409: U.S. English */ +const uint8_t MSD_MASS_StringVendor[MSD_MASS_SIZ_STRING_VENDOR] = + { + MSD_MASS_SIZ_STRING_VENDOR, /* Size of manufaturer string */ + 0x03, /* bDescriptorType = String descriptor */ + /* Manufacturer */ + 'O', 0, 'p', 0, 'e', 0, 'n', 0, 'p', 0, 'i', 0, 'l', 0, 'o', 0, + 't', 0, + }; +const uint8_t MSD_MASS_StringProduct[MSD_MASS_SIZ_STRING_PRODUCT] = + { + MSD_MASS_SIZ_STRING_PRODUCT, + 0x03, + /* Product name */ + 'O', 0, 'p', 0, 'e', 0, 'n', 0, 'P', 0, 'i', 0, 'l', 0, 'o', 0, 't', 0, + ' ', 0, 'M', 0, 'a', 0, 's', 0, 's', 0, ' ', 0, 'S', 0, 't', 0, 'o', 0, + 'r', 0, 'a', 0, 'g', 0, 'e', 0 + + }; + +uint8_t MSD_MASS_StringSerial[MSD_MASS_SIZ_STRING_SERIAL] = + { + MSD_MASS_SIZ_STRING_SERIAL, + 0x03, + /* Serial number */ + '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0, '0', 0 + }; +const uint8_t MSD_MASS_StringInterface[MSD_MASS_SIZ_STRING_INTERFACE] = + { + MSD_MASS_SIZ_STRING_INTERFACE, + 0x03, + /* Interface 0: */ + 'S', 0, 'D', 0, ' ', 0, 'C', 0, 'a', 0, 'r', 0, 'd', 0 + }; + +/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd_desc.h b/flight/PiOS/STM32F10x/Libraries/msd/msd_desc.h index 88d07b417..5b50a6339 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd_desc.h +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd_desc.h @@ -1,48 +1,48 @@ -/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** -* File Name : usb_desc.h -* Author : MCD Application Team -* Version : V3.0.1 -* Date : 04/27/2009 -* Description : Descriptor Header for Mass Storage Device -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_DESC_H -#define __USB_DESC_H - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported define -----------------------------------------------------------*/ -#define MSD_MASS_SIZ_DEVICE_DESC 18 -#define MSD_MASS_SIZ_CONFIG_DESC 32 - -#define MSD_MASS_SIZ_STRING_LANGID 4 -#define MSD_MASS_SIZ_STRING_VENDOR 20 -#define MSD_MASS_SIZ_STRING_PRODUCT 46 -#define MSD_MASS_SIZ_STRING_SERIAL 26 -#define MSD_MASS_SIZ_STRING_INTERFACE 16 - -/* Exported functions ------------------------------------------------------- */ -extern const uint8_t MSD_MASS_DeviceDescriptor[MSD_MASS_SIZ_DEVICE_DESC]; -extern const uint8_t MSD_MASS_ConfigDescriptor[MSD_MASS_SIZ_CONFIG_DESC]; - -extern const uint8_t MSD_MASS_StringLangID[MSD_MASS_SIZ_STRING_LANGID]; -extern const uint8_t MSD_MASS_StringVendor[MSD_MASS_SIZ_STRING_VENDOR]; -extern const uint8_t MSD_MASS_StringProduct[MSD_MASS_SIZ_STRING_PRODUCT]; -extern uint8_t MSD_MASS_StringSerial[MSD_MASS_SIZ_STRING_SERIAL]; -extern const uint8_t MSD_MASS_StringInterface[MSD_MASS_SIZ_STRING_INTERFACE]; - -#endif /* __USB_DESC_H */ - -/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ - +/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** +* File Name : usb_desc.h +* Author : MCD Application Team +* Version : V3.0.1 +* Date : 04/27/2009 +* Description : Descriptor Header for Mass Storage Device +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_DESC_H +#define __USB_DESC_H + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported define -----------------------------------------------------------*/ +#define MSD_MASS_SIZ_DEVICE_DESC 18 +#define MSD_MASS_SIZ_CONFIG_DESC 32 + +#define MSD_MASS_SIZ_STRING_LANGID 4 +#define MSD_MASS_SIZ_STRING_VENDOR 20 +#define MSD_MASS_SIZ_STRING_PRODUCT 46 +#define MSD_MASS_SIZ_STRING_SERIAL 26 +#define MSD_MASS_SIZ_STRING_INTERFACE 16 + +/* Exported functions ------------------------------------------------------- */ +extern const uint8_t MSD_MASS_DeviceDescriptor[MSD_MASS_SIZ_DEVICE_DESC]; +extern const uint8_t MSD_MASS_ConfigDescriptor[MSD_MASS_SIZ_CONFIG_DESC]; + +extern const uint8_t MSD_MASS_StringLangID[MSD_MASS_SIZ_STRING_LANGID]; +extern const uint8_t MSD_MASS_StringVendor[MSD_MASS_SIZ_STRING_VENDOR]; +extern const uint8_t MSD_MASS_StringProduct[MSD_MASS_SIZ_STRING_PRODUCT]; +extern uint8_t MSD_MASS_StringSerial[MSD_MASS_SIZ_STRING_SERIAL]; +extern const uint8_t MSD_MASS_StringInterface[MSD_MASS_SIZ_STRING_INTERFACE]; + +#endif /* __USB_DESC_H */ + +/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd_memory.c b/flight/PiOS/STM32F10x/Libraries/msd/msd_memory.c index 7df355c73..d7edc1b08 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd_memory.c +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd_memory.c @@ -1,242 +1,242 @@ -/** - ****************************************************************************** - * - * @file msd_memory.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief Memory Management Layer - * @see The GNU Public License (GPL) Version 3 - * @defgroup MSD MSD Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** -* File Name : memory.c -* Author : MCD Application Team -* Version : V3.0.1 -* Date : 04/27/2009 -* Description : Memory management layer -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Includes ------------------------------------------------------------------*/ - -#include -#include - -#include "msd.h" -#include "msd_memory.h" -#include "msd_scsi.h" -#include "msd_bot.h" - - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ - -/* Global variables ----------------------------------------------------------*/ -uint32_t MSD_Mass_Memory_Size[MSD_NUM_LUN]; -uint32_t MSD_Mass_Block_Size[MSD_NUM_LUN]; -uint32_t MSD_Mass_Block_Count[MSD_NUM_LUN]; - - -/* Private variables ---------------------------------------------------------*/ -static __IO uint32_t Block_Read_count = 0; -static __IO uint32_t Block_offset; -static __IO uint32_t Counter = 0; -static uint32_t Idx; -static uint32_t Data_Buffer[MSD_BULK_MAX_PACKET_SIZE *2]; /* 512 bytes*/ -static uint8_t TransferState = TXFR_IDLE; - - -/* Extern variables ----------------------------------------------------------*/ - -/* Private function prototypes -----------------------------------------------*/ -/* Extern function prototypes ------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - - -/******************************************************************************* -* Function Name : Read_Memory -* Description : Handle the Read operation from the microSD card. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_Read_Memory(uint8_t lun, uint32_t Memory_Offset, uint32_t Transfer_Length) -{ - static uint32_t Offset, Length; - - if (TransferState == TXFR_IDLE ) - { - Offset = Memory_Offset * MSD_Mass_Block_Size[lun]; - Length = Transfer_Length * MSD_Mass_Block_Size[lun]; - TransferState = TXFR_ONGOING; - } - - if (TransferState == TXFR_ONGOING ) - { - if (!Block_Read_count) - { - s32 status; - - switch( lun ) { - case 0: - if( MSD_Mass_Block_Size[lun] != 512 ) - break; - status = PIOS_SDCARD_SectorRead(Offset/512, (u8 *)Data_Buffer); - // TK: how to handle an error here? - break; - - default: - status = -1; - // TK: how to handle an error here? - } - - UserToPMABufferCopy((uint8_t *)Data_Buffer, MSD_ENDP1_TXADDR, MSD_BULK_MAX_PACKET_SIZE); - Block_Read_count = MSD_Mass_Block_Size[lun] - MSD_BULK_MAX_PACKET_SIZE; - Block_offset = MSD_BULK_MAX_PACKET_SIZE; - } - else - { - UserToPMABufferCopy((uint8_t *)Data_Buffer + Block_offset, MSD_ENDP1_TXADDR, MSD_BULK_MAX_PACKET_SIZE); - Block_Read_count -= MSD_BULK_MAX_PACKET_SIZE; - Block_offset += MSD_BULK_MAX_PACKET_SIZE; - } - - SetEPTxCount(ENDP1, MSD_BULK_MAX_PACKET_SIZE); - SetEPTxStatus(ENDP1, EP_TX_VALID); - Offset += MSD_BULK_MAX_PACKET_SIZE; - Length -= MSD_BULK_MAX_PACKET_SIZE; - - MSD_CSW.dDataResidue -= MSD_BULK_MAX_PACKET_SIZE; - } - if (Length == 0) - { - Block_Read_count = 0; - Block_offset = 0; - Offset = 0; - MSD_Bot_State = BOT_DATA_IN_LAST; - TransferState = TXFR_IDLE; - } -} - -/******************************************************************************* -* Function Name : Write_Memory -* Description : Handle the Write operation to the microSD card. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_Write_Memory (uint8_t lun, uint32_t Memory_Offset, uint32_t Transfer_Length) -{ - - static uint32_t W_Offset, W_Length; - - uint32_t temp = Counter + 64; - - if (TransferState == TXFR_IDLE ) - { - W_Offset = Memory_Offset * MSD_Mass_Block_Size[lun]; - W_Length = Transfer_Length * MSD_Mass_Block_Size[lun]; - TransferState = TXFR_ONGOING; - } - - if (TransferState == TXFR_ONGOING ) - { - - for (Idx = 0 ; Counter < temp; Counter++) - { - *((uint8_t *)Data_Buffer + Counter) = MSD_Bulk_Data_Buff[Idx++]; - } - - W_Offset += MSD_Data_Len; - W_Length -= MSD_Data_Len; - - if (!(W_Length % MSD_Mass_Block_Size[lun])) - { - Counter = 0; - - s32 status; - u32 Offset = W_Offset - MSD_Mass_Block_Size[lun]; - - switch( lun ) { - case 0: - if( MSD_Mass_Block_Size[lun] != 512 ) - break; - status = PIOS_SDCARD_SectorWrite(Offset/512, (u8 *)Data_Buffer); - // TK: how to handle an error here? - break; - - default: - status = -1; - // TK: how to handle an error here? - } - } - - MSD_CSW.dDataResidue -= MSD_Data_Len; - SetEPRxStatus(ENDP2, EP_RX_VALID); /* enable the next transaction*/ - } - - if ((W_Length == 0) || (MSD_Bot_State == BOT_CSW_Send)) - { - Counter = 0; - MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); - TransferState = TXFR_IDLE; - } -} - - -/******************************************************************************* -* Function Name : MAL_GetStatus -* Description : Get status -* Input : None -* Output : None -* Return : None -*******************************************************************************/ -uint16_t MSD_MAL_GetStatus (uint8_t lun) -{ - // LUN removed or disabled? - if( !MSD_LUN_AvailableGet(lun) ) - return 1; - - if( lun == 0 ) { - SDCARDCsdTypeDef csd; - if( PIOS_SDCARD_CSDRead(&csd) < 0 ) - return 1; - - u32 DeviceSizeMul = csd.DeviceSizeMul + 2; - u32 temp_block_mul = (1 << csd.RdBlockLen)/ 512; - MSD_Mass_Block_Count[lun] = ((csd.DeviceSize + 1) * (1 << (DeviceSizeMul))) * temp_block_mul; - MSD_Mass_Block_Size[lun] = 512; - MSD_Mass_Memory_Size[lun] = (MSD_Mass_Block_Count[lun] * MSD_Mass_Block_Size[0]); - - return 0; - } - - return 1; -} - -/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ - +/** + ****************************************************************************** + * + * @file msd_memory.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Memory Management Layer + * @see The GNU Public License (GPL) Version 3 + * @defgroup MSD MSD Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** +* File Name : memory.c +* Author : MCD Application Team +* Version : V3.0.1 +* Date : 04/27/2009 +* Description : Memory management layer +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Includes ------------------------------------------------------------------*/ + +#include +#include + +#include "msd.h" +#include "msd_memory.h" +#include "msd_scsi.h" +#include "msd_bot.h" + + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ + +/* Global variables ----------------------------------------------------------*/ +uint32_t MSD_Mass_Memory_Size[MSD_NUM_LUN]; +uint32_t MSD_Mass_Block_Size[MSD_NUM_LUN]; +uint32_t MSD_Mass_Block_Count[MSD_NUM_LUN]; + + +/* Private variables ---------------------------------------------------------*/ +static __IO uint32_t Block_Read_count = 0; +static __IO uint32_t Block_offset; +static __IO uint32_t Counter = 0; +static uint32_t Idx; +static uint32_t Data_Buffer[MSD_BULK_MAX_PACKET_SIZE *2]; /* 512 bytes*/ +static uint8_t TransferState = TXFR_IDLE; + + +/* Extern variables ----------------------------------------------------------*/ + +/* Private function prototypes -----------------------------------------------*/ +/* Extern function prototypes ------------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + + +/******************************************************************************* +* Function Name : Read_Memory +* Description : Handle the Read operation from the microSD card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_Read_Memory(uint8_t lun, uint32_t Memory_Offset, uint32_t Transfer_Length) +{ + static uint32_t Offset, Length; + + if (TransferState == TXFR_IDLE ) + { + Offset = Memory_Offset * MSD_Mass_Block_Size[lun]; + Length = Transfer_Length * MSD_Mass_Block_Size[lun]; + TransferState = TXFR_ONGOING; + } + + if (TransferState == TXFR_ONGOING ) + { + if (!Block_Read_count) + { + s32 status; + + switch( lun ) { + case 0: + if( MSD_Mass_Block_Size[lun] != 512 ) + break; + status = PIOS_SDCARD_SectorRead(Offset/512, (u8 *)Data_Buffer); + // TK: how to handle an error here? + break; + + default: + status = -1; + // TK: how to handle an error here? + } + + UserToPMABufferCopy((uint8_t *)Data_Buffer, MSD_ENDP1_TXADDR, MSD_BULK_MAX_PACKET_SIZE); + Block_Read_count = MSD_Mass_Block_Size[lun] - MSD_BULK_MAX_PACKET_SIZE; + Block_offset = MSD_BULK_MAX_PACKET_SIZE; + } + else + { + UserToPMABufferCopy((uint8_t *)Data_Buffer + Block_offset, MSD_ENDP1_TXADDR, MSD_BULK_MAX_PACKET_SIZE); + Block_Read_count -= MSD_BULK_MAX_PACKET_SIZE; + Block_offset += MSD_BULK_MAX_PACKET_SIZE; + } + + SetEPTxCount(ENDP1, MSD_BULK_MAX_PACKET_SIZE); + SetEPTxStatus(ENDP1, EP_TX_VALID); + Offset += MSD_BULK_MAX_PACKET_SIZE; + Length -= MSD_BULK_MAX_PACKET_SIZE; + + MSD_CSW.dDataResidue -= MSD_BULK_MAX_PACKET_SIZE; + } + if (Length == 0) + { + Block_Read_count = 0; + Block_offset = 0; + Offset = 0; + MSD_Bot_State = BOT_DATA_IN_LAST; + TransferState = TXFR_IDLE; + } +} + +/******************************************************************************* +* Function Name : Write_Memory +* Description : Handle the Write operation to the microSD card. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_Write_Memory (uint8_t lun, uint32_t Memory_Offset, uint32_t Transfer_Length) +{ + + static uint32_t W_Offset, W_Length; + + uint32_t temp = Counter + 64; + + if (TransferState == TXFR_IDLE ) + { + W_Offset = Memory_Offset * MSD_Mass_Block_Size[lun]; + W_Length = Transfer_Length * MSD_Mass_Block_Size[lun]; + TransferState = TXFR_ONGOING; + } + + if (TransferState == TXFR_ONGOING ) + { + + for (Idx = 0 ; Counter < temp; Counter++) + { + *((uint8_t *)Data_Buffer + Counter) = MSD_Bulk_Data_Buff[Idx++]; + } + + W_Offset += MSD_Data_Len; + W_Length -= MSD_Data_Len; + + if (!(W_Length % MSD_Mass_Block_Size[lun])) + { + Counter = 0; + + s32 status; + u32 Offset = W_Offset - MSD_Mass_Block_Size[lun]; + + switch( lun ) { + case 0: + if( MSD_Mass_Block_Size[lun] != 512 ) + break; + status = PIOS_SDCARD_SectorWrite(Offset/512, (u8 *)Data_Buffer); + // TK: how to handle an error here? + break; + + default: + status = -1; + // TK: how to handle an error here? + } + } + + MSD_CSW.dDataResidue -= MSD_Data_Len; + SetEPRxStatus(ENDP2, EP_RX_VALID); /* enable the next transaction*/ + } + + if ((W_Length == 0) || (MSD_Bot_State == BOT_CSW_Send)) + { + Counter = 0; + MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); + TransferState = TXFR_IDLE; + } +} + + +/******************************************************************************* +* Function Name : MAL_GetStatus +* Description : Get status +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +uint16_t MSD_MAL_GetStatus (uint8_t lun) +{ + // LUN removed or disabled? + if( !MSD_LUN_AvailableGet(lun) ) + return 1; + + if( lun == 0 ) { + SDCARDCsdTypeDef csd; + if( PIOS_SDCARD_CSDRead(&csd) < 0 ) + return 1; + + u32 DeviceSizeMul = csd.DeviceSizeMul + 2; + u32 temp_block_mul = (1 << csd.RdBlockLen)/ 512; + MSD_Mass_Block_Count[lun] = ((csd.DeviceSize + 1) * (1 << (DeviceSizeMul))) * temp_block_mul; + MSD_Mass_Block_Size[lun] = 512; + MSD_Mass_Memory_Size[lun] = (MSD_Mass_Block_Count[lun] * MSD_Mass_Block_Size[0]); + + return 0; + } + + return 1; +} + +/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd_memory.h b/flight/PiOS/STM32F10x/Libraries/msd/msd_memory.h index 24d30d71d..e7cba65e0 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd_memory.h +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd_memory.h @@ -1,43 +1,43 @@ -/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** -* File Name : memory.h -* Author : MCD Application Team -* Version : V3.0.1 -* Date : 04/27/2009 -* Description : Memory management layer -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __memory_H -#define __memory_H - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" -#include "msd.h" - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -#define TXFR_IDLE 0 -#define TXFR_ONGOING 1 - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -extern void MSD_Write_Memory (uint8_t lun, uint32_t Memory_Offset, uint32_t Transfer_Length); -extern void MSD_Read_Memory (uint8_t lun, uint32_t Memory_Offset, uint32_t Transfer_Length); -extern uint16_t MSD_MAL_GetStatus (uint8_t lun); - -/* Exported variables ------------------------------------------------------- */ -extern uint32_t MSD_Mass_Memory_Size[MSD_NUM_LUN]; -extern uint32_t MSD_Mass_Block_Size[MSD_NUM_LUN]; -extern uint32_t MSD_Mass_Block_Count[MSD_NUM_LUN]; - -#endif /* __memory_H */ - -/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ - +/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** +* File Name : memory.h +* Author : MCD Application Team +* Version : V3.0.1 +* Date : 04/27/2009 +* Description : Memory management layer +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __memory_H +#define __memory_H + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" +#include "msd.h" + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +#define TXFR_IDLE 0 +#define TXFR_ONGOING 1 + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +extern void MSD_Write_Memory (uint8_t lun, uint32_t Memory_Offset, uint32_t Transfer_Length); +extern void MSD_Read_Memory (uint8_t lun, uint32_t Memory_Offset, uint32_t Transfer_Length); +extern uint16_t MSD_MAL_GetStatus (uint8_t lun); + +/* Exported variables ------------------------------------------------------- */ +extern uint32_t MSD_Mass_Memory_Size[MSD_NUM_LUN]; +extern uint32_t MSD_Mass_Block_Size[MSD_NUM_LUN]; +extern uint32_t MSD_Mass_Block_Count[MSD_NUM_LUN]; + +#endif /* __memory_H */ + +/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi.c b/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi.c index 746ee2dda..bb87c33d4 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi.c +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi.c @@ -1,430 +1,430 @@ -/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** -* File Name : usb_scsi.c -* Author : MCD Application Team -* Version : V3.0.1 -* Date : 04/27/2009 -* Description : All processing related to the SCSI commands -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Includes ------------------------------------------------------------------*/ -#include -#include - -#include - -#include "msd.h" -#include "msd_scsi.h" -#include "msd_bot.h" -#include "msd_memory.h" -//#include "nand_if.h" -//#include "platform_config.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* External variables --------------------------------------------------------*/ - -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/******************************************************************************* -* Function Name : SCSI_Inquiry_Cmd -* Description : SCSI Inquiry Command routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_Inquiry_Cmd(uint8_t lun) -{ - uint8_t* Inquiry_Data; - uint16_t Inquiry_Data_Length; - - if (MSD_CBW.CB[1] & 0x01)/*Evpd is set*/ - { - Inquiry_Data = MSD_Page00_Inquiry_Data; - Inquiry_Data_Length = 5; - } - else - { - - if ( lun == 0) - { - Inquiry_Data = MSD_Standard_Inquiry_Data; - } - else - { - Inquiry_Data = MSD_Standard_Inquiry_Data2; - } - - if (MSD_CBW.CB[4] <= STANDARD_INQUIRY_DATA_LEN) - Inquiry_Data_Length = MSD_CBW.CB[4]; - else - Inquiry_Data_Length = STANDARD_INQUIRY_DATA_LEN; - - } - MSD_Transfer_Data_Request(Inquiry_Data, Inquiry_Data_Length); -} - -/******************************************************************************* -* Function Name : MSD_SCSI_ReadFormatCapacity_Cmd -* Description : SCSI ReadFormatCapacity Command routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_ReadFormatCapacity_Cmd(uint8_t lun) -{ - - if (MSD_MAL_GetStatus(lun) != 0 ) - { - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, NOT_READY, MEDIUM_NOT_PRESENT); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_ENABLE); - MSD_Bot_Abort(DIR_IN); - return; - } - MSD_ReadFormatCapacity_Data[4] = (uint8_t)(MSD_Mass_Block_Count[lun] >> 24); - MSD_ReadFormatCapacity_Data[5] = (uint8_t)(MSD_Mass_Block_Count[lun] >> 16); - MSD_ReadFormatCapacity_Data[6] = (uint8_t)(MSD_Mass_Block_Count[lun] >> 8); - MSD_ReadFormatCapacity_Data[7] = (uint8_t)(MSD_Mass_Block_Count[lun]); - - MSD_ReadFormatCapacity_Data[9] = (uint8_t)(MSD_Mass_Block_Size[lun] >> 16); - MSD_ReadFormatCapacity_Data[10] = (uint8_t)(MSD_Mass_Block_Size[lun] >> 8); - MSD_ReadFormatCapacity_Data[11] = (uint8_t)(MSD_Mass_Block_Size[lun]); - MSD_Transfer_Data_Request(MSD_ReadFormatCapacity_Data, READ_FORMAT_CAPACITY_DATA_LEN); -} - -/******************************************************************************* -* Function Name : MSD_SCSI_ReadCapacity10_Cmd -* Description : SCSI ReadCapacity10 Command routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_ReadCapacity10_Cmd(uint8_t lun) -{ - - if (MSD_MAL_GetStatus(lun)) - { - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, NOT_READY, MEDIUM_NOT_PRESENT); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_ENABLE); - MSD_Bot_Abort(DIR_IN); - return; - } - - MSD_ReadCapacity10_Data[0] = (uint8_t)((MSD_Mass_Block_Count[lun] - 1) >> 24); - MSD_ReadCapacity10_Data[1] = (uint8_t)((MSD_Mass_Block_Count[lun] - 1) >> 16); - MSD_ReadCapacity10_Data[2] = (uint8_t)((MSD_Mass_Block_Count[lun] - 1) >> 8); - MSD_ReadCapacity10_Data[3] = (uint8_t)((MSD_Mass_Block_Count[lun] - 1)); - - MSD_ReadCapacity10_Data[4] = (uint8_t)(MSD_Mass_Block_Size[lun] >> 24); - MSD_ReadCapacity10_Data[5] = (uint8_t)(MSD_Mass_Block_Size[lun] >> 16); - MSD_ReadCapacity10_Data[6] = (uint8_t)(MSD_Mass_Block_Size[lun] >> 8); - MSD_ReadCapacity10_Data[7] = (uint8_t)(MSD_Mass_Block_Size[lun]); - MSD_Transfer_Data_Request(MSD_ReadCapacity10_Data, READ_CAPACITY10_DATA_LEN); -} - -/******************************************************************************* -* Function Name : MSD_SCSI_ModeSense6_Cmd -* Description : SCSI ModeSense6 Command routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_ModeSense6_Cmd (uint8_t lun) -{ - MSD_Transfer_Data_Request(MSD_Mode_Sense6_data, MODE_SENSE6_DATA_LEN); -} - -/******************************************************************************* -* Function Name : MSD_SCSI_ModeSense10_Cmd -* Description : SCSI ModeSense10 Command routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_ModeSense10_Cmd (uint8_t lun) -{ - MSD_Transfer_Data_Request(MSD_Mode_Sense10_data, MODE_SENSE10_DATA_LEN); -} - -/******************************************************************************* -* Function Name : MSD_SCSI_RequestSense_Cmd -* Description : SCSI RequestSense Command routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_RequestSense_Cmd (uint8_t lun) -{ - uint8_t Request_Sense_data_Length; - - if (MSD_CBW.CB[4] <= REQUEST_SENSE_DATA_LEN) - { - Request_Sense_data_Length = MSD_CBW.CB[4]; - } - else - { - Request_Sense_data_Length = REQUEST_SENSE_DATA_LEN; - } - MSD_Transfer_Data_Request(MSD_Scsi_Sense_Data, Request_Sense_data_Length); -} - -/******************************************************************************* -* Function Name : MSD_Set_Scsi_Sense_Data -* Description : Set Scsi Sense Data routine. -* Input : uint8_t Sens_Key - uint8_t Asc. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_Set_Scsi_Sense_Data(uint8_t lun, uint8_t Sens_Key, uint8_t Asc) -{ - MSD_Scsi_Sense_Data[2] = Sens_Key; - MSD_Scsi_Sense_Data[12] = Asc; -} - -/******************************************************************************* -* Function Name : MSD_SCSI_Start_Stop_Unit_Cmd -* Description : SCSI Start_Stop_Unit Command routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_Start_Stop_Unit_Cmd(uint8_t lun) -{ - MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); -} - -/******************************************************************************* -* Function Name : MSD_SCSI_Read10_Cmd -* Description : SCSI Read10 Command routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_Read10_Cmd(uint8_t lun , uint32_t LBA , uint32_t BlockNbr) -{ - - if (MSD_Bot_State == BOT_IDLE) - { - if (!(MSD_SCSI_Address_Management(MSD_CBW.bLUN, SCSI_READ10, LBA, BlockNbr)))/*address out of range*/ - { - return; - } - - if ((MSD_CBW.bmFlags & 0x80) != 0) - { - MSD_Bot_State = BOT_DATA_IN; - MSD_Read_Memory(lun, LBA , BlockNbr); - } - else - { - MSD_Bot_Abort(BOTH_DIR); - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_ENABLE); - } - return; - } - else if (MSD_Bot_State == BOT_DATA_IN) - { - MSD_Read_Memory(lun , LBA , BlockNbr); - } -} - -/******************************************************************************* -* Function Name : MSD_SCSI_Write10_Cmd -* Description : SCSI Write10 Command routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_Write10_Cmd(uint8_t lun , uint32_t LBA , uint32_t BlockNbr) -{ - - if (MSD_Bot_State == BOT_IDLE) - { - if (!(MSD_SCSI_Address_Management(MSD_CBW.bLUN, SCSI_WRITE10 , LBA, BlockNbr)))/*address out of range*/ - { - return; - } - - if ((MSD_CBW.bmFlags & 0x80) == 0) - { - MSD_Bot_State = BOT_DATA_OUT; - SetEPRxStatus(ENDP2, EP_RX_VALID); - } - else - { - MSD_Bot_Abort(DIR_IN); - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); - } - return; - } - else if (MSD_Bot_State == BOT_DATA_OUT) - { - MSD_Write_Memory(lun , LBA , BlockNbr); - } -} - -/******************************************************************************* -* Function Name : MSD_SCSI_Verify10_Cmd -* Description : SCSI Verify10 Command routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_Verify10_Cmd(uint8_t lun) -{ - if ((MSD_CBW.dDataLength == 0) && !(MSD_CBW.CB[1] & BLKVFY))/* BLKVFY not set*/ - { - MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); - } - else - { - MSD_Bot_Abort(BOTH_DIR); - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); - } -} -/******************************************************************************* -* Function Name : MSD_SCSI_Valid_Cmd -* Description : Valid Commands routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_Valid_Cmd(uint8_t lun) -{ - if (MSD_CBW.dDataLength != 0) - { - MSD_Bot_Abort(BOTH_DIR); - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_COMMAND); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); - } - else - MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); -} -/******************************************************************************* -* Function Name : MSD_SCSI_Valid_Cmd -* Description : Valid Commands routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_TestUnitReady_Cmd(uint8_t lun) -{ - if (MSD_MAL_GetStatus(lun)) - { - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, NOT_READY, MEDIUM_NOT_PRESENT); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_ENABLE); - MSD_Bot_Abort(DIR_IN); - return; - } - else - { - MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); - } -} -/******************************************************************************* -* Function Name : MSD_SCSI_Format_Cmd -* Description : Format Commands routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_Format_Cmd(uint8_t lun) -{ - if (MSD_MAL_GetStatus(lun)) - { - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, NOT_READY, MEDIUM_NOT_PRESENT); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_ENABLE); - MSD_Bot_Abort(DIR_IN); - return; - } -#ifdef USE_STM3210E_EVAL - else - { - NAND_Format(); - MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); - } -#endif - -} -/******************************************************************************* -* Function Name : MSD_SCSI_Invalid_Cmd -* Description : Invalid Commands routine -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void MSD_SCSI_Invalid_Cmd(uint8_t lun) -{ - if (MSD_CBW.dDataLength == 0) - { - MSD_Bot_Abort(DIR_IN); - } - else - { - if ((MSD_CBW.bmFlags & 0x80) != 0) - { - MSD_Bot_Abort(DIR_IN); - } - else - { - MSD_Bot_Abort(BOTH_DIR); - } - } - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_COMMAND); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); -} - -/******************************************************************************* -* Function Name : MSD_SCSI_Address_Management -* Description : Test the received address. -* Input : uint8_t Cmd : the command can be SCSI_READ10 or SCSI_WRITE10. -* Output : None. -* Return : Read\Write status (bool). -*******************************************************************************/ -bool MSD_SCSI_Address_Management(uint8_t lun , uint8_t Cmd , uint32_t LBA , uint32_t BlockNbr) -{ - - if ((LBA + BlockNbr) > MSD_Mass_Block_Count[lun] ) - { - if (Cmd == SCSI_WRITE10) - { - MSD_Bot_Abort(BOTH_DIR); - } - MSD_Bot_Abort(DIR_IN); - MSD_Set_Scsi_Sense_Data(lun, ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); - return (FALSE); - } - - - if (MSD_CBW.dDataLength != BlockNbr * MSD_Mass_Block_Size[lun]) - { - if (Cmd == SCSI_WRITE10) - { - MSD_Bot_Abort(BOTH_DIR); - } - else - { - MSD_Bot_Abort(DIR_IN); - } - MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); - MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); - return (FALSE); - } - return (TRUE); -} -/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ - +/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** +* File Name : usb_scsi.c +* Author : MCD Application Team +* Version : V3.0.1 +* Date : 04/27/2009 +* Description : All processing related to the SCSI commands +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Includes ------------------------------------------------------------------*/ +#include +#include + +#include + +#include "msd.h" +#include "msd_scsi.h" +#include "msd_bot.h" +#include "msd_memory.h" +//#include "nand_if.h" +//#include "platform_config.h" + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* External variables --------------------------------------------------------*/ + +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +/******************************************************************************* +* Function Name : SCSI_Inquiry_Cmd +* Description : SCSI Inquiry Command routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_Inquiry_Cmd(uint8_t lun) +{ + uint8_t* Inquiry_Data; + uint16_t Inquiry_Data_Length; + + if (MSD_CBW.CB[1] & 0x01)/*Evpd is set*/ + { + Inquiry_Data = MSD_Page00_Inquiry_Data; + Inquiry_Data_Length = 5; + } + else + { + + if ( lun == 0) + { + Inquiry_Data = MSD_Standard_Inquiry_Data; + } + else + { + Inquiry_Data = MSD_Standard_Inquiry_Data2; + } + + if (MSD_CBW.CB[4] <= STANDARD_INQUIRY_DATA_LEN) + Inquiry_Data_Length = MSD_CBW.CB[4]; + else + Inquiry_Data_Length = STANDARD_INQUIRY_DATA_LEN; + + } + MSD_Transfer_Data_Request(Inquiry_Data, Inquiry_Data_Length); +} + +/******************************************************************************* +* Function Name : MSD_SCSI_ReadFormatCapacity_Cmd +* Description : SCSI ReadFormatCapacity Command routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_ReadFormatCapacity_Cmd(uint8_t lun) +{ + + if (MSD_MAL_GetStatus(lun) != 0 ) + { + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, NOT_READY, MEDIUM_NOT_PRESENT); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_ENABLE); + MSD_Bot_Abort(DIR_IN); + return; + } + MSD_ReadFormatCapacity_Data[4] = (uint8_t)(MSD_Mass_Block_Count[lun] >> 24); + MSD_ReadFormatCapacity_Data[5] = (uint8_t)(MSD_Mass_Block_Count[lun] >> 16); + MSD_ReadFormatCapacity_Data[6] = (uint8_t)(MSD_Mass_Block_Count[lun] >> 8); + MSD_ReadFormatCapacity_Data[7] = (uint8_t)(MSD_Mass_Block_Count[lun]); + + MSD_ReadFormatCapacity_Data[9] = (uint8_t)(MSD_Mass_Block_Size[lun] >> 16); + MSD_ReadFormatCapacity_Data[10] = (uint8_t)(MSD_Mass_Block_Size[lun] >> 8); + MSD_ReadFormatCapacity_Data[11] = (uint8_t)(MSD_Mass_Block_Size[lun]); + MSD_Transfer_Data_Request(MSD_ReadFormatCapacity_Data, READ_FORMAT_CAPACITY_DATA_LEN); +} + +/******************************************************************************* +* Function Name : MSD_SCSI_ReadCapacity10_Cmd +* Description : SCSI ReadCapacity10 Command routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_ReadCapacity10_Cmd(uint8_t lun) +{ + + if (MSD_MAL_GetStatus(lun)) + { + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, NOT_READY, MEDIUM_NOT_PRESENT); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_ENABLE); + MSD_Bot_Abort(DIR_IN); + return; + } + + MSD_ReadCapacity10_Data[0] = (uint8_t)((MSD_Mass_Block_Count[lun] - 1) >> 24); + MSD_ReadCapacity10_Data[1] = (uint8_t)((MSD_Mass_Block_Count[lun] - 1) >> 16); + MSD_ReadCapacity10_Data[2] = (uint8_t)((MSD_Mass_Block_Count[lun] - 1) >> 8); + MSD_ReadCapacity10_Data[3] = (uint8_t)((MSD_Mass_Block_Count[lun] - 1)); + + MSD_ReadCapacity10_Data[4] = (uint8_t)(MSD_Mass_Block_Size[lun] >> 24); + MSD_ReadCapacity10_Data[5] = (uint8_t)(MSD_Mass_Block_Size[lun] >> 16); + MSD_ReadCapacity10_Data[6] = (uint8_t)(MSD_Mass_Block_Size[lun] >> 8); + MSD_ReadCapacity10_Data[7] = (uint8_t)(MSD_Mass_Block_Size[lun]); + MSD_Transfer_Data_Request(MSD_ReadCapacity10_Data, READ_CAPACITY10_DATA_LEN); +} + +/******************************************************************************* +* Function Name : MSD_SCSI_ModeSense6_Cmd +* Description : SCSI ModeSense6 Command routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_ModeSense6_Cmd (uint8_t lun) +{ + MSD_Transfer_Data_Request(MSD_Mode_Sense6_data, MODE_SENSE6_DATA_LEN); +} + +/******************************************************************************* +* Function Name : MSD_SCSI_ModeSense10_Cmd +* Description : SCSI ModeSense10 Command routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_ModeSense10_Cmd (uint8_t lun) +{ + MSD_Transfer_Data_Request(MSD_Mode_Sense10_data, MODE_SENSE10_DATA_LEN); +} + +/******************************************************************************* +* Function Name : MSD_SCSI_RequestSense_Cmd +* Description : SCSI RequestSense Command routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_RequestSense_Cmd (uint8_t lun) +{ + uint8_t Request_Sense_data_Length; + + if (MSD_CBW.CB[4] <= REQUEST_SENSE_DATA_LEN) + { + Request_Sense_data_Length = MSD_CBW.CB[4]; + } + else + { + Request_Sense_data_Length = REQUEST_SENSE_DATA_LEN; + } + MSD_Transfer_Data_Request(MSD_Scsi_Sense_Data, Request_Sense_data_Length); +} + +/******************************************************************************* +* Function Name : MSD_Set_Scsi_Sense_Data +* Description : Set Scsi Sense Data routine. +* Input : uint8_t Sens_Key + uint8_t Asc. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_Set_Scsi_Sense_Data(uint8_t lun, uint8_t Sens_Key, uint8_t Asc) +{ + MSD_Scsi_Sense_Data[2] = Sens_Key; + MSD_Scsi_Sense_Data[12] = Asc; +} + +/******************************************************************************* +* Function Name : MSD_SCSI_Start_Stop_Unit_Cmd +* Description : SCSI Start_Stop_Unit Command routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_Start_Stop_Unit_Cmd(uint8_t lun) +{ + MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); +} + +/******************************************************************************* +* Function Name : MSD_SCSI_Read10_Cmd +* Description : SCSI Read10 Command routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_Read10_Cmd(uint8_t lun , uint32_t LBA , uint32_t BlockNbr) +{ + + if (MSD_Bot_State == BOT_IDLE) + { + if (!(MSD_SCSI_Address_Management(MSD_CBW.bLUN, SCSI_READ10, LBA, BlockNbr)))/*address out of range*/ + { + return; + } + + if ((MSD_CBW.bmFlags & 0x80) != 0) + { + MSD_Bot_State = BOT_DATA_IN; + MSD_Read_Memory(lun, LBA , BlockNbr); + } + else + { + MSD_Bot_Abort(BOTH_DIR); + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_ENABLE); + } + return; + } + else if (MSD_Bot_State == BOT_DATA_IN) + { + MSD_Read_Memory(lun , LBA , BlockNbr); + } +} + +/******************************************************************************* +* Function Name : MSD_SCSI_Write10_Cmd +* Description : SCSI Write10 Command routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_Write10_Cmd(uint8_t lun , uint32_t LBA , uint32_t BlockNbr) +{ + + if (MSD_Bot_State == BOT_IDLE) + { + if (!(MSD_SCSI_Address_Management(MSD_CBW.bLUN, SCSI_WRITE10 , LBA, BlockNbr)))/*address out of range*/ + { + return; + } + + if ((MSD_CBW.bmFlags & 0x80) == 0) + { + MSD_Bot_State = BOT_DATA_OUT; + SetEPRxStatus(ENDP2, EP_RX_VALID); + } + else + { + MSD_Bot_Abort(DIR_IN); + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); + } + return; + } + else if (MSD_Bot_State == BOT_DATA_OUT) + { + MSD_Write_Memory(lun , LBA , BlockNbr); + } +} + +/******************************************************************************* +* Function Name : MSD_SCSI_Verify10_Cmd +* Description : SCSI Verify10 Command routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_Verify10_Cmd(uint8_t lun) +{ + if ((MSD_CBW.dDataLength == 0) && !(MSD_CBW.CB[1] & BLKVFY))/* BLKVFY not set*/ + { + MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); + } + else + { + MSD_Bot_Abort(BOTH_DIR); + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); + } +} +/******************************************************************************* +* Function Name : MSD_SCSI_Valid_Cmd +* Description : Valid Commands routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_Valid_Cmd(uint8_t lun) +{ + if (MSD_CBW.dDataLength != 0) + { + MSD_Bot_Abort(BOTH_DIR); + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_COMMAND); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); + } + else + MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); +} +/******************************************************************************* +* Function Name : MSD_SCSI_Valid_Cmd +* Description : Valid Commands routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_TestUnitReady_Cmd(uint8_t lun) +{ + if (MSD_MAL_GetStatus(lun)) + { + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, NOT_READY, MEDIUM_NOT_PRESENT); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_ENABLE); + MSD_Bot_Abort(DIR_IN); + return; + } + else + { + MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); + } +} +/******************************************************************************* +* Function Name : MSD_SCSI_Format_Cmd +* Description : Format Commands routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_Format_Cmd(uint8_t lun) +{ + if (MSD_MAL_GetStatus(lun)) + { + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, NOT_READY, MEDIUM_NOT_PRESENT); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_ENABLE); + MSD_Bot_Abort(DIR_IN); + return; + } +#ifdef USE_STM3210E_EVAL + else + { + NAND_Format(); + MSD_Set_CSW (CSW_CMD_PASSED, SEND_CSW_ENABLE); + } +#endif + +} +/******************************************************************************* +* Function Name : MSD_SCSI_Invalid_Cmd +* Description : Invalid Commands routine +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +void MSD_SCSI_Invalid_Cmd(uint8_t lun) +{ + if (MSD_CBW.dDataLength == 0) + { + MSD_Bot_Abort(DIR_IN); + } + else + { + if ((MSD_CBW.bmFlags & 0x80) != 0) + { + MSD_Bot_Abort(DIR_IN); + } + else + { + MSD_Bot_Abort(BOTH_DIR); + } + } + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_COMMAND); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); +} + +/******************************************************************************* +* Function Name : MSD_SCSI_Address_Management +* Description : Test the received address. +* Input : uint8_t Cmd : the command can be SCSI_READ10 or SCSI_WRITE10. +* Output : None. +* Return : Read\Write status (bool). +*******************************************************************************/ +bool MSD_SCSI_Address_Management(uint8_t lun , uint8_t Cmd , uint32_t LBA , uint32_t BlockNbr) +{ + + if ((LBA + BlockNbr) > MSD_Mass_Block_Count[lun] ) + { + if (Cmd == SCSI_WRITE10) + { + MSD_Bot_Abort(BOTH_DIR); + } + MSD_Bot_Abort(DIR_IN); + MSD_Set_Scsi_Sense_Data(lun, ILLEGAL_REQUEST, ADDRESS_OUT_OF_RANGE); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); + return (FALSE); + } + + + if (MSD_CBW.dDataLength != BlockNbr * MSD_Mass_Block_Size[lun]) + { + if (Cmd == SCSI_WRITE10) + { + MSD_Bot_Abort(BOTH_DIR); + } + else + { + MSD_Bot_Abort(DIR_IN); + } + MSD_Set_Scsi_Sense_Data(MSD_CBW.bLUN, ILLEGAL_REQUEST, INVALID_FIELED_IN_COMMAND); + MSD_Set_CSW (CSW_CMD_FAILED, SEND_CSW_DISABLE); + return (FALSE); + } + return (TRUE); +} +/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi.h b/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi.h index 45b0a28d6..2f1325b4c 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi.h +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi.h @@ -1,142 +1,142 @@ -/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** -* File Name : usb_scsi.h -* Author : MCD Application Team -* Version : V3.0.1 -* Date : 04/27/2009 -* Description : All processing related to the SCSI commands -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_SCSI_H -#define __USB_SCSI_H - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/* SCSI Commands */ -#define SCSI_FORMAT_UNIT 0x04 -#define SCSI_INQUIRY 0x12 -#define SCSI_MODE_SELECT6 0x15 -#define SCSI_MODE_SELECT10 0x55 -#define SCSI_MODE_SENSE6 0x1A -#define SCSI_MODE_SENSE10 0x5A -#define SCSI_ALLOW_MEDIUM_REMOVAL 0x1E -#define SCSI_READ6 0x08 -#define SCSI_READ10 0x28 -#define SCSI_READ12 0xA8 -#define SCSI_READ16 0x88 - -#define SCSI_READ_CAPACITY10 0x25 -#define SCSI_READ_CAPACITY16 0x9E - -#define SCSI_REQUEST_SENSE 0x03 -#define SCSI_START_STOP_UNIT 0x1B -#define SCSI_TEST_UNIT_READY 0x00 -#define SCSI_WRITE6 0x0A -#define SCSI_WRITE10 0x2A -#define SCSI_WRITE12 0xAA -#define SCSI_WRITE16 0x8A - -#define SCSI_VERIFY10 0x2F -#define SCSI_VERIFY12 0xAF -#define SCSI_VERIFY16 0x8F - -#define SCSI_SEND_DIAGNOSTIC 0x1D -#define SCSI_READ_FORMAT_CAPACITIES 0x23 - -#define NO_SENSE 0 -#define RECOVERED_ERROR 1 -#define NOT_READY 2 -#define MEDIUM_ERROR 3 -#define HARDWARE_ERROR 4 -#define ILLEGAL_REQUEST 5 -#define UNIT_ATTENTION 6 -#define DATA_PROTECT 7 -#define BLANK_CHECK 8 -#define VENDOR_SPECIFIC 9 -#define COPY_ABORTED 10 -#define ABORTED_COMMAND 11 -#define VOLUME_OVERFLOW 13 -#define MISCOMPARE 14 - - -#define INVALID_COMMAND 0x20 -#define INVALID_FIELED_IN_COMMAND 0x24 -#define PARAMETER_LIST_LENGTH_ERROR 0x1A -#define INVALID_FIELD_IN_PARAMETER_LIST 0x26 -#define ADDRESS_OUT_OF_RANGE 0x21 -#define MEDIUM_NOT_PRESENT 0x3A -#define MEDIUM_HAVE_CHANGED 0x28 - -#define READ_FORMAT_CAPACITY_DATA_LEN 0x0C -#define READ_CAPACITY10_DATA_LEN 0x08 -#define MODE_SENSE10_DATA_LEN 0x08 -#define MODE_SENSE6_DATA_LEN 0x04 -#define REQUEST_SENSE_DATA_LEN 0x12 -#define STANDARD_INQUIRY_DATA_LEN 0x24 -#define BLKVFY 0x04 - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -extern void MSD_SCSI_Inquiry_Cmd(uint8_t lun); -extern void MSD_SCSI_ReadFormatCapacity_Cmd(uint8_t lun); -extern void MSD_SCSI_ReadCapacity10_Cmd(uint8_t lun); -extern void MSD_SCSI_RequestSense_Cmd (uint8_t lun); -extern void MSD_SCSI_Start_Stop_Unit_Cmd(uint8_t lun); -extern void MSD_SCSI_ModeSense6_Cmd (uint8_t lun); -extern void MSD_SCSI_ModeSense10_Cmd (uint8_t lun); -extern void MSD_SCSI_Write10_Cmd(uint8_t lun , uint32_t LBA , uint32_t BlockNbr); -extern void MSD_SCSI_Read10_Cmd(uint8_t lun , uint32_t LBA , uint32_t BlockNbr); -extern void MSD_SCSI_Verify10_Cmd(uint8_t lun); - -extern void MSD_SCSI_Invalid_Cmd(uint8_t lun); -extern void MSD_SCSI_Valid_Cmd(uint8_t lun); -extern bool MSD_SCSI_Address_Management(uint8_t lun , uint8_t Cmd , uint32_t LBA , uint32_t BlockNbr); - -extern void MSD_Set_Scsi_Sense_Data(uint8_t lun , uint8_t Sens_Key, uint8_t Asc); -extern void MSD_SCSI_TestUnitReady_Cmd (uint8_t lun); -extern void MSD_SCSI_Format_Cmd (uint8_t lun); - -//#define MSD_SCSI_TestUnitReady_Cmd MSD_SCSI_Valid_Cmd -#define MSD_SCSI_Prevent_Removal_Cmd MSD_SCSI_Valid_Cmd - -/* Invalid (Unsupported) commands */ -#define MSD_SCSI_READ_CAPACITY16_Cmd MSD_SCSI_Invalid_Cmd -//#define MSD_SCSI_FormatUnit_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Write6_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Write16_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Write12_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Read6_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Read12_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Read16_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Send_Diagnostic_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Mode_Select6_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Mode_Select10_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Verify12_Cmd MSD_SCSI_Invalid_Cmd -#define MSD_SCSI_Verify16_Cmd MSD_SCSI_Invalid_Cmd - - -/* Exported variables ------------------------------------------------------- */ -extern uint8_t MSD_Page00_Inquiry_Data[]; -extern uint8_t MSD_Standard_Inquiry_Data[]; -extern uint8_t MSD_Standard_Inquiry_Data2[]; -extern uint8_t MSD_Mode_Sense6_data[]; -extern uint8_t MSD_Mode_Sense10_data[]; -extern uint8_t MSD_Scsi_Sense_Data[]; -extern uint8_t MSD_ReadCapacity10_Data[]; -extern uint8_t MSD_ReadFormatCapacity_Data []; - - -#endif /* __USB_SCSI_H */ - -/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ - +/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** +* File Name : usb_scsi.h +* Author : MCD Application Team +* Version : V3.0.1 +* Date : 04/27/2009 +* Description : All processing related to the SCSI commands +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __USB_SCSI_H +#define __USB_SCSI_H + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* SCSI Commands */ +#define SCSI_FORMAT_UNIT 0x04 +#define SCSI_INQUIRY 0x12 +#define SCSI_MODE_SELECT6 0x15 +#define SCSI_MODE_SELECT10 0x55 +#define SCSI_MODE_SENSE6 0x1A +#define SCSI_MODE_SENSE10 0x5A +#define SCSI_ALLOW_MEDIUM_REMOVAL 0x1E +#define SCSI_READ6 0x08 +#define SCSI_READ10 0x28 +#define SCSI_READ12 0xA8 +#define SCSI_READ16 0x88 + +#define SCSI_READ_CAPACITY10 0x25 +#define SCSI_READ_CAPACITY16 0x9E + +#define SCSI_REQUEST_SENSE 0x03 +#define SCSI_START_STOP_UNIT 0x1B +#define SCSI_TEST_UNIT_READY 0x00 +#define SCSI_WRITE6 0x0A +#define SCSI_WRITE10 0x2A +#define SCSI_WRITE12 0xAA +#define SCSI_WRITE16 0x8A + +#define SCSI_VERIFY10 0x2F +#define SCSI_VERIFY12 0xAF +#define SCSI_VERIFY16 0x8F + +#define SCSI_SEND_DIAGNOSTIC 0x1D +#define SCSI_READ_FORMAT_CAPACITIES 0x23 + +#define NO_SENSE 0 +#define RECOVERED_ERROR 1 +#define NOT_READY 2 +#define MEDIUM_ERROR 3 +#define HARDWARE_ERROR 4 +#define ILLEGAL_REQUEST 5 +#define UNIT_ATTENTION 6 +#define DATA_PROTECT 7 +#define BLANK_CHECK 8 +#define VENDOR_SPECIFIC 9 +#define COPY_ABORTED 10 +#define ABORTED_COMMAND 11 +#define VOLUME_OVERFLOW 13 +#define MISCOMPARE 14 + + +#define INVALID_COMMAND 0x20 +#define INVALID_FIELED_IN_COMMAND 0x24 +#define PARAMETER_LIST_LENGTH_ERROR 0x1A +#define INVALID_FIELD_IN_PARAMETER_LIST 0x26 +#define ADDRESS_OUT_OF_RANGE 0x21 +#define MEDIUM_NOT_PRESENT 0x3A +#define MEDIUM_HAVE_CHANGED 0x28 + +#define READ_FORMAT_CAPACITY_DATA_LEN 0x0C +#define READ_CAPACITY10_DATA_LEN 0x08 +#define MODE_SENSE10_DATA_LEN 0x08 +#define MODE_SENSE6_DATA_LEN 0x04 +#define REQUEST_SENSE_DATA_LEN 0x12 +#define STANDARD_INQUIRY_DATA_LEN 0x24 +#define BLKVFY 0x04 + +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +extern void MSD_SCSI_Inquiry_Cmd(uint8_t lun); +extern void MSD_SCSI_ReadFormatCapacity_Cmd(uint8_t lun); +extern void MSD_SCSI_ReadCapacity10_Cmd(uint8_t lun); +extern void MSD_SCSI_RequestSense_Cmd (uint8_t lun); +extern void MSD_SCSI_Start_Stop_Unit_Cmd(uint8_t lun); +extern void MSD_SCSI_ModeSense6_Cmd (uint8_t lun); +extern void MSD_SCSI_ModeSense10_Cmd (uint8_t lun); +extern void MSD_SCSI_Write10_Cmd(uint8_t lun , uint32_t LBA , uint32_t BlockNbr); +extern void MSD_SCSI_Read10_Cmd(uint8_t lun , uint32_t LBA , uint32_t BlockNbr); +extern void MSD_SCSI_Verify10_Cmd(uint8_t lun); + +extern void MSD_SCSI_Invalid_Cmd(uint8_t lun); +extern void MSD_SCSI_Valid_Cmd(uint8_t lun); +extern bool MSD_SCSI_Address_Management(uint8_t lun , uint8_t Cmd , uint32_t LBA , uint32_t BlockNbr); + +extern void MSD_Set_Scsi_Sense_Data(uint8_t lun , uint8_t Sens_Key, uint8_t Asc); +extern void MSD_SCSI_TestUnitReady_Cmd (uint8_t lun); +extern void MSD_SCSI_Format_Cmd (uint8_t lun); + +//#define MSD_SCSI_TestUnitReady_Cmd MSD_SCSI_Valid_Cmd +#define MSD_SCSI_Prevent_Removal_Cmd MSD_SCSI_Valid_Cmd + +/* Invalid (Unsupported) commands */ +#define MSD_SCSI_READ_CAPACITY16_Cmd MSD_SCSI_Invalid_Cmd +//#define MSD_SCSI_FormatUnit_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Write6_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Write16_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Write12_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Read6_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Read12_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Read16_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Send_Diagnostic_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Mode_Select6_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Mode_Select10_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Verify12_Cmd MSD_SCSI_Invalid_Cmd +#define MSD_SCSI_Verify16_Cmd MSD_SCSI_Invalid_Cmd + + +/* Exported variables ------------------------------------------------------- */ +extern uint8_t MSD_Page00_Inquiry_Data[]; +extern uint8_t MSD_Standard_Inquiry_Data[]; +extern uint8_t MSD_Standard_Inquiry_Data2[]; +extern uint8_t MSD_Mode_Sense6_data[]; +extern uint8_t MSD_Mode_Sense10_data[]; +extern uint8_t MSD_Scsi_Sense_Data[]; +extern uint8_t MSD_ReadCapacity10_Data[]; +extern uint8_t MSD_ReadFormatCapacity_Data []; + + +#endif /* __USB_SCSI_H */ + +/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi_data.c b/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi_data.c index a9522f936..e83af9501 100644 --- a/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi_data.c +++ b/flight/PiOS/STM32F10x/Libraries/msd/msd_scsi_data.c @@ -1,144 +1,144 @@ -/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** -* File Name : scsi_data.c -* Author : MCD Application Team -* Version : V3.0.1 -* Date : 04/27/2009 -* Description : Initialization of the SCSI data -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Includes ------------------------------------------------------------------*/ -#include "msd_scsi.h" -#include "msd_memory.h" -uint8_t MSD_Page00_Inquiry_Data[] = - { - 0x00, /* PERIPHERAL QUALIFIER & PERIPHERAL DEVICE TYPE*/ - 0x00, - 0x00, - 0x00, - 0x00 /* Supported Pages 00*/ - }; -uint8_t MSD_Standard_Inquiry_Data[] = - { - 0x00, /* Direct Access Device */ - 0x80, /* RMB = 1: Removable Medium */ - 0x02, /* Version: No conformance claim to standard */ - 0x02, - - 36 - 4, /* Additional Length */ - 0x00, /* SCCS = 1: Storage Controller Component */ - 0x00, - 0x00, - /* Vendor Identification */ - 'G', 'e', 'n', 'e', 'r', 'i', 'c', ' ', - /* Product Identification */ - 'S', 'D', ' ', 'C', 'a', 'r', 'd', ' ', - 'R', 'e', 'a', 'd', 'e', 'r', ' ', ' ', - /* Product Revision Level */ - '1', '.', '0', ' ' - }; -uint8_t MSD_Standard_Inquiry_Data2[] = - { - 0x00, /* Direct Access Device */ - 0x80, /* RMB = 1: Removable Medium */ - 0x02, /* Version: No conformance claim to standard */ - 0x02, - - 36 - 4, /* Additional Length */ - 0x00, /* SCCS = 1: Storage Controller Component */ - 0x00, - 0x00, - /* Vendor Identification */ - 'S', 'T', 'M', ' ', ' ', ' ', ' ', ' ', - /* Product Identification */ - 'N', 'A', 'N', 'D', ' ', 'F', 'l', 'a', 's', 'h', ' ', - 'D', 'i', 's', 'k', ' ', - /* Product Revision Level */ - '1', '.', '0', ' ' - }; -/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/ -uint8_t MSD_Mode_Sense6_data[] = - { - 0x03, - 0x00, - 0x00, - 0x00, - }; - -/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/ - -uint8_t MSD_Mode_Sense10_data[] = - { - 0x00, - 0x06, - 0x00, - 0x00, - 0x00, - 0x00, - 0x00, - 0x00 - }; -uint8_t MSD_Scsi_Sense_Data[] = - { - 0x70, /*RespCode*/ - 0x00, /*SegmentNumber*/ - NO_SENSE, /* Sens_Key*/ - 0x00, - 0x00, - 0x00, - 0x00, /*Information*/ - 0x0A, /*AdditionalSenseLength*/ - 0x00, - 0x00, - 0x00, - 0x00, /*CmdInformation*/ - NO_SENSE, /*Asc*/ - 0x00, /*ASCQ*/ - 0x00, /*FRUC*/ - 0x00, /*TBD*/ - 0x00, - 0x00 /*SenseKeySpecific*/ - }; -uint8_t MSD_ReadCapacity10_Data[] = - { - /* Last Logical Block */ - 0, - 0, - 0, - 0, - - /* Block Length */ - 0, - 0, - 0, - 0 - }; - -uint8_t MSD_ReadFormatCapacity_Data [] = - { - 0x00, - 0x00, - 0x00, - 0x08, /* Capacity List Length */ - - /* Block Count */ - 0, - 0, - 0, - 0, - - /* Block Length */ - 0x02,/* Descriptor Code: Formatted Media */ - 0, - 0, - 0 - }; - -/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ - +/******************** (C) COPYRIGHT 2009 STMicroelectronics ******************** +* File Name : scsi_data.c +* Author : MCD Application Team +* Version : V3.0.1 +* Date : 04/27/2009 +* Description : Initialization of the SCSI data +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Includes ------------------------------------------------------------------*/ +#include "msd_scsi.h" +#include "msd_memory.h" +uint8_t MSD_Page00_Inquiry_Data[] = + { + 0x00, /* PERIPHERAL QUALIFIER & PERIPHERAL DEVICE TYPE*/ + 0x00, + 0x00, + 0x00, + 0x00 /* Supported Pages 00*/ + }; +uint8_t MSD_Standard_Inquiry_Data[] = + { + 0x00, /* Direct Access Device */ + 0x80, /* RMB = 1: Removable Medium */ + 0x02, /* Version: No conformance claim to standard */ + 0x02, + + 36 - 4, /* Additional Length */ + 0x00, /* SCCS = 1: Storage Controller Component */ + 0x00, + 0x00, + /* Vendor Identification */ + 'G', 'e', 'n', 'e', 'r', 'i', 'c', ' ', + /* Product Identification */ + 'S', 'D', ' ', 'C', 'a', 'r', 'd', ' ', + 'R', 'e', 'a', 'd', 'e', 'r', ' ', ' ', + /* Product Revision Level */ + '1', '.', '0', ' ' + }; +uint8_t MSD_Standard_Inquiry_Data2[] = + { + 0x00, /* Direct Access Device */ + 0x80, /* RMB = 1: Removable Medium */ + 0x02, /* Version: No conformance claim to standard */ + 0x02, + + 36 - 4, /* Additional Length */ + 0x00, /* SCCS = 1: Storage Controller Component */ + 0x00, + 0x00, + /* Vendor Identification */ + 'S', 'T', 'M', ' ', ' ', ' ', ' ', ' ', + /* Product Identification */ + 'N', 'A', 'N', 'D', ' ', 'F', 'l', 'a', 's', 'h', ' ', + 'D', 'i', 's', 'k', ' ', + /* Product Revision Level */ + '1', '.', '0', ' ' + }; +/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/ +uint8_t MSD_Mode_Sense6_data[] = + { + 0x03, + 0x00, + 0x00, + 0x00, + }; + +/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/ + +uint8_t MSD_Mode_Sense10_data[] = + { + 0x00, + 0x06, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00 + }; +uint8_t MSD_Scsi_Sense_Data[] = + { + 0x70, /*RespCode*/ + 0x00, /*SegmentNumber*/ + NO_SENSE, /* Sens_Key*/ + 0x00, + 0x00, + 0x00, + 0x00, /*Information*/ + 0x0A, /*AdditionalSenseLength*/ + 0x00, + 0x00, + 0x00, + 0x00, /*CmdInformation*/ + NO_SENSE, /*Asc*/ + 0x00, /*ASCQ*/ + 0x00, /*FRUC*/ + 0x00, /*TBD*/ + 0x00, + 0x00 /*SenseKeySpecific*/ + }; +uint8_t MSD_ReadCapacity10_Data[] = + { + /* Last Logical Block */ + 0, + 0, + 0, + 0, + + /* Block Length */ + 0, + 0, + 0, + 0 + }; + +uint8_t MSD_ReadFormatCapacity_Data [] = + { + 0x00, + 0x00, + 0x00, + 0x08, /* Capacity List Length */ + + /* Block Count */ + 0, + 0, + 0, + 0, + + /* Block Length */ + 0x02,/* Descriptor Code: Formatted Media */ + 0, + 0, + 0 + }; + +/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/PiOS/STM32F10x/library.mk b/flight/PiOS/STM32F10x/library.mk index fc493c84a..df95cfc72 100644 --- a/flight/PiOS/STM32F10x/library.mk +++ b/flight/PiOS/STM32F10x/library.mk @@ -12,7 +12,7 @@ LINKER_SCRIPTS_PATH = $(PIOS_DEVLIB) CDEFS += -DSTM32F10X -DSTM32F10X_$(MODEL) CDEFS += -DUSE_STDPERIPH_DRIVER CDEFS += -DARM_MATH_CM3 -ARCHFLAGS += -mcpu=cortex-m3 +ARCHFLAGS += -mcpu=cortex-m3 --specs=nano.specs # Board-specific startup files ASRC += $(PIOS_DEVLIB)startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld index 19f70959d..6763f4275 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld @@ -1,114 +1,114 @@ -/* Stub out these functions since we don't use them anyway */ -PROVIDE ( vPortSVCHandler = 0 ) ; -PROVIDE ( xPortPendSVHandler = 0 ) ; -PROVIDE ( xPortSysTickHandler = 0 ) ; - -/* This is the size of the stack for early init and for all FreeRTOS IRQs */ -_irq_stack_size = 0x400; - -/* Section Definitions */ -SECTIONS -{ - .text : - { - PROVIDE (pios_isr_vector_table_base = .); - KEEP(*(.isr_vector .isr_vector.*)) - *(.text .text.* .gnu.linkonce.t.*) - *(.glue_7t) *(.glue_7) - *(.rodata .rodata* .gnu.linkonce.r.*) - } > BL_FLASH - - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) - } > BL_FLASH - - .ARM.exidx : - { - *(.ARM.exidx* .gnu.linkonce.armexidx.*) - } > BL_FLASH - - . = ALIGN(4); - _etext = .; - _sidata = .; - - .data : AT (_etext) - { - _sdata = .; - *(.data .data.*) - . = ALIGN(4); - _edata = . ; - } > SRAM - - /* .bss section which is used for uninitialized data */ - .bss (NOLOAD) : - { - _sbss = . ; - *(.bss .bss.*) - *(COMMON) - . = ALIGN(4); - _ebss = . ; - } > SRAM - - /* - * This stack is used both as the initial sp during early init as well as ultimately - * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that - * is used for _all_ interrupt handlers. The end of this stack should be placed - * against the lowest address in RAM so that a stack overrun results in a hard fault - * at the first access beyond the end of the stack. - */ - .irq_stack : - { - . = ALIGN(4); - _irq_stack_end = . ; - . = . + _irq_stack_size ; - . = ALIGN(4); - _irq_stack_top = . - 4 ; - _init_stack_top = _irq_stack_top; - . = ALIGN(4); - } > SRAM - - . = ALIGN(4); - _end = . ; - - .boardinfo : - { - . = ALIGN(4); - KEEP(*(.boardinfo)) - . = ALIGN(ORIGIN(BD_INFO)+LENGTH(BD_INFO)); - } > BD_INFO - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } -} +/* Stub out these functions since we don't use them anyway */ +PROVIDE ( vPortSVCHandler = 0 ) ; +PROVIDE ( xPortPendSVHandler = 0 ) ; +PROVIDE ( xPortSysTickHandler = 0 ) ; + +/* This is the size of the stack for early init and for all FreeRTOS IRQs */ +_irq_stack_size = 0x400; + +/* Section Definitions */ +SECTIONS +{ + .text : + { + PROVIDE (pios_isr_vector_table_base = .); + KEEP(*(.isr_vector .isr_vector.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + } > BL_FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > BL_FLASH + + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > BL_FLASH + + . = ALIGN(4); + _etext = .; + _sidata = .; + + .data : AT (_etext) + { + _sdata = .; + *(.data .data.*) + . = ALIGN(4); + _edata = . ; + } > SRAM + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + _sbss = . ; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + } > SRAM + + /* + * This stack is used both as the initial sp during early init as well as ultimately + * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that + * is used for _all_ interrupt handlers. The end of this stack should be placed + * against the lowest address in RAM so that a stack overrun results in a hard fault + * at the first access beyond the end of the stack. + */ + .irq_stack : + { + . = ALIGN(4); + _irq_stack_end = . ; + . = . + _irq_stack_size ; + . = ALIGN(4); + _irq_stack_top = . - 4 ; + _init_stack_top = _irq_stack_top; + . = ALIGN(4); + } > SRAM + + . = ALIGN(4); + _end = . ; + + .boardinfo : + { + . = ALIGN(4); + KEEP(*(.boardinfo)) + . = ALIGN(ORIGIN(BD_INFO)+LENGTH(BD_INFO)); + } > BD_INFO + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_memory.ld b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_memory.ld index fd36c31ba..66451bf62 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_memory.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_memory.ld @@ -1,7 +1,7 @@ -MEMORY -{ - BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x03000 - 0x00080 - BD_INFO (r) : ORIGIN = 0x08003000 - 0x80, LENGTH = 0x00080 - FLASH (rx) : ORIGIN = 0x08003000, LENGTH = 0x20000 - 0x03000 - SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x05000 -} +MEMORY +{ + BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x03000 - 0x00080 + BD_INFO (r) : ORIGIN = 0x08003000 - 0x80, LENGTH = 0x00080 + FLASH (rx) : ORIGIN = 0x08003000, LENGTH = 0x20000 - 0x03000 + SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x05000 +} diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld index 5df4741af..f3c6b468f 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld @@ -1,144 +1,144 @@ -/* This is the size of the stack for all FreeRTOS IRQs */ -_irq_stack_size = 0x240; -/* This is the size of the stack for early init: life span is until scheduler starts */ -_init_stack_size = 0x100; - -/* Stub out these functions since we don't use them anyway */ -PROVIDE ( vPortSVCHandler = 0 ) ; -PROVIDE ( xPortPendSVHandler = 0 ) ; -PROVIDE ( xPortSysTickHandler = 0 ) ; - -PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO)); - -/* Section Definitions */ -SECTIONS -{ - .text : - { - PROVIDE (pios_isr_vector_table_base = .); - KEEP(*(.isr_vector .isr_vector.*)) - *(.text .text.* .gnu.linkonce.t.*) - *(.glue_7t) *(.glue_7) - *(.rodata .rodata* .gnu.linkonce.r.*) - } > FLASH - - /* module sections */ - .initcallmodule.init : - { - . = ALIGN(4); - __module_initcall_start = .; - KEEP(*(.initcallmodule.init)) - . = ALIGN(4); - __module_initcall_end = .; - } >FLASH - - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) - } > FLASH - - .ARM.exidx : - { - *(.ARM.exidx* .gnu.linkonce.armexidx.*) - } > FLASH - - . = ALIGN(4); - _etext = .; - _sidata = .; - - /* - * This stack is used both as the initial sp during early init as well as ultimately - * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that - * is used for _all_ interrupt handlers. The end of this stack should be placed - * against the lowest address in RAM so that a stack overrun results in a hard fault - * at the first access beyond the end of the stack. - */ - .irq_stack : - { - . = ALIGN(4); - _irq_stack_end = . ; - . = . + _irq_stack_size ; - . = ALIGN(4); - _irq_stack_top = . - 4 ; - . = ALIGN(4); - } > SRAM - - .data : AT (_etext) - { - _sdata = .; - *(.data .data.*) - . = ALIGN(4); - _edata = . ; - } > SRAM - - - - /* .bss section which is used for uninitialized data */ - .bss (NOLOAD) : - { - _sbss = . ; - *(.bss .bss.*) - *(COMMON) - } > SRAM - - .heap (NOLOAD) : - { - . = ALIGN(4); - _sheap = . ; - _sheap_pre_rtos = . ; - *(.heap) - . = ALIGN(4); - _eheap = . ; - _eheap_pre_rtos = . ; - _init_stack_end = . ; - _sheap_post_rtos = . ; - . = . + _init_stack_size ; - . = ALIGN(4); - _eheap_post_rtos = . ; - _init_stack_top = . - 4 ; - } > SRAM - - _eram = ORIGIN(SRAM) + LENGTH(SRAM) ; - _ebss = _eram ; - - /* keep the heap section at the end of the SRAM - * this will allow to claim the remaining bytes not used - * at run time! (done by the reset vector). - */ - - PROVIDE ( _end = _ebss ) ; - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } -} +/* This is the size of the stack for all FreeRTOS IRQs */ +_irq_stack_size = 0x240; +/* This is the size of the stack for early init: life span is until scheduler starts */ +_init_stack_size = 0x100; + +/* Stub out these functions since we don't use them anyway */ +PROVIDE ( vPortSVCHandler = 0 ) ; +PROVIDE ( xPortPendSVHandler = 0 ) ; +PROVIDE ( xPortSysTickHandler = 0 ) ; + +PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO)); + +/* Section Definitions */ +SECTIONS +{ + .text : + { + PROVIDE (pios_isr_vector_table_base = .); + KEEP(*(.isr_vector .isr_vector.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + } > FLASH + + /* module sections */ + .initcallmodule.init : + { + . = ALIGN(4); + __module_initcall_start = .; + KEEP(*(.initcallmodule.init)) + . = ALIGN(4); + __module_initcall_end = .; + } >FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > FLASH + + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > FLASH + + . = ALIGN(4); + _etext = .; + _sidata = .; + + /* + * This stack is used both as the initial sp during early init as well as ultimately + * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that + * is used for _all_ interrupt handlers. The end of this stack should be placed + * against the lowest address in RAM so that a stack overrun results in a hard fault + * at the first access beyond the end of the stack. + */ + .irq_stack : + { + . = ALIGN(4); + _irq_stack_end = . ; + . = . + _irq_stack_size ; + . = ALIGN(4); + _irq_stack_top = . - 4 ; + . = ALIGN(4); + } > SRAM + + .data : AT (_etext) + { + _sdata = .; + *(.data .data.*) + . = ALIGN(4); + _edata = . ; + } > SRAM + + + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + _sbss = . ; + *(.bss .bss.*) + *(COMMON) + } > SRAM + + .heap (NOLOAD) : + { + . = ALIGN(4); + _sheap = . ; + _sheap_pre_rtos = . ; + *(.heap) + . = ALIGN(4); + _eheap = . ; + _eheap_pre_rtos = . ; + _init_stack_end = . ; + _sheap_post_rtos = . ; + . = . + _init_stack_size ; + . = ALIGN(4); + _eheap_post_rtos = . ; + _init_stack_top = . - 4 ; + } > SRAM + + _eram = ORIGIN(SRAM) + LENGTH(SRAM) ; + _ebss = _eram ; + + /* keep the heap section at the end of the SRAM + * this will allow to claim the remaining bytes not used + * at run time! (done by the reset vector). + */ + + PROVIDE ( _end = _ebss ) ; + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_BL_sections.ld index 19f70959d..6763f4275 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_BL_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_BL_sections.ld @@ -1,114 +1,114 @@ -/* Stub out these functions since we don't use them anyway */ -PROVIDE ( vPortSVCHandler = 0 ) ; -PROVIDE ( xPortPendSVHandler = 0 ) ; -PROVIDE ( xPortSysTickHandler = 0 ) ; - -/* This is the size of the stack for early init and for all FreeRTOS IRQs */ -_irq_stack_size = 0x400; - -/* Section Definitions */ -SECTIONS -{ - .text : - { - PROVIDE (pios_isr_vector_table_base = .); - KEEP(*(.isr_vector .isr_vector.*)) - *(.text .text.* .gnu.linkonce.t.*) - *(.glue_7t) *(.glue_7) - *(.rodata .rodata* .gnu.linkonce.r.*) - } > BL_FLASH - - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) - } > BL_FLASH - - .ARM.exidx : - { - *(.ARM.exidx* .gnu.linkonce.armexidx.*) - } > BL_FLASH - - . = ALIGN(4); - _etext = .; - _sidata = .; - - .data : AT (_etext) - { - _sdata = .; - *(.data .data.*) - . = ALIGN(4); - _edata = . ; - } > SRAM - - /* .bss section which is used for uninitialized data */ - .bss (NOLOAD) : - { - _sbss = . ; - *(.bss .bss.*) - *(COMMON) - . = ALIGN(4); - _ebss = . ; - } > SRAM - - /* - * This stack is used both as the initial sp during early init as well as ultimately - * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that - * is used for _all_ interrupt handlers. The end of this stack should be placed - * against the lowest address in RAM so that a stack overrun results in a hard fault - * at the first access beyond the end of the stack. - */ - .irq_stack : - { - . = ALIGN(4); - _irq_stack_end = . ; - . = . + _irq_stack_size ; - . = ALIGN(4); - _irq_stack_top = . - 4 ; - _init_stack_top = _irq_stack_top; - . = ALIGN(4); - } > SRAM - - . = ALIGN(4); - _end = . ; - - .boardinfo : - { - . = ALIGN(4); - KEEP(*(.boardinfo)) - . = ALIGN(ORIGIN(BD_INFO)+LENGTH(BD_INFO)); - } > BD_INFO - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } -} +/* Stub out these functions since we don't use them anyway */ +PROVIDE ( vPortSVCHandler = 0 ) ; +PROVIDE ( xPortPendSVHandler = 0 ) ; +PROVIDE ( xPortSysTickHandler = 0 ) ; + +/* This is the size of the stack for early init and for all FreeRTOS IRQs */ +_irq_stack_size = 0x400; + +/* Section Definitions */ +SECTIONS +{ + .text : + { + PROVIDE (pios_isr_vector_table_base = .); + KEEP(*(.isr_vector .isr_vector.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + } > BL_FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > BL_FLASH + + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > BL_FLASH + + . = ALIGN(4); + _etext = .; + _sidata = .; + + .data : AT (_etext) + { + _sdata = .; + *(.data .data.*) + . = ALIGN(4); + _edata = . ; + } > SRAM + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + _sbss = . ; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + } > SRAM + + /* + * This stack is used both as the initial sp during early init as well as ultimately + * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that + * is used for _all_ interrupt handlers. The end of this stack should be placed + * against the lowest address in RAM so that a stack overrun results in a hard fault + * at the first access beyond the end of the stack. + */ + .irq_stack : + { + . = ALIGN(4); + _irq_stack_end = . ; + . = . + _irq_stack_size ; + . = ALIGN(4); + _irq_stack_top = . - 4 ; + _init_stack_top = _irq_stack_top; + . = ALIGN(4); + } > SRAM + + . = ALIGN(4); + _end = . ; + + .boardinfo : + { + . = ALIGN(4); + KEEP(*(.boardinfo)) + . = ALIGN(ORIGIN(BD_INFO)+LENGTH(BD_INFO)); + } > BD_INFO + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_memory.ld b/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_memory.ld index 04aa69ccb..80b110bba 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_memory.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_memory.ld @@ -1,8 +1,8 @@ -MEMORY -{ - BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x03000 - 0x00080 - BD_INFO (r) : ORIGIN = 0x08003000 - 0x80, LENGTH = 0x00080 - FLASH (rx) : ORIGIN = 0x08003000, LENGTH = 0x20000 - 0x03000 - 0x00400 - EE_FLASH (rw) : ORIGIN = 0x0801FC00, LENGTH = 0x00400 - SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x05000 -} +MEMORY +{ + BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x03000 - 0x00080 + BD_INFO (r) : ORIGIN = 0x08003000 - 0x80, LENGTH = 0x00080 + FLASH (rx) : ORIGIN = 0x08003000, LENGTH = 0x20000 - 0x03000 - 0x00400 + EE_FLASH (rw) : ORIGIN = 0x0801FC00, LENGTH = 0x00400 + SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x05000 +} diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_sections.ld index 074dad236..7f87323a0 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_PIPXTREME_sections.ld @@ -1,144 +1,144 @@ -/* This is the size of the stack for all FreeRTOS IRQs */ -_irq_stack_size = 0x1A0; -/* This is the size of the stack for early init: life span is until scheduler starts */ -_init_stack_size = 0x100; - -/* Stub out these functions since we don't use them anyway */ -PROVIDE ( vPortSVCHandler = 0 ) ; -PROVIDE ( xPortPendSVHandler = 0 ) ; -PROVIDE ( xPortSysTickHandler = 0 ) ; - -PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO)); - -/* Section Definitions */ -SECTIONS -{ - .text : - { - PROVIDE (pios_isr_vector_table_base = .); - KEEP(*(.isr_vector .isr_vector.*)) - *(.text .text.* .gnu.linkonce.t.*) - *(.glue_7t) *(.glue_7) - *(.rodata .rodata* .gnu.linkonce.r.*) - } > FLASH - - /* module sections */ - .initcallmodule.init : - { - . = ALIGN(4); - __module_initcall_start = .; - KEEP(*(.initcallmodule.init)) - . = ALIGN(4); - __module_initcall_end = .; - } >FLASH - - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) - } > FLASH - - .ARM.exidx : - { - *(.ARM.exidx* .gnu.linkonce.armexidx.*) - } > FLASH - - . = ALIGN(4); - _etext = .; - _sidata = .; - - /* - * This stack is used both as the initial sp during early init as well as ultimately - * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that - * is used for _all_ interrupt handlers. The end of this stack should be placed - * against the lowest address in RAM so that a stack overrun results in a hard fault - * at the first access beyond the end of the stack. - */ - .irq_stack : - { - . = ALIGN(4); - _irq_stack_end = . ; - . = . + _irq_stack_size ; - . = ALIGN(4); - _irq_stack_top = . - 4 ; - . = ALIGN(4); - } > SRAM - - .data : AT (_etext) - { - _sdata = .; - *(.data .data.*) - . = ALIGN(4); - _edata = . ; - } > SRAM - - - - /* .bss section which is used for uninitialized data */ - .bss (NOLOAD) : - { - _sbss = . ; - *(.bss .bss.*) - *(COMMON) - } > SRAM - - .heap (NOLOAD) : - { - . = ALIGN(4); - _sheap = . ; - _sheap_pre_rtos = . ; - *(.heap) - . = ALIGN(4); - _eheap = . ; - _eheap_pre_rtos = . ; - _init_stack_end = . ; - _sheap_post_rtos = . ; - . = . + _init_stack_size ; - . = ALIGN(4); - _eheap_post_rtos = . ; - _init_stack_top = . - 4 ; - } > SRAM - - _eram = ORIGIN(SRAM) + LENGTH(SRAM) ; - _ebss = _eram ; - - /* keep the heap section at the end of the SRAM - * this will allow to claim the remaining bytes not used - * at run time! (done by the reset vector). - */ - - PROVIDE ( _end = _ebss ) ; - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } -} +/* This is the size of the stack for all FreeRTOS IRQs */ +_irq_stack_size = 0x1A0; +/* This is the size of the stack for early init: life span is until scheduler starts */ +_init_stack_size = 0x100; + +/* Stub out these functions since we don't use them anyway */ +PROVIDE ( vPortSVCHandler = 0 ) ; +PROVIDE ( xPortPendSVHandler = 0 ) ; +PROVIDE ( xPortSysTickHandler = 0 ) ; + +PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO)); + +/* Section Definitions */ +SECTIONS +{ + .text : + { + PROVIDE (pios_isr_vector_table_base = .); + KEEP(*(.isr_vector .isr_vector.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + } > FLASH + + /* module sections */ + .initcallmodule.init : + { + . = ALIGN(4); + __module_initcall_start = .; + KEEP(*(.initcallmodule.init)) + . = ALIGN(4); + __module_initcall_end = .; + } >FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > FLASH + + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > FLASH + + . = ALIGN(4); + _etext = .; + _sidata = .; + + /* + * This stack is used both as the initial sp during early init as well as ultimately + * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that + * is used for _all_ interrupt handlers. The end of this stack should be placed + * against the lowest address in RAM so that a stack overrun results in a hard fault + * at the first access beyond the end of the stack. + */ + .irq_stack : + { + . = ALIGN(4); + _irq_stack_end = . ; + . = . + _irq_stack_size ; + . = ALIGN(4); + _irq_stack_top = . - 4 ; + . = ALIGN(4); + } > SRAM + + .data : AT (_etext) + { + _sdata = .; + *(.data .data.*) + . = ALIGN(4); + _edata = . ; + } > SRAM + + + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + _sbss = . ; + *(.bss .bss.*) + *(COMMON) + } > SRAM + + .heap (NOLOAD) : + { + . = ALIGN(4); + _sheap = . ; + _sheap_pre_rtos = . ; + *(.heap) + . = ALIGN(4); + _eheap = . ; + _eheap_pre_rtos = . ; + _init_stack_end = . ; + _sheap_post_rtos = . ; + . = . + _init_stack_size ; + . = ALIGN(4); + _eheap_post_rtos = . ; + _init_stack_top = . - 4 ; + } > SRAM + + _eram = ORIGIN(SRAM) + LENGTH(SRAM) ; + _ebss = _eram ; + + /* keep the heap section at the end of the SRAM + * this will allow to claim the remaining bytes not used + * at run time! (done by the reset vector). + */ + + PROVIDE ( _end = _ebss ) ; + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} diff --git a/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld index c7414707d..eabe17a83 100644 --- a/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld @@ -1,356 +1,356 @@ -/* This is the size of the stack for early init and for all FreeRTOS IRQs */ -_irq_stack_size = 0x800; - -/* Check valid alignment for VTOR */ -ASSERT(ORIGIN(BL_FLASH) == ALIGN(ORIGIN(BL_FLASH), 0x80), "Start of memory region flash not aligned for startup vector table"); - -/* -this sends all unreferenced IRQHandlers to reset -*/ - - -PROVIDE ( Undefined_Handler = 0 ) ; -PROVIDE ( SWI_Handler = 0 ) ; -PROVIDE ( IRQ_Handler = 0 ) ; -PROVIDE ( Prefetch_Handler = 0 ) ; -PROVIDE ( Abort_Handler = 0 ) ; -PROVIDE ( FIQ_Handler = 0 ) ; - -PROVIDE ( NMI_Handler = 0 ) ; -PROVIDE ( HardFault_Handler = 0 ) ; -PROVIDE ( MemManage_Handler = 0 ) ; -PROVIDE ( BusFault_Handler = 0 ) ; -PROVIDE ( UsageFault_Handler = 0 ) ; -PROVIDE ( vPortSVCHandler = 0 ) ; -PROVIDE ( DebugMon_Handler = 0 ) ; -PROVIDE ( xPortPendSVHandler = 0 ) ; -PROVIDE ( xPortSysTickHandler = 0 ) ; - -PROVIDE ( WWDG_IRQHandler = 0 ) ; -PROVIDE ( PVD_IRQHandler = 0 ) ; -PROVIDE ( TAMPER_IRQHandler = 0 ) ; -PROVIDE ( RTC_IRQHandler = 0 ) ; -PROVIDE ( FLASH_IRQHandler = 0 ) ; -PROVIDE ( RCC_IRQHandler = 0 ) ; -PROVIDE ( EXTI0_IRQHandler = 0 ) ; -PROVIDE ( EXTI1_IRQHandler = 0 ) ; -PROVIDE ( EXTI2_IRQHandler = 0 ) ; -PROVIDE ( EXTI3_IRQHandler = 0 ) ; -PROVIDE ( EXTI4_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel1_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel2_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel3_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel4_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel5_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel6_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel7_IRQHandler = 0 ) ; -PROVIDE ( ADC_IRQHandler = 0 ) ; -PROVIDE ( USB_HP_CAN1_TX_IRQHandler = 0 ) ; -PROVIDE ( USB_LP_CAN1_RX0_IRQHandler = 0 ) ; -PROVIDE ( CAN1_RX1_IRQHandler = 0 ) ; -PROVIDE ( CAN1_SCE_IRQHandler = 0 ) ; -PROVIDE ( EXTI9_5_IRQHandler = 0 ) ; -PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ; -PROVIDE ( TIM1_UP_IRQHandler = 0 ) ; -PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ; -PROVIDE ( TIM1_CC_IRQHandler = 0 ) ; -PROVIDE ( TIM2_IRQHandler = 0 ) ; -PROVIDE ( TIM3_IRQHandler = 0 ) ; -PROVIDE ( TIM4_IRQHandler = 0 ) ; -PROVIDE ( I2C1_EV_IRQHandler = 0 ) ; -PROVIDE ( I2C1_ER_IRQHandler = 0 ) ; -PROVIDE ( I2C2_EV_IRQHandler = 0 ) ; -PROVIDE ( I2C2_ER_IRQHandler = 0 ) ; -PROVIDE ( SPI1_IRQHandler = 0 ) ; -PROVIDE ( SPI2_IRQHandler = 0 ) ; -PROVIDE ( USART1_IRQHandler = 0 ) ; -PROVIDE ( USART2_IRQHandler = 0 ) ; -PROVIDE ( USART3_IRQHandler = 0 ) ; -PROVIDE ( EXTI15_10_IRQHandler = 0 ) ; -PROVIDE ( RTCAlarm_IRQHandler = 0 ) ; -PROVIDE ( USBWakeUp_IRQHandler = 0 ) ; -PROVIDE ( TIM8_BRK_IRQHandler = 0 ) ; -PROVIDE ( TIM8_UP_IRQHandler = 0 ) ; -PROVIDE ( TIM8_TRG_COM_IRQHandler = 0 ) ; -PROVIDE ( TIM8_CC_IRQHandler = 0 ) ; -PROVIDE ( ADC3_IRQHandler = 0 ) ; -PROVIDE ( FSMC_IRQHandler = 0 ) ; -PROVIDE ( SDIO_IRQHandler = 0 ) ; -PROVIDE ( TIM5_IRQHandler = 0 ) ; -PROVIDE ( SPI3_IRQHandler = 0 ) ; -PROVIDE ( UART4_IRQHandler = 0 ) ; -PROVIDE ( UART5_IRQHandler = 0 ) ; -PROVIDE ( TIM6_IRQHandler = 0 ) ; -PROVIDE ( TIM7_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel1_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel2_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel3_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel4_5_IRQHandler = 0 ) ; - - - -/******************************************************************************/ -/* Peripheral memory map */ -/******************************************************************************/ -/*this allows to compile the ST lib in "non-debug" mode*/ - - -/* Peripheral and SRAM base address in the alias region */ -PERIPH_BB_BASE = 0x42000000; -SRAM_BB_BASE = 0x22000000; - -/* Peripheral and SRAM base address in the bit-band region */ -SRAM_BASE = 0x20000000; -PERIPH_BASE = 0x40000000; - -/* Flash registers base address */ -PROVIDE ( FLASH_BASE = 0x40022000); -/* Flash Option Bytes base address */ -PROVIDE ( OB_BASE = 0x1FFFF800); - -/* Peripheral memory map */ -APB1PERIPH_BASE = PERIPH_BASE ; -APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ; -AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ; - -PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ; -PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ; -PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ; -PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ; -PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ; -PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ; -PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ; -PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ; -PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ; -PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ; -PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ; -PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ; -PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ; -PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ; - -PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ; -PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ; -PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ; -PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ; -PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ; -PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ; -PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ; -PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ; -PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ; -PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ; -PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ; -PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ; - -PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ; -PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ; -PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ; -PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ; -PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ; -PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ; -PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ; -PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ; -PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ; - -/* System Control Space memory map */ -SCS_BASE = 0xE000E000; - -PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ; -PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ; -PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ; - - -/* Sections Definitions */ - -SECTIONS -{ - /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */ - .isr_vector : - { - PROVIDE (pios_isr_vector_table_base = .); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } > BL_FLASH - - /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */ - .flashtext : - { - . = ALIGN(4); - *(.flashtext) /* Startup code */ - . = ALIGN(4); - } > BL_FLASH - - /* the program code is stored in the .text section, which goes to Flash */ - .text : - { - . = ALIGN(4); - - *(.text) /* remaining code */ - *(.text.*) /* remaining code */ - *(.rodata) /* read-only data (constants) */ - *(.rodata*) - *(.glue_7) - *(.glue_7t) - - . = ALIGN(4); - _etext = .; - /* This is used by the startup in order to initialize the .data secion */ - _sidata = _etext; - } > BL_FLASH - - - /* - * This stack is used both as the initial sp during early init as well as ultimately - * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that - * is used for _all_ interrupt handlers. The end of this stack should be placed - * against the lowest address in RAM so that a stack overrun results in a hard fault - * at the first access beyond the end of the stack. - */ - .irq_stack : - { - . = ALIGN(4); - _irq_stack_end = . ; - . = . + _irq_stack_size ; - . = ALIGN(4); - _irq_stack_top = . - 4 ; - _init_stack_top = _irq_stack_top; - . = ALIGN(4); - } >RAM - - - /* This is the initialized data section - The program executes knowing that the data is in the RAM - but the loader puts the initial values in the FLASH (inidata). - It is one task of the startup to copy the initial values from FLASH to RAM. */ - .data : AT ( _sidata ) - { - . = ALIGN(4); - /* This is used by the startup in order to initialize the .data secion */ - _sdata = . ; - - *(.data) - *(.data.*) - . = ALIGN(4); - /* This is used by the startup in order to initialize the .data secion */ - _edata = . ; - } >RAM - - - - /* This is the uninitialized data section */ - .bss : - { - . = ALIGN(4); - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; - - *(.bss) - *(COMMON) - - . = ALIGN(4); - /* This is used by the startup in order to initialize the .bss secion */ - _ebss = . ; - } >RAM - - PROVIDE ( end = _ebss ); - PROVIDE ( _end = _ebss ); - - /* this is the FLASH Bank1 */ - /* the C or assembly source must explicitly place the code or data there - using the "section" attribute */ - .b1text : - { - *(.b1text) /* remaining code */ - *(.b1rodata) /* read-only data (constants) */ - *(.b1rodata*) - } >FLASHB1 - - /* this is the EXTMEM */ - /* the C or assembly source must explicitly place the code or data there - using the "section" attribute */ - - /* EXTMEM Bank0 */ - .eb0text : - { - *(.eb0text) /* remaining code */ - *(.eb0rodata) /* read-only data (constants) */ - *(.eb0rodata*) - } >EXTMEMB0 - - /* EXTMEM Bank1 */ - .eb1text : - { - *(.eb1text) /* remaining code */ - *(.eb1rodata) /* read-only data (constants) */ - *(.eb1rodata*) - } >EXTMEMB1 - - /* EXTMEM Bank2 */ - .eb2text : - { - *(.eb2text) /* remaining code */ - *(.eb2rodata) /* read-only data (constants) */ - *(.eb2rodata*) - } >EXTMEMB2 - - /* EXTMEM Bank0 */ - .eb3text : - { - *(.eb3text) /* remaining code */ - *(.eb3rodata) /* read-only data (constants) */ - *(.eb3rodata*) - } >EXTMEMB3 - - __exidx_start = .; - __exidx_end = .; - - .boardinfo : - { - . = ALIGN(4); - KEEP(*(.boardinfo)) - . = ALIGN(4); - } > BD_INFO - - /* after that it's only debugging information. */ - - /* remove the debugging information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } -} +/* This is the size of the stack for early init and for all FreeRTOS IRQs */ +_irq_stack_size = 0x800; + +/* Check valid alignment for VTOR */ +ASSERT(ORIGIN(BL_FLASH) == ALIGN(ORIGIN(BL_FLASH), 0x80), "Start of memory region flash not aligned for startup vector table"); + +/* +this sends all unreferenced IRQHandlers to reset +*/ + + +PROVIDE ( Undefined_Handler = 0 ) ; +PROVIDE ( SWI_Handler = 0 ) ; +PROVIDE ( IRQ_Handler = 0 ) ; +PROVIDE ( Prefetch_Handler = 0 ) ; +PROVIDE ( Abort_Handler = 0 ) ; +PROVIDE ( FIQ_Handler = 0 ) ; + +PROVIDE ( NMI_Handler = 0 ) ; +PROVIDE ( HardFault_Handler = 0 ) ; +PROVIDE ( MemManage_Handler = 0 ) ; +PROVIDE ( BusFault_Handler = 0 ) ; +PROVIDE ( UsageFault_Handler = 0 ) ; +PROVIDE ( vPortSVCHandler = 0 ) ; +PROVIDE ( DebugMon_Handler = 0 ) ; +PROVIDE ( xPortPendSVHandler = 0 ) ; +PROVIDE ( xPortSysTickHandler = 0 ) ; + +PROVIDE ( WWDG_IRQHandler = 0 ) ; +PROVIDE ( PVD_IRQHandler = 0 ) ; +PROVIDE ( TAMPER_IRQHandler = 0 ) ; +PROVIDE ( RTC_IRQHandler = 0 ) ; +PROVIDE ( FLASH_IRQHandler = 0 ) ; +PROVIDE ( RCC_IRQHandler = 0 ) ; +PROVIDE ( EXTI0_IRQHandler = 0 ) ; +PROVIDE ( EXTI1_IRQHandler = 0 ) ; +PROVIDE ( EXTI2_IRQHandler = 0 ) ; +PROVIDE ( EXTI3_IRQHandler = 0 ) ; +PROVIDE ( EXTI4_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel1_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel2_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel3_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel4_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel5_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel6_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel7_IRQHandler = 0 ) ; +PROVIDE ( ADC_IRQHandler = 0 ) ; +PROVIDE ( USB_HP_CAN1_TX_IRQHandler = 0 ) ; +PROVIDE ( USB_LP_CAN1_RX0_IRQHandler = 0 ) ; +PROVIDE ( CAN1_RX1_IRQHandler = 0 ) ; +PROVIDE ( CAN1_SCE_IRQHandler = 0 ) ; +PROVIDE ( EXTI9_5_IRQHandler = 0 ) ; +PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ; +PROVIDE ( TIM1_UP_IRQHandler = 0 ) ; +PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ; +PROVIDE ( TIM1_CC_IRQHandler = 0 ) ; +PROVIDE ( TIM2_IRQHandler = 0 ) ; +PROVIDE ( TIM3_IRQHandler = 0 ) ; +PROVIDE ( TIM4_IRQHandler = 0 ) ; +PROVIDE ( I2C1_EV_IRQHandler = 0 ) ; +PROVIDE ( I2C1_ER_IRQHandler = 0 ) ; +PROVIDE ( I2C2_EV_IRQHandler = 0 ) ; +PROVIDE ( I2C2_ER_IRQHandler = 0 ) ; +PROVIDE ( SPI1_IRQHandler = 0 ) ; +PROVIDE ( SPI2_IRQHandler = 0 ) ; +PROVIDE ( USART1_IRQHandler = 0 ) ; +PROVIDE ( USART2_IRQHandler = 0 ) ; +PROVIDE ( USART3_IRQHandler = 0 ) ; +PROVIDE ( EXTI15_10_IRQHandler = 0 ) ; +PROVIDE ( RTCAlarm_IRQHandler = 0 ) ; +PROVIDE ( USBWakeUp_IRQHandler = 0 ) ; +PROVIDE ( TIM8_BRK_IRQHandler = 0 ) ; +PROVIDE ( TIM8_UP_IRQHandler = 0 ) ; +PROVIDE ( TIM8_TRG_COM_IRQHandler = 0 ) ; +PROVIDE ( TIM8_CC_IRQHandler = 0 ) ; +PROVIDE ( ADC3_IRQHandler = 0 ) ; +PROVIDE ( FSMC_IRQHandler = 0 ) ; +PROVIDE ( SDIO_IRQHandler = 0 ) ; +PROVIDE ( TIM5_IRQHandler = 0 ) ; +PROVIDE ( SPI3_IRQHandler = 0 ) ; +PROVIDE ( UART4_IRQHandler = 0 ) ; +PROVIDE ( UART5_IRQHandler = 0 ) ; +PROVIDE ( TIM6_IRQHandler = 0 ) ; +PROVIDE ( TIM7_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel1_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel2_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel3_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel4_5_IRQHandler = 0 ) ; + + + +/******************************************************************************/ +/* Peripheral memory map */ +/******************************************************************************/ +/*this allows to compile the ST lib in "non-debug" mode*/ + + +/* Peripheral and SRAM base address in the alias region */ +PERIPH_BB_BASE = 0x42000000; +SRAM_BB_BASE = 0x22000000; + +/* Peripheral and SRAM base address in the bit-band region */ +SRAM_BASE = 0x20000000; +PERIPH_BASE = 0x40000000; + +/* Flash registers base address */ +PROVIDE ( FLASH_BASE = 0x40022000); +/* Flash Option Bytes base address */ +PROVIDE ( OB_BASE = 0x1FFFF800); + +/* Peripheral memory map */ +APB1PERIPH_BASE = PERIPH_BASE ; +APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ; +AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ; + +PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ; +PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ; +PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ; +PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ; +PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ; +PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ; +PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ; +PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ; +PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ; +PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ; +PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ; +PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ; +PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ; +PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ; + +PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ; +PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ; +PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ; +PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ; +PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ; +PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ; +PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ; +PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ; +PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ; +PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ; +PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ; +PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ; + +PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ; +PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ; +PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ; +PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ; +PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ; +PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ; +PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ; +PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ; +PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ; + +/* System Control Space memory map */ +SCS_BASE = 0xE000E000; + +PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ; +PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ; +PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ; + + +/* Sections Definitions */ + +SECTIONS +{ + /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */ + .isr_vector : + { + PROVIDE (pios_isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } > BL_FLASH + + /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */ + .flashtext : + { + . = ALIGN(4); + *(.flashtext) /* Startup code */ + . = ALIGN(4); + } > BL_FLASH + + /* the program code is stored in the .text section, which goes to Flash */ + .text : + { + . = ALIGN(4); + + *(.text) /* remaining code */ + *(.text.*) /* remaining code */ + *(.rodata) /* read-only data (constants) */ + *(.rodata*) + *(.glue_7) + *(.glue_7t) + + . = ALIGN(4); + _etext = .; + /* This is used by the startup in order to initialize the .data secion */ + _sidata = _etext; + } > BL_FLASH + + + /* + * This stack is used both as the initial sp during early init as well as ultimately + * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that + * is used for _all_ interrupt handlers. The end of this stack should be placed + * against the lowest address in RAM so that a stack overrun results in a hard fault + * at the first access beyond the end of the stack. + */ + .irq_stack : + { + . = ALIGN(4); + _irq_stack_end = . ; + . = . + _irq_stack_size ; + . = ALIGN(4); + _irq_stack_top = . - 4 ; + _init_stack_top = _irq_stack_top; + . = ALIGN(4); + } >RAM + + + /* This is the initialized data section + The program executes knowing that the data is in the RAM + but the loader puts the initial values in the FLASH (inidata). + It is one task of the startup to copy the initial values from FLASH to RAM. */ + .data : AT ( _sidata ) + { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .data secion */ + _sdata = . ; + + *(.data) + *(.data.*) + . = ALIGN(4); + /* This is used by the startup in order to initialize the .data secion */ + _edata = . ; + } >RAM + + + + /* This is the uninitialized data section */ + .bss : + { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; + + *(.bss) + *(COMMON) + + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _ebss = . ; + } >RAM + + PROVIDE ( end = _ebss ); + PROVIDE ( _end = _ebss ); + + /* this is the FLASH Bank1 */ + /* the C or assembly source must explicitly place the code or data there + using the "section" attribute */ + .b1text : + { + *(.b1text) /* remaining code */ + *(.b1rodata) /* read-only data (constants) */ + *(.b1rodata*) + } >FLASHB1 + + /* this is the EXTMEM */ + /* the C or assembly source must explicitly place the code or data there + using the "section" attribute */ + + /* EXTMEM Bank0 */ + .eb0text : + { + *(.eb0text) /* remaining code */ + *(.eb0rodata) /* read-only data (constants) */ + *(.eb0rodata*) + } >EXTMEMB0 + + /* EXTMEM Bank1 */ + .eb1text : + { + *(.eb1text) /* remaining code */ + *(.eb1rodata) /* read-only data (constants) */ + *(.eb1rodata*) + } >EXTMEMB1 + + /* EXTMEM Bank2 */ + .eb2text : + { + *(.eb2text) /* remaining code */ + *(.eb2rodata) /* read-only data (constants) */ + *(.eb2rodata*) + } >EXTMEMB2 + + /* EXTMEM Bank0 */ + .eb3text : + { + *(.eb3text) /* remaining code */ + *(.eb3rodata) /* read-only data (constants) */ + *(.eb3rodata*) + } >EXTMEMB3 + + __exidx_start = .; + __exidx_end = .; + + .boardinfo : + { + . = ALIGN(4); + KEEP(*(.boardinfo)) + . = ALIGN(4); + } > BD_INFO + + /* after that it's only debugging information. */ + + /* remove the debugging information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} diff --git a/flight/PiOS/STM32F10x/link_STM3210E_OP_memory.ld b/flight/PiOS/STM32F10x/link_STM3210E_OP_memory.ld index ce70e2e5c..3aa69dc5e 100644 --- a/flight/PiOS/STM32F10x/link_STM3210E_OP_memory.ld +++ b/flight/PiOS/STM32F10x/link_STM3210E_OP_memory.ld @@ -1,12 +1,12 @@ -MEMORY -{ - RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 0x10000 - BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x05000 - 0x00080 - BD_INFO (r) : ORIGIN = 0x08005000 - 0x80, LENGTH = 0x00080 - FLASH (rx) : ORIGIN = 0x08005000, LENGTH = 0x80000 - 0x05000 - FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0 -} +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 0x10000 + BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x05000 - 0x00080 + BD_INFO (r) : ORIGIN = 0x08005000 - 0x80, LENGTH = 0x00080 + FLASH (rx) : ORIGIN = 0x08005000, LENGTH = 0x80000 - 0x05000 + FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0 + EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0 + EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0 + EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0 + EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0 +} diff --git a/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld index d3b33f955..a71ed73c8 100644 --- a/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld @@ -1,383 +1,383 @@ -/* This is the size of the stack for early init and for all FreeRTOS IRQs */ -_irq_stack_size = 0x800; -/* This is the size of the stack for early init: life span is until scheduler starts */ -_init_stack_size = 0x800; - -/* Check valid alignment for VTOR */ -ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region flash not aligned for startup vector table"); - -/* -this sends all unreferenced IRQHandlers to reset -*/ - - -PROVIDE ( Undefined_Handler = 0 ) ; -PROVIDE ( SWI_Handler = 0 ) ; -PROVIDE ( IRQ_Handler = 0 ) ; -PROVIDE ( Prefetch_Handler = 0 ) ; -PROVIDE ( Abort_Handler = 0 ) ; -PROVIDE ( FIQ_Handler = 0 ) ; - -PROVIDE ( NMI_Handler = 0 ) ; -PROVIDE ( HardFault_Handler = 0 ) ; -PROVIDE ( MemManage_Handler = 0 ) ; -PROVIDE ( BusFault_Handler = 0 ) ; -PROVIDE ( UsageFault_Handler = 0 ) ; -PROVIDE ( vPortSVCHandler = 0 ) ; -PROVIDE ( DebugMon_Handler = 0 ) ; -PROVIDE ( xPortPendSVHandler = 0 ) ; -PROVIDE ( xPortSysTickHandler = 0 ) ; - -PROVIDE ( WWDG_IRQHandler = 0 ) ; -PROVIDE ( PVD_IRQHandler = 0 ) ; -PROVIDE ( TAMPER_IRQHandler = 0 ) ; -PROVIDE ( RTC_IRQHandler = 0 ) ; -PROVIDE ( FLASH_IRQHandler = 0 ) ; -PROVIDE ( RCC_IRQHandler = 0 ) ; -PROVIDE ( EXTI0_IRQHandler = 0 ) ; -PROVIDE ( EXTI1_IRQHandler = 0 ) ; -PROVIDE ( EXTI2_IRQHandler = 0 ) ; -PROVIDE ( EXTI3_IRQHandler = 0 ) ; -PROVIDE ( EXTI4_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel1_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel2_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel3_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel4_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel5_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel6_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel7_IRQHandler = 0 ) ; -PROVIDE ( ADC_IRQHandler = 0 ) ; -PROVIDE ( USB_HP_CAN1_TX_IRQHandler = 0 ) ; -PROVIDE ( USB_LP_CAN1_RX0_IRQHandler = 0 ) ; -PROVIDE ( CAN1_RX1_IRQHandler = 0 ) ; -PROVIDE ( CAN1_SCE_IRQHandler = 0 ) ; -PROVIDE ( EXTI9_5_IRQHandler = 0 ) ; -PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ; -PROVIDE ( TIM1_UP_IRQHandler = 0 ) ; -PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ; -PROVIDE ( TIM1_CC_IRQHandler = 0 ) ; -PROVIDE ( TIM2_IRQHandler = 0 ) ; -PROVIDE ( TIM3_IRQHandler = 0 ) ; -PROVIDE ( TIM4_IRQHandler = 0 ) ; -PROVIDE ( I2C1_EV_IRQHandler = 0 ) ; -PROVIDE ( I2C1_ER_IRQHandler = 0 ) ; -PROVIDE ( I2C2_EV_IRQHandler = 0 ) ; -PROVIDE ( I2C2_ER_IRQHandler = 0 ) ; -PROVIDE ( SPI1_IRQHandler = 0 ) ; -PROVIDE ( SPI2_IRQHandler = 0 ) ; -PROVIDE ( USART1_IRQHandler = 0 ) ; -PROVIDE ( USART2_IRQHandler = 0 ) ; -PROVIDE ( USART3_IRQHandler = 0 ) ; -PROVIDE ( EXTI15_10_IRQHandler = 0 ) ; -PROVIDE ( RTCAlarm_IRQHandler = 0 ) ; -PROVIDE ( USBWakeUp_IRQHandler = 0 ) ; -PROVIDE ( TIM8_BRK_IRQHandler = 0 ) ; -PROVIDE ( TIM8_UP_IRQHandler = 0 ) ; -PROVIDE ( TIM8_TRG_COM_IRQHandler = 0 ) ; -PROVIDE ( TIM8_CC_IRQHandler = 0 ) ; -PROVIDE ( ADC3_IRQHandler = 0 ) ; -PROVIDE ( FSMC_IRQHandler = 0 ) ; -PROVIDE ( SDIO_IRQHandler = 0 ) ; -PROVIDE ( TIM5_IRQHandler = 0 ) ; -PROVIDE ( SPI3_IRQHandler = 0 ) ; -PROVIDE ( UART4_IRQHandler = 0 ) ; -PROVIDE ( UART5_IRQHandler = 0 ) ; -PROVIDE ( TIM6_IRQHandler = 0 ) ; -PROVIDE ( TIM7_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel1_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel2_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel3_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel4_5_IRQHandler = 0 ) ; - - - -/******************************************************************************/ -/* Peripheral memory map */ -/******************************************************************************/ -/*this allows to compile the ST lib in "non-debug" mode*/ - - -/* Peripheral and SRAM base address in the alias region */ -PERIPH_BB_BASE = 0x42000000; -SRAM_BB_BASE = 0x22000000; - -/* Peripheral and SRAM base address in the bit-band region */ -SRAM_BASE = 0x20000000; -PERIPH_BASE = 0x40000000; - -/* Flash registers base address */ -PROVIDE ( FLASH_BASE = 0x40022000); -/* Flash Option Bytes base address */ -PROVIDE ( OB_BASE = 0x1FFFF800); - -/* Peripheral memory map */ -APB1PERIPH_BASE = PERIPH_BASE ; -APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ; -AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ; - -PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ; -PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ; -PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ; -PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ; -PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ; -PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ; -PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ; -PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ; -PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ; -PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ; -PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ; -PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ; -PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ; -PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ; - -PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ; -PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ; -PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ; -PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ; -PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ; -PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ; -PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ; -PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ; -PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ; -PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ; -PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ; -PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ; - -PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ; -PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ; -PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ; -PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ; -PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ; -PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ; -PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ; -PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ; -PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ; - -/* System Control Space memory map */ -SCS_BASE = 0xE000E000; - -PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ; -PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ; -PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ; - -PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO)); - -/* Sections Definitions */ - -SECTIONS -{ - /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */ - .isr_vector : - { - PROVIDE (pios_isr_vector_table_base = .); - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */ - .flashtext : - { - . = ALIGN(4); - *(.flashtext) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* module sections */ - .initcallmodule.init : - { - . = ALIGN(4); - __module_initcall_start = .; - KEEP(*(.initcallmodule.init)) - . = ALIGN(4); - __module_initcall_end = .; - } >FLASH - - /* the program code is stored in the .text section, which goes to Flash */ - .text : - { - . = ALIGN(4); - - *(.text) /* remaining code */ - *(.text.*) /* remaining code */ - *(.rodata) /* read-only data (constants) */ - *(.rodata*) - *(.glue_7) - *(.glue_7t) - - . = ALIGN(4); - _etext = .; - /* This is used by the startup in order to initialize the .data secion */ - _sidata = _etext; - } >FLASH - - /* - * This stack is used both as the initial sp during early init as well as ultimately - * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that - * is used for _all_ interrupt handlers. The end of this stack should be placed - * against the lowest address in RAM so that a stack overrun results in a hard fault - * at the first access beyond the end of the stack. - */ - .irq_stack : - { - . = ALIGN(4); - _irq_stack_end = . ; - . = . + _irq_stack_size ; - . = ALIGN(4); - _irq_stack_top = . - 4 ; - . = ALIGN(4); - } >RAM - - - /* This is the initialized data section - The program executes knowing that the data is in the RAM - but the loader puts the initial values in the FLASH (inidata). - It is one task of the startup to copy the initial values from FLASH to RAM. */ - .data : AT ( _sidata ) - { - . = ALIGN(4); - /* This is used by the startup in order to initialize the .data secion */ - _sdata = . ; - - *(.data) - *(.data.*) - . = ALIGN(4); - /* This is used by the startup in order to initialize the .data secion */ - _edata = . ; - } >RAM - - - - /* This is the uninitialized data section */ - .bss : - { - . = ALIGN(4); - /* This is used by the startup in order to initialize the .bss section */ - _sbss = .; - - *(.bss) - *(COMMON) - } >RAM - - .heap (NOLOAD) : - { - . = ALIGN(4); - _sheap = . ; - _sheap_pre_rtos = . ; - *(.heap) - . = ALIGN(4); - _eheap = . ; - _eheap_pre_rtos = . ; - _init_stack_end = . ; - _sheap_post_rtos = . ; - . = . + _init_stack_size ; - . = ALIGN(4); - _eheap_post_rtos = . ; - _init_stack_top = . - 4 ; - } > RAM - - _eram = ORIGIN(RAM) + LENGTH(RAM) ; - _ebss = _eram ; - - /* keep the heap section at the end of the SRAM - * this will allow to claim the remaining bytes not used - * at run time! (done by the reset vector). - */ - - PROVIDE ( end = _ebss ); - PROVIDE ( _end = _ebss ); - - /* this is the FLASH Bank1 */ - /* the C or assembly source must explicitly place the code or data there - using the "section" attribute */ - .b1text : - { - *(.b1text) /* remaining code */ - *(.b1rodata) /* read-only data (constants) */ - *(.b1rodata*) - } >FLASHB1 - - /* this is the EXTMEM */ - /* the C or assembly source must explicitly place the code or data there - using the "section" attribute */ - - /* EXTMEM Bank0 */ - .eb0text : - { - *(.eb0text) /* remaining code */ - *(.eb0rodata) /* read-only data (constants) */ - *(.eb0rodata*) - } >EXTMEMB0 - - /* EXTMEM Bank1 */ - .eb1text : - { - *(.eb1text) /* remaining code */ - *(.eb1rodata) /* read-only data (constants) */ - *(.eb1rodata*) - } >EXTMEMB1 - - /* EXTMEM Bank2 */ - .eb2text : - { - *(.eb2text) /* remaining code */ - *(.eb2rodata) /* read-only data (constants) */ - *(.eb2rodata*) - } >EXTMEMB2 - - /* EXTMEM Bank0 */ - .eb3text : - { - *(.eb3text) /* remaining code */ - *(.eb3rodata) /* read-only data (constants) */ - *(.eb3rodata*) - } >EXTMEMB3 - - __exidx_start = .; - __exidx_end = .; - - /* after that it's only debugging information. */ - - /* remove the debugging information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } -} - - +/* This is the size of the stack for early init and for all FreeRTOS IRQs */ +_irq_stack_size = 0x800; +/* This is the size of the stack for early init: life span is until scheduler starts */ +_init_stack_size = 0x800; + +/* Check valid alignment for VTOR */ +ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region flash not aligned for startup vector table"); + +/* +this sends all unreferenced IRQHandlers to reset +*/ + + +PROVIDE ( Undefined_Handler = 0 ) ; +PROVIDE ( SWI_Handler = 0 ) ; +PROVIDE ( IRQ_Handler = 0 ) ; +PROVIDE ( Prefetch_Handler = 0 ) ; +PROVIDE ( Abort_Handler = 0 ) ; +PROVIDE ( FIQ_Handler = 0 ) ; + +PROVIDE ( NMI_Handler = 0 ) ; +PROVIDE ( HardFault_Handler = 0 ) ; +PROVIDE ( MemManage_Handler = 0 ) ; +PROVIDE ( BusFault_Handler = 0 ) ; +PROVIDE ( UsageFault_Handler = 0 ) ; +PROVIDE ( vPortSVCHandler = 0 ) ; +PROVIDE ( DebugMon_Handler = 0 ) ; +PROVIDE ( xPortPendSVHandler = 0 ) ; +PROVIDE ( xPortSysTickHandler = 0 ) ; + +PROVIDE ( WWDG_IRQHandler = 0 ) ; +PROVIDE ( PVD_IRQHandler = 0 ) ; +PROVIDE ( TAMPER_IRQHandler = 0 ) ; +PROVIDE ( RTC_IRQHandler = 0 ) ; +PROVIDE ( FLASH_IRQHandler = 0 ) ; +PROVIDE ( RCC_IRQHandler = 0 ) ; +PROVIDE ( EXTI0_IRQHandler = 0 ) ; +PROVIDE ( EXTI1_IRQHandler = 0 ) ; +PROVIDE ( EXTI2_IRQHandler = 0 ) ; +PROVIDE ( EXTI3_IRQHandler = 0 ) ; +PROVIDE ( EXTI4_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel1_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel2_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel3_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel4_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel5_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel6_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel7_IRQHandler = 0 ) ; +PROVIDE ( ADC_IRQHandler = 0 ) ; +PROVIDE ( USB_HP_CAN1_TX_IRQHandler = 0 ) ; +PROVIDE ( USB_LP_CAN1_RX0_IRQHandler = 0 ) ; +PROVIDE ( CAN1_RX1_IRQHandler = 0 ) ; +PROVIDE ( CAN1_SCE_IRQHandler = 0 ) ; +PROVIDE ( EXTI9_5_IRQHandler = 0 ) ; +PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ; +PROVIDE ( TIM1_UP_IRQHandler = 0 ) ; +PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ; +PROVIDE ( TIM1_CC_IRQHandler = 0 ) ; +PROVIDE ( TIM2_IRQHandler = 0 ) ; +PROVIDE ( TIM3_IRQHandler = 0 ) ; +PROVIDE ( TIM4_IRQHandler = 0 ) ; +PROVIDE ( I2C1_EV_IRQHandler = 0 ) ; +PROVIDE ( I2C1_ER_IRQHandler = 0 ) ; +PROVIDE ( I2C2_EV_IRQHandler = 0 ) ; +PROVIDE ( I2C2_ER_IRQHandler = 0 ) ; +PROVIDE ( SPI1_IRQHandler = 0 ) ; +PROVIDE ( SPI2_IRQHandler = 0 ) ; +PROVIDE ( USART1_IRQHandler = 0 ) ; +PROVIDE ( USART2_IRQHandler = 0 ) ; +PROVIDE ( USART3_IRQHandler = 0 ) ; +PROVIDE ( EXTI15_10_IRQHandler = 0 ) ; +PROVIDE ( RTCAlarm_IRQHandler = 0 ) ; +PROVIDE ( USBWakeUp_IRQHandler = 0 ) ; +PROVIDE ( TIM8_BRK_IRQHandler = 0 ) ; +PROVIDE ( TIM8_UP_IRQHandler = 0 ) ; +PROVIDE ( TIM8_TRG_COM_IRQHandler = 0 ) ; +PROVIDE ( TIM8_CC_IRQHandler = 0 ) ; +PROVIDE ( ADC3_IRQHandler = 0 ) ; +PROVIDE ( FSMC_IRQHandler = 0 ) ; +PROVIDE ( SDIO_IRQHandler = 0 ) ; +PROVIDE ( TIM5_IRQHandler = 0 ) ; +PROVIDE ( SPI3_IRQHandler = 0 ) ; +PROVIDE ( UART4_IRQHandler = 0 ) ; +PROVIDE ( UART5_IRQHandler = 0 ) ; +PROVIDE ( TIM6_IRQHandler = 0 ) ; +PROVIDE ( TIM7_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel1_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel2_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel3_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel4_5_IRQHandler = 0 ) ; + + + +/******************************************************************************/ +/* Peripheral memory map */ +/******************************************************************************/ +/*this allows to compile the ST lib in "non-debug" mode*/ + + +/* Peripheral and SRAM base address in the alias region */ +PERIPH_BB_BASE = 0x42000000; +SRAM_BB_BASE = 0x22000000; + +/* Peripheral and SRAM base address in the bit-band region */ +SRAM_BASE = 0x20000000; +PERIPH_BASE = 0x40000000; + +/* Flash registers base address */ +PROVIDE ( FLASH_BASE = 0x40022000); +/* Flash Option Bytes base address */ +PROVIDE ( OB_BASE = 0x1FFFF800); + +/* Peripheral memory map */ +APB1PERIPH_BASE = PERIPH_BASE ; +APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ; +AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ; + +PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ; +PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ; +PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ; +PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ; +PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ; +PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ; +PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ; +PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ; +PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ; +PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ; +PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ; +PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ; +PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ; +PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ; + +PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ; +PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ; +PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ; +PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ; +PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ; +PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ; +PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ; +PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ; +PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ; +PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ; +PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ; +PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ; + +PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ; +PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ; +PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ; +PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ; +PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ; +PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ; +PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ; +PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ; +PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ; + +/* System Control Space memory map */ +SCS_BASE = 0xE000E000; + +PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ; +PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ; +PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ; + +PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO)); + +/* Sections Definitions */ + +SECTIONS +{ + /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */ + .isr_vector : + { + PROVIDE (pios_isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */ + .flashtext : + { + . = ALIGN(4); + *(.flashtext) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* module sections */ + .initcallmodule.init : + { + . = ALIGN(4); + __module_initcall_start = .; + KEEP(*(.initcallmodule.init)) + . = ALIGN(4); + __module_initcall_end = .; + } >FLASH + + /* the program code is stored in the .text section, which goes to Flash */ + .text : + { + . = ALIGN(4); + + *(.text) /* remaining code */ + *(.text.*) /* remaining code */ + *(.rodata) /* read-only data (constants) */ + *(.rodata*) + *(.glue_7) + *(.glue_7t) + + . = ALIGN(4); + _etext = .; + /* This is used by the startup in order to initialize the .data secion */ + _sidata = _etext; + } >FLASH + + /* + * This stack is used both as the initial sp during early init as well as ultimately + * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that + * is used for _all_ interrupt handlers. The end of this stack should be placed + * against the lowest address in RAM so that a stack overrun results in a hard fault + * at the first access beyond the end of the stack. + */ + .irq_stack : + { + . = ALIGN(4); + _irq_stack_end = . ; + . = . + _irq_stack_size ; + . = ALIGN(4); + _irq_stack_top = . - 4 ; + . = ALIGN(4); + } >RAM + + + /* This is the initialized data section + The program executes knowing that the data is in the RAM + but the loader puts the initial values in the FLASH (inidata). + It is one task of the startup to copy the initial values from FLASH to RAM. */ + .data : AT ( _sidata ) + { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .data secion */ + _sdata = . ; + + *(.data) + *(.data.*) + . = ALIGN(4); + /* This is used by the startup in order to initialize the .data secion */ + _edata = . ; + } >RAM + + + + /* This is the uninitialized data section */ + .bss : + { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; + + *(.bss) + *(COMMON) + } >RAM + + .heap (NOLOAD) : + { + . = ALIGN(4); + _sheap = . ; + _sheap_pre_rtos = . ; + *(.heap) + . = ALIGN(4); + _eheap = . ; + _eheap_pre_rtos = . ; + _init_stack_end = . ; + _sheap_post_rtos = . ; + . = . + _init_stack_size ; + . = ALIGN(4); + _eheap_post_rtos = . ; + _init_stack_top = . - 4 ; + } > RAM + + _eram = ORIGIN(RAM) + LENGTH(RAM) ; + _ebss = _eram ; + + /* keep the heap section at the end of the SRAM + * this will allow to claim the remaining bytes not used + * at run time! (done by the reset vector). + */ + + PROVIDE ( end = _ebss ); + PROVIDE ( _end = _ebss ); + + /* this is the FLASH Bank1 */ + /* the C or assembly source must explicitly place the code or data there + using the "section" attribute */ + .b1text : + { + *(.b1text) /* remaining code */ + *(.b1rodata) /* read-only data (constants) */ + *(.b1rodata*) + } >FLASHB1 + + /* this is the EXTMEM */ + /* the C or assembly source must explicitly place the code or data there + using the "section" attribute */ + + /* EXTMEM Bank0 */ + .eb0text : + { + *(.eb0text) /* remaining code */ + *(.eb0rodata) /* read-only data (constants) */ + *(.eb0rodata*) + } >EXTMEMB0 + + /* EXTMEM Bank1 */ + .eb1text : + { + *(.eb1text) /* remaining code */ + *(.eb1rodata) /* read-only data (constants) */ + *(.eb1rodata*) + } >EXTMEMB1 + + /* EXTMEM Bank2 */ + .eb2text : + { + *(.eb2text) /* remaining code */ + *(.eb2rodata) /* read-only data (constants) */ + *(.eb2rodata*) + } >EXTMEMB2 + + /* EXTMEM Bank0 */ + .eb3text : + { + *(.eb3text) /* remaining code */ + *(.eb3rodata) /* read-only data (constants) */ + *(.eb3rodata*) + } >EXTMEMB3 + + __exidx_start = .; + __exidx_end = .; + + /* after that it's only debugging information. */ + + /* remove the debugging information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} + + diff --git a/flight/PiOS/STM32F10x/link_stm32f10x_HD.ld b/flight/PiOS/STM32F10x/link_stm32f10x_HD.ld index 6b6ba6ef0..3c960e455 100644 --- a/flight/PiOS/STM32F10x/link_stm32f10x_HD.ld +++ b/flight/PiOS/STM32F10x/link_stm32f10x_HD.ld @@ -1,411 +1,411 @@ -/** - ****************************************************************************** - * - * @file link_stm32f10x_HD.ld - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2009. - * @brief PiOS linker for the OpenPilot board - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Memory Spaces Definitions */ -MEMORY -{ - RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K - FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0 - EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0 -} - -/* higher address of the user mode stack */ -_estack = 0x20010000; - -/* default stack sizes. - -These are used by the startup in order to allocate stacks for the different modes. - -Note: FreeRTOS gives each task an own stack -*/ - -__Stack_Size = 128 ; - -PROVIDE ( _Stack_Size = __Stack_Size ) ; - -__Stack_Init = _estack - __Stack_Size ; - -/*"PROVIDE" allows to easily override these values from an object file or the commmand line.*/ -PROVIDE ( _Stack_Init = __Stack_Init ) ; - -/* -There will be a link error if there is not this amount of RAM free at the end. -*/ -_Minimum_Stack_Size = 0x100 ; - -/* Check valid alignment for VTOR */ -ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region flash not aligned for startup vector table"); - - -/* -this sends all unreferenced IRQHandlers to reset -*/ - - -PROVIDE ( Undefined_Handler = 0 ) ; -PROVIDE ( SWI_Handler = 0 ) ; -PROVIDE ( IRQ_Handler = 0 ) ; -PROVIDE ( Prefetch_Handler = 0 ) ; -PROVIDE ( Abort_Handler = 0 ) ; -PROVIDE ( FIQ_Handler = 0 ) ; - -PROVIDE ( NMI_Handler = 0 ) ; -PROVIDE ( HardFault_Handler = 0 ) ; -PROVIDE ( MemManage_Handler = 0 ) ; -PROVIDE ( BusFault_Handler = 0 ) ; -PROVIDE ( UsageFault_Handler = 0 ) ; -PROVIDE ( SVC_Handler = 0 ) ; -PROVIDE ( DebugMon_Handler = 0 ) ; -PROVIDE ( PendSV_Handler = 0 ) ; -PROVIDE ( SysTick_Handler = 0 ) ; - -PROVIDE ( WWDG_IRQHandler = 0 ) ; -PROVIDE ( PVD_IRQHandler = 0 ) ; -PROVIDE ( TAMPER_IRQHandler = 0 ) ; -PROVIDE ( RTC_IRQHandler = 0 ) ; -PROVIDE ( FLASH_IRQHandler = 0 ) ; -PROVIDE ( RCC_IRQHandler = 0 ) ; -PROVIDE ( EXTI0_IRQHandler = 0 ) ; -PROVIDE ( EXTI1_IRQHandler = 0 ) ; -PROVIDE ( EXTI2_IRQHandler = 0 ) ; -PROVIDE ( EXTI3_IRQHandler = 0 ) ; -PROVIDE ( EXTI4_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel1_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel2_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel3_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel4_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel5_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel6_IRQHandler = 0 ) ; -PROVIDE ( DMAChannel7_IRQHandler = 0 ) ; -PROVIDE ( ADC_IRQHandler = 0 ) ; -PROVIDE ( USB_HP_CAN1_TX_IRQHandler = 0 ) ; -PROVIDE ( USB_LP_CAN1_RX0_IRQHandler = 0 ) ; -PROVIDE ( CAN1_RX1_IRQHandler = 0 ) ; -PROVIDE ( CAN1_SCE_IRQHandler = 0 ) ; -PROVIDE ( EXTI9_5_IRQHandler = 0 ) ; -PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ; -PROVIDE ( TIM1_UP_IRQHandler = 0 ) ; -PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ; -PROVIDE ( TIM1_CC_IRQHandler = 0 ) ; -PROVIDE ( TIM2_IRQHandler = 0 ) ; -PROVIDE ( TIM3_IRQHandler = 0 ) ; -PROVIDE ( TIM4_IRQHandler = 0 ) ; -PROVIDE ( I2C1_EV_IRQHandler = 0 ) ; -PROVIDE ( I2C1_ER_IRQHandler = 0 ) ; -PROVIDE ( I2C2_EV_IRQHandler = 0 ) ; -PROVIDE ( I2C2_ER_IRQHandler = 0 ) ; -PROVIDE ( SPI1_IRQHandler = 0 ) ; -PROVIDE ( SPI2_IRQHandler = 0 ) ; -PROVIDE ( USART1_IRQHandler = 0 ) ; -PROVIDE ( USART2_IRQHandler = 0 ) ; -PROVIDE ( USART3_IRQHandler = 0 ) ; -PROVIDE ( EXTI15_10_IRQHandler = 0 ) ; -PROVIDE ( RTCAlarm_IRQHandler = 0 ) ; -PROVIDE ( USBWakeUp_IRQHandler = 0 ) ; -PROVIDE ( TIM8_BRK_IRQHandler = 0 ) ; -PROVIDE ( TIM8_UP_IRQHandler = 0 ) ; -PROVIDE ( TIM8_TRG_COM_IRQHandler = 0 ) ; -PROVIDE ( TIM8_CC_IRQHandler = 0 ) ; -PROVIDE ( ADC3_IRQHandler = 0 ) ; -PROVIDE ( FSMC_IRQHandler = 0 ) ; -PROVIDE ( SDIO_IRQHandler = 0 ) ; -PROVIDE ( TIM5_IRQHandler = 0 ) ; -PROVIDE ( SPI3_IRQHandler = 0 ) ; -PROVIDE ( UART4_IRQHandler = 0 ) ; -PROVIDE ( UART5_IRQHandler = 0 ) ; -PROVIDE ( TIM6_IRQHandler = 0 ) ; -PROVIDE ( TIM7_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel1_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel2_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel3_IRQHandler = 0 ) ; -PROVIDE ( DMA2_Channel4_5_IRQHandler = 0 ) ; - - - -/******************************************************************************/ -/* Peripheral memory map */ -/******************************************************************************/ -/*this allows to compile the ST lib in "non-debug" mode*/ - - -/* Peripheral and SRAM base address in the alias region */ -PERIPH_BB_BASE = 0x42000000; -SRAM_BB_BASE = 0x22000000; - -/* Peripheral and SRAM base address in the bit-band region */ -SRAM_BASE = 0x20000000; -PERIPH_BASE = 0x40000000; - -/* Flash registers base address */ -PROVIDE ( FLASH_BASE = 0x40022000); -/* Flash Option Bytes base address */ -PROVIDE ( OB_BASE = 0x1FFFF800); - -/* Peripheral memory map */ -APB1PERIPH_BASE = PERIPH_BASE ; -APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ; -AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ; - -PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ; -PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ; -PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ; -PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ; -PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ; -PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ; -PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ; -PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ; -PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ; -PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ; -PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ; -PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ; -PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ; -PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ; - -PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ; -PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ; -PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ; -PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ; -PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ; -PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ; -PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ; -PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ; -PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ; -PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ; -PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ; -PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ; - -PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ; -PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ; -PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ; -PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ; -PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ; -PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ; -PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ; -PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ; -PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ; - -/* System Control Space memory map */ -SCS_BASE = 0xE000E000; - -PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ; -PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ; -PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ; - - -/* Sections Definitions */ - -SECTIONS -{ - - /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */ - .isr_vector : - { - KEEP(*(.isr_vector)) /* Startup code */ - . = ALIGN(4); - } >FLASH - - /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */ - .flashtext : - { - . = ALIGN(4); - *(.flashtext) /* Startup code */ - . = ALIGN(4); - } >FLASH - - - /* the program code is stored in the .text section, which goes to Flash */ - .text : - { - . = ALIGN(4); - - *(.text) /* remaining code */ - *(.text.*) /* remaining code */ - *(.rodata) /* read-only data (constants) */ - *(.rodata*) - *(.glue_7) - *(.glue_7t) - - . = ALIGN(4); - _etext = .; - /* This is used by the startup in order to initialize the .data secion */ - _sidata = _etext; - } >FLASH - - - - /* This is the initialized data section - The program executes knowing that the data is in the RAM - but the loader puts the initial values in the FLASH (inidata). - It is one task of the startup to copy the initial values from FLASH to RAM. */ - .data : AT ( _sidata ) - { - . = ALIGN(4); - /* This is used by the startup in order to initialize the .data secion */ - _sdata = . ; - - *(.data) - *(.data.*) - . = ALIGN(4); - /* This is used by the startup in order to initialize the .data secion */ - _edata = . ; - } >RAM - - - - /* This is the uninitialized data section */ - .bss : - { - . = ALIGN(4); - /* This is used by the startup in order to initialize the .bss secion */ - _sbss = .; - - *(.bss) - *(COMMON) - - . = ALIGN(4); - /* This is used by the startup in order to initialize the .bss secion */ - _ebss = . ; - } >RAM - - PROVIDE ( end = _ebss ); - PROVIDE ( _end = _ebss ); - - /* This is the user stack section - This is just to check that there is enough RAM left for the User mode stack - It should generate an error if it's full. - */ - ._usrstack : - { - . = ALIGN(4); - _susrstack = . ; - - . = . + _Minimum_Stack_Size ; - - . = ALIGN(4); - _eusrstack = . ; - } >RAM - - - - /* this is the FLASH Bank1 */ - /* the C or assembly source must explicitly place the code or data there - using the "section" attribute */ - .b1text : - { - *(.b1text) /* remaining code */ - *(.b1rodata) /* read-only data (constants) */ - *(.b1rodata*) - } >FLASHB1 - - /* this is the EXTMEM */ - /* the C or assembly source must explicitly place the code or data there - using the "section" attribute */ - - /* EXTMEM Bank0 */ - .eb0text : - { - *(.eb0text) /* remaining code */ - *(.eb0rodata) /* read-only data (constants) */ - *(.eb0rodata*) - } >EXTMEMB0 - - /* EXTMEM Bank1 */ - .eb1text : - { - *(.eb1text) /* remaining code */ - *(.eb1rodata) /* read-only data (constants) */ - *(.eb1rodata*) - } >EXTMEMB1 - - /* EXTMEM Bank2 */ - .eb2text : - { - *(.eb2text) /* remaining code */ - *(.eb2rodata) /* read-only data (constants) */ - *(.eb2rodata*) - } >EXTMEMB2 - - /* EXTMEM Bank0 */ - .eb3text : - { - *(.eb3text) /* remaining code */ - *(.eb3rodata) /* read-only data (constants) */ - *(.eb3rodata*) - } >EXTMEMB3 - - __exidx_start = .; - __exidx_end = .; - - /* after that it's only debugging information. */ - - /* remove the debugging information from the standard libraries */ - /DISCARD/ : - { - libc.a ( * ) - libm.a ( * ) - libgcc.a ( * ) - } - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } -} - - +/** + ****************************************************************************** + * + * @file link_stm32f10x_HD.ld + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2009. + * @brief PiOS linker for the OpenPilot board + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Memory Spaces Definitions */ +MEMORY +{ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K + FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0 + EXTMEMB0 (rx) : ORIGIN = 0x00000000, LENGTH = 0 + EXTMEMB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0 + EXTMEMB2 (rx) : ORIGIN = 0x00000000, LENGTH = 0 + EXTMEMB3 (rx) : ORIGIN = 0x00000000, LENGTH = 0 +} + +/* higher address of the user mode stack */ +_estack = 0x20010000; + +/* default stack sizes. + +These are used by the startup in order to allocate stacks for the different modes. + +Note: FreeRTOS gives each task an own stack +*/ + +__Stack_Size = 128 ; + +PROVIDE ( _Stack_Size = __Stack_Size ) ; + +__Stack_Init = _estack - __Stack_Size ; + +/*"PROVIDE" allows to easily override these values from an object file or the commmand line.*/ +PROVIDE ( _Stack_Init = __Stack_Init ) ; + +/* +There will be a link error if there is not this amount of RAM free at the end. +*/ +_Minimum_Stack_Size = 0x100 ; + +/* Check valid alignment for VTOR */ +ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region flash not aligned for startup vector table"); + + +/* +this sends all unreferenced IRQHandlers to reset +*/ + + +PROVIDE ( Undefined_Handler = 0 ) ; +PROVIDE ( SWI_Handler = 0 ) ; +PROVIDE ( IRQ_Handler = 0 ) ; +PROVIDE ( Prefetch_Handler = 0 ) ; +PROVIDE ( Abort_Handler = 0 ) ; +PROVIDE ( FIQ_Handler = 0 ) ; + +PROVIDE ( NMI_Handler = 0 ) ; +PROVIDE ( HardFault_Handler = 0 ) ; +PROVIDE ( MemManage_Handler = 0 ) ; +PROVIDE ( BusFault_Handler = 0 ) ; +PROVIDE ( UsageFault_Handler = 0 ) ; +PROVIDE ( SVC_Handler = 0 ) ; +PROVIDE ( DebugMon_Handler = 0 ) ; +PROVIDE ( PendSV_Handler = 0 ) ; +PROVIDE ( SysTick_Handler = 0 ) ; + +PROVIDE ( WWDG_IRQHandler = 0 ) ; +PROVIDE ( PVD_IRQHandler = 0 ) ; +PROVIDE ( TAMPER_IRQHandler = 0 ) ; +PROVIDE ( RTC_IRQHandler = 0 ) ; +PROVIDE ( FLASH_IRQHandler = 0 ) ; +PROVIDE ( RCC_IRQHandler = 0 ) ; +PROVIDE ( EXTI0_IRQHandler = 0 ) ; +PROVIDE ( EXTI1_IRQHandler = 0 ) ; +PROVIDE ( EXTI2_IRQHandler = 0 ) ; +PROVIDE ( EXTI3_IRQHandler = 0 ) ; +PROVIDE ( EXTI4_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel1_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel2_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel3_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel4_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel5_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel6_IRQHandler = 0 ) ; +PROVIDE ( DMAChannel7_IRQHandler = 0 ) ; +PROVIDE ( ADC_IRQHandler = 0 ) ; +PROVIDE ( USB_HP_CAN1_TX_IRQHandler = 0 ) ; +PROVIDE ( USB_LP_CAN1_RX0_IRQHandler = 0 ) ; +PROVIDE ( CAN1_RX1_IRQHandler = 0 ) ; +PROVIDE ( CAN1_SCE_IRQHandler = 0 ) ; +PROVIDE ( EXTI9_5_IRQHandler = 0 ) ; +PROVIDE ( TIM1_BRK_IRQHandler = 0 ) ; +PROVIDE ( TIM1_UP_IRQHandler = 0 ) ; +PROVIDE ( TIM1_TRG_COM_IRQHandler = 0 ) ; +PROVIDE ( TIM1_CC_IRQHandler = 0 ) ; +PROVIDE ( TIM2_IRQHandler = 0 ) ; +PROVIDE ( TIM3_IRQHandler = 0 ) ; +PROVIDE ( TIM4_IRQHandler = 0 ) ; +PROVIDE ( I2C1_EV_IRQHandler = 0 ) ; +PROVIDE ( I2C1_ER_IRQHandler = 0 ) ; +PROVIDE ( I2C2_EV_IRQHandler = 0 ) ; +PROVIDE ( I2C2_ER_IRQHandler = 0 ) ; +PROVIDE ( SPI1_IRQHandler = 0 ) ; +PROVIDE ( SPI2_IRQHandler = 0 ) ; +PROVIDE ( USART1_IRQHandler = 0 ) ; +PROVIDE ( USART2_IRQHandler = 0 ) ; +PROVIDE ( USART3_IRQHandler = 0 ) ; +PROVIDE ( EXTI15_10_IRQHandler = 0 ) ; +PROVIDE ( RTCAlarm_IRQHandler = 0 ) ; +PROVIDE ( USBWakeUp_IRQHandler = 0 ) ; +PROVIDE ( TIM8_BRK_IRQHandler = 0 ) ; +PROVIDE ( TIM8_UP_IRQHandler = 0 ) ; +PROVIDE ( TIM8_TRG_COM_IRQHandler = 0 ) ; +PROVIDE ( TIM8_CC_IRQHandler = 0 ) ; +PROVIDE ( ADC3_IRQHandler = 0 ) ; +PROVIDE ( FSMC_IRQHandler = 0 ) ; +PROVIDE ( SDIO_IRQHandler = 0 ) ; +PROVIDE ( TIM5_IRQHandler = 0 ) ; +PROVIDE ( SPI3_IRQHandler = 0 ) ; +PROVIDE ( UART4_IRQHandler = 0 ) ; +PROVIDE ( UART5_IRQHandler = 0 ) ; +PROVIDE ( TIM6_IRQHandler = 0 ) ; +PROVIDE ( TIM7_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel1_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel2_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel3_IRQHandler = 0 ) ; +PROVIDE ( DMA2_Channel4_5_IRQHandler = 0 ) ; + + + +/******************************************************************************/ +/* Peripheral memory map */ +/******************************************************************************/ +/*this allows to compile the ST lib in "non-debug" mode*/ + + +/* Peripheral and SRAM base address in the alias region */ +PERIPH_BB_BASE = 0x42000000; +SRAM_BB_BASE = 0x22000000; + +/* Peripheral and SRAM base address in the bit-band region */ +SRAM_BASE = 0x20000000; +PERIPH_BASE = 0x40000000; + +/* Flash registers base address */ +PROVIDE ( FLASH_BASE = 0x40022000); +/* Flash Option Bytes base address */ +PROVIDE ( OB_BASE = 0x1FFFF800); + +/* Peripheral memory map */ +APB1PERIPH_BASE = PERIPH_BASE ; +APB2PERIPH_BASE = (PERIPH_BASE + 0x10000) ; +AHBPERIPH_BASE = (PERIPH_BASE + 0x20000) ; + +PROVIDE ( TIM2 = (APB1PERIPH_BASE + 0x0000) ) ; +PROVIDE ( TIM3 = (APB1PERIPH_BASE + 0x0400) ) ; +PROVIDE ( TIM4 = (APB1PERIPH_BASE + 0x0800) ) ; +PROVIDE ( RTC = (APB1PERIPH_BASE + 0x2800) ) ; +PROVIDE ( WWDG = (APB1PERIPH_BASE + 0x2C00) ) ; +PROVIDE ( IWDG = (APB1PERIPH_BASE + 0x3000) ) ; +PROVIDE ( SPI2 = (APB1PERIPH_BASE + 0x3800) ) ; +PROVIDE ( USART2 = (APB1PERIPH_BASE + 0x4400) ) ; +PROVIDE ( USART3 = (APB1PERIPH_BASE + 0x4800) ) ; +PROVIDE ( I2C1 = (APB1PERIPH_BASE + 0x5400) ) ; +PROVIDE ( I2C2 = (APB1PERIPH_BASE + 0x5800) ) ; +PROVIDE ( CAN = (APB1PERIPH_BASE + 0x6400) ) ; +PROVIDE ( BKP = (APB1PERIPH_BASE + 0x6C00) ) ; +PROVIDE ( PWR = (APB1PERIPH_BASE + 0x7000) ) ; + +PROVIDE ( AFIO = (APB2PERIPH_BASE + 0x0000) ) ; +PROVIDE ( EXTI = (APB2PERIPH_BASE + 0x0400) ) ; +PROVIDE ( GPIOA = (APB2PERIPH_BASE + 0x0800) ) ; +PROVIDE ( GPIOB = (APB2PERIPH_BASE + 0x0C00) ) ; +PROVIDE ( GPIOC = (APB2PERIPH_BASE + 0x1000) ) ; +PROVIDE ( GPIOD = (APB2PERIPH_BASE + 0x1400) ) ; +PROVIDE ( GPIOE = (APB2PERIPH_BASE + 0x1800) ) ; +PROVIDE ( ADC1 = (APB2PERIPH_BASE + 0x2400) ) ; +PROVIDE ( ADC2 = (APB2PERIPH_BASE + 0x2800) ) ; +PROVIDE ( TIM1 = (APB2PERIPH_BASE + 0x2C00) ) ; +PROVIDE ( SPI1 = (APB2PERIPH_BASE + 0x3000) ) ; +PROVIDE ( USART1 = (APB2PERIPH_BASE + 0x3800) ) ; + +PROVIDE ( DMA = (AHBPERIPH_BASE + 0x0000) ) ; +PROVIDE ( DMA_Channel1 = (AHBPERIPH_BASE + 0x0008) ) ; +PROVIDE ( DMA_Channel2 = (AHBPERIPH_BASE + 0x001C) ) ; +PROVIDE ( DMA_Channel3 = (AHBPERIPH_BASE + 0x0030) ) ; +PROVIDE ( DMA_Channel4 = (AHBPERIPH_BASE + 0x0044) ) ; +PROVIDE ( DMA_Channel5 = (AHBPERIPH_BASE + 0x0058) ) ; +PROVIDE ( DMA_Channel6 = (AHBPERIPH_BASE + 0x006C) ) ; +PROVIDE ( DMA_Channel7 = (AHBPERIPH_BASE + 0x0080) ) ; +PROVIDE ( RCC = (AHBPERIPH_BASE + 0x1000) ) ; + +/* System Control Space memory map */ +SCS_BASE = 0xE000E000; + +PROVIDE ( SysTick = (SCS_BASE + 0x0010) ) ; +PROVIDE ( NVIC = (SCS_BASE + 0x0100) ) ; +PROVIDE ( SCB = (SCS_BASE + 0x0D00) ) ; + + +/* Sections Definitions */ + +SECTIONS +{ + + /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */ + .isr_vector : + { + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */ + .flashtext : + { + . = ALIGN(4); + *(.flashtext) /* Startup code */ + . = ALIGN(4); + } >FLASH + + + /* the program code is stored in the .text section, which goes to Flash */ + .text : + { + . = ALIGN(4); + + *(.text) /* remaining code */ + *(.text.*) /* remaining code */ + *(.rodata) /* read-only data (constants) */ + *(.rodata*) + *(.glue_7) + *(.glue_7t) + + . = ALIGN(4); + _etext = .; + /* This is used by the startup in order to initialize the .data secion */ + _sidata = _etext; + } >FLASH + + + + /* This is the initialized data section + The program executes knowing that the data is in the RAM + but the loader puts the initial values in the FLASH (inidata). + It is one task of the startup to copy the initial values from FLASH to RAM. */ + .data : AT ( _sidata ) + { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .data secion */ + _sdata = . ; + + *(.data) + *(.data.*) + . = ALIGN(4); + /* This is used by the startup in order to initialize the .data secion */ + _edata = . ; + } >RAM + + + + /* This is the uninitialized data section */ + .bss : + { + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; + + *(.bss) + *(COMMON) + + . = ALIGN(4); + /* This is used by the startup in order to initialize the .bss secion */ + _ebss = . ; + } >RAM + + PROVIDE ( end = _ebss ); + PROVIDE ( _end = _ebss ); + + /* This is the user stack section + This is just to check that there is enough RAM left for the User mode stack + It should generate an error if it's full. + */ + ._usrstack : + { + . = ALIGN(4); + _susrstack = . ; + + . = . + _Minimum_Stack_Size ; + + . = ALIGN(4); + _eusrstack = . ; + } >RAM + + + + /* this is the FLASH Bank1 */ + /* the C or assembly source must explicitly place the code or data there + using the "section" attribute */ + .b1text : + { + *(.b1text) /* remaining code */ + *(.b1rodata) /* read-only data (constants) */ + *(.b1rodata*) + } >FLASHB1 + + /* this is the EXTMEM */ + /* the C or assembly source must explicitly place the code or data there + using the "section" attribute */ + + /* EXTMEM Bank0 */ + .eb0text : + { + *(.eb0text) /* remaining code */ + *(.eb0rodata) /* read-only data (constants) */ + *(.eb0rodata*) + } >EXTMEMB0 + + /* EXTMEM Bank1 */ + .eb1text : + { + *(.eb1text) /* remaining code */ + *(.eb1rodata) /* read-only data (constants) */ + *(.eb1rodata*) + } >EXTMEMB1 + + /* EXTMEM Bank2 */ + .eb2text : + { + *(.eb2text) /* remaining code */ + *(.eb2rodata) /* read-only data (constants) */ + *(.eb2rodata*) + } >EXTMEMB2 + + /* EXTMEM Bank0 */ + .eb3text : + { + *(.eb3text) /* remaining code */ + *(.eb3rodata) /* read-only data (constants) */ + *(.eb3rodata*) + } >EXTMEMB3 + + __exidx_start = .; + __exidx_end = .; + + /* after that it's only debugging information. */ + + /* remove the debugging information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} + + diff --git a/flight/PiOS/STM32F10x/link_stm32f10x_MD.ld b/flight/PiOS/STM32F10x/link_stm32f10x_MD.ld index 63f359bcb..93acf10ad 100644 --- a/flight/PiOS/STM32F10x/link_stm32f10x_MD.ld +++ b/flight/PiOS/STM32F10x/link_stm32f10x_MD.ld @@ -1,88 +1,88 @@ -MEMORY -{ - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x00020000 - SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00005000 -} - -_estack = 0x20004FF0; - -/* Section Definitions */ -SECTIONS -{ - .text : - { - KEEP(*(.isr_vector .isr_vector.*)) - *(.text .text.* .gnu.linkonce.t.*) - *(.glue_7t) *(.glue_7) - *(.rodata .rodata* .gnu.linkonce.r.*) - } > FLASH - - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) - } > FLASH - - .ARM.exidx : - { - *(.ARM.exidx* .gnu.linkonce.armexidx.*) - } > FLASH - - . = ALIGN(4); - _etext = .; - _sidata = .; - - .data : AT (_etext) - { - _sdata = .; - *(.data .data.*) - . = ALIGN(4); - _edata = . ; - } > SRAM - - /* .bss section which is used for uninitialized data */ - .bss (NOLOAD) : - { - _sbss = . ; - *(.bss .bss.*) - *(COMMON) - . = ALIGN(4); - _ebss = . ; - } > SRAM - - . = ALIGN(4); - _end = . ; - - /* Stabs debugging sections. */ - .stab 0 : { *(.stab) } - .stabstr 0 : { *(.stabstr) } - .stab.excl 0 : { *(.stab.excl) } - .stab.exclstr 0 : { *(.stab.exclstr) } - .stab.index 0 : { *(.stab.index) } - .stab.indexstr 0 : { *(.stab.indexstr) } - .comment 0 : { *(.comment) } - /* DWARF debug sections. - Symbols in the DWARF debugging sections are relative to the beginning - of the section so we begin them at 0. */ - /* DWARF 1 */ - .debug 0 : { *(.debug) } - .line 0 : { *(.line) } - /* GNU DWARF 1 extensions */ - .debug_srcinfo 0 : { *(.debug_srcinfo) } - .debug_sfnames 0 : { *(.debug_sfnames) } - /* DWARF 1.1 and DWARF 2 */ - .debug_aranges 0 : { *(.debug_aranges) } - .debug_pubnames 0 : { *(.debug_pubnames) } - /* DWARF 2 */ - .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } - .debug_abbrev 0 : { *(.debug_abbrev) } - .debug_line 0 : { *(.debug_line) } - .debug_frame 0 : { *(.debug_frame) } - .debug_str 0 : { *(.debug_str) } - .debug_loc 0 : { *(.debug_loc) } - .debug_macinfo 0 : { *(.debug_macinfo) } - /* SGI/MIPS DWARF 2 extensions */ - .debug_weaknames 0 : { *(.debug_weaknames) } - .debug_funcnames 0 : { *(.debug_funcnames) } - .debug_typenames 0 : { *(.debug_typenames) } - .debug_varnames 0 : { *(.debug_varnames) } +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x00020000 + SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00005000 +} + +_estack = 0x20004FF0; + +/* Section Definitions */ +SECTIONS +{ + .text : + { + KEEP(*(.isr_vector .isr_vector.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + } > FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > FLASH + + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > FLASH + + . = ALIGN(4); + _etext = .; + _sidata = .; + + .data : AT (_etext) + { + _sdata = .; + *(.data .data.*) + . = ALIGN(4); + _edata = . ; + } > SRAM + + /* .bss section which is used for uninitialized data */ + .bss (NOLOAD) : + { + _sbss = . ; + *(.bss .bss.*) + *(COMMON) + . = ALIGN(4); + _ebss = . ; + } > SRAM + + . = ALIGN(4); + _end = . ; + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } } \ No newline at end of file diff --git a/flight/PiOS/STM32F10x/pios_eeprom.c b/flight/PiOS/STM32F10x/pios_eeprom.c index 182e3f4ed..a3e11c544 100644 --- a/flight/PiOS/STM32F10x/pios_eeprom.c +++ b/flight/PiOS/STM32F10x/pios_eeprom.c @@ -1,156 +1,156 @@ -/** -****************************************************************************** -* @addtogroup PIOS PIOS Core hardware abstraction layer -* @{ -* @addtogroup PIOS_EEPROM EEPROM reading/writing functions -* @brief PIOS EEPROM reading/writing functions -* @{ -* -* @file pios_eeprom.c -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief COM layer functions -* @see The GNU Public License (GPL) Version 3 -* -*****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include - -#ifdef PIOS_INCLUDE_FLASH_EEPROM - -#include -#include - -static struct pios_eeprom_cfg config; - -/** - * Initialize the flash eeprom device - * \param cfg The configuration structure. - */ -void PIOS_EEPROM_Init(const struct pios_eeprom_cfg *cfg) -{ - config = *cfg; -} - -/** - * Save a block of data to the flash eeprom device. - * \param data A pointer to the data to write. - * \param len The length of data to write. - * \return 0 on sucess - */ -int32_t PIOS_EEPROM_Save(uint8_t *data, uint32_t len) -{ - - // We need to write 32 bit words, so extend the length to be an even multiple of 4 bytes, - // and include 4 bytes for the 32 bit CRC. - uint32_t nwords = (len / 4) + 1 + (len % 4 ? 1 : 0); - uint32_t size = nwords * 4; - - // Ensure that the length is not longer than the max size. - if (size > config.max_size) - return -1; - - // Calculate a 32 bit CRC of the data. - uint32_t crc = PIOS_CRC32_updateCRC(0xffffffff, data, len); - - // Unlock the Flash Program Erase controller - FLASH_Unlock(); - - // See if we have to write the data. - if ((memcmp(data, (uint8_t*)config.base_address, len) == 0) && - (memcmp((uint8_t*)&crc, (uint8_t*)config.base_address + size - 4, 4) == 0)) - return 0; - - // TODO: Check that the area isn't already erased - - // Erase page - FLASH_Status fs = FLASH_ErasePage(config.base_address); - if (fs != FLASH_COMPLETE) - { // error - FLASH_Lock(); - return -2; - } - - // write 4 bytes at a time into program flash area (emulated EEPROM area) - uint8_t *p1 = data; - uint32_t *p3 = (uint32_t *)config.base_address; - for (int32_t i = 0; i < size; p3++) - { - uint32_t value = 0; - - if (i == (size - 4)) - { - // write the CRC. - value = crc; - i += 4; - } - else - { - if (i < len) value |= (uint32_t)*p1++ << 0; else value |= 0x000000ff; i++; - if (i < len) value |= (uint32_t)*p1++ << 8; else value |= 0x0000ff00; i++; - if (i < len) value |= (uint32_t)*p1++ << 16; else value |= 0x00ff0000; i++; - if (i < len) value |= (uint32_t)*p1++ << 24; else value |= 0xff000000; i++; - } - - // write a 32-bit value - fs = FLASH_ProgramWord((uint32_t)p3, value); - if (fs != FLASH_COMPLETE) - { - FLASH_Lock(); - return -3; - } - } - - // Lock the Flash Program Erase controller - FLASH_Lock(); - - return 0; -} - -/** - * Reads a block of data from the flash eeprom device. - * \param data A pointer to the output data buffer. - * \param len The length of data to read. - * \return 0 on sucess - */ -int32_t PIOS_EEPROM_Load(uint8_t *data, uint32_t len) -{ - - // We need to write 32 bit words, so the length should have been extended - // to an even multiple of 4 bytes, and should include 4 bytes for the 32 bit CRC. - uint32_t nwords = (len / 4) + 1 + (len % 4 ? 1 : 0); - uint32_t size = nwords * 4; - - // Ensure that the length is not longer than the max size. - if (size > config.max_size) - return -1; - - // Read the data from flash. - memcpy(data, (uint8_t*)config.base_address, len); - - // Read the CRC. - uint32_t crc_flash = *((uint32_t*)(config.base_address + size - 4)); - - // Calculate a 32 bit CRC of the data. - uint32_t crc = PIOS_CRC32_updateCRC(0xffffffff, data, len); - if(crc != crc_flash) - return -2; - - return 0; -} - -#endif /* PIOS_INCLUDE_FLASH_EEPROM */ +/** +****************************************************************************** +* @addtogroup PIOS PIOS Core hardware abstraction layer +* @{ +* @addtogroup PIOS_EEPROM EEPROM reading/writing functions +* @brief PIOS EEPROM reading/writing functions +* @{ +* +* @file pios_eeprom.c +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief COM layer functions +* @see The GNU Public License (GPL) Version 3 +* +*****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include + +#ifdef PIOS_INCLUDE_FLASH_EEPROM + +#include +#include + +static struct pios_eeprom_cfg config; + +/** + * Initialize the flash eeprom device + * \param cfg The configuration structure. + */ +void PIOS_EEPROM_Init(const struct pios_eeprom_cfg *cfg) +{ + config = *cfg; +} + +/** + * Save a block of data to the flash eeprom device. + * \param data A pointer to the data to write. + * \param len The length of data to write. + * \return 0 on sucess + */ +int32_t PIOS_EEPROM_Save(uint8_t *data, uint32_t len) +{ + + // We need to write 32 bit words, so extend the length to be an even multiple of 4 bytes, + // and include 4 bytes for the 32 bit CRC. + uint32_t nwords = (len / 4) + 1 + (len % 4 ? 1 : 0); + uint32_t size = nwords * 4; + + // Ensure that the length is not longer than the max size. + if (size > config.max_size) + return -1; + + // Calculate a 32 bit CRC of the data. + uint32_t crc = PIOS_CRC32_updateCRC(0xffffffff, data, len); + + // Unlock the Flash Program Erase controller + FLASH_Unlock(); + + // See if we have to write the data. + if ((memcmp(data, (uint8_t*)config.base_address, len) == 0) && + (memcmp((uint8_t*)&crc, (uint8_t*)config.base_address + size - 4, 4) == 0)) + return 0; + + // TODO: Check that the area isn't already erased + + // Erase page + FLASH_Status fs = FLASH_ErasePage(config.base_address); + if (fs != FLASH_COMPLETE) + { // error + FLASH_Lock(); + return -2; + } + + // write 4 bytes at a time into program flash area (emulated EEPROM area) + uint8_t *p1 = data; + uint32_t *p3 = (uint32_t *)config.base_address; + for (int32_t i = 0; i < size; p3++) + { + uint32_t value = 0; + + if (i == (size - 4)) + { + // write the CRC. + value = crc; + i += 4; + } + else + { + if (i < len) value |= (uint32_t)*p1++ << 0; else value |= 0x000000ff; i++; + if (i < len) value |= (uint32_t)*p1++ << 8; else value |= 0x0000ff00; i++; + if (i < len) value |= (uint32_t)*p1++ << 16; else value |= 0x00ff0000; i++; + if (i < len) value |= (uint32_t)*p1++ << 24; else value |= 0xff000000; i++; + } + + // write a 32-bit value + fs = FLASH_ProgramWord((uint32_t)p3, value); + if (fs != FLASH_COMPLETE) + { + FLASH_Lock(); + return -3; + } + } + + // Lock the Flash Program Erase controller + FLASH_Lock(); + + return 0; +} + +/** + * Reads a block of data from the flash eeprom device. + * \param data A pointer to the output data buffer. + * \param len The length of data to read. + * \return 0 on sucess + */ +int32_t PIOS_EEPROM_Load(uint8_t *data, uint32_t len) +{ + + // We need to write 32 bit words, so the length should have been extended + // to an even multiple of 4 bytes, and should include 4 bytes for the 32 bit CRC. + uint32_t nwords = (len / 4) + 1 + (len % 4 ? 1 : 0); + uint32_t size = nwords * 4; + + // Ensure that the length is not longer than the max size. + if (size > config.max_size) + return -1; + + // Read the data from flash. + memcpy(data, (uint8_t*)config.base_address, len); + + // Read the CRC. + uint32_t crc_flash = *((uint32_t*)(config.base_address + size - 4)); + + // Calculate a 32 bit CRC of the data. + uint32_t crc = PIOS_CRC32_updateCRC(0xffffffff, data, len); + if(crc != crc_flash) + return -2; + + return 0; +} + +#endif /* PIOS_INCLUDE_FLASH_EEPROM */ diff --git a/flight/PiOS/STM32F10x/pios_iap.c b/flight/PiOS/STM32F10x/pios_iap.c index ae286e231..0b4183948 100644 --- a/flight/PiOS/STM32F10x/pios_iap.c +++ b/flight/PiOS/STM32F10x/pios_iap.c @@ -1,126 +1,126 @@ -/*! - * @File iap.c - * @Brief - * - * Created on: Sep 6, 2010 - * Author: joe - */ - - -/**************************************************************************************** - * Header files - ****************************************************************************************/ -#include - -#ifdef PIOS_INCLUDE_IAP - -/**************************************************************************************** - * Private Definitions/Macros - ****************************************************************************************/ - -/* these definitions reside here for protection and privacy. */ -#define IAP_MAGIC_WORD_1 0x1122 -#define IAP_MAGIC_WORD_2 0xAA55 - -#define UPPERWORD16(lw) (uint16_t)((uint32_t)(lw)>>16) -#define LOWERWORD16(lw) (uint16_t)((uint32_t)(lw)&0x0000ffff) -#define UPPERBYTE(w) (uint8_t)((w)>>8) -#define LOWERBYTE(w) (uint8_t)((w)&0x00ff) - -/**************************************************************************************** - * Private Functions - ****************************************************************************************/ - -/**************************************************************************************** - * Private (static) Data - ****************************************************************************************/ - -/**************************************************************************************** - * Public/Global Data - ****************************************************************************************/ - -/*! - * \brief PIOS_IAP_Init - performs required initializations for iap module. - * \param none. - * \return none. - * \retval none. - * - * Created: Sep 8, 2010 10:10:48 PM by joe - */ -void PIOS_IAP_Init( void ) -{ - /* Enable CRC clock */ - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE); - - /* Enable PWR and BKP clock */ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); - - /* Enable write access to Backup domain */ - PWR_BackupAccessCmd(ENABLE); - - /* Clear Tamper pin Event(TE) pending flag */ - BKP_ClearFlag(); - -} - -/*! - * \brief Determines if an In-Application-Programming request has been made. - * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) - * \return TRUE - if correct sequence found, along with 'comm' updated. - * FALSE - Note that 'comm' will have an invalid comm identifier. - * \retval - * - */ -uint32_t PIOS_IAP_CheckRequest( void ) -{ - uint32_t retval = FALSE; - uint16_t reg1; - uint16_t reg2; - - reg1 = BKP_ReadBackupRegister( MAGIC_REG_1 ); - reg2 = BKP_ReadBackupRegister( MAGIC_REG_2 ); - - if( reg1 == IAP_MAGIC_WORD_1 && reg2 == IAP_MAGIC_WORD_2 ) { - // We have a match. - retval = TRUE; - } else { - retval = FALSE; - } - return retval; -} - - - -/*! - * \brief Sets the 1st word of the request sequence. - * \param n/a - * \return n/a - * \retval - */ -void PIOS_IAP_SetRequest1(void) -{ - BKP_WriteBackupRegister( MAGIC_REG_1, IAP_MAGIC_WORD_1); -} - -void PIOS_IAP_SetRequest2(void) -{ - BKP_WriteBackupRegister( MAGIC_REG_2, IAP_MAGIC_WORD_2); -} - -void PIOS_IAP_ClearRequest(void) -{ - BKP_WriteBackupRegister( MAGIC_REG_1, 0); - BKP_WriteBackupRegister( MAGIC_REG_2, 0); -} - -uint16_t PIOS_IAP_ReadBootCount(void) -{ - return BKP_ReadBackupRegister ( IAP_BOOTCOUNT ); -} - -void PIOS_IAP_WriteBootCount (uint16_t boot_count) -{ - BKP_WriteBackupRegister ( IAP_BOOTCOUNT, boot_count ); -} - -#endif /* PIOS_INCLUDE_IAP */ +/*! + * @File iap.c + * @Brief + * + * Created on: Sep 6, 2010 + * Author: joe + */ + + +/**************************************************************************************** + * Header files + ****************************************************************************************/ +#include + +#ifdef PIOS_INCLUDE_IAP + +/**************************************************************************************** + * Private Definitions/Macros + ****************************************************************************************/ + +/* these definitions reside here for protection and privacy. */ +#define IAP_MAGIC_WORD_1 0x1122 +#define IAP_MAGIC_WORD_2 0xAA55 + +#define UPPERWORD16(lw) (uint16_t)((uint32_t)(lw)>>16) +#define LOWERWORD16(lw) (uint16_t)((uint32_t)(lw)&0x0000ffff) +#define UPPERBYTE(w) (uint8_t)((w)>>8) +#define LOWERBYTE(w) (uint8_t)((w)&0x00ff) + +/**************************************************************************************** + * Private Functions + ****************************************************************************************/ + +/**************************************************************************************** + * Private (static) Data + ****************************************************************************************/ + +/**************************************************************************************** + * Public/Global Data + ****************************************************************************************/ + +/*! + * \brief PIOS_IAP_Init - performs required initializations for iap module. + * \param none. + * \return none. + * \retval none. + * + * Created: Sep 8, 2010 10:10:48 PM by joe + */ +void PIOS_IAP_Init( void ) +{ + /* Enable CRC clock */ + RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE); + + /* Enable PWR and BKP clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); + + /* Enable write access to Backup domain */ + PWR_BackupAccessCmd(ENABLE); + + /* Clear Tamper pin Event(TE) pending flag */ + BKP_ClearFlag(); + +} + +/*! + * \brief Determines if an In-Application-Programming request has been made. + * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) + * \return TRUE - if correct sequence found, along with 'comm' updated. + * FALSE - Note that 'comm' will have an invalid comm identifier. + * \retval + * + */ +uint32_t PIOS_IAP_CheckRequest( void ) +{ + uint32_t retval = FALSE; + uint16_t reg1; + uint16_t reg2; + + reg1 = BKP_ReadBackupRegister( MAGIC_REG_1 ); + reg2 = BKP_ReadBackupRegister( MAGIC_REG_2 ); + + if( reg1 == IAP_MAGIC_WORD_1 && reg2 == IAP_MAGIC_WORD_2 ) { + // We have a match. + retval = TRUE; + } else { + retval = FALSE; + } + return retval; +} + + + +/*! + * \brief Sets the 1st word of the request sequence. + * \param n/a + * \return n/a + * \retval + */ +void PIOS_IAP_SetRequest1(void) +{ + BKP_WriteBackupRegister( MAGIC_REG_1, IAP_MAGIC_WORD_1); +} + +void PIOS_IAP_SetRequest2(void) +{ + BKP_WriteBackupRegister( MAGIC_REG_2, IAP_MAGIC_WORD_2); +} + +void PIOS_IAP_ClearRequest(void) +{ + BKP_WriteBackupRegister( MAGIC_REG_1, 0); + BKP_WriteBackupRegister( MAGIC_REG_2, 0); +} + +uint16_t PIOS_IAP_ReadBootCount(void) +{ + return BKP_ReadBackupRegister ( IAP_BOOTCOUNT ); +} + +void PIOS_IAP_WriteBootCount (uint16_t boot_count) +{ + BKP_WriteBackupRegister ( IAP_BOOTCOUNT, boot_count ); +} + +#endif /* PIOS_INCLUDE_IAP */ diff --git a/flight/PiOS/STM32F10x/startup_stm32f10x_HD.S b/flight/PiOS/STM32F10x/startup_stm32f10x_HD.S index 83b2a82c2..afb4b5b0b 100644 --- a/flight/PiOS/STM32F10x/startup_stm32f10x_HD.S +++ b/flight/PiOS/STM32F10x/startup_stm32f10x_HD.S @@ -1,477 +1,477 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_hd.s - * @author MCD Application Team / David Ankers: Vector table for FreeRTOS - * @version V3.1.2 - * @date 09/28/2009 - * @brief STM32F10x High Density Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address, - * - Configure external SRAM mounted on STM3210E-EVAL board - * to be used as data memory (optional, to be enabled by user) - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2009 STMicroelectronics

- */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global SystemInit_ExtMemCtl_Dummy -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -.equ Initial_spTop, 0x20000400 -.equ BootRAM, 0xF1E0F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief Dummy SystemInit_ExtMemCtl function - * @param None - * @retval : None -*/ - .section .text.SystemInit_ExtMemCtl_Dummy,"ax",%progbits -SystemInit_ExtMemCtl_Dummy: - bx lr - .size SystemInit_ExtMemCtl_Dummy, .-SystemInit_ExtMemCtl_Dummy - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * - * @param None - * @retval : None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word USBWakeUp_IRQHandler - .word TIM8_BRK_IRQHandler - .word TIM8_UP_IRQHandler - .word TIM8_TRG_COM_IRQHandler - .word TIM8_CC_IRQHandler - .word ADC3_IRQHandler - .word FSMC_IRQHandler - .word SDIO_IRQHandler - .word TIM5_IRQHandler - .word SPI3_IRQHandler - .word UART4_IRQHandler - .word UART5_IRQHandler - .word TIM6_IRQHandler - .word TIM7_IRQHandler - .word DMA2_Channel1_IRQHandler - .word DMA2_Channel2_IRQHandler - .word DMA2_Channel3_IRQHandler - .word DMA2_Channel4_5_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x1E0. This is for boot in RAM mode for - STM32F10x High Density devices. */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - - .weak TIM8_BRK_IRQHandler - .thumb_set TIM8_BRK_IRQHandler,Default_Handler - - .weak TIM8_UP_IRQHandler - .thumb_set TIM8_UP_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_IRQHandler - .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak ADC3_IRQHandler - .thumb_set ADC3_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_IRQHandler - .thumb_set TIM6_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Channel1_IRQHandler - .thumb_set DMA2_Channel1_IRQHandler,Default_Handler - - .weak DMA2_Channel2_IRQHandler - .thumb_set DMA2_Channel2_IRQHandler,Default_Handler - - .weak DMA2_Channel3_IRQHandler - .thumb_set DMA2_Channel3_IRQHandler,Default_Handler - - .weak DMA2_Channel4_5_IRQHandler - .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler - - .weak SystemInit_ExtMemCtl - .thumb_set SystemInit_ExtMemCtl,SystemInit_ExtMemCtl_Dummy - +/** + ****************************************************************************** + * @file startup_stm32f10x_hd.s + * @author MCD Application Team / David Ankers: Vector table for FreeRTOS + * @version V3.1.2 + * @date 09/28/2009 + * @brief STM32F10x High Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address, + * - Configure external SRAM mounted on STM3210E-EVAL board + * to be used as data memory (optional, to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2009 STMicroelectronics

+ */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global SystemInit_ExtMemCtl_Dummy +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +.equ Initial_spTop, 0x20000400 +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief Dummy SystemInit_ExtMemCtl function + * @param None + * @retval : None +*/ + .section .text.SystemInit_ExtMemCtl_Dummy,"ax",%progbits +SystemInit_ExtMemCtl_Dummy: + bx lr + .size SystemInit_ExtMemCtl_Dummy, .-SystemInit_ExtMemCtl_Dummy + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_IRQHandler + .word TIM8_UP_IRQHandler + .word TIM8_TRG_COM_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_IRQHandler + .thumb_set TIM8_BRK_IRQHandler,Default_Handler + + .weak TIM8_UP_IRQHandler + .thumb_set TIM8_UP_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_IRQHandler + .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + + .weak SystemInit_ExtMemCtl + .thumb_set SystemInit_ExtMemCtl,SystemInit_ExtMemCtl_Dummy + diff --git a/flight/PiOS/STM32F10x/startup_stm32f10x_HD_OP.S b/flight/PiOS/STM32F10x/startup_stm32f10x_HD_OP.S index 159a9dd66..a0826115e 100644 --- a/flight/PiOS/STM32F10x/startup_stm32f10x_HD_OP.S +++ b/flight/PiOS/STM32F10x/startup_stm32f10x_HD_OP.S @@ -1,541 +1,541 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_hd.s - * @author MCD Application Team / David Ankers: Vector table for FreeRTOS - * @version V3.1.2 - * @date 09/28/2009 - * @brief STM32F10x High Density Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address, - * - Configure external SRAM mounted on STM3210E-EVAL board - * to be used as data memory (optional, to be enabled by user) - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ****************************************************************************** - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2009 STMicroelectronics

- */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global SystemInit_ExtMemCtl_Dummy -.global Default_Handler -.global xPortIncreaseHeapSize -.global Stack_Change - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss -/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ - -.equ BootRAM, 0xF1E0F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - -/* FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is - required, then adjust the Register Addresses */ - bl SystemInit_ExtMemCtl -/* restore original stack pointer */ - LDR r0, =_irq_stack_top - MSR msp, r0 - LDR r2, =_init_stack_top - MSR psp, r2 - /* check if irq and init stack are the same */ - /* if they are, we don't do stack swap */ - /* and lets bypass the monitoring as well for now */ - cmp r0, r2 - beq SectionBssInit -/* DO - * - stay in thread process mode - * - stay in privilege level - * - use process stack - */ - movs r0, #2 - MSR control, r0 - ISB -/* Fill IRQ stack for watermark monitoring */ - ldr r2, =_irq_stack_end - b LoopFillIRQStack - -FillIRQStack: - movw r3, #0xA5A5 - str r3, [r2], #4 - -LoopFillIRQStack: - ldr r3, = _irq_stack_top - cmp r2, r3 - bcc FillIRQStack - -SectionBssInit: -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss -/* Call the application's entry point.*/ - bl main -/* will never return here */ - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that swaps stack (from end of heap to irq_stack). - * Also reclaim the heap that was used as a stack. - * @param None - * @retval : None -*/ - .section .text.Stack_Change - .weak Stack_Change - .type Stack_Change, %function -Stack_Change: - mov r4, lr -/* Switches stack back momentarily to MSP */ - movs r0, #0 - msr control, r0 -Heap_Reclaim: -/* add heap_post_rtos to the heap (if the capability/function exist) */ -/* Also claim the unused memory (between end of heap to end of memory */ -/* CAREFULL: the heap section must be the last section in RAM in order this to work */ - ldr r0, = _init_stack_size - ldr r1, = _eheap_post_rtos - ldr r2, = _eram - subs r2, r2, r1 - adds r0, r0, r2 - bl xPortIncreaseHeapSize - bx r4 - .size Stack_Change, .-Stack_Change - -/** - * @brief Dummy SystemInit_ExtMemCtl function - * @param None - * @retval : None -*/ - .section .text.SystemInit_ExtMemCtl_Dummy,"ax",%progbits -SystemInit_ExtMemCtl_Dummy: - bx lr - .size SystemInit_ExtMemCtl_Dummy, .-SystemInit_ExtMemCtl_Dummy - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * - * @param None - * @retval : None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _irq_stack_top - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word vPortSVCHandler - .word DebugMon_Handler - .word 0 - .word xPortPendSVHandler - .word xPortSysTickHandler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word USBWakeUp_IRQHandler - .word TIM8_BRK_IRQHandler - .word TIM8_UP_IRQHandler - .word TIM8_TRG_COM_IRQHandler - .word TIM8_CC_IRQHandler - .word ADC3_IRQHandler - .word FSMC_IRQHandler - .word SDIO_IRQHandler - .word TIM5_IRQHandler - .word SPI3_IRQHandler - .word UART4_IRQHandler - .word UART5_IRQHandler - .word TIM6_IRQHandler - .word TIM7_IRQHandler - .word DMA2_Channel1_IRQHandler - .word DMA2_Channel2_IRQHandler - .word DMA2_Channel3_IRQHandler - .word DMA2_Channel4_5_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x1E0. This is for boot in RAM mode for - STM32F10x High Density devices. */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - - .weak TIM8_BRK_IRQHandler - .thumb_set TIM8_BRK_IRQHandler,Default_Handler - - .weak TIM8_UP_IRQHandler - .thumb_set TIM8_UP_IRQHandler,Default_Handler - - .weak TIM8_TRG_COM_IRQHandler - .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler - - .weak TIM8_CC_IRQHandler - .thumb_set TIM8_CC_IRQHandler,Default_Handler - - .weak ADC3_IRQHandler - .thumb_set ADC3_IRQHandler,Default_Handler - - .weak FSMC_IRQHandler - .thumb_set FSMC_IRQHandler,Default_Handler - - .weak SDIO_IRQHandler - .thumb_set SDIO_IRQHandler,Default_Handler - - .weak TIM5_IRQHandler - .thumb_set TIM5_IRQHandler,Default_Handler - - .weak SPI3_IRQHandler - .thumb_set SPI3_IRQHandler,Default_Handler - - .weak UART4_IRQHandler - .thumb_set UART4_IRQHandler,Default_Handler - - .weak UART5_IRQHandler - .thumb_set UART5_IRQHandler,Default_Handler - - .weak TIM6_IRQHandler - .thumb_set TIM6_IRQHandler,Default_Handler - - .weak TIM7_IRQHandler - .thumb_set TIM7_IRQHandler,Default_Handler - - .weak DMA2_Channel1_IRQHandler - .thumb_set DMA2_Channel1_IRQHandler,Default_Handler - - .weak DMA2_Channel2_IRQHandler - .thumb_set DMA2_Channel2_IRQHandler,Default_Handler - - .weak DMA2_Channel3_IRQHandler - .thumb_set DMA2_Channel3_IRQHandler,Default_Handler - - .weak DMA2_Channel4_5_IRQHandler - .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler - - .weak SystemInit_ExtMemCtl - .thumb_set SystemInit_ExtMemCtl,SystemInit_ExtMemCtl_Dummy - +/** + ****************************************************************************** + * @file startup_stm32f10x_hd.s + * @author MCD Application Team / David Ankers: Vector table for FreeRTOS + * @version V3.1.2 + * @date 09/28/2009 + * @brief STM32F10x High Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address, + * - Configure external SRAM mounted on STM3210E-EVAL board + * to be used as data memory (optional, to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2009 STMicroelectronics

+ */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global SystemInit_ExtMemCtl_Dummy +.global Default_Handler +.global xPortIncreaseHeapSize +.global Stack_Change + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is + required, then adjust the Register Addresses */ + bl SystemInit_ExtMemCtl +/* restore original stack pointer */ + LDR r0, =_irq_stack_top + MSR msp, r0 + LDR r2, =_init_stack_top + MSR psp, r2 + /* check if irq and init stack are the same */ + /* if they are, we don't do stack swap */ + /* and lets bypass the monitoring as well for now */ + cmp r0, r2 + beq SectionBssInit +/* DO + * - stay in thread process mode + * - stay in privilege level + * - use process stack + */ + movs r0, #2 + MSR control, r0 + ISB +/* Fill IRQ stack for watermark monitoring */ + ldr r2, =_irq_stack_end + b LoopFillIRQStack + +FillIRQStack: + movw r3, #0xA5A5 + str r3, [r2], #4 + +LoopFillIRQStack: + ldr r3, = _irq_stack_top + cmp r2, r3 + bcc FillIRQStack + +SectionBssInit: +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the application's entry point.*/ + bl main +/* will never return here */ + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that swaps stack (from end of heap to irq_stack). + * Also reclaim the heap that was used as a stack. + * @param None + * @retval : None +*/ + .section .text.Stack_Change + .weak Stack_Change + .type Stack_Change, %function +Stack_Change: + mov r4, lr +/* Switches stack back momentarily to MSP */ + movs r0, #0 + msr control, r0 +Heap_Reclaim: +/* add heap_post_rtos to the heap (if the capability/function exist) */ +/* Also claim the unused memory (between end of heap to end of memory */ +/* CAREFULL: the heap section must be the last section in RAM in order this to work */ + ldr r0, = _init_stack_size + ldr r1, = _eheap_post_rtos + ldr r2, = _eram + subs r2, r2, r1 + adds r0, r0, r2 + bl xPortIncreaseHeapSize + bx r4 + .size Stack_Change, .-Stack_Change + +/** + * @brief Dummy SystemInit_ExtMemCtl function + * @param None + * @retval : None +*/ + .section .text.SystemInit_ExtMemCtl_Dummy,"ax",%progbits +SystemInit_ExtMemCtl_Dummy: + bx lr + .size SystemInit_ExtMemCtl_Dummy, .-SystemInit_ExtMemCtl_Dummy + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _irq_stack_top + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word vPortSVCHandler + .word DebugMon_Handler + .word 0 + .word xPortPendSVHandler + .word xPortSysTickHandler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_IRQHandler + .word TIM8_UP_IRQHandler + .word TIM8_TRG_COM_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_IRQHandler + .thumb_set TIM8_BRK_IRQHandler,Default_Handler + + .weak TIM8_UP_IRQHandler + .thumb_set TIM8_UP_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_IRQHandler + .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + + .weak SystemInit_ExtMemCtl + .thumb_set SystemInit_ExtMemCtl,SystemInit_ExtMemCtl_Dummy + diff --git a/flight/PiOS/STM32F10x/startup_stm32f10x_MD.S b/flight/PiOS/STM32F10x/startup_stm32f10x_MD.S index 8177bc6e1..101499ca5 100644 --- a/flight/PiOS/STM32F10x/startup_stm32f10x_MD.S +++ b/flight/PiOS/STM32F10x/startup_stm32f10x_MD.S @@ -1,355 +1,355 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_md.s - * @author MCD Application Team / Angus Peart - * @version V3.1.2 - * @date 09/28/2009 - * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ******************************************************************************* - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2009 STMicroelectronics

- */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss - -.equ BootRAM, 0xF108F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss -/* Call the application's entry point.*/ - bl main - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * - * @param None - * @retval : None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _estack - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word SVC_Handler - .word DebugMon_Handler - .word 0 - .word PendSV_Handler - .word SysTick_Handler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word USBWakeUp_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x108. This is for boot in RAM mode for - STM32F10x Medium Density devices. */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - - +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team / Angus Peart + * @version V3.1.2 + * @date 09/28/2009 + * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ******************************************************************************* + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2009 STMicroelectronics

+ */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + diff --git a/flight/PiOS/STM32F10x/startup_stm32f10x_MD_CC.S b/flight/PiOS/STM32F10x/startup_stm32f10x_MD_CC.S index 828462ab6..1eead3af4 100644 --- a/flight/PiOS/STM32F10x/startup_stm32f10x_MD_CC.S +++ b/flight/PiOS/STM32F10x/startup_stm32f10x_MD_CC.S @@ -1,427 +1,427 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_md.s - * @author MCD Application Team / Angus Peart - * @version V3.1.2 - * @date 09/28/2009 - * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ******************************************************************************* - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2009 STMicroelectronics

- */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler -.global xPortIncreaseHeapSize -.global Stack_Change - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss - -.equ BootRAM, 0xF108F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - -/* - * From COrtex-M3 reference manual: - * - Handler IRQ always use SP_main - * - Process use SP_main or SP_process - * Here, we will use beginning of SRAM for IRQ (SP_main) - * and end of heap for initialization (SP_process). - * Once the schedule starts, all threads will use their own stack - * from heap and NOBOBY should use SP_process again. - */ - /* Do set/reset the stack pointers */ - LDR r0, =_irq_stack_top - MSR msp, r0 - LDR r2, =_init_stack_top - MSR psp, r2 - /* check if irq and init stack are the same */ - /* if they are, we don't do stack swap */ - /* and lets bypass the monitoring as well for now */ - cmp r0, r2 - beq SectionBssInit -/* DO - * - stay in thread process mode - * - stay in privilege level - * - use process stack - */ - movs r0, #2 - MSR control, r0 - ISB -/* Fill IRQ stack for watermark monitoring */ - ldr r2, =_irq_stack_end - b LoopFillIRQStack - -FillIRQStack: - movw r3, #0xA5A5 - str r3, [r2], #4 - -LoopFillIRQStack: - ldr r3, = _irq_stack_top - cmp r2, r3 - bcc FillIRQStack - -SectionBssInit: -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss -/* Call the application's entry point.*/ - bl main -/* will never return here */ - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that swaps stack (from end of heap to irq_stack). - * Also reclaim the heap that was used as a stack. - * @param None - * @retval : None -*/ - .section .text.Stack_Change - .weak Stack_Change - .type Stack_Change, %function -Stack_Change: - mov r4, lr -/* Switches stack back momentarily to MSP */ - movs r0, #0 - msr control, r0 -Heap_Reclaim: -/* add heap_post_rtos to the heap (if the capability/function exist) */ -/* Also claim the unused memory (between end of heap to end of memory */ -/* CAREFULL: the heap section must be the last section in RAM in order this to work */ - ldr r0, = _init_stack_size - ldr r1, = _eheap_post_rtos - ldr r2, = _eram - subs r2, r2, r1 - adds r0, r0, r2 - bl xPortIncreaseHeapSize - bx r4 - .size Stack_Change, .-Stack_Change - - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * - * @param None - * @retval : None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _irq_stack_top - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word vPortSVCHandler - .word DebugMon_Handler - .word 0 - .word xPortPendSVHandler - .word xPortSysTickHandler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word USBWakeUp_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x108. This is for boot in RAM mode for - STM32F10x Medium Density devices. */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - - +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team / Angus Peart + * @version V3.1.2 + * @date 09/28/2009 + * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ******************************************************************************* + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2009 STMicroelectronics

+ */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler +.global xPortIncreaseHeapSize +.global Stack_Change + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* + * From COrtex-M3 reference manual: + * - Handler IRQ always use SP_main + * - Process use SP_main or SP_process + * Here, we will use beginning of SRAM for IRQ (SP_main) + * and end of heap for initialization (SP_process). + * Once the schedule starts, all threads will use their own stack + * from heap and NOBOBY should use SP_process again. + */ + /* Do set/reset the stack pointers */ + LDR r0, =_irq_stack_top + MSR msp, r0 + LDR r2, =_init_stack_top + MSR psp, r2 + /* check if irq and init stack are the same */ + /* if they are, we don't do stack swap */ + /* and lets bypass the monitoring as well for now */ + cmp r0, r2 + beq SectionBssInit +/* DO + * - stay in thread process mode + * - stay in privilege level + * - use process stack + */ + movs r0, #2 + MSR control, r0 + ISB +/* Fill IRQ stack for watermark monitoring */ + ldr r2, =_irq_stack_end + b LoopFillIRQStack + +FillIRQStack: + movw r3, #0xA5A5 + str r3, [r2], #4 + +LoopFillIRQStack: + ldr r3, = _irq_stack_top + cmp r2, r3 + bcc FillIRQStack + +SectionBssInit: +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the application's entry point.*/ + bl main +/* will never return here */ + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that swaps stack (from end of heap to irq_stack). + * Also reclaim the heap that was used as a stack. + * @param None + * @retval : None +*/ + .section .text.Stack_Change + .weak Stack_Change + .type Stack_Change, %function +Stack_Change: + mov r4, lr +/* Switches stack back momentarily to MSP */ + movs r0, #0 + msr control, r0 +Heap_Reclaim: +/* add heap_post_rtos to the heap (if the capability/function exist) */ +/* Also claim the unused memory (between end of heap to end of memory */ +/* CAREFULL: the heap section must be the last section in RAM in order this to work */ + ldr r0, = _init_stack_size + ldr r1, = _eheap_post_rtos + ldr r2, = _eram + subs r2, r2, r1 + adds r0, r0, r2 + bl xPortIncreaseHeapSize + bx r4 + .size Stack_Change, .-Stack_Change + + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _irq_stack_top + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word vPortSVCHandler + .word DebugMon_Handler + .word 0 + .word xPortPendSVHandler + .word xPortSysTickHandler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + diff --git a/flight/PiOS/STM32F10x/startup_stm32f10x_MD_PX.S b/flight/PiOS/STM32F10x/startup_stm32f10x_MD_PX.S index 828462ab6..1eead3af4 100644 --- a/flight/PiOS/STM32F10x/startup_stm32f10x_MD_PX.S +++ b/flight/PiOS/STM32F10x/startup_stm32f10x_MD_PX.S @@ -1,427 +1,427 @@ -/** - ****************************************************************************** - * @file startup_stm32f10x_md.s - * @author MCD Application Team / Angus Peart - * @version V3.1.2 - * @date 09/28/2009 - * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. - * This module performs: - * - Set the initial SP - * - Set the initial PC == Reset_Handler, - * - Set the vector table entries with the exceptions ISR address - * - Branches to main in the C library (which eventually - * calls main()). - * After Reset the Cortex-M3 processor is in Thread mode, - * priority is Privileged, and the Stack is set to Main. - ******************************************************************************* - * @copy - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2009 STMicroelectronics

- */ - - .syntax unified - .cpu cortex-m3 - .fpu softvfp - .thumb - -.global g_pfnVectors -.global Default_Handler -.global xPortIncreaseHeapSize -.global Stack_Change - -/* start address for the initialization values of the .data section. -defined in linker script */ -.word _sidata -/* start address for the .data section. defined in linker script */ -.word _sdata -/* end address for the .data section. defined in linker script */ -.word _edata -/* start address for the .bss section. defined in linker script */ -.word _sbss -/* end address for the .bss section. defined in linker script */ -.word _ebss - -.equ BootRAM, 0xF108F85F -/** - * @brief This is the code that gets called when the processor first - * starts execution following a reset event. Only the absolutely - * necessary set is performed, after which the application - * supplied main() routine is called. - * @param None - * @retval : None -*/ - - .section .text.Reset_Handler - .weak Reset_Handler - .type Reset_Handler, %function -Reset_Handler: - -/* - * From COrtex-M3 reference manual: - * - Handler IRQ always use SP_main - * - Process use SP_main or SP_process - * Here, we will use beginning of SRAM for IRQ (SP_main) - * and end of heap for initialization (SP_process). - * Once the schedule starts, all threads will use their own stack - * from heap and NOBOBY should use SP_process again. - */ - /* Do set/reset the stack pointers */ - LDR r0, =_irq_stack_top - MSR msp, r0 - LDR r2, =_init_stack_top - MSR psp, r2 - /* check if irq and init stack are the same */ - /* if they are, we don't do stack swap */ - /* and lets bypass the monitoring as well for now */ - cmp r0, r2 - beq SectionBssInit -/* DO - * - stay in thread process mode - * - stay in privilege level - * - use process stack - */ - movs r0, #2 - MSR control, r0 - ISB -/* Fill IRQ stack for watermark monitoring */ - ldr r2, =_irq_stack_end - b LoopFillIRQStack - -FillIRQStack: - movw r3, #0xA5A5 - str r3, [r2], #4 - -LoopFillIRQStack: - ldr r3, = _irq_stack_top - cmp r2, r3 - bcc FillIRQStack - -SectionBssInit: -/* Copy the data segment initializers from flash to SRAM */ - movs r1, #0 - b LoopCopyDataInit - -CopyDataInit: - ldr r3, =_sidata - ldr r3, [r3, r1] - str r3, [r0, r1] - adds r1, r1, #4 - -LoopCopyDataInit: - ldr r0, =_sdata - ldr r3, =_edata - adds r2, r0, r1 - cmp r2, r3 - bcc CopyDataInit - ldr r2, =_sbss - b LoopFillZerobss -/* Zero fill the bss segment. */ -FillZerobss: - movs r3, #0 - str r3, [r2], #4 - -LoopFillZerobss: - ldr r3, = _ebss - cmp r2, r3 - bcc FillZerobss -/* Call the application's entry point.*/ - bl main -/* will never return here */ - bx lr -.size Reset_Handler, .-Reset_Handler - -/** - * @brief This is the code that swaps stack (from end of heap to irq_stack). - * Also reclaim the heap that was used as a stack. - * @param None - * @retval : None -*/ - .section .text.Stack_Change - .weak Stack_Change - .type Stack_Change, %function -Stack_Change: - mov r4, lr -/* Switches stack back momentarily to MSP */ - movs r0, #0 - msr control, r0 -Heap_Reclaim: -/* add heap_post_rtos to the heap (if the capability/function exist) */ -/* Also claim the unused memory (between end of heap to end of memory */ -/* CAREFULL: the heap section must be the last section in RAM in order this to work */ - ldr r0, = _init_stack_size - ldr r1, = _eheap_post_rtos - ldr r2, = _eram - subs r2, r2, r1 - adds r0, r0, r2 - bl xPortIncreaseHeapSize - bx r4 - .size Stack_Change, .-Stack_Change - - -/** - * @brief This is the code that gets called when the processor receives an - * unexpected interrupt. This simply enters an infinite loop, preserving - * the system state for examination by a debugger. - * - * @param None - * @retval : None -*/ - .section .text.Default_Handler,"ax",%progbits -Default_Handler: -Infinite_Loop: - b Infinite_Loop - .size Default_Handler, .-Default_Handler -/****************************************************************************** -* -* The minimal vector table for a Cortex M3. Note that the proper constructs -* must be placed on this to ensure that it ends up at physical address -* 0x0000.0000. -* -******************************************************************************/ - .section .isr_vector,"a",%progbits - .type g_pfnVectors, %object - .size g_pfnVectors, .-g_pfnVectors - - -g_pfnVectors: - .word _irq_stack_top - .word Reset_Handler - .word NMI_Handler - .word HardFault_Handler - .word MemManage_Handler - .word BusFault_Handler - .word UsageFault_Handler - .word 0 - .word 0 - .word 0 - .word 0 - .word vPortSVCHandler - .word DebugMon_Handler - .word 0 - .word xPortPendSVHandler - .word xPortSysTickHandler - .word WWDG_IRQHandler - .word PVD_IRQHandler - .word TAMPER_IRQHandler - .word RTC_IRQHandler - .word FLASH_IRQHandler - .word RCC_IRQHandler - .word EXTI0_IRQHandler - .word EXTI1_IRQHandler - .word EXTI2_IRQHandler - .word EXTI3_IRQHandler - .word EXTI4_IRQHandler - .word DMA1_Channel1_IRQHandler - .word DMA1_Channel2_IRQHandler - .word DMA1_Channel3_IRQHandler - .word DMA1_Channel4_IRQHandler - .word DMA1_Channel5_IRQHandler - .word DMA1_Channel6_IRQHandler - .word DMA1_Channel7_IRQHandler - .word ADC1_2_IRQHandler - .word USB_HP_CAN1_TX_IRQHandler - .word USB_LP_CAN1_RX0_IRQHandler - .word CAN1_RX1_IRQHandler - .word CAN1_SCE_IRQHandler - .word EXTI9_5_IRQHandler - .word TIM1_BRK_IRQHandler - .word TIM1_UP_IRQHandler - .word TIM1_TRG_COM_IRQHandler - .word TIM1_CC_IRQHandler - .word TIM2_IRQHandler - .word TIM3_IRQHandler - .word TIM4_IRQHandler - .word I2C1_EV_IRQHandler - .word I2C1_ER_IRQHandler - .word I2C2_EV_IRQHandler - .word I2C2_ER_IRQHandler - .word SPI1_IRQHandler - .word SPI2_IRQHandler - .word USART1_IRQHandler - .word USART2_IRQHandler - .word USART3_IRQHandler - .word EXTI15_10_IRQHandler - .word RTCAlarm_IRQHandler - .word USBWakeUp_IRQHandler - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word 0 - .word BootRAM /* @0x108. This is for boot in RAM mode for - STM32F10x Medium Density devices. */ - -/******************************************************************************* -* -* Provide weak aliases for each Exception handler to the Default_Handler. -* As they are weak aliases, any function with the same name will override -* this definition. -* -*******************************************************************************/ - - .weak NMI_Handler - .thumb_set NMI_Handler,Default_Handler - - .weak HardFault_Handler - .thumb_set HardFault_Handler,Default_Handler - - .weak MemManage_Handler - .thumb_set MemManage_Handler,Default_Handler - - .weak BusFault_Handler - .thumb_set BusFault_Handler,Default_Handler - - .weak UsageFault_Handler - .thumb_set UsageFault_Handler,Default_Handler - - .weak SVC_Handler - .thumb_set SVC_Handler,Default_Handler - - .weak DebugMon_Handler - .thumb_set DebugMon_Handler,Default_Handler - - .weak PendSV_Handler - .thumb_set PendSV_Handler,Default_Handler - - .weak SysTick_Handler - .thumb_set SysTick_Handler,Default_Handler - - .weak WWDG_IRQHandler - .thumb_set WWDG_IRQHandler,Default_Handler - - .weak PVD_IRQHandler - .thumb_set PVD_IRQHandler,Default_Handler - - .weak TAMPER_IRQHandler - .thumb_set TAMPER_IRQHandler,Default_Handler - - .weak RTC_IRQHandler - .thumb_set RTC_IRQHandler,Default_Handler - - .weak FLASH_IRQHandler - .thumb_set FLASH_IRQHandler,Default_Handler - - .weak RCC_IRQHandler - .thumb_set RCC_IRQHandler,Default_Handler - - .weak EXTI0_IRQHandler - .thumb_set EXTI0_IRQHandler,Default_Handler - - .weak EXTI1_IRQHandler - .thumb_set EXTI1_IRQHandler,Default_Handler - - .weak EXTI2_IRQHandler - .thumb_set EXTI2_IRQHandler,Default_Handler - - .weak EXTI3_IRQHandler - .thumb_set EXTI3_IRQHandler,Default_Handler - - .weak EXTI4_IRQHandler - .thumb_set EXTI4_IRQHandler,Default_Handler - - .weak DMA1_Channel1_IRQHandler - .thumb_set DMA1_Channel1_IRQHandler,Default_Handler - - .weak DMA1_Channel2_IRQHandler - .thumb_set DMA1_Channel2_IRQHandler,Default_Handler - - .weak DMA1_Channel3_IRQHandler - .thumb_set DMA1_Channel3_IRQHandler,Default_Handler - - .weak DMA1_Channel4_IRQHandler - .thumb_set DMA1_Channel4_IRQHandler,Default_Handler - - .weak DMA1_Channel5_IRQHandler - .thumb_set DMA1_Channel5_IRQHandler,Default_Handler - - .weak DMA1_Channel6_IRQHandler - .thumb_set DMA1_Channel6_IRQHandler,Default_Handler - - .weak DMA1_Channel7_IRQHandler - .thumb_set DMA1_Channel7_IRQHandler,Default_Handler - - .weak ADC1_2_IRQHandler - .thumb_set ADC1_2_IRQHandler,Default_Handler - - .weak USB_HP_CAN1_TX_IRQHandler - .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler - - .weak USB_LP_CAN1_RX0_IRQHandler - .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler - - .weak CAN1_RX1_IRQHandler - .thumb_set CAN1_RX1_IRQHandler,Default_Handler - - .weak CAN1_SCE_IRQHandler - .thumb_set CAN1_SCE_IRQHandler,Default_Handler - - .weak EXTI9_5_IRQHandler - .thumb_set EXTI9_5_IRQHandler,Default_Handler - - .weak TIM1_BRK_IRQHandler - .thumb_set TIM1_BRK_IRQHandler,Default_Handler - - .weak TIM1_UP_IRQHandler - .thumb_set TIM1_UP_IRQHandler,Default_Handler - - .weak TIM1_TRG_COM_IRQHandler - .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler - - .weak TIM1_CC_IRQHandler - .thumb_set TIM1_CC_IRQHandler,Default_Handler - - .weak TIM2_IRQHandler - .thumb_set TIM2_IRQHandler,Default_Handler - - .weak TIM3_IRQHandler - .thumb_set TIM3_IRQHandler,Default_Handler - - .weak TIM4_IRQHandler - .thumb_set TIM4_IRQHandler,Default_Handler - - .weak I2C1_EV_IRQHandler - .thumb_set I2C1_EV_IRQHandler,Default_Handler - - .weak I2C1_ER_IRQHandler - .thumb_set I2C1_ER_IRQHandler,Default_Handler - - .weak I2C2_EV_IRQHandler - .thumb_set I2C2_EV_IRQHandler,Default_Handler - - .weak I2C2_ER_IRQHandler - .thumb_set I2C2_ER_IRQHandler,Default_Handler - - .weak SPI1_IRQHandler - .thumb_set SPI1_IRQHandler,Default_Handler - - .weak SPI2_IRQHandler - .thumb_set SPI2_IRQHandler,Default_Handler - - .weak USART1_IRQHandler - .thumb_set USART1_IRQHandler,Default_Handler - - .weak USART2_IRQHandler - .thumb_set USART2_IRQHandler,Default_Handler - - .weak USART3_IRQHandler - .thumb_set USART3_IRQHandler,Default_Handler - - .weak EXTI15_10_IRQHandler - .thumb_set EXTI15_10_IRQHandler,Default_Handler - - .weak RTCAlarm_IRQHandler - .thumb_set RTCAlarm_IRQHandler,Default_Handler - - .weak USBWakeUp_IRQHandler - .thumb_set USBWakeUp_IRQHandler,Default_Handler - - +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team / Angus Peart + * @version V3.1.2 + * @date 09/28/2009 + * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ******************************************************************************* + * @copy + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2009 STMicroelectronics

+ */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler +.global xPortIncreaseHeapSize +.global Stack_Change + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* + * From COrtex-M3 reference manual: + * - Handler IRQ always use SP_main + * - Process use SP_main or SP_process + * Here, we will use beginning of SRAM for IRQ (SP_main) + * and end of heap for initialization (SP_process). + * Once the schedule starts, all threads will use their own stack + * from heap and NOBOBY should use SP_process again. + */ + /* Do set/reset the stack pointers */ + LDR r0, =_irq_stack_top + MSR msp, r0 + LDR r2, =_init_stack_top + MSR psp, r2 + /* check if irq and init stack are the same */ + /* if they are, we don't do stack swap */ + /* and lets bypass the monitoring as well for now */ + cmp r0, r2 + beq SectionBssInit +/* DO + * - stay in thread process mode + * - stay in privilege level + * - use process stack + */ + movs r0, #2 + MSR control, r0 + ISB +/* Fill IRQ stack for watermark monitoring */ + ldr r2, =_irq_stack_end + b LoopFillIRQStack + +FillIRQStack: + movw r3, #0xA5A5 + str r3, [r2], #4 + +LoopFillIRQStack: + ldr r3, = _irq_stack_top + cmp r2, r3 + bcc FillIRQStack + +SectionBssInit: +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the application's entry point.*/ + bl main +/* will never return here */ + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that swaps stack (from end of heap to irq_stack). + * Also reclaim the heap that was used as a stack. + * @param None + * @retval : None +*/ + .section .text.Stack_Change + .weak Stack_Change + .type Stack_Change, %function +Stack_Change: + mov r4, lr +/* Switches stack back momentarily to MSP */ + movs r0, #0 + msr control, r0 +Heap_Reclaim: +/* add heap_post_rtos to the heap (if the capability/function exist) */ +/* Also claim the unused memory (between end of heap to end of memory */ +/* CAREFULL: the heap section must be the last section in RAM in order this to work */ + ldr r0, = _init_stack_size + ldr r1, = _eheap_post_rtos + ldr r2, = _eram + subs r2, r2, r1 + adds r0, r0, r2 + bl xPortIncreaseHeapSize + bx r4 + .size Stack_Change, .-Stack_Change + + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _irq_stack_top + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word vPortSVCHandler + .word DebugMon_Handler + .word 0 + .word xPortPendSVHandler + .word xPortSysTickHandler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + diff --git a/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/osd/system_stm32f4xx.c b/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/osd/system_stm32f4xx.c index 17d935034..111067471 100644 --- a/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/osd/system_stm32f4xx.c +++ b/flight/PiOS/STM32F4xx/Libraries/CMSIS2/Device/ST/STM32F4xx/Source/osd/system_stm32f4xx.c @@ -1,553 +1,553 @@ -/** - ****************************************************************************** - * @file system_stm32f4xx.c - * @author MCD Application Team - * @version V1.0.0 - * @date 30-September-2011 - * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. - * This file contains the system clock configuration for STM32F4xx devices, - * and is generated by the clock configuration tool - * stm32f4xx_Clock_Configuration_V1.0.0.xls - * - * 1. This file provides two functions and one global variable to be called from - * user application: - * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier - * and Divider factors, AHB/APBx prescalers and Flash settings), - * depending on the configuration made in the clock xls tool. - * This function is called at startup just after reset and - * before branch to main program. This call is made inside - * the "startup_stm32f4xx.s" file. - * - * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used - * by the user application to setup the SysTick - * timer or configure other parameters. - * - * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must - * be called whenever the core clock is changed - * during program execution. - * - * 2. After each device reset the HSI (16 MHz) is used as system clock source. - * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to - * configure the system clock before to branch to main program. - * - * 3. If the system clock source selected by user fails to startup, the SystemInit() - * function will do nothing and HSI still used as system clock source. User can - * add some code to deal with this issue inside the SetSysClock() function. - * - * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define - * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or - * through PLL, and you are using different crystal you have to adapt the HSE - * value to your own configuration. - * - * 5. This file configures the system clock as follows: - *============================================================================= - *============================================================================= - * Supported STM32F4xx device revision | Rev A - *----------------------------------------------------------------------------- - * System Clock source | PLL (HSE) - *----------------------------------------------------------------------------- - * SYSCLK(Hz) | 168000000 - *----------------------------------------------------------------------------- - * HCLK(Hz) | 168000000 - *----------------------------------------------------------------------------- - * AHB Prescaler | 1 - *----------------------------------------------------------------------------- - * APB1 Prescaler | 4 - *----------------------------------------------------------------------------- - * APB2 Prescaler | 2 - *----------------------------------------------------------------------------- - * HSE Frequency(Hz) | 8000000 - *----------------------------------------------------------------------------- - * PLL_M | 10 - *----------------------------------------------------------------------------- - * PLL_N | 420 - *----------------------------------------------------------------------------- - * PLL_P | 2 - *----------------------------------------------------------------------------- - * PLL_Q | 7 - *----------------------------------------------------------------------------- - * PLLI2S_N | NA - *----------------------------------------------------------------------------- - * PLLI2S_R | NA - *----------------------------------------------------------------------------- - * I2S input clock | NA - *----------------------------------------------------------------------------- - * VDD(V) | 3.3 - *----------------------------------------------------------------------------- - * Main regulator output voltage | Scale1 mode - *----------------------------------------------------------------------------- - * Flash Latency(WS) | 5 - *----------------------------------------------------------------------------- - * Prefetch Buffer | OFF - *----------------------------------------------------------------------------- - * Instruction cache | ON - *----------------------------------------------------------------------------- - * Data cache | ON - *----------------------------------------------------------------------------- - * Require 48MHz for USB OTG FS, | Enabled - * SDIO and RNG clock | - *----------------------------------------------------------------------------- - *============================================================================= - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx_system - * @{ - */ - -/** @addtogroup STM32F4xx_System_Private_Includes - * @{ - */ - -#include "stm32f4xx.h" - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Defines - * @{ - */ - -/************************* Miscellaneous Configuration ************************/ -/*!< Uncomment the following line if you need to use external SRAM mounted - on STM324xG_EVAL board as data memory */ -/* #define DATA_IN_ExtSRAM */ - -/*!< Uncomment the following line if you need to relocate your vector Table in - Internal SRAM. */ -/* #define VECT_TAB_SRAM */ -#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field. -This value must be a multiple of 0x200. */ -/******************************************************************************/ - -/************************* PLL Parameters *************************************/ -/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */ -#define PLL_M 10 -#define PLL_N 420 - -/* SYSCLK = PLL_VCO / PLL_P */ -#define PLL_P 2 - -/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */ -#define PLL_Q 7 - -/******************************************************************************/ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Variables - * @{ - */ - -uint32_t SystemCoreClock = 168000000; - -__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes - * @{ - */ - -static void SetSysClock(void); -#ifdef DATA_IN_ExtSRAM -static void SystemInit_ExtMemCtl(void); -#endif /* DATA_IN_ExtSRAM */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Functions - * @{ - */ - -/** - * @brief Setup the microcontroller system - * Initialize the Embedded Flash Interface, the PLL and update the - * SystemFrequency variable. - * @param None - * @retval None - */ -void SystemInit(void) -{ - /* FPU settings ------------------------------------------------------------*/ -#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ -#endif - - /* Reset the RCC clock configuration to the default reset state ------------*/ - /* Set HSION bit */ - RCC->CR |= (uint32_t)0x00000001; - - /* Reset CFGR register */ - RCC->CFGR = 0x00000000; - - /* Reset HSEON, CSSON and PLLON bits */ - RCC->CR &= (uint32_t)0xFEF6FFFF; - - /* Reset PLLCFGR register */ - RCC->PLLCFGR = 0x24003010; - - /* Reset HSEBYP bit */ - RCC->CR &= (uint32_t)0xFFFBFFFF; - - /* Disable all interrupts */ - RCC->CIR = 0x00000000; - -#ifdef DATA_IN_ExtSRAM - SystemInit_ExtMemCtl(); -#endif /* DATA_IN_ExtSRAM */ - - /* Configure the System clock source, PLL Multiplier and Divider factors, - AHB/APBx prescalers and Flash settings ----------------------------------*/ - SetSysClock(); - - /* Configure the Vector Table location add offset address ------------------*/ -#ifdef VECT_TAB_SRAM - SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ -#else - SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ -#endif -} - -/** - * @brief Update SystemCoreClock variable according to Clock Register Values. - * The SystemCoreClock variable contains the core clock (HCLK), it can - * be used by the user application to setup the SysTick timer or configure - * other parameters. - * - * @note Each time the core clock (HCLK) changes, this function must be called - * to update SystemCoreClock variable value. Otherwise, any configuration - * based on this variable will be incorrect. - * - * @note - The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined - * constant and the selected clock source: - * - * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) - * - * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) - * - * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) - * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * - * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * - * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value - * 25 MHz), user has to ensure that HSE_VALUE is same as the real - * frequency of the crystal used. Otherwise, this function may - * have wrong result. - * - * - The result of this function could be not correct when using fractional - * value for HSE crystal. - * - * @param None - * @retval None - */ -void SystemCoreClockUpdate(void) -{ - uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; - - /* Get SYSCLK source -------------------------------------------------------*/ - tmp = RCC->CFGR & RCC_CFGR_SWS; - - switch (tmp) - { - case 0x00: /* HSI used as system clock source */ - SystemCoreClock = HSI_VALUE; - break; - case 0x04: /* HSE used as system clock source */ - SystemCoreClock = HSE_VALUE; - break; - case 0x08: /* PLL used as system clock source */ - - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N - SYSCLK = PLL_VCO / PLL_P - */ - pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22; - pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - - if (pllsource != 0) - { - /* HSE used as PLL clock source */ - pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); - } - else - { - /* HSI used as PLL clock source */ - pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); - } - - pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; - SystemCoreClock = pllvco/pllp; - break; - default: - SystemCoreClock = HSI_VALUE; - break; - } - /* Compute HCLK frequency --------------------------------------------------*/ - /* Get HCLK prescaler */ - tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; - /* HCLK frequency */ - SystemCoreClock >>= tmp; -} - -/** - * @brief Configures the System clock source, PLL Multiplier and Divider factors, - * AHB/APBx prescalers and Flash settings - * @Note This function should be called only once the RCC clock configuration - * is reset to the default reset state (done in SystemInit() function). - * @param None - * @retval None - */ -static void SetSysClock(void) -{ - /******************************************************************************/ - /* PLL (clocked by HSE) used as System clock source */ - /******************************************************************************/ - __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - /* Enable HSE */ - RCC->CR |= ((uint32_t)RCC_CR_HSEON); - - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC->CR & RCC_CR_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); - - if ((RCC->CR & RCC_CR_HSERDY) != RESET) - { - HSEStatus = (uint32_t)0x01; - } - else - { - HSEStatus = (uint32_t)0x00; - } - - if (HSEStatus == (uint32_t)0x01) - { - /* Select regulator voltage output Scale 1 mode, System frequency up to 168 MHz */ - RCC->APB1ENR |= RCC_APB1ENR_PWREN; - PWR->CR |= PWR_CR_VOS; - - /* HCLK = SYSCLK / 1*/ - RCC->CFGR |= RCC_CFGR_HPRE_DIV1; - - /* PCLK2 = HCLK / 2*/ - RCC->CFGR |= RCC_CFGR_PPRE2_DIV2; - - /* PCLK1 = HCLK / 4*/ - RCC->CFGR |= RCC_CFGR_PPRE1_DIV4; - - /* Configure the main PLL */ - RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | - (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24); - - /* Enable the main PLL */ - RCC->CR |= RCC_CR_PLLON; - - /* Wait till the main PLL is ready */ - while((RCC->CR & RCC_CR_PLLRDY) == 0) - { - } - - /* Configure Flash prefetch, Instruction cache, Data cache and wait state */ - FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS; - - /* Select the main PLL as system clock source */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); - RCC->CFGR |= RCC_CFGR_SW_PLL; - - /* Wait till the main PLL is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL); - { - } - } - else - { /* If HSE fails to start-up, the application will have wrong clock - configuration. User can add here some code to deal with this error */ - } - -} - -/** - * @brief Setup the external memory controller. Called in startup_stm32f4xx.s - * before jump to __main - * @param None - * @retval None - */ -#ifdef DATA_IN_ExtSRAM -/** - * @brief Setup the external memory controller. - * Called in startup_stm32f4xx.s before jump to main. - * This function configures the external SRAM mounted on STM324xG_EVAL board - * This SRAM will be used as program data memory (including heap and stack). - * @param None - * @retval None - */ -void SystemInit_ExtMemCtl(void) -{ - /*-- GPIOs Configuration -----------------------------------------------------*/ - /* - +-------------------+--------------------+------------------+------------------+ - + SRAM pins assignment + - +-------------------+--------------------+------------------+------------------+ - | PD0 <-> FSMC_D2 | PE0 <-> FSMC_NBL0 | PF0 <-> FSMC_A0 | PG0 <-> FSMC_A10 | - | PD1 <-> FSMC_D3 | PE1 <-> FSMC_NBL1 | PF1 <-> FSMC_A1 | PG1 <-> FSMC_A11 | - | PD4 <-> FSMC_NOE | PE3 <-> FSMC_A19 | PF2 <-> FSMC_A2 | PG2 <-> FSMC_A12 | - | PD5 <-> FSMC_NWE | PE4 <-> FSMC_A20 | PF3 <-> FSMC_A3 | PG3 <-> FSMC_A13 | - | PD8 <-> FSMC_D13 | PE7 <-> FSMC_D4 | PF4 <-> FSMC_A4 | PG4 <-> FSMC_A14 | - | PD9 <-> FSMC_D14 | PE8 <-> FSMC_D5 | PF5 <-> FSMC_A5 | PG5 <-> FSMC_A15 | - | PD10 <-> FSMC_D15 | PE9 <-> FSMC_D6 | PF12 <-> FSMC_A6 | PG9 <-> FSMC_NE2 | - | PD11 <-> FSMC_A16 | PE10 <-> FSMC_D7 | PF13 <-> FSMC_A7 |------------------+ - | PD12 <-> FSMC_A17 | PE11 <-> FSMC_D8 | PF14 <-> FSMC_A8 | - | PD13 <-> FSMC_A18 | PE12 <-> FSMC_D9 | PF15 <-> FSMC_A9 | - | PD14 <-> FSMC_D0 | PE13 <-> FSMC_D10 |------------------+ - | PD15 <-> FSMC_D1 | PE14 <-> FSMC_D11 | - | | PE15 <-> FSMC_D12 | - +-------------------+--------------------+ - */ - /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */ - RCC->AHB1ENR = 0x00000078; - - /* Connect PDx pins to FSMC Alternate function */ - GPIOD->AFR[0] = 0x00cc00cc; - GPIOD->AFR[1] = 0xcc0ccccc; - /* Configure PDx pins in Alternate function mode */ - GPIOD->MODER = 0xaaaa0a0a; - /* Configure PDx pins speed to 100 MHz */ - GPIOD->OSPEEDR = 0xffff0f0f; - /* Configure PDx pins Output type to push-pull */ - GPIOD->OTYPER = 0x00000000; - /* No pull-up, pull-down for PDx pins */ - GPIOD->PUPDR = 0x00000000; - - /* Connect PEx pins to FSMC Alternate function */ - GPIOE->AFR[0] = 0xc00cc0cc; - GPIOE->AFR[1] = 0xcccccccc; - /* Configure PEx pins in Alternate function mode */ - GPIOE->MODER = 0xaaaa828a; - /* Configure PEx pins speed to 100 MHz */ - GPIOE->OSPEEDR = 0xffffc3cf; - /* Configure PEx pins Output type to push-pull */ - GPIOE->OTYPER = 0x00000000; - /* No pull-up, pull-down for PEx pins */ - GPIOE->PUPDR = 0x00000000; - - /* Connect PFx pins to FSMC Alternate function */ - GPIOF->AFR[0] = 0x00cccccc; - GPIOF->AFR[1] = 0xcccc0000; - /* Configure PFx pins in Alternate function mode */ - GPIOF->MODER = 0xaa000aaa; - /* Configure PFx pins speed to 100 MHz */ - GPIOF->OSPEEDR = 0xff000fff; - /* Configure PFx pins Output type to push-pull */ - GPIOF->OTYPER = 0x00000000; - /* No pull-up, pull-down for PFx pins */ - GPIOF->PUPDR = 0x00000000; - - /* Connect PGx pins to FSMC Alternate function */ - GPIOG->AFR[0] = 0x00cccccc; - GPIOG->AFR[1] = 0x000000c0; - /* Configure PGx pins in Alternate function mode */ - GPIOG->MODER = 0x00080aaa; - /* Configure PGx pins speed to 100 MHz */ - GPIOG->OSPEEDR = 0x000c0fff; - /* Configure PGx pins Output type to push-pull */ - GPIOG->OTYPER = 0x00000000; - /* No pull-up, pull-down for PGx pins */ - GPIOG->PUPDR = 0x00000000; - - /*-- FSMC Configuration ------------------------------------------------------*/ - /* Enable the FSMC interface clock */ - RCC->AHB3ENR = 0x00000001; - - /* Configure and enable Bank1_SRAM2 */ - FSMC_Bank1->BTCR[2] = 0x00001015; - FSMC_Bank1->BTCR[3] = 0x00010603; - FSMC_Bank1E->BWTR[2] = 0x0fffffff; - /* - Bank1_SRAM2 is configured as follow: - - p.FSMC_AddressSetupTime = 3; - p.FSMC_AddressHoldTime = 0; - p.FSMC_DataSetupTime = 6; - p.FSMC_BusTurnAroundDuration = 1; - p.FSMC_CLKDivision = 0; - p.FSMC_DataLatency = 0; - p.FSMC_AccessMode = FSMC_AccessMode_A; - - FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2; - FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable; - FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_PSRAM; - FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b; - FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; - FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; - FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; - FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable; - FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; - FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable; - FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable; - FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; - FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable; - FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p; - FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p; - */ - -} -#endif /* DATA_IN_ExtSRAM */ - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file system_stm32f4xx.c + * @author MCD Application Team + * @version V1.0.0 + * @date 30-September-2011 + * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. + * This file contains the system clock configuration for STM32F4xx devices, + * and is generated by the clock configuration tool + * stm32f4xx_Clock_Configuration_V1.0.0.xls + * + * 1. This file provides two functions and one global variable to be called from + * user application: + * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier + * and Divider factors, AHB/APBx prescalers and Flash settings), + * depending on the configuration made in the clock xls tool. + * This function is called at startup just after reset and + * before branch to main program. This call is made inside + * the "startup_stm32f4xx.s" file. + * + * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used + * by the user application to setup the SysTick + * timer or configure other parameters. + * + * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must + * be called whenever the core clock is changed + * during program execution. + * + * 2. After each device reset the HSI (16 MHz) is used as system clock source. + * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to + * configure the system clock before to branch to main program. + * + * 3. If the system clock source selected by user fails to startup, the SystemInit() + * function will do nothing and HSI still used as system clock source. User can + * add some code to deal with this issue inside the SetSysClock() function. + * + * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define + * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or + * through PLL, and you are using different crystal you have to adapt the HSE + * value to your own configuration. + * + * 5. This file configures the system clock as follows: + *============================================================================= + *============================================================================= + * Supported STM32F4xx device revision | Rev A + *----------------------------------------------------------------------------- + * System Clock source | PLL (HSE) + *----------------------------------------------------------------------------- + * SYSCLK(Hz) | 168000000 + *----------------------------------------------------------------------------- + * HCLK(Hz) | 168000000 + *----------------------------------------------------------------------------- + * AHB Prescaler | 1 + *----------------------------------------------------------------------------- + * APB1 Prescaler | 4 + *----------------------------------------------------------------------------- + * APB2 Prescaler | 2 + *----------------------------------------------------------------------------- + * HSE Frequency(Hz) | 8000000 + *----------------------------------------------------------------------------- + * PLL_M | 10 + *----------------------------------------------------------------------------- + * PLL_N | 420 + *----------------------------------------------------------------------------- + * PLL_P | 2 + *----------------------------------------------------------------------------- + * PLL_Q | 7 + *----------------------------------------------------------------------------- + * PLLI2S_N | NA + *----------------------------------------------------------------------------- + * PLLI2S_R | NA + *----------------------------------------------------------------------------- + * I2S input clock | NA + *----------------------------------------------------------------------------- + * VDD(V) | 3.3 + *----------------------------------------------------------------------------- + * Main regulator output voltage | Scale1 mode + *----------------------------------------------------------------------------- + * Flash Latency(WS) | 5 + *----------------------------------------------------------------------------- + * Prefetch Buffer | OFF + *----------------------------------------------------------------------------- + * Instruction cache | ON + *----------------------------------------------------------------------------- + * Data cache | ON + *----------------------------------------------------------------------------- + * Require 48MHz for USB OTG FS, | Enabled + * SDIO and RNG clock | + *----------------------------------------------------------------------------- + *============================================================================= + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f4xx_system + * @{ + */ + +/** @addtogroup STM32F4xx_System_Private_Includes + * @{ + */ + +#include "stm32f4xx.h" + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Defines + * @{ + */ + +/************************* Miscellaneous Configuration ************************/ +/*!< Uncomment the following line if you need to use external SRAM mounted + on STM324xG_EVAL board as data memory */ +/* #define DATA_IN_ExtSRAM */ + +/*!< Uncomment the following line if you need to relocate your vector Table in + Internal SRAM. */ +/* #define VECT_TAB_SRAM */ +#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field. +This value must be a multiple of 0x200. */ +/******************************************************************************/ + +/************************* PLL Parameters *************************************/ +/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */ +#define PLL_M 10 +#define PLL_N 420 + +/* SYSCLK = PLL_VCO / PLL_P */ +#define PLL_P 2 + +/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */ +#define PLL_Q 7 + +/******************************************************************************/ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Variables + * @{ + */ + +uint32_t SystemCoreClock = 168000000; + +__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes + * @{ + */ + +static void SetSysClock(void); +#ifdef DATA_IN_ExtSRAM +static void SystemInit_ExtMemCtl(void); +#endif /* DATA_IN_ExtSRAM */ + +/** + * @} + */ + +/** @addtogroup STM32F4xx_System_Private_Functions + * @{ + */ + +/** + * @brief Setup the microcontroller system + * Initialize the Embedded Flash Interface, the PLL and update the + * SystemFrequency variable. + * @param None + * @retval None + */ +void SystemInit(void) +{ + /* FPU settings ------------------------------------------------------------*/ +#if (__FPU_PRESENT == 1) && (__FPU_USED == 1) + SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ +#endif + + /* Reset the RCC clock configuration to the default reset state ------------*/ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset CFGR register */ + RCC->CFGR = 0x00000000; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset PLLCFGR register */ + RCC->PLLCFGR = 0x24003010; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Disable all interrupts */ + RCC->CIR = 0x00000000; + +#ifdef DATA_IN_ExtSRAM + SystemInit_ExtMemCtl(); +#endif /* DATA_IN_ExtSRAM */ + + /* Configure the System clock source, PLL Multiplier and Divider factors, + AHB/APBx prescalers and Flash settings ----------------------------------*/ + SetSysClock(); + + /* Configure the Vector Table location add offset address ------------------*/ +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ +#endif +} + +/** + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock (HCLK), it can + * be used by the user application to setup the SysTick timer or configure + * other parameters. + * + * @note Each time the core clock (HCLK) changes, this function must be called + * to update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * or HSI_VALUE(*) multiplied/divided by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value + * 25 MHz), user has to ensure that HSE_VALUE is same as the real + * frequency of the crystal used. Otherwise, this function may + * have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * + * @param None + * @retval None + */ +void SystemCoreClockUpdate(void) +{ + uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* HSI used as system clock source */ + SystemCoreClock = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock source */ + SystemCoreClock = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock source */ + + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N + SYSCLK = PLL_VCO / PLL_P + */ + pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22; + pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; + + if (pllsource != 0) + { + /* HSE used as PLL clock source */ + pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + } + else + { + /* HSI used as PLL clock source */ + pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); + } + + pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; + SystemCoreClock = pllvco/pllp; + break; + default: + SystemCoreClock = HSI_VALUE; + break; + } + /* Compute HCLK frequency --------------------------------------------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK frequency */ + SystemCoreClock >>= tmp; +} + +/** + * @brief Configures the System clock source, PLL Multiplier and Divider factors, + * AHB/APBx prescalers and Flash settings + * @Note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). + * @param None + * @retval None + */ +static void SetSysClock(void) +{ + /******************************************************************************/ + /* PLL (clocked by HSE) used as System clock source */ + /******************************************************************************/ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0; + + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Select regulator voltage output Scale 1 mode, System frequency up to 168 MHz */ + RCC->APB1ENR |= RCC_APB1ENR_PWREN; + PWR->CR |= PWR_CR_VOS; + + /* HCLK = SYSCLK / 1*/ + RCC->CFGR |= RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK / 2*/ + RCC->CFGR |= RCC_CFGR_PPRE2_DIV2; + + /* PCLK1 = HCLK / 4*/ + RCC->CFGR |= RCC_CFGR_PPRE1_DIV4; + + /* Configure the main PLL */ + RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | + (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24); + + /* Enable the main PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till the main PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0) + { + } + + /* Configure Flash prefetch, Instruction cache, Data cache and wait state */ + FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS; + + /* Select the main PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= RCC_CFGR_SW_PLL; + + /* Wait till the main PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL); + { + } + } + else + { /* If HSE fails to start-up, the application will have wrong clock + configuration. User can add here some code to deal with this error */ + } + +} + +/** + * @brief Setup the external memory controller. Called in startup_stm32f4xx.s + * before jump to __main + * @param None + * @retval None + */ +#ifdef DATA_IN_ExtSRAM +/** + * @brief Setup the external memory controller. + * Called in startup_stm32f4xx.s before jump to main. + * This function configures the external SRAM mounted on STM324xG_EVAL board + * This SRAM will be used as program data memory (including heap and stack). + * @param None + * @retval None + */ +void SystemInit_ExtMemCtl(void) +{ + /*-- GPIOs Configuration -----------------------------------------------------*/ + /* + +-------------------+--------------------+------------------+------------------+ + + SRAM pins assignment + + +-------------------+--------------------+------------------+------------------+ + | PD0 <-> FSMC_D2 | PE0 <-> FSMC_NBL0 | PF0 <-> FSMC_A0 | PG0 <-> FSMC_A10 | + | PD1 <-> FSMC_D3 | PE1 <-> FSMC_NBL1 | PF1 <-> FSMC_A1 | PG1 <-> FSMC_A11 | + | PD4 <-> FSMC_NOE | PE3 <-> FSMC_A19 | PF2 <-> FSMC_A2 | PG2 <-> FSMC_A12 | + | PD5 <-> FSMC_NWE | PE4 <-> FSMC_A20 | PF3 <-> FSMC_A3 | PG3 <-> FSMC_A13 | + | PD8 <-> FSMC_D13 | PE7 <-> FSMC_D4 | PF4 <-> FSMC_A4 | PG4 <-> FSMC_A14 | + | PD9 <-> FSMC_D14 | PE8 <-> FSMC_D5 | PF5 <-> FSMC_A5 | PG5 <-> FSMC_A15 | + | PD10 <-> FSMC_D15 | PE9 <-> FSMC_D6 | PF12 <-> FSMC_A6 | PG9 <-> FSMC_NE2 | + | PD11 <-> FSMC_A16 | PE10 <-> FSMC_D7 | PF13 <-> FSMC_A7 |------------------+ + | PD12 <-> FSMC_A17 | PE11 <-> FSMC_D8 | PF14 <-> FSMC_A8 | + | PD13 <-> FSMC_A18 | PE12 <-> FSMC_D9 | PF15 <-> FSMC_A9 | + | PD14 <-> FSMC_D0 | PE13 <-> FSMC_D10 |------------------+ + | PD15 <-> FSMC_D1 | PE14 <-> FSMC_D11 | + | | PE15 <-> FSMC_D12 | + +-------------------+--------------------+ + */ + /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */ + RCC->AHB1ENR = 0x00000078; + + /* Connect PDx pins to FSMC Alternate function */ + GPIOD->AFR[0] = 0x00cc00cc; + GPIOD->AFR[1] = 0xcc0ccccc; + /* Configure PDx pins in Alternate function mode */ + GPIOD->MODER = 0xaaaa0a0a; + /* Configure PDx pins speed to 100 MHz */ + GPIOD->OSPEEDR = 0xffff0f0f; + /* Configure PDx pins Output type to push-pull */ + GPIOD->OTYPER = 0x00000000; + /* No pull-up, pull-down for PDx pins */ + GPIOD->PUPDR = 0x00000000; + + /* Connect PEx pins to FSMC Alternate function */ + GPIOE->AFR[0] = 0xc00cc0cc; + GPIOE->AFR[1] = 0xcccccccc; + /* Configure PEx pins in Alternate function mode */ + GPIOE->MODER = 0xaaaa828a; + /* Configure PEx pins speed to 100 MHz */ + GPIOE->OSPEEDR = 0xffffc3cf; + /* Configure PEx pins Output type to push-pull */ + GPIOE->OTYPER = 0x00000000; + /* No pull-up, pull-down for PEx pins */ + GPIOE->PUPDR = 0x00000000; + + /* Connect PFx pins to FSMC Alternate function */ + GPIOF->AFR[0] = 0x00cccccc; + GPIOF->AFR[1] = 0xcccc0000; + /* Configure PFx pins in Alternate function mode */ + GPIOF->MODER = 0xaa000aaa; + /* Configure PFx pins speed to 100 MHz */ + GPIOF->OSPEEDR = 0xff000fff; + /* Configure PFx pins Output type to push-pull */ + GPIOF->OTYPER = 0x00000000; + /* No pull-up, pull-down for PFx pins */ + GPIOF->PUPDR = 0x00000000; + + /* Connect PGx pins to FSMC Alternate function */ + GPIOG->AFR[0] = 0x00cccccc; + GPIOG->AFR[1] = 0x000000c0; + /* Configure PGx pins in Alternate function mode */ + GPIOG->MODER = 0x00080aaa; + /* Configure PGx pins speed to 100 MHz */ + GPIOG->OSPEEDR = 0x000c0fff; + /* Configure PGx pins Output type to push-pull */ + GPIOG->OTYPER = 0x00000000; + /* No pull-up, pull-down for PGx pins */ + GPIOG->PUPDR = 0x00000000; + + /*-- FSMC Configuration ------------------------------------------------------*/ + /* Enable the FSMC interface clock */ + RCC->AHB3ENR = 0x00000001; + + /* Configure and enable Bank1_SRAM2 */ + FSMC_Bank1->BTCR[2] = 0x00001015; + FSMC_Bank1->BTCR[3] = 0x00010603; + FSMC_Bank1E->BWTR[2] = 0x0fffffff; + /* + Bank1_SRAM2 is configured as follow: + + p.FSMC_AddressSetupTime = 3; + p.FSMC_AddressHoldTime = 0; + p.FSMC_DataSetupTime = 6; + p.FSMC_BusTurnAroundDuration = 1; + p.FSMC_CLKDivision = 0; + p.FSMC_DataLatency = 0; + p.FSMC_AccessMode = FSMC_AccessMode_A; + + FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2; + FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable; + FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_PSRAM; + FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b; + FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; + FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; + FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable; + FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable; + FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; + FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable; + FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p; + FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p; + */ + +} +#endif /* DATA_IN_ExtSRAM */ + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c index c2c143fe2..09800a733 100755 --- a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c +++ b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c @@ -1,350 +1,350 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - -/*----------------------------------------------------------- - * Implementation of functions defined in portable.h for the ARM CM4F port. - *----------------------------------------------------------*/ - -/* Scheduler includes. */ -#include "FreeRTOS.h" -#include "task.h" - -#ifndef __VFP_FP__ - #error This port can only be used when the project options are configured to enable hardware floating point support. -#endif - -/* Constants required to manipulate the NVIC. */ -#define portNVIC_SYSTICK_CTRL ( ( volatile unsigned long * ) 0xe000e010 ) -#define portNVIC_SYSTICK_LOAD ( ( volatile unsigned long * ) 0xe000e014 ) -#define portNVIC_INT_CTRL ( ( volatile unsigned long * ) 0xe000ed04 ) -#define portNVIC_SYSPRI2 ( ( volatile unsigned long * ) 0xe000ed20 ) -#define portNVIC_SYSTICK_CLK 0x00000004 -#define portNVIC_SYSTICK_INT 0x00000002 -#define portNVIC_SYSTICK_ENABLE 0x00000001 -#define portNVIC_PENDSVSET 0x10000000 -#define portNVIC_PENDSV_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 16 ) -#define portNVIC_SYSTICK_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 24 ) - -/* Constants required to manipulate the VFP. */ -#define portFPCCR ( ( volatile unsigned long * ) 0xe000ef34 ) /* Floating point context control register. */ -#define portASPEN_AND_LSPEN_BITS ( 0x3UL << 30UL ) - -/* Constants required to set up the initial stack. */ -#define portINITIAL_XPSR ( 0x01000000 ) -#define portINITIAL_EXEC_RETURN ( 0xfffffffd ) - -/* The priority used by the kernel is assigned to a variable to make access -from inline assembler easier. */ -const unsigned long ulKernelPriority = configKERNEL_INTERRUPT_PRIORITY; - -/* Each task maintains its own interrupt status in the critical nesting -variable. */ -static unsigned portBASE_TYPE uxCriticalNesting = 0xaaaaaaaa; - -/* - * Setup the timer to generate the tick interrupts. - */ -static void prvSetupTimerInterrupt( void ); - -/* - * Exception handlers. - */ -void xPortPendSVHandler( void ) __attribute__ (( naked )); -void xPortSysTickHandler( void ); -void vPortSVCHandler( void ) __attribute__ (( naked )); - -/* - * Start first task is a separate function so it can be tested in isolation. - */ -static void vPortStartFirstTask( void ) __attribute__ (( naked )); - -/* - * Function to enable the VFP. - */ - static void vPortEnableVFP( void ) __attribute__ (( naked )); - - -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) -{ - /* Simulate the stack frame as it would be created by a context switch - interrupt. */ - - /* Offset added to account for the way the MCU uses the stack on entry/exit - of interrupts, and to ensure alignment. */ - pxTopOfStack--; - - *pxTopOfStack = portINITIAL_XPSR; /* xPSR */ - pxTopOfStack--; - *pxTopOfStack = ( portSTACK_TYPE ) pxCode; /* PC */ - pxTopOfStack--; - *pxTopOfStack = 0; /* LR */ - - /* Save code space by skipping register initialisation. */ - pxTopOfStack -= 5; /* R12, R3, R2 and R1. */ - *pxTopOfStack = ( portSTACK_TYPE ) pvParameters; /* R0 */ - - /* A save method is being used that requires each task to maintain its - own exec return value. */ - pxTopOfStack--; - *pxTopOfStack = portINITIAL_EXEC_RETURN; - - pxTopOfStack -= 8; /* R11, R10, R9, R8, R7, R6, R5 and R4. */ - - return pxTopOfStack; -} -/*-----------------------------------------------------------*/ - -void vPortSVCHandler( void ) -{ - __asm volatile ( - " ldr r3, pxCurrentTCBConst2 \n" /* Restore the context. */ - " ldr r1, [r3] \n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */ - " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */ - " ldmia r0!, {r4-r11, r14} \n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */ - " msr psp, r0 \n" /* Restore the task stack pointer. */ - " mov r0, #0 \n" - " msr basepri, r0 \n" - " bx r14 \n" - " \n" - " .align 2 \n" - "pxCurrentTCBConst2: .word pxCurrentTCB \n" - ); -} -/*-----------------------------------------------------------*/ - -static void vPortStartFirstTask( void ) -{ - __asm volatile( - " ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */ - " ldr r0, [r0] \n" - " ldr r0, [r0] \n" - " msr msp, r0 \n" /* Set the msp back to the start of the stack. */ - " cpsie i \n" /* Globally enable interrupts. */ - " svc 0 \n" /* System call to start first task. */ - " nop \n" - ); -} -/*-----------------------------------------------------------*/ - -/* - * See header file for description. - */ -portBASE_TYPE xPortStartScheduler( void ) -{ - /* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0. - See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */ - configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY ); - - /* Make PendSV and SysTick the lowest priority interrupts. */ - *(portNVIC_SYSPRI2) |= portNVIC_PENDSV_PRI; - *(portNVIC_SYSPRI2) |= portNVIC_SYSTICK_PRI; - - /* Start the timer that generates the tick ISR. Interrupts are disabled - here already. */ - prvSetupTimerInterrupt(); - - /* Initialise the critical nesting count ready for the first task. */ - uxCriticalNesting = 0; - - /* Ensure the VFP is enabled - it should be anyway. */ - vPortEnableVFP(); - - /* Lazy save always. */ - *( portFPCCR ) |= portASPEN_AND_LSPEN_BITS; - - /* Start the first task. */ - vPortStartFirstTask(); - - /* Should not get here! */ - return 0; -} -/*-----------------------------------------------------------*/ - -void vPortEndScheduler( void ) -{ - /* It is unlikely that the CM4F port will require this function as there - is nothing to return to. */ -} -/*-----------------------------------------------------------*/ - -void vPortYieldFromISR( void ) -{ - /* Set a PendSV to request a context switch. */ - *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; -} -/*-----------------------------------------------------------*/ - -void vPortEnterCritical( void ) -{ - portDISABLE_INTERRUPTS(); - uxCriticalNesting++; -} -/*-----------------------------------------------------------*/ - -void vPortExitCritical( void ) -{ - uxCriticalNesting--; - if( uxCriticalNesting == 0 ) - { - portENABLE_INTERRUPTS(); - } -} -/*-----------------------------------------------------------*/ - -void xPortPendSVHandler( void ) -{ - /* This is a naked function. */ - - __asm volatile - ( - " mrs r0, psp \n" - " \n" - " ldr r3, pxCurrentTCBConst \n" /* Get the location of the current TCB. */ - " ldr r2, [r3] \n" - " \n" - " tst r14, #0x10 \n" /* Is the task using the FPU context? If so, push high vfp registers. */ - " it eq \n" - " vstmdbeq r0!, {s16-s31} \n" - " \n" - " stmdb r0!, {r4-r11, r14} \n" /* Save the core registers. */ - " \n" - " str r0, [r2] \n" /* Save the new top of stack into the first member of the TCB. */ - " \n" - " stmdb sp!, {r3, r14} \n" - " mov r0, %0 \n" - " msr basepri, r0 \n" - " bl vTaskSwitchContext \n" - " mov r0, #0 \n" - " msr basepri, r0 \n" - " ldmia sp!, {r3, r14} \n" - " \n" - " ldr r1, [r3] \n" /* The first item in pxCurrentTCB is the task top of stack. */ - " ldr r0, [r1] \n" - " \n" - " ldmia r0!, {r4-r11, r14} \n" /* Pop the core registers. */ - " \n" - " tst r14, #0x10 \n" /* Is the task using the FPU context? If so, pop the high vfp registers too. */ - " it eq \n" - " vldmiaeq r0!, {s16-s31} \n" - " \n" - " msr psp, r0 \n" - " bx r14 \n" - " \n" - " .align 2 \n" - "pxCurrentTCBConst: .word pxCurrentTCB \n" - ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY) - ); -} -/*-----------------------------------------------------------*/ - -void xPortSysTickHandler( void ) -{ -unsigned long ulDummy; - - /* If using preemption, also force a context switch. */ - #if configUSE_PREEMPTION == 1 - *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; - #endif - - ulDummy = portSET_INTERRUPT_MASK_FROM_ISR(); - { - vTaskIncrementTick(); - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( ulDummy ); -} -/*-----------------------------------------------------------*/ - -/* - * Setup the systick timer to generate the tick interrupts at the required - * frequency. - */ -void prvSetupTimerInterrupt( void ) -{ - /* Configure SysTick to interrupt at the requested rate. */ - *(portNVIC_SYSTICK_LOAD) = ( configCPU_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL; - *(portNVIC_SYSTICK_CTRL) = portNVIC_SYSTICK_CLK | portNVIC_SYSTICK_INT | portNVIC_SYSTICK_ENABLE; -} -/*-----------------------------------------------------------*/ - -/* This is a naked function. */ -static void vPortEnableVFP( void ) -{ - __asm volatile - ( - " ldr.w r0, =0xE000ED88 \n" /* The FPU enable bits are in the CPACR. */ - " ldr r1, [r0] \n" - " \n" - " orr r1, r1, #( 0xf << 20 ) \n" /* Enable CP10 and CP11 coprocessors, then save back. */ - " str r1, [r0] \n" - " bx r14 " - ); -} - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + +/*----------------------------------------------------------- + * Implementation of functions defined in portable.h for the ARM CM4F port. + *----------------------------------------------------------*/ + +/* Scheduler includes. */ +#include "FreeRTOS.h" +#include "task.h" + +#ifndef __VFP_FP__ + #error This port can only be used when the project options are configured to enable hardware floating point support. +#endif + +/* Constants required to manipulate the NVIC. */ +#define portNVIC_SYSTICK_CTRL ( ( volatile unsigned long * ) 0xe000e010 ) +#define portNVIC_SYSTICK_LOAD ( ( volatile unsigned long * ) 0xe000e014 ) +#define portNVIC_INT_CTRL ( ( volatile unsigned long * ) 0xe000ed04 ) +#define portNVIC_SYSPRI2 ( ( volatile unsigned long * ) 0xe000ed20 ) +#define portNVIC_SYSTICK_CLK 0x00000004 +#define portNVIC_SYSTICK_INT 0x00000002 +#define portNVIC_SYSTICK_ENABLE 0x00000001 +#define portNVIC_PENDSVSET 0x10000000 +#define portNVIC_PENDSV_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 16 ) +#define portNVIC_SYSTICK_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 24 ) + +/* Constants required to manipulate the VFP. */ +#define portFPCCR ( ( volatile unsigned long * ) 0xe000ef34 ) /* Floating point context control register. */ +#define portASPEN_AND_LSPEN_BITS ( 0x3UL << 30UL ) + +/* Constants required to set up the initial stack. */ +#define portINITIAL_XPSR ( 0x01000000 ) +#define portINITIAL_EXEC_RETURN ( 0xfffffffd ) + +/* The priority used by the kernel is assigned to a variable to make access +from inline assembler easier. */ +const unsigned long ulKernelPriority = configKERNEL_INTERRUPT_PRIORITY; + +/* Each task maintains its own interrupt status in the critical nesting +variable. */ +static unsigned portBASE_TYPE uxCriticalNesting = 0xaaaaaaaa; + +/* + * Setup the timer to generate the tick interrupts. + */ +static void prvSetupTimerInterrupt( void ); + +/* + * Exception handlers. + */ +void xPortPendSVHandler( void ) __attribute__ (( naked )); +void xPortSysTickHandler( void ); +void vPortSVCHandler( void ) __attribute__ (( naked )); + +/* + * Start first task is a separate function so it can be tested in isolation. + */ +static void vPortStartFirstTask( void ) __attribute__ (( naked )); + +/* + * Function to enable the VFP. + */ + static void vPortEnableVFP( void ) __attribute__ (( naked )); + + +/*-----------------------------------------------------------*/ + +/* + * See header file for description. + */ +portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ) +{ + /* Simulate the stack frame as it would be created by a context switch + interrupt. */ + + /* Offset added to account for the way the MCU uses the stack on entry/exit + of interrupts, and to ensure alignment. */ + pxTopOfStack--; + + *pxTopOfStack = portINITIAL_XPSR; /* xPSR */ + pxTopOfStack--; + *pxTopOfStack = ( portSTACK_TYPE ) pxCode; /* PC */ + pxTopOfStack--; + *pxTopOfStack = 0; /* LR */ + + /* Save code space by skipping register initialisation. */ + pxTopOfStack -= 5; /* R12, R3, R2 and R1. */ + *pxTopOfStack = ( portSTACK_TYPE ) pvParameters; /* R0 */ + + /* A save method is being used that requires each task to maintain its + own exec return value. */ + pxTopOfStack--; + *pxTopOfStack = portINITIAL_EXEC_RETURN; + + pxTopOfStack -= 8; /* R11, R10, R9, R8, R7, R6, R5 and R4. */ + + return pxTopOfStack; +} +/*-----------------------------------------------------------*/ + +void vPortSVCHandler( void ) +{ + __asm volatile ( + " ldr r3, pxCurrentTCBConst2 \n" /* Restore the context. */ + " ldr r1, [r3] \n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */ + " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */ + " ldmia r0!, {r4-r11, r14} \n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */ + " msr psp, r0 \n" /* Restore the task stack pointer. */ + " mov r0, #0 \n" + " msr basepri, r0 \n" + " bx r14 \n" + " \n" + " .align 2 \n" + "pxCurrentTCBConst2: .word pxCurrentTCB \n" + ); +} +/*-----------------------------------------------------------*/ + +static void vPortStartFirstTask( void ) +{ + __asm volatile( + " ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */ + " ldr r0, [r0] \n" + " ldr r0, [r0] \n" + " msr msp, r0 \n" /* Set the msp back to the start of the stack. */ + " cpsie i \n" /* Globally enable interrupts. */ + " svc 0 \n" /* System call to start first task. */ + " nop \n" + ); +} +/*-----------------------------------------------------------*/ + +/* + * See header file for description. + */ +portBASE_TYPE xPortStartScheduler( void ) +{ + /* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0. + See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */ + configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY ); + + /* Make PendSV and SysTick the lowest priority interrupts. */ + *(portNVIC_SYSPRI2) |= portNVIC_PENDSV_PRI; + *(portNVIC_SYSPRI2) |= portNVIC_SYSTICK_PRI; + + /* Start the timer that generates the tick ISR. Interrupts are disabled + here already. */ + prvSetupTimerInterrupt(); + + /* Initialise the critical nesting count ready for the first task. */ + uxCriticalNesting = 0; + + /* Ensure the VFP is enabled - it should be anyway. */ + vPortEnableVFP(); + + /* Lazy save always. */ + *( portFPCCR ) |= portASPEN_AND_LSPEN_BITS; + + /* Start the first task. */ + vPortStartFirstTask(); + + /* Should not get here! */ + return 0; +} +/*-----------------------------------------------------------*/ + +void vPortEndScheduler( void ) +{ + /* It is unlikely that the CM4F port will require this function as there + is nothing to return to. */ +} +/*-----------------------------------------------------------*/ + +void vPortYieldFromISR( void ) +{ + /* Set a PendSV to request a context switch. */ + *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; +} +/*-----------------------------------------------------------*/ + +void vPortEnterCritical( void ) +{ + portDISABLE_INTERRUPTS(); + uxCriticalNesting++; +} +/*-----------------------------------------------------------*/ + +void vPortExitCritical( void ) +{ + uxCriticalNesting--; + if( uxCriticalNesting == 0 ) + { + portENABLE_INTERRUPTS(); + } +} +/*-----------------------------------------------------------*/ + +void xPortPendSVHandler( void ) +{ + /* This is a naked function. */ + + __asm volatile + ( + " mrs r0, psp \n" + " \n" + " ldr r3, pxCurrentTCBConst \n" /* Get the location of the current TCB. */ + " ldr r2, [r3] \n" + " \n" + " tst r14, #0x10 \n" /* Is the task using the FPU context? If so, push high vfp registers. */ + " it eq \n" + " vstmdbeq r0!, {s16-s31} \n" + " \n" + " stmdb r0!, {r4-r11, r14} \n" /* Save the core registers. */ + " \n" + " str r0, [r2] \n" /* Save the new top of stack into the first member of the TCB. */ + " \n" + " stmdb sp!, {r3, r14} \n" + " mov r0, %0 \n" + " msr basepri, r0 \n" + " bl vTaskSwitchContext \n" + " mov r0, #0 \n" + " msr basepri, r0 \n" + " ldmia sp!, {r3, r14} \n" + " \n" + " ldr r1, [r3] \n" /* The first item in pxCurrentTCB is the task top of stack. */ + " ldr r0, [r1] \n" + " \n" + " ldmia r0!, {r4-r11, r14} \n" /* Pop the core registers. */ + " \n" + " tst r14, #0x10 \n" /* Is the task using the FPU context? If so, pop the high vfp registers too. */ + " it eq \n" + " vldmiaeq r0!, {s16-s31} \n" + " \n" + " msr psp, r0 \n" + " bx r14 \n" + " \n" + " .align 2 \n" + "pxCurrentTCBConst: .word pxCurrentTCB \n" + ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY) + ); +} +/*-----------------------------------------------------------*/ + +void xPortSysTickHandler( void ) +{ +unsigned long ulDummy; + + /* If using preemption, also force a context switch. */ + #if configUSE_PREEMPTION == 1 + *(portNVIC_INT_CTRL) = portNVIC_PENDSVSET; + #endif + + ulDummy = portSET_INTERRUPT_MASK_FROM_ISR(); + { + vTaskIncrementTick(); + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( ulDummy ); +} +/*-----------------------------------------------------------*/ + +/* + * Setup the systick timer to generate the tick interrupts at the required + * frequency. + */ +void prvSetupTimerInterrupt( void ) +{ + /* Configure SysTick to interrupt at the requested rate. */ + *(portNVIC_SYSTICK_LOAD) = ( configCPU_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL; + *(portNVIC_SYSTICK_CTRL) = portNVIC_SYSTICK_CLK | portNVIC_SYSTICK_INT | portNVIC_SYSTICK_ENABLE; +} +/*-----------------------------------------------------------*/ + +/* This is a naked function. */ +static void vPortEnableVFP( void ) +{ + __asm volatile + ( + " ldr.w r0, =0xE000ED88 \n" /* The FPU enable bits are in the CPACR. */ + " ldr r1, [r0] \n" + " \n" + " orr r1, r1, #( 0xf << 20 ) \n" /* Enable CP10 and CP11 coprocessors, then save back. */ + " str r1, [r0] \n" + " bx r14 " + ); +} + diff --git a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h index 798be5e09..507f07b6f 100755 --- a/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h +++ b/flight/PiOS/STM32F4xx/Libraries/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h @@ -1,178 +1,178 @@ -/* - FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. - - - *************************************************************************** - * * - * FreeRTOS tutorial books are available in pdf and paperback. * - * Complete, revised, and edited pdf reference manuals are also * - * available. * - * * - * Purchasing FreeRTOS documentation will not only help you, by * - * ensuring you get running as quickly as possible and with an * - * in-depth knowledge of how to use FreeRTOS, it will also help * - * the FreeRTOS project to continue with its mission of providing * - * professional grade, cross platform, de facto standard solutions * - * for microcontrollers - completely free of charge! * - * * - * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * - * * - * Thank you for using FreeRTOS, and thank you for your support! * - * * - *************************************************************************** - - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - >>>NOTE<<< The modification to the GPL is included to allow you to - distribute a combined work that includes FreeRTOS without being obliged to - provide the source code for proprietary components outside of the FreeRTOS - kernel. FreeRTOS is distributed in the hope that it will be useful, but - WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - *************************************************************************** - * * - * Having a problem? Start by reading the FAQ "My application does * - * not run, what could be wrong? * - * * - * http://www.FreeRTOS.org/FAQHelp.html * - * * - *************************************************************************** - - - http://www.FreeRTOS.org - Documentation, training, latest information, - license and contact details. - - http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, - including FreeRTOS+Trace - an indispensable productivity tool. - - Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell - the code with commercial support, indemnification, and middleware, under - the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also - provide a safety engineered and independently SIL3 certified version under - the SafeRTOS brand: http://www.SafeRTOS.com. -*/ - - -#ifndef PORTMACRO_H -#define PORTMACRO_H - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * Port specific definitions. - * - * The settings in this file configure FreeRTOS correctly for the - * given hardware and compiler. - * - * These settings should not be altered. - *----------------------------------------------------------- - */ - -/* Type definitions. */ -#define portCHAR char -#define portFLOAT float -#define portDOUBLE double -#define portLONG long -#define portSHORT short -#define portSTACK_TYPE unsigned portLONG -#define portBASE_TYPE long - -#if( configUSE_16_BIT_TICKS == 1 ) - typedef unsigned portSHORT portTickType; - #define portMAX_DELAY ( portTickType ) 0xffff -#else - typedef unsigned portLONG portTickType; - #define portMAX_DELAY ( portTickType ) 0xffffffff -#endif -/*-----------------------------------------------------------*/ - -/* Architecture specifics. */ -#define portSTACK_GROWTH ( -1 ) -#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) -#define portBYTE_ALIGNMENT 8 -/*-----------------------------------------------------------*/ - - -/* Scheduler utilities. */ -extern void vPortYieldFromISR( void ); - -#define portYIELD() vPortYieldFromISR() - -#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() -/*-----------------------------------------------------------*/ - - -/* Critical section management. */ - -/* - * Set basepri to portMAX_SYSCALL_INTERRUPT_PRIORITY without effecting other - * registers. r0 is clobbered. - */ -#define portSET_INTERRUPT_MASK() \ - __asm volatile \ - ( \ - " mov r0, %0 \n" \ - " msr basepri, r0 \n" \ - ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY):"r0" \ - ) - -/* - * Set basepri back to 0 without effective other registers. - * r0 is clobbered. FAQ: Setting BASEPRI to 0 is not a bug. Please see - * http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before disagreeing. - */ -#define portCLEAR_INTERRUPT_MASK() \ - __asm volatile \ - ( \ - " mov r0, #0 \n" \ - " msr basepri, r0 \n" \ - :::"r0" \ - ) - -/* FAQ: Setting BASEPRI to 0 in portCLEAR_INTERRUPT_MASK_FROM_ISR() is not a -bug. Please see http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before -disagreeing. */ -#define portSET_INTERRUPT_MASK_FROM_ISR() 0;portSET_INTERRUPT_MASK() -#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) portCLEAR_INTERRUPT_MASK();(void)x - - -extern void vPortEnterCritical( void ); -extern void vPortExitCritical( void ); - -#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() -#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() -#define portENTER_CRITICAL() vPortEnterCritical() -#define portEXIT_CRITICAL() vPortExitCritical() - -/* There are an uneven number of items on the initial stack, so -portALIGNMENT_ASSERT_pxCurrentTCB() will trigger false positive asserts. */ -#define portALIGNMENT_ASSERT_pxCurrentTCB ( void ) - -/*-----------------------------------------------------------*/ - -/* Task function macros as described on the FreeRTOS.org WEB site. */ -#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) -#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) - -#define portNOP() - -#ifdef __cplusplus -} -#endif - -#endif /* PORTMACRO_H */ - +/* + FreeRTOS V7.2.0 - Copyright (C) 2012 Real Time Engineers Ltd. + + + *************************************************************************** + * * + * FreeRTOS tutorial books are available in pdf and paperback. * + * Complete, revised, and edited pdf reference manuals are also * + * available. * + * * + * Purchasing FreeRTOS documentation will not only help you, by * + * ensuring you get running as quickly as possible and with an * + * in-depth knowledge of how to use FreeRTOS, it will also help * + * the FreeRTOS project to continue with its mission of providing * + * professional grade, cross platform, de facto standard solutions * + * for microcontrollers - completely free of charge! * + * * + * >>> See http://www.FreeRTOS.org/Documentation for details. <<< * + * * + * Thank you for using FreeRTOS, and thank you for your support! * + * * + *************************************************************************** + + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + >>>NOTE<<< The modification to the GPL is included to allow you to + distribute a combined work that includes FreeRTOS without being obliged to + provide the source code for proprietary components outside of the FreeRTOS + kernel. FreeRTOS is distributed in the hope that it will be useful, but + WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + *************************************************************************** + * * + * Having a problem? Start by reading the FAQ "My application does * + * not run, what could be wrong? * + * * + * http://www.FreeRTOS.org/FAQHelp.html * + * * + *************************************************************************** + + + http://www.FreeRTOS.org - Documentation, training, latest information, + license and contact details. + + http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products, + including FreeRTOS+Trace - an indispensable productivity tool. + + Real Time Engineers ltd license FreeRTOS to High Integrity Systems, who sell + the code with commercial support, indemnification, and middleware, under + the OpenRTOS brand: http://www.OpenRTOS.com. High Integrity Systems also + provide a safety engineered and independently SIL3 certified version under + the SafeRTOS brand: http://www.SafeRTOS.com. +*/ + + +#ifndef PORTMACRO_H +#define PORTMACRO_H + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * Port specific definitions. + * + * The settings in this file configure FreeRTOS correctly for the + * given hardware and compiler. + * + * These settings should not be altered. + *----------------------------------------------------------- + */ + +/* Type definitions. */ +#define portCHAR char +#define portFLOAT float +#define portDOUBLE double +#define portLONG long +#define portSHORT short +#define portSTACK_TYPE unsigned portLONG +#define portBASE_TYPE long + +#if( configUSE_16_BIT_TICKS == 1 ) + typedef unsigned portSHORT portTickType; + #define portMAX_DELAY ( portTickType ) 0xffff +#else + typedef unsigned portLONG portTickType; + #define portMAX_DELAY ( portTickType ) 0xffffffff +#endif +/*-----------------------------------------------------------*/ + +/* Architecture specifics. */ +#define portSTACK_GROWTH ( -1 ) +#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) +#define portBYTE_ALIGNMENT 8 +/*-----------------------------------------------------------*/ + + +/* Scheduler utilities. */ +extern void vPortYieldFromISR( void ); + +#define portYIELD() vPortYieldFromISR() + +#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() +/*-----------------------------------------------------------*/ + + +/* Critical section management. */ + +/* + * Set basepri to portMAX_SYSCALL_INTERRUPT_PRIORITY without effecting other + * registers. r0 is clobbered. + */ +#define portSET_INTERRUPT_MASK() \ + __asm volatile \ + ( \ + " mov r0, %0 \n" \ + " msr basepri, r0 \n" \ + ::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY):"r0" \ + ) + +/* + * Set basepri back to 0 without effective other registers. + * r0 is clobbered. FAQ: Setting BASEPRI to 0 is not a bug. Please see + * http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before disagreeing. + */ +#define portCLEAR_INTERRUPT_MASK() \ + __asm volatile \ + ( \ + " mov r0, #0 \n" \ + " msr basepri, r0 \n" \ + :::"r0" \ + ) + +/* FAQ: Setting BASEPRI to 0 in portCLEAR_INTERRUPT_MASK_FROM_ISR() is not a +bug. Please see http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html before +disagreeing. */ +#define portSET_INTERRUPT_MASK_FROM_ISR() 0;portSET_INTERRUPT_MASK() +#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) portCLEAR_INTERRUPT_MASK();(void)x + + +extern void vPortEnterCritical( void ); +extern void vPortExitCritical( void ); + +#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() +#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() +#define portENTER_CRITICAL() vPortEnterCritical() +#define portEXIT_CRITICAL() vPortExitCritical() + +/* There are an uneven number of items on the initial stack, so +portALIGNMENT_ASSERT_pxCurrentTCB() will trigger false positive asserts. */ +#define portALIGNMENT_ASSERT_pxCurrentTCB ( void ) + +/*-----------------------------------------------------------*/ + +/* Task function macros as described on the FreeRTOS.org WEB site. */ +#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) +#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) + +#define portNOP() + +#ifdef __cplusplus +} +#endif + +#endif /* PORTMACRO_H */ + diff --git a/flight/PiOS/inc/pios_eeprom.h b/flight/PiOS/inc/pios_eeprom.h index 14acc595e..2ab9a0a90 100644 --- a/flight/PiOS/inc/pios_eeprom.h +++ b/flight/PiOS/inc/pios_eeprom.h @@ -1,50 +1,50 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_EEPROM EEPROM reading/writing functions - * @brief PIOS EEPROM reading/writing functions - * @{ - * - * @file pios_eeprom.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @brief COM layer functions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_EEPROM_H -#define PIOS_EEPROM_H - -/* Public Structures */ -struct pios_eeprom_cfg { - uint32_t base_address; - uint32_t max_size; -}; - -/* Public Functions */ -extern void PIOS_EEPROM_Init(const struct pios_eeprom_cfg *cfg); -extern int32_t PIOS_EEPROM_Save(uint8_t *data, uint32_t len); -extern int32_t PIOS_EEPROM_Load(uint8_t *data, uint32_t len); - -#endif /* PIOS_EEPROM_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_EEPROM EEPROM reading/writing functions + * @brief PIOS EEPROM reading/writing functions + * @{ + * + * @file pios_eeprom.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief COM layer functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_EEPROM_H +#define PIOS_EEPROM_H + +/* Public Structures */ +struct pios_eeprom_cfg { + uint32_t base_address; + uint32_t max_size; +}; + +/* Public Functions */ +extern void PIOS_EEPROM_Init(const struct pios_eeprom_cfg *cfg); +extern int32_t PIOS_EEPROM_Save(uint8_t *data, uint32_t len); +extern int32_t PIOS_EEPROM_Load(uint8_t *data, uint32_t len); + +#endif /* PIOS_EEPROM_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_iap.h b/flight/PiOS/inc/pios_iap.h index 5ea916970..da36e434c 100644 --- a/flight/PiOS/inc/pios_iap.h +++ b/flight/PiOS/inc/pios_iap.h @@ -1,45 +1,45 @@ -/*! - * @File iap.h - * @Brief Header file for the In-Application-Programming Module - * - * Created on: Sep 6, 2010 - * Author: joe - */ - -#ifndef PIOS_IAP_H -#define PIOS_IAP_H - - -/**************************************************************************************** - * Header files - ****************************************************************************************/ - -/***************************************************************************************** - * Public Definitions/Macros - ****************************************************************************************/ -#if defined(STM32F4XX) -#define MAGIC_REG_1 RTC_BKP_DR1 -#define MAGIC_REG_2 RTC_BKP_DR2 -#define IAP_BOOTCOUNT RTC_BKP_DR3 -#else -#define MAGIC_REG_1 BKP_DR1 -#define MAGIC_REG_2 BKP_DR2 -#define IAP_BOOTCOUNT BKP_DR3 -#endif - -/**************************************************************************************** - * Public Functions - ****************************************************************************************/ -void PIOS_IAP_Init(void); -uint32_t PIOS_IAP_CheckRequest( void ); -void PIOS_IAP_SetRequest1(void); -void PIOS_IAP_SetRequest2(void); -void PIOS_IAP_ClearRequest(void); -uint16_t PIOS_IAP_ReadBootCount(void); -void PIOS_IAP_WriteBootCount(uint16_t); - -/**************************************************************************************** - * Public Data - ****************************************************************************************/ - -#endif /* PIOS_IAP_H */ +/*! + * @File iap.h + * @Brief Header file for the In-Application-Programming Module + * + * Created on: Sep 6, 2010 + * Author: joe + */ + +#ifndef PIOS_IAP_H +#define PIOS_IAP_H + + +/**************************************************************************************** + * Header files + ****************************************************************************************/ + +/***************************************************************************************** + * Public Definitions/Macros + ****************************************************************************************/ +#if defined(STM32F4XX) +#define MAGIC_REG_1 RTC_BKP_DR1 +#define MAGIC_REG_2 RTC_BKP_DR2 +#define IAP_BOOTCOUNT RTC_BKP_DR3 +#else +#define MAGIC_REG_1 BKP_DR1 +#define MAGIC_REG_2 BKP_DR2 +#define IAP_BOOTCOUNT BKP_DR3 +#endif + +/**************************************************************************************** + * Public Functions + ****************************************************************************************/ +void PIOS_IAP_Init(void); +uint32_t PIOS_IAP_CheckRequest( void ); +void PIOS_IAP_SetRequest1(void); +void PIOS_IAP_SetRequest2(void); +void PIOS_IAP_ClearRequest(void); +uint16_t PIOS_IAP_ReadBootCount(void); +void PIOS_IAP_WriteBootCount(uint16_t); + +/**************************************************************************************** + * Public Data + ****************************************************************************************/ + +#endif /* PIOS_IAP_H */ diff --git a/flight/PiOS/inc/pios_overo.h b/flight/PiOS/inc/pios_overo.h index 9e0f1d4e7..a7e984d90 100644 --- a/flight/PiOS/inc/pios_overo.h +++ b/flight/PiOS/inc/pios_overo.h @@ -1,42 +1,42 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_OVERO Overo Functions - * @{ - * - * @file pios_overo.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @brief Overo functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_OVERO_H -#define PIOS_OVERO_H - -extern void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id); -extern int32_t PIOS_OVERO_GetPacketCount(uint32_t overo_id); -extern int32_t PIOS_OVERO_GetWrittenBytes(uint32_t overo_id); - -#endif /* PIOS_OVERO_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_OVERO Overo Functions + * @{ + * + * @file pios_overo.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Overo functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_OVERO_H +#define PIOS_OVERO_H + +extern void PIOS_OVERO_DMA_irq_handler(uint32_t overo_id); +extern int32_t PIOS_OVERO_GetPacketCount(uint32_t overo_id); +extern int32_t PIOS_OVERO_GetWrittenBytes(uint32_t overo_id); + +#endif /* PIOS_OVERO_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_overo_priv.h b/flight/PiOS/inc/pios_overo_priv.h index b1a2e40a4..990a922ac 100644 --- a/flight/PiOS/inc/pios_overo_priv.h +++ b/flight/PiOS/inc/pios_overo_priv.h @@ -1,58 +1,58 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_OVERO Overo Functions - * @{ - * - * @file pios_overo_priv.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @brief Overo functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_OVERO_PRIV_H -#define PIOS_OVERO_PRIV_H - -#include -#include - -extern const struct pios_com_driver pios_overo_com_driver; - -struct pios_overo_cfg { - SPI_TypeDef *regs; - uint32_t remap; /* GPIO_Remap_* or GPIO_AF_* */ - SPI_InitTypeDef init; - bool use_crc; - struct stm32_dma dma; - struct stm32_gpio sclk; - struct stm32_gpio miso; - struct stm32_gpio mosi; - uint32_t slave_count; - struct stm32_gpio ssel[]; -}; - -extern int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg); - -#endif /* PIOS_OVERO_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_OVERO Overo Functions + * @{ + * + * @file pios_overo_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief Overo functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_OVERO_PRIV_H +#define PIOS_OVERO_PRIV_H + +#include +#include + +extern const struct pios_com_driver pios_overo_com_driver; + +struct pios_overo_cfg { + SPI_TypeDef *regs; + uint32_t remap; /* GPIO_Remap_* or GPIO_AF_* */ + SPI_InitTypeDef init; + bool use_crc; + struct stm32_dma dma; + struct stm32_gpio sclk; + struct stm32_gpio miso; + struct stm32_gpio mosi; + uint32_t slave_count; + struct stm32_gpio ssel[]; +}; + +extern int32_t PIOS_OVERO_Init(uint32_t * overo_id, const struct pios_overo_cfg * cfg); + +#endif /* PIOS_OVERO_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_rfm22b_priv.h b/flight/PiOS/inc/pios_rfm22b_priv.h index 27883311c..a437d727a 100644 --- a/flight/PiOS/inc/pios_rfm22b_priv.h +++ b/flight/PiOS/inc/pios_rfm22b_priv.h @@ -1,808 +1,808 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_RFM22B Radio Functions - * @brief PIOS interface for RFM22B Radio - * @{ - * - * @file pios_rfm22b_priv.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @brief RFM22B private definitions. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_RFM22B_PRIV_H -#define PIOS_RFM22B_PRIV_H - -#include -#include -#include -#include -#include "pios_rfm22b.h" -#include "pios_rfm22b_rcvr.h" - -// ************************************ - -#define RFM22_DEVICE_VERSION_V2 0x02 -#define RFM22_DEVICE_VERSION_A0 0x04 -#define RFM22_DEVICE_VERSION_B1 0x06 - -// ************************************ - -#define RFM22_MIN_CARRIER_FREQUENCY_HZ 240000000ul -#define RFM22_MAX_CARRIER_FREQUENCY_HZ 930000000ul - -// ************************************ - -#define BIT0 (1u << 0) -#define BIT1 (1u << 1) -#define BIT2 (1u << 2) -#define BIT3 (1u << 3) -#define BIT4 (1u << 4) -#define BIT5 (1u << 5) -#define BIT6 (1u << 6) -#define BIT7 (1u << 7) - -// ************************************ - -#define RFM22_DEVICE_TYPE 0x00 // R -#define RFM22_DT_MASK 0x1F - -#define RFM22_DEVICE_VERSION 0x01 // R -#define RFM22_DV_MASK 0x1F - -#define RFM22_device_status 0x02 // R -#define RFM22_ds_cps_mask 0x03 // Chip Power State mask -#define RFM22_ds_cps_idle 0x00 // IDLE Chip Power State -#define RFM22_ds_cps_rx 0x01 // RX Chip Power State -#define RFM22_ds_cps_tx 0x02 // TX Chip Power State -//#define RFM22_ds_lockdet 0x04 // -//#define RFM22_ds_freqerr 0x08 // -#define RFM22_ds_headerr 0x10 // Header Error Status. Indicates if the received packet has a header check error -#define RFM22_ds_rxffem 0x20 // RX FIFO Empty Status -#define RFM22_ds_ffunfl 0x40 // RX/TX FIFO Underflow Status -#define RFM22_ds_ffovfl 0x80 // RX/TX FIFO Overflow Status - -#define RFM22_interrupt_status1 0x03 // R -#define RFM22_is1_icrerror BIT0 // CRC Error. When set to 1 the cyclic redundancy check is failed. -#define RFM22_is1_ipkvalid BIT1 // Valid Packet Received.When set to 1 a valid packet has been received. -#define RFM22_is1_ipksent BIT2 // Packet Sent Interrupt. When set to1 a valid packet has been transmitted. -#define RFM22_is1_iext BIT3 // External Interrupt. When set to 1 an interrupt occurred on one of the GPIO�s if it is programmed so. The status can be checked in register 0Eh. See GPIOx Configuration section for the details. -#define RFM22_is1_irxffafull BIT4 // RX FIFO Almost Full.When set to 1 the RX FIFO has met its almost full threshold and needs to be read by the microcontroller. -#define RFM22_is1_ixtffaem BIT5 // TX FIFO Almost Empty. When set to 1 the TX FIFO is almost empty and needs to be filled. -#define RFM22_is1_itxffafull BIT6 // TX FIFO Almost Full. When set to 1 the TX FIFO has met its almost full threshold and needs to be transmitted. -#define RFM22_is1_ifferr BIT7 // FIFO Underflow/Overflow Error. When set to 1 the TX or RX FIFO has overflowed or underflowed. - -#define RFM22_interrupt_status2 0x04 // R -#define RFM22_is2_ipor BIT0 // Power-on-Reset (POR). When the chip detects a Power on Reset above the desired setting this bit will be set to 1. -#define RFM22_is2_ichiprdy BIT1 // Chip Ready (XTAL). When a chip ready event has been detected this bit will be set to 1. -#define RFM22_is2_ilbd BIT2 // Low Battery Detect. When a low battery event is been detected this bit will be set to 1. This interrupt event is saved even if it is not enabled by the mask register bit and causes an interrupt after it is enabled. -#define RFM22_is2_iwut BIT3 // Wake-Up-Timer. On the expiration of programmed wake-up timer this bit will be set to 1. -#define RFM22_is2_irssi BIT4 // RSSI. When RSSI level exceeds the programmed threshold this bit will be set to 1. -#define RFM22_is2_ipreainval BIT5 // Invalid Preamble Detected. When the preamble is not found within a period of time set by the invalid preamble detection threshold in Register 54h, this bit will be set to 1. -#define RFM22_is2_ipreaval BIT6 // Valid Preamble Detected. When a preamble is detected this bit will be set to 1. -#define RFM22_is2_iswdet BIT7 // Sync Word Detected. When a sync word is detected this bit will be set to 1. - -#define RFM22_interrupt_enable1 0x05 // R/W -#define RFM22_ie1_encrcerror BIT0 // Enable CRC Error. When set to 1 the CRC Error interrupt will be enabled. -#define RFM22_ie1_enpkvalid BIT1 // Enable Valid Packet Received. When ipkvalid = 1 the Valid Packet Received Interrupt will be enabled. -#define RFM22_ie1_enpksent BIT2 // Enable Packet Sent. When ipksent =1 the Packet Sense Interrupt will be enabled. -#define RFM22_ie1_enext BIT3 // Enable External Interrupt. When set to 1 the External Interrupt will be enabled. -#define RFM22_ie1_enrxffafull BIT4 // Enable RX FIFO Almost Full. When set to 1 the RX FIFO Almost Full interrupt will be enabled. -#define RFM22_ie1_entxffaem BIT5 // Enable TX FIFO Almost Empty. When set to 1 the TX FIFO Almost Empty interrupt will be enabled. -#define RFM22_ie1_entxffafull BIT6 // Enable TX FIFO Almost Full. When set to 1 the TX FIFO Almost Full interrupt will be enabled. -#define RFM22_ie1_enfferr BIT7 // Enable FIFO Underflow/Overflow. When set to 1 the FIFO Underflow/Overflow interrupt will be enabled. - -#define RFM22_interrupt_enable2 0x06 // R/W -#define RFM22_ie2_enpor BIT0 // Enable POR. When set to 1 the POR interrupt will be enabled. -#define RFM22_ie2_enchiprdy BIT1 // Enable Chip Ready (XTAL). When set to 1 the Chip Ready interrupt will be enabled. -#define RFM22_ie2_enlbd BIT2 // Enable Low Battery Detect. When set to 1 the Low Battery Detect interrupt will be enabled. -#define RFM22_ie2_enwut BIT3 // Enable Wake-Up Timer. When set to 1 the Wake-Up Timer interrupt will be enabled. -#define RFM22_ie2_enrssi BIT4 // Enable RSSI. When set to 1 the RSSI Interrupt will be enabled. -#define RFM22_ie2_enpreainval BIT5 // Enable Invalid Preamble Detected. When mpreadet =1 the Invalid Preamble Detected Interrupt will be enabled. -#define RFM22_ie2_enpreaval BIT6 // Enable Valid Preamble Detected. When mpreadet =1 the Valid Preamble Detected Interrupt will be enabled. -#define RFM22_ie2_enswdet BIT7 // Enable Sync Word Detected. When mpreadet =1 the Preamble Detected Interrupt will be enabled. - -#define RFM22_op_and_func_ctrl1 0x07 // R/W -#define RFM22_opfc1_xton 0x01 // READY Mode (Xtal is ON). -#define RFM22_opfc1_pllon 0x02 // TUNE Mode (PLL is ON). When pllon = 1 the PLL will remain enabled in Idle State. This will for faster turn-around time at the cost of increased current consumption in Idle State. -#define RFM22_opfc1_rxon 0x04 // RX on in Manual Receiver Mode. Automatically cleared if Multiple Packets config. is disabled and a valid packet received. -#define RFM22_opfc1_txon 0x08 // TX on in Manual Transmit Mode. Automatically cleared in FIFO mode once the packet is sent. Transmission can be aborted during packet transmission, however, when no data has been sent yet, transmission can only be aborted after the device is programmed to �unmodulated carrier� ("Register 71h. Modulation Mode Control 2"). -#define RFM22_opfc1_x32ksel 0x10 // 32,768 kHz Crystal Oscillator Select. 0: RC oscillator 1: 32 kHz crystal -#define RFM22_opfc1_enwt 0x20 // Enable Wake-Up-Timer. Enabled when enwt = 1. If the Wake-up-Timer function is enabled it will operate in any mode and notify the microcontroller through the GPIO interrupt when the timer expires. -#define RFM22_opfc1_enlbd 0x40 // Enable Low Battery Detect. When this bit is set to 1 the Low Battery Detector circuit and threshold comparison will be enabled. -#define RFM22_opfc1_swres 0x80 // Software Register Reset Bit. This bit may be used to reset all registers simultaneously to a DEFAULT state, without the need for sequentially writing to each individual register. The RESET is accomplished by setting swres = 1. This bit will be automatically cleared. - -#define RFM22_op_and_func_ctrl2 0x08 // R/W -#define RFM22_opfc2_ffclrtx 0x01 // TX FIFO Reset/Clear. This has to be a two writes operation: Setting ffclrtx =1 followed by ffclrtx = 0 will clear the contents of the TX FIFO. -#define RFM22_opfc2_ffclrrx 0x02 // RX FIFO Reset/Clear. This has to be a two writes operation: Setting ffclrrx =1 followed by ffclrrx = 0 will clear the contents of the RX FIFO. -#define RFM22_opfc2_enldm 0x04 // Enable Low Duty Cycle Mode. If this bit is set to 1 then the chip turns on the RX regularly. The frequency should be set in the Wake-Up Timer Period register, while the minimum ON time should be set in the Low-Duty Cycle Mode Duration register. The FIFO mode should be enabled also. -#define RFM22_opfc2_autotx 0x08 // Automatic Transmission. When autotx = 1 the transceiver will enter automatically TX State when the FIFO is almost full. When the FIFO is empty it will automatically return to the Idle State. -#define RFM22_opfc2_rxmpk 0x10 // RX Multi Packet. When the chip is selected to use FIFO Mode (dtmod[1:0]) and RX Packet Handling (enpacrx) then it will fill up the FIFO with multiple valid packets if this bit is set, otherwise the transceiver will automatically leave the RX State after the first valid packet has been received. -#define RFM22_opfc2_antdiv_mask 0xE0 // Enable Antenna Diversity. The GPIO must be configured for Antenna Diversity for the algorithm to work properly. - -#define RFM22_xtal_osc_load_cap 0x09 // R/W -#define RFM22_xolc_xlc_mask 0x7F // Tuning Capacitance for the 30 MHz XTAL. -#define RFM22_xolc_xtalshft 0x80 // Additional capacitance to course shift the frequency if xlc[6:0] is not sufficient. Not binary with xlc[6:0]. - -#define RFM22_cpu_output_clk 0x0A // R/W -#define RFM22_coc_30MHz 0x00 -#define RFM22_coc_15MHz 0x01 -#define RFM22_coc_10MHz 0x02 -#define RFM22_coc_4MHz 0x03 -#define RFM22_coc_3MHz 0x04 -#define RFM22_coc_2MHz 0x05 -#define RFM22_coc_1MHz 0x06 -#define RFM22_coc_32768Hz 0x07 -#define RFM22_coc_enlfc 0x08 -#define RFM22_coc_0cycle 0x00 -#define RFM22_coc_128cycles 0x10 -#define RFM22_coc_256cycles 0x20 -#define RFM22_coc_512cycles 0x30 - -#define RFM22_gpio0_config 0x0B // R/W -#define RFM22_gpio0_config_por 0x00 // Power-On-Reset (output) -#define RFM22_gpio0_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output) -#define RFM22_gpio0_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output) -#define RFM22_gpio0_config_ddi 0x03 // Direct Digital Input -#define RFM22_gpio0_config_eife 0x04 // External Interrupt, falling edge (input) -#define RFM22_gpio0_config_eire 0x05 // External Interrupt, rising edge (input) -#define RFM22_gpio0_config_eisc 0x06 // External Interrupt, state change (input) -#define RFM22_gpio0_config_ai 0x07 // ADC Analog Input -#define RFM22_gpio0_config_atni 0x08 // Reserved (Analog Test N Input) -#define RFM22_gpio0_config_atpi 0x09 // Reserved (Analog Test P Input) -#define RFM22_gpio0_config_ddo 0x0A // Direct Digital Output -#define RFM22_gpio0_config_dto 0x0B // Reserved (Digital Test Output) -#define RFM22_gpio0_config_atno 0x0C // Reserved (Analog Test N Output) -#define RFM22_gpio0_config_atpo 0x0D // Reserved (Analog Test P Output) -#define RFM22_gpio0_config_rv 0xOE // Reference Voltage (output) -#define RFM22_gpio0_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output) -#define RFM22_gpio0_config_txd 0x10 // TX Data input for direct modulation (input) -#define RFM22_gpio0_config_err 0x11 // External Retransmission Request (input) -#define RFM22_gpio0_config_txstate 0x12 // TX State (output) -#define RFM22_gpio0_config_txfifoaf 0x13 // TX FIFO Almost Full (output) -#define RFM22_gpio0_config_rxd 0x14 // RX Data (output) -#define RFM22_gpio0_config_rxstate 0x15 // RX State (output) -#define RFM22_gpio0_config_rxfifoaf 0x16 // RX FIFO Almost Full (output) -#define RFM22_gpio0_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output) -#define RFM22_gpio0_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output) -#define RFM22_gpio0_config_vpd 0x19 // Valid Preamble Detected (output) -#define RFM22_gpio0_config_ipd 0x1A // Invalid Preamble Detected (output) -#define RFM22_gpio0_config_swd 0x1B // Sync Word Detected (output) -#define RFM22_gpio0_config_cca 0x1C // Clear Channel Assessment (output) -#define RFM22_gpio0_config_vdd 0x1D // VDD -#define RFM22_gpio0_config_pup 0x20 -#define RFM22_gpio0_config_drv0 0x00 // output drive level -#define RFM22_gpio0_config_drv1 0x40 // output drive level -#define RFM22_gpio0_config_drv2 0x80 // output drive level -#define RFM22_gpio0_config_drv3 0xC0 // output drive level - -#define RFM22_gpio1_config 0x0C // R/W -#define RFM22_gpio1_config_ipor 0x00 // Inverted Power-On-Reset (output) -#define RFM22_gpio1_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output) -#define RFM22_gpio1_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output) -#define RFM22_gpio1_config_ddi 0x03 // Direct Digital Input -#define RFM22_gpio1_config_eife 0x04 // External Interrupt, falling edge (input) -#define RFM22_gpio1_config_eire 0x05 // External Interrupt, rising edge (input) -#define RFM22_gpio1_config_eisc 0x06 // External Interrupt, state change (input) -#define RFM22_gpio1_config_ai 0x07 // ADC Analog Input -#define RFM22_gpio1_config_atni 0x08 // Reserved (Analog Test N Input) -#define RFM22_gpio1_config_atpi 0x09 // Reserved (Analog Test P Input) -#define RFM22_gpio1_config_ddo 0x0A // Direct Digital Output -#define RFM22_gpio1_config_dto 0x0B // Reserved (Digital Test Output) -#define RFM22_gpio1_config_atno 0x0C // Reserved (Analog Test N Output) -#define RFM22_gpio1_config_atpo 0x0D // Reserved (Analog Test P Output) -#define RFM22_gpio1_config_rv 0xOE // Reference Voltage (output) -#define RFM22_gpio1_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output) -#define RFM22_gpio1_config_txd 0x10 // TX Data input for direct modulation (input) -#define RFM22_gpio1_config_err 0x11 // External Retransmission Request (input) -#define RFM22_gpio1_config_txstate 0x12 // TX State (output) -#define RFM22_gpio1_config_txfifoaf 0x13 // TX FIFO Almost Full (output) -#define RFM22_gpio1_config_rxd 0x14 // RX Data (output) -#define RFM22_gpio1_config_rxstate 0x15 // RX State (output) -#define RFM22_gpio1_config_rxfifoaf 0x16 // RX FIFO Almost Full (output) -#define RFM22_gpio1_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output) -#define RFM22_gpio1_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output) -#define RFM22_gpio1_config_vpd 0x19 // Valid Preamble Detected (output) -#define RFM22_gpio1_config_ipd 0x1A // Invalid Preamble Detected (output) -#define RFM22_gpio1_config_swd 0x1B // Sync Word Detected (output) -#define RFM22_gpio1_config_cca 0x1C // Clear Channel Assessment (output) -#define RFM22_gpio1_config_vdd 0x1D // VDD -#define RFM22_gpio1_config_pup 0x20 -#define RFM22_gpio1_config_drv0 0x00 // output drive level -#define RFM22_gpio1_config_drv1 0x40 // output drive level -#define RFM22_gpio1_config_drv2 0x80 // output drive level -#define RFM22_gpio1_config_drv3 0xC0 // output drive level - -#define RFM22_gpio2_config 0x0D // R/W -#define RFM22_gpio2_config_mc 0x00 // Microcontroller Clock (output) -#define RFM22_gpio2_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output) -#define RFM22_gpio2_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output) -#define RFM22_gpio2_config_ddi 0x03 // Direct Digital Input -#define RFM22_gpio2_config_eife 0x04 // External Interrupt, falling edge (input) -#define RFM22_gpio2_config_eire 0x05 // External Interrupt, rising edge (input) -#define RFM22_gpio2_config_eisc 0x06 // External Interrupt, state change (input) -#define RFM22_gpio2_config_ai 0x07 // ADC Analog Input -#define RFM22_gpio2_config_atni 0x08 // Reserved (Analog Test N Input) -#define RFM22_gpio2_config_atpi 0x09 // Reserved (Analog Test P Input) -#define RFM22_gpio2_config_ddo 0x0A // Direct Digital Output -#define RFM22_gpio2_config_dto 0x0B // Reserved (Digital Test Output) -#define RFM22_gpio2_config_atno 0x0C // Reserved (Analog Test N Output) -#define RFM22_gpio2_config_atpo 0x0D // Reserved (Analog Test P Output) -#define RFM22_gpio2_config_rv 0xOE // Reference Voltage (output) -#define RFM22_gpio2_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output) -#define RFM22_gpio2_config_txd 0x10 // TX Data input for direct modulation (input) -#define RFM22_gpio2_config_err 0x11 // External Retransmission Request (input) -#define RFM22_gpio2_config_txstate 0x12 // TX State (output) -#define RFM22_gpio2_config_txfifoaf 0x13 // TX FIFO Almost Full (output) -#define RFM22_gpio2_config_rxd 0x14 // RX Data (output) -#define RFM22_gpio2_config_rxstate 0x15 // RX State (output) -#define RFM22_gpio2_config_rxfifoaf 0x16 // RX FIFO Almost Full (output) -#define RFM22_gpio2_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output) -#define RFM22_gpio2_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output) -#define RFM22_gpio2_config_vpd 0x19 // Valid Preamble Detected (output) -#define RFM22_gpio2_config_ipd 0x1A // Invalid Preamble Detected (output) -#define RFM22_gpio2_config_swd 0x1B // Sync Word Detected (output) -#define RFM22_gpio2_config_cca 0x1C // Clear Channel Assessment (output) -#define RFM22_gpio2_config_vdd 0x1D // VDD -#define RFM22_gpio2_config_pup 0x20 -#define RFM22_gpio2_config_drv0 0x00 // output drive level -#define RFM22_gpio2_config_drv1 0x40 // output drive level -#define RFM22_gpio2_config_drv2 0x80 // output drive level -#define RFM22_gpio2_config_drv3 0xC0 // output drive level - -#define RFM22_io_port_config 0x0E // R/W -#define RFM22_io_port_extitst2 0x40 // External Interrupt Status. If the GPIO2 is programmed to be external interrupt sources then the status can be read here. -#define RFM22_io_port_extitst1 0x20 // External Interrupt Status. If the GPIO1 is programmed to be external interrupt sources then the status can be read here. -#define RFM22_io_port_extitst0 0x10 // External Interrupt Status. If the GPIO0 is programmed to be external interrupt sources then the status can be read here. -#define RFM22_io_port_itsdo 0x08 // Interrupt Request Output on the SDO Pin. nIRQ output is present on the SDO pin if this bit is set and the nSEL input is inactive (high). -#define RFM22_io_port_dio2 0x04 // Direct I/O for GPIO2. If the GPIO2 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO2 is configured to be a direct input then the value of the pin can be read here. -#define RFM22_io_port_dio1 0x02 // Direct I/O for GPIO1. If the GPIO1 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO1 is configured to be a direct input then the value of the pin can be read here. -#define RFM22_io_port_dio0 0x01 // Direct I/O for GPIO0. If the GPIO0 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO0 is configured to be a direct input then the value of the pin can be read here. -#define RFM22_io_port_default 0x00 // GPIO pins are default - -#define RFM22_adc_config 0x0F // R/W -#define RFM22_ac_adcgain0 0x00 -#define RFM22_ac_adcgain1 0x01 -#define RFM22_ac_adcgain2 0x02 -#define RFM22_ac_adcgain3 0x03 -#define RFM22_ac_adcref_bg 0x00 -#define RFM22_ac_adcref_vdd3 0x08 -#define RFM22_ac_adcref_vdd2 0x0C -#define RFM22_ac_adcsel_temp_sensor 0x00 -#define RFM22_ac_adcsel_gpio0 0x10 -#define RFM22_ac_adcsel_gpio1 0x20 -#define RFM22_ac_adcsel_gpio2 0x30 -#define RFM22_ac_adcsel_gpio01 0x40 -#define RFM22_ac_adcsel_gpio12 0x50 -#define RFM22_ac_adcsel_gpio02 0x60 -#define RFM22_ac_adcsel_gpio_gnd 0x70 -#define RFM22_ac_adcstartbusy 0x80 - -#define RFM22_adc_sensor_amp_offset 0x10 // R/W -#define RFM22_asao_adcoffs_mask 0x0F // ADC Sensor Amplifier Offset. The offset can be calculated as Offset = adcoffs[2:0] x VDD/1000; MSB = adcoffs[3] = Sign bit. - -#define RFM22_adc_value 0x11 // R .. Internal 8 bit ADC Output Value. - -#define RFM22_temp_sensor_calib 0x12 // R/W -#define RFM22_tsc_tstrim_mask 0x0F // Temperature Sensor Trim Value. -#define RFM22_tsc_entstrim 0x10 // Temperature Sensor Trim Enable. -#define RFM22_tsc_entsoffs 0x20 // Temperature Sensor Offset to Convert from K to �C. -#define RFM22_tsc_tsrange0 0x00 // Temperature Sensor Range Selection. �64C to +64C 0.5C resolution -#define RFM22_tsc_tsrange1 0x40 // -40 to +85C with 1.0C resolution -#define RFM22_tsc_tsrange2 0x80 // 0C to 85C with 0.5C resolution -#define RFM22_tsc_tsrange3 0xC0 // -40F to 216F with 1.0F resolution - -#define RFM22_temp_value_offset 0x13 // R/W - -#define RFM22_wakeup_timer_period1 0x14 // R/W -#define RFM22_wakeup_timer_period2 0x15 // R/W -#define RFM22_wakeup_timer_period3 0x16 // R/W - -#define RFM22_wakeup_timer_value1 0x17 // R -#define RFM22_wakeup_timer_value2 0x18 // R - -#define RFM22_low_dutycycle_mode_duration 0x19 // R/W -#define RFM22_low_battery_detector_threshold 0x1A // R/W - -#define RFM22_battery_volateg_level 0x1B // R - -#define RFM22_if_filter_bandwidth 0x1C // R/W -#define RFM22_iffbw_filset_mask 0x0F -#define RFM22_iffbw_ndec_exp_mask 0x70 -#define RFM22_iffbw_dwn3_bypass 0x80 - -#define RFM22_afc_loop_gearshift_override 0x1D // R/W -#define RFM22_afc_lp_gs_ovrd_afcgearl_mask 0x07 // AFC Low Gear Setting. -#define RFM22_afc_lp_gs_ovrd_afcgearh_mask 0x38 // AFC High Gear Setting. -#define RFM22_afc_lp_gs_ovrd_enafc 0x40 // AFC Enable. -#define RFM22_afc_lp_gs_ovrd_afcbd 0x80 // If set, the tolerated AFC frequency error will be halved. - -#define RFM22_afc_timing_control 0x1E // R/W - -#define RFM22_clk_recovery_gearshift_override 0x1F // R/W -#define RFM22_clk_recovery_oversampling_ratio 0x20 // R/W -#define RFM22_clk_recovery_offset2 0x21 // R/W -#define RFM22_clk_recovery_offset1 0x22 // R/W -#define RFM22_clk_recovery_offset0 0x23 // R/W -#define RFM22_clk_recovery_timing_loop_gain1 0x24 // R/W -#define RFM22_clk_recovery_timing_loop_gain0 0x25 // R/W - -#define RFM22_rssi 0x26 // R -#define RFM22_rssi_threshold_clear_chan_indicator 0x27 // R/W - -#define RFM22_antenna_diversity_register1 0x28 // R -#define RFM22_antenna_diversity_register2 0x29 // R - -#define RFM22_afc_limiter 0x2A // R/W .. AFC_pull_in_range = �AFCLimiter[7:0] x (hbsel+1) x 625 Hz - -#define RFM22_afc_correction_read 0x2B // R - -#define RFM22_ook_counter_value1 0x2C // R/W -#define RFM22_ook_counter_value2 0x2D // R/W - -#define RFM22_slicer_peak_hold 0x2E // R/W - -#define RFM22_data_access_control 0x30 // R/W -#define RFM22_dac_crc_ccitt 0x00 // -#define RFM22_dac_crc_crc16 0x01 // -#define RFM22_dac_crc_iec16 0x02 // -#define RFM22_dac_crc_biacheva 0x03 // -#define RFM22_dac_encrc 0x04 // CRC Enable. Cyclic Redundancy Check generation is enabled if this bit is set. -#define RFM22_dac_enpactx 0x08 // Enable Packet TX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpactx = 1 will enable automatic packet handling in the TX path. Register 30�4D allow for various configurations of the packet structure. Setting enpactx = 0 will not do any packet handling in the TX path. It will only transmit what is loaded to the FIFO. -#define RFM22_dac_skip2ph 0x10 // Skip 2nd Phase of Preamble Detection. If set, we skip the second phase of the preamble detection (under certain conditions) if antenna diversity is enabled. -#define RFM22_dac_crcdonly 0x20 // CRC Data Only Enable. When this bit is set to 1 the CRC is calculated on and checked against the packet data fields only. -#define RFM22_dac_lsbfrst 0x40 // LSB First Enable. The LSB of the data will be transmitted/received first if this bit is set. -#define RFM22_dac_enpacrx 0x80 // Enable Packet RX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpacrx = 1 will enable automatic packet handling in the RX path. Register 30�4D allow for various configurations of the packet structure. Setting enpacrx = 0 will not do any packet handling in the RX path. It will only receive everything after the sync word and fill up the RX FIFO. - -#define RFM22_ezmac_status 0x31 // R -#define RFM22_ezmac_status_pksent 0x01 // Packet Sent. A 1 a packet has been sent by the radio. (Same bit as in register 03, but reading it does not reset the IRQ) -#define RFM22_ezmac_status_pktx 0x02 // Packet Transmitting. When 1 the radio is currently transmitting a packet. -#define RFM22_ezmac_status_crcerror 0x04 // CRC Error. When 1 a Cyclic Redundancy Check error has been detected. (Same bit as in register 03, but reading it does not reset the IRQ) -#define RFM22_ezmac_status_pkvalid 0x08 // Valid Packet Received. When a 1 a valid packet has been received by the receiver. (Same bit as in register 03, but reading it does not reset the IRQ) -#define RFM22_ezmac_status_pkrx 0x10 // Packet Receiving. When 1 the radio is currently receiving a valid packet. -#define RFM22_ezmac_status_pksrch 0x20 // Packet Searching. When 1 the radio is searching for a valid packet. -#define RFM22_ezmac_status_rxcrc1 0x40 // If high, it indicates the last CRC received is all one�s. May indicated Transmitter underflow in case of CRC error. - -#define RFM22_header_control1 0x32 // R/W -#define RFM22_header_cntl1_bcen_none 0x00 // No broadcast address enable. -#define RFM22_header_cntl1_bcen_0 0x10 // Broadcast address enable for header byte 0. -#define RFM22_header_cntl1_bcen_1 0x20 // Broadcast address enable for header byte 1. -#define RFM22_header_cntl1_bcen_2 0x40 // Broadcast address enable for header byte 2. -#define RFM22_header_cntl1_bcen_3 0x80 // Broadcast address enable for header byte 3. -#define RFM22_header_cntl1_hdch_none 0x00 // No Received Header check -#define RFM22_header_cntl1_hdch_0 0x01 // Received Header check for byte 0. -#define RFM22_header_cntl1_hdch_1 0x02 // Received Header check for byte 1. -#define RFM22_header_cntl1_hdch_2 0x04 // Received Header check for byte 2. -#define RFM22_header_cntl1_hdch_3 0x08 // Received Header check for byte 3. - -#define RFM22_header_control2 0x33 // R/W -#define RFM22_header_cntl2_prealen 0x01 // MSB of Preamble Length. See register Preamble Length. -#define RFM22_header_cntl2_synclen_3 0x00 // Synchronization Word 3 -#define RFM22_header_cntl2_synclen_32 0x02 // Synchronization Word 3 followed by 2 -#define RFM22_header_cntl2_synclen_321 0x04 // Synchronization Word 3 followed by 2 followed by 1 -#define RFM22_header_cntl2_synclen_3210 0x06 // Synchronization Word 3 followed by 2 followed by 1 followed by 0 -#define RFM22_header_cntl2_fixpklen 0x08 // Fix Packet Length. When fixpklen = 1 the packet length (pklen[7:0]) is not included in the header. When fixpklen = 0 the packet length is included in the header. -#define RFM22_header_cntl2_hdlen_none 0x00 // no header -#define RFM22_header_cntl2_hdlen_3 0x10 // header 3 -#define RFM22_header_cntl2_hdlen_32 0x20 // header 3 and 2 -#define RFM22_header_cntl2_hdlen_321 0x30 // header 3 and 2 and 1 -#define RFM22_header_cntl2_hdlen_3210 0x40 // header 3 and 2 and 1 and 0 -#define RFM22_header_cntl2_skipsyn 0x80 // If high, the system will ignore the syncword search timeout reset. The chip will not return to searching for Preamble, but instead will remain searching for Sync word. - -#define RFM22_preamble_length 0x34 // R/W - -#define RFM22_preamble_detection_ctrl1 0x35 // R/W -#define RFM22_pre_det_ctrl1_preath_mask 0xF8 // Number of nibbles processed during detection. -#define RFM22_pre_det_ctrl1_rssi_offset_mask 0x07 // Value added as offset to RSSI calculation. Every increment in this register results in an increment of +4 dB in the RSSI. - -#define RFM22_sync_word3 0x36 // R/W -#define RFM22_sync_word2 0x37 // R/W -#define RFM22_sync_word1 0x38 // R/W -#define RFM22_sync_word0 0x39 // R/W - -#define RFM22_transmit_header3 0x3A // R/W -#define RFM22_transmit_header2 0x3B // R/W -#define RFM22_transmit_header1 0x3C // R/W -#define RFM22_transmit_header0 0x3D // R/W - -#define RFM22_transmit_packet_length 0x3E // R/W - -#define RFM22_check_header3 0x3F // R/W -#define RFM22_check_header2 0x40 // R/W -#define RFM22_check_header1 0x41 // R/W -#define RFM22_check_header0 0x42 // R/W - -#define RFM22_header_enable3 0x43 // R/W -#define RFM22_header_enable2 0x44 // R/W -#define RFM22_header_enable1 0x45 // R/W -#define RFM22_header_enable0 0x46 // R/W - -#define RFM22_received_header3 0x47 // R -#define RFM22_received_header2 0x48 // R -#define RFM22_received_header1 0x49 // R -#define RFM22_received_header0 0x4A // R - -#define RFM22_received_packet_length 0x4B // R - -#define RFM22_adc8_control 0x4F // R/W -/* -#define RFM22_analog_test_bus 0x50 // R/W -#define RFM22_digital_test_bus 0x51 // R/W -#define RFM22_tx_ramp_control 0x52 // R/W -#define RFM22_pll_tune_time 0x53 // R/W - -#define RFM22_calibration_control 0x55 // R/W - -#define RFM22_modem_test 0x56 // R/W - -#define RFM22_chargepump_test 0x57 // R/W -#define RFM22_chargepump_current_trimming_override 0x58 // R/W - -#define RFM22_divider_current_trimming 0x59 // R/W - -#define RFM22_vco_current_trimming 0x5A // R/W -#define RFM22_vco_calibration_override 0x5B // R/W - -#define RFM22_synthersizer_test 0x5C // R/W - -#define RFM22_block_enable_override1 0x5D // R/W -#define RFM22_block_enable_override2 0x5E // R/W -#define RFM22_block_enable_override3 0x5F // R/W -*/ -#define RFM22_channel_filter_coeff_addr 0x60 // R/W -#define RFM22_ch_fil_coeff_ad_inv_pre_th_mask 0xF0 // -#define RFM22_ch_fil_coeff_ad_chfiladd_mask 0x0F // Channel Filter Coefficient Look-up Table Address. The address for channel filter coefficients used in the RX path. - - -//#define RFM22_channel_filter_coeff_value 0x61 // R/W - -#define RFM22_xtal_osc_por_ctrl 0x62 // R/W -#define RFM22_xtal_osc_por_ctrl_pwst_mask 0xE0 // Internal Power States of the Chip. -#define RFM22_xtal_osc_por_ctrl_clkhyst 0x10 // Clock Hysteresis Setting. -#define RFM22_xtal_osc_por_ctrl_enbias2x 0x08 // 2 Times Higher Bias Current Enable. -#define RFM22_xtal_osc_por_ctrl_enamp2x 0x04 // 2 Times Higher Amplification Enable. -#define RFM22_xtal_osc_por_ctrl_bufovr 0x02 // Output Buffer Enable Override. -#define RFM22_xtal_osc_por_ctrl_enbuf 0x01 // Output Buffer Enable. -/* -#define RFM22_rc_osc_coarse_calbration_override 0x63 // R/W -#define RFM22_rc_osc_fine_calbration_override 0x64 // R/W - -#define RFM22_ldo_control_override 0x65 // R/W -#define RFM22_ldo_level_setting 0x66 // R/W - -#define RFM22_deltasigma_adc_tuning1 0x67 // R/W -#define RFM22_deltasigma_adc_tuning2 0x68 // R/W -*/ -#define RFM22_agc_override1 0x69 // R/W -#define RFM22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0. -#define RFM22_agc_ovr1_agcen 0x20 // Automatic Gain Control Enable. When this bit is set then the result of the control can be read out from bits [4:0], otherwise the gain can be controlled manually by writing into bits [4:0]. -#define RFM22_agc_ovr1_lnagain 0x10 // LNA Gain Select. 0 = min gain = 5dB, 1 = max gain = 25 dB. -#define RFM22_agc_ovr1_pga_mask 0x0F // PGA Gain Override Value. - -//#define RFM22_agc_override2 0x6A // R/W - -//#define RFM22_gfsk_fir_coeff_addr 0x6B // R/W -//#define RFM22_gfsk_fir_coeff_value 0x6C // R/W - -#define RFM22_tx_power 0x6D // R/W -#define RFM22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times. -#define RFM22_tx_pwr_papeaklvl_0 0x10 // " " -#define RFM22_tx_pwr_papeaklvl_1 0x20 // PA Peak Detect Level (direct from register). 00 = 6.5, 01 = 7, 10 = 7.5, 11 = 8, 00 = default -#define RFM22_tx_pwr_papeaken 0x40 // PA Peak Detector Enable. -#define RFM22_tx_pwr_papeakval 0x80 // PA Peak Detector Value Read Register. Reading a 1 in this register when the papeaken=1 then the PA drain voltage is too high and the match network needs adjusting for optimal efficiency. - -#define RFM22_tx_data_rate1 0x6E // R/W -#define RFM22_tx_data_rate0 0x6F // R/W - -#define RFM22_modulation_mode_control1 0x70 // R/W -#define RFM22_mmc1_enwhite 0x01 // Data Whitening is Enabled if this bit is set. -#define RFM22_mmc1_enmanch 0x02 // Manchester Coding is Enabled if this bit is set. -#define RFM22_mmc1_enmaninv 0x04 // Manchester Data Inversion is Enabled if this bit is set. -#define RFM22_mmc1_manppol 0x08 // Manchester Preamble Polarity (will transmit a series of 1 if set, or series of 0 if reset). -#define RFM22_mmc1_enphpwdn 0x10 // If set, the Packet Handler will be powered down when chip is in low power mode. -#define RFM22_mmc1_txdtrtscale 0x20 // This bit should be set for Data Rates below 30 kbps. - -#define RFM22_modulation_mode_control2 0x71 // R/W -#define RFM22_mmc2_modtyp_mask 0x03 // Modulation type. -#define RFM22_mmc2_modtyp_none 0x00 // -#define RFM22_mmc2_modtyp_ook 0x01 // -#define RFM22_mmc2_modtyp_fsk 0x02 // -#define RFM22_mmc2_modtyp_gfsk 0x03 // -#define RFM22_mmc2_fd 0x04 // MSB of Frequency Deviation Setting, see "Register 72h. Frequency Deviation". -#define RFM22_mmc2_eninv 0x08 // Invert TX and RX Data. -#define RFM22_mmc2_dtmod_mask 0x30 // Modulation source. -#define RFM22_mmc2_dtmod_dm_gpio 0x00 // -#define RFM22_mmc2_dtmod_dm_sdi 0x10 // -#define RFM22_mmc2_dtmod_fifo 0x20 // -#define RFM22_mmc2_dtmod_pn9 0x30 // -#define RFM22_mmc2_trclk_mask 0xC0 // TX Data Clock Configuration. -#define RFM22_mmc2_trclk_clk_none 0x00 // -#define RFM22_mmc2_trclk_clk_gpio 0x40 // -#define RFM22_mmc2_trclk_clk_sdo 0x80 // -#define RFM22_mmc2_trclk_clk_nirq 0xC0 // - -#define RFM22_frequency_deviation 0x72 // R/W - -#define RFM22_frequency_offset1 0x73 // R/W -#define RFM22_frequency_offset2 0x74 // R/W - -#define RFM22_frequency_band_select 0x75 // R/W -#define RFM22_fb_mask 0x1F -#define RFM22_fbs_hbsel 0x20 -#define RFM22_fbs_sbse 0x40 - -#define RFM22_nominal_carrier_frequency1 0x76 // R/W -#define RFM22_nominal_carrier_frequency0 0x77 // R/W - -#define RFM22_frequency_hopping_channel_select 0x79 // R/W -#define RFM22_frequency_hopping_step_size 0x7A // R/W - -#define RFM22_tx_fifo_control1 0x7C // R/W .. TX FIFO Almost Full Threshold (0 - 63) -#define RFM22_tx_fifo_control1_mask 0x3F - -#define RFM22_tx_fifo_control2 0x7D // R/W .. TX FIFO Almost Empty Threshold (0 - 63) -#define RFM22_tx_fifo_control2_mask 0x3F - -#define RFM22_rx_fifo_control 0x7E // R/W .. RX FIFO Almost Full Threshold (0 - 63) -#define RFM22_rx_fifo_control_mask 0x3F - -#define RFM22_fifo_access 0x7F // R/W - - -// External type definitions - -typedef int16_t (*t_rfm22_TxDataByteCallback) (void); -typedef bool (*t_rfm22_RxDataCallback) (void *data, uint8_t len); -enum pios_rfm22b_dev_magic { - PIOS_RFM22B_DEV_MAGIC = 0x68e971b6, -}; - -enum pios_rfm22b_state { - RFM22B_STATE_UNINITIALIZED, - RFM22B_STATE_INITIALIZING, - RFM22B_STATE_INITIALIZED, - RFM22B_STATE_INITIATING_CONNECTION, - RFM22B_STATE_WAIT_FOR_CONNECTION, - RFM22B_STATE_REQUESTING_CONNECTION, - RFM22B_STATE_ACCEPTING_CONNECTION, - RFM22B_STATE_CONNECTION_ACCEPTED, - RFM22B_STATE_RX_MODE, - RFM22B_STATE_WAIT_PREAMBLE, - RFM22B_STATE_WAIT_SYNC, - RFM22B_STATE_RX_DATA, - RFM22B_STATE_RX_FAILURE, - RFM22B_STATE_RECEIVING_STATUS, - RFM22B_STATE_TX_START, - RFM22B_STATE_TX_DATA, - RFM22B_STATE_TX_FAILURE, - RFM22B_STATE_SENDING_ACK, - RFM22B_STATE_SENDING_NACK, - RFM22B_STATE_RECEIVING_ACK, - RFM22B_STATE_RECEIVING_NACK, - RFM22B_STATE_TIMEOUT, - RFM22B_STATE_ERROR, - RFM22B_STATE_FATAL_ERROR, - - RFM22B_STATE_NUM_STATES // Must be last -}; - -enum pios_rfm22b_event { - RFM22B_EVENT_INT_RECEIVED, - RFM22B_EVENT_INITIALIZE, - RFM22B_EVENT_INITIALIZED, - RFM22B_EVENT_REQUEST_CONNECTION, - RFM22B_EVENT_WAIT_FOR_CONNECTION, - RFM22B_EVENT_CONNECTION_REQUESTED, - RFM22B_EVENT_CONNECTION_ACCEPTED, - RFM22B_EVENT_PACKET_ACKED, - RFM22B_EVENT_PACKET_NACKED, - RFM22B_EVENT_ACK_TIMEOUT, - RFM22B_EVENT_RX_MODE, - RFM22B_EVENT_PREAMBLE_DETECTED, - RFM22B_EVENT_SYNC_DETECTED, - RFM22B_EVENT_RX_COMPLETE, - RFM22B_EVENT_RX_ERROR, - RFM22B_EVENT_STATUS_RECEIVED, - RFM22B_EVENT_TX_START, - RFM22B_EVENT_FAILURE, - RFM22B_EVENT_TIMEOUT, - RFM22B_EVENT_ERROR, - RFM22B_EVENT_FATAL_ERROR, - - RFM22B_EVENT_NUM_EVENTS // Must be last -}; - -#define RFM22B_RX_PACKET_STATS_LEN 4 -enum pios_rfm22b_rx_packet_status { - RFM22B_GOOD_RX_PACKET = 0x00, - RFM22B_CORRECTED_RX_PACKET = 0x01, - RFM22B_ERROR_RX_PACKET = 0x2, - RFM22B_RESENT_TX_PACKET = 0x3 -}; - -typedef struct { - uint32_t pairID; - int8_t rssi; - int8_t afc_correction; - uint8_t lastContact; -} rfm22b_pair_stats; - -struct pios_rfm22b_dev { - enum pios_rfm22b_dev_magic magic; - struct pios_rfm22b_cfg cfg; - - // The SPI bus information - uint32_t spi_id; - uint32_t slave_num; - - // The device ID - uint32_t deviceID; - - // The destination ID - uint32_t destination_id; - - // Is this device a coordinator? - bool coordinator; - - // The task handle - xTaskHandle taskHandle; - - // The potential paired statistics - rfm22b_pair_stats pair_stats[OPLINKSTATUS_PAIRIDS_NUMELEM]; - - // ISR pending semaphore - xSemaphoreHandle isrPending; - - // The com configuration callback - PIOS_RFM22B_ComConfigCallback com_config_cb; - - // The COM callback functions. - pios_com_callback rx_in_cb; - uint32_t rx_in_context; - pios_com_callback tx_out_cb; - uint32_t tx_out_context; - - // the transmit power to use for data transmissions - uint8_t tx_power; - - // The RF datarate lookup index. - uint8_t datarate; - - // The state machine state and the current event - enum pios_rfm22b_state state; - - // The event queue handle - xQueueHandle eventQueue; - - // device status register - uint8_t device_status; - // interrupt status register 1 - uint8_t int_status1; - // interrupt status register 2 - uint8_t int_status2; - // ezmac status register - uint8_t ezmac_status; - - // The error statistics counters - uint16_t prev_rx_seq_num; - uint32_t rx_packet_stats[RFM22B_RX_PACKET_STATS_LEN]; - - // The packet statistics - struct rfm22b_stats stats; - - // Stats - uint16_t errors; - - // RSSI in dBm - int8_t rssi_dBm; - - // The packet queue handle - xQueueHandle packetQueue; - - // The tx data packet - PHPacket data_packet; - // The current tx packet - PHPacketHandle tx_packet; - // The previous tx packet (waiting for an ACK) - PHPacketHandle prev_tx_packet; - // The tx data read index - uint16_t tx_data_rd; - // The tx data write index - uint16_t tx_data_wr; - // The tx packet sequence number - uint16_t tx_seq; - - // The rx data packet - PHPacket rx_packet; - // The receive buffer write index - uint16_t rx_buffer_wr; - // The receive buffer write index - uint16_t rx_packet_len; - // Is the modem currently in Rx mode? - bool in_rx_mode; - - // The status packet - PHStatusPacket status_packet; - - // The ACK/NACK packet - PHAckNackPacket ack_nack_packet; - -#ifdef PIOS_PPM_RECEIVER - // The PPM packet - PHPpmPacket ppm_packet; -#endif - - // The connection packet. - PHConnectionPacket con_packet; - - // Send flags - bool send_status; - bool send_ppm; - bool send_connection_request; - bool time_to_send; - uint8_t time_to_send_offset; - - // The minimum frequency - uint32_t min_frequency; - // The maximum frequency - uint32_t max_frequency; - // The current nominal frequency - uint32_t frequency_hz; - // The frequency hopping step size - float frequency_step_size; - // current frequency hop channel - uint8_t frequency_hop_channel; - // the frequency hop step size - uint8_t frequency_hop_step_size_reg; - // afc correction reading (in Hz) - int8_t afc_correction_Hz; - - // The maximum time (ms) that it should take to transmit / receive a packet. - uint32_t max_packet_time; - portTickType packet_start_ticks; - portTickType tx_complete_ticks; - portTickType rx_complete_ticks; - uint8_t max_ack_delay; - - // The PPM channel values - uint16_t ppm_channel[PIOS_RFM22B_RCVR_MAX_CHANNELS]; - uint8_t ppm_supv_timer; - bool ppm_fresh; -}; - - -// External function definitions - -bool PIOS_RFM22_EXT_Int(void); -bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev); -void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event, bool inISR); - - -// Global variable definitions - -extern const struct pios_com_driver pios_rfm22b_com_driver; - -#endif /* PIOS_RFM22B_PRIV_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_RFM22B Radio Functions + * @brief PIOS interface for RFM22B Radio + * @{ + * + * @file pios_rfm22b_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief RFM22B private definitions. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_RFM22B_PRIV_H +#define PIOS_RFM22B_PRIV_H + +#include +#include +#include +#include +#include "pios_rfm22b.h" +#include "pios_rfm22b_rcvr.h" + +// ************************************ + +#define RFM22_DEVICE_VERSION_V2 0x02 +#define RFM22_DEVICE_VERSION_A0 0x04 +#define RFM22_DEVICE_VERSION_B1 0x06 + +// ************************************ + +#define RFM22_MIN_CARRIER_FREQUENCY_HZ 240000000ul +#define RFM22_MAX_CARRIER_FREQUENCY_HZ 930000000ul + +// ************************************ + +#define BIT0 (1u << 0) +#define BIT1 (1u << 1) +#define BIT2 (1u << 2) +#define BIT3 (1u << 3) +#define BIT4 (1u << 4) +#define BIT5 (1u << 5) +#define BIT6 (1u << 6) +#define BIT7 (1u << 7) + +// ************************************ + +#define RFM22_DEVICE_TYPE 0x00 // R +#define RFM22_DT_MASK 0x1F + +#define RFM22_DEVICE_VERSION 0x01 // R +#define RFM22_DV_MASK 0x1F + +#define RFM22_device_status 0x02 // R +#define RFM22_ds_cps_mask 0x03 // Chip Power State mask +#define RFM22_ds_cps_idle 0x00 // IDLE Chip Power State +#define RFM22_ds_cps_rx 0x01 // RX Chip Power State +#define RFM22_ds_cps_tx 0x02 // TX Chip Power State +//#define RFM22_ds_lockdet 0x04 // +//#define RFM22_ds_freqerr 0x08 // +#define RFM22_ds_headerr 0x10 // Header Error Status. Indicates if the received packet has a header check error +#define RFM22_ds_rxffem 0x20 // RX FIFO Empty Status +#define RFM22_ds_ffunfl 0x40 // RX/TX FIFO Underflow Status +#define RFM22_ds_ffovfl 0x80 // RX/TX FIFO Overflow Status + +#define RFM22_interrupt_status1 0x03 // R +#define RFM22_is1_icrerror BIT0 // CRC Error. When set to 1 the cyclic redundancy check is failed. +#define RFM22_is1_ipkvalid BIT1 // Valid Packet Received.When set to 1 a valid packet has been received. +#define RFM22_is1_ipksent BIT2 // Packet Sent Interrupt. When set to1 a valid packet has been transmitted. +#define RFM22_is1_iext BIT3 // External Interrupt. When set to 1 an interrupt occurred on one of the GPIO�s if it is programmed so. The status can be checked in register 0Eh. See GPIOx Configuration section for the details. +#define RFM22_is1_irxffafull BIT4 // RX FIFO Almost Full.When set to 1 the RX FIFO has met its almost full threshold and needs to be read by the microcontroller. +#define RFM22_is1_ixtffaem BIT5 // TX FIFO Almost Empty. When set to 1 the TX FIFO is almost empty and needs to be filled. +#define RFM22_is1_itxffafull BIT6 // TX FIFO Almost Full. When set to 1 the TX FIFO has met its almost full threshold and needs to be transmitted. +#define RFM22_is1_ifferr BIT7 // FIFO Underflow/Overflow Error. When set to 1 the TX or RX FIFO has overflowed or underflowed. + +#define RFM22_interrupt_status2 0x04 // R +#define RFM22_is2_ipor BIT0 // Power-on-Reset (POR). When the chip detects a Power on Reset above the desired setting this bit will be set to 1. +#define RFM22_is2_ichiprdy BIT1 // Chip Ready (XTAL). When a chip ready event has been detected this bit will be set to 1. +#define RFM22_is2_ilbd BIT2 // Low Battery Detect. When a low battery event is been detected this bit will be set to 1. This interrupt event is saved even if it is not enabled by the mask register bit and causes an interrupt after it is enabled. +#define RFM22_is2_iwut BIT3 // Wake-Up-Timer. On the expiration of programmed wake-up timer this bit will be set to 1. +#define RFM22_is2_irssi BIT4 // RSSI. When RSSI level exceeds the programmed threshold this bit will be set to 1. +#define RFM22_is2_ipreainval BIT5 // Invalid Preamble Detected. When the preamble is not found within a period of time set by the invalid preamble detection threshold in Register 54h, this bit will be set to 1. +#define RFM22_is2_ipreaval BIT6 // Valid Preamble Detected. When a preamble is detected this bit will be set to 1. +#define RFM22_is2_iswdet BIT7 // Sync Word Detected. When a sync word is detected this bit will be set to 1. + +#define RFM22_interrupt_enable1 0x05 // R/W +#define RFM22_ie1_encrcerror BIT0 // Enable CRC Error. When set to 1 the CRC Error interrupt will be enabled. +#define RFM22_ie1_enpkvalid BIT1 // Enable Valid Packet Received. When ipkvalid = 1 the Valid Packet Received Interrupt will be enabled. +#define RFM22_ie1_enpksent BIT2 // Enable Packet Sent. When ipksent =1 the Packet Sense Interrupt will be enabled. +#define RFM22_ie1_enext BIT3 // Enable External Interrupt. When set to 1 the External Interrupt will be enabled. +#define RFM22_ie1_enrxffafull BIT4 // Enable RX FIFO Almost Full. When set to 1 the RX FIFO Almost Full interrupt will be enabled. +#define RFM22_ie1_entxffaem BIT5 // Enable TX FIFO Almost Empty. When set to 1 the TX FIFO Almost Empty interrupt will be enabled. +#define RFM22_ie1_entxffafull BIT6 // Enable TX FIFO Almost Full. When set to 1 the TX FIFO Almost Full interrupt will be enabled. +#define RFM22_ie1_enfferr BIT7 // Enable FIFO Underflow/Overflow. When set to 1 the FIFO Underflow/Overflow interrupt will be enabled. + +#define RFM22_interrupt_enable2 0x06 // R/W +#define RFM22_ie2_enpor BIT0 // Enable POR. When set to 1 the POR interrupt will be enabled. +#define RFM22_ie2_enchiprdy BIT1 // Enable Chip Ready (XTAL). When set to 1 the Chip Ready interrupt will be enabled. +#define RFM22_ie2_enlbd BIT2 // Enable Low Battery Detect. When set to 1 the Low Battery Detect interrupt will be enabled. +#define RFM22_ie2_enwut BIT3 // Enable Wake-Up Timer. When set to 1 the Wake-Up Timer interrupt will be enabled. +#define RFM22_ie2_enrssi BIT4 // Enable RSSI. When set to 1 the RSSI Interrupt will be enabled. +#define RFM22_ie2_enpreainval BIT5 // Enable Invalid Preamble Detected. When mpreadet =1 the Invalid Preamble Detected Interrupt will be enabled. +#define RFM22_ie2_enpreaval BIT6 // Enable Valid Preamble Detected. When mpreadet =1 the Valid Preamble Detected Interrupt will be enabled. +#define RFM22_ie2_enswdet BIT7 // Enable Sync Word Detected. When mpreadet =1 the Preamble Detected Interrupt will be enabled. + +#define RFM22_op_and_func_ctrl1 0x07 // R/W +#define RFM22_opfc1_xton 0x01 // READY Mode (Xtal is ON). +#define RFM22_opfc1_pllon 0x02 // TUNE Mode (PLL is ON). When pllon = 1 the PLL will remain enabled in Idle State. This will for faster turn-around time at the cost of increased current consumption in Idle State. +#define RFM22_opfc1_rxon 0x04 // RX on in Manual Receiver Mode. Automatically cleared if Multiple Packets config. is disabled and a valid packet received. +#define RFM22_opfc1_txon 0x08 // TX on in Manual Transmit Mode. Automatically cleared in FIFO mode once the packet is sent. Transmission can be aborted during packet transmission, however, when no data has been sent yet, transmission can only be aborted after the device is programmed to �unmodulated carrier� ("Register 71h. Modulation Mode Control 2"). +#define RFM22_opfc1_x32ksel 0x10 // 32,768 kHz Crystal Oscillator Select. 0: RC oscillator 1: 32 kHz crystal +#define RFM22_opfc1_enwt 0x20 // Enable Wake-Up-Timer. Enabled when enwt = 1. If the Wake-up-Timer function is enabled it will operate in any mode and notify the microcontroller through the GPIO interrupt when the timer expires. +#define RFM22_opfc1_enlbd 0x40 // Enable Low Battery Detect. When this bit is set to 1 the Low Battery Detector circuit and threshold comparison will be enabled. +#define RFM22_opfc1_swres 0x80 // Software Register Reset Bit. This bit may be used to reset all registers simultaneously to a DEFAULT state, without the need for sequentially writing to each individual register. The RESET is accomplished by setting swres = 1. This bit will be automatically cleared. + +#define RFM22_op_and_func_ctrl2 0x08 // R/W +#define RFM22_opfc2_ffclrtx 0x01 // TX FIFO Reset/Clear. This has to be a two writes operation: Setting ffclrtx =1 followed by ffclrtx = 0 will clear the contents of the TX FIFO. +#define RFM22_opfc2_ffclrrx 0x02 // RX FIFO Reset/Clear. This has to be a two writes operation: Setting ffclrrx =1 followed by ffclrrx = 0 will clear the contents of the RX FIFO. +#define RFM22_opfc2_enldm 0x04 // Enable Low Duty Cycle Mode. If this bit is set to 1 then the chip turns on the RX regularly. The frequency should be set in the Wake-Up Timer Period register, while the minimum ON time should be set in the Low-Duty Cycle Mode Duration register. The FIFO mode should be enabled also. +#define RFM22_opfc2_autotx 0x08 // Automatic Transmission. When autotx = 1 the transceiver will enter automatically TX State when the FIFO is almost full. When the FIFO is empty it will automatically return to the Idle State. +#define RFM22_opfc2_rxmpk 0x10 // RX Multi Packet. When the chip is selected to use FIFO Mode (dtmod[1:0]) and RX Packet Handling (enpacrx) then it will fill up the FIFO with multiple valid packets if this bit is set, otherwise the transceiver will automatically leave the RX State after the first valid packet has been received. +#define RFM22_opfc2_antdiv_mask 0xE0 // Enable Antenna Diversity. The GPIO must be configured for Antenna Diversity for the algorithm to work properly. + +#define RFM22_xtal_osc_load_cap 0x09 // R/W +#define RFM22_xolc_xlc_mask 0x7F // Tuning Capacitance for the 30 MHz XTAL. +#define RFM22_xolc_xtalshft 0x80 // Additional capacitance to course shift the frequency if xlc[6:0] is not sufficient. Not binary with xlc[6:0]. + +#define RFM22_cpu_output_clk 0x0A // R/W +#define RFM22_coc_30MHz 0x00 +#define RFM22_coc_15MHz 0x01 +#define RFM22_coc_10MHz 0x02 +#define RFM22_coc_4MHz 0x03 +#define RFM22_coc_3MHz 0x04 +#define RFM22_coc_2MHz 0x05 +#define RFM22_coc_1MHz 0x06 +#define RFM22_coc_32768Hz 0x07 +#define RFM22_coc_enlfc 0x08 +#define RFM22_coc_0cycle 0x00 +#define RFM22_coc_128cycles 0x10 +#define RFM22_coc_256cycles 0x20 +#define RFM22_coc_512cycles 0x30 + +#define RFM22_gpio0_config 0x0B // R/W +#define RFM22_gpio0_config_por 0x00 // Power-On-Reset (output) +#define RFM22_gpio0_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output) +#define RFM22_gpio0_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output) +#define RFM22_gpio0_config_ddi 0x03 // Direct Digital Input +#define RFM22_gpio0_config_eife 0x04 // External Interrupt, falling edge (input) +#define RFM22_gpio0_config_eire 0x05 // External Interrupt, rising edge (input) +#define RFM22_gpio0_config_eisc 0x06 // External Interrupt, state change (input) +#define RFM22_gpio0_config_ai 0x07 // ADC Analog Input +#define RFM22_gpio0_config_atni 0x08 // Reserved (Analog Test N Input) +#define RFM22_gpio0_config_atpi 0x09 // Reserved (Analog Test P Input) +#define RFM22_gpio0_config_ddo 0x0A // Direct Digital Output +#define RFM22_gpio0_config_dto 0x0B // Reserved (Digital Test Output) +#define RFM22_gpio0_config_atno 0x0C // Reserved (Analog Test N Output) +#define RFM22_gpio0_config_atpo 0x0D // Reserved (Analog Test P Output) +#define RFM22_gpio0_config_rv 0xOE // Reference Voltage (output) +#define RFM22_gpio0_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output) +#define RFM22_gpio0_config_txd 0x10 // TX Data input for direct modulation (input) +#define RFM22_gpio0_config_err 0x11 // External Retransmission Request (input) +#define RFM22_gpio0_config_txstate 0x12 // TX State (output) +#define RFM22_gpio0_config_txfifoaf 0x13 // TX FIFO Almost Full (output) +#define RFM22_gpio0_config_rxd 0x14 // RX Data (output) +#define RFM22_gpio0_config_rxstate 0x15 // RX State (output) +#define RFM22_gpio0_config_rxfifoaf 0x16 // RX FIFO Almost Full (output) +#define RFM22_gpio0_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output) +#define RFM22_gpio0_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output) +#define RFM22_gpio0_config_vpd 0x19 // Valid Preamble Detected (output) +#define RFM22_gpio0_config_ipd 0x1A // Invalid Preamble Detected (output) +#define RFM22_gpio0_config_swd 0x1B // Sync Word Detected (output) +#define RFM22_gpio0_config_cca 0x1C // Clear Channel Assessment (output) +#define RFM22_gpio0_config_vdd 0x1D // VDD +#define RFM22_gpio0_config_pup 0x20 +#define RFM22_gpio0_config_drv0 0x00 // output drive level +#define RFM22_gpio0_config_drv1 0x40 // output drive level +#define RFM22_gpio0_config_drv2 0x80 // output drive level +#define RFM22_gpio0_config_drv3 0xC0 // output drive level + +#define RFM22_gpio1_config 0x0C // R/W +#define RFM22_gpio1_config_ipor 0x00 // Inverted Power-On-Reset (output) +#define RFM22_gpio1_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output) +#define RFM22_gpio1_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output) +#define RFM22_gpio1_config_ddi 0x03 // Direct Digital Input +#define RFM22_gpio1_config_eife 0x04 // External Interrupt, falling edge (input) +#define RFM22_gpio1_config_eire 0x05 // External Interrupt, rising edge (input) +#define RFM22_gpio1_config_eisc 0x06 // External Interrupt, state change (input) +#define RFM22_gpio1_config_ai 0x07 // ADC Analog Input +#define RFM22_gpio1_config_atni 0x08 // Reserved (Analog Test N Input) +#define RFM22_gpio1_config_atpi 0x09 // Reserved (Analog Test P Input) +#define RFM22_gpio1_config_ddo 0x0A // Direct Digital Output +#define RFM22_gpio1_config_dto 0x0B // Reserved (Digital Test Output) +#define RFM22_gpio1_config_atno 0x0C // Reserved (Analog Test N Output) +#define RFM22_gpio1_config_atpo 0x0D // Reserved (Analog Test P Output) +#define RFM22_gpio1_config_rv 0xOE // Reference Voltage (output) +#define RFM22_gpio1_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output) +#define RFM22_gpio1_config_txd 0x10 // TX Data input for direct modulation (input) +#define RFM22_gpio1_config_err 0x11 // External Retransmission Request (input) +#define RFM22_gpio1_config_txstate 0x12 // TX State (output) +#define RFM22_gpio1_config_txfifoaf 0x13 // TX FIFO Almost Full (output) +#define RFM22_gpio1_config_rxd 0x14 // RX Data (output) +#define RFM22_gpio1_config_rxstate 0x15 // RX State (output) +#define RFM22_gpio1_config_rxfifoaf 0x16 // RX FIFO Almost Full (output) +#define RFM22_gpio1_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output) +#define RFM22_gpio1_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output) +#define RFM22_gpio1_config_vpd 0x19 // Valid Preamble Detected (output) +#define RFM22_gpio1_config_ipd 0x1A // Invalid Preamble Detected (output) +#define RFM22_gpio1_config_swd 0x1B // Sync Word Detected (output) +#define RFM22_gpio1_config_cca 0x1C // Clear Channel Assessment (output) +#define RFM22_gpio1_config_vdd 0x1D // VDD +#define RFM22_gpio1_config_pup 0x20 +#define RFM22_gpio1_config_drv0 0x00 // output drive level +#define RFM22_gpio1_config_drv1 0x40 // output drive level +#define RFM22_gpio1_config_drv2 0x80 // output drive level +#define RFM22_gpio1_config_drv3 0xC0 // output drive level + +#define RFM22_gpio2_config 0x0D // R/W +#define RFM22_gpio2_config_mc 0x00 // Microcontroller Clock (output) +#define RFM22_gpio2_config_wut 0x01 // Wake-Up Timer: 1 when WUT has expired (output) +#define RFM22_gpio2_config_lbd 0x02 // Low Battery Detect: 1 when battery is below threshold setting (output) +#define RFM22_gpio2_config_ddi 0x03 // Direct Digital Input +#define RFM22_gpio2_config_eife 0x04 // External Interrupt, falling edge (input) +#define RFM22_gpio2_config_eire 0x05 // External Interrupt, rising edge (input) +#define RFM22_gpio2_config_eisc 0x06 // External Interrupt, state change (input) +#define RFM22_gpio2_config_ai 0x07 // ADC Analog Input +#define RFM22_gpio2_config_atni 0x08 // Reserved (Analog Test N Input) +#define RFM22_gpio2_config_atpi 0x09 // Reserved (Analog Test P Input) +#define RFM22_gpio2_config_ddo 0x0A // Direct Digital Output +#define RFM22_gpio2_config_dto 0x0B // Reserved (Digital Test Output) +#define RFM22_gpio2_config_atno 0x0C // Reserved (Analog Test N Output) +#define RFM22_gpio2_config_atpo 0x0D // Reserved (Analog Test P Output) +#define RFM22_gpio2_config_rv 0xOE // Reference Voltage (output) +#define RFM22_gpio2_config_dclk 0x0F // TX/RX Data CLK output to be used in conjunction with TX/RX Data pin (output) +#define RFM22_gpio2_config_txd 0x10 // TX Data input for direct modulation (input) +#define RFM22_gpio2_config_err 0x11 // External Retransmission Request (input) +#define RFM22_gpio2_config_txstate 0x12 // TX State (output) +#define RFM22_gpio2_config_txfifoaf 0x13 // TX FIFO Almost Full (output) +#define RFM22_gpio2_config_rxd 0x14 // RX Data (output) +#define RFM22_gpio2_config_rxstate 0x15 // RX State (output) +#define RFM22_gpio2_config_rxfifoaf 0x16 // RX FIFO Almost Full (output) +#define RFM22_gpio2_config_antswt1 0x17 // Antenna 1 Switch used for antenna diversity (output) +#define RFM22_gpio2_config_antswt2 0x18 // Antenna 2 Switch used for antenna diversity (output) +#define RFM22_gpio2_config_vpd 0x19 // Valid Preamble Detected (output) +#define RFM22_gpio2_config_ipd 0x1A // Invalid Preamble Detected (output) +#define RFM22_gpio2_config_swd 0x1B // Sync Word Detected (output) +#define RFM22_gpio2_config_cca 0x1C // Clear Channel Assessment (output) +#define RFM22_gpio2_config_vdd 0x1D // VDD +#define RFM22_gpio2_config_pup 0x20 +#define RFM22_gpio2_config_drv0 0x00 // output drive level +#define RFM22_gpio2_config_drv1 0x40 // output drive level +#define RFM22_gpio2_config_drv2 0x80 // output drive level +#define RFM22_gpio2_config_drv3 0xC0 // output drive level + +#define RFM22_io_port_config 0x0E // R/W +#define RFM22_io_port_extitst2 0x40 // External Interrupt Status. If the GPIO2 is programmed to be external interrupt sources then the status can be read here. +#define RFM22_io_port_extitst1 0x20 // External Interrupt Status. If the GPIO1 is programmed to be external interrupt sources then the status can be read here. +#define RFM22_io_port_extitst0 0x10 // External Interrupt Status. If the GPIO0 is programmed to be external interrupt sources then the status can be read here. +#define RFM22_io_port_itsdo 0x08 // Interrupt Request Output on the SDO Pin. nIRQ output is present on the SDO pin if this bit is set and the nSEL input is inactive (high). +#define RFM22_io_port_dio2 0x04 // Direct I/O for GPIO2. If the GPIO2 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO2 is configured to be a direct input then the value of the pin can be read here. +#define RFM22_io_port_dio1 0x02 // Direct I/O for GPIO1. If the GPIO1 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO1 is configured to be a direct input then the value of the pin can be read here. +#define RFM22_io_port_dio0 0x01 // Direct I/O for GPIO0. If the GPIO0 is configured to be a direct output then the value on the GPIO pin can be set here. If the GPIO0 is configured to be a direct input then the value of the pin can be read here. +#define RFM22_io_port_default 0x00 // GPIO pins are default + +#define RFM22_adc_config 0x0F // R/W +#define RFM22_ac_adcgain0 0x00 +#define RFM22_ac_adcgain1 0x01 +#define RFM22_ac_adcgain2 0x02 +#define RFM22_ac_adcgain3 0x03 +#define RFM22_ac_adcref_bg 0x00 +#define RFM22_ac_adcref_vdd3 0x08 +#define RFM22_ac_adcref_vdd2 0x0C +#define RFM22_ac_adcsel_temp_sensor 0x00 +#define RFM22_ac_adcsel_gpio0 0x10 +#define RFM22_ac_adcsel_gpio1 0x20 +#define RFM22_ac_adcsel_gpio2 0x30 +#define RFM22_ac_adcsel_gpio01 0x40 +#define RFM22_ac_adcsel_gpio12 0x50 +#define RFM22_ac_adcsel_gpio02 0x60 +#define RFM22_ac_adcsel_gpio_gnd 0x70 +#define RFM22_ac_adcstartbusy 0x80 + +#define RFM22_adc_sensor_amp_offset 0x10 // R/W +#define RFM22_asao_adcoffs_mask 0x0F // ADC Sensor Amplifier Offset. The offset can be calculated as Offset = adcoffs[2:0] x VDD/1000; MSB = adcoffs[3] = Sign bit. + +#define RFM22_adc_value 0x11 // R .. Internal 8 bit ADC Output Value. + +#define RFM22_temp_sensor_calib 0x12 // R/W +#define RFM22_tsc_tstrim_mask 0x0F // Temperature Sensor Trim Value. +#define RFM22_tsc_entstrim 0x10 // Temperature Sensor Trim Enable. +#define RFM22_tsc_entsoffs 0x20 // Temperature Sensor Offset to Convert from K to �C. +#define RFM22_tsc_tsrange0 0x00 // Temperature Sensor Range Selection. �64C to +64C 0.5C resolution +#define RFM22_tsc_tsrange1 0x40 // -40 to +85C with 1.0C resolution +#define RFM22_tsc_tsrange2 0x80 // 0C to 85C with 0.5C resolution +#define RFM22_tsc_tsrange3 0xC0 // -40F to 216F with 1.0F resolution + +#define RFM22_temp_value_offset 0x13 // R/W + +#define RFM22_wakeup_timer_period1 0x14 // R/W +#define RFM22_wakeup_timer_period2 0x15 // R/W +#define RFM22_wakeup_timer_period3 0x16 // R/W + +#define RFM22_wakeup_timer_value1 0x17 // R +#define RFM22_wakeup_timer_value2 0x18 // R + +#define RFM22_low_dutycycle_mode_duration 0x19 // R/W +#define RFM22_low_battery_detector_threshold 0x1A // R/W + +#define RFM22_battery_volateg_level 0x1B // R + +#define RFM22_if_filter_bandwidth 0x1C // R/W +#define RFM22_iffbw_filset_mask 0x0F +#define RFM22_iffbw_ndec_exp_mask 0x70 +#define RFM22_iffbw_dwn3_bypass 0x80 + +#define RFM22_afc_loop_gearshift_override 0x1D // R/W +#define RFM22_afc_lp_gs_ovrd_afcgearl_mask 0x07 // AFC Low Gear Setting. +#define RFM22_afc_lp_gs_ovrd_afcgearh_mask 0x38 // AFC High Gear Setting. +#define RFM22_afc_lp_gs_ovrd_enafc 0x40 // AFC Enable. +#define RFM22_afc_lp_gs_ovrd_afcbd 0x80 // If set, the tolerated AFC frequency error will be halved. + +#define RFM22_afc_timing_control 0x1E // R/W + +#define RFM22_clk_recovery_gearshift_override 0x1F // R/W +#define RFM22_clk_recovery_oversampling_ratio 0x20 // R/W +#define RFM22_clk_recovery_offset2 0x21 // R/W +#define RFM22_clk_recovery_offset1 0x22 // R/W +#define RFM22_clk_recovery_offset0 0x23 // R/W +#define RFM22_clk_recovery_timing_loop_gain1 0x24 // R/W +#define RFM22_clk_recovery_timing_loop_gain0 0x25 // R/W + +#define RFM22_rssi 0x26 // R +#define RFM22_rssi_threshold_clear_chan_indicator 0x27 // R/W + +#define RFM22_antenna_diversity_register1 0x28 // R +#define RFM22_antenna_diversity_register2 0x29 // R + +#define RFM22_afc_limiter 0x2A // R/W .. AFC_pull_in_range = �AFCLimiter[7:0] x (hbsel+1) x 625 Hz + +#define RFM22_afc_correction_read 0x2B // R + +#define RFM22_ook_counter_value1 0x2C // R/W +#define RFM22_ook_counter_value2 0x2D // R/W + +#define RFM22_slicer_peak_hold 0x2E // R/W + +#define RFM22_data_access_control 0x30 // R/W +#define RFM22_dac_crc_ccitt 0x00 // +#define RFM22_dac_crc_crc16 0x01 // +#define RFM22_dac_crc_iec16 0x02 // +#define RFM22_dac_crc_biacheva 0x03 // +#define RFM22_dac_encrc 0x04 // CRC Enable. Cyclic Redundancy Check generation is enabled if this bit is set. +#define RFM22_dac_enpactx 0x08 // Enable Packet TX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpactx = 1 will enable automatic packet handling in the TX path. Register 30�4D allow for various configurations of the packet structure. Setting enpactx = 0 will not do any packet handling in the TX path. It will only transmit what is loaded to the FIFO. +#define RFM22_dac_skip2ph 0x10 // Skip 2nd Phase of Preamble Detection. If set, we skip the second phase of the preamble detection (under certain conditions) if antenna diversity is enabled. +#define RFM22_dac_crcdonly 0x20 // CRC Data Only Enable. When this bit is set to 1 the CRC is calculated on and checked against the packet data fields only. +#define RFM22_dac_lsbfrst 0x40 // LSB First Enable. The LSB of the data will be transmitted/received first if this bit is set. +#define RFM22_dac_enpacrx 0x80 // Enable Packet RX Handling. If FIFO Mode (dtmod = 10) is being used automatic packet handling may be enabled. Setting enpacrx = 1 will enable automatic packet handling in the RX path. Register 30�4D allow for various configurations of the packet structure. Setting enpacrx = 0 will not do any packet handling in the RX path. It will only receive everything after the sync word and fill up the RX FIFO. + +#define RFM22_ezmac_status 0x31 // R +#define RFM22_ezmac_status_pksent 0x01 // Packet Sent. A 1 a packet has been sent by the radio. (Same bit as in register 03, but reading it does not reset the IRQ) +#define RFM22_ezmac_status_pktx 0x02 // Packet Transmitting. When 1 the radio is currently transmitting a packet. +#define RFM22_ezmac_status_crcerror 0x04 // CRC Error. When 1 a Cyclic Redundancy Check error has been detected. (Same bit as in register 03, but reading it does not reset the IRQ) +#define RFM22_ezmac_status_pkvalid 0x08 // Valid Packet Received. When a 1 a valid packet has been received by the receiver. (Same bit as in register 03, but reading it does not reset the IRQ) +#define RFM22_ezmac_status_pkrx 0x10 // Packet Receiving. When 1 the radio is currently receiving a valid packet. +#define RFM22_ezmac_status_pksrch 0x20 // Packet Searching. When 1 the radio is searching for a valid packet. +#define RFM22_ezmac_status_rxcrc1 0x40 // If high, it indicates the last CRC received is all one�s. May indicated Transmitter underflow in case of CRC error. + +#define RFM22_header_control1 0x32 // R/W +#define RFM22_header_cntl1_bcen_none 0x00 // No broadcast address enable. +#define RFM22_header_cntl1_bcen_0 0x10 // Broadcast address enable for header byte 0. +#define RFM22_header_cntl1_bcen_1 0x20 // Broadcast address enable for header byte 1. +#define RFM22_header_cntl1_bcen_2 0x40 // Broadcast address enable for header byte 2. +#define RFM22_header_cntl1_bcen_3 0x80 // Broadcast address enable for header byte 3. +#define RFM22_header_cntl1_hdch_none 0x00 // No Received Header check +#define RFM22_header_cntl1_hdch_0 0x01 // Received Header check for byte 0. +#define RFM22_header_cntl1_hdch_1 0x02 // Received Header check for byte 1. +#define RFM22_header_cntl1_hdch_2 0x04 // Received Header check for byte 2. +#define RFM22_header_cntl1_hdch_3 0x08 // Received Header check for byte 3. + +#define RFM22_header_control2 0x33 // R/W +#define RFM22_header_cntl2_prealen 0x01 // MSB of Preamble Length. See register Preamble Length. +#define RFM22_header_cntl2_synclen_3 0x00 // Synchronization Word 3 +#define RFM22_header_cntl2_synclen_32 0x02 // Synchronization Word 3 followed by 2 +#define RFM22_header_cntl2_synclen_321 0x04 // Synchronization Word 3 followed by 2 followed by 1 +#define RFM22_header_cntl2_synclen_3210 0x06 // Synchronization Word 3 followed by 2 followed by 1 followed by 0 +#define RFM22_header_cntl2_fixpklen 0x08 // Fix Packet Length. When fixpklen = 1 the packet length (pklen[7:0]) is not included in the header. When fixpklen = 0 the packet length is included in the header. +#define RFM22_header_cntl2_hdlen_none 0x00 // no header +#define RFM22_header_cntl2_hdlen_3 0x10 // header 3 +#define RFM22_header_cntl2_hdlen_32 0x20 // header 3 and 2 +#define RFM22_header_cntl2_hdlen_321 0x30 // header 3 and 2 and 1 +#define RFM22_header_cntl2_hdlen_3210 0x40 // header 3 and 2 and 1 and 0 +#define RFM22_header_cntl2_skipsyn 0x80 // If high, the system will ignore the syncword search timeout reset. The chip will not return to searching for Preamble, but instead will remain searching for Sync word. + +#define RFM22_preamble_length 0x34 // R/W + +#define RFM22_preamble_detection_ctrl1 0x35 // R/W +#define RFM22_pre_det_ctrl1_preath_mask 0xF8 // Number of nibbles processed during detection. +#define RFM22_pre_det_ctrl1_rssi_offset_mask 0x07 // Value added as offset to RSSI calculation. Every increment in this register results in an increment of +4 dB in the RSSI. + +#define RFM22_sync_word3 0x36 // R/W +#define RFM22_sync_word2 0x37 // R/W +#define RFM22_sync_word1 0x38 // R/W +#define RFM22_sync_word0 0x39 // R/W + +#define RFM22_transmit_header3 0x3A // R/W +#define RFM22_transmit_header2 0x3B // R/W +#define RFM22_transmit_header1 0x3C // R/W +#define RFM22_transmit_header0 0x3D // R/W + +#define RFM22_transmit_packet_length 0x3E // R/W + +#define RFM22_check_header3 0x3F // R/W +#define RFM22_check_header2 0x40 // R/W +#define RFM22_check_header1 0x41 // R/W +#define RFM22_check_header0 0x42 // R/W + +#define RFM22_header_enable3 0x43 // R/W +#define RFM22_header_enable2 0x44 // R/W +#define RFM22_header_enable1 0x45 // R/W +#define RFM22_header_enable0 0x46 // R/W + +#define RFM22_received_header3 0x47 // R +#define RFM22_received_header2 0x48 // R +#define RFM22_received_header1 0x49 // R +#define RFM22_received_header0 0x4A // R + +#define RFM22_received_packet_length 0x4B // R + +#define RFM22_adc8_control 0x4F // R/W +/* +#define RFM22_analog_test_bus 0x50 // R/W +#define RFM22_digital_test_bus 0x51 // R/W +#define RFM22_tx_ramp_control 0x52 // R/W +#define RFM22_pll_tune_time 0x53 // R/W + +#define RFM22_calibration_control 0x55 // R/W + +#define RFM22_modem_test 0x56 // R/W + +#define RFM22_chargepump_test 0x57 // R/W +#define RFM22_chargepump_current_trimming_override 0x58 // R/W + +#define RFM22_divider_current_trimming 0x59 // R/W + +#define RFM22_vco_current_trimming 0x5A // R/W +#define RFM22_vco_calibration_override 0x5B // R/W + +#define RFM22_synthersizer_test 0x5C // R/W + +#define RFM22_block_enable_override1 0x5D // R/W +#define RFM22_block_enable_override2 0x5E // R/W +#define RFM22_block_enable_override3 0x5F // R/W +*/ +#define RFM22_channel_filter_coeff_addr 0x60 // R/W +#define RFM22_ch_fil_coeff_ad_inv_pre_th_mask 0xF0 // +#define RFM22_ch_fil_coeff_ad_chfiladd_mask 0x0F // Channel Filter Coefficient Look-up Table Address. The address for channel filter coefficients used in the RX path. + + +//#define RFM22_channel_filter_coeff_value 0x61 // R/W + +#define RFM22_xtal_osc_por_ctrl 0x62 // R/W +#define RFM22_xtal_osc_por_ctrl_pwst_mask 0xE0 // Internal Power States of the Chip. +#define RFM22_xtal_osc_por_ctrl_clkhyst 0x10 // Clock Hysteresis Setting. +#define RFM22_xtal_osc_por_ctrl_enbias2x 0x08 // 2 Times Higher Bias Current Enable. +#define RFM22_xtal_osc_por_ctrl_enamp2x 0x04 // 2 Times Higher Amplification Enable. +#define RFM22_xtal_osc_por_ctrl_bufovr 0x02 // Output Buffer Enable Override. +#define RFM22_xtal_osc_por_ctrl_enbuf 0x01 // Output Buffer Enable. +/* +#define RFM22_rc_osc_coarse_calbration_override 0x63 // R/W +#define RFM22_rc_osc_fine_calbration_override 0x64 // R/W + +#define RFM22_ldo_control_override 0x65 // R/W +#define RFM22_ldo_level_setting 0x66 // R/W + +#define RFM22_deltasigma_adc_tuning1 0x67 // R/W +#define RFM22_deltasigma_adc_tuning2 0x68 // R/W +*/ +#define RFM22_agc_override1 0x69 // R/W +#define RFM22_agc_ovr1_sgi 0x40 // AGC Loop, Set Gain Increase. If set to 0 then gain increasing will not be allowed. If set to 1 then gain increasing is allowed, default is 0. +#define RFM22_agc_ovr1_agcen 0x20 // Automatic Gain Control Enable. When this bit is set then the result of the control can be read out from bits [4:0], otherwise the gain can be controlled manually by writing into bits [4:0]. +#define RFM22_agc_ovr1_lnagain 0x10 // LNA Gain Select. 0 = min gain = 5dB, 1 = max gain = 25 dB. +#define RFM22_agc_ovr1_pga_mask 0x0F // PGA Gain Override Value. + +//#define RFM22_agc_override2 0x6A // R/W + +//#define RFM22_gfsk_fir_coeff_addr 0x6B // R/W +//#define RFM22_gfsk_fir_coeff_value 0x6C // R/W + +#define RFM22_tx_power 0x6D // R/W +#define RFM22_tx_pwr_lna_sw 0x08 // LNA Switch Controller. If set, lna_sw control from the digital will go high during TX modes, and low during other times. If reset, the digital control signal is low at all times. +#define RFM22_tx_pwr_papeaklvl_0 0x10 // " " +#define RFM22_tx_pwr_papeaklvl_1 0x20 // PA Peak Detect Level (direct from register). 00 = 6.5, 01 = 7, 10 = 7.5, 11 = 8, 00 = default +#define RFM22_tx_pwr_papeaken 0x40 // PA Peak Detector Enable. +#define RFM22_tx_pwr_papeakval 0x80 // PA Peak Detector Value Read Register. Reading a 1 in this register when the papeaken=1 then the PA drain voltage is too high and the match network needs adjusting for optimal efficiency. + +#define RFM22_tx_data_rate1 0x6E // R/W +#define RFM22_tx_data_rate0 0x6F // R/W + +#define RFM22_modulation_mode_control1 0x70 // R/W +#define RFM22_mmc1_enwhite 0x01 // Data Whitening is Enabled if this bit is set. +#define RFM22_mmc1_enmanch 0x02 // Manchester Coding is Enabled if this bit is set. +#define RFM22_mmc1_enmaninv 0x04 // Manchester Data Inversion is Enabled if this bit is set. +#define RFM22_mmc1_manppol 0x08 // Manchester Preamble Polarity (will transmit a series of 1 if set, or series of 0 if reset). +#define RFM22_mmc1_enphpwdn 0x10 // If set, the Packet Handler will be powered down when chip is in low power mode. +#define RFM22_mmc1_txdtrtscale 0x20 // This bit should be set for Data Rates below 30 kbps. + +#define RFM22_modulation_mode_control2 0x71 // R/W +#define RFM22_mmc2_modtyp_mask 0x03 // Modulation type. +#define RFM22_mmc2_modtyp_none 0x00 // +#define RFM22_mmc2_modtyp_ook 0x01 // +#define RFM22_mmc2_modtyp_fsk 0x02 // +#define RFM22_mmc2_modtyp_gfsk 0x03 // +#define RFM22_mmc2_fd 0x04 // MSB of Frequency Deviation Setting, see "Register 72h. Frequency Deviation". +#define RFM22_mmc2_eninv 0x08 // Invert TX and RX Data. +#define RFM22_mmc2_dtmod_mask 0x30 // Modulation source. +#define RFM22_mmc2_dtmod_dm_gpio 0x00 // +#define RFM22_mmc2_dtmod_dm_sdi 0x10 // +#define RFM22_mmc2_dtmod_fifo 0x20 // +#define RFM22_mmc2_dtmod_pn9 0x30 // +#define RFM22_mmc2_trclk_mask 0xC0 // TX Data Clock Configuration. +#define RFM22_mmc2_trclk_clk_none 0x00 // +#define RFM22_mmc2_trclk_clk_gpio 0x40 // +#define RFM22_mmc2_trclk_clk_sdo 0x80 // +#define RFM22_mmc2_trclk_clk_nirq 0xC0 // + +#define RFM22_frequency_deviation 0x72 // R/W + +#define RFM22_frequency_offset1 0x73 // R/W +#define RFM22_frequency_offset2 0x74 // R/W + +#define RFM22_frequency_band_select 0x75 // R/W +#define RFM22_fb_mask 0x1F +#define RFM22_fbs_hbsel 0x20 +#define RFM22_fbs_sbse 0x40 + +#define RFM22_nominal_carrier_frequency1 0x76 // R/W +#define RFM22_nominal_carrier_frequency0 0x77 // R/W + +#define RFM22_frequency_hopping_channel_select 0x79 // R/W +#define RFM22_frequency_hopping_step_size 0x7A // R/W + +#define RFM22_tx_fifo_control1 0x7C // R/W .. TX FIFO Almost Full Threshold (0 - 63) +#define RFM22_tx_fifo_control1_mask 0x3F + +#define RFM22_tx_fifo_control2 0x7D // R/W .. TX FIFO Almost Empty Threshold (0 - 63) +#define RFM22_tx_fifo_control2_mask 0x3F + +#define RFM22_rx_fifo_control 0x7E // R/W .. RX FIFO Almost Full Threshold (0 - 63) +#define RFM22_rx_fifo_control_mask 0x3F + +#define RFM22_fifo_access 0x7F // R/W + + +// External type definitions + +typedef int16_t (*t_rfm22_TxDataByteCallback) (void); +typedef bool (*t_rfm22_RxDataCallback) (void *data, uint8_t len); +enum pios_rfm22b_dev_magic { + PIOS_RFM22B_DEV_MAGIC = 0x68e971b6, +}; + +enum pios_rfm22b_state { + RFM22B_STATE_UNINITIALIZED, + RFM22B_STATE_INITIALIZING, + RFM22B_STATE_INITIALIZED, + RFM22B_STATE_INITIATING_CONNECTION, + RFM22B_STATE_WAIT_FOR_CONNECTION, + RFM22B_STATE_REQUESTING_CONNECTION, + RFM22B_STATE_ACCEPTING_CONNECTION, + RFM22B_STATE_CONNECTION_ACCEPTED, + RFM22B_STATE_RX_MODE, + RFM22B_STATE_WAIT_PREAMBLE, + RFM22B_STATE_WAIT_SYNC, + RFM22B_STATE_RX_DATA, + RFM22B_STATE_RX_FAILURE, + RFM22B_STATE_RECEIVING_STATUS, + RFM22B_STATE_TX_START, + RFM22B_STATE_TX_DATA, + RFM22B_STATE_TX_FAILURE, + RFM22B_STATE_SENDING_ACK, + RFM22B_STATE_SENDING_NACK, + RFM22B_STATE_RECEIVING_ACK, + RFM22B_STATE_RECEIVING_NACK, + RFM22B_STATE_TIMEOUT, + RFM22B_STATE_ERROR, + RFM22B_STATE_FATAL_ERROR, + + RFM22B_STATE_NUM_STATES // Must be last +}; + +enum pios_rfm22b_event { + RFM22B_EVENT_INT_RECEIVED, + RFM22B_EVENT_INITIALIZE, + RFM22B_EVENT_INITIALIZED, + RFM22B_EVENT_REQUEST_CONNECTION, + RFM22B_EVENT_WAIT_FOR_CONNECTION, + RFM22B_EVENT_CONNECTION_REQUESTED, + RFM22B_EVENT_CONNECTION_ACCEPTED, + RFM22B_EVENT_PACKET_ACKED, + RFM22B_EVENT_PACKET_NACKED, + RFM22B_EVENT_ACK_TIMEOUT, + RFM22B_EVENT_RX_MODE, + RFM22B_EVENT_PREAMBLE_DETECTED, + RFM22B_EVENT_SYNC_DETECTED, + RFM22B_EVENT_RX_COMPLETE, + RFM22B_EVENT_RX_ERROR, + RFM22B_EVENT_STATUS_RECEIVED, + RFM22B_EVENT_TX_START, + RFM22B_EVENT_FAILURE, + RFM22B_EVENT_TIMEOUT, + RFM22B_EVENT_ERROR, + RFM22B_EVENT_FATAL_ERROR, + + RFM22B_EVENT_NUM_EVENTS // Must be last +}; + +#define RFM22B_RX_PACKET_STATS_LEN 4 +enum pios_rfm22b_rx_packet_status { + RFM22B_GOOD_RX_PACKET = 0x00, + RFM22B_CORRECTED_RX_PACKET = 0x01, + RFM22B_ERROR_RX_PACKET = 0x2, + RFM22B_RESENT_TX_PACKET = 0x3 +}; + +typedef struct { + uint32_t pairID; + int8_t rssi; + int8_t afc_correction; + uint8_t lastContact; +} rfm22b_pair_stats; + +struct pios_rfm22b_dev { + enum pios_rfm22b_dev_magic magic; + struct pios_rfm22b_cfg cfg; + + // The SPI bus information + uint32_t spi_id; + uint32_t slave_num; + + // The device ID + uint32_t deviceID; + + // The destination ID + uint32_t destination_id; + + // Is this device a coordinator? + bool coordinator; + + // The task handle + xTaskHandle taskHandle; + + // The potential paired statistics + rfm22b_pair_stats pair_stats[OPLINKSTATUS_PAIRIDS_NUMELEM]; + + // ISR pending semaphore + xSemaphoreHandle isrPending; + + // The com configuration callback + PIOS_RFM22B_ComConfigCallback com_config_cb; + + // The COM callback functions. + pios_com_callback rx_in_cb; + uint32_t rx_in_context; + pios_com_callback tx_out_cb; + uint32_t tx_out_context; + + // the transmit power to use for data transmissions + uint8_t tx_power; + + // The RF datarate lookup index. + uint8_t datarate; + + // The state machine state and the current event + enum pios_rfm22b_state state; + + // The event queue handle + xQueueHandle eventQueue; + + // device status register + uint8_t device_status; + // interrupt status register 1 + uint8_t int_status1; + // interrupt status register 2 + uint8_t int_status2; + // ezmac status register + uint8_t ezmac_status; + + // The error statistics counters + uint16_t prev_rx_seq_num; + uint32_t rx_packet_stats[RFM22B_RX_PACKET_STATS_LEN]; + + // The packet statistics + struct rfm22b_stats stats; + + // Stats + uint16_t errors; + + // RSSI in dBm + int8_t rssi_dBm; + + // The packet queue handle + xQueueHandle packetQueue; + + // The tx data packet + PHPacket data_packet; + // The current tx packet + PHPacketHandle tx_packet; + // The previous tx packet (waiting for an ACK) + PHPacketHandle prev_tx_packet; + // The tx data read index + uint16_t tx_data_rd; + // The tx data write index + uint16_t tx_data_wr; + // The tx packet sequence number + uint16_t tx_seq; + + // The rx data packet + PHPacket rx_packet; + // The receive buffer write index + uint16_t rx_buffer_wr; + // The receive buffer write index + uint16_t rx_packet_len; + // Is the modem currently in Rx mode? + bool in_rx_mode; + + // The status packet + PHStatusPacket status_packet; + + // The ACK/NACK packet + PHAckNackPacket ack_nack_packet; + +#ifdef PIOS_PPM_RECEIVER + // The PPM packet + PHPpmPacket ppm_packet; +#endif + + // The connection packet. + PHConnectionPacket con_packet; + + // Send flags + bool send_status; + bool send_ppm; + bool send_connection_request; + bool time_to_send; + uint8_t time_to_send_offset; + + // The minimum frequency + uint32_t min_frequency; + // The maximum frequency + uint32_t max_frequency; + // The current nominal frequency + uint32_t frequency_hz; + // The frequency hopping step size + float frequency_step_size; + // current frequency hop channel + uint8_t frequency_hop_channel; + // the frequency hop step size + uint8_t frequency_hop_step_size_reg; + // afc correction reading (in Hz) + int8_t afc_correction_Hz; + + // The maximum time (ms) that it should take to transmit / receive a packet. + uint32_t max_packet_time; + portTickType packet_start_ticks; + portTickType tx_complete_ticks; + portTickType rx_complete_ticks; + uint8_t max_ack_delay; + + // The PPM channel values + uint16_t ppm_channel[PIOS_RFM22B_RCVR_MAX_CHANNELS]; + uint8_t ppm_supv_timer; + bool ppm_fresh; +}; + + +// External function definitions + +bool PIOS_RFM22_EXT_Int(void); +bool PIOS_RFM22B_validate(struct pios_rfm22b_dev * rfm22b_dev); +void PIOS_RFM22B_InjectEvent(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_event event, bool inISR); + + +// Global variable definitions + +extern const struct pios_com_driver pios_rfm22b_com_driver; + +#endif /* PIOS_RFM22B_PRIV_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_spi.h b/flight/PiOS/inc/pios_spi.h index 759855c13..2abbf9c20 100644 --- a/flight/PiOS/inc/pios_spi.h +++ b/flight/PiOS/inc/pios_spi.h @@ -1,62 +1,62 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_SPI SPI Functions - * @{ - * - * @file pios_spi.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief SPI functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_SPI_H -#define PIOS_SPI_H - -/* Global types */ -typedef enum { - PIOS_SPI_PRESCALER_2 = 0, - PIOS_SPI_PRESCALER_4 = 1, - PIOS_SPI_PRESCALER_8 = 2, - PIOS_SPI_PRESCALER_16 = 3, - PIOS_SPI_PRESCALER_32 = 4, - PIOS_SPI_PRESCALER_64 = 5, - PIOS_SPI_PRESCALER_128 = 6, - PIOS_SPI_PRESCALER_256 = 7 -} SPIPrescalerTypeDef; - -/* Public Functions */ -extern int32_t PIOS_SPI_SetClockSpeed(uint32_t spi_id, SPIPrescalerTypeDef spi_prescaler); -extern int32_t PIOS_SPI_RC_PinSet(uint32_t spi_id, uint32_t slave_id, uint8_t pin_value); -extern int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b); -extern int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback); -extern int32_t PIOS_SPI_Busy(uint32_t spi_id); -extern int32_t PIOS_SPI_ClaimBus(uint32_t spi_id); -extern int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id); -extern int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id); -extern void PIOS_SPI_IRQ_Handler(uint32_t spi_id); -extern void PIOS_SPI_SetPrescalar(uint32_t spi_id, uint32_t prescalar); - -#endif /* PIOS_SPI_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_SPI SPI Functions + * @{ + * + * @file pios_spi.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief SPI functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_SPI_H +#define PIOS_SPI_H + +/* Global types */ +typedef enum { + PIOS_SPI_PRESCALER_2 = 0, + PIOS_SPI_PRESCALER_4 = 1, + PIOS_SPI_PRESCALER_8 = 2, + PIOS_SPI_PRESCALER_16 = 3, + PIOS_SPI_PRESCALER_32 = 4, + PIOS_SPI_PRESCALER_64 = 5, + PIOS_SPI_PRESCALER_128 = 6, + PIOS_SPI_PRESCALER_256 = 7 +} SPIPrescalerTypeDef; + +/* Public Functions */ +extern int32_t PIOS_SPI_SetClockSpeed(uint32_t spi_id, SPIPrescalerTypeDef spi_prescaler); +extern int32_t PIOS_SPI_RC_PinSet(uint32_t spi_id, uint32_t slave_id, uint8_t pin_value); +extern int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b); +extern int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback); +extern int32_t PIOS_SPI_Busy(uint32_t spi_id); +extern int32_t PIOS_SPI_ClaimBus(uint32_t spi_id); +extern int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id); +extern int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id); +extern void PIOS_SPI_IRQ_Handler(uint32_t spi_id); +extern void PIOS_SPI_SetPrescalar(uint32_t spi_id, uint32_t prescalar); + +#endif /* PIOS_SPI_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_udp.h b/flight/PiOS/inc/pios_udp.h index 36964a342..48a3b0987 100644 --- a/flight/PiOS/inc/pios_udp.h +++ b/flight/PiOS/inc/pios_udp.h @@ -1,35 +1,35 @@ -/** - ****************************************************************************** - * - * @file pios_usart.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief UDP functions header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_UDP_H -#define PIOS_UDP_H - - -/* Global Types */ - -/* Public Functions */ - -#endif /* PIOS_UDP_H */ +/** + ****************************************************************************** + * + * @file pios_usart.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief UDP functions header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_UDP_H +#define PIOS_UDP_H + + +/* Global Types */ + +/* Public Functions */ + +#endif /* PIOS_UDP_H */ diff --git a/flight/PiOS/inc/pios_video.h b/flight/PiOS/inc/pios_video.h index abdba4f6c..1689b0a09 100644 --- a/flight/PiOS/inc/pios_video.h +++ b/flight/PiOS/inc/pios_video.h @@ -1,104 +1,104 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_VIDEO Code for OSD video generator - * @brief OSD generator, Parts from CL-OSD and SUPEROSD project - * @{ - * - * @file pios_video.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief OSD generator, Parts from CL-OSD and SUPEROSD projects - * @see The GNU Public License (GPL) Version 3 - * - ****************************************************************************** - */ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_VIDEO_H -#define PIOS_VIDEO_H - -#include -#include - -struct pios_video_cfg { - const struct pios_spi_cfg mask; - const struct pios_spi_cfg level; - - const struct pios_exti_cfg * hsync; - const struct pios_exti_cfg * vsync; - - struct pios_tim_channel pixel_timer; - struct pios_tim_channel hsync_capture; - - TIM_OCInitTypeDef tim_oc_init; -}; - -// Time vars -typedef struct { - uint8_t sec; - uint8_t min; - uint8_t hour; -} TTime; - -extern TTime timex; - -extern void PIOS_Video_Init(const struct pios_video_cfg * cfg); -uint16_t PIOS_Video_GetOSDLines(void); -extern bool PIOS_Hsync_ISR(); -extern bool PIOS_Vsync_ISR(); - -// First OSD line -#define GRAPHICS_LINE 25 - -//top/left deadband -#define GRAPHICS_HDEADBAND 80 -#define GRAPHICS_VDEADBAND 0 - -#define PAL - -// Real OSD size -#ifdef PAL -//#define GRAPHICS_WIDTH_REAL (352+GRAPHICS_HDEADBAND) -#define GRAPHICS_WIDTH_REAL 416 - #define GRAPHICS_HEIGHT_REAL (270+GRAPHICS_VDEADBAND) -#else - #define GRAPHICS_WIDTH_REAL (312+GRAPHICS_HDEADBAND) - #define GRAPHICS_HEIGHT_REAL (225+GRAPHICS_VDEADBAND) -#endif - -//draw area -#define GRAPHICS_TOP 0 -#define GRAPHICS_LEFT 0 -#define GRAPHICS_BOTTOM (GRAPHICS_HEIGHT_REAL-GRAPHICS_VDEADBAND-1) -#define GRAPHICS_RIGHT (GRAPHICS_WIDTH_REAL-GRAPHICS_HDEADBAND-1) - - -#define GRAPHICS_WIDTH (GRAPHICS_WIDTH_REAL/8) -#define GRAPHICS_HEIGHT GRAPHICS_HEIGHT_REAL - -// dma lenght -#define BUFFER_LINE_LENGTH (GRAPHICS_WIDTH) //Yes, in bytes. - -// line types -#define LINE_TYPE_UNKNOWN 0 -#define LINE_TYPE_GRAPHICS 2 - -// Macro to swap buffers given a temporary pointer. -#define SWAP_BUFFS(tmp, a, b) { tmp = a; a = b; b = tmp; } - -#endif /* PIOS_VIDEO_H */ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_VIDEO Code for OSD video generator + * @brief OSD generator, Parts from CL-OSD and SUPEROSD project + * @{ + * + * @file pios_video.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief OSD generator, Parts from CL-OSD and SUPEROSD projects + * @see The GNU Public License (GPL) Version 3 + * + ****************************************************************************** + */ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_VIDEO_H +#define PIOS_VIDEO_H + +#include +#include + +struct pios_video_cfg { + const struct pios_spi_cfg mask; + const struct pios_spi_cfg level; + + const struct pios_exti_cfg * hsync; + const struct pios_exti_cfg * vsync; + + struct pios_tim_channel pixel_timer; + struct pios_tim_channel hsync_capture; + + TIM_OCInitTypeDef tim_oc_init; +}; + +// Time vars +typedef struct { + uint8_t sec; + uint8_t min; + uint8_t hour; +} TTime; + +extern TTime timex; + +extern void PIOS_Video_Init(const struct pios_video_cfg * cfg); +uint16_t PIOS_Video_GetOSDLines(void); +extern bool PIOS_Hsync_ISR(); +extern bool PIOS_Vsync_ISR(); + +// First OSD line +#define GRAPHICS_LINE 25 + +//top/left deadband +#define GRAPHICS_HDEADBAND 80 +#define GRAPHICS_VDEADBAND 0 + +#define PAL + +// Real OSD size +#ifdef PAL +//#define GRAPHICS_WIDTH_REAL (352+GRAPHICS_HDEADBAND) +#define GRAPHICS_WIDTH_REAL 416 + #define GRAPHICS_HEIGHT_REAL (270+GRAPHICS_VDEADBAND) +#else + #define GRAPHICS_WIDTH_REAL (312+GRAPHICS_HDEADBAND) + #define GRAPHICS_HEIGHT_REAL (225+GRAPHICS_VDEADBAND) +#endif + +//draw area +#define GRAPHICS_TOP 0 +#define GRAPHICS_LEFT 0 +#define GRAPHICS_BOTTOM (GRAPHICS_HEIGHT_REAL-GRAPHICS_VDEADBAND-1) +#define GRAPHICS_RIGHT (GRAPHICS_WIDTH_REAL-GRAPHICS_HDEADBAND-1) + + +#define GRAPHICS_WIDTH (GRAPHICS_WIDTH_REAL/8) +#define GRAPHICS_HEIGHT GRAPHICS_HEIGHT_REAL + +// dma lenght +#define BUFFER_LINE_LENGTH (GRAPHICS_WIDTH) //Yes, in bytes. + +// line types +#define LINE_TYPE_UNKNOWN 0 +#define LINE_TYPE_GRAPHICS 2 + +// Macro to swap buffers given a temporary pointer. +#define SWAP_BUFFS(tmp, a, b) { tmp = a; a = b; b = tmp; } + +#endif /* PIOS_VIDEO_H */ diff --git a/flight/PiOS/inc/stm32f2xx_conf.h b/flight/PiOS/inc/stm32f2xx_conf.h index 0ee7ea36e..bafb3715a 100644 --- a/flight/PiOS/inc/stm32f2xx_conf.h +++ b/flight/PiOS/inc/stm32f2xx_conf.h @@ -1,88 +1,88 @@ -/** - ****************************************************************************** - * @file Project/STM32F2xx_StdPeriph_Template/stm32f2xx_conf.h - * @author MCD Application Team - * @version V0.0.4 - * @date 13-January-2011 - * @brief Library configuration file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F2xx_CONF_H -#define __STM32F2xx_CONF_H - -/* Includes ------------------------------------------------------------------*/ -/* Uncomment the line below to enable peripheral header file inclusion */ -#include "stm32f2xx_adc.h" -//#include "stm32f2xx_can.h" -#include "stm32f2xx_crc.h" -//#include "stm32f2xx_cryp.h" -#include "stm32f2xx_dac.h" -//#include "stm32f2xx_dbgmcu.h" -//#include "stm32f2xx_dcmi.h" -#include "stm32f2xx_dma.h" -#include "stm32f2xx_exti.h" -#include "stm32f2xx_flash.h" -//#include "stm32f2xx_fsmc.h" -//#include "stm32f2xx_hash.h" -#include "stm32f2xx_gpio.h" -#include "stm32f2xx_i2c.h" -//#include "stm32f2xx_iwdg.h" -#include "stm32f2xx_pwr.h" -#include "stm32f2xx_rcc.h" -//#include "stm32f2xx_rng.h" -#include "stm32f2xx_rtc.h" -//#include "stm32f2xx_sdio.h" -#include "stm32f2xx_spi.h" -#include "stm32f2xx_syscfg.h" -#include "stm32f2xx_tim.h" -#include "stm32f2xx_usart.h" -#include "stm32f2xx_wwdg.h" -#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/* If an external clock source is used, then the value of the following define - should be set to the value of the external clock source, else, if no external - clock is used, keep this define commented */ -/*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */ - - -/* Uncomment the line below to expanse the "assert_param" macro in the - Standard Peripheral Library drivers code */ -/* #define USE_FULL_ASSERT 1 */ - -/* Exported macro ------------------------------------------------------------*/ -#ifdef USE_FULL_ASSERT - -/** - * @brief The assert_param macro is used for function's parameters check. - * @param expr: If expr is false, it calls assert_failed function - * which reports the name of the source file and the source - * line number of the call that failed. - * If expr is true, it returns no value. - * @retval None - */ - #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) -/* Exported functions ------------------------------------------------------- */ - void assert_failed(uint8_t* file, uint32_t line); -#else - #define assert_param(expr) ((void)0) -#endif /* USE_FULL_ASSERT */ - -#endif /* __STM32F2xx_CONF_H */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file Project/STM32F2xx_StdPeriph_Template/stm32f2xx_conf.h + * @author MCD Application Team + * @version V0.0.4 + * @date 13-January-2011 + * @brief Library configuration file. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F2xx_CONF_H +#define __STM32F2xx_CONF_H + +/* Includes ------------------------------------------------------------------*/ +/* Uncomment the line below to enable peripheral header file inclusion */ +#include "stm32f2xx_adc.h" +//#include "stm32f2xx_can.h" +#include "stm32f2xx_crc.h" +//#include "stm32f2xx_cryp.h" +#include "stm32f2xx_dac.h" +//#include "stm32f2xx_dbgmcu.h" +//#include "stm32f2xx_dcmi.h" +#include "stm32f2xx_dma.h" +#include "stm32f2xx_exti.h" +#include "stm32f2xx_flash.h" +//#include "stm32f2xx_fsmc.h" +//#include "stm32f2xx_hash.h" +#include "stm32f2xx_gpio.h" +#include "stm32f2xx_i2c.h" +//#include "stm32f2xx_iwdg.h" +#include "stm32f2xx_pwr.h" +#include "stm32f2xx_rcc.h" +//#include "stm32f2xx_rng.h" +#include "stm32f2xx_rtc.h" +//#include "stm32f2xx_sdio.h" +#include "stm32f2xx_spi.h" +#include "stm32f2xx_syscfg.h" +#include "stm32f2xx_tim.h" +#include "stm32f2xx_usart.h" +#include "stm32f2xx_wwdg.h" +#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* If an external clock source is used, then the value of the following define + should be set to the value of the external clock source, else, if no external + clock is used, keep this define commented */ +/*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */ + + +/* Uncomment the line below to expanse the "assert_param" macro in the + Standard Peripheral Library drivers code */ +/* #define USE_FULL_ASSERT 1 */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT + +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + +#endif /* __STM32F2xx_CONF_H */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/inc/stm32f4xx_conf.h b/flight/PiOS/inc/stm32f4xx_conf.h index ef9dd5342..4618691d2 100644 --- a/flight/PiOS/inc/stm32f4xx_conf.h +++ b/flight/PiOS/inc/stm32f4xx_conf.h @@ -1,88 +1,88 @@ -/** - ****************************************************************************** - * @file Project/STM32F4xx_StdPeriph_Template/stm32f4xx_conf.h - * @author MCD Application Team - * @version V0.0.4 - * @date 13-January-2011 - * @brief Library configuration file. - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_CONF_H -#define __STM32F4xx_CONF_H - -/* Includes ------------------------------------------------------------------*/ -/* Uncomment the line below to enable peripheral header file inclusion */ -#include "stm32f4xx_adc.h" -//#include "stm32f4xx_can.h" -#include "stm32f4xx_crc.h" -//#include "stm32f2xx_cryp.h" -#include "stm32f4xx_dac.h" -//#include "stm32f4xx_dbgmcu.h" -//#include "stm32f4xx_dcmi.h" -#include "stm32f4xx_dma.h" -#include "stm32f4xx_exti.h" -#include "stm32f4xx_flash.h" -//#include "stm32f4xx_fsmc.h" -//#include "stm32f4xx_hash.h" -#include "stm32f4xx_gpio.h" -#include "stm32f4xx_i2c.h" -//#include "stm32f4xx_iwdg.h" -#include "stm32f4xx_pwr.h" -#include "stm32f4xx_rcc.h" -//#include "stm32f4xx_rng.h" -#include "stm32f4xx_rtc.h" -//#include "stm32f4xx_sdio.h" -#include "stm32f4xx_spi.h" -#include "stm32f4xx_syscfg.h" -#include "stm32f4xx_tim.h" -#include "stm32f4xx_usart.h" -#include "stm32f4xx_wwdg.h" -#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/* If an external clock source is used, then the value of the following define - should be set to the value of the external clock source, else, if no external - clock is used, keep this define commented */ -/*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */ - - -/* Uncomment the line below to expanse the "assert_param" macro in the - Standard Peripheral Library drivers code */ -/* #define USE_FULL_ASSERT 1 */ - -/* Exported macro ------------------------------------------------------------*/ -#ifdef USE_FULL_ASSERT - -/** - * @brief The assert_param macro is used for function's parameters check. - * @param expr: If expr is false, it calls assert_failed function - * which reports the name of the source file and the source - * line number of the call that failed. - * If expr is true, it returns no value. - * @retval None - */ - #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) -/* Exported functions ------------------------------------------------------- */ - void assert_failed(uint8_t* file, uint32_t line); -#else - #define assert_param(expr) ((void)0) -#endif /* USE_FULL_ASSERT */ - -#endif /* __STM32F4xx_CONF_H */ - -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * @file Project/STM32F4xx_StdPeriph_Template/stm32f4xx_conf.h + * @author MCD Application Team + * @version V0.0.4 + * @date 13-January-2011 + * @brief Library configuration file. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_CONF_H +#define __STM32F4xx_CONF_H + +/* Includes ------------------------------------------------------------------*/ +/* Uncomment the line below to enable peripheral header file inclusion */ +#include "stm32f4xx_adc.h" +//#include "stm32f4xx_can.h" +#include "stm32f4xx_crc.h" +//#include "stm32f2xx_cryp.h" +#include "stm32f4xx_dac.h" +//#include "stm32f4xx_dbgmcu.h" +//#include "stm32f4xx_dcmi.h" +#include "stm32f4xx_dma.h" +#include "stm32f4xx_exti.h" +#include "stm32f4xx_flash.h" +//#include "stm32f4xx_fsmc.h" +//#include "stm32f4xx_hash.h" +#include "stm32f4xx_gpio.h" +#include "stm32f4xx_i2c.h" +//#include "stm32f4xx_iwdg.h" +#include "stm32f4xx_pwr.h" +#include "stm32f4xx_rcc.h" +//#include "stm32f4xx_rng.h" +#include "stm32f4xx_rtc.h" +//#include "stm32f4xx_sdio.h" +#include "stm32f4xx_spi.h" +#include "stm32f4xx_syscfg.h" +#include "stm32f4xx_tim.h" +#include "stm32f4xx_usart.h" +#include "stm32f4xx_wwdg.h" +#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */ + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* If an external clock source is used, then the value of the following define + should be set to the value of the external clock source, else, if no external + clock is used, keep this define commented */ +/*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */ + + +/* Uncomment the line below to expanse the "assert_param" macro in the + Standard Peripheral Library drivers code */ +/* #define USE_FULL_ASSERT 1 */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT + +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + +#endif /* __STM32F4xx_CONF_H */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/pios_sim_posix.h b/flight/PiOS/pios_sim_posix.h index 12fd81725..f7ac600bd 100644 --- a/flight/PiOS/pios_sim_posix.h +++ b/flight/PiOS/pios_sim_posix.h @@ -1,78 +1,78 @@ -/** - ****************************************************************************** - * - * @file pios.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main PiOS header. - * - Central header for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_SIM_POSIX_H -#define PIOS_SIM_POSIX_H - -/* PIOS Feature Selection */ -#include "pios_config.h" -#include - -#if defined(PIOS_INCLUDE_FREERTOS) -/* FreeRTOS Includes */ -#include "FreeRTOS.h" -#include "task.h" -#include "queue.h" -#include "semphr.h" -#endif - -/* C Lib Includes */ -#include -#include -#include -#include -#include -#include - -/* Generic initcall infrastructure */ -#include - -/* PIOS Board Specific Device Configuration */ -#include "pios_board.h" - -/* PIOS Hardware Includes (posix) */ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#if defined(PIOS_INCLUDE_IAP) -#include -#endif -#if defined(PIOS_INCLUDE_BL_HELPER) -#include -#endif - -#endif /* PIOS_POSIX_H */ +/** + ****************************************************************************** + * + * @file pios.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main PiOS header. + * - Central header for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_SIM_POSIX_H +#define PIOS_SIM_POSIX_H + +/* PIOS Feature Selection */ +#include "pios_config.h" +#include + +#if defined(PIOS_INCLUDE_FREERTOS) +/* FreeRTOS Includes */ +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "semphr.h" +#endif + +/* C Lib Includes */ +#include +#include +#include +#include +#include +#include + +/* Generic initcall infrastructure */ +#include + +/* PIOS Board Specific Device Configuration */ +#include "pios_board.h" + +/* PIOS Hardware Includes (posix) */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined(PIOS_INCLUDE_IAP) +#include +#endif +#if defined(PIOS_INCLUDE_BL_HELPER) +#include +#endif + +#endif /* PIOS_POSIX_H */ diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/croutine.c b/flight/PiOS/posix/Libraries/FreeRTOS/Source/croutine.c index d6f116262..1ef663f93 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/croutine.c +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/croutine.c @@ -1,371 +1,371 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#include "FreeRTOS.h" -#include "task.h" -#include "croutine.h" - -/* - * Some kernel aware debuggers require data to be viewed to be global, rather - * than file scope. - */ -#ifdef portREMOVE_STATIC_QUALIFIER - #define static -#endif - - -/* Lists for ready and blocked co-routines. --------------------*/ -static xList pxReadyCoRoutineLists[ configMAX_CO_ROUTINE_PRIORITIES ]; /*< Prioritised ready co-routines. */ -static xList xDelayedCoRoutineList1; /*< Delayed co-routines. */ -static xList xDelayedCoRoutineList2; /*< Delayed co-routines (two lists are used - one for delays that have overflowed the current tick count. */ -static xList * pxDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used. */ -static xList * pxOverflowDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used to hold co-routines that have overflowed the current tick count. */ -static xList xPendingReadyCoRoutineList; /*< Holds co-routines that have been readied by an external event. They cannot be added directly to the ready lists as the ready lists cannot be accessed by interrupts. */ - -/* Other file private variables. --------------------------------*/ -corCRCB * pxCurrentCoRoutine = NULL; -static unsigned portBASE_TYPE uxTopCoRoutineReadyPriority = 0; -static portTickType xCoRoutineTickCount = 0, xLastTickCount = 0, xPassedTicks = 0; - -/* The initial state of the co-routine when it is created. */ -#define corINITIAL_STATE ( 0 ) - -/* - * Place the co-routine represented by pxCRCB into the appropriate ready queue - * for the priority. It is inserted at the end of the list. - * - * This macro accesses the co-routine ready lists and therefore must not be - * used from within an ISR. - */ -#define prvAddCoRoutineToReadyQueue( pxCRCB ) \ -{ \ - if( pxCRCB->uxPriority > uxTopCoRoutineReadyPriority ) \ - { \ - uxTopCoRoutineReadyPriority = pxCRCB->uxPriority; \ - } \ - vListInsertEnd( ( xList * ) &( pxReadyCoRoutineLists[ pxCRCB->uxPriority ] ), &( pxCRCB->xGenericListItem ) ); \ -} - -/* - * Utility to ready all the lists used by the scheduler. This is called - * automatically upon the creation of the first co-routine. - */ -static void prvInitialiseCoRoutineLists( void ); - -/* - * Co-routines that are readied by an interrupt cannot be placed directly into - * the ready lists (there is no mutual exclusion). Instead they are placed in - * in the pending ready list in order that they can later be moved to the ready - * list by the co-routine scheduler. - */ -static void prvCheckPendingReadyList( void ); - -/* - * Macro that looks at the list of co-routines that are currently delayed to - * see if any require waking. - * - * Co-routines are stored in the queue in the order of their wake time - - * meaning once one co-routine has been found whose timer has not expired - * we need not look any further down the list. - */ -static void prvCheckDelayedList( void ); - -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ) -{ -signed portBASE_TYPE xReturn; -corCRCB *pxCoRoutine; - - /* Allocate the memory that will store the co-routine control block. */ - pxCoRoutine = ( corCRCB * ) pvPortMalloc( sizeof( corCRCB ) ); - if( pxCoRoutine ) - { - /* If pxCurrentCoRoutine is NULL then this is the first co-routine to - be created and the co-routine data structures need initialising. */ - if( pxCurrentCoRoutine == NULL ) - { - pxCurrentCoRoutine = pxCoRoutine; - prvInitialiseCoRoutineLists(); - } - - /* Check the priority is within limits. */ - if( uxPriority >= configMAX_CO_ROUTINE_PRIORITIES ) - { - uxPriority = configMAX_CO_ROUTINE_PRIORITIES - 1; - } - - /* Fill out the co-routine control block from the function parameters. */ - pxCoRoutine->uxState = corINITIAL_STATE; - pxCoRoutine->uxPriority = uxPriority; - pxCoRoutine->uxIndex = uxIndex; - pxCoRoutine->pxCoRoutineFunction = pxCoRoutineCode; - - /* Initialise all the other co-routine control block parameters. */ - vListInitialiseItem( &( pxCoRoutine->xGenericListItem ) ); - vListInitialiseItem( &( pxCoRoutine->xEventListItem ) ); - - /* Set the co-routine control block as a link back from the xListItem. - This is so we can get back to the containing CRCB from a generic item - in a list. */ - listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xGenericListItem ), pxCoRoutine ); - listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xEventListItem ), pxCoRoutine ); - - /* Event lists are always in priority order. */ - listSET_LIST_ITEM_VALUE( &( pxCoRoutine->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); - - /* Now the co-routine has been initialised it can be added to the ready - list at the correct priority. */ - prvAddCoRoutineToReadyQueue( pxCoRoutine ); - - xReturn = pdPASS; - } - else - { - xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; - } - - return xReturn; -} -/*-----------------------------------------------------------*/ - -void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ) -{ -portTickType xTimeToWake; - - /* Calculate the time to wake - this may overflow but this is - not a problem. */ - xTimeToWake = xCoRoutineTickCount + xTicksToDelay; - - /* We must remove ourselves from the ready list before adding - ourselves to the blocked list as the same list item is used for - both lists. */ - vListRemove( ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - - /* The list item will be inserted in wake time order. */ - listSET_LIST_ITEM_VALUE( &( pxCurrentCoRoutine->xGenericListItem ), xTimeToWake ); - - if( xTimeToWake < xCoRoutineTickCount ) - { - /* Wake time has overflowed. Place this item in the - overflow list. */ - vListInsert( ( xList * ) pxOverflowDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - } - else - { - /* The wake time has not overflowed, so we can use the - current block list. */ - vListInsert( ( xList * ) pxDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); - } - - if( pxEventList ) - { - /* Also add the co-routine to an event list. If this is done then the - function must be called with interrupts disabled. */ - vListInsert( pxEventList, &( pxCurrentCoRoutine->xEventListItem ) ); - } -} -/*-----------------------------------------------------------*/ - -static void prvCheckPendingReadyList( void ) -{ - /* Are there any co-routines waiting to get moved to the ready list? These - are co-routines that have been readied by an ISR. The ISR cannot access - the ready lists itself. */ - while( !listLIST_IS_EMPTY( &xPendingReadyCoRoutineList ) ) - { - corCRCB *pxUnblockedCRCB; - - /* The pending ready list can be accessed by an ISR. */ - portDISABLE_INTERRUPTS(); - { - pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( (&xPendingReadyCoRoutineList) ); - vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); - } - portENABLE_INTERRUPTS(); - - vListRemove( &( pxUnblockedCRCB->xGenericListItem ) ); - prvAddCoRoutineToReadyQueue( pxUnblockedCRCB ); - } -} -/*-----------------------------------------------------------*/ - -static void prvCheckDelayedList( void ) -{ -corCRCB *pxCRCB; - - xPassedTicks = xTaskGetTickCount() - xLastTickCount; - while( xPassedTicks ) - { - xCoRoutineTickCount++; - xPassedTicks--; - - /* If the tick count has overflowed we need to swap the ready lists. */ - if( xCoRoutineTickCount == 0 ) - { - xList * pxTemp; - - /* Tick count has overflowed so we need to swap the delay lists. If there are - any items in pxDelayedCoRoutineList here then there is an error! */ - pxTemp = pxDelayedCoRoutineList; - pxDelayedCoRoutineList = pxOverflowDelayedCoRoutineList; - pxOverflowDelayedCoRoutineList = pxTemp; - } - - /* See if this tick has made a timeout expire. */ - while( ( pxCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedCoRoutineList ) ) != NULL ) - { - if( xCoRoutineTickCount < listGET_LIST_ITEM_VALUE( &( pxCRCB->xGenericListItem ) ) ) - { - /* Timeout not yet expired. */ - break; - } - - portDISABLE_INTERRUPTS(); - { - /* The event could have occurred just before this critical - section. If this is the case then the generic list item will - have been moved to the pending ready list and the following - line is still valid. Also the pvContainer parameter will have - been set to NULL so the following lines are also valid. */ - vListRemove( &( pxCRCB->xGenericListItem ) ); - - /* Is the co-routine waiting on an event also? */ - if( pxCRCB->xEventListItem.pvContainer ) - { - vListRemove( &( pxCRCB->xEventListItem ) ); - } - } - portENABLE_INTERRUPTS(); - - prvAddCoRoutineToReadyQueue( pxCRCB ); - } - } - - xLastTickCount = xCoRoutineTickCount; -} -/*-----------------------------------------------------------*/ - -void vCoRoutineSchedule( void ) -{ - /* See if any co-routines readied by events need moving to the ready lists. */ - prvCheckPendingReadyList(); - - /* See if any delayed co-routines have timed out. */ - prvCheckDelayedList(); - - /* Find the highest priority queue that contains ready co-routines. */ - while( listLIST_IS_EMPTY( &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ) ) - { - if( uxTopCoRoutineReadyPriority == 0 ) - { - /* No more co-routines to check. */ - return; - } - --uxTopCoRoutineReadyPriority; - } - - /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the co-routines - of the same priority get an equal share of the processor time. */ - listGET_OWNER_OF_NEXT_ENTRY( pxCurrentCoRoutine, &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ); - - /* Call the co-routine. */ - ( pxCurrentCoRoutine->pxCoRoutineFunction )( pxCurrentCoRoutine, pxCurrentCoRoutine->uxIndex ); - - return; -} -/*-----------------------------------------------------------*/ - -static void prvInitialiseCoRoutineLists( void ) -{ -unsigned portBASE_TYPE uxPriority; - - for( uxPriority = 0; uxPriority < configMAX_CO_ROUTINE_PRIORITIES; uxPriority++ ) - { - vListInitialise( ( xList * ) &( pxReadyCoRoutineLists[ uxPriority ] ) ); - } - - vListInitialise( ( xList * ) &xDelayedCoRoutineList1 ); - vListInitialise( ( xList * ) &xDelayedCoRoutineList2 ); - vListInitialise( ( xList * ) &xPendingReadyCoRoutineList ); - - /* Start with pxDelayedCoRoutineList using list1 and the - pxOverflowDelayedCoRoutineList using list2. */ - pxDelayedCoRoutineList = &xDelayedCoRoutineList1; - pxOverflowDelayedCoRoutineList = &xDelayedCoRoutineList2; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ) -{ -corCRCB *pxUnblockedCRCB; -signed portBASE_TYPE xReturn; - - /* This function is called from within an interrupt. It can only access - event lists and the pending ready list. */ - pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); - vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); - vListInsertEnd( ( xList * ) &( xPendingReadyCoRoutineList ), &( pxUnblockedCRCB->xEventListItem ) ); - - if( pxUnblockedCRCB->uxPriority >= pxCurrentCoRoutine->uxPriority ) - { - xReturn = pdTRUE; - } - else - { - xReturn = pdFALSE; - } - - return xReturn; -} - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#include "FreeRTOS.h" +#include "task.h" +#include "croutine.h" + +/* + * Some kernel aware debuggers require data to be viewed to be global, rather + * than file scope. + */ +#ifdef portREMOVE_STATIC_QUALIFIER + #define static +#endif + + +/* Lists for ready and blocked co-routines. --------------------*/ +static xList pxReadyCoRoutineLists[ configMAX_CO_ROUTINE_PRIORITIES ]; /*< Prioritised ready co-routines. */ +static xList xDelayedCoRoutineList1; /*< Delayed co-routines. */ +static xList xDelayedCoRoutineList2; /*< Delayed co-routines (two lists are used - one for delays that have overflowed the current tick count. */ +static xList * pxDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used. */ +static xList * pxOverflowDelayedCoRoutineList; /*< Points to the delayed co-routine list currently being used to hold co-routines that have overflowed the current tick count. */ +static xList xPendingReadyCoRoutineList; /*< Holds co-routines that have been readied by an external event. They cannot be added directly to the ready lists as the ready lists cannot be accessed by interrupts. */ + +/* Other file private variables. --------------------------------*/ +corCRCB * pxCurrentCoRoutine = NULL; +static unsigned portBASE_TYPE uxTopCoRoutineReadyPriority = 0; +static portTickType xCoRoutineTickCount = 0, xLastTickCount = 0, xPassedTicks = 0; + +/* The initial state of the co-routine when it is created. */ +#define corINITIAL_STATE ( 0 ) + +/* + * Place the co-routine represented by pxCRCB into the appropriate ready queue + * for the priority. It is inserted at the end of the list. + * + * This macro accesses the co-routine ready lists and therefore must not be + * used from within an ISR. + */ +#define prvAddCoRoutineToReadyQueue( pxCRCB ) \ +{ \ + if( pxCRCB->uxPriority > uxTopCoRoutineReadyPriority ) \ + { \ + uxTopCoRoutineReadyPriority = pxCRCB->uxPriority; \ + } \ + vListInsertEnd( ( xList * ) &( pxReadyCoRoutineLists[ pxCRCB->uxPriority ] ), &( pxCRCB->xGenericListItem ) ); \ +} + +/* + * Utility to ready all the lists used by the scheduler. This is called + * automatically upon the creation of the first co-routine. + */ +static void prvInitialiseCoRoutineLists( void ); + +/* + * Co-routines that are readied by an interrupt cannot be placed directly into + * the ready lists (there is no mutual exclusion). Instead they are placed in + * in the pending ready list in order that they can later be moved to the ready + * list by the co-routine scheduler. + */ +static void prvCheckPendingReadyList( void ); + +/* + * Macro that looks at the list of co-routines that are currently delayed to + * see if any require waking. + * + * Co-routines are stored in the queue in the order of their wake time - + * meaning once one co-routine has been found whose timer has not expired + * we need not look any further down the list. + */ +static void prvCheckDelayedList( void ); + +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ) +{ +signed portBASE_TYPE xReturn; +corCRCB *pxCoRoutine; + + /* Allocate the memory that will store the co-routine control block. */ + pxCoRoutine = ( corCRCB * ) pvPortMalloc( sizeof( corCRCB ) ); + if( pxCoRoutine ) + { + /* If pxCurrentCoRoutine is NULL then this is the first co-routine to + be created and the co-routine data structures need initialising. */ + if( pxCurrentCoRoutine == NULL ) + { + pxCurrentCoRoutine = pxCoRoutine; + prvInitialiseCoRoutineLists(); + } + + /* Check the priority is within limits. */ + if( uxPriority >= configMAX_CO_ROUTINE_PRIORITIES ) + { + uxPriority = configMAX_CO_ROUTINE_PRIORITIES - 1; + } + + /* Fill out the co-routine control block from the function parameters. */ + pxCoRoutine->uxState = corINITIAL_STATE; + pxCoRoutine->uxPriority = uxPriority; + pxCoRoutine->uxIndex = uxIndex; + pxCoRoutine->pxCoRoutineFunction = pxCoRoutineCode; + + /* Initialise all the other co-routine control block parameters. */ + vListInitialiseItem( &( pxCoRoutine->xGenericListItem ) ); + vListInitialiseItem( &( pxCoRoutine->xEventListItem ) ); + + /* Set the co-routine control block as a link back from the xListItem. + This is so we can get back to the containing CRCB from a generic item + in a list. */ + listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xGenericListItem ), pxCoRoutine ); + listSET_LIST_ITEM_OWNER( &( pxCoRoutine->xEventListItem ), pxCoRoutine ); + + /* Event lists are always in priority order. */ + listSET_LIST_ITEM_VALUE( &( pxCoRoutine->xEventListItem ), configMAX_PRIORITIES - ( portTickType ) uxPriority ); + + /* Now the co-routine has been initialised it can be added to the ready + list at the correct priority. */ + prvAddCoRoutineToReadyQueue( pxCoRoutine ); + + xReturn = pdPASS; + } + else + { + xReturn = errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY; + } + + return xReturn; +} +/*-----------------------------------------------------------*/ + +void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ) +{ +portTickType xTimeToWake; + + /* Calculate the time to wake - this may overflow but this is + not a problem. */ + xTimeToWake = xCoRoutineTickCount + xTicksToDelay; + + /* We must remove ourselves from the ready list before adding + ourselves to the blocked list as the same list item is used for + both lists. */ + vListRemove( ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + + /* The list item will be inserted in wake time order. */ + listSET_LIST_ITEM_VALUE( &( pxCurrentCoRoutine->xGenericListItem ), xTimeToWake ); + + if( xTimeToWake < xCoRoutineTickCount ) + { + /* Wake time has overflowed. Place this item in the + overflow list. */ + vListInsert( ( xList * ) pxOverflowDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + } + else + { + /* The wake time has not overflowed, so we can use the + current block list. */ + vListInsert( ( xList * ) pxDelayedCoRoutineList, ( xListItem * ) &( pxCurrentCoRoutine->xGenericListItem ) ); + } + + if( pxEventList ) + { + /* Also add the co-routine to an event list. If this is done then the + function must be called with interrupts disabled. */ + vListInsert( pxEventList, &( pxCurrentCoRoutine->xEventListItem ) ); + } +} +/*-----------------------------------------------------------*/ + +static void prvCheckPendingReadyList( void ) +{ + /* Are there any co-routines waiting to get moved to the ready list? These + are co-routines that have been readied by an ISR. The ISR cannot access + the ready lists itself. */ + while( !listLIST_IS_EMPTY( &xPendingReadyCoRoutineList ) ) + { + corCRCB *pxUnblockedCRCB; + + /* The pending ready list can be accessed by an ISR. */ + portDISABLE_INTERRUPTS(); + { + pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( (&xPendingReadyCoRoutineList) ); + vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); + } + portENABLE_INTERRUPTS(); + + vListRemove( &( pxUnblockedCRCB->xGenericListItem ) ); + prvAddCoRoutineToReadyQueue( pxUnblockedCRCB ); + } +} +/*-----------------------------------------------------------*/ + +static void prvCheckDelayedList( void ) +{ +corCRCB *pxCRCB; + + xPassedTicks = xTaskGetTickCount() - xLastTickCount; + while( xPassedTicks ) + { + xCoRoutineTickCount++; + xPassedTicks--; + + /* If the tick count has overflowed we need to swap the ready lists. */ + if( xCoRoutineTickCount == 0 ) + { + xList * pxTemp; + + /* Tick count has overflowed so we need to swap the delay lists. If there are + any items in pxDelayedCoRoutineList here then there is an error! */ + pxTemp = pxDelayedCoRoutineList; + pxDelayedCoRoutineList = pxOverflowDelayedCoRoutineList; + pxOverflowDelayedCoRoutineList = pxTemp; + } + + /* See if this tick has made a timeout expire. */ + while( ( pxCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxDelayedCoRoutineList ) ) != NULL ) + { + if( xCoRoutineTickCount < listGET_LIST_ITEM_VALUE( &( pxCRCB->xGenericListItem ) ) ) + { + /* Timeout not yet expired. */ + break; + } + + portDISABLE_INTERRUPTS(); + { + /* The event could have occurred just before this critical + section. If this is the case then the generic list item will + have been moved to the pending ready list and the following + line is still valid. Also the pvContainer parameter will have + been set to NULL so the following lines are also valid. */ + vListRemove( &( pxCRCB->xGenericListItem ) ); + + /* Is the co-routine waiting on an event also? */ + if( pxCRCB->xEventListItem.pvContainer ) + { + vListRemove( &( pxCRCB->xEventListItem ) ); + } + } + portENABLE_INTERRUPTS(); + + prvAddCoRoutineToReadyQueue( pxCRCB ); + } + } + + xLastTickCount = xCoRoutineTickCount; +} +/*-----------------------------------------------------------*/ + +void vCoRoutineSchedule( void ) +{ + /* See if any co-routines readied by events need moving to the ready lists. */ + prvCheckPendingReadyList(); + + /* See if any delayed co-routines have timed out. */ + prvCheckDelayedList(); + + /* Find the highest priority queue that contains ready co-routines. */ + while( listLIST_IS_EMPTY( &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ) ) + { + if( uxTopCoRoutineReadyPriority == 0 ) + { + /* No more co-routines to check. */ + return; + } + --uxTopCoRoutineReadyPriority; + } + + /* listGET_OWNER_OF_NEXT_ENTRY walks through the list, so the co-routines + of the same priority get an equal share of the processor time. */ + listGET_OWNER_OF_NEXT_ENTRY( pxCurrentCoRoutine, &( pxReadyCoRoutineLists[ uxTopCoRoutineReadyPriority ] ) ); + + /* Call the co-routine. */ + ( pxCurrentCoRoutine->pxCoRoutineFunction )( pxCurrentCoRoutine, pxCurrentCoRoutine->uxIndex ); + + return; +} +/*-----------------------------------------------------------*/ + +static void prvInitialiseCoRoutineLists( void ) +{ +unsigned portBASE_TYPE uxPriority; + + for( uxPriority = 0; uxPriority < configMAX_CO_ROUTINE_PRIORITIES; uxPriority++ ) + { + vListInitialise( ( xList * ) &( pxReadyCoRoutineLists[ uxPriority ] ) ); + } + + vListInitialise( ( xList * ) &xDelayedCoRoutineList1 ); + vListInitialise( ( xList * ) &xDelayedCoRoutineList2 ); + vListInitialise( ( xList * ) &xPendingReadyCoRoutineList ); + + /* Start with pxDelayedCoRoutineList using list1 and the + pxOverflowDelayedCoRoutineList using list2. */ + pxDelayedCoRoutineList = &xDelayedCoRoutineList1; + pxOverflowDelayedCoRoutineList = &xDelayedCoRoutineList2; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ) +{ +corCRCB *pxUnblockedCRCB; +signed portBASE_TYPE xReturn; + + /* This function is called from within an interrupt. It can only access + event lists and the pending ready list. */ + pxUnblockedCRCB = ( corCRCB * ) listGET_OWNER_OF_HEAD_ENTRY( pxEventList ); + vListRemove( &( pxUnblockedCRCB->xEventListItem ) ); + vListInsertEnd( ( xList * ) &( xPendingReadyCoRoutineList ), &( pxUnblockedCRCB->xEventListItem ) ); + + if( pxUnblockedCRCB->uxPriority >= pxCurrentCoRoutine->uxPriority ) + { + xReturn = pdTRUE; + } + else + { + xReturn = pdFALSE; + } + + return xReturn; +} + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/FreeRTOS.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/FreeRTOS.h index ee02592ae..13dbb70e5 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/FreeRTOS.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/FreeRTOS.h @@ -1,420 +1,420 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef INC_FREERTOS_H -#define INC_FREERTOS_H - - -/* - * Include the generic headers required for the FreeRTOS port being used. - */ -#include - -/* Basic FreeRTOS definitions. */ -#include "projdefs.h" - -/* Application specific configuration options. */ -#include "FreeRTOSConfig.h" - -/* Definitions specific to the port being used. */ -#include "portable.h" - - -/* Defines the prototype to which the application task hook function must -conform. */ -typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); - - - - - -/* - * Check all the required application specific macros have been defined. - * These macros are application specific and (as downloaded) are defined - * within FreeRTOSConfig.h. - */ - -#ifndef configUSE_PREEMPTION - #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_IDLE_HOOK - #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_TICK_HOOK - #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_CO_ROUTINES - #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskPrioritySet - #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_uxTaskPriorityGet - #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelete - #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskCleanUpResources - #error Missing definition: INCLUDE_vTaskCleanUpResources should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskSuspend - #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelayUntil - #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef INCLUDE_vTaskDelay - #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_16_BIT_TICKS - #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. -#endif - -#ifndef configUSE_APPLICATION_TASK_TAG - #define configUSE_APPLICATION_TASK_TAG 0 -#endif - -#ifndef INCLUDE_uxTaskGetStackHighWaterMark - #define INCLUDE_uxTaskGetStackHighWaterMark 0 -#endif - -#ifndef configUSE_RECURSIVE_MUTEXES - #define configUSE_RECURSIVE_MUTEXES 0 -#endif - -#ifndef configUSE_MUTEXES - #define configUSE_MUTEXES 0 -#endif - -#ifndef configUSE_COUNTING_SEMAPHORES - #define configUSE_COUNTING_SEMAPHORES 0 -#endif - -#ifndef configUSE_ALTERNATIVE_API - #define configUSE_ALTERNATIVE_API 0 -#endif - -#ifndef portCRITICAL_NESTING_IN_TCB - #define portCRITICAL_NESTING_IN_TCB 0 -#endif - -#ifndef configMAX_TASK_NAME_LEN - #define configMAX_TASK_NAME_LEN 16 -#endif - -#ifndef configIDLE_SHOULD_YIELD - #define configIDLE_SHOULD_YIELD 1 -#endif - -#if configMAX_TASK_NAME_LEN < 1 - #undef configMAX_TASK_NAME_LEN - #define configMAX_TASK_NAME_LEN 1 -#endif - -#ifndef INCLUDE_xTaskResumeFromISR - #define INCLUDE_xTaskResumeFromISR 1 -#endif - -#ifndef INCLUDE_xTaskGetSchedulerState - #define INCLUDE_xTaskGetSchedulerState 0 -#endif - -#if ( configUSE_MUTEXES == 1 ) - /* xTaskGetCurrentTaskHandle is used by the priority inheritance mechanism - within the mutex implementation so must be available if mutexes are used. */ - #undef INCLUDE_xTaskGetCurrentTaskHandle - #define INCLUDE_xTaskGetCurrentTaskHandle 1 -#else - #ifndef INCLUDE_xTaskGetCurrentTaskHandle - #define INCLUDE_xTaskGetCurrentTaskHandle 0 - #endif -#endif - - -#ifndef portSET_INTERRUPT_MASK_FROM_ISR - #define portSET_INTERRUPT_MASK_FROM_ISR() 0 -#endif - -#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR - #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue -#endif - - -#ifndef configQUEUE_REGISTRY_SIZE - #define configQUEUE_REGISTRY_SIZE 0 -#endif - -#if configQUEUE_REGISTRY_SIZE < 1 - #define configQUEUE_REGISTRY_SIZE 0 - #define vQueueAddToRegistry( xQueue, pcName ) - #define vQueueUnregisterQueue( xQueue ) -#endif - - -/* Remove any unused trace macros. */ -#ifndef traceSTART - /* Used to perform any necessary initialisation - for example, open a file - into which trace is to be written. */ - #define traceSTART() -#endif - -#ifndef traceEND - /* Use to close a trace, for example close a file into which trace has been - written. */ - #define traceEND() -#endif - -#ifndef traceTASK_SWITCHED_IN - /* Called after a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the selected task. */ - #define traceTASK_SWITCHED_IN() -#endif - -#ifndef traceTASK_SWITCHED_OUT - /* Called before a task has been selected to run. pxCurrentTCB holds a pointer - to the task control block of the task being switched out. */ - #define traceTASK_SWITCHED_OUT() -#endif - -#ifndef traceBLOCKING_ON_QUEUE_RECEIVE - /* Task is about to block because it cannot read from a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the read was attempted. pxCurrentTCB points to the TCB of the - task that attempted the read. */ - #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceBLOCKING_ON_QUEUE_SEND - /* Task is about to block because it cannot write to a - queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore - upon which the write was attempted. pxCurrentTCB points to the TCB of the - task that attempted the write. */ - #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) -#endif - -#ifndef configCHECK_FOR_STACK_OVERFLOW - #define configCHECK_FOR_STACK_OVERFLOW 0 -#endif - -/* The following event macros are embedded in the kernel API calls. */ - -#ifndef traceQUEUE_CREATE - #define traceQUEUE_CREATE( pxNewQueue ) -#endif - -#ifndef traceQUEUE_CREATE_FAILED - #define traceQUEUE_CREATE_FAILED() -#endif - -#ifndef traceCREATE_MUTEX - #define traceCREATE_MUTEX( pxNewQueue ) -#endif - -#ifndef traceCREATE_MUTEX_FAILED - #define traceCREATE_MUTEX_FAILED() -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE - #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED - #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) -#endif - -#ifndef traceTAKE_MUTEX_RECURSIVE - #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE - #define traceCREATE_COUNTING_SEMAPHORE() -#endif - -#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED - #define traceCREATE_COUNTING_SEMAPHORE_FAILED() -#endif - -#ifndef traceQUEUE_SEND - #define traceQUEUE_SEND( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FAILED - #define traceQUEUE_SEND_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE - #define traceQUEUE_RECEIVE( pxQueue ) -#endif - -#ifndef traceQUEUE_PEEK - #define traceQUEUE_PEEK( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FAILED - #define traceQUEUE_RECEIVE_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR - #define traceQUEUE_SEND_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_SEND_FROM_ISR_FAILED - #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR - #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) -#endif - -#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED - #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) -#endif - -#ifndef traceQUEUE_DELETE - #define traceQUEUE_DELETE( pxQueue ) -#endif - -#ifndef traceTASK_CREATE - #define traceTASK_CREATE( pxNewTCB ) -#endif - -#ifndef traceTASK_CREATE_FAILED - #define traceTASK_CREATE_FAILED( pxNewTCB ) -#endif - -#ifndef traceTASK_DELETE - #define traceTASK_DELETE( pxTaskToDelete ) -#endif - -#ifndef traceTASK_DELAY_UNTIL - #define traceTASK_DELAY_UNTIL() -#endif - -#ifndef traceTASK_DELAY - #define traceTASK_DELAY() -#endif - -#ifndef traceTASK_PRIORITY_SET - #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) -#endif - -#ifndef traceTASK_SUSPEND - #define traceTASK_SUSPEND( pxTaskToSuspend ) -#endif - -#ifndef traceTASK_RESUME - #define traceTASK_RESUME( pxTaskToResume ) -#endif - -#ifndef traceTASK_RESUME_FROM_ISR - #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) -#endif - -#ifndef traceTASK_INCREMENT_TICK - #define traceTASK_INCREMENT_TICK( xTickCount ) -#endif - -#ifndef configGENERATE_RUN_TIME_STATS - #define configGENERATE_RUN_TIME_STATS 0 -#endif - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - - #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. - #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ - - #ifndef portGET_RUN_TIME_COUNTER_VALUE - #error If configGENERATE_RUN_TIME_STATS is defined then portGET_RUN_TIME_COUNTER_VALUE must also be defined. portGET_RUN_TIME_COUNTER_VALUE should evaluate to the counter value of the timer/counter peripheral used as the run time counter time base. - #endif /* portGET_RUN_TIME_COUNTER_VALUE */ - -#endif /* configGENERATE_RUN_TIME_STATS */ - -#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS - #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() -#endif - -#ifndef configUSE_MALLOC_FAILED_HOOK - #define configUSE_MALLOC_FAILED_HOOK 0 -#endif - -#ifndef portPRIVILEGE_BIT - #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) -#endif - -#ifndef portYIELD_WITHIN_API - #define portYIELD_WITHIN_API portYIELD -#endif - -#ifndef pvPortMallocAligned - #define pvPortMallocAligned( x, puxStackBuffer ) ( ( puxStackBuffer == NULL ) ? ( pvPortMalloc( x ) ) : ( puxStackBuffer ) ) -#endif - -#ifndef vPortFreeAligned - #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) -#endif - -#endif /* INC_FREERTOS_H */ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef INC_FREERTOS_H +#define INC_FREERTOS_H + + +/* + * Include the generic headers required for the FreeRTOS port being used. + */ +#include + +/* Basic FreeRTOS definitions. */ +#include "projdefs.h" + +/* Application specific configuration options. */ +#include "FreeRTOSConfig.h" + +/* Definitions specific to the port being used. */ +#include "portable.h" + + +/* Defines the prototype to which the application task hook function must +conform. */ +typedef portBASE_TYPE (*pdTASK_HOOK_CODE)( void * ); + + + + + +/* + * Check all the required application specific macros have been defined. + * These macros are application specific and (as downloaded) are defined + * within FreeRTOSConfig.h. + */ + +#ifndef configUSE_PREEMPTION + #error Missing definition: configUSE_PREEMPTION should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_IDLE_HOOK + #error Missing definition: configUSE_IDLE_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_TICK_HOOK + #error Missing definition: configUSE_TICK_HOOK should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_CO_ROUTINES + #error Missing definition: configUSE_CO_ROUTINES should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskPrioritySet + #error Missing definition: INCLUDE_vTaskPrioritySet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_uxTaskPriorityGet + #error Missing definition: INCLUDE_uxTaskPriorityGet should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelete + #error Missing definition: INCLUDE_vTaskDelete should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskCleanUpResources + #error Missing definition: INCLUDE_vTaskCleanUpResources should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskSuspend + #error Missing definition: INCLUDE_vTaskSuspend should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelayUntil + #error Missing definition: INCLUDE_vTaskDelayUntil should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef INCLUDE_vTaskDelay + #error Missing definition: INCLUDE_vTaskDelay should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_16_BIT_TICKS + #error Missing definition: configUSE_16_BIT_TICKS should be defined in FreeRTOSConfig.h as either 1 or 0. See the Configuration section of the FreeRTOS API documentation for details. +#endif + +#ifndef configUSE_APPLICATION_TASK_TAG + #define configUSE_APPLICATION_TASK_TAG 0 +#endif + +#ifndef INCLUDE_uxTaskGetStackHighWaterMark + #define INCLUDE_uxTaskGetStackHighWaterMark 0 +#endif + +#ifndef configUSE_RECURSIVE_MUTEXES + #define configUSE_RECURSIVE_MUTEXES 0 +#endif + +#ifndef configUSE_MUTEXES + #define configUSE_MUTEXES 0 +#endif + +#ifndef configUSE_COUNTING_SEMAPHORES + #define configUSE_COUNTING_SEMAPHORES 0 +#endif + +#ifndef configUSE_ALTERNATIVE_API + #define configUSE_ALTERNATIVE_API 0 +#endif + +#ifndef portCRITICAL_NESTING_IN_TCB + #define portCRITICAL_NESTING_IN_TCB 0 +#endif + +#ifndef configMAX_TASK_NAME_LEN + #define configMAX_TASK_NAME_LEN 16 +#endif + +#ifndef configIDLE_SHOULD_YIELD + #define configIDLE_SHOULD_YIELD 1 +#endif + +#if configMAX_TASK_NAME_LEN < 1 + #undef configMAX_TASK_NAME_LEN + #define configMAX_TASK_NAME_LEN 1 +#endif + +#ifndef INCLUDE_xTaskResumeFromISR + #define INCLUDE_xTaskResumeFromISR 1 +#endif + +#ifndef INCLUDE_xTaskGetSchedulerState + #define INCLUDE_xTaskGetSchedulerState 0 +#endif + +#if ( configUSE_MUTEXES == 1 ) + /* xTaskGetCurrentTaskHandle is used by the priority inheritance mechanism + within the mutex implementation so must be available if mutexes are used. */ + #undef INCLUDE_xTaskGetCurrentTaskHandle + #define INCLUDE_xTaskGetCurrentTaskHandle 1 +#else + #ifndef INCLUDE_xTaskGetCurrentTaskHandle + #define INCLUDE_xTaskGetCurrentTaskHandle 0 + #endif +#endif + + +#ifndef portSET_INTERRUPT_MASK_FROM_ISR + #define portSET_INTERRUPT_MASK_FROM_ISR() 0 +#endif + +#ifndef portCLEAR_INTERRUPT_MASK_FROM_ISR + #define portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedStatusValue ) ( void ) uxSavedStatusValue +#endif + + +#ifndef configQUEUE_REGISTRY_SIZE + #define configQUEUE_REGISTRY_SIZE 0 +#endif + +#if configQUEUE_REGISTRY_SIZE < 1 + #define configQUEUE_REGISTRY_SIZE 0 + #define vQueueAddToRegistry( xQueue, pcName ) + #define vQueueUnregisterQueue( xQueue ) +#endif + + +/* Remove any unused trace macros. */ +#ifndef traceSTART + /* Used to perform any necessary initialisation - for example, open a file + into which trace is to be written. */ + #define traceSTART() +#endif + +#ifndef traceEND + /* Use to close a trace, for example close a file into which trace has been + written. */ + #define traceEND() +#endif + +#ifndef traceTASK_SWITCHED_IN + /* Called after a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the selected task. */ + #define traceTASK_SWITCHED_IN() +#endif + +#ifndef traceTASK_SWITCHED_OUT + /* Called before a task has been selected to run. pxCurrentTCB holds a pointer + to the task control block of the task being switched out. */ + #define traceTASK_SWITCHED_OUT() +#endif + +#ifndef traceBLOCKING_ON_QUEUE_RECEIVE + /* Task is about to block because it cannot read from a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the read was attempted. pxCurrentTCB points to the TCB of the + task that attempted the read. */ + #define traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceBLOCKING_ON_QUEUE_SEND + /* Task is about to block because it cannot write to a + queue/mutex/semaphore. pxQueue is a pointer to the queue/mutex/semaphore + upon which the write was attempted. pxCurrentTCB points to the TCB of the + task that attempted the write. */ + #define traceBLOCKING_ON_QUEUE_SEND( pxQueue ) +#endif + +#ifndef configCHECK_FOR_STACK_OVERFLOW + #define configCHECK_FOR_STACK_OVERFLOW 0 +#endif + +/* The following event macros are embedded in the kernel API calls. */ + +#ifndef traceQUEUE_CREATE + #define traceQUEUE_CREATE( pxNewQueue ) +#endif + +#ifndef traceQUEUE_CREATE_FAILED + #define traceQUEUE_CREATE_FAILED() +#endif + +#ifndef traceCREATE_MUTEX + #define traceCREATE_MUTEX( pxNewQueue ) +#endif + +#ifndef traceCREATE_MUTEX_FAILED + #define traceCREATE_MUTEX_FAILED() +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE + #define traceGIVE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceGIVE_MUTEX_RECURSIVE_FAILED + #define traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ) +#endif + +#ifndef traceTAKE_MUTEX_RECURSIVE + #define traceTAKE_MUTEX_RECURSIVE( pxMutex ) +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE + #define traceCREATE_COUNTING_SEMAPHORE() +#endif + +#ifndef traceCREATE_COUNTING_SEMAPHORE_FAILED + #define traceCREATE_COUNTING_SEMAPHORE_FAILED() +#endif + +#ifndef traceQUEUE_SEND + #define traceQUEUE_SEND( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FAILED + #define traceQUEUE_SEND_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE + #define traceQUEUE_RECEIVE( pxQueue ) +#endif + +#ifndef traceQUEUE_PEEK + #define traceQUEUE_PEEK( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FAILED + #define traceQUEUE_RECEIVE_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR + #define traceQUEUE_SEND_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_SEND_FROM_ISR_FAILED + #define traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR + #define traceQUEUE_RECEIVE_FROM_ISR( pxQueue ) +#endif + +#ifndef traceQUEUE_RECEIVE_FROM_ISR_FAILED + #define traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ) +#endif + +#ifndef traceQUEUE_DELETE + #define traceQUEUE_DELETE( pxQueue ) +#endif + +#ifndef traceTASK_CREATE + #define traceTASK_CREATE( pxNewTCB ) +#endif + +#ifndef traceTASK_CREATE_FAILED + #define traceTASK_CREATE_FAILED( pxNewTCB ) +#endif + +#ifndef traceTASK_DELETE + #define traceTASK_DELETE( pxTaskToDelete ) +#endif + +#ifndef traceTASK_DELAY_UNTIL + #define traceTASK_DELAY_UNTIL() +#endif + +#ifndef traceTASK_DELAY + #define traceTASK_DELAY() +#endif + +#ifndef traceTASK_PRIORITY_SET + #define traceTASK_PRIORITY_SET( pxTask, uxNewPriority ) +#endif + +#ifndef traceTASK_SUSPEND + #define traceTASK_SUSPEND( pxTaskToSuspend ) +#endif + +#ifndef traceTASK_RESUME + #define traceTASK_RESUME( pxTaskToResume ) +#endif + +#ifndef traceTASK_RESUME_FROM_ISR + #define traceTASK_RESUME_FROM_ISR( pxTaskToResume ) +#endif + +#ifndef traceTASK_INCREMENT_TICK + #define traceTASK_INCREMENT_TICK( xTickCount ) +#endif + +#ifndef configGENERATE_RUN_TIME_STATS + #define configGENERATE_RUN_TIME_STATS 0 +#endif + +#if ( configGENERATE_RUN_TIME_STATS == 1 ) + + #ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #error If configGENERATE_RUN_TIME_STATS is defined then portCONFIGURE_TIMER_FOR_RUN_TIME_STATS must also be defined. portCONFIGURE_TIMER_FOR_RUN_TIME_STATS should call a port layer function to setup a peripheral timer/counter that can then be used as the run time counter time base. + #endif /* portCONFIGURE_TIMER_FOR_RUN_TIME_STATS */ + + #ifndef portGET_RUN_TIME_COUNTER_VALUE + #error If configGENERATE_RUN_TIME_STATS is defined then portGET_RUN_TIME_COUNTER_VALUE must also be defined. portGET_RUN_TIME_COUNTER_VALUE should evaluate to the counter value of the timer/counter peripheral used as the run time counter time base. + #endif /* portGET_RUN_TIME_COUNTER_VALUE */ + +#endif /* configGENERATE_RUN_TIME_STATS */ + +#ifndef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS + #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() +#endif + +#ifndef configUSE_MALLOC_FAILED_HOOK + #define configUSE_MALLOC_FAILED_HOOK 0 +#endif + +#ifndef portPRIVILEGE_BIT + #define portPRIVILEGE_BIT ( ( unsigned portBASE_TYPE ) 0x00 ) +#endif + +#ifndef portYIELD_WITHIN_API + #define portYIELD_WITHIN_API portYIELD +#endif + +#ifndef pvPortMallocAligned + #define pvPortMallocAligned( x, puxStackBuffer ) ( ( puxStackBuffer == NULL ) ? ( pvPortMalloc( x ) ) : ( puxStackBuffer ) ) +#endif + +#ifndef vPortFreeAligned + #define vPortFreeAligned( pvBlockToFree ) vPortFree( pvBlockToFree ) +#endif + +#endif /* INC_FREERTOS_H */ + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/StackMacros.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/StackMacros.h index a7514d790..baeb7bafa 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/StackMacros.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/StackMacros.h @@ -1,173 +1,173 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef STACK_MACROS_H -#define STACK_MACROS_H - -/* - * Call the stack overflow hook function if the stack of the task being swapped - * out is currently overflowed, or looks like it might have overflowed in the - * past. - * - * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check - * the current stack state only - comparing the current top of stack value to - * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 - * will also cause the last few stack bytes to be checked to ensure the value - * to which the bytes were set when the task was created have not been - * overwritten. Note this second test does not guarantee that an overflowed - * stack will always be recognised. - */ - -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) - - /* FreeRTOSConfig.h is not set to check for stack overflows. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ -/*-----------------------------------------------------------*/ - -#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) - - /* FreeRTOSConfig.h is only set to use the first method of - overflow checking. */ - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() - -#endif -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ - \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) - - /* Only the current stack state is to be checked. */ - #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ - { \ - extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ - \ - /* Is the currently saved stack pointer within the stack limit? */ \ - if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) - - #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ - { \ - extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ - char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ - static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ - tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ - \ - \ - pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ - \ - /* Has the extremity of the task stack ever been written over? */ \ - if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ - { \ - vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ - } \ - } - -#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ -/*-----------------------------------------------------------*/ - -#endif /* STACK_MACROS_H */ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef STACK_MACROS_H +#define STACK_MACROS_H + +/* + * Call the stack overflow hook function if the stack of the task being swapped + * out is currently overflowed, or looks like it might have overflowed in the + * past. + * + * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check + * the current stack state only - comparing the current top of stack value to + * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 + * will also cause the last few stack bytes to be checked to ensure the value + * to which the bytes were set when the task was created have not been + * overwritten. Note this second test does not guarantee that an overflowed + * stack will always be recognised. + */ + +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 0 ) + + /* FreeRTOSConfig.h is not set to check for stack overflows. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 0 */ +/*-----------------------------------------------------------*/ + +#if( configCHECK_FOR_STACK_OVERFLOW == 1 ) + + /* FreeRTOSConfig.h is only set to use the first method of + overflow checking. */ + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() + +#endif +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH < 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW > 0 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 0 ) && ( portSTACK_GROWTH > 0 ) ) + + /* Only the current stack state is to be checked. */ + #define taskFIRST_CHECK_FOR_STACK_OVERFLOW() \ + { \ + extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ + \ + /* Is the currently saved stack pointer within the stack limit? */ \ + if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pxCurrentTCB->pxStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) + + #define taskSECOND_CHECK_FOR_STACK_OVERFLOW() \ + { \ + extern void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed char *pcTaskName ); \ + char *pcEndOfStack = ( char * ) pxCurrentTCB->pxEndOfStack; \ + static const unsigned char ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ + tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ + \ + \ + pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ + \ + /* Has the extremity of the task stack ever been written over? */ \ + if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ + { \ + vApplicationStackOverflowHook( ( xTaskHandle ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ + } \ + } + +#endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ +/*-----------------------------------------------------------*/ + +#endif /* STACK_MACROS_H */ + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/croutine.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/croutine.h index c189a1e87..32f19198f 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/croutine.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/croutine.h @@ -1,749 +1,749 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include croutine.h" -#endif - - - - -#ifndef CO_ROUTINE_H -#define CO_ROUTINE_H - -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/* Used to hide the implementation of the co-routine control block. The -control block structure however has to be included in the header due to -the macro implementation of the co-routine functionality. */ -typedef void * xCoRoutineHandle; - -/* Defines the prototype to which co-routine functions must conform. */ -typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); - -typedef struct corCoRoutineControlBlock -{ - crCOROUTINE_CODE pxCoRoutineFunction; - xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ - xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ - unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ - unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ - unsigned short uxState; /*< Used internally by the co-routine implementation. */ -} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ - -/** - * croutine. h - *
- portBASE_TYPE xCoRoutineCreate(
-                                 crCOROUTINE_CODE pxCoRoutineCode,
-                                 unsigned portBASE_TYPE uxPriority,
-                                 unsigned portBASE_TYPE uxIndex
-                               );
- * - * Create a new co-routine and add it to the list of co-routines that are - * ready to run. - * - * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine - * functions require special syntax - see the co-routine section of the WEB - * documentation for more information. - * - * @param uxPriority The priority with respect to other co-routines at which - * the co-routine will run. - * - * @param uxIndex Used to distinguish between different co-routines that - * execute the same function. See the example below and the co-routine section - * of the WEB documentation for further information. - * - * @return pdPASS if the co-routine was successfully created and added to a ready - * list, otherwise an error code defined with ProjDefs.h. - * - * Example usage: -
- // Co-routine to be created.
- void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- static const char cLedToFlash[ 2 ] = { 5, 6 };
- static const portTickType xTimeToDelay[ 2 ] = { 200, 400 };
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // This co-routine just delays for a fixed period, then toggles
-         // an LED.  Two co-routines are created using this function, so
-         // the uxIndex parameter is used to tell the co-routine which
-         // LED to flash and how long to delay.  This assumes xQueue has
-         // already been created.
-         vParTestToggleLED( cLedToFlash[ uxIndex ] );
-         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
-
- // Function that creates two co-routines.
- void vOtherFunction( void )
- {
- unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-		
-     // Create two co-routines at priority 0.  The first is given index 0
-     // so (from the code above) toggles LED 5 every 200 ticks.  The second
-     // is given index 1 so toggles LED 6 every 400 ticks.
-     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
-     {
-         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
-     }
- }
-   
- * \defgroup xCoRoutineCreate xCoRoutineCreate - * \ingroup Tasks - */ -signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); - - -/** - * croutine. h - *
- void vCoRoutineSchedule( void );
- * - * Run a co-routine. - * - * vCoRoutineSchedule() executes the highest priority co-routine that is able - * to run. The co-routine will execute until it either blocks, yields or is - * preempted by a task. Co-routines execute cooperatively so one - * co-routine cannot be preempted by another, but can be preempted by a task. - * - * If an application comprises of both tasks and co-routines then - * vCoRoutineSchedule should be called from the idle task (in an idle task - * hook). - * - * Example usage: -
- // This idle task hook will schedule a co-routine each time it is called.
- // The rest of the idle task will execute between co-routine calls.
- void vApplicationIdleHook( void )
- {
-	vCoRoutineSchedule();
- }
-
- // Alternatively, if you do not require any other part of the idle task to
- // execute, the idle task hook can call vCoRoutineScheduler() within an
- // infinite loop.
- void vApplicationIdleHook( void )
- {
-    for( ;; )
-    {
-        vCoRoutineSchedule();
-    }
- }
- 
- * \defgroup vCoRoutineSchedule vCoRoutineSchedule - * \ingroup Tasks - */ -void vCoRoutineSchedule( void ); - -/** - * croutine. h - *
- crSTART( xCoRoutineHandle xHandle );
- * - * This macro MUST always be called at the start of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crSTART( pxCRCB ) switch( ( ( corCRCB * )pxCRCB )->uxState ) { case 0: - -/** - * croutine. h - *
- crEND();
- * - * This macro MUST always be called at the end of a co-routine function. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static long ulAVariable;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-          // Co-routine functionality goes here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crSTART crSTART - * \ingroup Tasks - */ -#define crEND() } - -/* - * These macros are intended for internal use by the co-routine implementation - * only. The macros should not be used directly by application writers. - */ -#define crSET_STATE0( xHandle ) ( ( corCRCB * )xHandle)->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): -#define crSET_STATE1( xHandle ) ( ( corCRCB * )xHandle)->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): - -/** - * croutine. h - *
- crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
- * - * Delay a co-routine for a fixed period of time. - * - * crDELAY can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * @param xHandle The handle of the co-routine to delay. This is the xHandle - * parameter of the co-routine function. - * - * @param xTickToDelay The number of ticks that the co-routine should delay - * for. The actual amount of time this equates to is defined by - * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS - * can be used to convert ticks to milliseconds. - * - * Example usage: -
- // Co-routine to be created.
- void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- // This may not be necessary for const variables.
- // We are to delay for 200ms.
- static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
-
-     // Must start every co-routine with a call to crSTART();
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-        // Delay for 200ms.
-        crDELAY( xHandle, xDelayTime );
-
-        // Do something here.
-     }
-
-     // Must end every co-routine with a call to crEND();
-     crEND();
- }
- * \defgroup crDELAY crDELAY - * \ingroup Tasks - */ -#define crDELAY( xHandle, xTicksToDelay ) \ - if( xTicksToDelay > 0 ) \ - { \ - vCoRoutineAddToDelayedList( xTicksToDelay, NULL ); \ - } \ - crSET_STATE0( xHandle ); - -/** - *
- crQUEUE_SEND(
-                  xCoRoutineHandle xHandle,
-                  xQueueHandle pxQueue,
-                  void *pvItemToQueue,
-                  portTickType xTicksToWait,
-                  portBASE_TYPE *pxResult
-             )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_SEND can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue on which the data will be posted. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvItemToQueue A pointer to the data being posted onto the queue. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied from pvItemToQueue into the queue - * itself. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for space to become available on the queue, should space not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example - * below). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully posted onto the queue, otherwise it will be set to an - * error defined within ProjDefs.h. - * - * Example usage: -
- // Co-routine function that blocks for a fixed period then posts a number onto
- // a queue.
- static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xNumberToPost = 0;
- static portBASE_TYPE xResult;
-
-    // Co-routines must begin with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // This assumes the queue has already been created.
-        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
-
-        if( xResult != pdPASS )
-        {
-            // The message was not posted!
-        }
-
-        // Increment the number to be posted onto the queue.
-        xNumberToPost++;
-
-        // Delay for 100 ticks.
-        crDELAY( xHandle, 100 );
-    }
-
-    // Co-routines must end with a call to crEND().
-    crEND();
- }
- * \defgroup crQUEUE_SEND crQUEUE_SEND - * \ingroup Tasks - */ -#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ -{ \ - *pxResult = xQueueCRSend( pxQueue, pvItemToQueue, xTicksToWait ); \ - if( *pxResult == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( xHandle ); \ - *pxResult = xQueueCRSend( pxQueue, pvItemToQueue, 0 ); \ - } \ - if( *pxResult == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( xHandle ); \ - *pxResult = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_RECEIVE(
-                     xCoRoutineHandle xHandle,
-                     xQueueHandle pxQueue,
-                     void *pvBuffer,
-                     portTickType xTicksToWait,
-                     portBASE_TYPE *pxResult
-                 )
- * - * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine - * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. - * - * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas - * xQueueSend() and xQueueReceive() can only be used from tasks. - * - * crQUEUE_RECEIVE can only be called from the co-routine function itself - not - * from within a function called by the co-routine function. This is because - * co-routines do not maintain their own stack. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xHandle The handle of the calling co-routine. This is the xHandle - * parameter of the co-routine function. - * - * @param pxQueue The handle of the queue from which the data will be received. - * The handle is obtained as the return value when the queue is created using - * the xQueueCreate() API function. - * - * @param pvBuffer The buffer into which the received item is to be copied. - * The number of bytes of each queued item is specified when the queue is - * created. This number of bytes is copied into pvBuffer. - * - * @param xTickToDelay The number of ticks that the co-routine should block - * to wait for data to become available from the queue, should data not be - * available immediately. The actual amount of time this equates to is defined - * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant - * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the - * crQUEUE_SEND example). - * - * @param pxResult The variable pointed to by pxResult will be set to pdPASS if - * data was successfully retrieved from the queue, otherwise it will be set to - * an error code as defined within ProjDefs.h. - * - * Example usage: -
- // A co-routine receives the number of an LED to flash from a queue.  It
- // blocks on the queue until the number is received.
- static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // Variables in co-routines must be declared static if they must maintain value across a blocking call.
- static portBASE_TYPE xResult;
- static unsigned portBASE_TYPE uxLEDToFlash;
-
-    // All co-routines must start with a call to crSTART().
-    crSTART( xHandle );
-
-    for( ;; )
-    {
-        // Wait for data to become available on the queue.
-        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-        if( xResult == pdPASS )
-        {
-            // We received the LED to flash - flash it!
-            vParTestToggleLED( uxLEDToFlash );
-        }
-    }
-
-    crEND();
- }
- * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ -{ \ - *pxResult = xQueueCRReceive( pxQueue, pvBuffer, xTicksToWait ); \ - if( *pxResult == errQUEUE_BLOCKED ) \ - { \ - crSET_STATE0( xHandle ); \ - *pxResult = xQueueCRReceive( pxQueue, pvBuffer, 0 ); \ - } \ - if( *pxResult == errQUEUE_YIELD ) \ - { \ - crSET_STATE1( xHandle ); \ - *pxResult = pdPASS; \ - } \ -} - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvItemToQueue,
-                            portBASE_TYPE xCoRoutinePreviouslyWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue - * that is being used from within a co-routine. - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto - * the same queue multiple times from a single interrupt. The first call - * should always pass in pdFALSE. Subsequent calls should pass in - * the value returned from the previous call. - * - * @return pdTRUE if a co-routine was woken by posting onto the queue. This is - * used by the ISR to determine if a context switch may be required following - * the ISR. - * - * Example usage: -
- // A co-routine that blocks on a queue waiting for characters to be received.
- static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- char cRxedChar;
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Wait for data to become available on the queue.  This assumes the
-         // queue xCommsRxQueue has already been created!
-         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
-
-         // Was a character received?
-         if( xResult == pdPASS )
-         {
-             // Process the character here.
-         }
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to send characters received on a serial port to
- // a co-routine.
- void vUART_ISR( void )
- {
- char cRxedChar;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     // We loop around reading characters until there are none left in the UART.
-     while( UART_RX_REG_NOT_EMPTY() )
-     {
-         // Obtain the character from the UART.
-         cRxedChar = UART_RX_REG;
-
-         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
-         // the first time around the loop.  If the post causes a co-routine
-         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
-         // In this manner we can ensure that if more than one co-routine is
-         // blocked on the queue only one is woken by this ISR no matter how
-         // many characters are posted to the queue.
-         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
-     }
- }
- * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) - - -/** - * croutine. h - *
-  crQUEUE_SEND_FROM_ISR(
-                            xQueueHandle pxQueue,
-                            void *pvBuffer,
-                            portBASE_TYPE * pxCoRoutineWoken
-                       )
- * - * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the - * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() - * functions used by tasks. - * - * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to - * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and - * xQueueReceiveFromISR() can only be used to pass data between a task and and - * ISR. - * - * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data - * from a queue that is being used from within a co-routine (a co-routine - * posted to the queue). - * - * See the co-routine section of the WEB documentation for information on - * passing data between tasks and co-routines and between ISR's and - * co-routines. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvBuffer A pointer to a buffer into which the received item will be - * placed. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from the queue into - * pvBuffer. - * - * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become - * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a - * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise - * *pxCoRoutineWoken will remain unchanged. - * - * @return pdTRUE an item was successfully received from the queue, otherwise - * pdFALSE. - * - * Example usage: -
- // A co-routine that posts a character to a queue then blocks for a fixed
- // period.  The character is incremented each time.
- static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
- {
- // cChar holds its value while this co-routine is blocked and must therefore
- // be declared static.
- static char cCharToTx = 'a';
- portBASE_TYPE xResult;
-
-     // All co-routines must start with a call to crSTART().
-     crSTART( xHandle );
-
-     for( ;; )
-     {
-         // Send the next character to the queue.
-         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
-
-         if( xResult == pdPASS )
-         {
-             // The character was successfully posted to the queue.
-         }
-		 else
-		 {
-			// Could not post the character to the queue.
-		 }
-
-         // Enable the UART Tx interrupt to cause an interrupt in this
-		 // hypothetical UART.  The interrupt will obtain the character
-		 // from the queue and send it.
-		 ENABLE_RX_INTERRUPT();
-
-		 // Increment to the next character then block for a fixed period.
-		 // cCharToTx will maintain its value across the delay as it is
-		 // declared static.
-		 cCharToTx++;
-		 if( cCharToTx > 'x' )
-		 {
-			cCharToTx = 'a';
-		 }
-		 crDELAY( 100 );
-     }
-
-     // All co-routines must end with a call to crEND().
-     crEND();
- }
-
- // An ISR that uses a queue to receive characters to send on a UART.
- void vUART_ISR( void )
- {
- char cCharToTx;
- portBASE_TYPE xCRWokenByPost = pdFALSE;
-
-     while( UART_TX_REG_EMPTY() )
-     {
-         // Are there any characters in the queue waiting to be sent?
-		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
-		 // is woken by the post - ensuring that only a single co-routine is
-		 // woken no matter how many times we go around this loop.
-         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
-		 {
-			 SEND_CHARACTER( cCharToTx );
-		 }
-     }
- }
- * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR - * \ingroup Tasks - */ -#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( pxQueue, pvBuffer, pxCoRoutineWoken ) - -/* - * This function is intended for internal use by the co-routine macros only. - * The macro nature of the co-routine implementation requires that the - * prototype appears here. The function should not be used by application - * writers. - * - * Removes the current co-routine from its ready list and places it in the - * appropriate delayed list. - */ -void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); - -/* - * This function is intended for internal use by the queue implementation only. - * The function should not be used by application writers. - * - * Removes the highest priority co-routine from the event list and places it in - * the pending ready list. - */ -signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); - -#ifdef __cplusplus -} -#endif - -#endif /* CO_ROUTINE_H */ +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include croutine.h" +#endif + + + + +#ifndef CO_ROUTINE_H +#define CO_ROUTINE_H + +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Used to hide the implementation of the co-routine control block. The +control block structure however has to be included in the header due to +the macro implementation of the co-routine functionality. */ +typedef void * xCoRoutineHandle; + +/* Defines the prototype to which co-routine functions must conform. */ +typedef void (*crCOROUTINE_CODE)( xCoRoutineHandle, unsigned portBASE_TYPE ); + +typedef struct corCoRoutineControlBlock +{ + crCOROUTINE_CODE pxCoRoutineFunction; + xListItem xGenericListItem; /*< List item used to place the CRCB in ready and blocked queues. */ + xListItem xEventListItem; /*< List item used to place the CRCB in event lists. */ + unsigned portBASE_TYPE uxPriority; /*< The priority of the co-routine in relation to other co-routines. */ + unsigned portBASE_TYPE uxIndex; /*< Used to distinguish between co-routines when multiple co-routines use the same co-routine function. */ + unsigned short uxState; /*< Used internally by the co-routine implementation. */ +} corCRCB; /* Co-routine control block. Note must be identical in size down to uxPriority with tskTCB. */ + +/** + * croutine. h + *
+ portBASE_TYPE xCoRoutineCreate(
+                                 crCOROUTINE_CODE pxCoRoutineCode,
+                                 unsigned portBASE_TYPE uxPriority,
+                                 unsigned portBASE_TYPE uxIndex
+                               );
+ * + * Create a new co-routine and add it to the list of co-routines that are + * ready to run. + * + * @param pxCoRoutineCode Pointer to the co-routine function. Co-routine + * functions require special syntax - see the co-routine section of the WEB + * documentation for more information. + * + * @param uxPriority The priority with respect to other co-routines at which + * the co-routine will run. + * + * @param uxIndex Used to distinguish between different co-routines that + * execute the same function. See the example below and the co-routine section + * of the WEB documentation for further information. + * + * @return pdPASS if the co-routine was successfully created and added to a ready + * list, otherwise an error code defined with ProjDefs.h. + * + * Example usage: +
+ // Co-routine to be created.
+ void vFlashCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ static const char cLedToFlash[ 2 ] = { 5, 6 };
+ static const portTickType xTimeToDelay[ 2 ] = { 200, 400 };
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // This co-routine just delays for a fixed period, then toggles
+         // an LED.  Two co-routines are created using this function, so
+         // the uxIndex parameter is used to tell the co-routine which
+         // LED to flash and how long to delay.  This assumes xQueue has
+         // already been created.
+         vParTestToggleLED( cLedToFlash[ uxIndex ] );
+         crDELAY( xHandle, uxFlashRates[ uxIndex ] );
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+
+ // Function that creates two co-routines.
+ void vOtherFunction( void )
+ {
+ unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+		
+     // Create two co-routines at priority 0.  The first is given index 0
+     // so (from the code above) toggles LED 5 every 200 ticks.  The second
+     // is given index 1 so toggles LED 6 every 400 ticks.
+     for( uxIndex = 0; uxIndex < 2; uxIndex++ )
+     {
+         xCoRoutineCreate( vFlashCoRoutine, 0, uxIndex );
+     }
+ }
+   
+ * \defgroup xCoRoutineCreate xCoRoutineCreate + * \ingroup Tasks + */ +signed portBASE_TYPE xCoRoutineCreate( crCOROUTINE_CODE pxCoRoutineCode, unsigned portBASE_TYPE uxPriority, unsigned portBASE_TYPE uxIndex ); + + +/** + * croutine. h + *
+ void vCoRoutineSchedule( void );
+ * + * Run a co-routine. + * + * vCoRoutineSchedule() executes the highest priority co-routine that is able + * to run. The co-routine will execute until it either blocks, yields or is + * preempted by a task. Co-routines execute cooperatively so one + * co-routine cannot be preempted by another, but can be preempted by a task. + * + * If an application comprises of both tasks and co-routines then + * vCoRoutineSchedule should be called from the idle task (in an idle task + * hook). + * + * Example usage: +
+ // This idle task hook will schedule a co-routine each time it is called.
+ // The rest of the idle task will execute between co-routine calls.
+ void vApplicationIdleHook( void )
+ {
+	vCoRoutineSchedule();
+ }
+
+ // Alternatively, if you do not require any other part of the idle task to
+ // execute, the idle task hook can call vCoRoutineScheduler() within an
+ // infinite loop.
+ void vApplicationIdleHook( void )
+ {
+    for( ;; )
+    {
+        vCoRoutineSchedule();
+    }
+ }
+ 
+ * \defgroup vCoRoutineSchedule vCoRoutineSchedule + * \ingroup Tasks + */ +void vCoRoutineSchedule( void ); + +/** + * croutine. h + *
+ crSTART( xCoRoutineHandle xHandle );
+ * + * This macro MUST always be called at the start of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crSTART( pxCRCB ) switch( ( ( corCRCB * )pxCRCB )->uxState ) { case 0: + +/** + * croutine. h + *
+ crEND();
+ * + * This macro MUST always be called at the end of a co-routine function. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static long ulAVariable;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+          // Co-routine functionality goes here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crSTART crSTART + * \ingroup Tasks + */ +#define crEND() } + +/* + * These macros are intended for internal use by the co-routine implementation + * only. The macros should not be used directly by application writers. + */ +#define crSET_STATE0( xHandle ) ( ( corCRCB * )xHandle)->uxState = (__LINE__ * 2); return; case (__LINE__ * 2): +#define crSET_STATE1( xHandle ) ( ( corCRCB * )xHandle)->uxState = ((__LINE__ * 2)+1); return; case ((__LINE__ * 2)+1): + +/** + * croutine. h + *
+ crDELAY( xCoRoutineHandle xHandle, portTickType xTicksToDelay );
+ * + * Delay a co-routine for a fixed period of time. + * + * crDELAY can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * @param xHandle The handle of the co-routine to delay. This is the xHandle + * parameter of the co-routine function. + * + * @param xTickToDelay The number of ticks that the co-routine should delay + * for. The actual amount of time this equates to is defined by + * configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant portTICK_RATE_MS + * can be used to convert ticks to milliseconds. + * + * Example usage: +
+ // Co-routine to be created.
+ void vACoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ // This may not be necessary for const variables.
+ // We are to delay for 200ms.
+ static const xTickType xDelayTime = 200 / portTICK_RATE_MS;
+
+     // Must start every co-routine with a call to crSTART();
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+        // Delay for 200ms.
+        crDELAY( xHandle, xDelayTime );
+
+        // Do something here.
+     }
+
+     // Must end every co-routine with a call to crEND();
+     crEND();
+ }
+ * \defgroup crDELAY crDELAY + * \ingroup Tasks + */ +#define crDELAY( xHandle, xTicksToDelay ) \ + if( xTicksToDelay > 0 ) \ + { \ + vCoRoutineAddToDelayedList( xTicksToDelay, NULL ); \ + } \ + crSET_STATE0( xHandle ); + +/** + *
+ crQUEUE_SEND(
+                  xCoRoutineHandle xHandle,
+                  xQueueHandle pxQueue,
+                  void *pvItemToQueue,
+                  portTickType xTicksToWait,
+                  portBASE_TYPE *pxResult
+             )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_SEND can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue on which the data will be posted. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvItemToQueue A pointer to the data being posted onto the queue. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied from pvItemToQueue into the queue + * itself. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for space to become available on the queue, should space not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see example + * below). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully posted onto the queue, otherwise it will be set to an + * error defined within ProjDefs.h. + * + * Example usage: +
+ // Co-routine function that blocks for a fixed period then posts a number onto
+ // a queue.
+ static void prvCoRoutineFlashTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xNumberToPost = 0;
+ static portBASE_TYPE xResult;
+
+    // Co-routines must begin with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // This assumes the queue has already been created.
+        crQUEUE_SEND( xHandle, xCoRoutineQueue, &xNumberToPost, NO_DELAY, &xResult );
+
+        if( xResult != pdPASS )
+        {
+            // The message was not posted!
+        }
+
+        // Increment the number to be posted onto the queue.
+        xNumberToPost++;
+
+        // Delay for 100 ticks.
+        crDELAY( xHandle, 100 );
+    }
+
+    // Co-routines must end with a call to crEND().
+    crEND();
+ }
+ * \defgroup crQUEUE_SEND crQUEUE_SEND + * \ingroup Tasks + */ +#define crQUEUE_SEND( xHandle, pxQueue, pvItemToQueue, xTicksToWait, pxResult ) \ +{ \ + *pxResult = xQueueCRSend( pxQueue, pvItemToQueue, xTicksToWait ); \ + if( *pxResult == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( xHandle ); \ + *pxResult = xQueueCRSend( pxQueue, pvItemToQueue, 0 ); \ + } \ + if( *pxResult == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( xHandle ); \ + *pxResult = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_RECEIVE(
+                     xCoRoutineHandle xHandle,
+                     xQueueHandle pxQueue,
+                     void *pvBuffer,
+                     portTickType xTicksToWait,
+                     portBASE_TYPE *pxResult
+                 )
+ * + * The macro's crQUEUE_SEND() and crQUEUE_RECEIVE() are the co-routine + * equivalent to the xQueueSend() and xQueueReceive() functions used by tasks. + * + * crQUEUE_SEND and crQUEUE_RECEIVE can only be used from a co-routine whereas + * xQueueSend() and xQueueReceive() can only be used from tasks. + * + * crQUEUE_RECEIVE can only be called from the co-routine function itself - not + * from within a function called by the co-routine function. This is because + * co-routines do not maintain their own stack. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xHandle The handle of the calling co-routine. This is the xHandle + * parameter of the co-routine function. + * + * @param pxQueue The handle of the queue from which the data will be received. + * The handle is obtained as the return value when the queue is created using + * the xQueueCreate() API function. + * + * @param pvBuffer The buffer into which the received item is to be copied. + * The number of bytes of each queued item is specified when the queue is + * created. This number of bytes is copied into pvBuffer. + * + * @param xTickToDelay The number of ticks that the co-routine should block + * to wait for data to become available from the queue, should data not be + * available immediately. The actual amount of time this equates to is defined + * by configTICK_RATE_HZ (set in FreeRTOSConfig.h). The constant + * portTICK_RATE_MS can be used to convert ticks to milliseconds (see the + * crQUEUE_SEND example). + * + * @param pxResult The variable pointed to by pxResult will be set to pdPASS if + * data was successfully retrieved from the queue, otherwise it will be set to + * an error code as defined within ProjDefs.h. + * + * Example usage: +
+ // A co-routine receives the number of an LED to flash from a queue.  It
+ // blocks on the queue until the number is received.
+ static void prvCoRoutineFlashWorkTask( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // Variables in co-routines must be declared static if they must maintain value across a blocking call.
+ static portBASE_TYPE xResult;
+ static unsigned portBASE_TYPE uxLEDToFlash;
+
+    // All co-routines must start with a call to crSTART().
+    crSTART( xHandle );
+
+    for( ;; )
+    {
+        // Wait for data to become available on the queue.
+        crQUEUE_RECEIVE( xHandle, xCoRoutineQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+        if( xResult == pdPASS )
+        {
+            // We received the LED to flash - flash it!
+            vParTestToggleLED( uxLEDToFlash );
+        }
+    }
+
+    crEND();
+ }
+ * \defgroup crQUEUE_RECEIVE crQUEUE_RECEIVE + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE( xHandle, pxQueue, pvBuffer, xTicksToWait, pxResult ) \ +{ \ + *pxResult = xQueueCRReceive( pxQueue, pvBuffer, xTicksToWait ); \ + if( *pxResult == errQUEUE_BLOCKED ) \ + { \ + crSET_STATE0( xHandle ); \ + *pxResult = xQueueCRReceive( pxQueue, pvBuffer, 0 ); \ + } \ + if( *pxResult == errQUEUE_YIELD ) \ + { \ + crSET_STATE1( xHandle ); \ + *pxResult = pdPASS; \ + } \ +} + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvItemToQueue,
+                            portBASE_TYPE xCoRoutinePreviouslyWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_SEND_FROM_ISR can only be called from an ISR to send data to a queue + * that is being used from within a co-routine. + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xCoRoutinePreviouslyWoken This is included so an ISR can post onto + * the same queue multiple times from a single interrupt. The first call + * should always pass in pdFALSE. Subsequent calls should pass in + * the value returned from the previous call. + * + * @return pdTRUE if a co-routine was woken by posting onto the queue. This is + * used by the ISR to determine if a context switch may be required following + * the ISR. + * + * Example usage: +
+ // A co-routine that blocks on a queue waiting for characters to be received.
+ static void vReceivingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ char cRxedChar;
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Wait for data to become available on the queue.  This assumes the
+         // queue xCommsRxQueue has already been created!
+         crQUEUE_RECEIVE( xHandle, xCommsRxQueue, &uxLEDToFlash, portMAX_DELAY, &xResult );
+
+         // Was a character received?
+         if( xResult == pdPASS )
+         {
+             // Process the character here.
+         }
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to send characters received on a serial port to
+ // a co-routine.
+ void vUART_ISR( void )
+ {
+ char cRxedChar;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     // We loop around reading characters until there are none left in the UART.
+     while( UART_RX_REG_NOT_EMPTY() )
+     {
+         // Obtain the character from the UART.
+         cRxedChar = UART_RX_REG;
+
+         // Post the character onto a queue.  xCRWokenByPost will be pdFALSE
+         // the first time around the loop.  If the post causes a co-routine
+         // to be woken (unblocked) then xCRWokenByPost will be set to pdTRUE.
+         // In this manner we can ensure that if more than one co-routine is
+         // blocked on the queue only one is woken by this ISR no matter how
+         // many characters are posted to the queue.
+         xCRWokenByPost = crQUEUE_SEND_FROM_ISR( xCommsRxQueue, &cRxedChar, xCRWokenByPost );
+     }
+ }
+ * \defgroup crQUEUE_SEND_FROM_ISR crQUEUE_SEND_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_SEND_FROM_ISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) xQueueCRSendFromISR( pxQueue, pvItemToQueue, xCoRoutinePreviouslyWoken ) + + +/** + * croutine. h + *
+  crQUEUE_SEND_FROM_ISR(
+                            xQueueHandle pxQueue,
+                            void *pvBuffer,
+                            portBASE_TYPE * pxCoRoutineWoken
+                       )
+ * + * The macro's crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() are the + * co-routine equivalent to the xQueueSendFromISR() and xQueueReceiveFromISR() + * functions used by tasks. + * + * crQUEUE_SEND_FROM_ISR() and crQUEUE_RECEIVE_FROM_ISR() can only be used to + * pass data between a co-routine and and ISR, whereas xQueueSendFromISR() and + * xQueueReceiveFromISR() can only be used to pass data between a task and and + * ISR. + * + * crQUEUE_RECEIVE_FROM_ISR can only be called from an ISR to receive data + * from a queue that is being used from within a co-routine (a co-routine + * posted to the queue). + * + * See the co-routine section of the WEB documentation for information on + * passing data between tasks and co-routines and between ISR's and + * co-routines. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvBuffer A pointer to a buffer into which the received item will be + * placed. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from the queue into + * pvBuffer. + * + * @param pxCoRoutineWoken A co-routine may be blocked waiting for space to become + * available on the queue. If crQUEUE_RECEIVE_FROM_ISR causes such a + * co-routine to unblock *pxCoRoutineWoken will get set to pdTRUE, otherwise + * *pxCoRoutineWoken will remain unchanged. + * + * @return pdTRUE an item was successfully received from the queue, otherwise + * pdFALSE. + * + * Example usage: +
+ // A co-routine that posts a character to a queue then blocks for a fixed
+ // period.  The character is incremented each time.
+ static void vSendingCoRoutine( xCoRoutineHandle xHandle, unsigned portBASE_TYPE uxIndex )
+ {
+ // cChar holds its value while this co-routine is blocked and must therefore
+ // be declared static.
+ static char cCharToTx = 'a';
+ portBASE_TYPE xResult;
+
+     // All co-routines must start with a call to crSTART().
+     crSTART( xHandle );
+
+     for( ;; )
+     {
+         // Send the next character to the queue.
+         crQUEUE_SEND( xHandle, xCoRoutineQueue, &cCharToTx, NO_DELAY, &xResult );
+
+         if( xResult == pdPASS )
+         {
+             // The character was successfully posted to the queue.
+         }
+		 else
+		 {
+			// Could not post the character to the queue.
+		 }
+
+         // Enable the UART Tx interrupt to cause an interrupt in this
+		 // hypothetical UART.  The interrupt will obtain the character
+		 // from the queue and send it.
+		 ENABLE_RX_INTERRUPT();
+
+		 // Increment to the next character then block for a fixed period.
+		 // cCharToTx will maintain its value across the delay as it is
+		 // declared static.
+		 cCharToTx++;
+		 if( cCharToTx > 'x' )
+		 {
+			cCharToTx = 'a';
+		 }
+		 crDELAY( 100 );
+     }
+
+     // All co-routines must end with a call to crEND().
+     crEND();
+ }
+
+ // An ISR that uses a queue to receive characters to send on a UART.
+ void vUART_ISR( void )
+ {
+ char cCharToTx;
+ portBASE_TYPE xCRWokenByPost = pdFALSE;
+
+     while( UART_TX_REG_EMPTY() )
+     {
+         // Are there any characters in the queue waiting to be sent?
+		 // xCRWokenByPost will automatically be set to pdTRUE if a co-routine
+		 // is woken by the post - ensuring that only a single co-routine is
+		 // woken no matter how many times we go around this loop.
+         if( crQUEUE_RECEIVE_FROM_ISR( pxQueue, &cCharToTx, &xCRWokenByPost ) )
+		 {
+			 SEND_CHARACTER( cCharToTx );
+		 }
+     }
+ }
+ * \defgroup crQUEUE_RECEIVE_FROM_ISR crQUEUE_RECEIVE_FROM_ISR + * \ingroup Tasks + */ +#define crQUEUE_RECEIVE_FROM_ISR( pxQueue, pvBuffer, pxCoRoutineWoken ) xQueueCRReceiveFromISR( pxQueue, pvBuffer, pxCoRoutineWoken ) + +/* + * This function is intended for internal use by the co-routine macros only. + * The macro nature of the co-routine implementation requires that the + * prototype appears here. The function should not be used by application + * writers. + * + * Removes the current co-routine from its ready list and places it in the + * appropriate delayed list. + */ +void vCoRoutineAddToDelayedList( portTickType xTicksToDelay, xList *pxEventList ); + +/* + * This function is intended for internal use by the queue implementation only. + * The function should not be used by application writers. + * + * Removes the highest priority co-routine from the event list and places it in + * the pending ready list. + */ +signed portBASE_TYPE xCoRoutineRemoveFromEventList( const xList *pxEventList ); + +#ifdef __cplusplus +} +#endif + +#endif /* CO_ROUTINE_H */ diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/list.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/list.h index 65712836e..6808fc323 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/list.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/list.h @@ -1,305 +1,305 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/* - * This is the list implementation used by the scheduler. While it is tailored - * heavily for the schedulers needs, it is also available for use by - * application code. - * - * xLists can only store pointers to xListItems. Each xListItem contains a - * numeric value (xItemValue). Most of the time the lists are sorted in - * descending item value order. - * - * Lists are created already containing one list item. The value of this - * item is the maximum possible that can be stored, it is therefore always at - * the end of the list and acts as a marker. The list member pxHead always - * points to this marker - even though it is at the tail of the list. This - * is because the tail contains a wrap back pointer to the true head of - * the list. - * - * In addition to it's value, each list item contains a pointer to the next - * item in the list (pxNext), a pointer to the list it is in (pxContainer) - * and a pointer to back to the object that contains it. These later two - * pointers are included for efficiency of list manipulation. There is - * effectively a two way link between the object containing the list item and - * the list item itself. - * - * - * \page ListIntroduction List Implementation - * \ingroup FreeRTOSIntro - */ - -/* - Changes from V4.3.1 - - + Included local const within listGET_OWNER_OF_NEXT_ENTRY() to assist - compiler with optimisation. Thanks B.R. -*/ - -#ifndef LIST_H -#define LIST_H - -#ifdef __cplusplus -extern "C" { -#endif -/* - * Definition of the only type of object that a list can contain. - */ -struct xLIST_ITEM -{ - portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ - volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ - volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ - void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ - void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ -}; -typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ - -struct xMINI_LIST_ITEM -{ - portTickType xItemValue; - volatile struct xLIST_ITEM *pxNext; - volatile struct xLIST_ITEM *pxPrevious; -}; -typedef struct xMINI_LIST_ITEM xMiniListItem; - -/* - * Definition of the type of queue used by the scheduler. - */ -typedef struct xLIST -{ - volatile unsigned portBASE_TYPE uxNumberOfItems; - volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ - volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ -} xList; - -/* - * Access macro to set the owner of a list item. The owner of a list item - * is the object (usually a TCB) that contains the list item. - * - * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) pxOwner - -/* - * Access macro to set the value of the list item. In most cases the value is - * used to sort the list in descending order. - * - * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = xValue - -/* - * Access macro the retrieve the value of the list item. The value can - * represent anything - for example a the priority of a task, or the time at - * which a task should be unblocked. - * - * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE - * \ingroup LinkedList - */ -#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) - -/* - * Access macro to determine if a list contains any items. The macro will - * only have the value true if the list is empty. - * - * \page listLIST_IS_EMPTY listLIST_IS_EMPTY - * \ingroup LinkedList - */ -#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) - -/* - * Access macro to return the number of items in the list. - */ -#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) - -/* - * Access function to obtain the owner of the next entry in a list. - * - * The list member pxIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list - * and returns that entries pxOwner parameter. Using multiple calls to this - * function it is therefore possible to move through every item contained in - * a list. - * - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the next item owner is to be returned. - * - * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ -{ \ -xList * const pxConstList = pxList; \ - /* Increment the index to the next item and return the item, ensuring */ \ - /* we don't return the marker used at the end of the list. */ \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ - { \ - ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ - } \ - pxTCB = ( pxConstList )->pxIndex->pvOwner; \ -} - - -/* - * Access function to obtain the owner of the first entry in a list. Lists - * are normally sorted in ascending item value order. - * - * This function returns the pxOwner member of the first item in the list. - * The pxOwner parameter of a list item is a pointer to the object that owns - * the list item. In the scheduler this is normally a task control block. - * The pxOwner parameter effectively creates a two way link between the list - * item and its owner. - * - * @param pxList The list from which the owner of the head item is to be - * returned. - * - * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY - * \ingroup LinkedList - */ -#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( ( pxList->uxNumberOfItems != ( unsigned portBASE_TYPE ) 0 ) ? ( (&( pxList->xListEnd ))->pxNext->pvOwner ) : ( NULL ) ) - -/* - * Check to see if a list item is within a list. The list item maintains a - * "container" pointer that points to the list it is in. All this macro does - * is check to see if the container and the list match. - * - * @param pxList The list we want to know if the list item is within. - * @param pxListItem The list item we want to know if is in the list. - * @return pdTRUE is the list item is in the list, otherwise pdFALSE. - * pointer against - */ -#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) pxList ) - -/* - * Must be called before a list is used! This initialises all the members - * of the list structure and inserts the xListEnd item into the list as a - * marker to the back of the list. - * - * @param pxList Pointer to the list being initialised. - * - * \page vListInitialise vListInitialise - * \ingroup LinkedList - */ -void vListInitialise( xList *pxList ); - -/* - * Must be called before a list item is used. This sets the list container to - * null so the item does not think that it is already contained in a list. - * - * @param pxItem Pointer to the list item being initialised. - * - * \page vListInitialiseItem vListInitialiseItem - * \ingroup LinkedList - */ -void vListInitialiseItem( xListItem *pxItem ); - -/* - * Insert a list item into a list. The item will be inserted into the list in - * a position determined by its item value (descending item value order). - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The item to that is to be placed in the list. - * - * \page vListInsert vListInsert - * \ingroup LinkedList - */ -void vListInsert( xList *pxList, xListItem *pxNewListItem ); - -/* - * Insert a list item into a list. The item will be inserted in a position - * such that it will be the last item within the list returned by multiple - * calls to listGET_OWNER_OF_NEXT_ENTRY. - * - * The list member pvIndex is used to walk through a list. Calling - * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. - * Placing an item in a list using vListInsertEnd effectively places the item - * in the list position pointed to by pvIndex. This means that every other - * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before - * the pvIndex parameter again points to the item being inserted. - * - * @param pxList The list into which the item is to be inserted. - * - * @param pxNewListItem The list item to be inserted into the list. - * - * \page vListInsertEnd vListInsertEnd - * \ingroup LinkedList - */ -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); - -/* - * Remove an item from a list. The list item has a pointer to the list that - * it is in, so only the list item need be passed into the function. - * - * @param vListRemove The item to be removed. The item will remove itself from - * the list pointed to by it's pxContainer parameter. - * - * \page vListRemove vListRemove - * \ingroup LinkedList - */ -void vListRemove( xListItem *pxItemToRemove ); - -#ifdef __cplusplus -} -#endif - -#endif - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/* + * This is the list implementation used by the scheduler. While it is tailored + * heavily for the schedulers needs, it is also available for use by + * application code. + * + * xLists can only store pointers to xListItems. Each xListItem contains a + * numeric value (xItemValue). Most of the time the lists are sorted in + * descending item value order. + * + * Lists are created already containing one list item. The value of this + * item is the maximum possible that can be stored, it is therefore always at + * the end of the list and acts as a marker. The list member pxHead always + * points to this marker - even though it is at the tail of the list. This + * is because the tail contains a wrap back pointer to the true head of + * the list. + * + * In addition to it's value, each list item contains a pointer to the next + * item in the list (pxNext), a pointer to the list it is in (pxContainer) + * and a pointer to back to the object that contains it. These later two + * pointers are included for efficiency of list manipulation. There is + * effectively a two way link between the object containing the list item and + * the list item itself. + * + * + * \page ListIntroduction List Implementation + * \ingroup FreeRTOSIntro + */ + +/* + Changes from V4.3.1 + + + Included local const within listGET_OWNER_OF_NEXT_ENTRY() to assist + compiler with optimisation. Thanks B.R. +*/ + +#ifndef LIST_H +#define LIST_H + +#ifdef __cplusplus +extern "C" { +#endif +/* + * Definition of the only type of object that a list can contain. + */ +struct xLIST_ITEM +{ + portTickType xItemValue; /*< The value being listed. In most cases this is used to sort the list in descending order. */ + volatile struct xLIST_ITEM * pxNext; /*< Pointer to the next xListItem in the list. */ + volatile struct xLIST_ITEM * pxPrevious;/*< Pointer to the previous xListItem in the list. */ + void * pvOwner; /*< Pointer to the object (normally a TCB) that contains the list item. There is therefore a two way link between the object containing the list item and the list item itself. */ + void * pvContainer; /*< Pointer to the list in which this list item is placed (if any). */ +}; +typedef struct xLIST_ITEM xListItem; /* For some reason lint wants this as two separate definitions. */ + +struct xMINI_LIST_ITEM +{ + portTickType xItemValue; + volatile struct xLIST_ITEM *pxNext; + volatile struct xLIST_ITEM *pxPrevious; +}; +typedef struct xMINI_LIST_ITEM xMiniListItem; + +/* + * Definition of the type of queue used by the scheduler. + */ +typedef struct xLIST +{ + volatile unsigned portBASE_TYPE uxNumberOfItems; + volatile xListItem * pxIndex; /*< Used to walk through the list. Points to the last item returned by a call to pvListGetOwnerOfNextEntry (). */ + volatile xMiniListItem xListEnd; /*< List item that contains the maximum possible item value meaning it is always at the end of the list and is therefore used as a marker. */ +} xList; + +/* + * Access macro to set the owner of a list item. The owner of a list item + * is the object (usually a TCB) that contains the list item. + * + * \page listSET_LIST_ITEM_OWNER listSET_LIST_ITEM_OWNER + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_OWNER( pxListItem, pxOwner ) ( pxListItem )->pvOwner = ( void * ) pxOwner + +/* + * Access macro to set the value of the list item. In most cases the value is + * used to sort the list in descending order. + * + * \page listSET_LIST_ITEM_VALUE listSET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listSET_LIST_ITEM_VALUE( pxListItem, xValue ) ( pxListItem )->xItemValue = xValue + +/* + * Access macro the retrieve the value of the list item. The value can + * represent anything - for example a the priority of a task, or the time at + * which a task should be unblocked. + * + * \page listGET_LIST_ITEM_VALUE listGET_LIST_ITEM_VALUE + * \ingroup LinkedList + */ +#define listGET_LIST_ITEM_VALUE( pxListItem ) ( ( pxListItem )->xItemValue ) + +/* + * Access macro to determine if a list contains any items. The macro will + * only have the value true if the list is empty. + * + * \page listLIST_IS_EMPTY listLIST_IS_EMPTY + * \ingroup LinkedList + */ +#define listLIST_IS_EMPTY( pxList ) ( ( pxList )->uxNumberOfItems == ( unsigned portBASE_TYPE ) 0 ) + +/* + * Access macro to return the number of items in the list. + */ +#define listCURRENT_LIST_LENGTH( pxList ) ( ( pxList )->uxNumberOfItems ) + +/* + * Access function to obtain the owner of the next entry in a list. + * + * The list member pxIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pxIndex to the next item in the list + * and returns that entries pxOwner parameter. Using multiple calls to this + * function it is therefore possible to move through every item contained in + * a list. + * + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the next item owner is to be returned. + * + * \page listGET_OWNER_OF_NEXT_ENTRY listGET_OWNER_OF_NEXT_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_NEXT_ENTRY( pxTCB, pxList ) \ +{ \ +xList * const pxConstList = pxList; \ + /* Increment the index to the next item and return the item, ensuring */ \ + /* we don't return the marker used at the end of the list. */ \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + if( ( pxConstList )->pxIndex == ( xListItem * ) &( ( pxConstList )->xListEnd ) ) \ + { \ + ( pxConstList )->pxIndex = ( pxConstList )->pxIndex->pxNext; \ + } \ + pxTCB = ( pxConstList )->pxIndex->pvOwner; \ +} + + +/* + * Access function to obtain the owner of the first entry in a list. Lists + * are normally sorted in ascending item value order. + * + * This function returns the pxOwner member of the first item in the list. + * The pxOwner parameter of a list item is a pointer to the object that owns + * the list item. In the scheduler this is normally a task control block. + * The pxOwner parameter effectively creates a two way link between the list + * item and its owner. + * + * @param pxList The list from which the owner of the head item is to be + * returned. + * + * \page listGET_OWNER_OF_HEAD_ENTRY listGET_OWNER_OF_HEAD_ENTRY + * \ingroup LinkedList + */ +#define listGET_OWNER_OF_HEAD_ENTRY( pxList ) ( ( pxList->uxNumberOfItems != ( unsigned portBASE_TYPE ) 0 ) ? ( (&( pxList->xListEnd ))->pxNext->pvOwner ) : ( NULL ) ) + +/* + * Check to see if a list item is within a list. The list item maintains a + * "container" pointer that points to the list it is in. All this macro does + * is check to see if the container and the list match. + * + * @param pxList The list we want to know if the list item is within. + * @param pxListItem The list item we want to know if is in the list. + * @return pdTRUE is the list item is in the list, otherwise pdFALSE. + * pointer against + */ +#define listIS_CONTAINED_WITHIN( pxList, pxListItem ) ( ( pxListItem )->pvContainer == ( void * ) pxList ) + +/* + * Must be called before a list is used! This initialises all the members + * of the list structure and inserts the xListEnd item into the list as a + * marker to the back of the list. + * + * @param pxList Pointer to the list being initialised. + * + * \page vListInitialise vListInitialise + * \ingroup LinkedList + */ +void vListInitialise( xList *pxList ); + +/* + * Must be called before a list item is used. This sets the list container to + * null so the item does not think that it is already contained in a list. + * + * @param pxItem Pointer to the list item being initialised. + * + * \page vListInitialiseItem vListInitialiseItem + * \ingroup LinkedList + */ +void vListInitialiseItem( xListItem *pxItem ); + +/* + * Insert a list item into a list. The item will be inserted into the list in + * a position determined by its item value (descending item value order). + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The item to that is to be placed in the list. + * + * \page vListInsert vListInsert + * \ingroup LinkedList + */ +void vListInsert( xList *pxList, xListItem *pxNewListItem ); + +/* + * Insert a list item into a list. The item will be inserted in a position + * such that it will be the last item within the list returned by multiple + * calls to listGET_OWNER_OF_NEXT_ENTRY. + * + * The list member pvIndex is used to walk through a list. Calling + * listGET_OWNER_OF_NEXT_ENTRY increments pvIndex to the next item in the list. + * Placing an item in a list using vListInsertEnd effectively places the item + * in the list position pointed to by pvIndex. This means that every other + * item within the list will be returned by listGET_OWNER_OF_NEXT_ENTRY before + * the pvIndex parameter again points to the item being inserted. + * + * @param pxList The list into which the item is to be inserted. + * + * @param pxNewListItem The list item to be inserted into the list. + * + * \page vListInsertEnd vListInsertEnd + * \ingroup LinkedList + */ +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ); + +/* + * Remove an item from a list. The list item has a pointer to the list that + * it is in, so only the list item need be passed into the function. + * + * @param vListRemove The item to be removed. The item will remove itself from + * the list pointed to by it's pxContainer parameter. + * + * \page vListRemove vListRemove + * \ingroup LinkedList + */ +void vListRemove( xListItem *pxItemToRemove ); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/mpu_wrappers.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/mpu_wrappers.h index e197d5085..ecbe76147 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/mpu_wrappers.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/mpu_wrappers.h @@ -1,135 +1,135 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef MPU_WRAPPERS_H -#define MPU_WRAPPERS_H - -/* This file redefines API functions to be called through a wrapper macro, but -only for ports that are using the MPU. */ -#ifdef portUSING_MPU_WRAPPERS - - /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is - included from queue.c or task.c to prevent it from having an effect within - those files. */ - #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - - #define xTaskGenericCreate MPU_xTaskGenericCreate - #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions - #define vTaskDelete MPU_vTaskDelete - #define vTaskDelayUntil MPU_vTaskDelayUntil - #define vTaskDelay MPU_vTaskDelay - #define uxTaskPriorityGet MPU_uxTaskPriorityGet - #define vTaskPrioritySet MPU_vTaskPrioritySet - #define vTaskSuspend MPU_vTaskSuspend - #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended - #define vTaskResume MPU_vTaskResume - #define vTaskSuspendAll MPU_vTaskSuspendAll - #define xTaskResumeAll MPU_xTaskResumeAll - #define xTaskGetTickCount MPU_xTaskGetTickCount - #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks - #define vTaskList MPU_vTaskList - #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats - #define vTaskStartTrace MPU_vTaskStartTrace - #define ulTaskEndTrace MPU_ulTaskEndTrace - #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag - #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag - #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook - #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark - #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle - #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState - - #define xQueueCreate MPU_xQueueCreate - #define xQueueCreateMutex MPU_xQueueCreateMutex - #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive - #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive - #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore - #define xQueueGenericSend MPU_xQueueGenericSend - #define xQueueAltGenericSend MPU_xQueueAltGenericSend - #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive - #define xQueueGenericReceive MPU_xQueueGenericReceive - #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting - #define vQueueDelete MPU_vQueueDelete - - #define pvPortMalloc MPU_pvPortMalloc - #define vPortFree MPU_vPortFree - #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize - #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks - - #if configQUEUE_REGISTRY_SIZE > 0 - #define vQueueAddToRegistry MPU_vQueueAddToRegistry - #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue - #endif - - /* Remove the privileged function macro. */ - #define PRIVILEGED_FUNCTION - - #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - - /* Ensure API functions go in the privileged execution section. */ - #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) - #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) - //#define PRIVILEGED_DATA - - #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ - -#else /* portUSING_MPU_WRAPPERS */ - - #define PRIVILEGED_FUNCTION - #define PRIVILEGED_DATA - #define portUSING_MPU_WRAPPERS 0 - -#endif /* portUSING_MPU_WRAPPERS */ - - -#endif /* MPU_WRAPPERS_H */ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef MPU_WRAPPERS_H +#define MPU_WRAPPERS_H + +/* This file redefines API functions to be called through a wrapper macro, but +only for ports that are using the MPU. */ +#ifdef portUSING_MPU_WRAPPERS + + /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE will be defined when this file is + included from queue.c or task.c to prevent it from having an effect within + those files. */ + #ifndef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + + #define xTaskGenericCreate MPU_xTaskGenericCreate + #define vTaskAllocateMPURegions MPU_vTaskAllocateMPURegions + #define vTaskDelete MPU_vTaskDelete + #define vTaskDelayUntil MPU_vTaskDelayUntil + #define vTaskDelay MPU_vTaskDelay + #define uxTaskPriorityGet MPU_uxTaskPriorityGet + #define vTaskPrioritySet MPU_vTaskPrioritySet + #define vTaskSuspend MPU_vTaskSuspend + #define xTaskIsTaskSuspended MPU_xTaskIsTaskSuspended + #define vTaskResume MPU_vTaskResume + #define vTaskSuspendAll MPU_vTaskSuspendAll + #define xTaskResumeAll MPU_xTaskResumeAll + #define xTaskGetTickCount MPU_xTaskGetTickCount + #define uxTaskGetNumberOfTasks MPU_uxTaskGetNumberOfTasks + #define vTaskList MPU_vTaskList + #define vTaskGetRunTimeStats MPU_vTaskGetRunTimeStats + #define vTaskStartTrace MPU_vTaskStartTrace + #define ulTaskEndTrace MPU_ulTaskEndTrace + #define vTaskSetApplicationTaskTag MPU_vTaskSetApplicationTaskTag + #define xTaskGetApplicationTaskTag MPU_xTaskGetApplicationTaskTag + #define xTaskCallApplicationTaskHook MPU_xTaskCallApplicationTaskHook + #define uxTaskGetStackHighWaterMark MPU_uxTaskGetStackHighWaterMark + #define xTaskGetCurrentTaskHandle MPU_xTaskGetCurrentTaskHandle + #define xTaskGetSchedulerState MPU_xTaskGetSchedulerState + + #define xQueueCreate MPU_xQueueCreate + #define xQueueCreateMutex MPU_xQueueCreateMutex + #define xQueueGiveMutexRecursive MPU_xQueueGiveMutexRecursive + #define xQueueTakeMutexRecursive MPU_xQueueTakeMutexRecursive + #define xQueueCreateCountingSemaphore MPU_xQueueCreateCountingSemaphore + #define xQueueGenericSend MPU_xQueueGenericSend + #define xQueueAltGenericSend MPU_xQueueAltGenericSend + #define xQueueAltGenericReceive MPU_xQueueAltGenericReceive + #define xQueueGenericReceive MPU_xQueueGenericReceive + #define uxQueueMessagesWaiting MPU_uxQueueMessagesWaiting + #define vQueueDelete MPU_vQueueDelete + + #define pvPortMalloc MPU_pvPortMalloc + #define vPortFree MPU_vPortFree + #define xPortGetFreeHeapSize MPU_xPortGetFreeHeapSize + #define vPortInitialiseBlocks MPU_vPortInitialiseBlocks + + #if configQUEUE_REGISTRY_SIZE > 0 + #define vQueueAddToRegistry MPU_vQueueAddToRegistry + #define vQueueUnregisterQueue MPU_vQueueUnregisterQueue + #endif + + /* Remove the privileged function macro. */ + #define PRIVILEGED_FUNCTION + + #else /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + + /* Ensure API functions go in the privileged execution section. */ + #define PRIVILEGED_FUNCTION __attribute__((section("privileged_functions"))) + #define PRIVILEGED_DATA __attribute__((section("privileged_data"))) + //#define PRIVILEGED_DATA + + #endif /* MPU_WRAPPERS_INCLUDED_FROM_API_FILE */ + +#else /* portUSING_MPU_WRAPPERS */ + + #define PRIVILEGED_FUNCTION + #define PRIVILEGED_DATA + #define portUSING_MPU_WRAPPERS 0 + +#endif /* portUSING_MPU_WRAPPERS */ + + +#endif /* MPU_WRAPPERS_H */ + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/portable.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/portable.h index b72a3f038..4b4636a21 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/portable.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/portable.h @@ -1,391 +1,391 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -/*----------------------------------------------------------- - * Portable layer API. Each function must be defined for each port. - *----------------------------------------------------------*/ - -#ifndef PORTABLE_H -#define PORTABLE_H - -/* Include the macro file relevant to the port being used. */ - -#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT - #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT - #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef GCC_MEGA_AVR - #include "../portable/GCC/ATMega323/portmacro.h" -#endif - -#ifdef IAR_MEGA_AVR - #include "../portable/IAR/ATMega323/portmacro.h" -#endif - -#ifdef MPLAB_PIC24_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_DSPIC_PORT - #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" -#endif - -#ifdef MPLAB_PIC18F_PORT - #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" -#endif - -#ifdef MPLAB_PIC32MX_PORT - #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" -#endif - -#ifdef _FEDPICC - #include "libFreeRTOS/Include/portmacro.h" -#endif - -#ifdef SDCC_CYGNAL - #include "../../Source/portable/SDCC/Cygnal/portmacro.h" -#endif - -#ifdef GCC_ARM7 - #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" -#endif - -#ifdef GCC_ARM7_ECLIPSE - #include "portmacro.h" -#endif - -#ifdef ROWLEY_LPC23xx - #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" -#endif - -#ifdef IAR_MSP430 - #include "..\..\Source\portable\IAR\MSP430\portmacro.h" -#endif - -#ifdef GCC_MSP430 - #include "../../Source/portable/GCC/MSP430F449/portmacro.h" -#endif - -#ifdef ROWLEY_MSP430 - #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" -#endif - -#ifdef ARM7_LPC21xx_KEIL_RVDS - #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" -#endif - -#ifdef SAM7_GCC - #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" -#endif - -#ifdef SAM7_IAR - #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" -#endif - -#ifdef SAM9XE_IAR - #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" -#endif - -#ifdef LPC2000_IAR - #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" -#endif - -#ifdef STR71X_IAR - #include "..\..\Source\portable\IAR\STR71x\portmacro.h" -#endif - -#ifdef STR75X_IAR - #include "..\..\Source\portable\IAR\STR75x\portmacro.h" -#endif - -#ifdef STR75X_GCC - #include "..\..\Source\portable\GCC\STR75x\portmacro.h" -#endif - -#ifdef STR91X_IAR - #include "..\..\Source\portable\IAR\STR91x\portmacro.h" -#endif - -#ifdef GCC_H8S - #include "../../Source/portable/GCC/H8S2329/portmacro.h" -#endif - -#ifdef GCC_AT91FR40008 - #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" -#endif - -#ifdef RVDS_ARMCM3_LM3S102 - #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3_LM3S102 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef GCC_ARMCM3 - #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARM_CM3 - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef IAR_ARMCM3_LM - #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" -#endif - -#ifdef HCS12_CODE_WARRIOR - #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" -#endif - -#ifdef MICROBLAZE_GCC - #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" -#endif - -#ifdef TERN_EE - #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" -#endif - -#ifdef GCC_HCS12 - #include "../../Source/portable/GCC/HCS12/portmacro.h" -#endif - -#ifdef GCC_MCF5235 - #include "../../Source/portable/GCC/MCF5235/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_GCC - #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" -#endif - -#ifdef COLDFIRE_V2_CODEWARRIOR - #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" -#endif - -#ifdef GCC_PPC405 - #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" -#endif - -#ifdef GCC_PPC440 - #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" -#endif - -#ifdef _16FX_SOFTUNE - #include "..\..\Source\portable\Softune\MB96340\portmacro.h" -#endif - -#ifdef BCC_INDUSTRIAL_PC_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef BCC_FLASH_LITE_186_PORT - /* A short file name has to be used in place of the normal - FreeRTOSConfig.h when using the Borland compiler. */ - #include "frconfig.h" - #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" - typedef void ( __interrupt __far *pxISR )(); -#endif - -#ifdef __GNUC__ - #ifdef __AVR32_AVR32A__ - #include "portmacro.h" - #endif -#endif - -#ifdef __ICCAVR32__ - #ifdef __CORE__ - #if __CORE__ == __AVR32A__ - #include "portmacro.h" - #endif - #endif -#endif - -#ifdef __91467D - #include "portmacro.h" -#endif - -#ifdef __96340 - #include "portmacro.h" -#endif - - -#ifdef __IAR_V850ES_Fx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx3_L__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Jx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_V850ES_Hx2__ - #include "../../Source/portable/IAR/V850ES/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -#ifdef __IAR_78K0R_Kx3L__ - #include "../../Source/portable/IAR/78K0R/portmacro.h" -#endif - -/* Catch all to ensure portmacro.h is included in the build. Newer demos -have the path as part of the project options, rather than as relative from -the project location. If portENTER_CRITICAL() has not been defined then -portmacro.h has not yet been included - as every portmacro.h provides a -portENTER_CRITICAL() definition. Check the demo application for your demo -to find the path to the correct portmacro.h file. */ -#ifndef portENTER_CRITICAL - #include "../../Source/portable/GCC/Posix/portmacro.h" - //#include "portmacro.h" -#endif - -#if portBYTE_ALIGNMENT == 8 - #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) -#endif - -#if portBYTE_ALIGNMENT == 4 - #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) -#endif - -#if portBYTE_ALIGNMENT == 2 - #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) -#endif - -#if portBYTE_ALIGNMENT == 1 - #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) -#endif - -#ifndef portBYTE_ALIGNMENT_MASK - #error "Invalid portBYTE_ALIGNMENT definition" -#endif - -#ifndef portNUM_CONFIGURABLE_REGIONS - #define portNUM_CONFIGURABLE_REGIONS 1 -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -#include "mpu_wrappers.h" - -/* - * Setup the stack of a new task so it is ready to be placed under the - * scheduler control. The registers have to be placed on the stack in - * the order that the port expects to find them. - * - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; -#else - portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ); -#endif - -/* - * Map to the memory management routines required for the port. - */ -void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; -void vPortFree( void *pv ) PRIVILEGED_FUNCTION; -void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; -size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; - -/* - * Setup the hardware ready for the scheduler to take control. This generally - * sets up a tick interrupt and sets timers for the correct tick frequency. - */ -portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so - * the hardware is left in its original condition after the scheduler stops - * executing. - */ -void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; - -/* - * The structures and methods of manipulating the MPU are contained within the - * port layer. - * - * Fills the xMPUSettings structure with the memory region information - * contained in xRegions. - */ -#if( portUSING_MPU_WRAPPERS == 1 ) - struct xMEMORY_REGION; - void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* PORTABLE_H */ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +/*----------------------------------------------------------- + * Portable layer API. Each function must be defined for each port. + *----------------------------------------------------------*/ + +#ifndef PORTABLE_H +#define PORTABLE_H + +/* Include the macro file relevant to the port being used. */ + +#ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT + #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef OPEN_WATCOM_FLASH_LITE_186_PORT + #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef GCC_MEGA_AVR + #include "../portable/GCC/ATMega323/portmacro.h" +#endif + +#ifdef IAR_MEGA_AVR + #include "../portable/IAR/ATMega323/portmacro.h" +#endif + +#ifdef MPLAB_PIC24_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_DSPIC_PORT + #include "..\..\Source\portable\MPLAB\PIC24_dsPIC\portmacro.h" +#endif + +#ifdef MPLAB_PIC18F_PORT + #include "..\..\Source\portable\MPLAB\PIC18F\portmacro.h" +#endif + +#ifdef MPLAB_PIC32MX_PORT + #include "..\..\Source\portable\MPLAB\PIC32MX\portmacro.h" +#endif + +#ifdef _FEDPICC + #include "libFreeRTOS/Include/portmacro.h" +#endif + +#ifdef SDCC_CYGNAL + #include "../../Source/portable/SDCC/Cygnal/portmacro.h" +#endif + +#ifdef GCC_ARM7 + #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" +#endif + +#ifdef GCC_ARM7_ECLIPSE + #include "portmacro.h" +#endif + +#ifdef ROWLEY_LPC23xx + #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" +#endif + +#ifdef IAR_MSP430 + #include "..\..\Source\portable\IAR\MSP430\portmacro.h" +#endif + +#ifdef GCC_MSP430 + #include "../../Source/portable/GCC/MSP430F449/portmacro.h" +#endif + +#ifdef ROWLEY_MSP430 + #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" +#endif + +#ifdef ARM7_LPC21xx_KEIL_RVDS + #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" +#endif + +#ifdef SAM7_GCC + #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" +#endif + +#ifdef SAM7_IAR + #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" +#endif + +#ifdef SAM9XE_IAR + #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" +#endif + +#ifdef LPC2000_IAR + #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" +#endif + +#ifdef STR71X_IAR + #include "..\..\Source\portable\IAR\STR71x\portmacro.h" +#endif + +#ifdef STR75X_IAR + #include "..\..\Source\portable\IAR\STR75x\portmacro.h" +#endif + +#ifdef STR75X_GCC + #include "..\..\Source\portable\GCC\STR75x\portmacro.h" +#endif + +#ifdef STR91X_IAR + #include "..\..\Source\portable\IAR\STR91x\portmacro.h" +#endif + +#ifdef GCC_H8S + #include "../../Source/portable/GCC/H8S2329/portmacro.h" +#endif + +#ifdef GCC_AT91FR40008 + #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" +#endif + +#ifdef RVDS_ARMCM3_LM3S102 + #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3_LM3S102 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef GCC_ARMCM3 + #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARM_CM3 + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef IAR_ARMCM3_LM + #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" +#endif + +#ifdef HCS12_CODE_WARRIOR + #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" +#endif + +#ifdef MICROBLAZE_GCC + #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" +#endif + +#ifdef TERN_EE + #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" +#endif + +#ifdef GCC_HCS12 + #include "../../Source/portable/GCC/HCS12/portmacro.h" +#endif + +#ifdef GCC_MCF5235 + #include "../../Source/portable/GCC/MCF5235/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_GCC + #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" +#endif + +#ifdef COLDFIRE_V2_CODEWARRIOR + #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" +#endif + +#ifdef GCC_PPC405 + #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" +#endif + +#ifdef GCC_PPC440 + #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" +#endif + +#ifdef _16FX_SOFTUNE + #include "..\..\Source\portable\Softune\MB96340\portmacro.h" +#endif + +#ifdef BCC_INDUSTRIAL_PC_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef BCC_FLASH_LITE_186_PORT + /* A short file name has to be used in place of the normal + FreeRTOSConfig.h when using the Borland compiler. */ + #include "frconfig.h" + #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" + typedef void ( __interrupt __far *pxISR )(); +#endif + +#ifdef __GNUC__ + #ifdef __AVR32_AVR32A__ + #include "portmacro.h" + #endif +#endif + +#ifdef __ICCAVR32__ + #ifdef __CORE__ + #if __CORE__ == __AVR32A__ + #include "portmacro.h" + #endif + #endif +#endif + +#ifdef __91467D + #include "portmacro.h" +#endif + +#ifdef __96340 + #include "portmacro.h" +#endif + + +#ifdef __IAR_V850ES_Fx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx3_L__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Jx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_V850ES_Hx2__ + #include "../../Source/portable/IAR/V850ES/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +#ifdef __IAR_78K0R_Kx3L__ + #include "../../Source/portable/IAR/78K0R/portmacro.h" +#endif + +/* Catch all to ensure portmacro.h is included in the build. Newer demos +have the path as part of the project options, rather than as relative from +the project location. If portENTER_CRITICAL() has not been defined then +portmacro.h has not yet been included - as every portmacro.h provides a +portENTER_CRITICAL() definition. Check the demo application for your demo +to find the path to the correct portmacro.h file. */ +#ifndef portENTER_CRITICAL + #include "../../Source/portable/GCC/Posix/portmacro.h" + //#include "portmacro.h" +#endif + +#if portBYTE_ALIGNMENT == 8 + #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) +#endif + +#if portBYTE_ALIGNMENT == 4 + #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) +#endif + +#if portBYTE_ALIGNMENT == 2 + #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) +#endif + +#if portBYTE_ALIGNMENT == 1 + #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) +#endif + +#ifndef portBYTE_ALIGNMENT_MASK + #error "Invalid portBYTE_ALIGNMENT definition" +#endif + +#ifndef portNUM_CONFIGURABLE_REGIONS + #define portNUM_CONFIGURABLE_REGIONS 1 +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +#include "mpu_wrappers.h" + +/* + * Setup the stack of a new task so it is ready to be placed under the + * scheduler control. The registers have to be placed on the stack in + * the order that the port expects to find them. + * + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters, portBASE_TYPE xRunPrivileged ) PRIVILEGED_FUNCTION; +#else + portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters ); +#endif + +/* + * Map to the memory management routines required for the port. + */ +void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; +void vPortFree( void *pv ) PRIVILEGED_FUNCTION; +void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; +size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; + +/* + * Setup the hardware ready for the scheduler to take control. This generally + * sets up a tick interrupt and sets timers for the correct tick frequency. + */ +portBASE_TYPE xPortStartScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so + * the hardware is left in its original condition after the scheduler stops + * executing. + */ +void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; + +/* + * The structures and methods of manipulating the MPU are contained within the + * port layer. + * + * Fills the xMPUSettings structure with the memory region information + * contained in xRegions. + */ +#if( portUSING_MPU_WRAPPERS == 1 ) + struct xMEMORY_REGION; + void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, portSTACK_TYPE *pxBottomOfStack, unsigned short usStackDepth ) PRIVILEGED_FUNCTION; +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* PORTABLE_H */ + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/projdefs.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/projdefs.h index 25e9560ea..4ce410132 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/projdefs.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/projdefs.h @@ -1,77 +1,77 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef PROJDEFS_H -#define PROJDEFS_H - -/* Defines the prototype to which task functions must conform. */ -typedef void (*pdTASK_CODE)( void * ); - -#define pdTRUE ( 1 ) -#define pdFALSE ( 0 ) - -#define pdPASS ( 1 ) -#define pdFAIL ( 0 ) -#define errQUEUE_EMPTY ( 0 ) -#define errQUEUE_FULL ( 0 ) - -/* Error definitions. */ -#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) -#define errNO_TASK_TO_RUN ( -2 ) -#define errQUEUE_BLOCKED ( -4 ) -#define errQUEUE_YIELD ( -5 ) - -#endif /* PROJDEFS_H */ - - - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef PROJDEFS_H +#define PROJDEFS_H + +/* Defines the prototype to which task functions must conform. */ +typedef void (*pdTASK_CODE)( void * ); + +#define pdTRUE ( 1 ) +#define pdFALSE ( 0 ) + +#define pdPASS ( 1 ) +#define pdFAIL ( 0 ) +#define errQUEUE_EMPTY ( 0 ) +#define errQUEUE_FULL ( 0 ) + +/* Error definitions. */ +#define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) +#define errNO_TASK_TO_RUN ( -2 ) +#define errQUEUE_BLOCKED ( -4 ) +#define errQUEUE_YIELD ( -5 ) + +#endif /* PROJDEFS_H */ + + + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/queue.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/queue.h index c26ccc7fe..055091624 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/queue.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/queue.h @@ -1,1261 +1,1261 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include queue.h" -#endif - - - - -#ifndef QUEUE_H -#define QUEUE_H - -#ifdef __cplusplus -extern "C" { -#endif - - -#include "mpu_wrappers.h" - - -typedef void * xQueueHandle; - - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - - -/** - * queue. h - *
- xQueueHandle xQueueCreate(
-							  unsigned portBASE_TYPE uxQueueLength,
-							  unsigned portBASE_TYPE uxItemSize
-						  );
- * 
- * - * Creates a new queue instance. This allocates the storage required by the - * new queue and returns a handle for the queue. - * - * @param uxQueueLength The maximum number of items that the queue can contain. - * - * @param uxItemSize The number of bytes each item in the queue will require. - * Items are queued by copy, not by reference, so this is the number of bytes - * that will be copied for each posted item. Each item on the queue must be - * the same size. - * - * @return If the queue is successfully create then a handle to the newly - * created queue is returned. If the queue cannot be created then 0 is - * returned. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- };
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-	if( xQueue1 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue2 == 0 )
-	{
-		// Queue was not created and must not be used.
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueCreate xQueueCreate - * \ingroup QueueManagement - */ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ); - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToToFront(
-								   xQueueHandle	xQueue,
-								   const	void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the front of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_FRONT ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBack(
-								   xQueueHandle	xQueue,
-								   const	void	*	pvItemToQueue,
-								   portTickType	xTicksToWait
-							   );
- * 
- * - * This is a macro that calls xQueueGenericSend(). - * - * Post an item to the back of a queue. The item is queued by copy, not by - * reference. This function must not be called from an interrupt service - * routine. See xQueueSendFromISR () for an alternative which may be used - * in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the queue - * is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSend(
-							  xQueueHandle xQueue,
-							  const void * pvItemToQueue,
-							  portTickType xTicksToWait
-						 );
- * 
- * - * This is a macro that calls xQueueGenericSend(). It is included for - * backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToFront() and xQueueSendToBack() macros. It is - * equivalent to xQueueSendToBack(). - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSend(
-									xQueueHandle xQueue,
-									const void * pvItemToQueue,
-									portTickType xTicksToWait
-									portBASE_TYPE xCopyPosition
-								);
- * 
- * - * It is preferred that the macros xQueueSend(), xQueueSendToFront() and - * xQueueSendToBack() are used in place of calling this function directly. - * - * Post an item on a queue. The item is queued by copy, not by reference. - * This function must not be called from an interrupt service routine. - * See xQueueSendFromISR () for an alternative which may be used in an ISR. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for space to become available on the queue, should it already - * be full. The call will return immediately if this is set to 0 and the - * queue is full. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- unsigned long ulVar = 10UL;
-
- void vATask( void *pvParameters )
- {
- xQueueHandle xQueue1, xQueue2;
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 unsigned long values.
-	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
-
-	// ...
-
-	if( xQueue1 != 0 )
-	{
-		// Send an unsigned long.  Wait for 10 ticks for space to become
-		// available if necessary.
-		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
-		{
-			// Failed to post the message, even after 10 ticks.
-		}
-	}
-
-	if( xQueue2 != 0 )
-	{
-		// Send a pointer to a struct AMessage object.  Don't block if the
-		// queue is already full.
-		pxMessage = & xMessage;
-		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueSend xQueueSend - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueuePeek(
-							 xQueueHandle xQueue,
-							 void *pvBuffer,
-							 portTickType xTicksToWait
-						 );
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue without removing the item from the queue. - * The item is received by copy so a buffer of adequate size must be - * provided. The number of bytes copied into the buffer was defined when - * the queue was created. - * - * Successfully received items remain on the queue so will be returned again - * by the next call, or a call to xQueueReceive(). - * - * This macro must not be used in an interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue - * is empty. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to peek the data from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Peek a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask, but the item still remains on the queue.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( xQueue, pvBuffer, xTicksToWait, pdTRUE ) - -/** - * queue. h - *
- portBASE_TYPE xQueueReceive(
-								 xQueueHandle xQueue,
-								 void *pvBuffer,
-								 portTickType xTicksToWait
-							);
- * - * This is a macro that calls the xQueueGenericReceive() function. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * Successfully received items are removed from the queue. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. xQueueReceive() will return immediately if xTicksToWait - * is zero and the queue is empty. The time is defined in tick periods so the - * constant portTICK_RATE_MS should be used to convert to real time if this is - * required. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( xQueue, pvBuffer, xTicksToWait, pdFALSE ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericReceive(
-									   xQueueHandle	xQueue,
-									   void	*pvBuffer,
-									   portTickType	xTicksToWait
-									   portBASE_TYPE	xJustPeek
-									);
- * - * It is preferred that the macro xQueueReceive() be used rather than calling - * this function directly. - * - * Receive an item from a queue. The item is received by copy so a buffer of - * adequate size must be provided. The number of bytes copied into the buffer - * was defined when the queue was created. - * - * This function must not be used in an interrupt service routine. See - * xQueueReceiveFromISR for an alternative that can. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param xTicksToWait The maximum amount of time the task should block - * waiting for an item to receive should the queue be empty at the time - * of the call. The time is defined in tick periods so the constant - * portTICK_RATE_MS should be used to convert to real time if this is required. - * xQueueGenericReceive() will return immediately if the queue is empty and - * xTicksToWait is 0. - * - * @param xJustPeek When set to true, the item received from the queue is not - * actually removed from the queue - meaning a subsequent call to - * xQueueReceive() will return the same item. When set to false, the item - * being received from the queue is also removed from the queue. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
- struct AMessage
- {
-	char ucMessageID;
-	char ucData[ 20 ];
- } xMessage;
-
- xQueueHandle xQueue;
-
- // Task to create a queue and post a value.
- void vATask( void *pvParameters )
- {
- struct AMessage *pxMessage;
-
-	// Create a queue capable of containing 10 pointers to AMessage structures.
-	// These should be passed by pointer as they contain a lot of data.
-	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Send a pointer to a struct AMessage object.  Don't block if the
-	// queue is already full.
-	pxMessage = & xMessage;
-	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
-
-	// ... Rest of task code.
- }
-
- // Task to receive from the queue.
- void vADifferentTask( void *pvParameters )
- {
- struct AMessage *pxRxedMessage;
-
-	if( xQueue != 0 )
-	{
-		// Receive a message on the created queue.  Block for 10 ticks if a
-		// message is not immediately available.
-		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
-		{
-			// pcRxedMessage now points to the struct AMessage variable posted
-			// by vATask.
-		}
-	}
-
-	// ... Rest of task code.
- }
- 
- * \defgroup xQueueReceive xQueueReceive - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); - -/** - * queue. h - *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
- * - * Return the number of messages stored in a queue. - * - * @param xQueue A handle to the queue being queried. - * - * @return The number of messages available in the queue. - * - * \page uxQueueMessagesWaiting uxQueueMessagesWaiting - * \ingroup QueueManagement - */ -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); - -/** - * queue. h - *
void vQueueDelete( xQueueHandle xQueue );
- * - * Delete a queue - freeing all the memory allocated for storing of items - * placed on the queue. - * - * @param xQueue A handle to the queue to be deleted. - * - * \page vQueueDelete vQueueDelete - * \ingroup QueueManagement - */ -void vQueueDelete( xQueueHandle xQueue ); - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToFrontFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the front of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPrioritTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_FRONT ) - - -/** - * queue. h - *
- portBASE_TYPE xQueueSendToBackFromISR(
-										 xQueueHandle pxQueue,
-										 const void *pvItemToQueue,
-										 portBASE_TYPE *pxHigherPriorityTaskWoken
-									  );
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). - * - * Post an item to the back of a queue. It is safe to use this macro from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		taskYIELD ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueSendFromISR(
-									 xQueueHandle pxQueue,
-									 const void *pvItemToQueue,
-									 portBASE_TYPE *pxHigherPriorityTaskWoken
-								);
- 
- * - * This is a macro that calls xQueueGenericSendFromISR(). It is included - * for backward compatibility with versions of FreeRTOS.org that did not - * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() - * macros. - * - * Post an item to the back of a queue. It is safe to use this function from - * within an interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWoken;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWoken = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post the byte.
-		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.
-	if( xHigherPriorityTaskWoken )
-	{
-		// Actual macro used here is port specific.
-		taskYIELD_FROM_ISR ();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) - -/** - * queue. h - *
- portBASE_TYPE xQueueGenericSendFromISR(
-										   xQueueHandle	pxQueue,
-										   const	void	*pvItemToQueue,
-										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
-										   portBASE_TYPE	xCopyPosition
-									   );
- 
- * - * It is preferred that the macros xQueueSendFromISR(), - * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place - * of calling this function directly. - * - * Post an item on a queue. It is safe to use this function from within an - * interrupt service routine. - * - * Items are queued by copy not reference so it is preferable to only - * queue small items, especially when called from an ISR. In most cases - * it would be preferable to store a pointer to the item being queued. - * - * @param xQueue The handle to the queue on which the item is to be posted. - * - * @param pvItemToQueue A pointer to the item that is to be placed on the - * queue. The size of the items the queue will hold was defined when the - * queue was created, so this many bytes will be copied from pvItemToQueue - * into the queue storage area. - * - * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the - * item at the back of the queue, or queueSEND_TO_FRONT to place the item - * at the front of the queue (for high priority messages). - * - * @return pdTRUE if the data was successfully sent to the queue, otherwise - * errQUEUE_FULL. - * - * Example usage for buffered IO (where the ISR can obtain more than one value - * per call): -
- void vBufferISR( void )
- {
- char cIn;
- portBASE_TYPE xHigherPriorityTaskWokenByPost;
-
-	// We have not woken a task at the start of the ISR.
-	xHigherPriorityTaskWokenByPost = pdFALSE;
-
-	// Loop until the buffer is empty.
-	do
-	{
-		// Obtain a byte from the buffer.
-		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
-
-		// Post each byte.
-		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
-
-	} while( portINPUT_BYTE( BUFFER_COUNT ) );
-
-	// Now the buffer is empty we can switch context if necessary.  Note that the
-	// name of the yield function required is port specific.
-	if( xHigherPriorityTaskWokenByPost )
-	{
-		taskYIELD_YIELD_FROM_ISR();
-	}
- }
- 
- * - * \defgroup xQueueSendFromISR xQueueSendFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); - -/** - * queue. h - *
- portBASE_TYPE xQueueReceiveFromISR(
-									   xQueueHandle	pxQueue,
-									   void	*pvBuffer,
-									   portBASE_TYPE	*pxTaskWoken
-								   );
- * 
- * - * Receive an item from a queue. It is safe to use this function from within an - * interrupt service routine. - * - * @param pxQueue The handle to the queue from which the item is to be - * received. - * - * @param pvBuffer Pointer to the buffer into which the received item will - * be copied. - * - * @param pxTaskWoken A task may be blocked waiting for space to become - * available on the queue. If xQueueReceiveFromISR causes such a task to - * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will - * remain unchanged. - * - * @return pdTRUE if an item was successfully received from the queue, - * otherwise pdFALSE. - * - * Example usage: -
-
- xQueueHandle xQueue;
-
- // Function to create a queue and post some values.
- void vAFunction( void *pvParameters )
- {
- char cValueToPost;
- const portTickType xBlockTime = ( portTickType )0xff;
-
-	// Create a queue capable of containing 10 characters.
-	xQueue = xQueueCreate( 10, sizeof( char ) );
-	if( xQueue == 0 )
-	{
-		// Failed to create the queue.
-	}
-
-	// ...
-
-	// Post some characters that will be used within an ISR.  If the queue
-	// is full then this task will block for xBlockTime ticks.
-	cValueToPost = 'a';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-	cValueToPost = 'b';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
-
-	// ... keep posting characters ... this task may block when the queue
-	// becomes full.
-
-	cValueToPost = 'c';
-	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
- }
-
- // ISR that outputs all the characters received on the queue.
- void vISR_Routine( void )
- {
- portBASE_TYPE xTaskWokenByReceive = pdFALSE;
- char cRxedChar;
-
-	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
-	{
-		// A character was received.  Output the character now.
-		vOutputCharacter( cRxedChar );
-
-		// If removing the character from the queue woke the task that was
-		// posting onto the queue cTaskWokenByReceive will have been set to
-		// pdTRUE.  No matter how many times this loop iterates only one
-		// task will be woken.
-	}
-
-	if( cTaskWokenByPost != ( char ) pdFALSE;
-	{
-		taskYIELD ();
-	}
- }
- 
- * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR - * \ingroup QueueManagement - */ -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ); - -/* - * Utilities to query queue that are safe to use from an ISR. These utilities - * should be used only from witin an ISR, or within a critical section. - */ -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); - - -/* - * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). - * Likewise xQueueAltGenericReceive() is an alternative version of - * xQueueGenericReceive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); -#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_FRONT ) -#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) -#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( xQueue, pvBuffer, xTicksToWait, pdFALSE ) -#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( xQueue, pvBuffer, xTicksToWait, pdTRUE ) - -/* - * The functions defined above are for passing data to and from tasks. The - * functions below are the equivalents for passing data to and from - * co-routines. - * - * These functions are called from the co-routine macro implementation and - * should not be called directly from application code. Instead use the macro - * wrappers defined within croutine.h. - */ -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); - -/* - * For internal use only. Use xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting() instead of calling these functions directly. - */ -xQueueHandle xQueueCreateMutex( void ); -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); - -/* - * For internal use only. Use xSemaphoreTakeMutexRecursive() or - * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. - */ -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ); -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ); - -/* - * The registry is provided as a means for kernel aware debuggers to - * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add - * a queue, semaphore or mutex handle to the registry if you want the handle - * to be available to a kernel aware debugger. If you are not using a kernel - * aware debugger then this function can be ignored. - * - * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the - * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 - * within FreeRTOSConfig.h for the registry to be available. Its value - * does not effect the number of queues, semaphores and mutexes that can be - * created - just the number that the registry can hold. - * - * @param xQueue The handle of the queue being added to the registry. This - * is the handle returned by a call to xQueueCreate(). Semaphore and mutex - * handles can also be passed in here. - * - * @param pcName The name to be associated with the handle. This is the - * name that the kernel aware debugger will display. - */ -#if configQUEUE_REGISTRY_SIZE > 0 - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); -#endif - - - - -#ifdef __cplusplus -} -#endif - -#endif /* QUEUE_H */ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include queue.h" +#endif + + + + +#ifndef QUEUE_H +#define QUEUE_H + +#ifdef __cplusplus +extern "C" { +#endif + + +#include "mpu_wrappers.h" + + +typedef void * xQueueHandle; + + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + + +/** + * queue. h + *
+ xQueueHandle xQueueCreate(
+							  unsigned portBASE_TYPE uxQueueLength,
+							  unsigned portBASE_TYPE uxItemSize
+						  );
+ * 
+ * + * Creates a new queue instance. This allocates the storage required by the + * new queue and returns a handle for the queue. + * + * @param uxQueueLength The maximum number of items that the queue can contain. + * + * @param uxItemSize The number of bytes each item in the queue will require. + * Items are queued by copy, not by reference, so this is the number of bytes + * that will be copied for each posted item. Each item on the queue must be + * the same size. + * + * @return If the queue is successfully create then a handle to the newly + * created queue is returned. If the queue cannot be created then 0 is + * returned. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ };
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+	if( xQueue1 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue2 == 0 )
+	{
+		// Queue was not created and must not be used.
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueCreate xQueueCreate + * \ingroup QueueManagement + */ +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToToFront(
+								   xQueueHandle	xQueue,
+								   const	void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the front of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToFront( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToFront( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_FRONT ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBack(
+								   xQueueHandle	xQueue,
+								   const	void	*	pvItemToQueue,
+								   portTickType	xTicksToWait
+							   );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). + * + * Post an item to the back of a queue. The item is queued by copy, not by + * reference. This function must not be called from an interrupt service + * routine. See xQueueSendFromISR () for an alternative which may be used + * in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the queue + * is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSendToBack( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSendToBack( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSend(
+							  xQueueHandle xQueue,
+							  const void * pvItemToQueue,
+							  portTickType xTicksToWait
+						 );
+ * 
+ * + * This is a macro that calls xQueueGenericSend(). It is included for + * backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToFront() and xQueueSendToBack() macros. It is + * equivalent to xQueueSendToBack(). + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10 ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0 );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +#define xQueueSend( xQueue, pvItemToQueue, xTicksToWait ) xQueueGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSend(
+									xQueueHandle xQueue,
+									const void * pvItemToQueue,
+									portTickType xTicksToWait
+									portBASE_TYPE xCopyPosition
+								);
+ * 
+ * + * It is preferred that the macros xQueueSend(), xQueueSendToFront() and + * xQueueSendToBack() are used in place of calling this function directly. + * + * Post an item on a queue. The item is queued by copy, not by reference. + * This function must not be called from an interrupt service routine. + * See xQueueSendFromISR () for an alternative which may be used in an ISR. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for space to become available on the queue, should it already + * be full. The call will return immediately if this is set to 0 and the + * queue is full. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the item was successfully posted, otherwise errQUEUE_FULL. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ unsigned long ulVar = 10UL;
+
+ void vATask( void *pvParameters )
+ {
+ xQueueHandle xQueue1, xQueue2;
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 unsigned long values.
+	xQueue1 = xQueueCreate( 10, sizeof( unsigned long ) );
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue2 = xQueueCreate( 10, sizeof( struct AMessage * ) );
+
+	// ...
+
+	if( xQueue1 != 0 )
+	{
+		// Send an unsigned long.  Wait for 10 ticks for space to become
+		// available if necessary.
+		if( xQueueGenericSend( xQueue1, ( void * ) &ulVar, ( portTickType ) 10, queueSEND_TO_BACK ) != pdPASS )
+		{
+			// Failed to post the message, even after 10 ticks.
+		}
+	}
+
+	if( xQueue2 != 0 )
+	{
+		// Send a pointer to a struct AMessage object.  Don't block if the
+		// queue is already full.
+		pxMessage = & xMessage;
+		xQueueGenericSend( xQueue2, ( void * ) &pxMessage, ( portTickType ) 0, queueSEND_TO_BACK );
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueSend xQueueSend + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueuePeek(
+							 xQueueHandle xQueue,
+							 void *pvBuffer,
+							 portTickType xTicksToWait
+						 );
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue without removing the item from the queue. + * The item is received by copy so a buffer of adequate size must be + * provided. The number of bytes copied into the buffer was defined when + * the queue was created. + * + * Successfully received items remain on the queue so will be returned again + * by the next call, or a call to xQueueReceive(). + * + * This macro must not be used in an interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueuePeek() will return immediately if xTicksToWait is 0 and the queue + * is empty. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to peek the data from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Peek a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueuePeek( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask, but the item still remains on the queue.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueuePeek( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( xQueue, pvBuffer, xTicksToWait, pdTRUE ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceive(
+								 xQueueHandle xQueue,
+								 void *pvBuffer,
+								 portTickType xTicksToWait
+							);
+ * + * This is a macro that calls the xQueueGenericReceive() function. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * Successfully received items are removed from the queue. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. xQueueReceive() will return immediately if xTicksToWait + * is zero and the queue is empty. The time is defined in tick periods so the + * constant portTICK_RATE_MS should be used to convert to real time if this is + * required. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +#define xQueueReceive( xQueue, pvBuffer, xTicksToWait ) xQueueGenericReceive( xQueue, pvBuffer, xTicksToWait, pdFALSE ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericReceive(
+									   xQueueHandle	xQueue,
+									   void	*pvBuffer,
+									   portTickType	xTicksToWait
+									   portBASE_TYPE	xJustPeek
+									);
+ * + * It is preferred that the macro xQueueReceive() be used rather than calling + * this function directly. + * + * Receive an item from a queue. The item is received by copy so a buffer of + * adequate size must be provided. The number of bytes copied into the buffer + * was defined when the queue was created. + * + * This function must not be used in an interrupt service routine. See + * xQueueReceiveFromISR for an alternative that can. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param xTicksToWait The maximum amount of time the task should block + * waiting for an item to receive should the queue be empty at the time + * of the call. The time is defined in tick periods so the constant + * portTICK_RATE_MS should be used to convert to real time if this is required. + * xQueueGenericReceive() will return immediately if the queue is empty and + * xTicksToWait is 0. + * + * @param xJustPeek When set to true, the item received from the queue is not + * actually removed from the queue - meaning a subsequent call to + * xQueueReceive() will return the same item. When set to false, the item + * being received from the queue is also removed from the queue. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+ struct AMessage
+ {
+	char ucMessageID;
+	char ucData[ 20 ];
+ } xMessage;
+
+ xQueueHandle xQueue;
+
+ // Task to create a queue and post a value.
+ void vATask( void *pvParameters )
+ {
+ struct AMessage *pxMessage;
+
+	// Create a queue capable of containing 10 pointers to AMessage structures.
+	// These should be passed by pointer as they contain a lot of data.
+	xQueue = xQueueCreate( 10, sizeof( struct AMessage * ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Send a pointer to a struct AMessage object.  Don't block if the
+	// queue is already full.
+	pxMessage = & xMessage;
+	xQueueSend( xQueue, ( void * ) &pxMessage, ( portTickType ) 0 );
+
+	// ... Rest of task code.
+ }
+
+ // Task to receive from the queue.
+ void vADifferentTask( void *pvParameters )
+ {
+ struct AMessage *pxRxedMessage;
+
+	if( xQueue != 0 )
+	{
+		// Receive a message on the created queue.  Block for 10 ticks if a
+		// message is not immediately available.
+		if( xQueueGenericReceive( xQueue, &( pxRxedMessage ), ( portTickType ) 10 ) )
+		{
+			// pcRxedMessage now points to the struct AMessage variable posted
+			// by vATask.
+		}
+	}
+
+	// ... Rest of task code.
+ }
+ 
+ * \defgroup xQueueReceive xQueueReceive + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle xQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeek ); + +/** + * queue. h + *
unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue );
+ * + * Return the number of messages stored in a queue. + * + * @param xQueue A handle to the queue being queried. + * + * @return The number of messages available in the queue. + * + * \page uxQueueMessagesWaiting uxQueueMessagesWaiting + * \ingroup QueueManagement + */ +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle xQueue ); + +/** + * queue. h + *
void vQueueDelete( xQueueHandle xQueue );
+ * + * Delete a queue - freeing all the memory allocated for storing of items + * placed on the queue. + * + * @param xQueue A handle to the queue to be deleted. + * + * \page vQueueDelete vQueueDelete + * \ingroup QueueManagement + */ +void vQueueDelete( xQueueHandle xQueue ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToFrontFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the front of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToFrontFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToFromFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPrioritTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToFrontFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToFrontFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_FRONT ) + + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendToBackFromISR(
+										 xQueueHandle pxQueue,
+										 const void *pvItemToQueue,
+										 portBASE_TYPE *pxHigherPriorityTaskWoken
+									  );
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). + * + * Post an item to the back of a queue. It is safe to use this macro from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendToBackFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendToBackFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendToBackFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendToBackFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueSendFromISR(
+									 xQueueHandle pxQueue,
+									 const void *pvItemToQueue,
+									 portBASE_TYPE *pxHigherPriorityTaskWoken
+								);
+ 
+ * + * This is a macro that calls xQueueGenericSendFromISR(). It is included + * for backward compatibility with versions of FreeRTOS.org that did not + * include the xQueueSendToBackFromISR() and xQueueSendToFrontFromISR() + * macros. + * + * Post an item to the back of a queue. It is safe to use this function from + * within an interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWoken;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWoken = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post the byte.
+		xQueueSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWoken );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.
+	if( xHigherPriorityTaskWoken )
+	{
+		// Actual macro used here is port specific.
+		taskYIELD_FROM_ISR ();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +#define xQueueSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( pxQueue, pvItemToQueue, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) + +/** + * queue. h + *
+ portBASE_TYPE xQueueGenericSendFromISR(
+										   xQueueHandle	pxQueue,
+										   const	void	*pvItemToQueue,
+										   portBASE_TYPE	*pxHigherPriorityTaskWoken,
+										   portBASE_TYPE	xCopyPosition
+									   );
+ 
+ * + * It is preferred that the macros xQueueSendFromISR(), + * xQueueSendToFrontFromISR() and xQueueSendToBackFromISR() be used in place + * of calling this function directly. + * + * Post an item on a queue. It is safe to use this function from within an + * interrupt service routine. + * + * Items are queued by copy not reference so it is preferable to only + * queue small items, especially when called from an ISR. In most cases + * it would be preferable to store a pointer to the item being queued. + * + * @param xQueue The handle to the queue on which the item is to be posted. + * + * @param pvItemToQueue A pointer to the item that is to be placed on the + * queue. The size of the items the queue will hold was defined when the + * queue was created, so this many bytes will be copied from pvItemToQueue + * into the queue storage area. + * + * @param pxHigherPriorityTaskWoken xQueueGenericSendFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if sending to the queue caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xQueueGenericSendFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @param xCopyPosition Can take the value queueSEND_TO_BACK to place the + * item at the back of the queue, or queueSEND_TO_FRONT to place the item + * at the front of the queue (for high priority messages). + * + * @return pdTRUE if the data was successfully sent to the queue, otherwise + * errQUEUE_FULL. + * + * Example usage for buffered IO (where the ISR can obtain more than one value + * per call): +
+ void vBufferISR( void )
+ {
+ char cIn;
+ portBASE_TYPE xHigherPriorityTaskWokenByPost;
+
+	// We have not woken a task at the start of the ISR.
+	xHigherPriorityTaskWokenByPost = pdFALSE;
+
+	// Loop until the buffer is empty.
+	do
+	{
+		// Obtain a byte from the buffer.
+		cIn = portINPUT_BYTE( RX_REGISTER_ADDRESS );
+
+		// Post each byte.
+		xQueueGenericSendFromISR( xRxQueue, &cIn, &xHigherPriorityTaskWokenByPost, queueSEND_TO_BACK );
+
+	} while( portINPUT_BYTE( BUFFER_COUNT ) );
+
+	// Now the buffer is empty we can switch context if necessary.  Note that the
+	// name of the yield function required is port specific.
+	if( xHigherPriorityTaskWokenByPost )
+	{
+		taskYIELD_YIELD_FROM_ISR();
+	}
+ }
+ 
+ * + * \defgroup xQueueSendFromISR xQueueSendFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ); + +/** + * queue. h + *
+ portBASE_TYPE xQueueReceiveFromISR(
+									   xQueueHandle	pxQueue,
+									   void	*pvBuffer,
+									   portBASE_TYPE	*pxTaskWoken
+								   );
+ * 
+ * + * Receive an item from a queue. It is safe to use this function from within an + * interrupt service routine. + * + * @param pxQueue The handle to the queue from which the item is to be + * received. + * + * @param pvBuffer Pointer to the buffer into which the received item will + * be copied. + * + * @param pxTaskWoken A task may be blocked waiting for space to become + * available on the queue. If xQueueReceiveFromISR causes such a task to + * unblock *pxTaskWoken will get set to pdTRUE, otherwise *pxTaskWoken will + * remain unchanged. + * + * @return pdTRUE if an item was successfully received from the queue, + * otherwise pdFALSE. + * + * Example usage: +
+
+ xQueueHandle xQueue;
+
+ // Function to create a queue and post some values.
+ void vAFunction( void *pvParameters )
+ {
+ char cValueToPost;
+ const portTickType xBlockTime = ( portTickType )0xff;
+
+	// Create a queue capable of containing 10 characters.
+	xQueue = xQueueCreate( 10, sizeof( char ) );
+	if( xQueue == 0 )
+	{
+		// Failed to create the queue.
+	}
+
+	// ...
+
+	// Post some characters that will be used within an ISR.  If the queue
+	// is full then this task will block for xBlockTime ticks.
+	cValueToPost = 'a';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+	cValueToPost = 'b';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+
+	// ... keep posting characters ... this task may block when the queue
+	// becomes full.
+
+	cValueToPost = 'c';
+	xQueueSend( xQueue, ( void * ) &cValueToPost, xBlockTime );
+ }
+
+ // ISR that outputs all the characters received on the queue.
+ void vISR_Routine( void )
+ {
+ portBASE_TYPE xTaskWokenByReceive = pdFALSE;
+ char cRxedChar;
+
+	while( xQueueReceiveFromISR( xQueue, ( void * ) &cRxedChar, &xTaskWokenByReceive) )
+	{
+		// A character was received.  Output the character now.
+		vOutputCharacter( cRxedChar );
+
+		// If removing the character from the queue woke the task that was
+		// posting onto the queue cTaskWokenByReceive will have been set to
+		// pdTRUE.  No matter how many times this loop iterates only one
+		// task will be woken.
+	}
+
+	if( cTaskWokenByPost != ( char ) pdFALSE;
+	{
+		taskYIELD ();
+	}
+ }
+ 
+ * \defgroup xQueueReceiveFromISR xQueueReceiveFromISR + * \ingroup QueueManagement + */ +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ); + +/* + * Utilities to query queue that are safe to use from an ISR. These utilities + * should be used only from witin an ISR, or within a critical section. + */ +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ); +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ); +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ); + + +/* + * xQueueAltGenericSend() is an alternative version of xQueueGenericSend(). + * Likewise xQueueAltGenericReceive() is an alternative version of + * xQueueGenericReceive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ); +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ); +#define xQueueAltSendToFront( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_FRONT ) +#define xQueueAltSendToBack( xQueue, pvItemToQueue, xTicksToWait ) xQueueAltGenericSend( xQueue, pvItemToQueue, xTicksToWait, queueSEND_TO_BACK ) +#define xQueueAltReceive( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( xQueue, pvBuffer, xTicksToWait, pdFALSE ) +#define xQueueAltPeek( xQueue, pvBuffer, xTicksToWait ) xQueueAltGenericReceive( xQueue, pvBuffer, xTicksToWait, pdTRUE ) + +/* + * The functions defined above are for passing data to and from tasks. The + * functions below are the equivalents for passing data to and from + * co-routines. + * + * These functions are called from the co-routine macro implementation and + * should not be called directly from application code. Instead use the macro + * wrappers defined within croutine.h. + */ +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ); +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ); +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ); +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ); + +/* + * For internal use only. Use xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting() instead of calling these functions directly. + */ +xQueueHandle xQueueCreateMutex( void ); +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ); + +/* + * For internal use only. Use xSemaphoreTakeMutexRecursive() or + * xSemaphoreGiveMutexRecursive() instead of calling these functions directly. + */ +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ); +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ); + +/* + * The registry is provided as a means for kernel aware debuggers to + * locate queues, semaphores and mutexes. Call vQueueAddToRegistry() add + * a queue, semaphore or mutex handle to the registry if you want the handle + * to be available to a kernel aware debugger. If you are not using a kernel + * aware debugger then this function can be ignored. + * + * configQUEUE_REGISTRY_SIZE defines the maximum number of handles the + * registry can hold. configQUEUE_REGISTRY_SIZE must be greater than 0 + * within FreeRTOSConfig.h for the registry to be available. Its value + * does not effect the number of queues, semaphores and mutexes that can be + * created - just the number that the registry can hold. + * + * @param xQueue The handle of the queue being added to the registry. This + * is the handle returned by a call to xQueueCreate(). Semaphore and mutex + * handles can also be passed in here. + * + * @param pcName The name to be associated with the handle. This is the + * name that the kernel aware debugger will display. + */ +#if configQUEUE_REGISTRY_SIZE > 0 + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcName ); +#endif + + + + +#ifdef __cplusplus +} +#endif + +#endif /* QUEUE_H */ + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/semphr.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/semphr.h index 3984e4bb9..1d6f34430 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/semphr.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/semphr.h @@ -1,711 +1,711 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include semphr.h" -#endif - -#ifndef SEMAPHORE_H -#define SEMAPHORE_H - -#include "queue.h" - -typedef xQueueHandle xSemaphoreHandle; - -#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1 ) -#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0 ) -#define semGIVE_BLOCK_TIME ( ( portTickType ) 0 ) - - -/** - * semphr. h - *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
- * - * Macro that implements a semaphore by using the existing queue mechanism. - * The queue length is 1 as this is a binary semaphore. The data size is 0 - * as we don't want to actually store any data - we just want to know if the - * queue is empty or full. - * - * This type of semaphore can be used for pure synchronisation between tasks or - * between an interrupt and a task. The semaphore need not be given back once - * obtained, so one task/interrupt can continuously 'give' the semaphore while - * another continuously 'takes' the semaphore. For this reason this type of - * semaphore does not use a priority inheritance mechanism. For an alternative - * that does use priority inheritance see xSemaphoreCreateMutex(). - * - * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
-    // This is a macro so pass the variable in directly.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary - * \ingroup Semaphores - */ -#define vSemaphoreCreateBinary( xSemaphore ) { \ - xSemaphore = xQueueCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH ); \ - if( xSemaphore != NULL ) \ - { \ - xSemaphoreGive( xSemaphore ); \ - } \ - } - -/** - * semphr. h - *
xSemaphoreTake( 
- *                   xSemaphoreHandle xSemaphore, 
- *                   portTickType xBlockTime 
- *               )
- * - * Macro to obtain a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). - * - * @param xSemaphore A handle to the semaphore being taken - obtained when - * the semaphore was created. - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. A block - * time of portMAX_DELAY can be used to block indefinitely (provided - * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). - * - * @return pdTRUE if the semaphore was obtained. pdFALSE - * if xBlockTime expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- // A task that creates a semaphore.
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
- }
-
- // A task that uses the semaphore.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xSemaphore != NULL )
-    {
-        // See if we can obtain the semaphore.  If the semaphore is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the semaphore and can now access the
-            // shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource.  Release the 
-            // semaphore.
-            xSemaphoreGive( xSemaphore );
-        }
-        else
-        {
-            // We could not obtain the semaphore and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTake xSemaphoreTake - * \ingroup Semaphores - */ -#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) xSemaphore, NULL, xBlockTime, pdFALSE ) - -/** - * semphr. h - * xSemaphoreTakeRecursive( - * xSemaphoreHandle xMutex, - * portTickType xBlockTime - * ) - * - * Macro to recursively obtain, or 'take', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being obtained. This is the - * handle returned by xSemaphoreCreateRecursiveMutex(); - * - * @param xBlockTime The time in ticks to wait for the semaphore to become - * available. The macro portTICK_RATE_MS can be used to convert this to a - * real time. A block time of zero can be used to poll the semaphore. If - * the task already owns the semaphore then xSemaphoreTakeRecursive() will - * return immediately no matter what the value of xBlockTime. - * - * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime - * expired without the semaphore becoming available. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, but instead buried in a more complex
-			// call structure.  This is just for illustrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive - * \ingroup Semaphores - */ -#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( xMutex, xBlockTime ) - - -/* - * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) xSemaphore, NULL, xBlockTime, pdFALSE ) - -/** - * semphr. h - *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or - * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). - * - * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for - * an alternative which can be used from an ISR. - * - * This macro must also not be used on semaphores created using - * xSemaphoreCreateRecursiveMutex(). - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. - * Semaphores are implemented using queues. An error can occur if there is - * no space on the queue to post a message - indicating that the - * semaphore was not first obtained correctly. - * - * Example usage: -
- xSemaphoreHandle xSemaphore = NULL;
-
- void vATask( void * pvParameters )
- {
-    // Create the semaphore to guard a shared resource.
-    vSemaphoreCreateBinary( xSemaphore );
-
-    if( xSemaphore != NULL )
-    {
-        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-        {
-            // We would expect this call to fail because we cannot give
-            // a semaphore without first "taking" it!
-        }
-
-        // Obtain the semaphore - don't block if the semaphore is not
-        // immediately available.
-        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
-        {
-            // We now have the semaphore and can access the shared resource.
-
-            // ...
-
-            // We have finished accessing the shared resource so can free the
-            // semaphore.
-            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
-            {
-                // We would not expect this call to fail because we must have
-                // obtained the semaphore to get here.
-            }
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGive xSemaphoreGive - * \ingroup Semaphores - */ -#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) xSemaphore, NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
- * - * Macro to recursively release, or 'give', a mutex type semaphore. - * The mutex must have previously been created using a call to - * xSemaphoreCreateRecursiveMutex(); - * - * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this - * macro to be available. - * - * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * @param xMutex A handle to the mutex being released, or 'given'. This is the - * handle returned by xSemaphoreCreateMutex(); - * - * @return pdTRUE if the semaphore was given. - * - * Example usage: -
- xSemaphoreHandle xMutex = NULL;
-
- // A task that creates a mutex.
- void vATask( void * pvParameters )
- {
-    // Create the mutex to guard a shared resource.
-    xMutex = xSemaphoreCreateRecursiveMutex();
- }
-
- // A task that uses the mutex.
- void vAnotherTask( void * pvParameters )
- {
-    // ... Do other things.
-
-    if( xMutex != NULL )
-    {
-        // See if we can obtain the mutex.  If the mutex is not available
-        // wait 10 ticks to see if it becomes free.	
-        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
-        {
-            // We were able to obtain the mutex and can now access the
-            // shared resource.
-
-            // ...
-            // For some reason due to the nature of the code further calls to 
-			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
-			// code these would not be just sequential calls as this would make
-			// no sense.  Instead the calls are likely to be buried inside
-			// a more complex call structure.
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
-
-            // The mutex has now been 'taken' three times, so will not be 
-			// available to another task until it has also been given back
-			// three times.  Again it is unlikely that real code would have
-			// these calls sequentially, it would be more likely that the calls
-			// to xSemaphoreGiveRecursive() would be called as a call stack
-			// unwound.  This is just for demonstrative purposes.
-            xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-			xSemaphoreGiveRecursive( xMutex );
-
-			// Now the mutex can be taken by other tasks.
-        }
-        else
-        {
-            // We could not obtain the mutex and can therefore not access
-            // the shared resource safely.
-        }
-    }
- }
- 
- * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive - * \ingroup Semaphores - */ -#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( xMutex ) - -/* - * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). - * - * The source code that implements the alternative (Alt) API is much - * simpler because it executes everything from within a critical section. - * This is the approach taken by many other RTOSes, but FreeRTOS.org has the - * preferred fully featured API too. The fully featured API has more - * complex code that takes longer to execute, but makes much less use of - * critical sections. Therefore the alternative API sacrifices interrupt - * responsiveness to gain execution speed, whereas the fully featured API - * sacrifices execution speed to ensure better interrupt responsiveness. - */ -#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) xSemaphore, NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) - -/** - * semphr. h - *
- xSemaphoreGiveFromISR( 
-                          xSemaphoreHandle xSemaphore, 
-                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
-                      )
- * - * Macro to release a semaphore. The semaphore must have previously been - * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). - * - * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) - * must not be used with this macro. - * - * This macro can be used from an ISR. - * - * @param xSemaphore A handle to the semaphore being released. This is the - * handle returned when the semaphore was created. - * - * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set - * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task - * to unblock, and the unblocked task has a priority higher than the currently - * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then - * a context switch should be requested before the interrupt is exited. - * - * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. - * - * Example usage: -
- \#define LONG_TIME 0xffff
- \#define TICKS_TO_WAIT	10
- xSemaphoreHandle xSemaphore = NULL;
-
- // Repetitive task.
- void vATask( void * pvParameters )
- {
-    for( ;; )
-    {
-        // We want this task to run every 10 ticks of a timer.  The semaphore 
-        // was created before this task was started.
-
-        // Block waiting for the semaphore to become available.
-        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
-        {
-            // It is time to execute.
-
-            // ...
-
-            // We have finished our task.  Return to the top of the loop where
-            // we will block on the semaphore until it is time to execute 
-            // again.  Note when using the semaphore for synchronisation with an
-			// ISR in this manner there is no need to 'give' the semaphore back.
-        }
-    }
- }
-
- // Timer ISR
- void vTimerISR( void * pvParameters )
- {
- static unsigned char ucLocalTickCount = 0;
- static signed portBASE_TYPE xHigherPriorityTaskWoken;
-
-    // A timer tick has occurred.
-
-    // ... Do other time functions.
-
-    // Is it time for vATask () to run?
-	xHigherPriorityTaskWoken = pdFALSE;
-    ucLocalTickCount++;
-    if( ucLocalTickCount >= TICKS_TO_WAIT )
-    {
-        // Unblock the task by releasing the semaphore.
-        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
-
-        // Reset the count so we release the semaphore again in 10 ticks time.
-        ucLocalTickCount = 0;
-    }
-
-    if( xHigherPriorityTaskWoken != pdFALSE )
-    {
-        // We can force a context switch here.  Context switching from an
-        // ISR uses port specific syntax.  Check the demo task for your port
-        // to find the syntax required.
-    }
- }
- 
- * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR - * \ingroup Semaphores - */ -#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) xSemaphore, NULL, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateMutex( void )
- * - * Macro that implements a mutex semaphore by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the xSemaphoreTake() - * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and - * xSemaphoreGiveRecursive() macros should not be used. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateMutex() xQueueCreateMutex() - - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
- * - * Macro that implements a recursive mutex by using the existing queue - * mechanism. - * - * Mutexes created using this macro can be accessed using the - * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The - * xSemaphoreTake() and xSemaphoreGive() macros should not be used. - * - * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex - * doesn't become available again until the owner has called - * xSemaphoreGiveRecursive() for each successful 'take' request. For example, - * if a task successfully 'takes' the same mutex 5 times then the mutex will - * not be available to any other task until it has also 'given' the mutex back - * exactly five times. - * - * This type of semaphore uses a priority inheritance mechanism so a task - * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the - * semaphore it is no longer required. - * - * Mutex type semaphores cannot be used from within interrupt service routines. - * - * See vSemaphoreCreateBinary() for an alternative implementation that can be - * used for pure synchronisation (where one task or interrupt always 'gives' the - * semaphore and another always 'takes' the semaphore) and from within interrupt - * service routines. - * - * @return xSemaphore Handle to the created mutex semaphore. Should be of type - * xSemaphoreHandle. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
-    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
-    // This is a macro so pass the variable in directly.
-    xSemaphore = xSemaphoreCreateRecursiveMutex();
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex - * \ingroup Semaphores - */ -#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex() - -/** - * semphr. h - *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
- * - * Macro that creates a counting semaphore by using the existing - * queue mechanism. - * - * Counting semaphores are typically used for two things: - * - * 1) Counting events. - * - * In this usage scenario an event handler will 'give' a semaphore each time - * an event occurs (incrementing the semaphore count value), and a handler - * task will 'take' a semaphore each time it processes an event - * (decrementing the semaphore count value). The count value is therefore - * the difference between the number of events that have occurred and the - * number that have been processed. In this case it is desirable for the - * initial count value to be zero. - * - * 2) Resource management. - * - * In this usage scenario the count value indicates the number of resources - * available. To obtain control of a resource a task must first obtain a - * semaphore - decrementing the semaphore count value. When the count value - * reaches zero there are no free resources. When a task finishes with the - * resource it 'gives' the semaphore back - incrementing the semaphore count - * value. In this case it is desirable for the initial count value to be - * equal to the maximum count value, indicating that all resources are free. - * - * @param uxMaxCount The maximum count value that can be reached. When the - * semaphore reaches this value it can no longer be 'given'. - * - * @param uxInitialCount The count value assigned to the semaphore when it is - * created. - * - * @return Handle to the created semaphore. Null if the semaphore could not be - * created. - * - * Example usage: -
- xSemaphoreHandle xSemaphore;
-
- void vATask( void * pvParameters )
- {
- xSemaphoreHandle xSemaphore = NULL;
-
-    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
-    // The max value to which the semaphore can count should be 10, and the
-    // initial value assigned to the count should be 0.
-    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
-
-    if( xSemaphore != NULL )
-    {
-        // The semaphore was created successfully.
-        // The semaphore can now be used.  
-    }
- }
- 
- * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting - * \ingroup Semaphores - */ -#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( uxMaxCount, uxInitialCount ) - - -#endif /* SEMAPHORE_H */ - - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include semphr.h" +#endif + +#ifndef SEMAPHORE_H +#define SEMAPHORE_H + +#include "queue.h" + +typedef xQueueHandle xSemaphoreHandle; + +#define semBINARY_SEMAPHORE_QUEUE_LENGTH ( ( unsigned char ) 1 ) +#define semSEMAPHORE_QUEUE_ITEM_LENGTH ( ( unsigned char ) 0 ) +#define semGIVE_BLOCK_TIME ( ( portTickType ) 0 ) + + +/** + * semphr. h + *
vSemaphoreCreateBinary( xSemaphoreHandle xSemaphore )
+ * + * Macro that implements a semaphore by using the existing queue mechanism. + * The queue length is 1 as this is a binary semaphore. The data size is 0 + * as we don't want to actually store any data - we just want to know if the + * queue is empty or full. + * + * This type of semaphore can be used for pure synchronisation between tasks or + * between an interrupt and a task. The semaphore need not be given back once + * obtained, so one task/interrupt can continuously 'give' the semaphore while + * another continuously 'takes' the semaphore. For this reason this type of + * semaphore does not use a priority inheritance mechanism. For an alternative + * that does use priority inheritance see xSemaphoreCreateMutex(). + * + * @param xSemaphore Handle to the created semaphore. Should be of type xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to vSemaphoreCreateBinary ().
+    // This is a macro so pass the variable in directly.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateBinary vSemaphoreCreateBinary + * \ingroup Semaphores + */ +#define vSemaphoreCreateBinary( xSemaphore ) { \ + xSemaphore = xQueueCreate( ( unsigned portBASE_TYPE ) 1, semSEMAPHORE_QUEUE_ITEM_LENGTH ); \ + if( xSemaphore != NULL ) \ + { \ + xSemaphoreGive( xSemaphore ); \ + } \ + } + +/** + * semphr. h + *
xSemaphoreTake( 
+ *                   xSemaphoreHandle xSemaphore, 
+ *                   portTickType xBlockTime 
+ *               )
+ * + * Macro to obtain a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). + * + * @param xSemaphore A handle to the semaphore being taken - obtained when + * the semaphore was created. + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. A block + * time of portMAX_DELAY can be used to block indefinitely (provided + * INCLUDE_vTaskSuspend is set to 1 in FreeRTOSConfig.h). + * + * @return pdTRUE if the semaphore was obtained. pdFALSE + * if xBlockTime expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // A task that creates a semaphore.
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+ }
+
+ // A task that uses the semaphore.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xSemaphore != NULL )
+    {
+        // See if we can obtain the semaphore.  If the semaphore is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the semaphore and can now access the
+            // shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource.  Release the 
+            // semaphore.
+            xSemaphoreGive( xSemaphore );
+        }
+        else
+        {
+            // We could not obtain the semaphore and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTake xSemaphoreTake + * \ingroup Semaphores + */ +#define xSemaphoreTake( xSemaphore, xBlockTime ) xQueueGenericReceive( ( xQueueHandle ) xSemaphore, NULL, xBlockTime, pdFALSE ) + +/** + * semphr. h + * xSemaphoreTakeRecursive( + * xSemaphoreHandle xMutex, + * portTickType xBlockTime + * ) + * + * Macro to recursively obtain, or 'take', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being obtained. This is the + * handle returned by xSemaphoreCreateRecursiveMutex(); + * + * @param xBlockTime The time in ticks to wait for the semaphore to become + * available. The macro portTICK_RATE_MS can be used to convert this to a + * real time. A block time of zero can be used to poll the semaphore. If + * the task already owns the semaphore then xSemaphoreTakeRecursive() will + * return immediately no matter what the value of xBlockTime. + * + * @return pdTRUE if the semaphore was obtained. pdFALSE if xBlockTime + * expired without the semaphore becoming available. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xSemaphore, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, but instead buried in a more complex
+			// call structure.  This is just for illustrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive + * \ingroup Semaphores + */ +#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( xMutex, xBlockTime ) + + +/* + * xSemaphoreAltTake() is an alternative version of xSemaphoreTake(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltTake( xSemaphore, xBlockTime ) xQueueAltGenericReceive( ( xQueueHandle ) xSemaphore, NULL, xBlockTime, pdFALSE ) + +/** + * semphr. h + *
xSemaphoreGive( xSemaphoreHandle xSemaphore )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary(), xSemaphoreCreateMutex() or + * xSemaphoreCreateCounting(). and obtained using sSemaphoreTake(). + * + * This macro must not be used from an ISR. See xSemaphoreGiveFromISR () for + * an alternative which can be used from an ISR. + * + * This macro must also not be used on semaphores created using + * xSemaphoreCreateRecursiveMutex(). + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @return pdTRUE if the semaphore was released. pdFALSE if an error occurred. + * Semaphores are implemented using queues. An error can occur if there is + * no space on the queue to post a message - indicating that the + * semaphore was not first obtained correctly. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore = NULL;
+
+ void vATask( void * pvParameters )
+ {
+    // Create the semaphore to guard a shared resource.
+    vSemaphoreCreateBinary( xSemaphore );
+
+    if( xSemaphore != NULL )
+    {
+        if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+        {
+            // We would expect this call to fail because we cannot give
+            // a semaphore without first "taking" it!
+        }
+
+        // Obtain the semaphore - don't block if the semaphore is not
+        // immediately available.
+        if( xSemaphoreTake( xSemaphore, ( portTickType ) 0 ) )
+        {
+            // We now have the semaphore and can access the shared resource.
+
+            // ...
+
+            // We have finished accessing the shared resource so can free the
+            // semaphore.
+            if( xSemaphoreGive( xSemaphore ) != pdTRUE )
+            {
+                // We would not expect this call to fail because we must have
+                // obtained the semaphore to get here.
+            }
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGive xSemaphoreGive + * \ingroup Semaphores + */ +#define xSemaphoreGive( xSemaphore ) xQueueGenericSend( ( xQueueHandle ) xSemaphore, NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreGiveRecursive( xSemaphoreHandle xMutex )
+ * + * Macro to recursively release, or 'give', a mutex type semaphore. + * The mutex must have previously been created using a call to + * xSemaphoreCreateRecursiveMutex(); + * + * configUSE_RECURSIVE_MUTEXES must be set to 1 in FreeRTOSConfig.h for this + * macro to be available. + * + * This macro must not be used on mutexes created using xSemaphoreCreateMutex(). + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * @param xMutex A handle to the mutex being released, or 'given'. This is the + * handle returned by xSemaphoreCreateMutex(); + * + * @return pdTRUE if the semaphore was given. + * + * Example usage: +
+ xSemaphoreHandle xMutex = NULL;
+
+ // A task that creates a mutex.
+ void vATask( void * pvParameters )
+ {
+    // Create the mutex to guard a shared resource.
+    xMutex = xSemaphoreCreateRecursiveMutex();
+ }
+
+ // A task that uses the mutex.
+ void vAnotherTask( void * pvParameters )
+ {
+    // ... Do other things.
+
+    if( xMutex != NULL )
+    {
+        // See if we can obtain the mutex.  If the mutex is not available
+        // wait 10 ticks to see if it becomes free.	
+        if( xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 ) == pdTRUE )
+        {
+            // We were able to obtain the mutex and can now access the
+            // shared resource.
+
+            // ...
+            // For some reason due to the nature of the code further calls to 
+			// xSemaphoreTakeRecursive() are made on the same mutex.  In real
+			// code these would not be just sequential calls as this would make
+			// no sense.  Instead the calls are likely to be buried inside
+			// a more complex call structure.
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+            xSemaphoreTakeRecursive( xMutex, ( portTickType ) 10 );
+
+            // The mutex has now been 'taken' three times, so will not be 
+			// available to another task until it has also been given back
+			// three times.  Again it is unlikely that real code would have
+			// these calls sequentially, it would be more likely that the calls
+			// to xSemaphoreGiveRecursive() would be called as a call stack
+			// unwound.  This is just for demonstrative purposes.
+            xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+			xSemaphoreGiveRecursive( xMutex );
+
+			// Now the mutex can be taken by other tasks.
+        }
+        else
+        {
+            // We could not obtain the mutex and can therefore not access
+            // the shared resource safely.
+        }
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive + * \ingroup Semaphores + */ +#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( xMutex ) + +/* + * xSemaphoreAltGive() is an alternative version of xSemaphoreGive(). + * + * The source code that implements the alternative (Alt) API is much + * simpler because it executes everything from within a critical section. + * This is the approach taken by many other RTOSes, but FreeRTOS.org has the + * preferred fully featured API too. The fully featured API has more + * complex code that takes longer to execute, but makes much less use of + * critical sections. Therefore the alternative API sacrifices interrupt + * responsiveness to gain execution speed, whereas the fully featured API + * sacrifices execution speed to ensure better interrupt responsiveness. + */ +#define xSemaphoreAltGive( xSemaphore ) xQueueAltGenericSend( ( xQueueHandle ) xSemaphore, NULL, semGIVE_BLOCK_TIME, queueSEND_TO_BACK ) + +/** + * semphr. h + *
+ xSemaphoreGiveFromISR( 
+                          xSemaphoreHandle xSemaphore, 
+                          signed portBASE_TYPE *pxHigherPriorityTaskWoken
+                      )
+ * + * Macro to release a semaphore. The semaphore must have previously been + * created with a call to vSemaphoreCreateBinary() or xSemaphoreCreateCounting(). + * + * Mutex type semaphores (those created using a call to xSemaphoreCreateMutex()) + * must not be used with this macro. + * + * This macro can be used from an ISR. + * + * @param xSemaphore A handle to the semaphore being released. This is the + * handle returned when the semaphore was created. + * + * @param pxHigherPriorityTaskWoken xSemaphoreGiveFromISR() will set + * *pxHigherPriorityTaskWoken to pdTRUE if giving the semaphore caused a task + * to unblock, and the unblocked task has a priority higher than the currently + * running task. If xSemaphoreGiveFromISR() sets this value to pdTRUE then + * a context switch should be requested before the interrupt is exited. + * + * @return pdTRUE if the semaphore was successfully given, otherwise errQUEUE_FULL. + * + * Example usage: +
+ \#define LONG_TIME 0xffff
+ \#define TICKS_TO_WAIT	10
+ xSemaphoreHandle xSemaphore = NULL;
+
+ // Repetitive task.
+ void vATask( void * pvParameters )
+ {
+    for( ;; )
+    {
+        // We want this task to run every 10 ticks of a timer.  The semaphore 
+        // was created before this task was started.
+
+        // Block waiting for the semaphore to become available.
+        if( xSemaphoreTake( xSemaphore, LONG_TIME ) == pdTRUE )
+        {
+            // It is time to execute.
+
+            // ...
+
+            // We have finished our task.  Return to the top of the loop where
+            // we will block on the semaphore until it is time to execute 
+            // again.  Note when using the semaphore for synchronisation with an
+			// ISR in this manner there is no need to 'give' the semaphore back.
+        }
+    }
+ }
+
+ // Timer ISR
+ void vTimerISR( void * pvParameters )
+ {
+ static unsigned char ucLocalTickCount = 0;
+ static signed portBASE_TYPE xHigherPriorityTaskWoken;
+
+    // A timer tick has occurred.
+
+    // ... Do other time functions.
+
+    // Is it time for vATask () to run?
+	xHigherPriorityTaskWoken = pdFALSE;
+    ucLocalTickCount++;
+    if( ucLocalTickCount >= TICKS_TO_WAIT )
+    {
+        // Unblock the task by releasing the semaphore.
+        xSemaphoreGiveFromISR( xSemaphore, &xHigherPriorityTaskWoken );
+
+        // Reset the count so we release the semaphore again in 10 ticks time.
+        ucLocalTickCount = 0;
+    }
+
+    if( xHigherPriorityTaskWoken != pdFALSE )
+    {
+        // We can force a context switch here.  Context switching from an
+        // ISR uses port specific syntax.  Check the demo task for your port
+        // to find the syntax required.
+    }
+ }
+ 
+ * \defgroup xSemaphoreGiveFromISR xSemaphoreGiveFromISR + * \ingroup Semaphores + */ +#define xSemaphoreGiveFromISR( xSemaphore, pxHigherPriorityTaskWoken ) xQueueGenericSendFromISR( ( xQueueHandle ) xSemaphore, NULL, pxHigherPriorityTaskWoken, queueSEND_TO_BACK ) + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateMutex( void )
+ * + * Macro that implements a mutex semaphore by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the xSemaphoreTake() + * and xSemaphoreGive() macros. The xSemaphoreTakeRecursive() and + * xSemaphoreGiveRecursive() macros should not be used. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateMutex() xQueueCreateMutex() + + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateRecursiveMutex( void )
+ * + * Macro that implements a recursive mutex by using the existing queue + * mechanism. + * + * Mutexes created using this macro can be accessed using the + * xSemaphoreTakeRecursive() and xSemaphoreGiveRecursive() macros. The + * xSemaphoreTake() and xSemaphoreGive() macros should not be used. + * + * A mutex used recursively can be 'taken' repeatedly by the owner. The mutex + * doesn't become available again until the owner has called + * xSemaphoreGiveRecursive() for each successful 'take' request. For example, + * if a task successfully 'takes' the same mutex 5 times then the mutex will + * not be available to any other task until it has also 'given' the mutex back + * exactly five times. + * + * This type of semaphore uses a priority inheritance mechanism so a task + * 'taking' a semaphore MUST ALWAYS 'give' the semaphore back once the + * semaphore it is no longer required. + * + * Mutex type semaphores cannot be used from within interrupt service routines. + * + * See vSemaphoreCreateBinary() for an alternative implementation that can be + * used for pure synchronisation (where one task or interrupt always 'gives' the + * semaphore and another always 'takes' the semaphore) and from within interrupt + * service routines. + * + * @return xSemaphore Handle to the created mutex semaphore. Should be of type + * xSemaphoreHandle. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+    // Semaphore cannot be used before a call to xSemaphoreCreateMutex().
+    // This is a macro so pass the variable in directly.
+    xSemaphore = xSemaphoreCreateRecursiveMutex();
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup vSemaphoreCreateMutex vSemaphoreCreateMutex + * \ingroup Semaphores + */ +#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex() + +/** + * semphr. h + *
xSemaphoreHandle xSemaphoreCreateCounting( unsigned portBASE_TYPE uxMaxCount, unsigned portBASE_TYPE uxInitialCount )
+ * + * Macro that creates a counting semaphore by using the existing + * queue mechanism. + * + * Counting semaphores are typically used for two things: + * + * 1) Counting events. + * + * In this usage scenario an event handler will 'give' a semaphore each time + * an event occurs (incrementing the semaphore count value), and a handler + * task will 'take' a semaphore each time it processes an event + * (decrementing the semaphore count value). The count value is therefore + * the difference between the number of events that have occurred and the + * number that have been processed. In this case it is desirable for the + * initial count value to be zero. + * + * 2) Resource management. + * + * In this usage scenario the count value indicates the number of resources + * available. To obtain control of a resource a task must first obtain a + * semaphore - decrementing the semaphore count value. When the count value + * reaches zero there are no free resources. When a task finishes with the + * resource it 'gives' the semaphore back - incrementing the semaphore count + * value. In this case it is desirable for the initial count value to be + * equal to the maximum count value, indicating that all resources are free. + * + * @param uxMaxCount The maximum count value that can be reached. When the + * semaphore reaches this value it can no longer be 'given'. + * + * @param uxInitialCount The count value assigned to the semaphore when it is + * created. + * + * @return Handle to the created semaphore. Null if the semaphore could not be + * created. + * + * Example usage: +
+ xSemaphoreHandle xSemaphore;
+
+ void vATask( void * pvParameters )
+ {
+ xSemaphoreHandle xSemaphore = NULL;
+
+    // Semaphore cannot be used before a call to xSemaphoreCreateCounting().
+    // The max value to which the semaphore can count should be 10, and the
+    // initial value assigned to the count should be 0.
+    xSemaphore = xSemaphoreCreateCounting( 10, 0 );
+
+    if( xSemaphore != NULL )
+    {
+        // The semaphore was created successfully.
+        // The semaphore can now be used.  
+    }
+ }
+ 
+ * \defgroup xSemaphoreCreateCounting xSemaphoreCreateCounting + * \ingroup Semaphores + */ +#define xSemaphoreCreateCounting( uxMaxCount, uxInitialCount ) xQueueCreateCountingSemaphore( uxMaxCount, uxInitialCount ) + + +#endif /* SEMAPHORE_H */ + + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/task.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/task.h index df059e001..6a0c53250 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/task.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/include/task.h @@ -1,1263 +1,1263 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef INC_FREERTOS_H - #error "#include FreeRTOS.h" must appear in source files before "#include task.h" -#endif - - - -#ifndef TASK_H -#define TASK_H - -#include "portable.h" -#include "list.h" - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * MACROS AND DEFINITIONS - *----------------------------------------------------------*/ - -#define tskKERNEL_VERSION_NUMBER "V6.0.4" - -/** - * task. h - * - * Type by which tasks are referenced. For example, a call to xTaskCreate - * returns (via a pointer parameter) an xTaskHandle variable that can then - * be used as a parameter to vTaskDelete to delete the task. - * - * \page xTaskHandle xTaskHandle - * \ingroup Tasks - */ -typedef void * xTaskHandle; - -/* - * Used internally only. - */ -typedef struct xTIME_OUT -{ - portBASE_TYPE xOverflowCount; - portTickType xTimeOnEntering; -} xTimeOutType; - -/* - * Defines the memory ranges allocated to the task when an MPU is used. - */ -typedef struct xMEMORY_REGION -{ - void *pvBaseAddress; - unsigned long ulLengthInBytes; - unsigned long ulParameters; -} xMemoryRegion; - -/* - * Parameters required to create an MPU protected task. - */ -typedef struct xTASK_PARAMTERS -{ - pdTASK_CODE pvTaskCode; - const signed char * const pcName; - unsigned short usStackDepth; - void *pvParameters; - unsigned portBASE_TYPE uxPriority; - portSTACK_TYPE *puxStackBuffer; - xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; -} xTaskParameters; - -/* - * Defines the priority used by the idle task. This must not be modified. - * - * \ingroup TaskUtils - */ -#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0 ) - -/** - * task. h - * - * Macro for forcing a context switch. - * - * \page taskYIELD taskYIELD - * \ingroup SchedulerControl - */ -#define taskYIELD() portYIELD() - -/** - * task. h - * - * Macro to mark the start of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskENTER_CRITICAL taskENTER_CRITICAL - * \ingroup SchedulerControl - */ -#define taskENTER_CRITICAL() portENTER_CRITICAL() - -/** - * task. h - * - * Macro to mark the end of a critical code region. Preemptive context - * switches cannot occur when in a critical region. - * - * NOTE: This may alter the stack (depending on the portable implementation) - * so must be used with care! - * - * \page taskEXIT_CRITICAL taskEXIT_CRITICAL - * \ingroup SchedulerControl - */ -#define taskEXIT_CRITICAL() portEXIT_CRITICAL() - -/** - * task. h - * - * Macro to disable all maskable interrupts. - * - * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() - -/** - * task. h - * - * Macro to enable microcontroller interrupts. - * - * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS - * \ingroup SchedulerControl - */ -#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() - -/* Definitions returned by xTaskGetSchedulerState(). */ -#define taskSCHEDULER_NOT_STARTED 0 -#define taskSCHEDULER_RUNNING 1 -#define taskSCHEDULER_SUSPENDED 2 - -/*----------------------------------------------------------- - * TASK CREATION API - *----------------------------------------------------------*/ - -/** - * task. h - *
- portBASE_TYPE xTaskCreate(
-							  pdTASK_CODE pvTaskCode,
-							  const char * const pcName,
-							  unsigned short usStackDepth,
-							  void *pvParameters,
-							  unsigned portBASE_TYPE uxPriority,
-							  xTaskHandle *pvCreatedTask
-						  );
- * - * Create a new task and add it to the list of tasks that are ready to run. - * - * xTaskCreate() can only be used to create a task that has unrestricted - * access to the entire microcontroller memory map. Systems that include MPU - * support can alternatively create an MPU constrained task using - * xTaskCreateRestricted(). - * - * @param pvTaskCode Pointer to the task entry function. Tasks - * must be implemented to never return (i.e. continuous loop). - * - * @param pcName A descriptive name for the task. This is mainly used to - * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default - * is 16. - * - * @param usStackDepth The size of the task stack specified as the number of - * variables the stack can hold - not the number of bytes. For example, if - * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes - * will be allocated for stack storage. - * - * @param pvParameters Pointer that will be used as the parameter for the task - * being created. - * - * @param uxPriority The priority at which the task should run. Systems that - * include MPU support can optionally create tasks in a privileged (system) - * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For - * example, to create a privileged task at priority 2 the uxPriority parameter - * should be set to ( 2 | portPRIVILEGE_BIT ). - * - * @param pvCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
- // Task to be created.
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-	 }
- }
-
- // Function that creates a task.
- void vOtherFunction( void )
- {
- static unsigned char ucParameterToPass;
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
-	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
-	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
-	 // the new task attempts to access it.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup xTaskCreate xTaskCreate - * \ingroup Tasks - */ -#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) - -/** - * task. h - *
- portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
- * - * xTaskCreateRestricted() should only be used in systems that include an MPU - * implementation. - * - * Create a new task and add it to the list of tasks that are ready to run. - * The function parameters define the memory regions and associated access - * permissions allocated to the task. - * - * @param pxTaskDefinition Pointer to a structure that contains a member - * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API - * documentation) plus an optional stack buffer and the memory region - * definitions. - * - * @param pxCreatedTask Used to pass back a handle by which the created task - * can be referenced. - * - * @return pdPASS if the task was successfully created and added to a ready - * list, otherwise an error code defined in the file errors. h - * - * Example usage: -
-// Create an xTaskParameters structure that defines the task to be created.
-static const xTaskParameters xCheckTaskParameters =
-{
-	vATask,		// pvTaskCode - the function that implements the task.
-	"ATask",	// pcName - just a text name for the task to assist debugging.
-	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
-	NULL,		// pvParameters - passed into the task function as the function parameters.
-	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
-	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
-
-	// xRegions - Allocate up to three separate memory regions for access by
-	// the task, with appropriate access permissions.  Different processors have
-	// different memory alignment requirements - refer to the FreeRTOS documentation
-	// for full information.
-	{											
-		// Base address					Length	Parameters
-        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
-        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
-        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
-	}
-};
-
-int main( void )
-{
-xTaskHandle xHandle;
-
-	// Create a task from the const structure defined above.  The task handle
-	// is requested (the second parameter is not NULL) but in this case just for
-	// demonstration purposes as its not actually used.
-	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
-
-	// Start the scheduler.
-	vTaskStartScheduler();
-
-	// Will only get here if there was insufficient memory to create the idle
-	// task.
-	for( ;; );
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) - -/** - * task. h - *
- void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
- * - * Memory regions are assigned to a restricted task when the task is created by - * a call to xTaskCreateRestricted(). These regions can be redefined using - * vTaskAllocateMPURegions(). - * - * @param xTask The handle of the task being updated. - * - * @param xRegions A pointer to an xMemoryRegion structure that contains the - * new memory region definitions. - * - * Example usage: -
-// Define an array of xMemoryRegion structures that configures an MPU region
-// allowing read/write access for 1024 bytes starting at the beginning of the
-// ucOneKByte array.  The other two of the maximum 3 definable regions are
-// unused so set to zero.
-static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
-{											
-	// Base address		Length		Parameters
-	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
-	{ 0,				0,			0 },
-	{ 0,				0,			0 }
-};
-
-void vATask( void *pvParameters )
-{
-	// This task was created such that it has access to certain regions of
-	// memory as defined by the MPU configuration.  At some point it is 
-	// desired that these MPU regions are replaced with that defined in the
-	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
-	// for this purpose.  NULL is used as the task handle to indicate that this
-	// function should modify the MPU regions of the calling task.
-	vTaskAllocateMPURegions( NULL, xAltRegions );
-	
-	// Now the task can continue its function, but from this point on can only
-	// access its stack and the ucOneKByte array (unless any other statically
-	// defined or shared regions have been declared elsewhere).
-}
-   
- * \defgroup xTaskCreateRestricted xTaskCreateRestricted - * \ingroup Tasks - */ -void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelete( xTaskHandle pxTask );
- * - * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Remove a task from the RTOS real time kernels management. The task being - * deleted will be removed from all ready, blocked, suspended and event lists. - * - * NOTE: The idle task is responsible for freeing the kernel allocated - * memory from tasks that have been deleted. It is therefore important that - * the idle task is not starved of microcontroller processing time if your - * application makes any calls to vTaskDelete (). Memory allocated by the - * task code is not automatically freed, and should be freed before the task - * is deleted. - * - * See the demo application file death.c for sample code that utilises - * vTaskDelete (). - * - * @param pxTask The handle of the task to be deleted. Passing NULL will - * cause the calling task to be deleted. - * - * Example usage: -
- void vOtherFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create the task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // Use the handle to delete the task.
-	 vTaskDelete( xHandle );
- }
-   
- * \defgroup vTaskDelete vTaskDelete - * \ingroup Tasks - */ -void vTaskDelete( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; - - -/*----------------------------------------------------------- - * TASK CONTROL API - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskDelay( portTickType xTicksToDelay );
- * - * Delay a task for a given number of ticks. The actual time that the - * task remains blocked depends on the tick rate. The constant - * portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * - * vTaskDelay() specifies a time at which the task wishes to unblock relative to - * the time at which vTaskDelay() is called. For example, specifying a block - * period of 100 ticks will cause the task to unblock 100 ticks after - * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method - * of controlling the frequency of a cyclical task as the path taken through the - * code, as well as other task and interrupt activity, will effect the frequency - * at which vTaskDelay() gets called and therefore the time at which the task - * next executes. See vTaskDelayUntil() for an alternative API function designed - * to facilitate fixed frequency execution. It does this by specifying an - * absolute time (rather than a relative time) at which the calling task should - * unblock. - * - * @param xTicksToDelay The amount of time, in tick periods, that - * the calling task should block. - * - * Example usage: - - void vTaskFunction( void * pvParameters ) - { - void vTaskFunction( void * pvParameters ) - { - // Block for 500ms. - const portTickType xDelay = 500 / portTICK_RATE_MS; - - for( ;; ) - { - // Simply toggle the LED every 500ms, blocking between each toggle. - vToggleLED(); - vTaskDelay( xDelay ); - } - } - - * \defgroup vTaskDelay vTaskDelay - * \ingroup TaskCtrl - */ -void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
- * - * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Delay a task until a specified time. This function can be used by cyclical - * tasks to ensure a constant execution frequency. - * - * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will - * cause a task to block for the specified number of ticks from the time vTaskDelay () is - * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed - * execution frequency as the time between a task starting to execute and that task - * calling vTaskDelay () may not be fixed [the task may take a different path though the - * code between calls, or may get interrupted or preempted a different number of times - * each time it executes]. - * - * Whereas vTaskDelay () specifies a wake time relative to the time at which the function - * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to - * unblock. - * - * The constant portTICK_RATE_MS can be used to calculate real time from the tick - * rate - with the resolution of one tick period. - * - * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the - * task was last unblocked. The variable must be initialised with the current time - * prior to its first use (see the example below). Following this the variable is - * automatically updated within vTaskDelayUntil (). - * - * @param xTimeIncrement The cycle time period. The task will be unblocked at - * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the - * same xTimeIncrement parameter value will cause the task to execute with - * a fixed interface period. - * - * Example usage: -
- // Perform an action every 10 ticks.
- void vTaskFunction( void * pvParameters )
- {
- portTickType xLastWakeTime;
- const portTickType xFrequency = 10;
-
-	 // Initialise the xLastWakeTime variable with the current time.
-	 xLastWakeTime = xTaskGetTickCount ();
-	 for( ;; )
-	 {
-		 // Wait for the next cycle.
-		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
-
-		 // Perform action here.
-	 }
- }
-   
- * \defgroup vTaskDelayUntil vTaskDelayUntil - * \ingroup TaskCtrl - */ -void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
- * - * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Obtain the priority of any task. - * - * @param pxTask Handle of the task to be queried. Passing a NULL - * handle results in the priority of the calling task being returned. - * - * @return The priority of pxTask. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to obtain the priority of the created task.
-	 // It was created with tskIDLE_PRIORITY, but may have changed
-	 // it itself.
-	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
-	 {
-		 // The task has changed it's priority.
-	 }
-
-	 // ...
-
-	 // Is our priority higher than the created task?
-	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
-	 {
-		 // Our priority (obtained using NULL handle) is higher.
-	 }
- }
-   
- * \defgroup uxTaskPriorityGet uxTaskPriorityGet - * \ingroup TaskCtrl - */ -unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
- * - * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Set the priority of any task. - * - * A context switch will occur before the function returns if the priority - * being set is higher than the currently executing task. - * - * @param pxTask Handle to the task for which the priority is being set. - * Passing a NULL handle results in the priority of the calling task being set. - * - * @param uxNewPriority The priority to which the task will be set. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to raise the priority of the created task.
-	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
-
-	 // ...
-
-	 // Use a NULL handle to raise our priority to the same value.
-	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
- }
-   
- * \defgroup vTaskPrioritySet vTaskPrioritySet - * \ingroup TaskCtrl - */ -void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Suspend any task. When suspended a task will never get any microcontroller - * processing time, no matter what its priority. - * - * Calls to vTaskSuspend are not accumulative - - * i.e. calling vTaskSuspend () twice on the same task still only requires one - * call to vTaskResume () to ready the suspended task. - * - * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL - * handle will cause the calling task to be suspended. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Suspend ourselves.
-	 vTaskSuspend( NULL );
-
-	 // We cannot get here unless another task calls vTaskResume
-	 // with our handle as the parameter.
- }
-   
- * \defgroup vTaskSuspend vTaskSuspend - * \ingroup TaskCtrl - */ -void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskResume( xTaskHandle pxTaskToResume );
- * - * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. - * See the configuration section for more information. - * - * Resumes a suspended task. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * vTaskResume (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * Example usage: -
- void vAFunction( void )
- {
- xTaskHandle xHandle;
-
-	 // Create a task, storing the handle.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
-
-	 // ...
-
-	 // Use the handle to suspend the created task.
-	 vTaskSuspend( xHandle );
-
-	 // ...
-
-	 // The created task will not run during this period, unless
-	 // another task calls vTaskResume( xHandle ).
-
-	 //...
-
-
-	 // Resume the suspended task ourselves.
-	 vTaskResume( xHandle );
-
-	 // The created task will once again get microcontroller processing
-	 // time in accordance with it priority within the system.
- }
-   
- * \defgroup vTaskResume vTaskResume - * \ingroup TaskCtrl - */ -void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
- * - * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * An implementation of vTaskResume() that can be called from within an ISR. - * - * A task that has been suspended by one of more calls to vTaskSuspend () - * will be made available for running again by a single call to - * xTaskResumeFromISR (). - * - * @param pxTaskToResume Handle to the task being readied. - * - * \defgroup vTaskResumeFromISR vTaskResumeFromISR - * \ingroup TaskCtrl - */ -portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * SCHEDULER CONTROL - *----------------------------------------------------------*/ - -/** - * task. h - *
void vTaskStartScheduler( void );
- * - * Starts the real time kernel tick processing. After calling the kernel - * has control over which tasks are executed and when. This function - * does not return until an executing task calls vTaskEndScheduler (). - * - * At least one task should be created via a call to xTaskCreate () - * before calling vTaskStartScheduler (). The idle task is created - * automatically when the first application task is created. - * - * See the demo application file main.c for an example of creating - * tasks and starting the kernel. - * - * Example usage: -
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will not get here unless a task calls vTaskEndScheduler ()
- }
-   
- * - * \defgroup vTaskStartScheduler vTaskStartScheduler - * \ingroup SchedulerControl - */ -void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskEndScheduler( void );
- * - * Stops the real time kernel tick. All created tasks will be automatically - * deleted and multitasking (either preemptive or cooperative) will - * stop. Execution then resumes from the point where vTaskStartScheduler () - * was called, as if vTaskStartScheduler () had just returned. - * - * See the demo application file main. c in the demo/PC directory for an - * example that uses vTaskEndScheduler (). - * - * vTaskEndScheduler () requires an exit function to be defined within the - * portable layer (see vPortEndScheduler () in port. c for the PC port). This - * performs hardware specific operations such as stopping the kernel tick. - * - * vTaskEndScheduler () will cause all of the resources allocated by the - * kernel to be freed - but will not free resources allocated by application - * tasks. - * - * Example usage: -
- void vTaskCode( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // At some point we want to end the real time kernel processing
-		 // so call ...
-		 vTaskEndScheduler ();
-	 }
- }
-
- void vAFunction( void )
- {
-	 // Create at least one task before starting the kernel.
-	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
-
-	 // Start the real time kernel with preemption.
-	 vTaskStartScheduler ();
-
-	 // Will only get here when the vTaskCode () task has called
-	 // vTaskEndScheduler ().  When we get here we are back to single task
-	 // execution.
- }
-   
- * - * \defgroup vTaskEndScheduler vTaskEndScheduler - * \ingroup SchedulerControl - */ -void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskSuspendAll( void );
- * - * Suspends all real time kernel activity while keeping interrupts (including the - * kernel tick) enabled. - * - * After calling vTaskSuspendAll () the calling task will continue to execute - * without risk of being swapped out until a call to xTaskResumeAll () has been - * made. - * - * API functions that have the potential to cause a context switch (for example, - * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler - * is suspended. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the kernel
-		 // tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.
-		 xTaskResumeAll ();
-	 }
- }
-   
- * \defgroup vTaskSuspendAll vTaskSuspendAll - * \ingroup SchedulerControl - */ -void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
char xTaskResumeAll( void );
- * - * Resumes real time kernel activity following a call to vTaskSuspendAll (). - * After a call to vTaskSuspendAll () the kernel will take control of which - * task is executing at any time. - * - * @return If resuming the scheduler caused a context switch then pdTRUE is - * returned, otherwise pdFALSE is returned. - * - * Example usage: -
- void vTask1( void * pvParameters )
- {
-	 for( ;; )
-	 {
-		 // Task code goes here.
-
-		 // ...
-
-		 // At some point the task wants to perform a long operation during
-		 // which it does not want to get swapped out.  It cannot use
-		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
-		 // operation may cause interrupts to be missed - including the
-		 // ticks.
-
-		 // Prevent the real time kernel swapping out the task.
-		 vTaskSuspendAll ();
-
-		 // Perform the operation here.  There is no need to use critical
-		 // sections as we have all the microcontroller processing time.
-		 // During this time interrupts will still operate and the real
-		 // time kernel tick count will be maintained.
-
-		 // ...
-
-		 // The operation is complete.  Restart the kernel.  We want to force
-		 // a context switch - but there is no point if resuming the scheduler
-		 // caused a context switch already.
-		 if( !xTaskResumeAll () )
-		 {
-			  taskYIELD ();
-		 }
-	 }
- }
-   
- * \defgroup xTaskResumeAll xTaskResumeAll - * \ingroup SchedulerControl - */ -signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
- * - * Utility task that simply returns pdTRUE if the task referenced by xTask is - * currently in the Suspended state, or pdFALSE if the task referenced by xTask - * is in any other state. - * - */ -signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/*----------------------------------------------------------- - * TASK UTILITIES - *----------------------------------------------------------*/ - -/** - * task. h - *
volatile portTickType xTaskGetTickCount( void );
- * - * @return The count of ticks since vTaskStartScheduler was called. - * - * \page xTaskGetTickCount xTaskGetTickCount - * \ingroup TaskUtils - */ -portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned short uxTaskGetNumberOfTasks( void );
- * - * @return The number of tasks that the real time kernel is currently managing. - * This includes all ready, blocked and suspended tasks. A task that - * has been deleted but not yet freed by the idle task will also be - * included in the count. - * - * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks - * \ingroup TaskUtils - */ -unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskList( char *pcWriteBuffer );
- * - * configUSE_TRACE_FACILITY must be defined as 1 for this function to be - * available. See the configuration section for more information. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Lists all the current tasks, along with their current state and stack - * usage high water mark. - * - * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or - * suspended ('S'). - * - * @param pcWriteBuffer A buffer into which the above mentioned details - * will be written, in ascii form. This buffer is assumed to be large - * enough to contain the generated report. Approximately 40 bytes per - * task should be sufficient. - * - * \page vTaskList vTaskList - * \ingroup TaskUtils - */ -void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
- * - * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function - * to be available. The application must also then provide definitions - * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and - * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter - * and return the timers current count value respectively. The counter - * should be at least 10 times the frequency of the tick count. - * - * NOTE: This function will disable interrupts for its duration. It is - * not intended for normal application runtime use but as a debug aid. - * - * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total - * accumulated execution time being stored for each task. The resolution - * of the accumulated time value depends on the frequency of the timer - * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. - * Calling vTaskGetRunTimeStats() writes the total execution time of each - * task into a buffer, both as an absolute count value and as a percentage - * of the total system execution time. - * - * @param pcWriteBuffer A buffer into which the execution times will be - * written, in ascii form. This buffer is assumed to be large enough to - * contain the generated report. Approximately 40 bytes per task should - * be sufficient. - * - * \page vTaskGetRunTimeStats vTaskGetRunTimeStats - * \ingroup TaskUtils - */ -void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
void vTaskStartTrace( char * pcBuffer, unsigned portBASE_TYPE uxBufferSize );
- * - * Starts a real time kernel activity trace. The trace logs the identity of - * which task is running when. - * - * The trace file is stored in binary format. A separate DOS utility called - * convtrce.exe is used to convert this into a tab delimited text file which - * can be viewed and plotted in a spread sheet. - * - * @param pcBuffer The buffer into which the trace will be written. - * - * @param ulBufferSize The size of pcBuffer in bytes. The trace will continue - * until either the buffer in full, or ulTaskEndTrace () is called. - * - * \page vTaskStartTrace vTaskStartTrace - * \ingroup TaskUtils - */ -void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) PRIVILEGED_FUNCTION; - -/** - * task. h - *
unsigned long ulTaskEndTrace( void );
- * - * Stops a kernel activity trace. See vTaskStartTrace (). - * - * @return The number of bytes that have been written into the trace buffer. - * - * \page usTaskEndTrace usTaskEndTrace - * \ingroup TaskUtils - */ -unsigned long ulTaskEndTrace( void ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
- * - * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for - * this function to be available. - * - * Returns the high water mark of the stack associated with xTask. That is, - * the minimum free stack space there has been (in bytes) since the task - * started. The smaller the returned number the closer the task has come - * to overflowing its stack. - * - * @param xTask Handle of the task associated with the stack to be checked. - * Set xTask to NULL to check the stack of the calling task. - * - * @return The smallest amount of free stack space there has been (in bytes) - * since the task referenced by xTask was created. - */ -unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Sets pxHookFunction to be the task hook function used by the task xTask. - * Passing xTask as NULL has the effect of setting the calling tasks hook - * function. - */ -void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
- * - * Returns the pxHookFunction value assigned to the task xTask. - */ -pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; - -/** - * task.h - *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
- * - * Calls the hook function associated with xTask. Passing xTask as NULL has - * the effect of calling the Running tasks (the calling task) hook function. - * - * pvParameter is passed to the hook function for the task to interpret as it - * wants. - */ -portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; - - -/*----------------------------------------------------------- - * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES - *----------------------------------------------------------*/ - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Called from the real time kernel tick (either preemptive or cooperative), - * this increments the tick count and checks if any tasks that are blocked - * for a finite period required removing from a blocked list and placing on - * a ready list. - */ -void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes the calling task from the ready list and places it both - * on the list of tasks waiting for a particular event, and the - * list of delayed tasks. The task will be removed from both lists - * and replaced on the ready list should either the event occur (and - * there be no higher priority tasks waiting on the same event) or - * the delay period expires. - * - * @param pxEventList The list containing tasks that are blocked waiting - * for the event to occur. - * - * @param xTicksToWait The maximum amount of time that the task should wait - * for the event to occur. This is specified in kernel ticks,the constant - * portTICK_RATE_MS can be used to convert kernel ticks into a real time - * period. - */ -void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. - * - * Removes a task from both the specified event list and the list of blocked - * tasks, and places it on a ready queue. - * - * xTaskRemoveFromEventList () will be called if either an event occurs to - * unblock a task, or the block timeout period expires. - * - * @return pdTRUE if the task being removed has a higher priority than the task - * making the call, otherwise pdFALSE. - */ -signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN - * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * INCLUDE_vTaskCleanUpResources and INCLUDE_vTaskSuspend must be defined as 1 - * for this function to be available. - * See the configuration section for more information. - * - * Empties the ready and delayed queues of task control blocks, freeing the - * memory allocated for the task control block and task stacks as it goes. - */ -void vTaskCleanUpResources( void ) PRIVILEGED_FUNCTION; - -/* - * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY - * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS - * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. - * - * Sets the pointer to the current TCB to the TCB of the highest priority task - * that is ready to run. - */ -void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; - -/* - * Return the handle of the calling task. - */ -xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; - -/* - * Capture the current time status for future reference. - */ -void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; - -/* - * Compare the time status now with that previously captured to see if the - * timeout has expired. - */ -portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; - -/* - * Shortcut used by the queue implementation to prevent unnecessary call to - * taskYIELD(); - */ -void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; - -/* - * Returns the scheduler state as taskSCHEDULER_RUNNING, - * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. - */ -portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; - -/* - * Raises the priority of the mutex holder to that of the calling task should - * the mutex holder have a priority less than the calling task. - */ -void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Set the priority of a task back to its proper priority in the case that it - * inherited a higher priority while it was holding a semaphore. - */ -void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; - -/* - * Generic version of the task creation function which is in turn called by the - * xTaskCreate() and xTaskCreateRestricted() macros. - */ -signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pvTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; - -#ifdef __cplusplus -} -#endif -#endif /* TASK_H */ - - - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef INC_FREERTOS_H + #error "#include FreeRTOS.h" must appear in source files before "#include task.h" +#endif + + + +#ifndef TASK_H +#define TASK_H + +#include "portable.h" +#include "list.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * MACROS AND DEFINITIONS + *----------------------------------------------------------*/ + +#define tskKERNEL_VERSION_NUMBER "V6.0.4" + +/** + * task. h + * + * Type by which tasks are referenced. For example, a call to xTaskCreate + * returns (via a pointer parameter) an xTaskHandle variable that can then + * be used as a parameter to vTaskDelete to delete the task. + * + * \page xTaskHandle xTaskHandle + * \ingroup Tasks + */ +typedef void * xTaskHandle; + +/* + * Used internally only. + */ +typedef struct xTIME_OUT +{ + portBASE_TYPE xOverflowCount; + portTickType xTimeOnEntering; +} xTimeOutType; + +/* + * Defines the memory ranges allocated to the task when an MPU is used. + */ +typedef struct xMEMORY_REGION +{ + void *pvBaseAddress; + unsigned long ulLengthInBytes; + unsigned long ulParameters; +} xMemoryRegion; + +/* + * Parameters required to create an MPU protected task. + */ +typedef struct xTASK_PARAMTERS +{ + pdTASK_CODE pvTaskCode; + const signed char * const pcName; + unsigned short usStackDepth; + void *pvParameters; + unsigned portBASE_TYPE uxPriority; + portSTACK_TYPE *puxStackBuffer; + xMemoryRegion xRegions[ portNUM_CONFIGURABLE_REGIONS ]; +} xTaskParameters; + +/* + * Defines the priority used by the idle task. This must not be modified. + * + * \ingroup TaskUtils + */ +#define tskIDLE_PRIORITY ( ( unsigned portBASE_TYPE ) 0 ) + +/** + * task. h + * + * Macro for forcing a context switch. + * + * \page taskYIELD taskYIELD + * \ingroup SchedulerControl + */ +#define taskYIELD() portYIELD() + +/** + * task. h + * + * Macro to mark the start of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskENTER_CRITICAL taskENTER_CRITICAL + * \ingroup SchedulerControl + */ +#define taskENTER_CRITICAL() portENTER_CRITICAL() + +/** + * task. h + * + * Macro to mark the end of a critical code region. Preemptive context + * switches cannot occur when in a critical region. + * + * NOTE: This may alter the stack (depending on the portable implementation) + * so must be used with care! + * + * \page taskEXIT_CRITICAL taskEXIT_CRITICAL + * \ingroup SchedulerControl + */ +#define taskEXIT_CRITICAL() portEXIT_CRITICAL() + +/** + * task. h + * + * Macro to disable all maskable interrupts. + * + * \page taskDISABLE_INTERRUPTS taskDISABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskDISABLE_INTERRUPTS() portDISABLE_INTERRUPTS() + +/** + * task. h + * + * Macro to enable microcontroller interrupts. + * + * \page taskENABLE_INTERRUPTS taskENABLE_INTERRUPTS + * \ingroup SchedulerControl + */ +#define taskENABLE_INTERRUPTS() portENABLE_INTERRUPTS() + +/* Definitions returned by xTaskGetSchedulerState(). */ +#define taskSCHEDULER_NOT_STARTED 0 +#define taskSCHEDULER_RUNNING 1 +#define taskSCHEDULER_SUSPENDED 2 + +/*----------------------------------------------------------- + * TASK CREATION API + *----------------------------------------------------------*/ + +/** + * task. h + *
+ portBASE_TYPE xTaskCreate(
+							  pdTASK_CODE pvTaskCode,
+							  const char * const pcName,
+							  unsigned short usStackDepth,
+							  void *pvParameters,
+							  unsigned portBASE_TYPE uxPriority,
+							  xTaskHandle *pvCreatedTask
+						  );
+ * + * Create a new task and add it to the list of tasks that are ready to run. + * + * xTaskCreate() can only be used to create a task that has unrestricted + * access to the entire microcontroller memory map. Systems that include MPU + * support can alternatively create an MPU constrained task using + * xTaskCreateRestricted(). + * + * @param pvTaskCode Pointer to the task entry function. Tasks + * must be implemented to never return (i.e. continuous loop). + * + * @param pcName A descriptive name for the task. This is mainly used to + * facilitate debugging. Max length defined by tskMAX_TASK_NAME_LEN - default + * is 16. + * + * @param usStackDepth The size of the task stack specified as the number of + * variables the stack can hold - not the number of bytes. For example, if + * the stack is 16 bits wide and usStackDepth is defined as 100, 200 bytes + * will be allocated for stack storage. + * + * @param pvParameters Pointer that will be used as the parameter for the task + * being created. + * + * @param uxPriority The priority at which the task should run. Systems that + * include MPU support can optionally create tasks in a privileged (system) + * mode by setting bit portPRIVILEGE_BIT of the priority parameter. For + * example, to create a privileged task at priority 2 the uxPriority parameter + * should be set to ( 2 | portPRIVILEGE_BIT ). + * + * @param pvCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+ // Task to be created.
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+	 }
+ }
+
+ // Function that creates a task.
+ void vOtherFunction( void )
+ {
+ static unsigned char ucParameterToPass;
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.  Note that the passed parameter ucParameterToPass
+	 // must exist for the lifetime of the task, so in this case is declared static.  If it was just an
+	 // an automatic stack variable it might no longer exist, or at least have been corrupted, by the time
+	 // the new task attempts to access it.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, &ucParameterToPass, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup xTaskCreate xTaskCreate + * \ingroup Tasks + */ +#define xTaskCreate( pvTaskCode, pcName, usStackDepth, pvParameters, uxPriority, pxCreatedTask ) xTaskGenericCreate( ( pvTaskCode ), ( pcName ), ( usStackDepth ), ( pvParameters ), ( uxPriority ), ( pxCreatedTask ), ( NULL ), ( NULL ) ) + +/** + * task. h + *
+ portBASE_TYPE xTaskCreateRestricted( xTaskParameters *pxTaskDefinition, xTaskHandle *pxCreatedTask );
+ * + * xTaskCreateRestricted() should only be used in systems that include an MPU + * implementation. + * + * Create a new task and add it to the list of tasks that are ready to run. + * The function parameters define the memory regions and associated access + * permissions allocated to the task. + * + * @param pxTaskDefinition Pointer to a structure that contains a member + * for each of the normal xTaskCreate() parameters (see the xTaskCreate() API + * documentation) plus an optional stack buffer and the memory region + * definitions. + * + * @param pxCreatedTask Used to pass back a handle by which the created task + * can be referenced. + * + * @return pdPASS if the task was successfully created and added to a ready + * list, otherwise an error code defined in the file errors. h + * + * Example usage: +
+// Create an xTaskParameters structure that defines the task to be created.
+static const xTaskParameters xCheckTaskParameters =
+{
+	vATask,		// pvTaskCode - the function that implements the task.
+	"ATask",	// pcName - just a text name for the task to assist debugging.
+	100,		// usStackDepth	- the stack size DEFINED IN WORDS.
+	NULL,		// pvParameters - passed into the task function as the function parameters.
+	( 1UL | portPRIVILEGE_BIT ),// uxPriority - task priority, set the portPRIVILEGE_BIT if the task should run in a privileged state.
+	cStackBuffer,// puxStackBuffer - the buffer to be used as the task stack.
+
+	// xRegions - Allocate up to three separate memory regions for access by
+	// the task, with appropriate access permissions.  Different processors have
+	// different memory alignment requirements - refer to the FreeRTOS documentation
+	// for full information.
+	{											
+		// Base address					Length	Parameters
+        { cReadWriteArray,				32,		portMPU_REGION_READ_WRITE },
+        { cReadOnlyArray,				32,		portMPU_REGION_READ_ONLY },
+        { cPrivilegedOnlyAccessArray,	128,	portMPU_REGION_PRIVILEGED_READ_WRITE }
+	}
+};
+
+int main( void )
+{
+xTaskHandle xHandle;
+
+	// Create a task from the const structure defined above.  The task handle
+	// is requested (the second parameter is not NULL) but in this case just for
+	// demonstration purposes as its not actually used.
+	xTaskCreateRestricted( &xRegTest1Parameters, &xHandle );
+
+	// Start the scheduler.
+	vTaskStartScheduler();
+
+	// Will only get here if there was insufficient memory to create the idle
+	// task.
+	for( ;; );
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +#define xTaskCreateRestricted( x, pxCreatedTask ) xTaskGenericCreate( ((x)->pvTaskCode), ((x)->pcName), ((x)->usStackDepth), ((x)->pvParameters), ((x)->uxPriority), (pxCreatedTask), ((x)->puxStackBuffer), ((x)->xRegions) ) + +/** + * task. h + *
+ void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions );
+ * + * Memory regions are assigned to a restricted task when the task is created by + * a call to xTaskCreateRestricted(). These regions can be redefined using + * vTaskAllocateMPURegions(). + * + * @param xTask The handle of the task being updated. + * + * @param xRegions A pointer to an xMemoryRegion structure that contains the + * new memory region definitions. + * + * Example usage: +
+// Define an array of xMemoryRegion structures that configures an MPU region
+// allowing read/write access for 1024 bytes starting at the beginning of the
+// ucOneKByte array.  The other two of the maximum 3 definable regions are
+// unused so set to zero.
+static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
+{											
+	// Base address		Length		Parameters
+	{ ucOneKByte,		1024,		portMPU_REGION_READ_WRITE },
+	{ 0,				0,			0 },
+	{ 0,				0,			0 }
+};
+
+void vATask( void *pvParameters )
+{
+	// This task was created such that it has access to certain regions of
+	// memory as defined by the MPU configuration.  At some point it is 
+	// desired that these MPU regions are replaced with that defined in the
+	// xAltRegions const struct above.  Use a call to vTaskAllocateMPURegions()
+	// for this purpose.  NULL is used as the task handle to indicate that this
+	// function should modify the MPU regions of the calling task.
+	vTaskAllocateMPURegions( NULL, xAltRegions );
+	
+	// Now the task can continue its function, but from this point on can only
+	// access its stack and the ucOneKByte array (unless any other statically
+	// defined or shared regions have been declared elsewhere).
+}
+   
+ * \defgroup xTaskCreateRestricted xTaskCreateRestricted + * \ingroup Tasks + */ +void vTaskAllocateMPURegions( xTaskHandle xTask, const xMemoryRegion * const pxRegions ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelete( xTaskHandle pxTask );
+ * + * INCLUDE_vTaskDelete must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Remove a task from the RTOS real time kernels management. The task being + * deleted will be removed from all ready, blocked, suspended and event lists. + * + * NOTE: The idle task is responsible for freeing the kernel allocated + * memory from tasks that have been deleted. It is therefore important that + * the idle task is not starved of microcontroller processing time if your + * application makes any calls to vTaskDelete (). Memory allocated by the + * task code is not automatically freed, and should be freed before the task + * is deleted. + * + * See the demo application file death.c for sample code that utilises + * vTaskDelete (). + * + * @param pxTask The handle of the task to be deleted. Passing NULL will + * cause the calling task to be deleted. + * + * Example usage: +
+ void vOtherFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create the task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // Use the handle to delete the task.
+	 vTaskDelete( xHandle );
+ }
+   
+ * \defgroup vTaskDelete vTaskDelete + * \ingroup Tasks + */ +void vTaskDelete( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; + + +/*----------------------------------------------------------- + * TASK CONTROL API + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskDelay( portTickType xTicksToDelay );
+ * + * Delay a task for a given number of ticks. The actual time that the + * task remains blocked depends on the tick rate. The constant + * portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * INCLUDE_vTaskDelay must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * + * vTaskDelay() specifies a time at which the task wishes to unblock relative to + * the time at which vTaskDelay() is called. For example, specifying a block + * period of 100 ticks will cause the task to unblock 100 ticks after + * vTaskDelay() is called. vTaskDelay() does not therefore provide a good method + * of controlling the frequency of a cyclical task as the path taken through the + * code, as well as other task and interrupt activity, will effect the frequency + * at which vTaskDelay() gets called and therefore the time at which the task + * next executes. See vTaskDelayUntil() for an alternative API function designed + * to facilitate fixed frequency execution. It does this by specifying an + * absolute time (rather than a relative time) at which the calling task should + * unblock. + * + * @param xTicksToDelay The amount of time, in tick periods, that + * the calling task should block. + * + * Example usage: + + void vTaskFunction( void * pvParameters ) + { + void vTaskFunction( void * pvParameters ) + { + // Block for 500ms. + const portTickType xDelay = 500 / portTICK_RATE_MS; + + for( ;; ) + { + // Simply toggle the LED every 500ms, blocking between each toggle. + vToggleLED(); + vTaskDelay( xDelay ); + } + } + + * \defgroup vTaskDelay vTaskDelay + * \ingroup TaskCtrl + */ +void vTaskDelay( portTickType xTicksToDelay ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskDelayUntil( portTickType *pxPreviousWakeTime, portTickType xTimeIncrement );
+ * + * INCLUDE_vTaskDelayUntil must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Delay a task until a specified time. This function can be used by cyclical + * tasks to ensure a constant execution frequency. + * + * This function differs from vTaskDelay () in one important aspect: vTaskDelay () will + * cause a task to block for the specified number of ticks from the time vTaskDelay () is + * called. It is therefore difficult to use vTaskDelay () by itself to generate a fixed + * execution frequency as the time between a task starting to execute and that task + * calling vTaskDelay () may not be fixed [the task may take a different path though the + * code between calls, or may get interrupted or preempted a different number of times + * each time it executes]. + * + * Whereas vTaskDelay () specifies a wake time relative to the time at which the function + * is called, vTaskDelayUntil () specifies the absolute (exact) time at which it wishes to + * unblock. + * + * The constant portTICK_RATE_MS can be used to calculate real time from the tick + * rate - with the resolution of one tick period. + * + * @param pxPreviousWakeTime Pointer to a variable that holds the time at which the + * task was last unblocked. The variable must be initialised with the current time + * prior to its first use (see the example below). Following this the variable is + * automatically updated within vTaskDelayUntil (). + * + * @param xTimeIncrement The cycle time period. The task will be unblocked at + * time *pxPreviousWakeTime + xTimeIncrement. Calling vTaskDelayUntil with the + * same xTimeIncrement parameter value will cause the task to execute with + * a fixed interface period. + * + * Example usage: +
+ // Perform an action every 10 ticks.
+ void vTaskFunction( void * pvParameters )
+ {
+ portTickType xLastWakeTime;
+ const portTickType xFrequency = 10;
+
+	 // Initialise the xLastWakeTime variable with the current time.
+	 xLastWakeTime = xTaskGetTickCount ();
+	 for( ;; )
+	 {
+		 // Wait for the next cycle.
+		 vTaskDelayUntil( &xLastWakeTime, xFrequency );
+
+		 // Perform action here.
+	 }
+ }
+   
+ * \defgroup vTaskDelayUntil vTaskDelayUntil + * \ingroup TaskCtrl + */ +void vTaskDelayUntil( portTickType * const pxPreviousWakeTime, portTickType xTimeIncrement ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask );
+ * + * INCLUDE_xTaskPriorityGet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Obtain the priority of any task. + * + * @param pxTask Handle of the task to be queried. Passing a NULL + * handle results in the priority of the calling task being returned. + * + * @return The priority of pxTask. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to obtain the priority of the created task.
+	 // It was created with tskIDLE_PRIORITY, but may have changed
+	 // it itself.
+	 if( uxTaskPriorityGet( xHandle ) != tskIDLE_PRIORITY )
+	 {
+		 // The task has changed it's priority.
+	 }
+
+	 // ...
+
+	 // Is our priority higher than the created task?
+	 if( uxTaskPriorityGet( xHandle ) < uxTaskPriorityGet( NULL ) )
+	 {
+		 // Our priority (obtained using NULL handle) is higher.
+	 }
+ }
+   
+ * \defgroup uxTaskPriorityGet uxTaskPriorityGet + * \ingroup TaskCtrl + */ +unsigned portBASE_TYPE uxTaskPriorityGet( xTaskHandle pxTask ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority );
+ * + * INCLUDE_vTaskPrioritySet must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Set the priority of any task. + * + * A context switch will occur before the function returns if the priority + * being set is higher than the currently executing task. + * + * @param pxTask Handle to the task for which the priority is being set. + * Passing a NULL handle results in the priority of the calling task being set. + * + * @param uxNewPriority The priority to which the task will be set. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to raise the priority of the created task.
+	 vTaskPrioritySet( xHandle, tskIDLE_PRIORITY + 1 );
+
+	 // ...
+
+	 // Use a NULL handle to raise our priority to the same value.
+	 vTaskPrioritySet( NULL, tskIDLE_PRIORITY + 1 );
+ }
+   
+ * \defgroup vTaskPrioritySet vTaskPrioritySet + * \ingroup TaskCtrl + */ +void vTaskPrioritySet( xTaskHandle pxTask, unsigned portBASE_TYPE uxNewPriority ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspend( xTaskHandle pxTaskToSuspend );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Suspend any task. When suspended a task will never get any microcontroller + * processing time, no matter what its priority. + * + * Calls to vTaskSuspend are not accumulative - + * i.e. calling vTaskSuspend () twice on the same task still only requires one + * call to vTaskResume () to ready the suspended task. + * + * @param pxTaskToSuspend Handle to the task being suspended. Passing a NULL + * handle will cause the calling task to be suspended. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Suspend ourselves.
+	 vTaskSuspend( NULL );
+
+	 // We cannot get here unless another task calls vTaskResume
+	 // with our handle as the parameter.
+ }
+   
+ * \defgroup vTaskSuspend vTaskSuspend + * \ingroup TaskCtrl + */ +void vTaskSuspend( xTaskHandle pxTaskToSuspend ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskResume( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_vTaskSuspend must be defined as 1 for this function to be available. + * See the configuration section for more information. + * + * Resumes a suspended task. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * vTaskResume (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * Example usage: +
+ void vAFunction( void )
+ {
+ xTaskHandle xHandle;
+
+	 // Create a task, storing the handle.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, &xHandle );
+
+	 // ...
+
+	 // Use the handle to suspend the created task.
+	 vTaskSuspend( xHandle );
+
+	 // ...
+
+	 // The created task will not run during this period, unless
+	 // another task calls vTaskResume( xHandle ).
+
+	 //...
+
+
+	 // Resume the suspended task ourselves.
+	 vTaskResume( xHandle );
+
+	 // The created task will once again get microcontroller processing
+	 // time in accordance with it priority within the system.
+ }
+   
+ * \defgroup vTaskResume vTaskResume + * \ingroup TaskCtrl + */ +void vTaskResume( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void xTaskResumeFromISR( xTaskHandle pxTaskToResume );
+ * + * INCLUDE_xTaskResumeFromISR must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * An implementation of vTaskResume() that can be called from within an ISR. + * + * A task that has been suspended by one of more calls to vTaskSuspend () + * will be made available for running again by a single call to + * xTaskResumeFromISR (). + * + * @param pxTaskToResume Handle to the task being readied. + * + * \defgroup vTaskResumeFromISR vTaskResumeFromISR + * \ingroup TaskCtrl + */ +portBASE_TYPE xTaskResumeFromISR( xTaskHandle pxTaskToResume ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * SCHEDULER CONTROL + *----------------------------------------------------------*/ + +/** + * task. h + *
void vTaskStartScheduler( void );
+ * + * Starts the real time kernel tick processing. After calling the kernel + * has control over which tasks are executed and when. This function + * does not return until an executing task calls vTaskEndScheduler (). + * + * At least one task should be created via a call to xTaskCreate () + * before calling vTaskStartScheduler (). The idle task is created + * automatically when the first application task is created. + * + * See the demo application file main.c for an example of creating + * tasks and starting the kernel. + * + * Example usage: +
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will not get here unless a task calls vTaskEndScheduler ()
+ }
+   
+ * + * \defgroup vTaskStartScheduler vTaskStartScheduler + * \ingroup SchedulerControl + */ +void vTaskStartScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskEndScheduler( void );
+ * + * Stops the real time kernel tick. All created tasks will be automatically + * deleted and multitasking (either preemptive or cooperative) will + * stop. Execution then resumes from the point where vTaskStartScheduler () + * was called, as if vTaskStartScheduler () had just returned. + * + * See the demo application file main. c in the demo/PC directory for an + * example that uses vTaskEndScheduler (). + * + * vTaskEndScheduler () requires an exit function to be defined within the + * portable layer (see vPortEndScheduler () in port. c for the PC port). This + * performs hardware specific operations such as stopping the kernel tick. + * + * vTaskEndScheduler () will cause all of the resources allocated by the + * kernel to be freed - but will not free resources allocated by application + * tasks. + * + * Example usage: +
+ void vTaskCode( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // At some point we want to end the real time kernel processing
+		 // so call ...
+		 vTaskEndScheduler ();
+	 }
+ }
+
+ void vAFunction( void )
+ {
+	 // Create at least one task before starting the kernel.
+	 xTaskCreate( vTaskCode, "NAME", STACK_SIZE, NULL, tskIDLE_PRIORITY, NULL );
+
+	 // Start the real time kernel with preemption.
+	 vTaskStartScheduler ();
+
+	 // Will only get here when the vTaskCode () task has called
+	 // vTaskEndScheduler ().  When we get here we are back to single task
+	 // execution.
+ }
+   
+ * + * \defgroup vTaskEndScheduler vTaskEndScheduler + * \ingroup SchedulerControl + */ +void vTaskEndScheduler( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskSuspendAll( void );
+ * + * Suspends all real time kernel activity while keeping interrupts (including the + * kernel tick) enabled. + * + * After calling vTaskSuspendAll () the calling task will continue to execute + * without risk of being swapped out until a call to xTaskResumeAll () has been + * made. + * + * API functions that have the potential to cause a context switch (for example, + * vTaskDelayUntil(), xQueueSend(), etc.) must not be called while the scheduler + * is suspended. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the kernel
+		 // tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.
+		 xTaskResumeAll ();
+	 }
+ }
+   
+ * \defgroup vTaskSuspendAll vTaskSuspendAll + * \ingroup SchedulerControl + */ +void vTaskSuspendAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
char xTaskResumeAll( void );
+ * + * Resumes real time kernel activity following a call to vTaskSuspendAll (). + * After a call to vTaskSuspendAll () the kernel will take control of which + * task is executing at any time. + * + * @return If resuming the scheduler caused a context switch then pdTRUE is + * returned, otherwise pdFALSE is returned. + * + * Example usage: +
+ void vTask1( void * pvParameters )
+ {
+	 for( ;; )
+	 {
+		 // Task code goes here.
+
+		 // ...
+
+		 // At some point the task wants to perform a long operation during
+		 // which it does not want to get swapped out.  It cannot use
+		 // taskENTER_CRITICAL ()/taskEXIT_CRITICAL () as the length of the
+		 // operation may cause interrupts to be missed - including the
+		 // ticks.
+
+		 // Prevent the real time kernel swapping out the task.
+		 vTaskSuspendAll ();
+
+		 // Perform the operation here.  There is no need to use critical
+		 // sections as we have all the microcontroller processing time.
+		 // During this time interrupts will still operate and the real
+		 // time kernel tick count will be maintained.
+
+		 // ...
+
+		 // The operation is complete.  Restart the kernel.  We want to force
+		 // a context switch - but there is no point if resuming the scheduler
+		 // caused a context switch already.
+		 if( !xTaskResumeAll () )
+		 {
+			  taskYIELD ();
+		 }
+	 }
+ }
+   
+ * \defgroup xTaskResumeAll xTaskResumeAll + * \ingroup SchedulerControl + */ +signed portBASE_TYPE xTaskResumeAll( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask );
+ * + * Utility task that simply returns pdTRUE if the task referenced by xTask is + * currently in the Suspended state, or pdFALSE if the task referenced by xTask + * is in any other state. + * + */ +signed portBASE_TYPE xTaskIsTaskSuspended( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/*----------------------------------------------------------- + * TASK UTILITIES + *----------------------------------------------------------*/ + +/** + * task. h + *
volatile portTickType xTaskGetTickCount( void );
+ * + * @return The count of ticks since vTaskStartScheduler was called. + * + * \page xTaskGetTickCount xTaskGetTickCount + * \ingroup TaskUtils + */ +portTickType xTaskGetTickCount( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned short uxTaskGetNumberOfTasks( void );
+ * + * @return The number of tasks that the real time kernel is currently managing. + * This includes all ready, blocked and suspended tasks. A task that + * has been deleted but not yet freed by the idle task will also be + * included in the count. + * + * \page uxTaskGetNumberOfTasks uxTaskGetNumberOfTasks + * \ingroup TaskUtils + */ +unsigned portBASE_TYPE uxTaskGetNumberOfTasks( void ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskList( char *pcWriteBuffer );
+ * + * configUSE_TRACE_FACILITY must be defined as 1 for this function to be + * available. See the configuration section for more information. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Lists all the current tasks, along with their current state and stack + * usage high water mark. + * + * Tasks are reported as blocked ('B'), ready ('R'), deleted ('D') or + * suspended ('S'). + * + * @param pcWriteBuffer A buffer into which the above mentioned details + * will be written, in ascii form. This buffer is assumed to be large + * enough to contain the generated report. Approximately 40 bytes per + * task should be sufficient. + * + * \page vTaskList vTaskList + * \ingroup TaskUtils + */ +void vTaskList( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskGetRunTimeStats( char *pcWriteBuffer );
+ * + * configGENERATE_RUN_TIME_STATS must be defined as 1 for this function + * to be available. The application must also then provide definitions + * for portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() and + * portGET_RUN_TIME_COUNTER_VALUE to configure a peripheral timer/counter + * and return the timers current count value respectively. The counter + * should be at least 10 times the frequency of the tick count. + * + * NOTE: This function will disable interrupts for its duration. It is + * not intended for normal application runtime use but as a debug aid. + * + * Setting configGENERATE_RUN_TIME_STATS to 1 will result in a total + * accumulated execution time being stored for each task. The resolution + * of the accumulated time value depends on the frequency of the timer + * configured by the portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() macro. + * Calling vTaskGetRunTimeStats() writes the total execution time of each + * task into a buffer, both as an absolute count value and as a percentage + * of the total system execution time. + * + * @param pcWriteBuffer A buffer into which the execution times will be + * written, in ascii form. This buffer is assumed to be large enough to + * contain the generated report. Approximately 40 bytes per task should + * be sufficient. + * + * \page vTaskGetRunTimeStats vTaskGetRunTimeStats + * \ingroup TaskUtils + */ +void vTaskGetRunTimeStats( signed char *pcWriteBuffer ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
void vTaskStartTrace( char * pcBuffer, unsigned portBASE_TYPE uxBufferSize );
+ * + * Starts a real time kernel activity trace. The trace logs the identity of + * which task is running when. + * + * The trace file is stored in binary format. A separate DOS utility called + * convtrce.exe is used to convert this into a tab delimited text file which + * can be viewed and plotted in a spread sheet. + * + * @param pcBuffer The buffer into which the trace will be written. + * + * @param ulBufferSize The size of pcBuffer in bytes. The trace will continue + * until either the buffer in full, or ulTaskEndTrace () is called. + * + * \page vTaskStartTrace vTaskStartTrace + * \ingroup TaskUtils + */ +void vTaskStartTrace( signed char * pcBuffer, unsigned long ulBufferSize ) PRIVILEGED_FUNCTION; + +/** + * task. h + *
unsigned long ulTaskEndTrace( void );
+ * + * Stops a kernel activity trace. See vTaskStartTrace (). + * + * @return The number of bytes that have been written into the trace buffer. + * + * \page usTaskEndTrace usTaskEndTrace + * \ingroup TaskUtils + */ +unsigned long ulTaskEndTrace( void ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask );
+ * + * INCLUDE_uxTaskGetStackHighWaterMark must be set to 1 in FreeRTOSConfig.h for + * this function to be available. + * + * Returns the high water mark of the stack associated with xTask. That is, + * the minimum free stack space there has been (in bytes) since the task + * started. The smaller the returned number the closer the task has come + * to overflowing its stack. + * + * @param xTask Handle of the task associated with the stack to be checked. + * Set xTask to NULL to check the stack of the calling task. + * + * @return The smallest amount of free stack space there has been (in bytes) + * since the task referenced by xTask was created. + */ +unsigned portBASE_TYPE uxTaskGetStackHighWaterMark( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Sets pxHookFunction to be the task hook function used by the task xTask. + * Passing xTask as NULL has the effect of setting the calling tasks hook + * function. + */ +void vTaskSetApplicationTaskTag( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
void xTaskGetApplicationTaskTag( xTaskHandle xTask );
+ * + * Returns the pxHookFunction value assigned to the task xTask. + */ +pdTASK_HOOK_CODE xTaskGetApplicationTaskTag( xTaskHandle xTask ) PRIVILEGED_FUNCTION; + +/** + * task.h + *
portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, pdTASK_HOOK_CODE pxHookFunction );
+ * + * Calls the hook function associated with xTask. Passing xTask as NULL has + * the effect of calling the Running tasks (the calling task) hook function. + * + * pvParameter is passed to the hook function for the task to interpret as it + * wants. + */ +portBASE_TYPE xTaskCallApplicationTaskHook( xTaskHandle xTask, void *pvParameter ) PRIVILEGED_FUNCTION; + + +/*----------------------------------------------------------- + * SCHEDULER INTERNALS AVAILABLE FOR PORTING PURPOSES + *----------------------------------------------------------*/ + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Called from the real time kernel tick (either preemptive or cooperative), + * this increments the tick count and checks if any tasks that are blocked + * for a finite period required removing from a blocked list and placing on + * a ready list. + */ +void vTaskIncrementTick( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes the calling task from the ready list and places it both + * on the list of tasks waiting for a particular event, and the + * list of delayed tasks. The task will be removed from both lists + * and replaced on the ready list should either the event occur (and + * there be no higher priority tasks waiting on the same event) or + * the delay period expires. + * + * @param pxEventList The list containing tasks that are blocked waiting + * for the event to occur. + * + * @param xTicksToWait The maximum amount of time that the task should wait + * for the event to occur. This is specified in kernel ticks,the constant + * portTICK_RATE_MS can be used to convert kernel ticks into a real time + * period. + */ +void vTaskPlaceOnEventList( const xList * const pxEventList, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * THIS FUNCTION MUST BE CALLED WITH INTERRUPTS DISABLED. + * + * Removes a task from both the specified event list and the list of blocked + * tasks, and places it on a ready queue. + * + * xTaskRemoveFromEventList () will be called if either an event occurs to + * unblock a task, or the block timeout period expires. + * + * @return pdTRUE if the task being removed has a higher priority than the task + * making the call, otherwise pdFALSE. + */ +signed portBASE_TYPE xTaskRemoveFromEventList( const xList * const pxEventList ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS AN + * INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * INCLUDE_vTaskCleanUpResources and INCLUDE_vTaskSuspend must be defined as 1 + * for this function to be available. + * See the configuration section for more information. + * + * Empties the ready and delayed queues of task control blocks, freeing the + * memory allocated for the task control block and task stacks as it goes. + */ +void vTaskCleanUpResources( void ) PRIVILEGED_FUNCTION; + +/* + * THIS FUNCTION MUST NOT BE USED FROM APPLICATION CODE. IT IS ONLY + * INTENDED FOR USE WHEN IMPLEMENTING A PORT OF THE SCHEDULER AND IS + * AN INTERFACE WHICH IS FOR THE EXCLUSIVE USE OF THE SCHEDULER. + * + * Sets the pointer to the current TCB to the TCB of the highest priority task + * that is ready to run. + */ +void vTaskSwitchContext( void ) PRIVILEGED_FUNCTION; + +/* + * Return the handle of the calling task. + */ +xTaskHandle xTaskGetCurrentTaskHandle( void ) PRIVILEGED_FUNCTION; + +/* + * Capture the current time status for future reference. + */ +void vTaskSetTimeOutState( xTimeOutType * const pxTimeOut ) PRIVILEGED_FUNCTION; + +/* + * Compare the time status now with that previously captured to see if the + * timeout has expired. + */ +portBASE_TYPE xTaskCheckForTimeOut( xTimeOutType * const pxTimeOut, portTickType * const pxTicksToWait ) PRIVILEGED_FUNCTION; + +/* + * Shortcut used by the queue implementation to prevent unnecessary call to + * taskYIELD(); + */ +void vTaskMissedYield( void ) PRIVILEGED_FUNCTION; + +/* + * Returns the scheduler state as taskSCHEDULER_RUNNING, + * taskSCHEDULER_NOT_STARTED or taskSCHEDULER_SUSPENDED. + */ +portBASE_TYPE xTaskGetSchedulerState( void ) PRIVILEGED_FUNCTION; + +/* + * Raises the priority of the mutex holder to that of the calling task should + * the mutex holder have a priority less than the calling task. + */ +void vTaskPriorityInherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Set the priority of a task back to its proper priority in the case that it + * inherited a higher priority while it was holding a semaphore. + */ +void vTaskPriorityDisinherit( xTaskHandle * const pxMutexHolder ) PRIVILEGED_FUNCTION; + +/* + * Generic version of the task creation function which is in turn called by the + * xTaskCreate() and xTaskCreateRestricted() macros. + */ +signed portBASE_TYPE xTaskGenericCreate( pdTASK_CODE pvTaskCode, const signed char * const pcName, unsigned short usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pxCreatedTask, portSTACK_TYPE *puxStackBuffer, const xMemoryRegion * const xRegions ) PRIVILEGED_FUNCTION; + +#ifdef __cplusplus +} +#endif +#endif /* TASK_H */ + + + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/list.c b/flight/PiOS/posix/Libraries/FreeRTOS/Source/list.c index fe970ee1a..d7b76f918 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/list.c +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/list.c @@ -1,191 +1,191 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#include -#include "FreeRTOS.h" -#include "list.h" - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -void vListInitialise( xList *pxList ) -{ - /* The list structure contains a list item which is used to mark the - end of the list. To initialise the list the list end is inserted - as the only list entry. */ - pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); - - /* The list end value is the highest possible value in the list to - ensure it remains at the end of the list. */ - pxList->xListEnd.xItemValue = portMAX_DELAY; - - /* The list end next and previous pointers point to itself so we know - when the list is empty. */ - pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); - pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); - - pxList->uxNumberOfItems = 0; -} -/*-----------------------------------------------------------*/ - -void vListInitialiseItem( xListItem *pxItem ) -{ - /* Make sure the list item is not recorded as being on a list. */ - pxItem->pvContainer = NULL; -} -/*-----------------------------------------------------------*/ - -void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) -{ -volatile xListItem * pxIndex; - - /* Insert a new list item into pxList, but rather than sort the list, - makes the new list item the last item to be removed by a call to - pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by - the pxIndex member. */ - pxIndex = pxList->pxIndex; - - pxNewListItem->pxNext = pxIndex->pxNext; - pxNewListItem->pxPrevious = pxList->pxIndex; - pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; - pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListInsert( xList *pxList, xListItem *pxNewListItem ) -{ -volatile xListItem *pxIterator; -portTickType xValueOfInsertion; - - /* Insert the new list item into the list, sorted in ulListItem order. */ - xValueOfInsertion = pxNewListItem->xItemValue; - - /* If the list already contains a list item with the same item value then - the new list item should be placed after it. This ensures that TCB's which - are stored in ready lists (all of which have the same ulListItem value) - get an equal share of the CPU. However, if the xItemValue is the same as - the back marker the iteration loop below will not end. This means we need - to guard against this by checking the value first and modifying the - algorithm slightly if necessary. */ - if( xValueOfInsertion == portMAX_DELAY ) - { - pxIterator = pxList->xListEnd.pxPrevious; - } - else - { - /* *** NOTE *********************************************************** - If you find your application is crashing here then likely causes are: - 1) Stack overflow - - see http://www.freertos.org/Stacks-and-stack-overflow-checking.html - 2) Incorrect interrupt priority assignment, especially on Cortex M3 - parts where numerically high priority values denote low actual - interrupt priories, which can seem counter intuitive. See - configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html - 3) Calling an API function from within a critical section or when - the scheduler is suspended. - 4) Using a queue or semaphore before it has been initialised or - before the scheduler has been started (are interrupts firing - before vTaskStartScheduler() has been called?). - See http://www.freertos.org/FAQHelp.html for more tips. - **********************************************************************/ - - for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) - { - /* There is nothing to do here, we are just iterating to the - wanted insertion position. */ - } - } - - pxNewListItem->pxNext = pxIterator->pxNext; - pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; - pxNewListItem->pxPrevious = pxIterator; - pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; - - /* Remember which list the item is in. This allows fast removal of the - item later. */ - pxNewListItem->pvContainer = ( void * ) pxList; - - ( pxList->uxNumberOfItems )++; -} -/*-----------------------------------------------------------*/ - -void vListRemove( xListItem *pxItemToRemove ) -{ -xList * pxList; - - pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; - pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; - - /* The list item knows which list it is in. Obtain the list from the list - item. */ - pxList = ( xList * ) pxItemToRemove->pvContainer; - - /* Make sure the index is left pointing to a valid item. */ - if( pxList->pxIndex == pxItemToRemove ) - { - pxList->pxIndex = pxItemToRemove->pxPrevious; - } - - pxItemToRemove->pvContainer = NULL; - ( pxList->uxNumberOfItems )--; -} -/*-----------------------------------------------------------*/ - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#include +#include "FreeRTOS.h" +#include "list.h" + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +void vListInitialise( xList *pxList ) +{ + /* The list structure contains a list item which is used to mark the + end of the list. To initialise the list the list end is inserted + as the only list entry. */ + pxList->pxIndex = ( xListItem * ) &( pxList->xListEnd ); + + /* The list end value is the highest possible value in the list to + ensure it remains at the end of the list. */ + pxList->xListEnd.xItemValue = portMAX_DELAY; + + /* The list end next and previous pointers point to itself so we know + when the list is empty. */ + pxList->xListEnd.pxNext = ( xListItem * ) &( pxList->xListEnd ); + pxList->xListEnd.pxPrevious = ( xListItem * ) &( pxList->xListEnd ); + + pxList->uxNumberOfItems = 0; +} +/*-----------------------------------------------------------*/ + +void vListInitialiseItem( xListItem *pxItem ) +{ + /* Make sure the list item is not recorded as being on a list. */ + pxItem->pvContainer = NULL; +} +/*-----------------------------------------------------------*/ + +void vListInsertEnd( xList *pxList, xListItem *pxNewListItem ) +{ +volatile xListItem * pxIndex; + + /* Insert a new list item into pxList, but rather than sort the list, + makes the new list item the last item to be removed by a call to + pvListGetOwnerOfNextEntry. This means it has to be the item pointed to by + the pxIndex member. */ + pxIndex = pxList->pxIndex; + + pxNewListItem->pxNext = pxIndex->pxNext; + pxNewListItem->pxPrevious = pxList->pxIndex; + pxIndex->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxIndex->pxNext = ( volatile xListItem * ) pxNewListItem; + pxList->pxIndex = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListInsert( xList *pxList, xListItem *pxNewListItem ) +{ +volatile xListItem *pxIterator; +portTickType xValueOfInsertion; + + /* Insert the new list item into the list, sorted in ulListItem order. */ + xValueOfInsertion = pxNewListItem->xItemValue; + + /* If the list already contains a list item with the same item value then + the new list item should be placed after it. This ensures that TCB's which + are stored in ready lists (all of which have the same ulListItem value) + get an equal share of the CPU. However, if the xItemValue is the same as + the back marker the iteration loop below will not end. This means we need + to guard against this by checking the value first and modifying the + algorithm slightly if necessary. */ + if( xValueOfInsertion == portMAX_DELAY ) + { + pxIterator = pxList->xListEnd.pxPrevious; + } + else + { + /* *** NOTE *********************************************************** + If you find your application is crashing here then likely causes are: + 1) Stack overflow - + see http://www.freertos.org/Stacks-and-stack-overflow-checking.html + 2) Incorrect interrupt priority assignment, especially on Cortex M3 + parts where numerically high priority values denote low actual + interrupt priories, which can seem counter intuitive. See + configMAX_SYSCALL_INTERRUPT_PRIORITY on http://www.freertos.org/a00110.html + 3) Calling an API function from within a critical section or when + the scheduler is suspended. + 4) Using a queue or semaphore before it has been initialised or + before the scheduler has been started (are interrupts firing + before vTaskStartScheduler() has been called?). + See http://www.freertos.org/FAQHelp.html for more tips. + **********************************************************************/ + + for( pxIterator = ( xListItem * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) + { + /* There is nothing to do here, we are just iterating to the + wanted insertion position. */ + } + } + + pxNewListItem->pxNext = pxIterator->pxNext; + pxNewListItem->pxNext->pxPrevious = ( volatile xListItem * ) pxNewListItem; + pxNewListItem->pxPrevious = pxIterator; + pxIterator->pxNext = ( volatile xListItem * ) pxNewListItem; + + /* Remember which list the item is in. This allows fast removal of the + item later. */ + pxNewListItem->pvContainer = ( void * ) pxList; + + ( pxList->uxNumberOfItems )++; +} +/*-----------------------------------------------------------*/ + +void vListRemove( xListItem *pxItemToRemove ) +{ +xList * pxList; + + pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; + pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; + + /* The list item knows which list it is in. Obtain the list from the list + item. */ + pxList = ( xList * ) pxItemToRemove->pvContainer; + + /* Make sure the index is left pointing to a valid item. */ + if( pxList->pxIndex == pxItemToRemove ) + { + pxList->pxIndex = pxItemToRemove->pxPrevious; + } + + pxItemToRemove->pvContainer = NULL; + ( pxList->uxNumberOfItems )--; +} +/*-----------------------------------------------------------*/ + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h b/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h index 775c2bac9..1742ea177 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/GCC/Posix/portmacro.h @@ -1,159 +1,159 @@ -/* - FreeRTOS.org V5.2.0 - Copyright (C) 2003-2009 Richard Barry. - - This file is part of the FreeRTOS.org distribution. - - FreeRTOS.org is free software; you can redistribute it and/or modify it - under the terms of the GNU General Public License (version 2) as published - by the Free Software Foundation and modified by the FreeRTOS exception. - - FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. - - You should have received a copy of the GNU General Public License along - with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 - Temple Place, Suite 330, Boston, MA 02111-1307 USA. - - A special exception to the GPL is included to allow you to distribute a - combined work that includes FreeRTOS.org without being obliged to provide - the source code for any proprietary components. See the licensing section - of http://www.FreeRTOS.org for full details. - - - *************************************************************************** - * * - * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * - * * - * This is a concise, step by step, 'hands on' guide that describes both * - * general multitasking concepts and FreeRTOS specifics. It presents and * - * explains numerous examples that are written using the FreeRTOS API. * - * Full source code for all the examples is provided in an accompanying * - * .zip file. * - * * - *************************************************************************** - - 1 tab == 4 spaces! - - Please ensure to read the configuration and relevant port sections of the - online documentation. - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -#ifndef PORTMACRO_H -#define PORTMACRO_H - -#ifdef __cplusplus -extern "C" { -#endif - -/*----------------------------------------------------------- - * Port specific definitions. - * - * The settings in this file configure FreeRTOS correctly for the - * given hardware and compiler. - * - * These settings should not be altered. - *----------------------------------------------------------- - */ - -/* Type definitions. */ -#define portCHAR char -#define portFLOAT float -#define portDOUBLE double -#define portLONG int -#define portSHORT short -#define portSTACK_TYPE unsigned long -#define portBASE_TYPE long - -#if( configUSE_16_BIT_TICKS == 1 ) - typedef unsigned portSHORT portTickType; - #define portMAX_DELAY ( portTickType ) 0xffff -#else - typedef unsigned portLONG portTickType; - #define portMAX_DELAY ( portTickType ) 0xffffffff -#endif -/*-----------------------------------------------------------*/ - -/* Architecture specifics. */ -#define portSTACK_GROWTH ( -1 ) -#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) -#define portTICK_RATE_MICROSECONDS ( ( portTickType ) 1000000 / configTICK_RATE_HZ ) -#define portBYTE_ALIGNMENT 4 -#define portREMOVE_STATIC_QUALIFIER -/*-----------------------------------------------------------*/ - - -/* Scheduler utilities. */ -extern void vPortYieldFromISR( void ); -extern void vPortYield( void ); - -#define portYIELD() vPortYield() - -#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() -/*-----------------------------------------------------------*/ - - -/* Critical section management. */ -extern void vPortDisableInterrupts( void ); -extern void vPortEnableInterrupts( void ); -#define portSET_INTERRUPT_MASK() ( vPortDisableInterrupts() ) -#define portCLEAR_INTERRUPT_MASK() ( vPortEnableInterrupts() ) - -extern portBASE_TYPE xPortSetInterruptMask( void ); -extern void vPortClearInterruptMask( portBASE_TYPE xMask ); - -#define portSET_INTERRUPT_MASK_FROM_ISR() xPortSetInterruptMask() -#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) vPortClearInterruptMask(x) - - -extern void vPortEnterCritical( void ); -extern void vPortExitCritical( void ); - -#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() -#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() -#define portENTER_CRITICAL() vPortEnterCritical() -#define portEXIT_CRITICAL() vPortExitCritical() -/*-----------------------------------------------------------*/ - -/* Task function macros as described on the FreeRTOS.org WEB site. */ -#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) -#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) - -#define portNOP() - -#define portOUTPUT_BYTE( a, b ) - -extern void vPortForciblyEndThread( void *pxTaskToDelete ); -#define traceTASK_DELETE( pxTaskToDelete ) vPortForciblyEndThread( pxTaskToDelete ) - -extern void vPortAddTaskHandle( void *pxTaskHandle ); -#define traceTASK_CREATE( pxNewTCB ) vPortAddTaskHandle( pxNewTCB ) - -/* Posix Signal definitions that can be changed or read as appropriate. */ -#define SIG_SUSPEND SIGUSR1 - -/* Make use of times(man 2) to gather run-time statistics on the tasks. */ -extern void vPortFindTicksPerSecond( void ); -#undef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS -#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vPortFindTicksPerSecond() /* Nothing to do because the timer is already present. */ -extern unsigned long ulPortGetTimerValue( void ); -#undef portGET_RUN_TIME_COUNTER_VALUE -#define portGET_RUN_TIME_COUNTER_VALUE() ulPortGetTimerValue() /* Query the System time stats for this process. */ - -#ifdef __cplusplus -} -#endif - -#endif /* PORTMACRO_H */ - +/* + FreeRTOS.org V5.2.0 - Copyright (C) 2003-2009 Richard Barry. + + This file is part of the FreeRTOS.org distribution. + + FreeRTOS.org is free software; you can redistribute it and/or modify it + under the terms of the GNU General Public License (version 2) as published + by the Free Software Foundation and modified by the FreeRTOS exception. + + FreeRTOS.org is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. + + You should have received a copy of the GNU General Public License along + with FreeRTOS.org; if not, write to the Free Software Foundation, Inc., 59 + Temple Place, Suite 330, Boston, MA 02111-1307 USA. + + A special exception to the GPL is included to allow you to distribute a + combined work that includes FreeRTOS.org without being obliged to provide + the source code for any proprietary components. See the licensing section + of http://www.FreeRTOS.org for full details. + + + *************************************************************************** + * * + * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation * + * * + * This is a concise, step by step, 'hands on' guide that describes both * + * general multitasking concepts and FreeRTOS specifics. It presents and * + * explains numerous examples that are written using the FreeRTOS API. * + * Full source code for all the examples is provided in an accompanying * + * .zip file. * + * * + *************************************************************************** + + 1 tab == 4 spaces! + + Please ensure to read the configuration and relevant port sections of the + online documentation. + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +#ifndef PORTMACRO_H +#define PORTMACRO_H + +#ifdef __cplusplus +extern "C" { +#endif + +/*----------------------------------------------------------- + * Port specific definitions. + * + * The settings in this file configure FreeRTOS correctly for the + * given hardware and compiler. + * + * These settings should not be altered. + *----------------------------------------------------------- + */ + +/* Type definitions. */ +#define portCHAR char +#define portFLOAT float +#define portDOUBLE double +#define portLONG int +#define portSHORT short +#define portSTACK_TYPE unsigned long +#define portBASE_TYPE long + +#if( configUSE_16_BIT_TICKS == 1 ) + typedef unsigned portSHORT portTickType; + #define portMAX_DELAY ( portTickType ) 0xffff +#else + typedef unsigned portLONG portTickType; + #define portMAX_DELAY ( portTickType ) 0xffffffff +#endif +/*-----------------------------------------------------------*/ + +/* Architecture specifics. */ +#define portSTACK_GROWTH ( -1 ) +#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ ) +#define portTICK_RATE_MICROSECONDS ( ( portTickType ) 1000000 / configTICK_RATE_HZ ) +#define portBYTE_ALIGNMENT 4 +#define portREMOVE_STATIC_QUALIFIER +/*-----------------------------------------------------------*/ + + +/* Scheduler utilities. */ +extern void vPortYieldFromISR( void ); +extern void vPortYield( void ); + +#define portYIELD() vPortYield() + +#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR() +/*-----------------------------------------------------------*/ + + +/* Critical section management. */ +extern void vPortDisableInterrupts( void ); +extern void vPortEnableInterrupts( void ); +#define portSET_INTERRUPT_MASK() ( vPortDisableInterrupts() ) +#define portCLEAR_INTERRUPT_MASK() ( vPortEnableInterrupts() ) + +extern portBASE_TYPE xPortSetInterruptMask( void ); +extern void vPortClearInterruptMask( portBASE_TYPE xMask ); + +#define portSET_INTERRUPT_MASK_FROM_ISR() xPortSetInterruptMask() +#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) vPortClearInterruptMask(x) + + +extern void vPortEnterCritical( void ); +extern void vPortExitCritical( void ); + +#define portDISABLE_INTERRUPTS() portSET_INTERRUPT_MASK() +#define portENABLE_INTERRUPTS() portCLEAR_INTERRUPT_MASK() +#define portENTER_CRITICAL() vPortEnterCritical() +#define portEXIT_CRITICAL() vPortExitCritical() +/*-----------------------------------------------------------*/ + +/* Task function macros as described on the FreeRTOS.org WEB site. */ +#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) +#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) + +#define portNOP() + +#define portOUTPUT_BYTE( a, b ) + +extern void vPortForciblyEndThread( void *pxTaskToDelete ); +#define traceTASK_DELETE( pxTaskToDelete ) vPortForciblyEndThread( pxTaskToDelete ) + +extern void vPortAddTaskHandle( void *pxTaskHandle ); +#define traceTASK_CREATE( pxNewTCB ) vPortAddTaskHandle( pxNewTCB ) + +/* Posix Signal definitions that can be changed or read as appropriate. */ +#define SIG_SUSPEND SIGUSR1 + +/* Make use of times(man 2) to gather run-time statistics on the tasks. */ +extern void vPortFindTicksPerSecond( void ); +#undef portCONFIGURE_TIMER_FOR_RUN_TIME_STATS +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() vPortFindTicksPerSecond() /* Nothing to do because the timer is already present. */ +extern unsigned long ulPortGetTimerValue( void ); +#undef portGET_RUN_TIME_COUNTER_VALUE +#define portGET_RUN_TIME_COUNTER_VALUE() ulPortGetTimerValue() /* Query the System time stats for this process. */ + +#ifdef __cplusplus +} +#endif + +#endif /* PORTMACRO_H */ + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c b/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c index e4fd22f8a..190b8d58c 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/portable/MemMang/heap_3.c @@ -1,117 +1,117 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - - -/* - * Implementation of pvPortMalloc() and vPortFree() that relies on the - * compilers own malloc() and free() implementations. - * - * This file can only be used if the linker is configured to to generate - * a heap memory area. - * - * See heap_2.c and heap_1.c for alternative implementations, and the memory - * management pages of http://www.FreeRTOS.org for more information. - */ - -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/*-----------------------------------------------------------*/ - -void *pvPortMalloc( size_t xWantedSize ) -{ -void *pvReturn; - - vTaskSuspendAll(); - { - pvReturn = malloc( xWantedSize ); - } - xTaskResumeAll(); - - #if( configUSE_MALLOC_FAILED_HOOK == 1 ) - { - if( pvReturn == NULL ) - { - extern void vApplicationMallocFailedHook( void ); - vApplicationMallocFailedHook(); - } - } - #endif - - return pvReturn; -} -/*-----------------------------------------------------------*/ - -void vPortFree( void *pv ) -{ - if( pv ) - { - vTaskSuspendAll(); - { - free( pv ); - } - xTaskResumeAll(); - } -} - - - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + + +/* + * Implementation of pvPortMalloc() and vPortFree() that relies on the + * compilers own malloc() and free() implementations. + * + * This file can only be used if the linker is configured to to generate + * a heap memory area. + * + * See heap_2.c and heap_1.c for alternative implementations, and the memory + * management pages of http://www.FreeRTOS.org for more information. + */ + +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*-----------------------------------------------------------*/ + +void *pvPortMalloc( size_t xWantedSize ) +{ +void *pvReturn; + + vTaskSuspendAll(); + { + pvReturn = malloc( xWantedSize ); + } + xTaskResumeAll(); + + #if( configUSE_MALLOC_FAILED_HOOK == 1 ) + { + if( pvReturn == NULL ) + { + extern void vApplicationMallocFailedHook( void ); + vApplicationMallocFailedHook(); + } + } + #endif + + return pvReturn; +} +/*-----------------------------------------------------------*/ + +void vPortFree( void *pv ) +{ + if( pv ) + { + vTaskSuspendAll(); + { + free( pv ); + } + xTaskResumeAll(); + } +} + + + diff --git a/flight/PiOS/posix/Libraries/FreeRTOS/Source/queue.c b/flight/PiOS/posix/Libraries/FreeRTOS/Source/queue.c index 7258f7a3e..3827ca65f 100644 --- a/flight/PiOS/posix/Libraries/FreeRTOS/Source/queue.c +++ b/flight/PiOS/posix/Libraries/FreeRTOS/Source/queue.c @@ -1,1465 +1,1465 @@ -/* - FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. - - *************************************************************************** - * * - * If you are: * - * * - * + New to FreeRTOS, * - * + Wanting to learn FreeRTOS or multitasking in general quickly * - * + Looking for basic training, * - * + Wanting to improve your FreeRTOS skills and productivity * - * * - * then take a look at the FreeRTOS eBook * - * * - * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * - * http://www.FreeRTOS.org/Documentation * - * * - * A pdf reference manual is also available. Both are usually delivered * - * to your inbox within 20 minutes to two hours when purchased between 8am * - * and 8pm GMT (although please allow up to 24 hours in case of * - * exceptional circumstances). Thank you for your support! * - * * - *************************************************************************** - - This file is part of the FreeRTOS distribution. - - FreeRTOS is free software; you can redistribute it and/or modify it under - the terms of the GNU General Public License (version 2) as published by the - Free Software Foundation AND MODIFIED BY the FreeRTOS exception. - ***NOTE*** The exception to the GPL is included to allow you to distribute - a combined work that includes FreeRTOS without being obliged to provide the - source code for proprietary components outside of the FreeRTOS kernel. - FreeRTOS is distributed in the hope that it will be useful, but WITHOUT - ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or - FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for - more details. You should have received a copy of the GNU General Public - License and the FreeRTOS license exception along with FreeRTOS; if not it - can be viewed here: http://www.freertos.org/a00114.html and also obtained - by writing to Richard Barry, contact details for whom are available on the - FreeRTOS WEB site. - - 1 tab == 4 spaces! - - http://www.FreeRTOS.org - Documentation, latest information, license and - contact details. - - http://www.SafeRTOS.com - A version that is certified for use in safety - critical systems. - - http://www.OpenRTOS.com - Commercial support, development, porting, - licensing and training services. -*/ - -#include -#include - -/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining -all the API functions to use the MPU wrappers. That should only be done when -task.h is included from an application file. */ -#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -#include "FreeRTOS.h" -#include "task.h" -#include "croutine.h" - -#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE - -/*----------------------------------------------------------- - * PUBLIC LIST API documented in list.h - *----------------------------------------------------------*/ - -/* Constants used with the cRxLock and cTxLock structure members. */ -#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) -#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) - -#define queueERRONEOUS_UNBLOCK ( -1 ) - -/* For internal use only. */ -#define queueSEND_TO_BACK ( 0 ) -#define queueSEND_TO_FRONT ( 1 ) - -/* Effectively make a union out of the xQUEUE structure. */ -#define pxMutexHolder pcTail -#define uxQueueType pcHead -#define uxRecursiveCallCount pcReadFrom -#define queueQUEUE_IS_MUTEX NULL - -/* Semaphores do not actually store or copy data, so have an items size of -zero. */ -#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( 0 ) -#define queueDONT_BLOCK ( ( portTickType ) 0 ) -#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0 ) - -/* - * Definition of the queue used by the scheduler. - * Items are queued by copy, not reference. - */ -typedef struct QueueDefinition -{ - signed char *pcHead; /*< Points to the beginning of the queue storage area. */ - signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ - - signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ - signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ - - xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ - xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ - - volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ - unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ - unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ - - signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ - -} xQUEUE; -/*-----------------------------------------------------------*/ - -/* - * Inside this file xQueueHandle is a pointer to a xQUEUE structure. - * To keep the definition private the API header file defines it as a - * pointer to void. - */ -typedef xQUEUE * xQueueHandle; - -/* - * Prototypes for public functions are included here so we don't have to - * include the API header file (as it defines xQueueHandle differently). These - * functions are documented in the API header file. - */ -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateMutex( void ) PRIVILEGED_FUNCTION; -xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; -portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Co-routine queue functions differ from task queue functions. Co-routines are - * an optional component. - */ -#if configUSE_CO_ROUTINES == 1 - signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; - signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; -#endif - -/* - * The queue registry is just a means for kernel aware debuggers to locate - * queue structures. It has no other purpose so is an optional component. - */ -#if configQUEUE_REGISTRY_SIZE > 0 - - /* The type stored within the queue registry array. This allows a name - to be assigned to each queue making kernel aware debugging a little - more user friendly. */ - typedef struct QUEUE_REGISTRY_ITEM - { - signed char *pcQueueName; - xQueueHandle xHandle; - } xQueueRegistryItem; - - /* The queue registry is simply an array of xQueueRegistryItem structures. - The pcQueueName member of a structure being NULL is indicative of the - array position being vacant. */ - xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; - - /* Removes a queue from the registry by simply setting the pcQueueName - member to NULL. */ - static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; -#endif - -/* - * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not - * prevent an ISR from adding or removing items to the queue, but does prevent - * an ISR from removing tasks from the queue event lists. If an ISR finds a - * queue is locked it will instead increment the appropriate queue lock count - * to indicate that a task may require unblocking. When the queue in unlocked - * these lock counts are inspected, and the appropriate action taken. - */ -static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any data in a queue. - * - * @return pdTRUE if the queue contains no items, otherwise pdFALSE. - */ -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Uses a critical section to determine if there is any space in a queue. - * - * @return pdTRUE if there is no space, otherwise pdFALSE; - */ -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; - -/* - * Copies an item into the queue, either at the front of the queue or the - * back of the queue. - */ -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; - -/* - * Copies an item out of a queue. - */ -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; -/*-----------------------------------------------------------*/ - -/* - * Macro to mark a queue as locked. Locking a queue prevents an ISR from - * accessing the queue event lists. - */ -#define prvLockQueue( pxQueue ) \ -{ \ - taskENTER_CRITICAL(); \ - { \ - if( pxQueue->xRxLock == queueUNLOCKED ) \ - { \ - pxQueue->xRxLock = queueLOCKED_UNMODIFIED; \ - } \ - if( pxQueue->xTxLock == queueUNLOCKED ) \ - { \ - pxQueue->xTxLock = queueLOCKED_UNMODIFIED; \ - } \ - } \ - taskEXIT_CRITICAL(); \ -} -/*-----------------------------------------------------------*/ - - -/*----------------------------------------------------------- - * PUBLIC QUEUE MANAGEMENT API documented in queue.h - *----------------------------------------------------------*/ - -xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) -{ -xQUEUE *pxNewQueue; -size_t xQueueSizeInBytes; - - /* Allocate the new queue structure. */ - if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) - { - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Create the list of pointers to queue items. The queue is one byte - longer than asked for to make wrap checking easier/faster. */ - xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; - - pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); - if( pxNewQueue->pcHead != NULL ) - { - /* Initialise the queue members as described above where the - queue type is defined. */ - pxNewQueue->pcTail = pxNewQueue->pcHead + ( uxQueueLength * uxItemSize ); - pxNewQueue->uxMessagesWaiting = 0; - pxNewQueue->pcWriteTo = pxNewQueue->pcHead; - pxNewQueue->pcReadFrom = pxNewQueue->pcHead + ( ( uxQueueLength - 1 ) * uxItemSize ); - pxNewQueue->uxLength = uxQueueLength; - pxNewQueue->uxItemSize = uxItemSize; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - /* Likewise ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); - - traceQUEUE_CREATE( pxNewQueue ); - return pxNewQueue; - } - else - { - traceQUEUE_CREATE_FAILED(); - vPortFree( pxNewQueue ); - } - } - } - - /* Will only reach here if we could not allocate enough memory or no memory - was required. */ - return NULL; -} -/*-----------------------------------------------------------*/ - -#if ( configUSE_MUTEXES == 1 ) - - xQueueHandle xQueueCreateMutex( void ) - { - xQUEUE *pxNewQueue; - - /* Allocate the new queue structure. */ - pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); - if( pxNewQueue != NULL ) - { - /* Information required for priority inheritance. */ - pxNewQueue->pxMutexHolder = NULL; - pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; - - /* Queues used as a mutex no data is actually copied into or out - of the queue. */ - pxNewQueue->pcWriteTo = NULL; - pxNewQueue->pcReadFrom = NULL; - - /* Each mutex has a length of 1 (like a binary semaphore) and - an item size of 0 as nothing is actually copied into or out - of the mutex. */ - pxNewQueue->uxMessagesWaiting = 0; - pxNewQueue->uxLength = 1; - pxNewQueue->uxItemSize = 0; - pxNewQueue->xRxLock = queueUNLOCKED; - pxNewQueue->xTxLock = queueUNLOCKED; - - /* Ensure the event queues start with the correct state. */ - vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); - vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); - - /* Start with the semaphore in the expected state. */ - xQueueGenericSend( pxNewQueue, NULL, 0, queueSEND_TO_BACK ); - - traceCREATE_MUTEX( pxNewQueue ); - } - else - { - traceCREATE_MUTEX_FAILED(); - } - - return pxNewQueue; - } - -#endif /* configUSE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_RECURSIVE_MUTEXES == 1 - - portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) - { - portBASE_TYPE xReturn; - - /* If this is the task that holds the mutex then pxMutexHolder will not - change outside of this task. If this task does not hold the mutex then - pxMutexHolder can never coincidentally equal the tasks handle, and as - this is the only condition we are interested in it does not matter if - pxMutexHolder is accessed simultaneously by another task. Therefore no - mutual exclusion is required to test the pxMutexHolder variable. */ - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - traceGIVE_MUTEX_RECURSIVE( pxMutex ); - - /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to - the task handle, therefore no underflow check is required. Also, - uxRecursiveCallCount is only modified by the mutex holder, and as - there can only be one, no mutual exclusion is required to modify the - uxRecursiveCallCount member. */ - ( pxMutex->uxRecursiveCallCount )--; - - /* Have we unwound the call count? */ - if( pxMutex->uxRecursiveCallCount == 0 ) - { - /* Return the mutex. This will automatically unblock any other - task that might be waiting to access the mutex. */ - xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); - } - - xReturn = pdPASS; - } - else - { - /* We cannot give the mutex because we are not the holder. */ - xReturn = pdFAIL; - - traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_RECURSIVE_MUTEXES == 1 - - portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) - { - portBASE_TYPE xReturn; - - /* Comments regarding mutual exclusion as per those within - xQueueGiveMutexRecursive(). */ - - traceTAKE_MUTEX_RECURSIVE( pxMutex ); - - if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) - { - ( pxMutex->uxRecursiveCallCount )++; - xReturn = pdPASS; - } - else - { - xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); - - /* pdPASS will only be returned if we successfully obtained the mutex, - we may have blocked to reach here. */ - if( xReturn == pdPASS ) - { - ( pxMutex->uxRecursiveCallCount )++; - } - } - - return xReturn; - } - -#endif /* configUSE_RECURSIVE_MUTEXES */ -/*-----------------------------------------------------------*/ - -#if configUSE_COUNTING_SEMAPHORES == 1 - - xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) - { - xQueueHandle pxHandle; - - pxHandle = xQueueCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH ); - - if( pxHandle != NULL ) - { - pxHandle->uxMessagesWaiting = uxInitialCount; - - traceCREATE_COUNTING_SEMAPHORE(); - } - else - { - traceCREATE_COUNTING_SEMAPHORE_FAILED(); - } - - return pxHandle; - } - -#endif /* configUSE_COUNTING_SEMAPHORES */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. Yes it is ok to do - this from within the critical section - the kernel - takes care of that. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting the - function. */ - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was full and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - - /* Return to the original privilege level before exiting - the function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was full and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - - /* Unlocking the queue means queue events can effect the - event list. It is possible that interrupts occurring now - remove this task from the event list again - but as the - scheduler is suspended the task will go onto the pending - ready last instead of the actual ready list. */ - prvUnlockQueue( pxQueue ); - - /* Resuming the scheduler will move tasks from the pending - ready list into the ready list - so it is feasible that this - task is already in a ready list before it yields - in which - case the yield will not cause a context switch unless there - is also a higher priority task in the pending ready list. */ - if( !xTaskResumeAll() ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - /* The timeout has expired. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - - /* Return to the original privilege level before exiting the - function. */ - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } -} -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there room on the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND( pxQueue ); - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If there was a task waiting for data to arrive on the - queue then unblock it now. */ - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) - { - /* The unblocked task has a priority higher than - our own so yield immediately. */ - portYIELD_WITHIN_API(); - } - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - return errQUEUE_FULL; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueFull( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_SEND( pxQueue ); - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_SEND_FAILED( pxQueue ); - return errQUEUE_FULL; - } - } - taskEXIT_CRITICAL(); - } - } - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -#if configUSE_ALTERNATIVE_API == 1 - - signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) - { - signed portBASE_TYPE xEntryTimeSet = pdFALSE; - xTimeOutType xTimeOut; - signed char *pcOriginalReadPosition; - - for( ;; ) - { - taskENTER_CRITICAL(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - taskENTER_CRITICAL(); - { - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - portYIELD_WITHIN_API(); - } - } - else - { - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } - taskEXIT_CRITICAL(); - } - } - - -#endif /* configUSE_ALTERNATIVE_API */ -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - /* Similar to xQueueGenericSend, except we don't block if there is no room - in the queue. Also we don't directly wake a task that was blocked on a - queue read, instead we return a flag to say whether a context switch is - required or not (i.e. has a task with a higher priority than us been woken - by this post). */ - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - traceQUEUE_SEND_FROM_ISR( pxQueue ); - - prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); - - /* If the queue is locked we do not alter the event list. This will - be done when the queue is unlocked later. */ - if( pxQueue->xTxLock == queueUNLOCKED ) - { - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - *pxHigherPriorityTaskWoken = pdTRUE; - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was posted while it was locked. */ - ++( pxQueue->xTxLock ); - } - - xReturn = pdPASS; - } - else - { - traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); - xReturn = errQUEUE_FULL; - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) -{ -signed portBASE_TYPE xEntryTimeSet = pdFALSE; -xTimeOutType xTimeOut; -signed char *pcOriginalReadPosition; - - /* This function relaxes the coding standard somewhat to allow return - statements within the function itself. This is done in the interest - of execution time efficiency. */ - - for( ;; ) - { - taskENTER_CRITICAL(); - { - /* Is there data in the queue now? To be running we must be - the highest priority task wanting to access the queue. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Remember our read position in case we are just peeking. */ - pcOriginalReadPosition = pxQueue->pcReadFrom; - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - - if( xJustPeeking == pdFALSE ) - { - traceQUEUE_RECEIVE( pxQueue ); - - /* We are actually removing data. */ - --( pxQueue->uxMessagesWaiting ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* Record the information required to implement - priority inheritance should it become necessary. */ - pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); - } - } - #endif - - if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) - { - portYIELD_WITHIN_API(); - } - } - } - else - { - traceQUEUE_PEEK( pxQueue ); - - /* We are not removing the data, so reset our read - pointer. */ - pxQueue->pcReadFrom = pcOriginalReadPosition; - - /* The data is being left in the queue, so see if there are - any other tasks waiting for the data. */ - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than this task. */ - portYIELD_WITHIN_API(); - } - } - - } - - taskEXIT_CRITICAL(); - return pdPASS; - } - else - { - if( xTicksToWait == ( portTickType ) 0 ) - { - /* The queue was empty and no block time is specified (or - the block time has expired) so leave now. */ - taskEXIT_CRITICAL(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - else if( xEntryTimeSet == pdFALSE ) - { - /* The queue was empty and a block time was specified so - configure the timeout structure. */ - vTaskSetTimeOutState( &xTimeOut ); - xEntryTimeSet = pdTRUE; - } - } - } - taskEXIT_CRITICAL(); - - /* Interrupts and other tasks can send to and receive from the queue - now the critical section has been exited. */ - - vTaskSuspendAll(); - prvLockQueue( pxQueue ); - - /* Update the timeout state to see if it has expired yet. */ - if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) - { - if( prvIsQueueEmpty( pxQueue ) ) - { - traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); - - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - portENTER_CRITICAL(); - { - vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); - } - portEXIT_CRITICAL(); - } - } - #endif - - vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); - prvUnlockQueue( pxQueue ); - if( !xTaskResumeAll() ) - { - portYIELD_WITHIN_API(); - } - } - else - { - /* Try again. */ - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - } - } - else - { - prvUnlockQueue( pxQueue ); - ( void ) xTaskResumeAll(); - traceQUEUE_RECEIVE_FAILED( pxQueue ); - return errQUEUE_EMPTY; - } - } -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) -{ -signed portBASE_TYPE xReturn; -unsigned portBASE_TYPE uxSavedInterruptStatus; - - uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); - { - /* We cannot block from an ISR, so check there is data available. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); - - prvCopyDataFromQueue( pxQueue, pvBuffer ); - --( pxQueue->uxMessagesWaiting ); - - /* If the queue is locked we will not modify the event list. Instead - we update the lock count so the task that unlocks the queue will know - that an ISR has removed data while the queue was locked. */ - if( pxQueue->xRxLock == queueUNLOCKED ) - { - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - /* The task waiting has a higher priority than us so - force a context switch. */ - *pxTaskWoken = pdTRUE; - } - } - } - else - { - /* Increment the lock count so the task that unlocks the queue - knows that data was removed while it was locked. */ - ++( pxQueue->xRxLock ); - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); - } - } - portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - taskENTER_CRITICAL(); - uxReturn = pxQueue->uxMessagesWaiting; - taskEXIT_CRITICAL(); - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) -{ -unsigned portBASE_TYPE uxReturn; - - uxReturn = pxQueue->uxMessagesWaiting; - - return uxReturn; -} -/*-----------------------------------------------------------*/ - -void vQueueDelete( xQueueHandle pxQueue ) -{ - traceQUEUE_DELETE( pxQueue ); - vQueueUnregisterQueue( pxQueue ); - vPortFree( pxQueue->pcHead ); - vPortFree( pxQueue ); -} -/*-----------------------------------------------------------*/ - -static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) -{ - if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) - { - #if ( configUSE_MUTEXES == 1 ) - { - if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) - { - /* The mutex is no longer being held. */ - vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); - pxQueue->pxMutexHolder = NULL; - } - } - #endif - } - else if( xPosition == queueSEND_TO_BACK ) - { - memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcWriteTo += pxQueue->uxItemSize; - if( pxQueue->pcWriteTo >= pxQueue->pcTail ) - { - pxQueue->pcWriteTo = pxQueue->pcHead; - } - } - else - { - memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); - pxQueue->pcReadFrom -= pxQueue->uxItemSize; - if( pxQueue->pcReadFrom < pxQueue->pcHead ) - { - pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); - } - } - - ++( pxQueue->uxMessagesWaiting ); -} -/*-----------------------------------------------------------*/ - -static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) -{ - if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) - { - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - } -} -/*-----------------------------------------------------------*/ - -static void prvUnlockQueue( xQueueHandle pxQueue ) -{ - /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ - - /* The lock counts contains the number of extra data items placed or - removed from the queue while the queue was locked. When a queue is - locked items can be added or removed, but the event lists cannot be - updated. */ - taskENTER_CRITICAL(); - { - /* See if data was added to the queue while it was locked. */ - while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) - { - /* Data was posted while the queue was locked. Are any tasks - blocked waiting for data to become available? */ - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - /* Tasks that are removed from the event list will get added to - the pending ready list as the scheduler is still suspended. */ - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The task waiting has a higher priority so record that a - context switch is required. */ - vTaskMissedYield(); - } - - --( pxQueue->xTxLock ); - } - else - { - break; - } - } - - pxQueue->xTxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); - - /* Do the same for the Rx lock. */ - taskENTER_CRITICAL(); - { - while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) - { - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) - { - if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - vTaskMissedYield(); - } - - --( pxQueue->xRxLock ); - } - else - { - break; - } - } - - pxQueue->xRxLock = queueUNLOCKED; - } - taskEXIT_CRITICAL(); -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - taskENTER_CRITICAL(); - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - taskEXIT_CRITICAL(); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) -{ -signed portBASE_TYPE xReturn; - - xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); - - return xReturn; -} -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already full we may have to block. A critical section - is required to prevent an interrupt removing something from the queue - between the check to see if the queue is full and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( prvIsQueueFull( pxQueue ) ) - { - /* The queue is full - do we want to block or just leave without - posting? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is called from a coroutine we cannot block directly, but - return indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - /* There is room in the queue, copy the data into the queue. */ - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - xReturn = pdPASS; - - /* Were any co-routines waiting for data to become available? */ - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - /* The co-routine waiting has a higher priority so record - that a yield might be appropriate. */ - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = errQUEUE_FULL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) -{ -signed portBASE_TYPE xReturn; - - /* If the queue is already empty we may have to block. A critical section - is required to prevent an interrupt adding something to the queue - between the check to see if the queue is empty and blocking on the queue. */ - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) - { - /* There are no messages in the queue, do we want to block or just - leave with nothing? */ - if( xTicksToWait > ( portTickType ) 0 ) - { - /* As this is a co-routine we cannot block directly, but return - indicating that we need to block. */ - vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); - portENABLE_INTERRUPTS(); - return errQUEUE_BLOCKED; - } - else - { - portENABLE_INTERRUPTS(); - return errQUEUE_FULL; - } - } - } - portENABLE_INTERRUPTS(); - - portNOP(); - - portDISABLE_INTERRUPTS(); - { - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Data is available from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - xReturn = pdPASS; - - /* Were any co-routines waiting for space to become available? */ - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) - { - /* In this instance the co-routine could be placed directly - into the ready list as we are within a critical section. - Instead the same pending ready list mechanism is used as if - the event were caused from within an interrupt. */ - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - xReturn = errQUEUE_YIELD; - } - } - } - else - { - xReturn = pdFAIL; - } - } - portENABLE_INTERRUPTS(); - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - - - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) -{ - /* Cannot block within an ISR so if there is no space on the queue then - exit without doing anything. */ - if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) - { - prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); - - /* We only want to wake one co-routine per ISR, so check that a - co-routine has not already been woken. */ - if( !xCoRoutinePreviouslyWoken ) - { - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) - { - return pdTRUE; - } - } - } - } - - return xCoRoutinePreviouslyWoken; -} -#endif -/*-----------------------------------------------------------*/ - -#if configUSE_CO_ROUTINES == 1 -signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) -{ -signed portBASE_TYPE xReturn; - - /* We cannot block from an ISR, so check there is data available. If - not then just leave without doing anything. */ - if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) - { - /* Copy the data from the queue. */ - pxQueue->pcReadFrom += pxQueue->uxItemSize; - if( pxQueue->pcReadFrom >= pxQueue->pcTail ) - { - pxQueue->pcReadFrom = pxQueue->pcHead; - } - --( pxQueue->uxMessagesWaiting ); - memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); - - if( !( *pxCoRoutineWoken ) ) - { - if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) - { - if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) - { - *pxCoRoutineWoken = pdTRUE; - } - } - } - - xReturn = pdPASS; - } - else - { - xReturn = pdFAIL; - } - - return xReturn; -} -#endif -/*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) - { - unsigned portBASE_TYPE ux; - - /* See if there is an empty space in the registry. A NULL name denotes - a free slot. */ - for( ux = 0; ux < configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].pcQueueName == NULL ) - { - /* Store the information on this queue. */ - xQueueRegistry[ ux ].pcQueueName = pcQueueName; - xQueueRegistry[ ux ].xHandle = xQueue; - break; - } - } - } - -#endif - /*-----------------------------------------------------------*/ - -#if configQUEUE_REGISTRY_SIZE > 0 - - static void vQueueUnregisterQueue( xQueueHandle xQueue ) - { - unsigned portBASE_TYPE ux; - - /* See if the handle of the queue being unregistered in actually in the - registry. */ - for( ux = 0; ux < configQUEUE_REGISTRY_SIZE; ux++ ) - { - if( xQueueRegistry[ ux ].xHandle == xQueue ) - { - /* Set the name to NULL to show that this slot if free again. */ - xQueueRegistry[ ux ].pcQueueName = NULL; - break; - } - } - - } - -#endif - +/* + FreeRTOS V6.0.4 - Copyright (C) 2010 Real Time Engineers Ltd. + + *************************************************************************** + * * + * If you are: * + * * + * + New to FreeRTOS, * + * + Wanting to learn FreeRTOS or multitasking in general quickly * + * + Looking for basic training, * + * + Wanting to improve your FreeRTOS skills and productivity * + * * + * then take a look at the FreeRTOS eBook * + * * + * "Using the FreeRTOS Real Time Kernel - a Practical Guide" * + * http://www.FreeRTOS.org/Documentation * + * * + * A pdf reference manual is also available. Both are usually delivered * + * to your inbox within 20 minutes to two hours when purchased between 8am * + * and 8pm GMT (although please allow up to 24 hours in case of * + * exceptional circumstances). Thank you for your support! * + * * + *************************************************************************** + + This file is part of the FreeRTOS distribution. + + FreeRTOS is free software; you can redistribute it and/or modify it under + the terms of the GNU General Public License (version 2) as published by the + Free Software Foundation AND MODIFIED BY the FreeRTOS exception. + ***NOTE*** The exception to the GPL is included to allow you to distribute + a combined work that includes FreeRTOS without being obliged to provide the + source code for proprietary components outside of the FreeRTOS kernel. + FreeRTOS is distributed in the hope that it will be useful, but WITHOUT + ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or + FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for + more details. You should have received a copy of the GNU General Public + License and the FreeRTOS license exception along with FreeRTOS; if not it + can be viewed here: http://www.freertos.org/a00114.html and also obtained + by writing to Richard Barry, contact details for whom are available on the + FreeRTOS WEB site. + + 1 tab == 4 spaces! + + http://www.FreeRTOS.org - Documentation, latest information, license and + contact details. + + http://www.SafeRTOS.com - A version that is certified for use in safety + critical systems. + + http://www.OpenRTOS.com - Commercial support, development, porting, + licensing and training services. +*/ + +#include +#include + +/* Defining MPU_WRAPPERS_INCLUDED_FROM_API_FILE prevents task.h from redefining +all the API functions to use the MPU wrappers. That should only be done when +task.h is included from an application file. */ +#define MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +#include "FreeRTOS.h" +#include "task.h" +#include "croutine.h" + +#undef MPU_WRAPPERS_INCLUDED_FROM_API_FILE + +/*----------------------------------------------------------- + * PUBLIC LIST API documented in list.h + *----------------------------------------------------------*/ + +/* Constants used with the cRxLock and cTxLock structure members. */ +#define queueUNLOCKED ( ( signed portBASE_TYPE ) -1 ) +#define queueLOCKED_UNMODIFIED ( ( signed portBASE_TYPE ) 0 ) + +#define queueERRONEOUS_UNBLOCK ( -1 ) + +/* For internal use only. */ +#define queueSEND_TO_BACK ( 0 ) +#define queueSEND_TO_FRONT ( 1 ) + +/* Effectively make a union out of the xQUEUE structure. */ +#define pxMutexHolder pcTail +#define uxQueueType pcHead +#define uxRecursiveCallCount pcReadFrom +#define queueQUEUE_IS_MUTEX NULL + +/* Semaphores do not actually store or copy data, so have an items size of +zero. */ +#define queueSEMAPHORE_QUEUE_ITEM_LENGTH ( 0 ) +#define queueDONT_BLOCK ( ( portTickType ) 0 ) +#define queueMUTEX_GIVE_BLOCK_TIME ( ( portTickType ) 0 ) + +/* + * Definition of the queue used by the scheduler. + * Items are queued by copy, not reference. + */ +typedef struct QueueDefinition +{ + signed char *pcHead; /*< Points to the beginning of the queue storage area. */ + signed char *pcTail; /*< Points to the byte at the end of the queue storage area. Once more byte is allocated than necessary to store the queue items, this is used as a marker. */ + + signed char *pcWriteTo; /*< Points to the free next place in the storage area. */ + signed char *pcReadFrom; /*< Points to the last place that a queued item was read from. */ + + xList xTasksWaitingToSend; /*< List of tasks that are blocked waiting to post onto this queue. Stored in priority order. */ + xList xTasksWaitingToReceive; /*< List of tasks that are blocked waiting to read from this queue. Stored in priority order. */ + + volatile unsigned portBASE_TYPE uxMessagesWaiting;/*< The number of items currently in the queue. */ + unsigned portBASE_TYPE uxLength; /*< The length of the queue defined as the number of items it will hold, not the number of bytes. */ + unsigned portBASE_TYPE uxItemSize; /*< The size of each items that the queue will hold. */ + + signed portBASE_TYPE xRxLock; /*< Stores the number of items received from the queue (removed from the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + signed portBASE_TYPE xTxLock; /*< Stores the number of items transmitted to the queue (added to the queue) while the queue was locked. Set to queueUNLOCKED when the queue is not locked. */ + +} xQUEUE; +/*-----------------------------------------------------------*/ + +/* + * Inside this file xQueueHandle is a pointer to a xQUEUE structure. + * To keep the definition private the API header file defines it as a + * pointer to void. + */ +typedef xQUEUE * xQueueHandle; + +/* + * Prototypes for public functions are included here so we don't have to + * include the API header file (as it defines xQueueHandle differently). These + * functions are documented in the API header file. + */ +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSend( xQueueHandle xQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +void vQueueDelete( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateMutex( void ) PRIVILEGED_FUNCTION; +xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle xMutex, portTickType xBlockTime ) PRIVILEGED_FUNCTION; +portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle xMutex ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Co-routine queue functions differ from task queue functions. Co-routines are + * an optional component. + */ +#if configUSE_CO_ROUTINES == 1 + signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxTaskWoken ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; + signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) PRIVILEGED_FUNCTION; +#endif + +/* + * The queue registry is just a means for kernel aware debuggers to locate + * queue structures. It has no other purpose so is an optional component. + */ +#if configQUEUE_REGISTRY_SIZE > 0 + + /* The type stored within the queue registry array. This allows a name + to be assigned to each queue making kernel aware debugging a little + more user friendly. */ + typedef struct QUEUE_REGISTRY_ITEM + { + signed char *pcQueueName; + xQueueHandle xHandle; + } xQueueRegistryItem; + + /* The queue registry is simply an array of xQueueRegistryItem structures. + The pcQueueName member of a structure being NULL is indicative of the + array position being vacant. */ + xQueueRegistryItem xQueueRegistry[ configQUEUE_REGISTRY_SIZE ]; + + /* Removes a queue from the registry by simply setting the pcQueueName + member to NULL. */ + static void vQueueUnregisterQueue( xQueueHandle xQueue ) PRIVILEGED_FUNCTION; + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) PRIVILEGED_FUNCTION; +#endif + +/* + * Unlocks a queue locked by a call to prvLockQueue. Locking a queue does not + * prevent an ISR from adding or removing items to the queue, but does prevent + * an ISR from removing tasks from the queue event lists. If an ISR finds a + * queue is locked it will instead increment the appropriate queue lock count + * to indicate that a task may require unblocking. When the queue in unlocked + * these lock counts are inspected, and the appropriate action taken. + */ +static void prvUnlockQueue( xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any data in a queue. + * + * @return pdTRUE if the queue contains no items, otherwise pdFALSE. + */ +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Uses a critical section to determine if there is any space in a queue. + * + * @return pdTRUE if there is no space, otherwise pdFALSE; + */ +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) PRIVILEGED_FUNCTION; + +/* + * Copies an item into the queue, either at the front of the queue or the + * back of the queue. + */ +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) PRIVILEGED_FUNCTION; + +/* + * Copies an item out of a queue. + */ +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) PRIVILEGED_FUNCTION; +/*-----------------------------------------------------------*/ + +/* + * Macro to mark a queue as locked. Locking a queue prevents an ISR from + * accessing the queue event lists. + */ +#define prvLockQueue( pxQueue ) \ +{ \ + taskENTER_CRITICAL(); \ + { \ + if( pxQueue->xRxLock == queueUNLOCKED ) \ + { \ + pxQueue->xRxLock = queueLOCKED_UNMODIFIED; \ + } \ + if( pxQueue->xTxLock == queueUNLOCKED ) \ + { \ + pxQueue->xTxLock = queueLOCKED_UNMODIFIED; \ + } \ + } \ + taskEXIT_CRITICAL(); \ +} +/*-----------------------------------------------------------*/ + + +/*----------------------------------------------------------- + * PUBLIC QUEUE MANAGEMENT API documented in queue.h + *----------------------------------------------------------*/ + +xQueueHandle xQueueCreate( unsigned portBASE_TYPE uxQueueLength, unsigned portBASE_TYPE uxItemSize ) +{ +xQUEUE *pxNewQueue; +size_t xQueueSizeInBytes; + + /* Allocate the new queue structure. */ + if( uxQueueLength > ( unsigned portBASE_TYPE ) 0 ) + { + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Create the list of pointers to queue items. The queue is one byte + longer than asked for to make wrap checking easier/faster. */ + xQueueSizeInBytes = ( size_t ) ( uxQueueLength * uxItemSize ) + ( size_t ) 1; + + pxNewQueue->pcHead = ( signed char * ) pvPortMalloc( xQueueSizeInBytes ); + if( pxNewQueue->pcHead != NULL ) + { + /* Initialise the queue members as described above where the + queue type is defined. */ + pxNewQueue->pcTail = pxNewQueue->pcHead + ( uxQueueLength * uxItemSize ); + pxNewQueue->uxMessagesWaiting = 0; + pxNewQueue->pcWriteTo = pxNewQueue->pcHead; + pxNewQueue->pcReadFrom = pxNewQueue->pcHead + ( ( uxQueueLength - 1 ) * uxItemSize ); + pxNewQueue->uxLength = uxQueueLength; + pxNewQueue->uxItemSize = uxItemSize; + pxNewQueue->xRxLock = queueUNLOCKED; + pxNewQueue->xTxLock = queueUNLOCKED; + + /* Likewise ensure the event queues start with the correct state. */ + vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + + traceQUEUE_CREATE( pxNewQueue ); + return pxNewQueue; + } + else + { + traceQUEUE_CREATE_FAILED(); + vPortFree( pxNewQueue ); + } + } + } + + /* Will only reach here if we could not allocate enough memory or no memory + was required. */ + return NULL; +} +/*-----------------------------------------------------------*/ + +#if ( configUSE_MUTEXES == 1 ) + + xQueueHandle xQueueCreateMutex( void ) + { + xQUEUE *pxNewQueue; + + /* Allocate the new queue structure. */ + pxNewQueue = ( xQUEUE * ) pvPortMalloc( sizeof( xQUEUE ) ); + if( pxNewQueue != NULL ) + { + /* Information required for priority inheritance. */ + pxNewQueue->pxMutexHolder = NULL; + pxNewQueue->uxQueueType = queueQUEUE_IS_MUTEX; + + /* Queues used as a mutex no data is actually copied into or out + of the queue. */ + pxNewQueue->pcWriteTo = NULL; + pxNewQueue->pcReadFrom = NULL; + + /* Each mutex has a length of 1 (like a binary semaphore) and + an item size of 0 as nothing is actually copied into or out + of the mutex. */ + pxNewQueue->uxMessagesWaiting = 0; + pxNewQueue->uxLength = 1; + pxNewQueue->uxItemSize = 0; + pxNewQueue->xRxLock = queueUNLOCKED; + pxNewQueue->xTxLock = queueUNLOCKED; + + /* Ensure the event queues start with the correct state. */ + vListInitialise( &( pxNewQueue->xTasksWaitingToSend ) ); + vListInitialise( &( pxNewQueue->xTasksWaitingToReceive ) ); + + /* Start with the semaphore in the expected state. */ + xQueueGenericSend( pxNewQueue, NULL, 0, queueSEND_TO_BACK ); + + traceCREATE_MUTEX( pxNewQueue ); + } + else + { + traceCREATE_MUTEX_FAILED(); + } + + return pxNewQueue; + } + +#endif /* configUSE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_RECURSIVE_MUTEXES == 1 + + portBASE_TYPE xQueueGiveMutexRecursive( xQueueHandle pxMutex ) + { + portBASE_TYPE xReturn; + + /* If this is the task that holds the mutex then pxMutexHolder will not + change outside of this task. If this task does not hold the mutex then + pxMutexHolder can never coincidentally equal the tasks handle, and as + this is the only condition we are interested in it does not matter if + pxMutexHolder is accessed simultaneously by another task. Therefore no + mutual exclusion is required to test the pxMutexHolder variable. */ + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + traceGIVE_MUTEX_RECURSIVE( pxMutex ); + + /* uxRecursiveCallCount cannot be zero if pxMutexHolder is equal to + the task handle, therefore no underflow check is required. Also, + uxRecursiveCallCount is only modified by the mutex holder, and as + there can only be one, no mutual exclusion is required to modify the + uxRecursiveCallCount member. */ + ( pxMutex->uxRecursiveCallCount )--; + + /* Have we unwound the call count? */ + if( pxMutex->uxRecursiveCallCount == 0 ) + { + /* Return the mutex. This will automatically unblock any other + task that might be waiting to access the mutex. */ + xQueueGenericSend( pxMutex, NULL, queueMUTEX_GIVE_BLOCK_TIME, queueSEND_TO_BACK ); + } + + xReturn = pdPASS; + } + else + { + /* We cannot give the mutex because we are not the holder. */ + xReturn = pdFAIL; + + traceGIVE_MUTEX_RECURSIVE_FAILED( pxMutex ); + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_RECURSIVE_MUTEXES == 1 + + portBASE_TYPE xQueueTakeMutexRecursive( xQueueHandle pxMutex, portTickType xBlockTime ) + { + portBASE_TYPE xReturn; + + /* Comments regarding mutual exclusion as per those within + xQueueGiveMutexRecursive(). */ + + traceTAKE_MUTEX_RECURSIVE( pxMutex ); + + if( pxMutex->pxMutexHolder == xTaskGetCurrentTaskHandle() ) + { + ( pxMutex->uxRecursiveCallCount )++; + xReturn = pdPASS; + } + else + { + xReturn = xQueueGenericReceive( pxMutex, NULL, xBlockTime, pdFALSE ); + + /* pdPASS will only be returned if we successfully obtained the mutex, + we may have blocked to reach here. */ + if( xReturn == pdPASS ) + { + ( pxMutex->uxRecursiveCallCount )++; + } + } + + return xReturn; + } + +#endif /* configUSE_RECURSIVE_MUTEXES */ +/*-----------------------------------------------------------*/ + +#if configUSE_COUNTING_SEMAPHORES == 1 + + xQueueHandle xQueueCreateCountingSemaphore( unsigned portBASE_TYPE uxCountValue, unsigned portBASE_TYPE uxInitialCount ) + { + xQueueHandle pxHandle; + + pxHandle = xQueueCreate( ( unsigned portBASE_TYPE ) uxCountValue, queueSEMAPHORE_QUEUE_ITEM_LENGTH ); + + if( pxHandle != NULL ) + { + pxHandle->uxMessagesWaiting = uxInitialCount; + + traceCREATE_COUNTING_SEMAPHORE(); + } + else + { + traceCREATE_COUNTING_SEMAPHORE_FAILED(); + } + + return pxHandle; + } + +#endif /* configUSE_COUNTING_SEMAPHORES */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. Yes it is ok to do + this from within the critical section - the kernel + takes care of that. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting the + function. */ + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was full and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + + /* Return to the original privilege level before exiting + the function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was full and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + + /* Unlocking the queue means queue events can effect the + event list. It is possible that interrupts occurring now + remove this task from the event list again - but as the + scheduler is suspended the task will go onto the pending + ready last instead of the actual ready list. */ + prvUnlockQueue( pxQueue ); + + /* Resuming the scheduler will move tasks from the pending + ready list into the ready list - so it is feasible that this + task is already in a ready list before it yields - in which + case the yield will not cause a context switch unless there + is also a higher priority task in the pending ready list. */ + if( !xTaskResumeAll() ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + /* The timeout has expired. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + + /* Return to the original privilege level before exiting the + function. */ + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } +} +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericSend( xQueueHandle pxQueue, const void * const pvItemToQueue, portTickType xTicksToWait, portBASE_TYPE xCopyPosition ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there room on the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND( pxQueue ); + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If there was a task waiting for data to arrive on the + queue then unblock it now. */ + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) == pdTRUE ) + { + /* The unblocked task has a priority higher than + our own so yield immediately. */ + portYIELD_WITHIN_API(); + } + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + return errQUEUE_FULL; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueFull( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_SEND( pxQueue ); + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToSend ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_SEND_FAILED( pxQueue ); + return errQUEUE_FULL; + } + } + taskEXIT_CRITICAL(); + } + } + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +#if configUSE_ALTERNATIVE_API == 1 + + signed portBASE_TYPE xQueueAltGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) + { + signed portBASE_TYPE xEntryTimeSet = pdFALSE; + xTimeOutType xTimeOut; + signed char *pcOriginalReadPosition; + + for( ;; ) + { + taskENTER_CRITICAL(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + taskENTER_CRITICAL(); + { + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + portYIELD_WITHIN_API(); + } + } + else + { + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } + taskEXIT_CRITICAL(); + } + } + + +#endif /* configUSE_ALTERNATIVE_API */ +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericSendFromISR( xQueueHandle pxQueue, const void * const pvItemToQueue, signed portBASE_TYPE *pxHigherPriorityTaskWoken, portBASE_TYPE xCopyPosition ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + /* Similar to xQueueGenericSend, except we don't block if there is no room + in the queue. Also we don't directly wake a task that was blocked on a + queue read, instead we return a flag to say whether a context switch is + required or not (i.e. has a task with a higher priority than us been woken + by this post). */ + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + traceQUEUE_SEND_FROM_ISR( pxQueue ); + + prvCopyDataToQueue( pxQueue, pvItemToQueue, xCopyPosition ); + + /* If the queue is locked we do not alter the event list. This will + be done when the queue is unlocked later. */ + if( pxQueue->xTxLock == queueUNLOCKED ) + { + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + *pxHigherPriorityTaskWoken = pdTRUE; + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was posted while it was locked. */ + ++( pxQueue->xTxLock ); + } + + xReturn = pdPASS; + } + else + { + traceQUEUE_SEND_FROM_ISR_FAILED( pxQueue ); + xReturn = errQUEUE_FULL; + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueGenericReceive( xQueueHandle pxQueue, void * const pvBuffer, portTickType xTicksToWait, portBASE_TYPE xJustPeeking ) +{ +signed portBASE_TYPE xEntryTimeSet = pdFALSE; +xTimeOutType xTimeOut; +signed char *pcOriginalReadPosition; + + /* This function relaxes the coding standard somewhat to allow return + statements within the function itself. This is done in the interest + of execution time efficiency. */ + + for( ;; ) + { + taskENTER_CRITICAL(); + { + /* Is there data in the queue now? To be running we must be + the highest priority task wanting to access the queue. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Remember our read position in case we are just peeking. */ + pcOriginalReadPosition = pxQueue->pcReadFrom; + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + + if( xJustPeeking == pdFALSE ) + { + traceQUEUE_RECEIVE( pxQueue ); + + /* We are actually removing data. */ + --( pxQueue->uxMessagesWaiting ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* Record the information required to implement + priority inheritance should it become necessary. */ + pxQueue->pxMutexHolder = xTaskGetCurrentTaskHandle(); + } + } + #endif + + if( listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) == pdFALSE ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) == pdTRUE ) + { + portYIELD_WITHIN_API(); + } + } + } + else + { + traceQUEUE_PEEK( pxQueue ); + + /* We are not removing the data, so reset our read + pointer. */ + pxQueue->pcReadFrom = pcOriginalReadPosition; + + /* The data is being left in the queue, so see if there are + any other tasks waiting for the data. */ + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than this task. */ + portYIELD_WITHIN_API(); + } + } + + } + + taskEXIT_CRITICAL(); + return pdPASS; + } + else + { + if( xTicksToWait == ( portTickType ) 0 ) + { + /* The queue was empty and no block time is specified (or + the block time has expired) so leave now. */ + taskEXIT_CRITICAL(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + else if( xEntryTimeSet == pdFALSE ) + { + /* The queue was empty and a block time was specified so + configure the timeout structure. */ + vTaskSetTimeOutState( &xTimeOut ); + xEntryTimeSet = pdTRUE; + } + } + } + taskEXIT_CRITICAL(); + + /* Interrupts and other tasks can send to and receive from the queue + now the critical section has been exited. */ + + vTaskSuspendAll(); + prvLockQueue( pxQueue ); + + /* Update the timeout state to see if it has expired yet. */ + if( xTaskCheckForTimeOut( &xTimeOut, &xTicksToWait ) == pdFALSE ) + { + if( prvIsQueueEmpty( pxQueue ) ) + { + traceBLOCKING_ON_QUEUE_RECEIVE( pxQueue ); + + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + portENTER_CRITICAL(); + { + vTaskPriorityInherit( ( void * ) pxQueue->pxMutexHolder ); + } + portEXIT_CRITICAL(); + } + } + #endif + + vTaskPlaceOnEventList( &( pxQueue->xTasksWaitingToReceive ), xTicksToWait ); + prvUnlockQueue( pxQueue ); + if( !xTaskResumeAll() ) + { + portYIELD_WITHIN_API(); + } + } + else + { + /* Try again. */ + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + } + } + else + { + prvUnlockQueue( pxQueue ); + ( void ) xTaskResumeAll(); + traceQUEUE_RECEIVE_FAILED( pxQueue ); + return errQUEUE_EMPTY; + } + } +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueReceiveFromISR( xQueueHandle pxQueue, void * const pvBuffer, signed portBASE_TYPE *pxTaskWoken ) +{ +signed portBASE_TYPE xReturn; +unsigned portBASE_TYPE uxSavedInterruptStatus; + + uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); + { + /* We cannot block from an ISR, so check there is data available. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + traceQUEUE_RECEIVE_FROM_ISR( pxQueue ); + + prvCopyDataFromQueue( pxQueue, pvBuffer ); + --( pxQueue->uxMessagesWaiting ); + + /* If the queue is locked we will not modify the event list. Instead + we update the lock count so the task that unlocks the queue will know + that an ISR has removed data while the queue was locked. */ + if( pxQueue->xRxLock == queueUNLOCKED ) + { + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + /* The task waiting has a higher priority than us so + force a context switch. */ + *pxTaskWoken = pdTRUE; + } + } + } + else + { + /* Increment the lock count so the task that unlocks the queue + knows that data was removed while it was locked. */ + ++( pxQueue->xRxLock ); + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + traceQUEUE_RECEIVE_FROM_ISR_FAILED( pxQueue ); + } + } + portCLEAR_INTERRUPT_MASK_FROM_ISR( uxSavedInterruptStatus ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaiting( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + taskENTER_CRITICAL(); + uxReturn = pxQueue->uxMessagesWaiting; + taskEXIT_CRITICAL(); + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +unsigned portBASE_TYPE uxQueueMessagesWaitingFromISR( const xQueueHandle pxQueue ) +{ +unsigned portBASE_TYPE uxReturn; + + uxReturn = pxQueue->uxMessagesWaiting; + + return uxReturn; +} +/*-----------------------------------------------------------*/ + +void vQueueDelete( xQueueHandle pxQueue ) +{ + traceQUEUE_DELETE( pxQueue ); + vQueueUnregisterQueue( pxQueue ); + vPortFree( pxQueue->pcHead ); + vPortFree( pxQueue ); +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataToQueue( xQUEUE *pxQueue, const void *pvItemToQueue, portBASE_TYPE xPosition ) +{ + if( pxQueue->uxItemSize == ( unsigned portBASE_TYPE ) 0 ) + { + #if ( configUSE_MUTEXES == 1 ) + { + if( pxQueue->uxQueueType == queueQUEUE_IS_MUTEX ) + { + /* The mutex is no longer being held. */ + vTaskPriorityDisinherit( ( void * ) pxQueue->pxMutexHolder ); + pxQueue->pxMutexHolder = NULL; + } + } + #endif + } + else if( xPosition == queueSEND_TO_BACK ) + { + memcpy( ( void * ) pxQueue->pcWriteTo, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcWriteTo += pxQueue->uxItemSize; + if( pxQueue->pcWriteTo >= pxQueue->pcTail ) + { + pxQueue->pcWriteTo = pxQueue->pcHead; + } + } + else + { + memcpy( ( void * ) pxQueue->pcReadFrom, pvItemToQueue, ( unsigned ) pxQueue->uxItemSize ); + pxQueue->pcReadFrom -= pxQueue->uxItemSize; + if( pxQueue->pcReadFrom < pxQueue->pcHead ) + { + pxQueue->pcReadFrom = ( pxQueue->pcTail - pxQueue->uxItemSize ); + } + } + + ++( pxQueue->uxMessagesWaiting ); +} +/*-----------------------------------------------------------*/ + +static void prvCopyDataFromQueue( xQUEUE * const pxQueue, const void *pvBuffer ) +{ + if( pxQueue->uxQueueType != queueQUEUE_IS_MUTEX ) + { + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + } +} +/*-----------------------------------------------------------*/ + +static void prvUnlockQueue( xQueueHandle pxQueue ) +{ + /* THIS FUNCTION MUST BE CALLED WITH THE SCHEDULER SUSPENDED. */ + + /* The lock counts contains the number of extra data items placed or + removed from the queue while the queue was locked. When a queue is + locked items can be added or removed, but the event lists cannot be + updated. */ + taskENTER_CRITICAL(); + { + /* See if data was added to the queue while it was locked. */ + while( pxQueue->xTxLock > queueLOCKED_UNMODIFIED ) + { + /* Data was posted while the queue was locked. Are any tasks + blocked waiting for data to become available? */ + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + /* Tasks that are removed from the event list will get added to + the pending ready list as the scheduler is still suspended. */ + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The task waiting has a higher priority so record that a + context switch is required. */ + vTaskMissedYield(); + } + + --( pxQueue->xTxLock ); + } + else + { + break; + } + } + + pxQueue->xTxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); + + /* Do the same for the Rx lock. */ + taskENTER_CRITICAL(); + { + while( pxQueue->xRxLock > queueLOCKED_UNMODIFIED ) + { + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) + { + if( xTaskRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + vTaskMissedYield(); + } + + --( pxQueue->xRxLock ); + } + else + { + break; + } + } + + pxQueue->xRxLock = queueUNLOCKED; + } + taskEXIT_CRITICAL(); +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueEmpty( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueEmptyFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + xReturn = ( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +static signed portBASE_TYPE prvIsQueueFull( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + taskENTER_CRITICAL(); + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + taskEXIT_CRITICAL(); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +signed portBASE_TYPE xQueueIsQueueFullFromISR( const xQueueHandle pxQueue ) +{ +signed portBASE_TYPE xReturn; + + xReturn = ( pxQueue->uxMessagesWaiting == pxQueue->uxLength ); + + return xReturn; +} +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSend( xQueueHandle pxQueue, const void *pvItemToQueue, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already full we may have to block. A critical section + is required to prevent an interrupt removing something from the queue + between the check to see if the queue is full and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( prvIsQueueFull( pxQueue ) ) + { + /* The queue is full - do we want to block or just leave without + posting? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is called from a coroutine we cannot block directly, but + return indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToSend ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + /* There is room in the queue, copy the data into the queue. */ + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + xReturn = pdPASS; + + /* Were any co-routines waiting for data to become available? */ + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + /* The co-routine waiting has a higher priority so record + that a yield might be appropriate. */ + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = errQUEUE_FULL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceive( xQueueHandle pxQueue, void *pvBuffer, portTickType xTicksToWait ) +{ +signed portBASE_TYPE xReturn; + + /* If the queue is already empty we may have to block. A critical section + is required to prevent an interrupt adding something to the queue + between the check to see if the queue is empty and blocking on the queue. */ + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting == ( unsigned portBASE_TYPE ) 0 ) + { + /* There are no messages in the queue, do we want to block or just + leave with nothing? */ + if( xTicksToWait > ( portTickType ) 0 ) + { + /* As this is a co-routine we cannot block directly, but return + indicating that we need to block. */ + vCoRoutineAddToDelayedList( xTicksToWait, &( pxQueue->xTasksWaitingToReceive ) ); + portENABLE_INTERRUPTS(); + return errQUEUE_BLOCKED; + } + else + { + portENABLE_INTERRUPTS(); + return errQUEUE_FULL; + } + } + } + portENABLE_INTERRUPTS(); + + portNOP(); + + portDISABLE_INTERRUPTS(); + { + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Data is available from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + xReturn = pdPASS; + + /* Were any co-routines waiting for space to become available? */ + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) + { + /* In this instance the co-routine could be placed directly + into the ready list as we are within a critical section. + Instead the same pending ready list mechanism is used as if + the event were caused from within an interrupt. */ + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + xReturn = errQUEUE_YIELD; + } + } + } + else + { + xReturn = pdFAIL; + } + } + portENABLE_INTERRUPTS(); + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + + + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRSendFromISR( xQueueHandle pxQueue, const void *pvItemToQueue, signed portBASE_TYPE xCoRoutinePreviouslyWoken ) +{ + /* Cannot block within an ISR so if there is no space on the queue then + exit without doing anything. */ + if( pxQueue->uxMessagesWaiting < pxQueue->uxLength ) + { + prvCopyDataToQueue( pxQueue, pvItemToQueue, queueSEND_TO_BACK ); + + /* We only want to wake one co-routine per ISR, so check that a + co-routine has not already been woken. */ + if( !xCoRoutinePreviouslyWoken ) + { + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToReceive ) ) ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToReceive ) ) != pdFALSE ) + { + return pdTRUE; + } + } + } + } + + return xCoRoutinePreviouslyWoken; +} +#endif +/*-----------------------------------------------------------*/ + +#if configUSE_CO_ROUTINES == 1 +signed portBASE_TYPE xQueueCRReceiveFromISR( xQueueHandle pxQueue, void *pvBuffer, signed portBASE_TYPE *pxCoRoutineWoken ) +{ +signed portBASE_TYPE xReturn; + + /* We cannot block from an ISR, so check there is data available. If + not then just leave without doing anything. */ + if( pxQueue->uxMessagesWaiting > ( unsigned portBASE_TYPE ) 0 ) + { + /* Copy the data from the queue. */ + pxQueue->pcReadFrom += pxQueue->uxItemSize; + if( pxQueue->pcReadFrom >= pxQueue->pcTail ) + { + pxQueue->pcReadFrom = pxQueue->pcHead; + } + --( pxQueue->uxMessagesWaiting ); + memcpy( ( void * ) pvBuffer, ( void * ) pxQueue->pcReadFrom, ( unsigned ) pxQueue->uxItemSize ); + + if( !( *pxCoRoutineWoken ) ) + { + if( !listLIST_IS_EMPTY( &( pxQueue->xTasksWaitingToSend ) ) ) + { + if( xCoRoutineRemoveFromEventList( &( pxQueue->xTasksWaitingToSend ) ) != pdFALSE ) + { + *pxCoRoutineWoken = pdTRUE; + } + } + } + + xReturn = pdPASS; + } + else + { + xReturn = pdFAIL; + } + + return xReturn; +} +#endif +/*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + void vQueueAddToRegistry( xQueueHandle xQueue, signed char *pcQueueName ) + { + unsigned portBASE_TYPE ux; + + /* See if there is an empty space in the registry. A NULL name denotes + a free slot. */ + for( ux = 0; ux < configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].pcQueueName == NULL ) + { + /* Store the information on this queue. */ + xQueueRegistry[ ux ].pcQueueName = pcQueueName; + xQueueRegistry[ ux ].xHandle = xQueue; + break; + } + } + } + +#endif + /*-----------------------------------------------------------*/ + +#if configQUEUE_REGISTRY_SIZE > 0 + + static void vQueueUnregisterQueue( xQueueHandle xQueue ) + { + unsigned portBASE_TYPE ux; + + /* See if the handle of the queue being unregistered in actually in the + registry. */ + for( ux = 0; ux < configQUEUE_REGISTRY_SIZE; ux++ ) + { + if( xQueueRegistry[ ux ].xHandle == xQueue ) + { + /* Set the name to NULL to show that this slot if free again. */ + xQueueRegistry[ ux ].pcQueueName = NULL; + break; + } + } + + } + +#endif + diff --git a/flight/PiOS/posix/pios_delay.c b/flight/PiOS/posix/pios_delay.c index 6cdeabd0d..f871e11fa 100644 --- a/flight/PiOS/posix/pios_delay.c +++ b/flight/PiOS/posix/pios_delay.c @@ -1,104 +1,104 @@ -/** - ****************************************************************************** - * - * @file pios_delay.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief Delay Functions - * - Provides a micro-second granular delay using a TIM - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_DELAY Delay Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_DELAY) - -/** -* Initialises the Timer used by PIOS_DELAY functions
-* This is called from pios.c as part of the main() function -* at system start up. -* \return < 0 if initialisation failed -*/ -#include - -int32_t PIOS_DELAY_Init(void) -{ - // stub - - /* No error */ - return 0; -} - -/** -* Waits for a specific number of uS
-* Example:
-* \code -* // Wait for 500 uS -* PIOS_DELAY_Wait_uS(500); -* \endcode -* \param[in] uS delay (1..65535 microseconds) -* \return < 0 on errors -*/ +/** + ****************************************************************************** + * + * @file pios_delay.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Delay Functions + * - Provides a micro-second granular delay using a TIM + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_DELAY Delay Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_DELAY) + +/** +* Initialises the Timer used by PIOS_DELAY functions
+* This is called from pios.c as part of the main() function +* at system start up. +* \return < 0 if initialisation failed +*/ +#include + +int32_t PIOS_DELAY_Init(void) +{ + // stub + + /* No error */ + return 0; +} + +/** +* Waits for a specific number of uS
+* Example:
+* \code +* // Wait for 500 uS +* PIOS_DELAY_Wait_uS(500); +* \endcode +* \param[in] uS delay (1..65535 microseconds) +* \return < 0 on errors +*/ int32_t PIOS_DELAY_WaituS(uint32_t uS) -{ - static struct timespec wait,rest; - wait.tv_sec=0; - wait.tv_nsec=1000*uS; - while (nanosleep(&wait,&rest)!=0) { - wait=rest; - } - - /* No error */ - return 0; -} - - -/** -* Waits for a specific number of mS
-* Example:
-* \code -* // Wait for 500 mS -* PIOS_DELAY_Wait_mS(500); -* \endcode -* \param[in] mS delay (1..65535 milliseconds) -* \return < 0 on errors -*/ +{ + static struct timespec wait,rest; + wait.tv_sec=0; + wait.tv_nsec=1000*uS; + while (nanosleep(&wait,&rest)!=0) { + wait=rest; + } + + /* No error */ + return 0; +} + + +/** +* Waits for a specific number of mS
+* Example:
+* \code +* // Wait for 500 mS +* PIOS_DELAY_Wait_mS(500); +* \endcode +* \param[in] mS delay (1..65535 milliseconds) +* \return < 0 on errors +*/ int32_t PIOS_DELAY_WaitmS(uint32_t mS) -{ - //for(int i = 0; i < mS; i++) { - // PIOS_DELAY_WaituS(1000); - static struct timespec wait,rest; - wait.tv_sec=mS/1000; - wait.tv_nsec=(mS%1000)*1000000; - while (nanosleep(&wait,&rest)!=0) { - wait=rest; - } - //} - - /* No error */ - return 0; -} - +{ + //for(int i = 0; i < mS; i++) { + // PIOS_DELAY_WaituS(1000); + static struct timespec wait,rest; + wait.tv_sec=mS/1000; + wait.tv_nsec=(mS%1000)*1000000; + while (nanosleep(&wait,&rest)!=0) { + wait=rest; + } + //} + + /* No error */ + return 0; +} + /** * @brief Query the Delay timer for the current uS * @return A microsecond value @@ -139,4 +139,4 @@ uint32_t PIOS_DELAY_DiffuS(uint32_t raw) } -#endif +#endif diff --git a/flight/PiOS/posix/pios_iap.c b/flight/PiOS/posix/pios_iap.c index be5b19536..aef9f6c54 100644 --- a/flight/PiOS/posix/pios_iap.c +++ b/flight/PiOS/posix/pios_iap.c @@ -1,69 +1,69 @@ -/*! - * @File iap.c - * @Brief - * - * Created on: Sep 6, 2010 - * Author: joe - */ - - -/**************************************************************************************** - * Header files - ****************************************************************************************/ -#include - -/*! - * \brief PIOS_IAP_Init - performs required initializations for iap module. - * \param none. - * \return none. - * \retval none. - * - * Created: Sep 8, 2010 10:10:48 PM by joe - */ -void PIOS_IAP_Init( void ) -{ - -} - -/*! - * \brief Determines if an In-Application-Programming request has been made. - * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) - * \return TRUE - if correct sequence found, along with 'comm' updated. - * FALSE - Note that 'comm' will have an invalid comm identifier. - * \retval - * - */ -uint32_t PIOS_IAP_CheckRequest( void ) -{ - - return false; -} - - - -/*! - * \brief Sets the 1st word of the request sequence. - * \param n/a - * \return n/a - * \retval - */ -void PIOS_IAP_SetRequest1(void) -{ -} - -void PIOS_IAP_SetRequest2(void) -{ -} - -void PIOS_IAP_ClearRequest(void) -{ -} - -uint16_t PIOS_IAP_ReadBootCount(void) -{ - return 0; -} - -void PIOS_IAP_WriteBootCount (uint16_t boot_count) -{ -} +/*! + * @File iap.c + * @Brief + * + * Created on: Sep 6, 2010 + * Author: joe + */ + + +/**************************************************************************************** + * Header files + ****************************************************************************************/ +#include + +/*! + * \brief PIOS_IAP_Init - performs required initializations for iap module. + * \param none. + * \return none. + * \retval none. + * + * Created: Sep 8, 2010 10:10:48 PM by joe + */ +void PIOS_IAP_Init( void ) +{ + +} + +/*! + * \brief Determines if an In-Application-Programming request has been made. + * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) + * \return TRUE - if correct sequence found, along with 'comm' updated. + * FALSE - Note that 'comm' will have an invalid comm identifier. + * \retval + * + */ +uint32_t PIOS_IAP_CheckRequest( void ) +{ + + return false; +} + + + +/*! + * \brief Sets the 1st word of the request sequence. + * \param n/a + * \return n/a + * \retval + */ +void PIOS_IAP_SetRequest1(void) +{ +} + +void PIOS_IAP_SetRequest2(void) +{ +} + +void PIOS_IAP_ClearRequest(void) +{ +} + +uint16_t PIOS_IAP_ReadBootCount(void) +{ + return 0; +} + +void PIOS_IAP_WriteBootCount (uint16_t boot_count) +{ +} diff --git a/flight/PiOS/posix/pios_led.c b/flight/PiOS/posix/pios_led.c index 8e0776883..db833e1c3 100644 --- a/flight/PiOS/posix/pios_led.c +++ b/flight/PiOS/posix/pios_led.c @@ -1,102 +1,102 @@ -/** - ****************************************************************************** - * - * @file pios_led.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief LED functions, init, toggle, on & off. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_LED LED Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_LED) - -/* Private Function Prototypes */ - - -/* Local Variables */ -//static GPIO_TypeDef* LED_GPIO_PORT[PIOS_LED_NUM] = PIOS_LED_PORTS; -//static const uint32_t LED_GPIO_PIN[PIOS_LED_NUM] = PIOS_LED_PINS; -//static const uint32_t LED_GPIO_CLK[PIOS_LED_NUM] = PIOS_LED_CLKS; -static uint8_t LED_GPIO[PIOS_LED_NUM]; - - +/** + ****************************************************************************** + * + * @file pios_led.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief LED functions, init, toggle, on & off. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_LED LED Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_LED) + +/* Private Function Prototypes */ + + +/* Local Variables */ +//static GPIO_TypeDef* LED_GPIO_PORT[PIOS_LED_NUM] = PIOS_LED_PORTS; +//static const uint32_t LED_GPIO_PIN[PIOS_LED_NUM] = PIOS_LED_PINS; +//static const uint32_t LED_GPIO_CLK[PIOS_LED_NUM] = PIOS_LED_CLKS; +static uint8_t LED_GPIO[PIOS_LED_NUM]; + + static inline void PIOS_SetLED(uint32_t LED,uint8_t stat) { - printf("PIOS: LED %i status %i\n",LED,stat); - LED_GPIO[LED]=stat; -} - -/** -* Initialises all the LED's -*/ -void PIOS_LED_Init(void) -{ - //GPIO_InitTypeDef GPIO_InitStructure; - //GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; - //GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - - for(int LEDNum = 0; LEDNum < PIOS_LED_NUM; LEDNum++) { - //RCC_APB2PeriphClockCmd(LED_GPIO_CLK[LEDNum], ENABLE); - //GPIO_InitStructure.GPIO_Pin = LED_GPIO_PIN[LEDNum]; - //GPIO_Init(LED_GPIO_PORT[LEDNum], &GPIO_InitStructure); - - /* LED's Off */ - //LED_GPIO_PORT[LEDNum]->BSRR = LED_GPIO_PIN[LEDNum]; - LED_GPIO[LEDNum]=0; - } -} - - -/** -* Turn on LED -* \param[in] LED LED Name (LED1, LED2) -*/ + printf("PIOS: LED %i status %i\n",LED,stat); + LED_GPIO[LED]=stat; +} + +/** +* Initialises all the LED's +*/ +void PIOS_LED_Init(void) +{ + //GPIO_InitTypeDef GPIO_InitStructure; + //GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + //GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + + for(int LEDNum = 0; LEDNum < PIOS_LED_NUM; LEDNum++) { + //RCC_APB2PeriphClockCmd(LED_GPIO_CLK[LEDNum], ENABLE); + //GPIO_InitStructure.GPIO_Pin = LED_GPIO_PIN[LEDNum]; + //GPIO_Init(LED_GPIO_PORT[LEDNum], &GPIO_InitStructure); + + /* LED's Off */ + //LED_GPIO_PORT[LEDNum]->BSRR = LED_GPIO_PIN[LEDNum]; + LED_GPIO[LEDNum]=0; + } +} + + +/** +* Turn on LED +* \param[in] LED LED Name (LED1, LED2) +*/ void PIOS_LED_On(uint32_t LED) -{ - //LED_GPIO_PORT[LED]->BRR = LED_GPIO_PIN[LED]; - PIOS_SetLED(LED,1); -} - - -/** -* Turn off LED -* \param[in] LED LED Name (LED1, LED2) -*/ +{ + //LED_GPIO_PORT[LED]->BRR = LED_GPIO_PIN[LED]; + PIOS_SetLED(LED,1); +} + + +/** +* Turn off LED +* \param[in] LED LED Name (LED1, LED2) +*/ void PIOS_LED_Off(uint32_t LED) -{ - //LED_GPIO_PORT[LED]->BSRR = LED_GPIO_PIN[LED]; - PIOS_SetLED(LED,0); -} - - -/** -* Toggle LED on/off -* \param[in] LED LED Name (LED1, LED2) -*/ +{ + //LED_GPIO_PORT[LED]->BSRR = LED_GPIO_PIN[LED]; + PIOS_SetLED(LED,0); +} + + +/** +* Toggle LED on/off +* \param[in] LED LED Name (LED1, LED2) +*/ void PIOS_LED_Toggle(uint32_t LED) -{ - //LED_GPIO_PORT[LED]->ODR ^= LED_GPIO_PIN[LED]; - PIOS_SetLED(LED,LED_GPIO[LED]?0:1); -} - -#endif +{ + //LED_GPIO_PORT[LED]->ODR ^= LED_GPIO_PIN[LED]; + PIOS_SetLED(LED,LED_GPIO[LED]?0:1); +} + +#endif diff --git a/flight/PiOS/posix/pios_sdcard.c b/flight/PiOS/posix/pios_sdcard.c index d9e0b3760..9aff090f0 100644 --- a/flight/PiOS/posix/pios_sdcard.c +++ b/flight/PiOS/posix/pios_sdcard.c @@ -1,300 +1,300 @@ -/** - ****************************************************************************** - * - * @file pios_sdcard.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief Sets up basic system hardware, functions are called from Main. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_SDCARD SDCard Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_SDCARD) - - -/** -* Initialises SPI pins and peripheral to access MMC/SD Card -* \param[in] mode currently only mode 0 supported -* \return < 0 if initialisation failed -*/ -int32_t PIOS_SDCARD_Init(uint32_t spi_id) -{ - /* No error */ - return 0; -} - - -/** -* Connects to SD Card -* \return < 0 if initialisation sequence failed -*/ -int32_t PIOS_SDCARD_PowerOn(void) -{ - return 0; /* Status should be 0 if nothing went wrong! */ -} - - -/** -* Disconnects from SD Card -* \return < 0 on errors -*/ -int32_t PIOS_SDCARD_PowerOff(void) -{ - return 0; // no error -} - - -/** -* If SD card was previously available: Checks if the SD Card is still -* available by sending the STATUS command.
-* This takes ca. 10 uS -* -* If SD card was previously not available: Checks if the SD Card is -* available by sending the IDLE command at low speed.
-* This takes ca. 500 uS!
-* Once we got a positive response, SDCARD_PowerOn() will be -* called by this function to initialize the card completely. -* -* Example for Connection/Disconnection detection: -* \code -* // this function is called each second from a low-priority task -* // If multiple tasks are accessing the SD card, add a semaphore/mutex -* // to avoid IO access collisions with other tasks! -* u8 sdcard_available; -* int32_t CheckSDCard(void) -* { -* // check if SD card is available -* // High speed access if the card was previously available -* u8 prev_sdcard_available = sdcard_available; -* sdcard_available = PIOS_SDCARD_CheckAvailable(prev_sdcard_available); -* -* if(sdcard_available && !prev_sdcard_available) { -* // SD Card has been connected -* -* // now it's possible to read/write sectors -* -* } else if( !sdcard_available && prev_sdcard_available ) { -* // SD Card has been disconnected -* -* // here you can notify your application about this state -* } -* -* return 0; // no error -* } -* \endcode -* \param[in] was_available should only be set if the SD card was previously available -* \return 0 if no response from SD Card -* \return 1 if SD card is accessible -*/ -int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available) -{ - return 1; /* 1 = available, 0 = not available. */ -} - - -/** -* Sends command to SD card -* \param[in] cmd SD card command -* \param[in] addr 32bit address -* \param[in] crc precalculated CRC -* \return >= 0x00 if command has been sent successfully (contains received byte) -* \return -1 if no response from SD Card (timeout) -*/ -int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc) -{ - return -1; -} - - -/** -* Reads 512 bytes from selected sector -* \param[in] sector 32bit sector -* \param[in] *buffer pointer to 512 byte buffer -* \return 0 if whole sector has been successfully read -* \return -error if error occured during read operation:
-*
    -*
  • Bit 0 - In idle state if 1 -*
  • Bit 1 - Erase Reset if 1 -*
  • Bit 2 - Illgal Command if 1 -*
  • Bit 3 - Com CRC Error if 1 -*
  • Bit 4 - Erase Sequence Error if 1 -*
  • Bit 5 - Address Error if 1 -*
  • Bit 6 - Parameter Error if 1 -*
  • Bit 7 - Not used, always '0' -*
-* \return -256 if timeout during command has been sent -* \return -257 if timeout while waiting for start token -*/ -int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer) -{ - return -256; -} - - -/** -* Writes 512 bytes into selected sector -* \param[in] sector 32bit sector -* \param[in] *buffer pointer to 512 byte buffer -* \return 0 if whole sector has been successfully read -* \return -error if error occured during read operation:
-*
    -*
  • Bit 0 - In idle state if 1 -*
  • Bit 1 - Erase Reset if 1 -*
  • Bit 2 - Illgal Command if 1 -*
  • Bit 3 - Com CRC Error if 1 -*
  • Bit 4 - Erase Sequence Error if 1 -*
  • Bit 5 - Address Error if 1 -*
  • Bit 6 - Parameter Error if 1 -*
  • Bit 7 - Not used, always '0' -*
-* \return -256 if timeout during command has been sent -* \return -257 if write operation not accepted -* \return -258 if timeout during write operation -*/ -int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer) -{ - return -256; -} - - -/** -* Reads the CID informations from SD Card -* \param[in] *cid pointer to buffer which holds the CID informations -* \return 0 if the informations haven been successfully read -* \return -error if error occured during read operation -* \return -256 if timeout during command has been sent -* \return -257 if timeout while waiting for start token -*/ -int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid) -{ - return -256; -} - -/** -* Reads the CSD informations from SD Card -* \param[in] *csd pointer to buffer which holds the CSD informations -* \return 0 if the informations haven been successfully read -* \return -error if error occured during read operation -* \return -256 if timeout during command has been sent -* \return -257 if timeout while waiting for start token -*/ -int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd) -{ - return -256; -} - -/** -* Attempts to write a startup log to the SDCard -* return 0 No errors -* return -1 Error deleting file -* return -2 Error opening file -* return -3 Error writing file -*/ -int32_t PIOS_SDCARD_StartupLog(void) -{ - return -3; -} - -/** - * Check if the SD card has been mounted - * @return 0 if no - * @return 1 if yes - */ -int32_t PIOS_SDCARD_IsMounted() -{ - return 1; -} - -/** -* Mounts the file system -* param[in] CreateStartupLog 1 = True, 0 = False -* return 0 No errors -* return -1 SDCard not available -* return -2 Cannot find first partition -* return -3 No volume information -* return -4 Error writing startup log file -*/ -int32_t PIOS_SDCARD_MountFS(uint32_t CreateStartupLog) -{ - return 0; -} - -/** -* Mounts the file system -* return Amount of free bytes -*/ -int32_t PIOS_SDCARD_GetFree(void) -{ - return 10240; -} - -/** -* Read from file -* return 0 No error -* return -1 DFS_ReadFile failed -* return -2 Less bytes read than expected -*/ -//int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len) -//{ - /* No error */ -// return -1; -//} - -/** -* Read a line from file -* returns Number of bytes read -*/ -//int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len) -//{ -// return -1; -//} - -/** -* Copy a file -* WARNING: This will overwrite the destination file even if it exists -* param[in] *Source Path to file to copy -* param[in] *Destination Path to destination file -* return 0 No errors -* return -1 Source file doesn't exist -* return -2 Failed to create destination file -* return -3 DFS_ReadFile failed -* return -4 DFS_WriteFile failed -*/ -int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination) -{ - return -2; -} - -/** -* Delete a file -* param[in] *Filename File to delete -* return 0 No errors -* return -1 Error deleting file -*/ -int32_t PIOS_SDCARD_FileDelete(char *Filename) -{ - return -1; -} - -#endif +/** + ****************************************************************************** + * + * @file pios_sdcard.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) + * @brief Sets up basic system hardware, functions are called from Main. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_SDCARD SDCard Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_SDCARD) + + +/** +* Initialises SPI pins and peripheral to access MMC/SD Card +* \param[in] mode currently only mode 0 supported +* \return < 0 if initialisation failed +*/ +int32_t PIOS_SDCARD_Init(uint32_t spi_id) +{ + /* No error */ + return 0; +} + + +/** +* Connects to SD Card +* \return < 0 if initialisation sequence failed +*/ +int32_t PIOS_SDCARD_PowerOn(void) +{ + return 0; /* Status should be 0 if nothing went wrong! */ +} + + +/** +* Disconnects from SD Card +* \return < 0 on errors +*/ +int32_t PIOS_SDCARD_PowerOff(void) +{ + return 0; // no error +} + + +/** +* If SD card was previously available: Checks if the SD Card is still +* available by sending the STATUS command.
+* This takes ca. 10 uS +* +* If SD card was previously not available: Checks if the SD Card is +* available by sending the IDLE command at low speed.
+* This takes ca. 500 uS!
+* Once we got a positive response, SDCARD_PowerOn() will be +* called by this function to initialize the card completely. +* +* Example for Connection/Disconnection detection: +* \code +* // this function is called each second from a low-priority task +* // If multiple tasks are accessing the SD card, add a semaphore/mutex +* // to avoid IO access collisions with other tasks! +* u8 sdcard_available; +* int32_t CheckSDCard(void) +* { +* // check if SD card is available +* // High speed access if the card was previously available +* u8 prev_sdcard_available = sdcard_available; +* sdcard_available = PIOS_SDCARD_CheckAvailable(prev_sdcard_available); +* +* if(sdcard_available && !prev_sdcard_available) { +* // SD Card has been connected +* +* // now it's possible to read/write sectors +* +* } else if( !sdcard_available && prev_sdcard_available ) { +* // SD Card has been disconnected +* +* // here you can notify your application about this state +* } +* +* return 0; // no error +* } +* \endcode +* \param[in] was_available should only be set if the SD card was previously available +* \return 0 if no response from SD Card +* \return 1 if SD card is accessible +*/ +int32_t PIOS_SDCARD_CheckAvailable(uint8_t was_available) +{ + return 1; /* 1 = available, 0 = not available. */ +} + + +/** +* Sends command to SD card +* \param[in] cmd SD card command +* \param[in] addr 32bit address +* \param[in] crc precalculated CRC +* \return >= 0x00 if command has been sent successfully (contains received byte) +* \return -1 if no response from SD Card (timeout) +*/ +int32_t PIOS_SDCARD_SendSDCCmd(uint8_t cmd, uint32_t addr, uint8_t crc) +{ + return -1; +} + + +/** +* Reads 512 bytes from selected sector +* \param[in] sector 32bit sector +* \param[in] *buffer pointer to 512 byte buffer +* \return 0 if whole sector has been successfully read +* \return -error if error occured during read operation:
+*
    +*
  • Bit 0 - In idle state if 1 +*
  • Bit 1 - Erase Reset if 1 +*
  • Bit 2 - Illgal Command if 1 +*
  • Bit 3 - Com CRC Error if 1 +*
  • Bit 4 - Erase Sequence Error if 1 +*
  • Bit 5 - Address Error if 1 +*
  • Bit 6 - Parameter Error if 1 +*
  • Bit 7 - Not used, always '0' +*
+* \return -256 if timeout during command has been sent +* \return -257 if timeout while waiting for start token +*/ +int32_t PIOS_SDCARD_SectorRead(uint32_t sector, uint8_t *buffer) +{ + return -256; +} + + +/** +* Writes 512 bytes into selected sector +* \param[in] sector 32bit sector +* \param[in] *buffer pointer to 512 byte buffer +* \return 0 if whole sector has been successfully read +* \return -error if error occured during read operation:
+*
    +*
  • Bit 0 - In idle state if 1 +*
  • Bit 1 - Erase Reset if 1 +*
  • Bit 2 - Illgal Command if 1 +*
  • Bit 3 - Com CRC Error if 1 +*
  • Bit 4 - Erase Sequence Error if 1 +*
  • Bit 5 - Address Error if 1 +*
  • Bit 6 - Parameter Error if 1 +*
  • Bit 7 - Not used, always '0' +*
+* \return -256 if timeout during command has been sent +* \return -257 if write operation not accepted +* \return -258 if timeout during write operation +*/ +int32_t PIOS_SDCARD_SectorWrite(uint32_t sector, uint8_t *buffer) +{ + return -256; +} + + +/** +* Reads the CID informations from SD Card +* \param[in] *cid pointer to buffer which holds the CID informations +* \return 0 if the informations haven been successfully read +* \return -error if error occured during read operation +* \return -256 if timeout during command has been sent +* \return -257 if timeout while waiting for start token +*/ +int32_t PIOS_SDCARD_CIDRead(SDCARDCidTypeDef *cid) +{ + return -256; +} + +/** +* Reads the CSD informations from SD Card +* \param[in] *csd pointer to buffer which holds the CSD informations +* \return 0 if the informations haven been successfully read +* \return -error if error occured during read operation +* \return -256 if timeout during command has been sent +* \return -257 if timeout while waiting for start token +*/ +int32_t PIOS_SDCARD_CSDRead(SDCARDCsdTypeDef *csd) +{ + return -256; +} + +/** +* Attempts to write a startup log to the SDCard +* return 0 No errors +* return -1 Error deleting file +* return -2 Error opening file +* return -3 Error writing file +*/ +int32_t PIOS_SDCARD_StartupLog(void) +{ + return -3; +} + +/** + * Check if the SD card has been mounted + * @return 0 if no + * @return 1 if yes + */ +int32_t PIOS_SDCARD_IsMounted() +{ + return 1; +} + +/** +* Mounts the file system +* param[in] CreateStartupLog 1 = True, 0 = False +* return 0 No errors +* return -1 SDCard not available +* return -2 Cannot find first partition +* return -3 No volume information +* return -4 Error writing startup log file +*/ +int32_t PIOS_SDCARD_MountFS(uint32_t CreateStartupLog) +{ + return 0; +} + +/** +* Mounts the file system +* return Amount of free bytes +*/ +int32_t PIOS_SDCARD_GetFree(void) +{ + return 10240; +} + +/** +* Read from file +* return 0 No error +* return -1 DFS_ReadFile failed +* return -2 Less bytes read than expected +*/ +//int32_t PIOS_SDCARD_ReadBuffer(PFILEINFO fileinfo, uint8_t *buffer, uint32_t len) +//{ + /* No error */ +// return -1; +//} + +/** +* Read a line from file +* returns Number of bytes read +*/ +//int32_t PIOS_SDCARD_ReadLine(PFILEINFO fileinfo, uint8_t *buffer, uint32_t max_len) +//{ +// return -1; +//} + +/** +* Copy a file +* WARNING: This will overwrite the destination file even if it exists +* param[in] *Source Path to file to copy +* param[in] *Destination Path to destination file +* return 0 No errors +* return -1 Source file doesn't exist +* return -2 Failed to create destination file +* return -3 DFS_ReadFile failed +* return -4 DFS_WriteFile failed +*/ +int32_t PIOS_SDCARD_FileCopy(char *Source, char *Destination) +{ + return -2; +} + +/** +* Delete a file +* param[in] *Filename File to delete +* return 0 No errors +* return -1 Error deleting file +*/ +int32_t PIOS_SDCARD_FileDelete(char *Filename) +{ + return -1; +} + +#endif diff --git a/flight/PiOS/posix/pios_sys.c b/flight/PiOS/posix/pios_sys.c index 6b685f6fe..f4197f74e 100644 --- a/flight/PiOS/posix/pios_sys.c +++ b/flight/PiOS/posix/pios_sys.c @@ -1,196 +1,196 @@ -/** - ****************************************************************************** - * - * @file pios_sys.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief Sets up basic system hardware, functions are called from Main. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_SYS System Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_SYS) - - -/* Private Function Prototypes */ -void NVIC_Configuration(void); -void SysTick_Handler(void); - -/* Local Macros */ -#define MEM8(addr) (*((volatile uint8_t *)(addr))) - -/** -* Initialises all system peripherals -*/ -void PIOS_SYS_Init(void) -{ - - /** - * stub - */ - printf("PIOS_SYS_Init\n"); - - /* Initialise Basic NVIC */ - NVIC_Configuration(); - -#if defined(PIOS_INCLUDE_LED) - /* Initialise LEDs */ - PIOS_LED_Init(); -#endif -} - -/** -* Shutdown PIOS and reset the microcontroller:
-*
    -*
  • Disable all RTOS tasks -*
  • Disable all interrupts -*
  • Turn off all board LEDs -*
  • Reset STM32 -*
-* \return < 0 if reset failed -*/ -int32_t PIOS_SYS_Reset(void) -{ - /** - * stub - */ - printf("PIOS_SYS_Reset\n"); - /* Disable all RTOS tasks */ -#if defined(PIOS_INCLUDE_FREERTOS) - /* port specific FreeRTOS function to disable tasks (nested) */ - portENTER_CRITICAL(); -#endif - - // disable all interrupts - //PIOS_IRQ_Disable(); - - // turn off all board LEDs - #if (PIOS_LED_NUM == 1) - PIOS_LED_Off(LED1); - #elif (PIOS_LED_NUM == 2) - PIOS_LED_Off(LED1); - PIOS_LED_Off(LED2); - #endif - - - - /* Reset STM32 */ - //RCC_APB2PeriphResetCmd(0xfffffff8, ENABLE); /* MBHP_CORE_STM32: don't reset GPIOA/AF due to USB pins */ - //RCC_APB1PeriphResetCmd(0xff7fffff, ENABLE); /* don't reset USB, so that the connection can survive! */ - - //RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); - //RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); - //SCB->AIRCR = NVIC_AIRCR_VECTKEY | (1 << NVIC_VECTRESET); - exit(1); - - while(1); - - /* We will never reach this point */ - return -1; -} - -/** -* Returns the serial number as a string -* param[out] uint8_t pointer to a string which can store at least 12 bytes -* (12 bytes returned for STM32) -* return < 0 if feature not supported -*/ -int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array) -{ - /* Stored in the so called "electronic signature" */ - for (int i = 0; i < PIOS_SYS_SERIAL_NUM_BINARY_LEN; ++i) { - array[i] = 0xff; - } - - /* No error */ - return 0; -} - -/** -* Returns the serial number as a string -* param[out] str pointer to a string which can store at least 32 digits + zero terminator! -* (24 digits returned for STM32) -* return < 0 if feature not supported -*/ -int32_t PIOS_SYS_SerialNumberGet(char *str) -{ - /* Stored in the so called "electronic signature" */ - int i; - for (i = 0; i < PIOS_SYS_SERIAL_NUM_ASCII_LEN; ++i) { - str[i] = 'F'; - } - str[i] = '\0'; - - /* No error */ - return 0; -} - -/** -* Configures Vector Table base location and SysTick -*/ -void NVIC_Configuration(void) -{ - /** - * stub - */ - printf("NVIC_Configuration\n"); - /* Set the Vector Table base address as specified in .ld file */ - //NVIC_SetVectorTable(PIOS_NVIC_VECTTAB_FLASH, 0x0); - - /* 4 bits for Interrupt priorities so no sub priorities */ - //NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4); - - /* Configure HCLK clock as SysTick clock source. */ - //SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK); -} - -#ifdef USE_FULL_ASSERT -/** -* Reports the name of the source file and the source line number -* where the assert_param error has occurred. -* \param[in] file pointer to the source file name -* \param[in] line assert_param error line source number -* \retval None -*/ -void assert_failed(uint8_t* file, uint32_t line) -{ - /* When serial debugging is implemented, use something like this. */ - /* printf("Wrong parameters value: file %s on line %d\r\n", file, line); */ - printf("Wrong parameters value: file %s on line %d\r\n", file, line); - - /* Setup the LEDs to Alternate */ - PIOS_LED_On(LED1); - PIOS_LED_Off(LED2); - - /* Infinite loop */ - while (1) - { - PIOS_LED_Toggle(LED1); - PIOS_LED_Toggle(LED2); - for(int i = 0; i < 1000000; i++); - } -} -#endif - -#endif +/** + ****************************************************************************** + * + * @file pios_sys.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Sets up basic system hardware, functions are called from Main. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_SYS System Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_SYS) + + +/* Private Function Prototypes */ +void NVIC_Configuration(void); +void SysTick_Handler(void); + +/* Local Macros */ +#define MEM8(addr) (*((volatile uint8_t *)(addr))) + +/** +* Initialises all system peripherals +*/ +void PIOS_SYS_Init(void) +{ + + /** + * stub + */ + printf("PIOS_SYS_Init\n"); + + /* Initialise Basic NVIC */ + NVIC_Configuration(); + +#if defined(PIOS_INCLUDE_LED) + /* Initialise LEDs */ + PIOS_LED_Init(); +#endif +} + +/** +* Shutdown PIOS and reset the microcontroller:
+*
    +*
  • Disable all RTOS tasks +*
  • Disable all interrupts +*
  • Turn off all board LEDs +*
  • Reset STM32 +*
+* \return < 0 if reset failed +*/ +int32_t PIOS_SYS_Reset(void) +{ + /** + * stub + */ + printf("PIOS_SYS_Reset\n"); + /* Disable all RTOS tasks */ +#if defined(PIOS_INCLUDE_FREERTOS) + /* port specific FreeRTOS function to disable tasks (nested) */ + portENTER_CRITICAL(); +#endif + + // disable all interrupts + //PIOS_IRQ_Disable(); + + // turn off all board LEDs + #if (PIOS_LED_NUM == 1) + PIOS_LED_Off(LED1); + #elif (PIOS_LED_NUM == 2) + PIOS_LED_Off(LED1); + PIOS_LED_Off(LED2); + #endif + + + + /* Reset STM32 */ + //RCC_APB2PeriphResetCmd(0xfffffff8, ENABLE); /* MBHP_CORE_STM32: don't reset GPIOA/AF due to USB pins */ + //RCC_APB1PeriphResetCmd(0xff7fffff, ENABLE); /* don't reset USB, so that the connection can survive! */ + + //RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); + //RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); + //SCB->AIRCR = NVIC_AIRCR_VECTKEY | (1 << NVIC_VECTRESET); + exit(1); + + while(1); + + /* We will never reach this point */ + return -1; +} + +/** +* Returns the serial number as a string +* param[out] uint8_t pointer to a string which can store at least 12 bytes +* (12 bytes returned for STM32) +* return < 0 if feature not supported +*/ +int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array) +{ + /* Stored in the so called "electronic signature" */ + for (int i = 0; i < PIOS_SYS_SERIAL_NUM_BINARY_LEN; ++i) { + array[i] = 0xff; + } + + /* No error */ + return 0; +} + +/** +* Returns the serial number as a string +* param[out] str pointer to a string which can store at least 32 digits + zero terminator! +* (24 digits returned for STM32) +* return < 0 if feature not supported +*/ +int32_t PIOS_SYS_SerialNumberGet(char *str) +{ + /* Stored in the so called "electronic signature" */ + int i; + for (i = 0; i < PIOS_SYS_SERIAL_NUM_ASCII_LEN; ++i) { + str[i] = 'F'; + } + str[i] = '\0'; + + /* No error */ + return 0; +} + +/** +* Configures Vector Table base location and SysTick +*/ +void NVIC_Configuration(void) +{ + /** + * stub + */ + printf("NVIC_Configuration\n"); + /* Set the Vector Table base address as specified in .ld file */ + //NVIC_SetVectorTable(PIOS_NVIC_VECTTAB_FLASH, 0x0); + + /* 4 bits for Interrupt priorities so no sub priorities */ + //NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4); + + /* Configure HCLK clock as SysTick clock source. */ + //SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK); +} + +#ifdef USE_FULL_ASSERT +/** +* Reports the name of the source file and the source line number +* where the assert_param error has occurred. +* \param[in] file pointer to the source file name +* \param[in] line assert_param error line source number +* \retval None +*/ +void assert_failed(uint8_t* file, uint32_t line) +{ + /* When serial debugging is implemented, use something like this. */ + /* printf("Wrong parameters value: file %s on line %d\r\n", file, line); */ + printf("Wrong parameters value: file %s on line %d\r\n", file, line); + + /* Setup the LEDs to Alternate */ + PIOS_LED_On(LED1); + PIOS_LED_Off(LED2); + + /* Infinite loop */ + while (1) + { + PIOS_LED_Toggle(LED1); + PIOS_LED_Toggle(LED2); + for(int i = 0; i < 1000000; i++); + } +} +#endif + +#endif diff --git a/flight/PiOS/posix/pios_udp.c b/flight/PiOS/posix/pios_udp.c index 2c98c42ee..c3e495f23 100644 --- a/flight/PiOS/posix/pios_udp.c +++ b/flight/PiOS/posix/pios_udp.c @@ -1,245 +1,245 @@ -/** - ****************************************************************************** - * - * @file pios_udp.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief UDP commands. Inits UDPs, controls UDPs & Interupt handlers. - * @see The GNU Public License (GPL) Version 3 - * @defgroup PIOS_UDP UDP Functions - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* Project Includes */ -#include "pios.h" - -#if defined(PIOS_INCLUDE_UDP) - -#include -#include - -/* We need a list of UDP devices */ - -#define PIOS_UDP_MAX_DEV 256 -static int8_t pios_udp_num_devices = 0; - -static pios_udp_dev pios_udp_devices[PIOS_UDP_MAX_DEV]; - - - -/* Provide a COM driver */ -static void PIOS_UDP_ChangeBaud(uint32_t udp_id, uint32_t baud); -static void PIOS_UDP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context); -static void PIOS_UDP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context); -static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail); -static void PIOS_UDP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail); - -const struct pios_com_driver pios_udp_com_driver = { - .set_baud = PIOS_UDP_ChangeBaud, - .tx_start = PIOS_UDP_TxStart, - .rx_start = PIOS_UDP_RxStart, - .bind_tx_cb = PIOS_UDP_RegisterTxCallback, - .bind_rx_cb = PIOS_UDP_RegisterRxCallback, -}; - - -static pios_udp_dev * find_udp_dev_by_id (uint8_t udp) -{ - if (udp >= pios_udp_num_devices) { - /* Undefined UDP port for this board (see pios_board.c) */ - PIOS_Assert(0); - return NULL; - } - - /* Get a handle for the device configuration */ - return &(pios_udp_devices[udp]); -} - -/** - * RxThread - */ -void * PIOS_UDP_RxThread(void * udp_dev_n) -{ - - pios_udp_dev * udp_dev = (pios_udp_dev*) udp_dev_n; - - /** - * com devices never get closed except by application "reboot" - * we also never give up our mutex except for waiting - */ - while(1) { - - /** - * receive - */ - int received; - udp_dev->clientLength=sizeof(udp_dev->client); - if ((received = recvfrom(udp_dev->socket, - &udp_dev->rx_buffer, - PIOS_UDP_RX_BUFFER_SIZE, - 0, - (struct sockaddr *) &udp_dev->client, - (socklen_t*)&udp_dev->clientLength)) >= 0) - { - - /* copy received data to buffer if possible */ - /* we do NOT buffer data locally. If the com buffer can't receive, data is discarded! */ - /* (thats what the USART driver does too!) */ - bool rx_need_yield = false; - if (udp_dev->rx_in_cb) { - (void) (udp_dev->rx_in_cb)(udp_dev->rx_in_context, udp_dev->rx_buffer, received, NULL, &rx_need_yield); - } - -#if defined(PIOS_INCLUDE_FREERTOS) - if (rx_need_yield) { - vPortYieldFromISR(); - } -#endif /* PIOS_INCLUDE_FREERTOS */ - - } - - - } -} - - -/** -* Open UDP socket -*/ -int32_t PIOS_UDP_Init(uint32_t * udp_id, const struct pios_udp_cfg * cfg) -{ - - pios_udp_dev * udp_dev = &pios_udp_devices[pios_udp_num_devices]; - - pios_udp_num_devices++; - - - /* initialize */ - udp_dev->rx_in_cb = NULL; - udp_dev->tx_out_cb = NULL; - udp_dev->cfg=cfg; - - /* assign socket */ - udp_dev->socket = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP); - memset(&udp_dev->server,0,sizeof(udp_dev->server)); - memset(&udp_dev->client,0,sizeof(udp_dev->client)); - udp_dev->server.sin_family = AF_INET; - udp_dev->server.sin_addr.s_addr = inet_addr(udp_dev->cfg->ip); - udp_dev->server.sin_port = htons(udp_dev->cfg->port); - int res= bind(udp_dev->socket, (struct sockaddr *)&udp_dev->server,sizeof(udp_dev->server)); - - /* Create transmit thread for this connection */ +/** + ****************************************************************************** + * + * @file pios_udp.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief UDP commands. Inits UDPs, controls UDPs & Interupt handlers. + * @see The GNU Public License (GPL) Version 3 + * @defgroup PIOS_UDP UDP Functions + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_UDP) + +#include +#include + +/* We need a list of UDP devices */ + +#define PIOS_UDP_MAX_DEV 256 +static int8_t pios_udp_num_devices = 0; + +static pios_udp_dev pios_udp_devices[PIOS_UDP_MAX_DEV]; + + + +/* Provide a COM driver */ +static void PIOS_UDP_ChangeBaud(uint32_t udp_id, uint32_t baud); +static void PIOS_UDP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context); +static void PIOS_UDP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context); +static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail); +static void PIOS_UDP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail); + +const struct pios_com_driver pios_udp_com_driver = { + .set_baud = PIOS_UDP_ChangeBaud, + .tx_start = PIOS_UDP_TxStart, + .rx_start = PIOS_UDP_RxStart, + .bind_tx_cb = PIOS_UDP_RegisterTxCallback, + .bind_rx_cb = PIOS_UDP_RegisterRxCallback, +}; + + +static pios_udp_dev * find_udp_dev_by_id (uint8_t udp) +{ + if (udp >= pios_udp_num_devices) { + /* Undefined UDP port for this board (see pios_board.c) */ + PIOS_Assert(0); + return NULL; + } + + /* Get a handle for the device configuration */ + return &(pios_udp_devices[udp]); +} + +/** + * RxThread + */ +void * PIOS_UDP_RxThread(void * udp_dev_n) +{ + + pios_udp_dev * udp_dev = (pios_udp_dev*) udp_dev_n; + + /** + * com devices never get closed except by application "reboot" + * we also never give up our mutex except for waiting + */ + while(1) { + + /** + * receive + */ + int received; + udp_dev->clientLength=sizeof(udp_dev->client); + if ((received = recvfrom(udp_dev->socket, + &udp_dev->rx_buffer, + PIOS_UDP_RX_BUFFER_SIZE, + 0, + (struct sockaddr *) &udp_dev->client, + (socklen_t*)&udp_dev->clientLength)) >= 0) + { + + /* copy received data to buffer if possible */ + /* we do NOT buffer data locally. If the com buffer can't receive, data is discarded! */ + /* (thats what the USART driver does too!) */ + bool rx_need_yield = false; + if (udp_dev->rx_in_cb) { + (void) (udp_dev->rx_in_cb)(udp_dev->rx_in_context, udp_dev->rx_buffer, received, NULL, &rx_need_yield); + } + +#if defined(PIOS_INCLUDE_FREERTOS) + if (rx_need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ + + } + + + } +} + + +/** +* Open UDP socket +*/ +int32_t PIOS_UDP_Init(uint32_t * udp_id, const struct pios_udp_cfg * cfg) +{ + + pios_udp_dev * udp_dev = &pios_udp_devices[pios_udp_num_devices]; + + pios_udp_num_devices++; + + + /* initialize */ + udp_dev->rx_in_cb = NULL; + udp_dev->tx_out_cb = NULL; + udp_dev->cfg=cfg; + + /* assign socket */ + udp_dev->socket = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP); + memset(&udp_dev->server,0,sizeof(udp_dev->server)); + memset(&udp_dev->client,0,sizeof(udp_dev->client)); + udp_dev->server.sin_family = AF_INET; + udp_dev->server.sin_addr.s_addr = inet_addr(udp_dev->cfg->ip); + udp_dev->server.sin_port = htons(udp_dev->cfg->port); + int res= bind(udp_dev->socket, (struct sockaddr *)&udp_dev->server,sizeof(udp_dev->server)); + + /* Create transmit thread for this connection */ #if defined(PIOS_INCLUDE_FREERTOS) //( pdTASK_CODE pvTaskCode, const portCHAR * const pcName, unsigned portSHORT usStackDepth, void *pvParameters, unsigned portBASE_TYPE uxPriority, xTaskHandle *pvCreatedTask ); xTaskCreate((pdTASK_CODE)PIOS_UDP_RxThread, (const signed char *)"UDP_Rx_Thread",1024,(void*)udp_dev,(tskIDLE_PRIORITY + 1),&udp_dev->rxThread); #else - pthread_create(&udp_dev->rxThread, NULL, PIOS_UDP_RxThread, (void*)udp_dev); + pthread_create(&udp_dev->rxThread, NULL, PIOS_UDP_RxThread, (void*)udp_dev); #endif - - printf("udp dev %i - socket %i opened - result %i\n",pios_udp_num_devices-1,udp_dev->socket,res); - - *udp_id = pios_udp_num_devices-1; - - return res; -} - - -void PIOS_UDP_ChangeBaud(uint32_t udp_id, uint32_t baud) -{ - /** - * doesn't apply! - */ -} - - -static void PIOS_UDP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail) -{ - /** - * lazy! - */ -} - - -static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail) -{ - pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); - - PIOS_Assert(udp_dev); - - int32_t length,len,rem; - - /** - * we send everything directly whenever notified of data to send (lazy!) - */ - if (udp_dev->tx_out_cb) { - while (tx_bytes_avail>0) { - bool tx_need_yield = false; - length = (udp_dev->tx_out_cb)(udp_dev->tx_out_context, udp_dev->tx_buffer, PIOS_UDP_RX_BUFFER_SIZE, NULL, &tx_need_yield); - rem = length; - while (rem>0) { - len = sendto(udp_dev->socket, udp_dev->tx_buffer+length-rem, rem, 0, - (struct sockaddr *) &udp_dev->client, - sizeof(udp_dev->client)); - if (len<=0) { - rem=0; - } else { - rem -= len; - } - } - tx_bytes_avail -= length; - } - } - -} - -static void PIOS_UDP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context) -{ - pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); - - PIOS_Assert(udp_dev); - - /* - * Order is important in these assignments since ISR uses _cb - * field to determine if it's ok to dereference _cb and _context - */ - udp_dev->rx_in_context = context; - udp_dev->rx_in_cb = rx_in_cb; -} - -static void PIOS_UDP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context) -{ - pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); - - PIOS_Assert(udp_dev); - - /* - * Order is important in these assignments since ISR uses _cb - * field to determine if it's ok to dereference _cb and _context - */ - udp_dev->tx_out_context = context; - udp_dev->tx_out_cb = tx_out_cb; -} - - - - - -#endif + + printf("udp dev %i - socket %i opened - result %i\n",pios_udp_num_devices-1,udp_dev->socket,res); + + *udp_id = pios_udp_num_devices-1; + + return res; +} + + +void PIOS_UDP_ChangeBaud(uint32_t udp_id, uint32_t baud) +{ + /** + * doesn't apply! + */ +} + + +static void PIOS_UDP_RxStart(uint32_t udp_id, uint16_t rx_bytes_avail) +{ + /** + * lazy! + */ +} + + +static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail) +{ + pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); + + PIOS_Assert(udp_dev); + + int32_t length,len,rem; + + /** + * we send everything directly whenever notified of data to send (lazy!) + */ + if (udp_dev->tx_out_cb) { + while (tx_bytes_avail>0) { + bool tx_need_yield = false; + length = (udp_dev->tx_out_cb)(udp_dev->tx_out_context, udp_dev->tx_buffer, PIOS_UDP_RX_BUFFER_SIZE, NULL, &tx_need_yield); + rem = length; + while (rem>0) { + len = sendto(udp_dev->socket, udp_dev->tx_buffer+length-rem, rem, 0, + (struct sockaddr *) &udp_dev->client, + sizeof(udp_dev->client)); + if (len<=0) { + rem=0; + } else { + rem -= len; + } + } + tx_bytes_avail -= length; + } + } + +} + +static void PIOS_UDP_RegisterRxCallback(uint32_t udp_id, pios_com_callback rx_in_cb, uint32_t context) +{ + pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); + + PIOS_Assert(udp_dev); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + udp_dev->rx_in_context = context; + udp_dev->rx_in_cb = rx_in_cb; +} + +static void PIOS_UDP_RegisterTxCallback(uint32_t udp_id, pios_com_callback tx_out_cb, uint32_t context) +{ + pios_udp_dev * udp_dev = find_udp_dev_by_id(udp_id); + + PIOS_Assert(udp_dev); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + udp_dev->tx_out_context = context; + udp_dev->tx_out_cb = tx_out_cb; +} + + + + + +#endif diff --git a/flight/PiOS/posix/pios_wdg.c b/flight/PiOS/posix/pios_wdg.c index e60bb549d..eeb4d759a 100644 --- a/flight/PiOS/posix/pios_wdg.c +++ b/flight/PiOS/posix/pios_wdg.c @@ -1,124 +1,124 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_WDG Watchdog Functions - * @brief PIOS Comamnds to initialize and clear watchdog timer - * @{ - * - * @file pios_spi.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @brief Hardware Abstraction Layer for SPI ports of STM32 - * @see The GNU Public License (GPL) Version 3 - * @notes - * - * The PIOS Watchdog provides a HAL to initialize a watchdog - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pios.h" - -/** - * @brief Initialize the watchdog timer for a specified timeout - * - * It is important to note that this function returns the achieved timeout - * for this hardware. For hardware indendence this should be checked when - * scheduling updates. Other hardware dependent details may need to be - * considered such as a window time which sets a minimum update time, - * and this function should return a recommended delay for clearing. - * - * For the STM32 nominal clock rate is 32 khz, but for the maximum clock rate of - * 60 khz and a prescalar of 4 yields a clock rate of 15 khz. The delay that is - * set in the watchdog assumes the nominal clock rate, but the delay for FreeRTOS - * to use is 75% of the minimal delay. - * - * @param[in] delayMs The delay period in ms - * @returns Maximum recommended delay between updates - */ -uint16_t PIOS_WDG_Init() -{ - return 0; -} - -/** - * @brief Register a module against the watchdog - * - * There are two ways to use PIOS WDG: this is for when - * multiple modules must be monitored. In this case they - * must first register against the watchdog system and - * only when all of the modules have been updated with the - * watchdog be cleared. Each module must have its own - * bit in the 16 bit - * - * @param[in] flag the bit this module wants to use - * @returns True if that bit is unregistered - */ -bool PIOS_WDG_RegisterFlag(uint16_t flag_requested) -{ - return true; -} - -/** - * @brief Function called by modules to indicate they are still running - * - * This function will set this flag in the active flags register (which is - * a backup regsiter) and if all the registered flags are set will clear - * the watchdog and set only this flag in the backup register - * - * @param[in] flag the flag to set - * @return true if the watchdog cleared, false if flags are pending - */ -bool PIOS_WDG_UpdateFlag(uint16_t flag) -{ - return true; -} - -/** - * @brief Returns the flags that were set at bootup - * - * This is used for diagnostics, if only one flag not set this - * was likely the module that wasn't running before reset - * - * @return The active flags register from bootup - */ -uint16_t PIOS_WDG_GetBootupFlags() -{ - return (uint16_t) 0xffff; -} - -/** - * @brief Returns the currently active flags - * - * For external monitoring - * - * @return The active flags register - */ -uint16_t PIOS_WDG_GetActiveFlags() -{ - return (uint16_t) 0xffff; -} - -/** - * @brief Clear the watchdog timer - * - * This function must be called at the appropriate delay to prevent a reset event occuring - */ -void PIOS_WDG_Clear(void) -{ -} +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_WDG Watchdog Functions + * @brief PIOS Comamnds to initialize and clear watchdog timer + * @{ + * + * @file pios_spi.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) + * @brief Hardware Abstraction Layer for SPI ports of STM32 + * @see The GNU Public License (GPL) Version 3 + * @notes + * + * The PIOS Watchdog provides a HAL to initialize a watchdog + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios.h" + +/** + * @brief Initialize the watchdog timer for a specified timeout + * + * It is important to note that this function returns the achieved timeout + * for this hardware. For hardware indendence this should be checked when + * scheduling updates. Other hardware dependent details may need to be + * considered such as a window time which sets a minimum update time, + * and this function should return a recommended delay for clearing. + * + * For the STM32 nominal clock rate is 32 khz, but for the maximum clock rate of + * 60 khz and a prescalar of 4 yields a clock rate of 15 khz. The delay that is + * set in the watchdog assumes the nominal clock rate, but the delay for FreeRTOS + * to use is 75% of the minimal delay. + * + * @param[in] delayMs The delay period in ms + * @returns Maximum recommended delay between updates + */ +uint16_t PIOS_WDG_Init() +{ + return 0; +} + +/** + * @brief Register a module against the watchdog + * + * There are two ways to use PIOS WDG: this is for when + * multiple modules must be monitored. In this case they + * must first register against the watchdog system and + * only when all of the modules have been updated with the + * watchdog be cleared. Each module must have its own + * bit in the 16 bit + * + * @param[in] flag the bit this module wants to use + * @returns True if that bit is unregistered + */ +bool PIOS_WDG_RegisterFlag(uint16_t flag_requested) +{ + return true; +} + +/** + * @brief Function called by modules to indicate they are still running + * + * This function will set this flag in the active flags register (which is + * a backup regsiter) and if all the registered flags are set will clear + * the watchdog and set only this flag in the backup register + * + * @param[in] flag the flag to set + * @return true if the watchdog cleared, false if flags are pending + */ +bool PIOS_WDG_UpdateFlag(uint16_t flag) +{ + return true; +} + +/** + * @brief Returns the flags that were set at bootup + * + * This is used for diagnostics, if only one flag not set this + * was likely the module that wasn't running before reset + * + * @return The active flags register from bootup + */ +uint16_t PIOS_WDG_GetBootupFlags() +{ + return (uint16_t) 0xffff; +} + +/** + * @brief Returns the currently active flags + * + * For external monitoring + * + * @return The active flags register + */ +uint16_t PIOS_WDG_GetActiveFlags() +{ + return (uint16_t) 0xffff; +} + +/** + * @brief Clear the watchdog timer + * + * This function must be called at the appropriate delay to prevent a reset event occuring + */ +void PIOS_WDG_Clear(void) +{ +} diff --git a/flight/targets/BootloaderUpdater/inc/pios_config.h b/flight/targets/BootloaderUpdater/inc/pios_config.h index b9a0ebb3b..7741291f7 100644 --- a/flight/targets/BootloaderUpdater/inc/pios_config.h +++ b/flight/targets/BootloaderUpdater/inc/pios_config.h @@ -1,46 +1,46 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @{ - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * Central compile time config for the project. - * In particular, pios_config.h is where you define which PiOS libraries - * and features are included in the firmware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* Enable/Disable PiOS modules */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_BL_HELPER - -#endif /* PIOS_CONFIG_H */ - -/** - * @} - * @} +/** + ****************************************************************************** + * @addtogroup OpenPilotBL OpenPilot BootLoader + * @{ + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * In particular, pios_config.h is where you define which PiOS libraries + * and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* Enable/Disable PiOS modules */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_BL_HELPER + +#endif /* PIOS_CONFIG_H */ + +/** + * @} + * @} */ diff --git a/flight/targets/BootloaderUpdater/main.c b/flight/targets/BootloaderUpdater/main.c index ff2c5ae2e..038e17cc7 100644 --- a/flight/targets/BootloaderUpdater/main.c +++ b/flight/targets/BootloaderUpdater/main.c @@ -1,167 +1,167 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @brief These files contain the code to the OpenPilot MB Bootloader. - * - * @{ - * @file main.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This is the file with the main function of the OpenPilot BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -/* Bootloader Includes */ -#include -#include -#include "pios_board_info.h" - -#define MAX_WRI_RETRYS 3 -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void FLASH_Download(); -void error(int, int); - -/* The ADDRESSES of the _binary_* symbols are the important - * data. This is non-intuitive for _binary_size where you - * might expect its value to hold the size but you'd be wrong. - */ -extern uint32_t _binary_start; -extern uint32_t _binary_end; -extern uint32_t _binary_size; -const uint32_t * embedded_image_start = (uint32_t *) &(_binary_start); -const uint32_t * embedded_image_end = (uint32_t *) &(_binary_end); -const uint32_t embedded_image_size = (uint32_t) &(_binary_size); - -int main() -{ - - PIOS_SYS_Init(); - PIOS_Board_Init(); - PIOS_LED_On(PIOS_LED_HEARTBEAT); - PIOS_DELAY_WaitmS(3000); - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - - /// Self overwrite check - uint32_t base_address = SCB->VTOR; - if ((0x08000000 + embedded_image_size) > base_address) - error(PIOS_LED_HEARTBEAT, 1); - /// - - /* - * Make sure the bootloader we're carrying is for the same - * board type and board revision as the one we're running on. - * - * Assume the bootloader in flash and the bootloader contained in - * the updater both carry a board_info_blob at the end of the image. - */ - - /* Calculate how far the board_info_blob is from the beginning of the bootloader */ - uint32_t board_info_blob_offset = (uint32_t) &pios_board_info_blob - (uint32_t)0x08000000; - - /* Use the same offset into our embedded bootloader image */ - struct pios_board_info * new_board_info_blob = (struct pios_board_info *) - ((uint32_t)embedded_image_start + board_info_blob_offset); - - /* Compare the two board info blobs to make sure they're for the same HW revision */ - if ((pios_board_info_blob.magic != new_board_info_blob->magic) || - (pios_board_info_blob.board_type != new_board_info_blob->board_type) || - (pios_board_info_blob.board_rev != new_board_info_blob->board_rev)) { - error(PIOS_LED_HEARTBEAT, 2); - } - - /* Embedded bootloader looks like it's the right one for this HW, proceed... */ - - FLASH_Unlock(); - - /// Bootloader memory space erase - uint32_t pageAddress; - pageAddress = 0x08000000; - bool fail = false; - while ((pageAddress < base_address) && (fail == false)) { - for (int retry = 0; retry < MAX_DEL_RETRYS; ++retry) { - if (FLASH_ErasePage(pageAddress) == FLASH_COMPLETE) { - fail = false; - break; - } else { - fail = true; - } - } -#ifdef STM32F10X_HD - pageAddress += 2048; -#elif defined (STM32F10X_MD) - pageAddress += 1024; -#endif - } - - if (fail == true) - error(PIOS_LED_HEARTBEAT, 3); - - - /// - - /// Bootloader programing - for (uint32_t offset = 0; offset < embedded_image_size / sizeof(uint32_t); ++offset) { - bool result = false; - PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); - for (uint8_t retry = 0; retry < MAX_WRI_RETRYS; ++retry) { - if (result == false) { - result = (FLASH_ProgramWord(0x08000000 + (offset * 4), embedded_image_start[offset]) - == FLASH_COMPLETE) ? true : false; - } - } - if (result == false) - error(PIOS_LED_HEARTBEAT, 4); - } - /// - for (uint8_t x = 0; x < 3; ++x) { - PIOS_LED_On(PIOS_LED_HEARTBEAT); - PIOS_DELAY_WaitmS(1000); - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - PIOS_DELAY_WaitmS(1000); - } - - /// Invalidate the bootloader updater so we won't run - /// the update again on the next power cycle. - FLASH_ProgramWord(base_address, 0); - FLASH_Lock(); - - for (;;) { - PIOS_DELAY_WaitmS(1000); - } - -} - -void error(int led, int code) -{ - for (;;) { - PIOS_DELAY_WaitmS(1000); - for (int x = 0; x < code; x++) { - PIOS_LED_On(led); - PIOS_DELAY_WaitmS(200); - PIOS_LED_Off(led); - PIOS_DELAY_WaitmS(1000); - } - PIOS_DELAY_WaitmS(1000); - for (int x = 0; x < 10; x++) { - PIOS_LED_On(led); - PIOS_DELAY_WaitmS(200); - PIOS_LED_Off(led); - PIOS_DELAY_WaitmS(200); - } - } +/** + ****************************************************************************** + * @addtogroup OpenPilotBL OpenPilot BootLoader + * @brief These files contain the code to the OpenPilot MB Bootloader. + * + * @{ + * @file main.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This is the file with the main function of the OpenPilot BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/* Bootloader Includes */ +#include +#include +#include "pios_board_info.h" + +#define MAX_WRI_RETRYS 3 +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void FLASH_Download(); +void error(int, int); + +/* The ADDRESSES of the _binary_* symbols are the important + * data. This is non-intuitive for _binary_size where you + * might expect its value to hold the size but you'd be wrong. + */ +extern uint32_t _binary_start; +extern uint32_t _binary_end; +extern uint32_t _binary_size; +const uint32_t * embedded_image_start = (uint32_t *) &(_binary_start); +const uint32_t * embedded_image_end = (uint32_t *) &(_binary_end); +const uint32_t embedded_image_size = (uint32_t) &(_binary_size); + +int main() +{ + + PIOS_SYS_Init(); + PIOS_Board_Init(); + PIOS_LED_On(PIOS_LED_HEARTBEAT); + PIOS_DELAY_WaitmS(3000); + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + + /// Self overwrite check + uint32_t base_address = SCB->VTOR; + if ((0x08000000 + embedded_image_size) > base_address) + error(PIOS_LED_HEARTBEAT, 1); + /// + + /* + * Make sure the bootloader we're carrying is for the same + * board type and board revision as the one we're running on. + * + * Assume the bootloader in flash and the bootloader contained in + * the updater both carry a board_info_blob at the end of the image. + */ + + /* Calculate how far the board_info_blob is from the beginning of the bootloader */ + uint32_t board_info_blob_offset = (uint32_t) &pios_board_info_blob - (uint32_t)0x08000000; + + /* Use the same offset into our embedded bootloader image */ + struct pios_board_info * new_board_info_blob = (struct pios_board_info *) + ((uint32_t)embedded_image_start + board_info_blob_offset); + + /* Compare the two board info blobs to make sure they're for the same HW revision */ + if ((pios_board_info_blob.magic != new_board_info_blob->magic) || + (pios_board_info_blob.board_type != new_board_info_blob->board_type) || + (pios_board_info_blob.board_rev != new_board_info_blob->board_rev)) { + error(PIOS_LED_HEARTBEAT, 2); + } + + /* Embedded bootloader looks like it's the right one for this HW, proceed... */ + + FLASH_Unlock(); + + /// Bootloader memory space erase + uint32_t pageAddress; + pageAddress = 0x08000000; + bool fail = false; + while ((pageAddress < base_address) && (fail == false)) { + for (int retry = 0; retry < MAX_DEL_RETRYS; ++retry) { + if (FLASH_ErasePage(pageAddress) == FLASH_COMPLETE) { + fail = false; + break; + } else { + fail = true; + } + } +#ifdef STM32F10X_HD + pageAddress += 2048; +#elif defined (STM32F10X_MD) + pageAddress += 1024; +#endif + } + + if (fail == true) + error(PIOS_LED_HEARTBEAT, 3); + + + /// + + /// Bootloader programing + for (uint32_t offset = 0; offset < embedded_image_size / sizeof(uint32_t); ++offset) { + bool result = false; + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); + for (uint8_t retry = 0; retry < MAX_WRI_RETRYS; ++retry) { + if (result == false) { + result = (FLASH_ProgramWord(0x08000000 + (offset * 4), embedded_image_start[offset]) + == FLASH_COMPLETE) ? true : false; + } + } + if (result == false) + error(PIOS_LED_HEARTBEAT, 4); + } + /// + for (uint8_t x = 0; x < 3; ++x) { + PIOS_LED_On(PIOS_LED_HEARTBEAT); + PIOS_DELAY_WaitmS(1000); + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + PIOS_DELAY_WaitmS(1000); + } + + /// Invalidate the bootloader updater so we won't run + /// the update again on the next power cycle. + FLASH_ProgramWord(base_address, 0); + FLASH_Lock(); + + for (;;) { + PIOS_DELAY_WaitmS(1000); + } + +} + +void error(int led, int code) +{ + for (;;) { + PIOS_DELAY_WaitmS(1000); + for (int x = 0; x < code; x++) { + PIOS_LED_On(led); + PIOS_DELAY_WaitmS(200); + PIOS_LED_Off(led); + PIOS_DELAY_WaitmS(1000); + } + PIOS_DELAY_WaitmS(1000); + for (int x = 0; x < 10; x++) { + PIOS_LED_On(led); + PIOS_DELAY_WaitmS(200); + PIOS_LED_Off(led); + PIOS_DELAY_WaitmS(200); + } + } } \ No newline at end of file diff --git a/flight/targets/Bootloaders/CopterControl/inc/common.h b/flight/targets/Bootloaders/CopterControl/inc/common.h index 9ecff4079..9010fddd9 100644 --- a/flight/targets/Bootloaders/CopterControl/inc/common.h +++ b/flight/targets/Bootloaders/CopterControl/inc/common.h @@ -1,115 +1,115 @@ -/** - ****************************************************************************** - * @addtogroup CopterControlBL CopterControl BootLoader - * @brief These files contain the code to the CopterControl Bootloader. - * - * @{ - * @file common.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This file contains various common defines for the BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef COMMON_H_ -#define COMMON_H_ - -//#include "board.h" - -typedef enum { - start, keepgoing, -} DownloadAction; - -/**************************************************/ -/* OP_DFU states */ -/**************************************************/ - -typedef enum { - DFUidle, //0 - uploading, //1 - wrong_packet_received, //2 - too_many_packets, //3 - too_few_packets, //4 - Last_operation_Success, //5 - downloading, //6 - BLidle, //7 - Last_operation_failed, //8 - uploadingStarting, //9 - outsideDevCapabilities, //10 - CRC_Fail,//11 - failed_jump, -//12 -} DFUStates; -/**************************************************/ -/* OP_DFU commands */ -/**************************************************/ -typedef enum { - Reserved, //0 - Req_Capabilities, //1 - Rep_Capabilities, //2 - EnterDFU, //3 - JumpFW, //4 - Reset, //5 - Abort_Operation, //6 - Upload, //7 - Op_END, //8 - Download_Req, //9 - Download, //10 - Status_Request, //11 - Status_Rep -//12 -} DFUCommands; - -typedef enum { - High_Density, Medium_Density -} DeviceType; -/**************************************************/ -/* OP_DFU transfer types */ -/**************************************************/ -typedef enum { - FW, //0 - Descript -//2 -} DFUTransfer; -/**************************************************/ -/* OP_DFU transfer port */ -/**************************************************/ -typedef enum { - Usb, //0 - Serial -//2 -} DFUPort; -/**************************************************/ -/* OP_DFU programable programable HW types */ -/**************************************************/ -typedef enum { - Self_flash, //0 - Remote_flash_via_spi -//1 -} DFUProgType; -/**************************************************/ -/* OP_DFU programable sources */ -/**************************************************/ -#define USB 0 -#define SPI 1 - -#define DownloadDelay 100000 - -#define MAX_DEL_RETRYS 3 -#define MAX_WRI_RETRYS 3 - -#endif /* COMMON_H_ */ +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file common.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains various common defines for the BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef COMMON_H_ +#define COMMON_H_ + +//#include "board.h" + +typedef enum { + start, keepgoing, +} DownloadAction; + +/**************************************************/ +/* OP_DFU states */ +/**************************************************/ + +typedef enum { + DFUidle, //0 + uploading, //1 + wrong_packet_received, //2 + too_many_packets, //3 + too_few_packets, //4 + Last_operation_Success, //5 + downloading, //6 + BLidle, //7 + Last_operation_failed, //8 + uploadingStarting, //9 + outsideDevCapabilities, //10 + CRC_Fail,//11 + failed_jump, +//12 +} DFUStates; +/**************************************************/ +/* OP_DFU commands */ +/**************************************************/ +typedef enum { + Reserved, //0 + Req_Capabilities, //1 + Rep_Capabilities, //2 + EnterDFU, //3 + JumpFW, //4 + Reset, //5 + Abort_Operation, //6 + Upload, //7 + Op_END, //8 + Download_Req, //9 + Download, //10 + Status_Request, //11 + Status_Rep +//12 +} DFUCommands; + +typedef enum { + High_Density, Medium_Density +} DeviceType; +/**************************************************/ +/* OP_DFU transfer types */ +/**************************************************/ +typedef enum { + FW, //0 + Descript +//2 +} DFUTransfer; +/**************************************************/ +/* OP_DFU transfer port */ +/**************************************************/ +typedef enum { + Usb, //0 + Serial +//2 +} DFUPort; +/**************************************************/ +/* OP_DFU programable programable HW types */ +/**************************************************/ +typedef enum { + Self_flash, //0 + Remote_flash_via_spi +//1 +} DFUProgType; +/**************************************************/ +/* OP_DFU programable sources */ +/**************************************************/ +#define USB 0 +#define SPI 1 + +#define DownloadDelay 100000 + +#define MAX_DEL_RETRYS 3 +#define MAX_WRI_RETRYS 3 + +#endif /* COMMON_H_ */ diff --git a/flight/targets/Bootloaders/CopterControl/inc/op_dfu.h b/flight/targets/Bootloaders/CopterControl/inc/op_dfu.h index e031c3364..262852fc4 100644 --- a/flight/targets/Bootloaders/CopterControl/inc/op_dfu.h +++ b/flight/targets/Bootloaders/CopterControl/inc/op_dfu.h @@ -1,60 +1,60 @@ -/** - ****************************************************************************** - * - * @file op_dfu.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __OP_DFU_H -#define __OP_DFU_H -#include "common.h" -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -typedef struct { - uint8_t programmingType; - uint8_t readWriteFlags; - uint32_t startOfUserCode; - uint32_t sizeOfCode; - uint8_t sizeOfDescription; - uint8_t BL_Version; - uint16_t devID; - DeviceType devType; - uint32_t FW_Crc; -} Device; - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported define -----------------------------------------------------------*/ -#define COMMAND 0 -#define COUNT 1 -#define DATA 5 - -/* Exported functions ------------------------------------------------------- */ -void processComand(uint8_t *Receive_Buffer); -uint32_t baseOfAdressType(uint8_t type); -uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); -void OPDfuIni(uint8_t discover); -void DataDownload(DownloadAction); -bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); -#endif /* __OP_DFU_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * + * @file op_dfu.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __OP_DFU_H +#define __OP_DFU_H +#include "common.h" +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef struct { + uint8_t programmingType; + uint8_t readWriteFlags; + uint32_t startOfUserCode; + uint32_t sizeOfCode; + uint8_t sizeOfDescription; + uint8_t BL_Version; + uint16_t devID; + DeviceType devType; + uint32_t FW_Crc; +} Device; + +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported define -----------------------------------------------------------*/ +#define COMMAND 0 +#define COUNT 1 +#define DATA 5 + +/* Exported functions ------------------------------------------------------- */ +void processComand(uint8_t *Receive_Buffer); +uint32_t baseOfAdressType(uint8_t type); +uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); +void OPDfuIni(uint8_t discover); +void DataDownload(DownloadAction); +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); +#endif /* __OP_DFU_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/targets/Bootloaders/CopterControl/inc/pios_config.h b/flight/targets/Bootloaders/CopterControl/inc/pios_config.h index 6661f0b18..d5e32c891 100644 --- a/flight/targets/Bootloaders/CopterControl/inc/pios_config.h +++ b/flight/targets/Bootloaders/CopterControl/inc/pios_config.h @@ -1,53 +1,53 @@ -/** - ****************************************************************************** - * @addtogroup CopterControlBL CopterControl BootLoader - * @brief These files contain the code to the CopterControl Bootloader. - * @{ - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * Central compile time config for the project. - * In particular, pios_config.h is where you define which PiOS libraries - * and features are included in the firmware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* Enable/Disable PiOS modules */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_COM_MSG -#define PIOS_INCLUDE_BL_HELPER -#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT - -#endif /* PIOS_CONFIG_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * @{ + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * In particular, pios_config.h is where you define which PiOS libraries + * and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* Enable/Disable PiOS modules */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_COM_MSG +#define PIOS_INCLUDE_BL_HELPER +#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT + +#endif /* PIOS_CONFIG_H */ + +/** + * @} + * @} + */ diff --git a/flight/targets/Bootloaders/CopterControl/main.c b/flight/targets/Bootloaders/CopterControl/main.c index 77c02f18b..ef1ccb240 100644 --- a/flight/targets/Bootloaders/CopterControl/main.c +++ b/flight/targets/Bootloaders/CopterControl/main.c @@ -1,205 +1,205 @@ -/** - ****************************************************************************** - * @addtogroup CopterControlBL CopterControl BootLoader - * @brief These files contain the code to the CopterControl Bootloader. - * - * @{ - * @file main.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This is the file with the main function of the OpenPilot BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -/* Bootloader Includes */ -#include -#include -#include "op_dfu.h" -#include "usb_lib.h" -#include "pios_iap.h" -#include "fifo_buffer.h" -#include "pios_com_msg.h" -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void FLASH_Download(); -#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) - -/* Private typedef -----------------------------------------------------------*/ -typedef void (*pFunction)(void); -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -pFunction Jump_To_Application; -uint32_t JumpAddress; - -/// LEDs PWM -uint32_t period1 = 5000; // 5 mS -uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS -uint32_t period2 = 5000; // 5 mS -uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS - - -//////////////////////////////////////// -uint8_t tempcount = 0; - -/* Extern variables ----------------------------------------------------------*/ -DFUStates DeviceState; -int16_t status = 0; -uint8_t JumpToApp = FALSE; -uint8_t GO_dfu = FALSE; -uint8_t USB_connected = FALSE; -uint8_t User_DFU_request = FALSE; -static uint8_t mReceive_Buffer[63]; -/* Private function prototypes -----------------------------------------------*/ -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); -uint8_t processRX(); -void jump_to_app(); - -int main() { - PIOS_SYS_Init(); - PIOS_Board_Init(); - PIOS_IAP_Init(); - - USB_connected = PIOS_USB_CableConnected(0); - - if (PIOS_IAP_CheckRequest() == TRUE) { - PIOS_DELAY_WaitmS(1000); - User_DFU_request = TRUE; - PIOS_IAP_ClearRequest(); - } - - GO_dfu = (USB_connected == TRUE) || (User_DFU_request == TRUE); - - if (GO_dfu == TRUE) { - PIOS_Board_Init(); - if (User_DFU_request == TRUE) - DeviceState = DFUidle; - else - DeviceState = BLidle; - } else - JumpToApp = TRUE; - - uint32_t stopwatch = 0; - uint32_t prev_ticks = PIOS_DELAY_GetuS(); - while (TRUE) { - /* Update the stopwatch */ - uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); - prev_ticks += elapsed_ticks; - stopwatch += elapsed_ticks; - - if (JumpToApp == TRUE) - jump_to_app(); - - switch (DeviceState) { - case Last_operation_Success: - case uploadingStarting: - case DFUidle: - period1 = 5000; - sweep_steps1 = 100; - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - case uploading: - period1 = 5000; - sweep_steps1 = 100; - period2 = 2500; - sweep_steps2 = 50; - break; - case downloading: - period1 = 2500; - sweep_steps1 = 50; - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - case BLidle: - period1 = 0; - PIOS_LED_On(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - default://error - period1 = 5000; - sweep_steps1 = 100; - period2 = 5000; - sweep_steps2 = 100; - } - - if (period1 != 0) { - if (LedPWM(period1, sweep_steps1, stopwatch)) - PIOS_LED_On(PIOS_LED_HEARTBEAT); - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else - PIOS_LED_On(PIOS_LED_HEARTBEAT); - - if (period2 != 0) { - if (LedPWM(period2, sweep_steps2, stopwatch)) - PIOS_LED_On(PIOS_LED_HEARTBEAT); - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - - if (stopwatch > 50 * 1000 * 1000) - stopwatch = 0; - if ((stopwatch > 6 * 1000 * 1000) && (DeviceState - == BLidle)) - JumpToApp = TRUE; - - processRX(); - DataDownload(start); - } -} - -void jump_to_app() { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - - if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ - FLASH_Lock(); - RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); - RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); - _SetCNTR(0); // clear interrupt mask - _SetISTR(0); // clear all requests - JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); - Jump_To_Application = (pFunction) JumpAddress; - /* Initialize user application's Stack Pointer */ - __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); - Jump_To_Application(); - } else { - DeviceState = failed_jump; - return; - } -} -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { - uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ - uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ - - uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ - if (curr_sweep & 1) { - pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ - } - return ((count % pwm_period) > pwm_duty) ? 1 : 0; -} - -uint8_t processRX() { - if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { - processComand(mReceive_Buffer); - } - return TRUE; -} - +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file main.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This is the file with the main function of the OpenPilot BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/* Bootloader Includes */ +#include +#include +#include "op_dfu.h" +#include "usb_lib.h" +#include "pios_iap.h" +#include "fifo_buffer.h" +#include "pios_com_msg.h" +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void FLASH_Download(); +#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) + +/* Private typedef -----------------------------------------------------------*/ +typedef void (*pFunction)(void); +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +pFunction Jump_To_Application; +uint32_t JumpAddress; + +/// LEDs PWM +uint32_t period1 = 5000; // 5 mS +uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS +uint32_t period2 = 5000; // 5 mS +uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS + + +//////////////////////////////////////// +uint8_t tempcount = 0; + +/* Extern variables ----------------------------------------------------------*/ +DFUStates DeviceState; +int16_t status = 0; +uint8_t JumpToApp = FALSE; +uint8_t GO_dfu = FALSE; +uint8_t USB_connected = FALSE; +uint8_t User_DFU_request = FALSE; +static uint8_t mReceive_Buffer[63]; +/* Private function prototypes -----------------------------------------------*/ +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); +uint8_t processRX(); +void jump_to_app(); + +int main() { + PIOS_SYS_Init(); + PIOS_Board_Init(); + PIOS_IAP_Init(); + + USB_connected = PIOS_USB_CableConnected(0); + + if (PIOS_IAP_CheckRequest() == TRUE) { + PIOS_DELAY_WaitmS(1000); + User_DFU_request = TRUE; + PIOS_IAP_ClearRequest(); + } + + GO_dfu = (USB_connected == TRUE) || (User_DFU_request == TRUE); + + if (GO_dfu == TRUE) { + PIOS_Board_Init(); + if (User_DFU_request == TRUE) + DeviceState = DFUidle; + else + DeviceState = BLidle; + } else + JumpToApp = TRUE; + + uint32_t stopwatch = 0; + uint32_t prev_ticks = PIOS_DELAY_GetuS(); + while (TRUE) { + /* Update the stopwatch */ + uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); + prev_ticks += elapsed_ticks; + stopwatch += elapsed_ticks; + + if (JumpToApp == TRUE) + jump_to_app(); + + switch (DeviceState) { + case Last_operation_Success: + case uploadingStarting: + case DFUidle: + period1 = 5000; + sweep_steps1 = 100; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case uploading: + period1 = 5000; + sweep_steps1 = 100; + period2 = 2500; + sweep_steps2 = 50; + break; + case downloading: + period1 = 2500; + sweep_steps1 = 50; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case BLidle: + period1 = 0; + PIOS_LED_On(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + default://error + period1 = 5000; + sweep_steps1 = 100; + period2 = 5000; + sweep_steps2 = 100; + } + + if (period1 != 0) { + if (LedPWM(period1, sweep_steps1, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_On(PIOS_LED_HEARTBEAT); + + if (period2 != 0) { + if (LedPWM(period2, sweep_steps2, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + + if (stopwatch > 50 * 1000 * 1000) + stopwatch = 0; + if ((stopwatch > 6 * 1000 * 1000) && (DeviceState + == BLidle)) + JumpToApp = TRUE; + + processRX(); + DataDownload(start); + } +} + +void jump_to_app() { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ + FLASH_Lock(); + RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); + RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); + _SetCNTR(0); // clear interrupt mask + _SetISTR(0); // clear all requests + JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); + Jump_To_Application = (pFunction) JumpAddress; + /* Initialize user application's Stack Pointer */ + __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); + Jump_To_Application(); + } else { + DeviceState = failed_jump; + return; + } +} +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { + uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ + uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ + + uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ + if (curr_sweep & 1) { + pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ + } + return ((count % pwm_period) > pwm_duty) ? 1 : 0; +} + +uint8_t processRX() { + if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { + processComand(mReceive_Buffer); + } + return TRUE; +} + diff --git a/flight/targets/Bootloaders/CopterControl/op_dfu.c b/flight/targets/Bootloaders/CopterControl/op_dfu.c index 9f98d3394..75c2bd832 100644 --- a/flight/targets/Bootloaders/CopterControl/op_dfu.c +++ b/flight/targets/Bootloaders/CopterControl/op_dfu.c @@ -1,467 +1,467 @@ -/** - ****************************************************************************** - * @addtogroup CopterControlBL CopterControl BootLoader - * @brief These files contain the code to the CopterControl Bootloader. - * - * @{ - * @file op_dfu.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This file contains the DFU commands handling code - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Includes ------------------------------------------------------------------*/ -#include "pios.h" -#include "op_dfu.h" -#include "pios_bl_helper.h" -#include "pios_com_msg.h" -#include -//programmable devices -Device devicesTable[10]; -uint8_t numberOfDevices = 0; - -DFUProgType currentProgrammingDestination; //flash, flash_trough spi -uint8_t currentDeviceCanRead; -uint8_t currentDeviceCanWrite; -Device currentDevice; - -uint8_t Buffer[64]; -uint8_t echoBuffer[64]; -uint8_t SendBuffer[64]; -uint8_t Command = 0; -uint8_t EchoReqFlag = 0; -uint8_t EchoAnsFlag = 0; -uint8_t StartFlag = 0; -uint32_t Aditionals = 0; -uint32_t SizeOfTransfer = 0; -uint32_t Expected_CRC = 0; -uint8_t SizeOfLastPacket = 0; -uint32_t Next_Packet = 0; -uint8_t TransferType; -uint32_t Count = 0; -uint32_t Data; -uint8_t Data0; -uint8_t Data1; -uint8_t Data2; -uint8_t Data3; -uint8_t offset = 0; -uint32_t aux; -//Download vars -uint32_t downSizeOfLastPacket = 0; -uint32_t downPacketTotal = 0; -uint32_t downPacketCurrent = 0; -DFUTransfer downType = 0; -/* Extern variables ----------------------------------------------------------*/ -extern DFUStates DeviceState; -extern uint8_t JumpToApp; -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -void sendData(uint8_t * buf, uint16_t size); -uint32_t CalcFirmCRC(void); - -void DataDownload(DownloadAction action) { - if ((DeviceState == downloading)) { - - uint8_t packetSize; - uint32_t offset; - uint32_t partoffset; - SendBuffer[0] = 0x01; - SendBuffer[1] = Download; - SendBuffer[2] = downPacketCurrent >> 24; - SendBuffer[3] = downPacketCurrent >> 16; - SendBuffer[4] = downPacketCurrent >> 8; - SendBuffer[5] = downPacketCurrent; - if (downPacketCurrent == downPacketTotal - 1) { - packetSize = downSizeOfLastPacket; - } else { - packetSize = 14; - } - for (uint8_t x = 0; x < packetSize; ++x) { - partoffset = (downPacketCurrent * 14 * 4) + (x * 4); - offset = baseOfAdressType(downType) + partoffset; - if (!flash_read(SendBuffer + (6 + x * 4), offset, - currentProgrammingDestination)) { - DeviceState = Last_operation_failed; - } - } - downPacketCurrent = downPacketCurrent + 1; - if (downPacketCurrent > downPacketTotal - 1) { - DeviceState = Last_operation_Success; - Aditionals = (uint32_t) Download; - } - sendData(SendBuffer + 1, 63); - } -} -void processComand(uint8_t *xReceive_Buffer) { - - Command = xReceive_Buffer[COMMAND]; -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Received COMMAND:%d|",Command); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - EchoReqFlag = (Command >> 7); - EchoAnsFlag = (Command >> 6) & 0x01; - StartFlag = (Command >> 5) & 0x01; - Count = xReceive_Buffer[COUNT] << 24; - Count += xReceive_Buffer[COUNT + 1] << 16; - Count += xReceive_Buffer[COUNT + 2] << 8; - Count += xReceive_Buffer[COUNT + 3]; - - Data = xReceive_Buffer[DATA] << 24; - Data += xReceive_Buffer[DATA + 1] << 16; - Data += xReceive_Buffer[DATA + 2] << 8; - Data += xReceive_Buffer[DATA + 3]; - Data0 = xReceive_Buffer[DATA]; - Data1 = xReceive_Buffer[DATA + 1]; - Data2 = xReceive_Buffer[DATA + 2]; - Data3 = xReceive_Buffer[DATA + 3]; - Command = Command & 0b00011111; - - if (EchoReqFlag == 1) { - memcpy(echoBuffer, Buffer, 64); - } - switch (Command) { - case EnterDFU: - if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) - || (DeviceState == DFUidle)) { - if (Data0 > 0) - OPDfuIni(TRUE); - DeviceState = DFUidle; - currentProgrammingDestination = devicesTable[Data0].programmingType; - currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; - currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 - & 0x01; - currentDevice = devicesTable[Data0]; - uint8_t result = 0; - switch (currentProgrammingDestination) { - case Self_flash: - result = PIOS_BL_HELPER_FLASH_Ini(); - break; - case Remote_flash_via_spi: - result = TRUE; - break; - default: - DeviceState = Last_operation_failed; - Aditionals = (uint16_t) Command; - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - } - break; - case Upload: - if ((DeviceState == DFUidle) || (DeviceState == uploading)) { - if ((StartFlag == 1) && (Next_Packet == 0)) { - TransferType = Data0; - SizeOfTransfer = Count; - Next_Packet = 1; - Expected_CRC = Data2 << 24; - Expected_CRC += Data3 << 16; - Expected_CRC += xReceive_Buffer[DATA + 4] << 8; - Expected_CRC += xReceive_Buffer[DATA + 5]; - SizeOfLastPacket = Data1; - - if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) - * 14 * 4 + SizeOfLastPacket * 4) == TRUE) { - DeviceState = outsideDevCapabilities; - Aditionals = (uint32_t) Command; - } else { - uint8_t result = 1; - if (TransferType == FW) { - switch (currentProgrammingDestination) { - case Self_flash: - result = PIOS_BL_HELPER_FLASH_Start(); - break; - case Remote_flash_via_spi: - result = FALSE; - break; - default: - break; - } - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } else { - - DeviceState = uploading; - } - } - } else if ((StartFlag != 1) && (Next_Packet != 0)) { - if (Count > SizeOfTransfer) { - DeviceState = too_many_packets; - Aditionals = Count; - } else if (Count == Next_Packet - 1) { - uint8_t numberOfWords = 14; - if (Count == SizeOfTransfer - 1)//is this the last packet? - { - numberOfWords = SizeOfLastPacket; - } - uint8_t result = 0; - switch (currentProgrammingDestination) { - case Self_flash: - for (uint8_t x = 0; x < numberOfWords; ++x) { - offset = 4 * x; - Data = xReceive_Buffer[DATA + offset] << 24; - Data += xReceive_Buffer[DATA + 1 + offset] << 16; - Data += xReceive_Buffer[DATA + 2 + offset] << 8; - Data += xReceive_Buffer[DATA + 3 + offset]; - aux = baseOfAdressType(TransferType) + (uint32_t)( - Count * 14 * 4 + x * 4); - result = 0; - for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { - if (result == 0) { - result = (FLASH_ProgramWord(aux, Data) - == FLASH_COMPLETE) ? 1 : 0; - } - } - } - break; - case Remote_flash_via_spi: - result = FALSE; // No support for this for the PipX - break; - default: - result = 0; - break; - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - - ++Next_Packet; - } else { - DeviceState = wrong_packet_received; - Aditionals = Count; - } - } else { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - } - break; - case Req_Capabilities: - OPDfuIni(TRUE); - Buffer[0] = 0x01; - Buffer[1] = Rep_Capabilities; - if (Data0 == 0) { - Buffer[2] = 0; - Buffer[3] = 0; - Buffer[4] = 0; - Buffer[5] = 0; - Buffer[6] = 0; - Buffer[7] = numberOfDevices; - uint16_t WRFlags = 0; - for (int x = 0; x < numberOfDevices; ++x) { - WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) - | WRFlags); - } - Buffer[8] = WRFlags >> 8; - Buffer[9] = WRFlags; - } else { - Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; - Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; - Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; - Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; - Buffer[6] = Data0; - Buffer[7] = devicesTable[Data0 - 1].BL_Version; - Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; - Buffer[9] = devicesTable[Data0 - 1].devID; - Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; - Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; - Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; - Buffer[13] = devicesTable[Data0 - 1].FW_Crc; - Buffer[14] = devicesTable[Data0 - 1].devID >> 8; - Buffer[15] = devicesTable[Data0 - 1].devID; - } - sendData(Buffer + 1, 63); - break; - case JumpFW: - if (Data == 0x5AFE) { - /* Force board into safe mode */ - PIOS_IAP_WriteBootCount(0xFFFF); - } - FLASH_Lock(); - JumpToApp = 1; - break; - case Reset: - PIOS_SYS_Reset(); - break; - case Abort_Operation: - Next_Packet = 0; - DeviceState = DFUidle; - break; - - case Op_END: - if (DeviceState == uploading) { - if (Next_Packet - 1 == SizeOfTransfer) { - Next_Packet = 0; - if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { - DeviceState = Last_operation_Success; - } else { - DeviceState = CRC_Fail; - } - } - if (Next_Packet - 1 < SizeOfTransfer) { - Next_Packet = 0; - DeviceState = too_few_packets; - } - } - break; - case Download_Req: -#ifdef DEBUG_SSP - sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - if (DeviceState == DFUidle) { -#ifdef DEBUG_SSP - PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); -#endif - downType = Data0; - downPacketTotal = Count; - downSizeOfLastPacket = Data1; - if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 - + downSizeOfLastPacket) == 1) { - DeviceState = outsideDevCapabilities; - Aditionals = (uint32_t) Command; - - } else { - downPacketCurrent = 0; - DeviceState = downloading; - } - } else { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - break; - - case Status_Request: - Buffer[0] = 0x01; - Buffer[1] = Status_Rep; - if (DeviceState == wrong_packet_received) { - Buffer[2] = Aditionals >> 24; - Buffer[3] = Aditionals >> 16; - Buffer[4] = Aditionals >> 8; - Buffer[5] = Aditionals; - } else { - Buffer[2] = 0; - Buffer[3] = ((uint16_t) Aditionals) >> 8; - Buffer[4] = ((uint16_t) Aditionals); - Buffer[5] = 0; - } - Buffer[6] = DeviceState; - Buffer[7] = 0; - Buffer[8] = 0; - Buffer[9] = 0; - sendData(Buffer + 1, 63); - if (DeviceState == Last_operation_Success) { - DeviceState = DFUidle; - } - break; - case Status_Rep: - - break; - - } - if (EchoReqFlag == 1) { - echoBuffer[1] = echoBuffer[1] | EchoAnsFlag; - sendData(echoBuffer + 1, 63); - } - return; -} -void OPDfuIni(uint8_t discover) { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - Device dev; - - dev.programmingType = Self_flash; - dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); - dev.startOfUserCode = bdinfo->fw_base; - dev.sizeOfCode = bdinfo->fw_size; - dev.sizeOfDescription = bdinfo->desc_size; - dev.BL_Version = bdinfo->bl_rev; - dev.FW_Crc = CalcFirmCRC(); - dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); - dev.devType = bdinfo->hw_type; - numberOfDevices = 1; - devicesTable[0] = dev; - if (discover) { - //TODO check other devices trough spi or whatever - } -} -uint32_t baseOfAdressType(DFUTransfer type) { - switch (type) { - case FW: - return currentDevice.startOfUserCode; - break; - case Descript: - return currentDevice.startOfUserCode + currentDevice.sizeOfCode; - break; - default: - - return 0; - } -} -uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { - switch (type) { - case FW: - return (size > currentDevice.sizeOfCode) ? 1 : 0; - break; - case Descript: - return (size > currentDevice.sizeOfDescription) ? 1 : 0; - break; - default: - return TRUE; - } -} - -uint32_t CalcFirmCRC() { - switch (currentProgrammingDestination) { - case Self_flash: - return PIOS_BL_HELPER_CRC_Memory_Calc(); - break; - case Remote_flash_via_spi: - return 0; - break; - default: - return 0; - break; - } - -} -void sendData(uint8_t * buf, uint16_t size) { - PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); -} - -bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { - switch (type) { - case Remote_flash_via_spi: - return FALSE; // We should not get this for the PipX - break; - case Self_flash: - for (uint8_t x = 0; x < 4; ++x) { - buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); - } - return TRUE; - break; - default: - return FALSE; - } -} +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file op_dfu.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains the DFU commands handling code + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Includes ------------------------------------------------------------------*/ +#include "pios.h" +#include "op_dfu.h" +#include "pios_bl_helper.h" +#include "pios_com_msg.h" +#include +//programmable devices +Device devicesTable[10]; +uint8_t numberOfDevices = 0; + +DFUProgType currentProgrammingDestination; //flash, flash_trough spi +uint8_t currentDeviceCanRead; +uint8_t currentDeviceCanWrite; +Device currentDevice; + +uint8_t Buffer[64]; +uint8_t echoBuffer[64]; +uint8_t SendBuffer[64]; +uint8_t Command = 0; +uint8_t EchoReqFlag = 0; +uint8_t EchoAnsFlag = 0; +uint8_t StartFlag = 0; +uint32_t Aditionals = 0; +uint32_t SizeOfTransfer = 0; +uint32_t Expected_CRC = 0; +uint8_t SizeOfLastPacket = 0; +uint32_t Next_Packet = 0; +uint8_t TransferType; +uint32_t Count = 0; +uint32_t Data; +uint8_t Data0; +uint8_t Data1; +uint8_t Data2; +uint8_t Data3; +uint8_t offset = 0; +uint32_t aux; +//Download vars +uint32_t downSizeOfLastPacket = 0; +uint32_t downPacketTotal = 0; +uint32_t downPacketCurrent = 0; +DFUTransfer downType = 0; +/* Extern variables ----------------------------------------------------------*/ +extern DFUStates DeviceState; +extern uint8_t JumpToApp; +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +void sendData(uint8_t * buf, uint16_t size); +uint32_t CalcFirmCRC(void); + +void DataDownload(DownloadAction action) { + if ((DeviceState == downloading)) { + + uint8_t packetSize; + uint32_t offset; + uint32_t partoffset; + SendBuffer[0] = 0x01; + SendBuffer[1] = Download; + SendBuffer[2] = downPacketCurrent >> 24; + SendBuffer[3] = downPacketCurrent >> 16; + SendBuffer[4] = downPacketCurrent >> 8; + SendBuffer[5] = downPacketCurrent; + if (downPacketCurrent == downPacketTotal - 1) { + packetSize = downSizeOfLastPacket; + } else { + packetSize = 14; + } + for (uint8_t x = 0; x < packetSize; ++x) { + partoffset = (downPacketCurrent * 14 * 4) + (x * 4); + offset = baseOfAdressType(downType) + partoffset; + if (!flash_read(SendBuffer + (6 + x * 4), offset, + currentProgrammingDestination)) { + DeviceState = Last_operation_failed; + } + } + downPacketCurrent = downPacketCurrent + 1; + if (downPacketCurrent > downPacketTotal - 1) { + DeviceState = Last_operation_Success; + Aditionals = (uint32_t) Download; + } + sendData(SendBuffer + 1, 63); + } +} +void processComand(uint8_t *xReceive_Buffer) { + + Command = xReceive_Buffer[COMMAND]; +#ifdef DEBUG_SSP + char str[63]= {0}; + sprintf(str,"Received COMMAND:%d|",Command); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + EchoReqFlag = (Command >> 7); + EchoAnsFlag = (Command >> 6) & 0x01; + StartFlag = (Command >> 5) & 0x01; + Count = xReceive_Buffer[COUNT] << 24; + Count += xReceive_Buffer[COUNT + 1] << 16; + Count += xReceive_Buffer[COUNT + 2] << 8; + Count += xReceive_Buffer[COUNT + 3]; + + Data = xReceive_Buffer[DATA] << 24; + Data += xReceive_Buffer[DATA + 1] << 16; + Data += xReceive_Buffer[DATA + 2] << 8; + Data += xReceive_Buffer[DATA + 3]; + Data0 = xReceive_Buffer[DATA]; + Data1 = xReceive_Buffer[DATA + 1]; + Data2 = xReceive_Buffer[DATA + 2]; + Data3 = xReceive_Buffer[DATA + 3]; + Command = Command & 0b00011111; + + if (EchoReqFlag == 1) { + memcpy(echoBuffer, Buffer, 64); + } + switch (Command) { + case EnterDFU: + if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) + || (DeviceState == DFUidle)) { + if (Data0 > 0) + OPDfuIni(TRUE); + DeviceState = DFUidle; + currentProgrammingDestination = devicesTable[Data0].programmingType; + currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; + currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 + & 0x01; + currentDevice = devicesTable[Data0]; + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Ini(); + break; + case Remote_flash_via_spi: + result = TRUE; + break; + default: + DeviceState = Last_operation_failed; + Aditionals = (uint16_t) Command; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Upload: + if ((DeviceState == DFUidle) || (DeviceState == uploading)) { + if ((StartFlag == 1) && (Next_Packet == 0)) { + TransferType = Data0; + SizeOfTransfer = Count; + Next_Packet = 1; + Expected_CRC = Data2 << 24; + Expected_CRC += Data3 << 16; + Expected_CRC += xReceive_Buffer[DATA + 4] << 8; + Expected_CRC += xReceive_Buffer[DATA + 5]; + SizeOfLastPacket = Data1; + + if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) + * 14 * 4 + SizeOfLastPacket * 4) == TRUE) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + } else { + uint8_t result = 1; + if (TransferType == FW) { + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Start(); + break; + case Remote_flash_via_spi: + result = FALSE; + break; + default: + break; + } + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } else { + + DeviceState = uploading; + } + } + } else if ((StartFlag != 1) && (Next_Packet != 0)) { + if (Count > SizeOfTransfer) { + DeviceState = too_many_packets; + Aditionals = Count; + } else if (Count == Next_Packet - 1) { + uint8_t numberOfWords = 14; + if (Count == SizeOfTransfer - 1)//is this the last packet? + { + numberOfWords = SizeOfLastPacket; + } + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + for (uint8_t x = 0; x < numberOfWords; ++x) { + offset = 4 * x; + Data = xReceive_Buffer[DATA + offset] << 24; + Data += xReceive_Buffer[DATA + 1 + offset] << 16; + Data += xReceive_Buffer[DATA + 2 + offset] << 8; + Data += xReceive_Buffer[DATA + 3 + offset]; + aux = baseOfAdressType(TransferType) + (uint32_t)( + Count * 14 * 4 + x * 4); + result = 0; + for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { + if (result == 0) { + result = (FLASH_ProgramWord(aux, Data) + == FLASH_COMPLETE) ? 1 : 0; + } + } + } + break; + case Remote_flash_via_spi: + result = FALSE; // No support for this for the PipX + break; + default: + result = 0; + break; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + + ++Next_Packet; + } else { + DeviceState = wrong_packet_received; + Aditionals = Count; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Req_Capabilities: + OPDfuIni(TRUE); + Buffer[0] = 0x01; + Buffer[1] = Rep_Capabilities; + if (Data0 == 0) { + Buffer[2] = 0; + Buffer[3] = 0; + Buffer[4] = 0; + Buffer[5] = 0; + Buffer[6] = 0; + Buffer[7] = numberOfDevices; + uint16_t WRFlags = 0; + for (int x = 0; x < numberOfDevices; ++x) { + WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) + | WRFlags); + } + Buffer[8] = WRFlags >> 8; + Buffer[9] = WRFlags; + } else { + Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; + Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; + Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; + Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; + Buffer[6] = Data0; + Buffer[7] = devicesTable[Data0 - 1].BL_Version; + Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; + Buffer[9] = devicesTable[Data0 - 1].devID; + Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; + Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; + Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; + Buffer[13] = devicesTable[Data0 - 1].FW_Crc; + Buffer[14] = devicesTable[Data0 - 1].devID >> 8; + Buffer[15] = devicesTable[Data0 - 1].devID; + } + sendData(Buffer + 1, 63); + break; + case JumpFW: + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); + } + FLASH_Lock(); + JumpToApp = 1; + break; + case Reset: + PIOS_SYS_Reset(); + break; + case Abort_Operation: + Next_Packet = 0; + DeviceState = DFUidle; + break; + + case Op_END: + if (DeviceState == uploading) { + if (Next_Packet - 1 == SizeOfTransfer) { + Next_Packet = 0; + if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { + DeviceState = Last_operation_Success; + } else { + DeviceState = CRC_Fail; + } + } + if (Next_Packet - 1 < SizeOfTransfer) { + Next_Packet = 0; + DeviceState = too_few_packets; + } + } + break; + case Download_Req: +#ifdef DEBUG_SSP + sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + if (DeviceState == DFUidle) { +#ifdef DEBUG_SSP + PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); +#endif + downType = Data0; + downPacketTotal = Count; + downSizeOfLastPacket = Data1; + if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 + + downSizeOfLastPacket) == 1) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + + } else { + downPacketCurrent = 0; + DeviceState = downloading; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + break; + + case Status_Request: + Buffer[0] = 0x01; + Buffer[1] = Status_Rep; + if (DeviceState == wrong_packet_received) { + Buffer[2] = Aditionals >> 24; + Buffer[3] = Aditionals >> 16; + Buffer[4] = Aditionals >> 8; + Buffer[5] = Aditionals; + } else { + Buffer[2] = 0; + Buffer[3] = ((uint16_t) Aditionals) >> 8; + Buffer[4] = ((uint16_t) Aditionals); + Buffer[5] = 0; + } + Buffer[6] = DeviceState; + Buffer[7] = 0; + Buffer[8] = 0; + Buffer[9] = 0; + sendData(Buffer + 1, 63); + if (DeviceState == Last_operation_Success) { + DeviceState = DFUidle; + } + break; + case Status_Rep: + + break; + + } + if (EchoReqFlag == 1) { + echoBuffer[1] = echoBuffer[1] | EchoAnsFlag; + sendData(echoBuffer + 1, 63); + } + return; +} +void OPDfuIni(uint8_t discover) { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + Device dev; + + dev.programmingType = Self_flash; + dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); + dev.startOfUserCode = bdinfo->fw_base; + dev.sizeOfCode = bdinfo->fw_size; + dev.sizeOfDescription = bdinfo->desc_size; + dev.BL_Version = bdinfo->bl_rev; + dev.FW_Crc = CalcFirmCRC(); + dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); + dev.devType = bdinfo->hw_type; + numberOfDevices = 1; + devicesTable[0] = dev; + if (discover) { + //TODO check other devices trough spi or whatever + } +} +uint32_t baseOfAdressType(DFUTransfer type) { + switch (type) { + case FW: + return currentDevice.startOfUserCode; + break; + case Descript: + return currentDevice.startOfUserCode + currentDevice.sizeOfCode; + break; + default: + + return 0; + } +} +uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { + switch (type) { + case FW: + return (size > currentDevice.sizeOfCode) ? 1 : 0; + break; + case Descript: + return (size > currentDevice.sizeOfDescription) ? 1 : 0; + break; + default: + return TRUE; + } +} + +uint32_t CalcFirmCRC() { + switch (currentProgrammingDestination) { + case Self_flash: + return PIOS_BL_HELPER_CRC_Memory_Calc(); + break; + case Remote_flash_via_spi: + return 0; + break; + default: + return 0; + break; + } + +} +void sendData(uint8_t * buf, uint16_t size) { + PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); +} + +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { + switch (type) { + case Remote_flash_via_spi: + return FALSE; // We should not get this for the PipX + break; + case Self_flash: + for (uint8_t x = 0; x < 4; ++x) { + buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); + } + return TRUE; + break; + default: + return FALSE; + } +} diff --git a/flight/targets/Bootloaders/OSD/inc/common.h b/flight/targets/Bootloaders/OSD/inc/common.h index 9ecff4079..9010fddd9 100644 --- a/flight/targets/Bootloaders/OSD/inc/common.h +++ b/flight/targets/Bootloaders/OSD/inc/common.h @@ -1,115 +1,115 @@ -/** - ****************************************************************************** - * @addtogroup CopterControlBL CopterControl BootLoader - * @brief These files contain the code to the CopterControl Bootloader. - * - * @{ - * @file common.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This file contains various common defines for the BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef COMMON_H_ -#define COMMON_H_ - -//#include "board.h" - -typedef enum { - start, keepgoing, -} DownloadAction; - -/**************************************************/ -/* OP_DFU states */ -/**************************************************/ - -typedef enum { - DFUidle, //0 - uploading, //1 - wrong_packet_received, //2 - too_many_packets, //3 - too_few_packets, //4 - Last_operation_Success, //5 - downloading, //6 - BLidle, //7 - Last_operation_failed, //8 - uploadingStarting, //9 - outsideDevCapabilities, //10 - CRC_Fail,//11 - failed_jump, -//12 -} DFUStates; -/**************************************************/ -/* OP_DFU commands */ -/**************************************************/ -typedef enum { - Reserved, //0 - Req_Capabilities, //1 - Rep_Capabilities, //2 - EnterDFU, //3 - JumpFW, //4 - Reset, //5 - Abort_Operation, //6 - Upload, //7 - Op_END, //8 - Download_Req, //9 - Download, //10 - Status_Request, //11 - Status_Rep -//12 -} DFUCommands; - -typedef enum { - High_Density, Medium_Density -} DeviceType; -/**************************************************/ -/* OP_DFU transfer types */ -/**************************************************/ -typedef enum { - FW, //0 - Descript -//2 -} DFUTransfer; -/**************************************************/ -/* OP_DFU transfer port */ -/**************************************************/ -typedef enum { - Usb, //0 - Serial -//2 -} DFUPort; -/**************************************************/ -/* OP_DFU programable programable HW types */ -/**************************************************/ -typedef enum { - Self_flash, //0 - Remote_flash_via_spi -//1 -} DFUProgType; -/**************************************************/ -/* OP_DFU programable sources */ -/**************************************************/ -#define USB 0 -#define SPI 1 - -#define DownloadDelay 100000 - -#define MAX_DEL_RETRYS 3 -#define MAX_WRI_RETRYS 3 - -#endif /* COMMON_H_ */ +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file common.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains various common defines for the BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef COMMON_H_ +#define COMMON_H_ + +//#include "board.h" + +typedef enum { + start, keepgoing, +} DownloadAction; + +/**************************************************/ +/* OP_DFU states */ +/**************************************************/ + +typedef enum { + DFUidle, //0 + uploading, //1 + wrong_packet_received, //2 + too_many_packets, //3 + too_few_packets, //4 + Last_operation_Success, //5 + downloading, //6 + BLidle, //7 + Last_operation_failed, //8 + uploadingStarting, //9 + outsideDevCapabilities, //10 + CRC_Fail,//11 + failed_jump, +//12 +} DFUStates; +/**************************************************/ +/* OP_DFU commands */ +/**************************************************/ +typedef enum { + Reserved, //0 + Req_Capabilities, //1 + Rep_Capabilities, //2 + EnterDFU, //3 + JumpFW, //4 + Reset, //5 + Abort_Operation, //6 + Upload, //7 + Op_END, //8 + Download_Req, //9 + Download, //10 + Status_Request, //11 + Status_Rep +//12 +} DFUCommands; + +typedef enum { + High_Density, Medium_Density +} DeviceType; +/**************************************************/ +/* OP_DFU transfer types */ +/**************************************************/ +typedef enum { + FW, //0 + Descript +//2 +} DFUTransfer; +/**************************************************/ +/* OP_DFU transfer port */ +/**************************************************/ +typedef enum { + Usb, //0 + Serial +//2 +} DFUPort; +/**************************************************/ +/* OP_DFU programable programable HW types */ +/**************************************************/ +typedef enum { + Self_flash, //0 + Remote_flash_via_spi +//1 +} DFUProgType; +/**************************************************/ +/* OP_DFU programable sources */ +/**************************************************/ +#define USB 0 +#define SPI 1 + +#define DownloadDelay 100000 + +#define MAX_DEL_RETRYS 3 +#define MAX_WRI_RETRYS 3 + +#endif /* COMMON_H_ */ diff --git a/flight/targets/Bootloaders/OSD/inc/op_dfu.h b/flight/targets/Bootloaders/OSD/inc/op_dfu.h index e031c3364..262852fc4 100644 --- a/flight/targets/Bootloaders/OSD/inc/op_dfu.h +++ b/flight/targets/Bootloaders/OSD/inc/op_dfu.h @@ -1,60 +1,60 @@ -/** - ****************************************************************************** - * - * @file op_dfu.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __OP_DFU_H -#define __OP_DFU_H -#include "common.h" -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -typedef struct { - uint8_t programmingType; - uint8_t readWriteFlags; - uint32_t startOfUserCode; - uint32_t sizeOfCode; - uint8_t sizeOfDescription; - uint8_t BL_Version; - uint16_t devID; - DeviceType devType; - uint32_t FW_Crc; -} Device; - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported define -----------------------------------------------------------*/ -#define COMMAND 0 -#define COUNT 1 -#define DATA 5 - -/* Exported functions ------------------------------------------------------- */ -void processComand(uint8_t *Receive_Buffer); -uint32_t baseOfAdressType(uint8_t type); -uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); -void OPDfuIni(uint8_t discover); -void DataDownload(DownloadAction); -bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); -#endif /* __OP_DFU_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * + * @file op_dfu.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __OP_DFU_H +#define __OP_DFU_H +#include "common.h" +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef struct { + uint8_t programmingType; + uint8_t readWriteFlags; + uint32_t startOfUserCode; + uint32_t sizeOfCode; + uint8_t sizeOfDescription; + uint8_t BL_Version; + uint16_t devID; + DeviceType devType; + uint32_t FW_Crc; +} Device; + +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported define -----------------------------------------------------------*/ +#define COMMAND 0 +#define COUNT 1 +#define DATA 5 + +/* Exported functions ------------------------------------------------------- */ +void processComand(uint8_t *Receive_Buffer); +uint32_t baseOfAdressType(uint8_t type); +uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); +void OPDfuIni(uint8_t discover); +void DataDownload(DownloadAction); +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); +#endif /* __OP_DFU_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/targets/Bootloaders/OSD/main.c b/flight/targets/Bootloaders/OSD/main.c index 90e946b56..98515fb1f 100644 --- a/flight/targets/Bootloaders/OSD/main.c +++ b/flight/targets/Bootloaders/OSD/main.c @@ -1,208 +1,208 @@ -/** - ****************************************************************************** - * @addtogroup RevolutionBL Revolution BootLoader - * @brief These files contain the code to the Revolution Bootloader. - * - * @{ - * @file main.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This is the file with the main function of the Revolution BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -/* Bootloader Includes */ -#include -#include -#include -#include "op_dfu.h" -#include "pios_iap.h" -#include "fifo_buffer.h" -#include "pios_com_msg.h" -#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void FLASH_Download(); -#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) - -/* Private typedef -----------------------------------------------------------*/ -typedef void (*pFunction)(void); -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -pFunction Jump_To_Application; -uint32_t JumpAddress; - -/// LEDs PWM -uint32_t period1 = 5000; // 5 mS -uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS -uint32_t period2 = 5000; // 5 mS -uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS - - -//////////////////////////////////////// -uint8_t tempcount = 0; - -/* Extern variables ----------------------------------------------------------*/ -DFUStates DeviceState; -int16_t status = 0; -bool JumpToApp = false; -bool GO_dfu = false; -bool USB_connected = false; -bool User_DFU_request = false; -static uint8_t mReceive_Buffer[63]; -/* Private function prototypes -----------------------------------------------*/ -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); -uint8_t processRX(); -void jump_to_app(); - -int main() { - PIOS_SYS_Init(); - PIOS_Board_Init(); - PIOS_IAP_Init(); - - USB_connected = PIOS_USB_CheckAvailable(0); - - if (PIOS_IAP_CheckRequest() == true) { - PIOS_DELAY_WaitmS(1000); - User_DFU_request = true; - PIOS_IAP_ClearRequest(); - } - - GO_dfu = (USB_connected == true) || (User_DFU_request == true); - - if (GO_dfu == true) { - PIOS_Board_Init(); - if (User_DFU_request == true) - DeviceState = DFUidle; - else - DeviceState = BLidle; - } else - JumpToApp = true; - - uint32_t stopwatch = 0; - uint32_t prev_ticks = PIOS_DELAY_GetuS(); - while (true) { - /* Update the stopwatch */ - uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); - prev_ticks += elapsed_ticks; - stopwatch += elapsed_ticks; - - if (JumpToApp == true) - jump_to_app(); - - switch (DeviceState) { - case Last_operation_Success: - case uploadingStarting: - case DFUidle: - period1 = 5000; - sweep_steps1 = 100; - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - case uploading: - period1 = 5000; - sweep_steps1 = 100; - period2 = 2500; - sweep_steps2 = 50; - break; - case downloading: - period1 = 2500; - sweep_steps1 = 50; - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - case BLidle: - period1 = 0; - PIOS_LED_On(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - default://error - period1 = 5000; - sweep_steps1 = 100; - period2 = 5000; - sweep_steps2 = 100; - } - - if (period1 != 0) { - if (LedPWM(period1, sweep_steps1, stopwatch)) - PIOS_LED_On(PIOS_LED_HEARTBEAT); - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else - PIOS_LED_On(PIOS_LED_HEARTBEAT); - - if (period2 != 0) { - if (LedPWM(period2, sweep_steps2, stopwatch)) - PIOS_LED_On(PIOS_LED_HEARTBEAT); - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - - if (stopwatch > 50 * 1000 * 1000) - stopwatch = 0; - if ((stopwatch > 6 * 1000 * 1000) && (DeviceState - == BLidle)) - JumpToApp = true; - - processRX(); - DataDownload(start); - } -} - -void jump_to_app() { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - - PIOS_LED_On(PIOS_LED_HEARTBEAT); - if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ - FLASH_Lock(); - RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); - RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); - - PIOS_USBHOOK_Deactivate(); - - JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); - Jump_To_Application = (pFunction) JumpAddress; - /* Initialize user application's Stack Pointer */ - __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); - Jump_To_Application(); - } else { - DeviceState = failed_jump; - return; - } -} -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { - uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ - uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ - - uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ - if (curr_sweep & 1) { - pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ - } - return ((count % pwm_period) > pwm_duty) ? 1 : 0; -} - -uint8_t processRX() { - if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { - processComand(mReceive_Buffer); - } - return true; -} - +/** + ****************************************************************************** + * @addtogroup RevolutionBL Revolution BootLoader + * @brief These files contain the code to the Revolution Bootloader. + * + * @{ + * @file main.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This is the file with the main function of the Revolution BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/* Bootloader Includes */ +#include +#include +#include +#include "op_dfu.h" +#include "pios_iap.h" +#include "fifo_buffer.h" +#include "pios_com_msg.h" +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void FLASH_Download(); +#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) + +/* Private typedef -----------------------------------------------------------*/ +typedef void (*pFunction)(void); +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +pFunction Jump_To_Application; +uint32_t JumpAddress; + +/// LEDs PWM +uint32_t period1 = 5000; // 5 mS +uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS +uint32_t period2 = 5000; // 5 mS +uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS + + +//////////////////////////////////////// +uint8_t tempcount = 0; + +/* Extern variables ----------------------------------------------------------*/ +DFUStates DeviceState; +int16_t status = 0; +bool JumpToApp = false; +bool GO_dfu = false; +bool USB_connected = false; +bool User_DFU_request = false; +static uint8_t mReceive_Buffer[63]; +/* Private function prototypes -----------------------------------------------*/ +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); +uint8_t processRX(); +void jump_to_app(); + +int main() { + PIOS_SYS_Init(); + PIOS_Board_Init(); + PIOS_IAP_Init(); + + USB_connected = PIOS_USB_CheckAvailable(0); + + if (PIOS_IAP_CheckRequest() == true) { + PIOS_DELAY_WaitmS(1000); + User_DFU_request = true; + PIOS_IAP_ClearRequest(); + } + + GO_dfu = (USB_connected == true) || (User_DFU_request == true); + + if (GO_dfu == true) { + PIOS_Board_Init(); + if (User_DFU_request == true) + DeviceState = DFUidle; + else + DeviceState = BLidle; + } else + JumpToApp = true; + + uint32_t stopwatch = 0; + uint32_t prev_ticks = PIOS_DELAY_GetuS(); + while (true) { + /* Update the stopwatch */ + uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); + prev_ticks += elapsed_ticks; + stopwatch += elapsed_ticks; + + if (JumpToApp == true) + jump_to_app(); + + switch (DeviceState) { + case Last_operation_Success: + case uploadingStarting: + case DFUidle: + period1 = 5000; + sweep_steps1 = 100; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case uploading: + period1 = 5000; + sweep_steps1 = 100; + period2 = 2500; + sweep_steps2 = 50; + break; + case downloading: + period1 = 2500; + sweep_steps1 = 50; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case BLidle: + period1 = 0; + PIOS_LED_On(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + default://error + period1 = 5000; + sweep_steps1 = 100; + period2 = 5000; + sweep_steps2 = 100; + } + + if (period1 != 0) { + if (LedPWM(period1, sweep_steps1, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_On(PIOS_LED_HEARTBEAT); + + if (period2 != 0) { + if (LedPWM(period2, sweep_steps2, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + + if (stopwatch > 50 * 1000 * 1000) + stopwatch = 0; + if ((stopwatch > 6 * 1000 * 1000) && (DeviceState + == BLidle)) + JumpToApp = true; + + processRX(); + DataDownload(start); + } +} + +void jump_to_app() { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + PIOS_LED_On(PIOS_LED_HEARTBEAT); + if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ + FLASH_Lock(); + RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); + RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); + + PIOS_USBHOOK_Deactivate(); + + JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); + Jump_To_Application = (pFunction) JumpAddress; + /* Initialize user application's Stack Pointer */ + __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); + Jump_To_Application(); + } else { + DeviceState = failed_jump; + return; + } +} +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { + uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ + uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ + + uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ + if (curr_sweep & 1) { + pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ + } + return ((count % pwm_period) > pwm_duty) ? 1 : 0; +} + +uint8_t processRX() { + if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { + processComand(mReceive_Buffer); + } + return true; +} + diff --git a/flight/targets/Bootloaders/OSD/op_dfu.c b/flight/targets/Bootloaders/OSD/op_dfu.c index 3aceedcfb..16281dd4d 100644 --- a/flight/targets/Bootloaders/OSD/op_dfu.c +++ b/flight/targets/Bootloaders/OSD/op_dfu.c @@ -1,468 +1,468 @@ -/** - ****************************************************************************** - * @addtogroup CopterControlBL CopterControl BootLoader - * @brief These files contain the code to the CopterControl Bootloader. - * - * @{ - * @file op_dfu.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This file contains the DFU commands handling code - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Includes ------------------------------------------------------------------*/ -#include "pios.h" -#include -#include "op_dfu.h" -#include "pios_bl_helper.h" -#include "pios_com_msg.h" -#include -//programmable devices -Device devicesTable[10]; -uint8_t numberOfDevices = 0; - -DFUProgType currentProgrammingDestination; //flash, flash_trough spi -uint8_t currentDeviceCanRead; -uint8_t currentDeviceCanWrite; -Device currentDevice; - -uint8_t Buffer[64]; -uint8_t echoBuffer[64]; -uint8_t SendBuffer[64]; -uint8_t Command = 0; -uint8_t EchoReqFlag = 0; -uint8_t EchoAnsFlag = 0; -uint8_t StartFlag = 0; -uint32_t Aditionals = 0; -uint32_t SizeOfTransfer = 0; -uint32_t Expected_CRC = 0; -uint8_t SizeOfLastPacket = 0; -uint32_t Next_Packet = 0; -uint8_t TransferType; -uint32_t Count = 0; -uint32_t Data; -uint8_t Data0; -uint8_t Data1; -uint8_t Data2; -uint8_t Data3; -uint8_t offset = 0; -uint32_t aux; -//Download vars -uint32_t downSizeOfLastPacket = 0; -uint32_t downPacketTotal = 0; -uint32_t downPacketCurrent = 0; -DFUTransfer downType = 0; -/* Extern variables ----------------------------------------------------------*/ -extern DFUStates DeviceState; -extern uint8_t JumpToApp; -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -void sendData(uint8_t * buf, uint16_t size); -uint32_t CalcFirmCRC(void); - -void DataDownload(DownloadAction action) { - if ((DeviceState == downloading)) { - - uint8_t packetSize; - uint32_t offset; - uint32_t partoffset; - SendBuffer[0] = 0x01; - SendBuffer[1] = Download; - SendBuffer[2] = downPacketCurrent >> 24; - SendBuffer[3] = downPacketCurrent >> 16; - SendBuffer[4] = downPacketCurrent >> 8; - SendBuffer[5] = downPacketCurrent; - if (downPacketCurrent == downPacketTotal - 1) { - packetSize = downSizeOfLastPacket; - } else { - packetSize = 14; - } - for (uint8_t x = 0; x < packetSize; ++x) { - partoffset = (downPacketCurrent * 14 * 4) + (x * 4); - offset = baseOfAdressType(downType) + partoffset; - if (!flash_read(SendBuffer + (6 + x * 4), offset, - currentProgrammingDestination)) { - DeviceState = Last_operation_failed; - } - } - downPacketCurrent = downPacketCurrent + 1; - if (downPacketCurrent > downPacketTotal - 1) { - DeviceState = Last_operation_Success; - Aditionals = (uint32_t) Download; - } - sendData(SendBuffer + 1, 63); - } -} -void processComand(uint8_t *xReceive_Buffer) { - - Command = xReceive_Buffer[COMMAND]; -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Received COMMAND:%d|",Command); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - EchoReqFlag = (Command >> 7); - EchoAnsFlag = (Command >> 6) & 0x01; - StartFlag = (Command >> 5) & 0x01; - Count = xReceive_Buffer[COUNT] << 24; - Count += xReceive_Buffer[COUNT + 1] << 16; - Count += xReceive_Buffer[COUNT + 2] << 8; - Count += xReceive_Buffer[COUNT + 3]; - - Data = xReceive_Buffer[DATA] << 24; - Data += xReceive_Buffer[DATA + 1] << 16; - Data += xReceive_Buffer[DATA + 2] << 8; - Data += xReceive_Buffer[DATA + 3]; - Data0 = xReceive_Buffer[DATA]; - Data1 = xReceive_Buffer[DATA + 1]; - Data2 = xReceive_Buffer[DATA + 2]; - Data3 = xReceive_Buffer[DATA + 3]; - Command = Command & 0b00011111; - - if (EchoReqFlag == 1) { - memcpy(echoBuffer, xReceive_Buffer, 64); - } - switch (Command) { - case EnterDFU: - if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) - || (DeviceState == DFUidle)) { - if (Data0 > 0) - OPDfuIni(true); - DeviceState = DFUidle; - currentProgrammingDestination = devicesTable[Data0].programmingType; - currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; - currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 - & 0x01; - currentDevice = devicesTable[Data0]; - uint8_t result = 0; - switch (currentProgrammingDestination) { - case Self_flash: - result = PIOS_BL_HELPER_FLASH_Ini(); - break; - case Remote_flash_via_spi: - result = true; - break; - default: - DeviceState = Last_operation_failed; - Aditionals = (uint16_t) Command; - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - } - break; - case Upload: - if ((DeviceState == DFUidle) || (DeviceState == uploading)) { - if ((StartFlag == 1) && (Next_Packet == 0)) { - TransferType = Data0; - SizeOfTransfer = Count; - Next_Packet = 1; - Expected_CRC = Data2 << 24; - Expected_CRC += Data3 << 16; - Expected_CRC += xReceive_Buffer[DATA + 4] << 8; - Expected_CRC += xReceive_Buffer[DATA + 5]; - SizeOfLastPacket = Data1; - - if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) - * 14 * 4 + SizeOfLastPacket * 4) == true) { - DeviceState = outsideDevCapabilities; - Aditionals = (uint32_t) Command; - } else { - uint8_t result = 1; - if (TransferType == FW) { - switch (currentProgrammingDestination) { - case Self_flash: - result = PIOS_BL_HELPER_FLASH_Start(); - break; - case Remote_flash_via_spi: - result = false; - break; - default: - break; - } - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } else { - - DeviceState = uploading; - } - } - } else if ((StartFlag != 1) && (Next_Packet != 0)) { - if (Count > SizeOfTransfer) { - DeviceState = too_many_packets; - Aditionals = Count; - } else if (Count == Next_Packet - 1) { - uint8_t numberOfWords = 14; - if (Count == SizeOfTransfer - 1)//is this the last packet? - { - numberOfWords = SizeOfLastPacket; - } - uint8_t result = 0; - switch (currentProgrammingDestination) { - case Self_flash: - for (uint8_t x = 0; x < numberOfWords; ++x) { - offset = 4 * x; - Data = xReceive_Buffer[DATA + offset] << 24; - Data += xReceive_Buffer[DATA + 1 + offset] << 16; - Data += xReceive_Buffer[DATA + 2 + offset] << 8; - Data += xReceive_Buffer[DATA + 3 + offset]; - aux = baseOfAdressType(TransferType) + (uint32_t)( - Count * 14 * 4 + x * 4); - result = 0; - for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { - if (result == 0) { - result = (FLASH_ProgramWord(aux, Data) - == FLASH_COMPLETE) ? 1 : 0; - } - } - } - break; - case Remote_flash_via_spi: - result = false; // No support for this for the PipX - break; - default: - result = 0; - break; - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - - ++Next_Packet; - } else { - DeviceState = wrong_packet_received; - Aditionals = Count; - } - } else { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - } - break; - case Req_Capabilities: - OPDfuIni(true); - Buffer[0] = 0x01; - Buffer[1] = Rep_Capabilities; - if (Data0 == 0) { - Buffer[2] = 0; - Buffer[3] = 0; - Buffer[4] = 0; - Buffer[5] = 0; - Buffer[6] = 0; - Buffer[7] = numberOfDevices; - uint16_t WRFlags = 0; - for (int x = 0; x < numberOfDevices; ++x) { - WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) - | WRFlags); - } - Buffer[8] = WRFlags >> 8; - Buffer[9] = WRFlags; - } else { - Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; - Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; - Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; - Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; - Buffer[6] = Data0; - Buffer[7] = devicesTable[Data0 - 1].BL_Version; - Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; - Buffer[9] = devicesTable[Data0 - 1].devID; - Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; - Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; - Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; - Buffer[13] = devicesTable[Data0 - 1].FW_Crc; - Buffer[14] = devicesTable[Data0 - 1].devID >> 8; - Buffer[15] = devicesTable[Data0 - 1].devID; - } - sendData(Buffer + 1, 63); - break; - case JumpFW: - if (Data == 0x5AFE) { - /* Force board into safe mode */ - PIOS_IAP_WriteBootCount(0xFFFF); - } - FLASH_Lock(); - JumpToApp = 1; - break; - case Reset: - PIOS_SYS_Reset(); - break; - case Abort_Operation: - Next_Packet = 0; - DeviceState = DFUidle; - break; - - case Op_END: - if (DeviceState == uploading) { - if (Next_Packet - 1 == SizeOfTransfer) { - Next_Packet = 0; - if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { - DeviceState = Last_operation_Success; - } else { - DeviceState = CRC_Fail; - } - } - if (Next_Packet - 1 < SizeOfTransfer) { - Next_Packet = 0; - DeviceState = too_few_packets; - } - } - break; - case Download_Req: -#ifdef DEBUG_SSP - sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - if (DeviceState == DFUidle) { -#ifdef DEBUG_SSP - PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); -#endif - downType = Data0; - downPacketTotal = Count; - downSizeOfLastPacket = Data1; - if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 * 4 - + downSizeOfLastPacket * 4) == 1) { - DeviceState = outsideDevCapabilities; - Aditionals = (uint32_t) Command; - - } else { - downPacketCurrent = 0; - DeviceState = downloading; - } - } else { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - break; - - case Status_Request: - Buffer[0] = 0x01; - Buffer[1] = Status_Rep; - if (DeviceState == wrong_packet_received) { - Buffer[2] = Aditionals >> 24; - Buffer[3] = Aditionals >> 16; - Buffer[4] = Aditionals >> 8; - Buffer[5] = Aditionals; - } else { - Buffer[2] = 0; - Buffer[3] = ((uint16_t) Aditionals) >> 8; - Buffer[4] = ((uint16_t) Aditionals); - Buffer[5] = 0; - } - Buffer[6] = DeviceState; - Buffer[7] = 0; - Buffer[8] = 0; - Buffer[9] = 0; - sendData(Buffer + 1, 63); - if (DeviceState == Last_operation_Success) { - DeviceState = DFUidle; - } - break; - case Status_Rep: - - break; - - } - if (EchoReqFlag == 1) { - echoBuffer[0] = echoBuffer[0] | (1 << 6); - sendData(echoBuffer, 63); - } - return; -} -void OPDfuIni(uint8_t discover) { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - Device dev; - - dev.programmingType = Self_flash; - dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); - dev.startOfUserCode = bdinfo->fw_base; - dev.sizeOfCode = bdinfo->fw_size; - dev.sizeOfDescription = bdinfo->desc_size; - dev.BL_Version = bdinfo->bl_rev; - dev.FW_Crc = CalcFirmCRC(); - dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); - dev.devType = bdinfo->hw_type; - numberOfDevices = 1; - devicesTable[0] = dev; - if (discover) { - //TODO check other devices trough spi or whatever - } -} -uint32_t baseOfAdressType(DFUTransfer type) { - switch (type) { - case FW: - return currentDevice.startOfUserCode; - break; - case Descript: - return currentDevice.startOfUserCode + currentDevice.sizeOfCode; - break; - default: - - return 0; - } -} -uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { - switch (type) { - case FW: - return (size > currentDevice.sizeOfCode) ? 1 : 0; - break; - case Descript: - return (size > currentDevice.sizeOfDescription) ? 1 : 0; - break; - default: - return true; - } -} - -uint32_t CalcFirmCRC() { - switch (currentProgrammingDestination) { - case Self_flash: - return PIOS_BL_HELPER_CRC_Memory_Calc(); - break; - case Remote_flash_via_spi: - return 0; - break; - default: - return 0; - break; - } - -} -void sendData(uint8_t * buf, uint16_t size) { - PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); -} - -bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { - switch (type) { - case Remote_flash_via_spi: - return false; // We should not get this for the PipX - break; - case Self_flash: - for (uint8_t x = 0; x < 4; ++x) { - buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); - } - return true; - break; - default: - return false; - } -} +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file op_dfu.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains the DFU commands handling code + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Includes ------------------------------------------------------------------*/ +#include "pios.h" +#include +#include "op_dfu.h" +#include "pios_bl_helper.h" +#include "pios_com_msg.h" +#include +//programmable devices +Device devicesTable[10]; +uint8_t numberOfDevices = 0; + +DFUProgType currentProgrammingDestination; //flash, flash_trough spi +uint8_t currentDeviceCanRead; +uint8_t currentDeviceCanWrite; +Device currentDevice; + +uint8_t Buffer[64]; +uint8_t echoBuffer[64]; +uint8_t SendBuffer[64]; +uint8_t Command = 0; +uint8_t EchoReqFlag = 0; +uint8_t EchoAnsFlag = 0; +uint8_t StartFlag = 0; +uint32_t Aditionals = 0; +uint32_t SizeOfTransfer = 0; +uint32_t Expected_CRC = 0; +uint8_t SizeOfLastPacket = 0; +uint32_t Next_Packet = 0; +uint8_t TransferType; +uint32_t Count = 0; +uint32_t Data; +uint8_t Data0; +uint8_t Data1; +uint8_t Data2; +uint8_t Data3; +uint8_t offset = 0; +uint32_t aux; +//Download vars +uint32_t downSizeOfLastPacket = 0; +uint32_t downPacketTotal = 0; +uint32_t downPacketCurrent = 0; +DFUTransfer downType = 0; +/* Extern variables ----------------------------------------------------------*/ +extern DFUStates DeviceState; +extern uint8_t JumpToApp; +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +void sendData(uint8_t * buf, uint16_t size); +uint32_t CalcFirmCRC(void); + +void DataDownload(DownloadAction action) { + if ((DeviceState == downloading)) { + + uint8_t packetSize; + uint32_t offset; + uint32_t partoffset; + SendBuffer[0] = 0x01; + SendBuffer[1] = Download; + SendBuffer[2] = downPacketCurrent >> 24; + SendBuffer[3] = downPacketCurrent >> 16; + SendBuffer[4] = downPacketCurrent >> 8; + SendBuffer[5] = downPacketCurrent; + if (downPacketCurrent == downPacketTotal - 1) { + packetSize = downSizeOfLastPacket; + } else { + packetSize = 14; + } + for (uint8_t x = 0; x < packetSize; ++x) { + partoffset = (downPacketCurrent * 14 * 4) + (x * 4); + offset = baseOfAdressType(downType) + partoffset; + if (!flash_read(SendBuffer + (6 + x * 4), offset, + currentProgrammingDestination)) { + DeviceState = Last_operation_failed; + } + } + downPacketCurrent = downPacketCurrent + 1; + if (downPacketCurrent > downPacketTotal - 1) { + DeviceState = Last_operation_Success; + Aditionals = (uint32_t) Download; + } + sendData(SendBuffer + 1, 63); + } +} +void processComand(uint8_t *xReceive_Buffer) { + + Command = xReceive_Buffer[COMMAND]; +#ifdef DEBUG_SSP + char str[63]= {0}; + sprintf(str,"Received COMMAND:%d|",Command); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + EchoReqFlag = (Command >> 7); + EchoAnsFlag = (Command >> 6) & 0x01; + StartFlag = (Command >> 5) & 0x01; + Count = xReceive_Buffer[COUNT] << 24; + Count += xReceive_Buffer[COUNT + 1] << 16; + Count += xReceive_Buffer[COUNT + 2] << 8; + Count += xReceive_Buffer[COUNT + 3]; + + Data = xReceive_Buffer[DATA] << 24; + Data += xReceive_Buffer[DATA + 1] << 16; + Data += xReceive_Buffer[DATA + 2] << 8; + Data += xReceive_Buffer[DATA + 3]; + Data0 = xReceive_Buffer[DATA]; + Data1 = xReceive_Buffer[DATA + 1]; + Data2 = xReceive_Buffer[DATA + 2]; + Data3 = xReceive_Buffer[DATA + 3]; + Command = Command & 0b00011111; + + if (EchoReqFlag == 1) { + memcpy(echoBuffer, xReceive_Buffer, 64); + } + switch (Command) { + case EnterDFU: + if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) + || (DeviceState == DFUidle)) { + if (Data0 > 0) + OPDfuIni(true); + DeviceState = DFUidle; + currentProgrammingDestination = devicesTable[Data0].programmingType; + currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; + currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 + & 0x01; + currentDevice = devicesTable[Data0]; + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Ini(); + break; + case Remote_flash_via_spi: + result = true; + break; + default: + DeviceState = Last_operation_failed; + Aditionals = (uint16_t) Command; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Upload: + if ((DeviceState == DFUidle) || (DeviceState == uploading)) { + if ((StartFlag == 1) && (Next_Packet == 0)) { + TransferType = Data0; + SizeOfTransfer = Count; + Next_Packet = 1; + Expected_CRC = Data2 << 24; + Expected_CRC += Data3 << 16; + Expected_CRC += xReceive_Buffer[DATA + 4] << 8; + Expected_CRC += xReceive_Buffer[DATA + 5]; + SizeOfLastPacket = Data1; + + if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) + * 14 * 4 + SizeOfLastPacket * 4) == true) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + } else { + uint8_t result = 1; + if (TransferType == FW) { + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Start(); + break; + case Remote_flash_via_spi: + result = false; + break; + default: + break; + } + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } else { + + DeviceState = uploading; + } + } + } else if ((StartFlag != 1) && (Next_Packet != 0)) { + if (Count > SizeOfTransfer) { + DeviceState = too_many_packets; + Aditionals = Count; + } else if (Count == Next_Packet - 1) { + uint8_t numberOfWords = 14; + if (Count == SizeOfTransfer - 1)//is this the last packet? + { + numberOfWords = SizeOfLastPacket; + } + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + for (uint8_t x = 0; x < numberOfWords; ++x) { + offset = 4 * x; + Data = xReceive_Buffer[DATA + offset] << 24; + Data += xReceive_Buffer[DATA + 1 + offset] << 16; + Data += xReceive_Buffer[DATA + 2 + offset] << 8; + Data += xReceive_Buffer[DATA + 3 + offset]; + aux = baseOfAdressType(TransferType) + (uint32_t)( + Count * 14 * 4 + x * 4); + result = 0; + for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { + if (result == 0) { + result = (FLASH_ProgramWord(aux, Data) + == FLASH_COMPLETE) ? 1 : 0; + } + } + } + break; + case Remote_flash_via_spi: + result = false; // No support for this for the PipX + break; + default: + result = 0; + break; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + + ++Next_Packet; + } else { + DeviceState = wrong_packet_received; + Aditionals = Count; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Req_Capabilities: + OPDfuIni(true); + Buffer[0] = 0x01; + Buffer[1] = Rep_Capabilities; + if (Data0 == 0) { + Buffer[2] = 0; + Buffer[3] = 0; + Buffer[4] = 0; + Buffer[5] = 0; + Buffer[6] = 0; + Buffer[7] = numberOfDevices; + uint16_t WRFlags = 0; + for (int x = 0; x < numberOfDevices; ++x) { + WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) + | WRFlags); + } + Buffer[8] = WRFlags >> 8; + Buffer[9] = WRFlags; + } else { + Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; + Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; + Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; + Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; + Buffer[6] = Data0; + Buffer[7] = devicesTable[Data0 - 1].BL_Version; + Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; + Buffer[9] = devicesTable[Data0 - 1].devID; + Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; + Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; + Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; + Buffer[13] = devicesTable[Data0 - 1].FW_Crc; + Buffer[14] = devicesTable[Data0 - 1].devID >> 8; + Buffer[15] = devicesTable[Data0 - 1].devID; + } + sendData(Buffer + 1, 63); + break; + case JumpFW: + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); + } + FLASH_Lock(); + JumpToApp = 1; + break; + case Reset: + PIOS_SYS_Reset(); + break; + case Abort_Operation: + Next_Packet = 0; + DeviceState = DFUidle; + break; + + case Op_END: + if (DeviceState == uploading) { + if (Next_Packet - 1 == SizeOfTransfer) { + Next_Packet = 0; + if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { + DeviceState = Last_operation_Success; + } else { + DeviceState = CRC_Fail; + } + } + if (Next_Packet - 1 < SizeOfTransfer) { + Next_Packet = 0; + DeviceState = too_few_packets; + } + } + break; + case Download_Req: +#ifdef DEBUG_SSP + sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + if (DeviceState == DFUidle) { +#ifdef DEBUG_SSP + PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); +#endif + downType = Data0; + downPacketTotal = Count; + downSizeOfLastPacket = Data1; + if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 * 4 + + downSizeOfLastPacket * 4) == 1) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + + } else { + downPacketCurrent = 0; + DeviceState = downloading; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + break; + + case Status_Request: + Buffer[0] = 0x01; + Buffer[1] = Status_Rep; + if (DeviceState == wrong_packet_received) { + Buffer[2] = Aditionals >> 24; + Buffer[3] = Aditionals >> 16; + Buffer[4] = Aditionals >> 8; + Buffer[5] = Aditionals; + } else { + Buffer[2] = 0; + Buffer[3] = ((uint16_t) Aditionals) >> 8; + Buffer[4] = ((uint16_t) Aditionals); + Buffer[5] = 0; + } + Buffer[6] = DeviceState; + Buffer[7] = 0; + Buffer[8] = 0; + Buffer[9] = 0; + sendData(Buffer + 1, 63); + if (DeviceState == Last_operation_Success) { + DeviceState = DFUidle; + } + break; + case Status_Rep: + + break; + + } + if (EchoReqFlag == 1) { + echoBuffer[0] = echoBuffer[0] | (1 << 6); + sendData(echoBuffer, 63); + } + return; +} +void OPDfuIni(uint8_t discover) { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + Device dev; + + dev.programmingType = Self_flash; + dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); + dev.startOfUserCode = bdinfo->fw_base; + dev.sizeOfCode = bdinfo->fw_size; + dev.sizeOfDescription = bdinfo->desc_size; + dev.BL_Version = bdinfo->bl_rev; + dev.FW_Crc = CalcFirmCRC(); + dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); + dev.devType = bdinfo->hw_type; + numberOfDevices = 1; + devicesTable[0] = dev; + if (discover) { + //TODO check other devices trough spi or whatever + } +} +uint32_t baseOfAdressType(DFUTransfer type) { + switch (type) { + case FW: + return currentDevice.startOfUserCode; + break; + case Descript: + return currentDevice.startOfUserCode + currentDevice.sizeOfCode; + break; + default: + + return 0; + } +} +uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { + switch (type) { + case FW: + return (size > currentDevice.sizeOfCode) ? 1 : 0; + break; + case Descript: + return (size > currentDevice.sizeOfDescription) ? 1 : 0; + break; + default: + return true; + } +} + +uint32_t CalcFirmCRC() { + switch (currentProgrammingDestination) { + case Self_flash: + return PIOS_BL_HELPER_CRC_Memory_Calc(); + break; + case Remote_flash_via_spi: + return 0; + break; + default: + return 0; + break; + } + +} +void sendData(uint8_t * buf, uint16_t size) { + PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); +} + +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { + switch (type) { + case Remote_flash_via_spi: + return false; // We should not get this for the PipX + break; + case Self_flash: + for (uint8_t x = 0; x < 4; ++x) { + buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); + } + return true; + break; + default: + return false; + } +} diff --git a/flight/targets/Bootloaders/PipXtreme/inc/common.h b/flight/targets/Bootloaders/PipXtreme/inc/common.h index 085f07061..9973764e9 100644 --- a/flight/targets/Bootloaders/PipXtreme/inc/common.h +++ b/flight/targets/Bootloaders/PipXtreme/inc/common.h @@ -1,115 +1,115 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @brief These files contain the code to the OpenPilot MB Bootloader. - * - * @{ - * @file common.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This file contains various common defines for the BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef COMMON_H_ -#define COMMON_H_ - -//#include "board.h" - -typedef enum { - start, keepgoing, -} DownloadAction; - -/**************************************************/ -/* OP_DFU states */ -/**************************************************/ - -typedef enum { - DFUidle, //0 - uploading, //1 - wrong_packet_received, //2 - too_many_packets, //3 - too_few_packets, //4 - Last_operation_Success, //5 - downloading, //6 - BLidle, //7 - Last_operation_failed, //8 - uploadingStarting, //9 - outsideDevCapabilities, //10 - CRC_Fail,//11 - failed_jump, -//12 -} DFUStates; -/**************************************************/ -/* OP_DFU commands */ -/**************************************************/ -typedef enum { - Reserved, //0 - Req_Capabilities, //1 - Rep_Capabilities, //2 - EnterDFU, //3 - JumpFW, //4 - Reset, //5 - Abort_Operation, //6 - Upload, //7 - Op_END, //8 - Download_Req, //9 - Download, //10 - Status_Request, //11 - Status_Rep -//12 -} DFUCommands; - -typedef enum { - High_Density, Medium_Density -} DeviceType; -/**************************************************/ -/* OP_DFU transfer types */ -/**************************************************/ -typedef enum { - FW, //0 - Descript -//2 -} DFUTransfer; -/**************************************************/ -/* OP_DFU transfer port */ -/**************************************************/ -typedef enum { - Usb, //0 - Serial -//2 -} DFUPort; -/**************************************************/ -/* OP_DFU programable programable HW types */ -/**************************************************/ -typedef enum { - Self_flash, //0 - Remote_flash_via_spi -//1 -} DFUProgType; -/**************************************************/ -/* OP_DFU programable sources */ -/**************************************************/ -#define USB 0 -#define SPI 1 - -#define DownloadDelay 100000 - -#define MAX_DEL_RETRYS 3 -#define MAX_WRI_RETRYS 3 - -#endif /* COMMON_H_ */ +/** + ****************************************************************************** + * @addtogroup OpenPilotBL OpenPilot BootLoader + * @brief These files contain the code to the OpenPilot MB Bootloader. + * + * @{ + * @file common.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains various common defines for the BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef COMMON_H_ +#define COMMON_H_ + +//#include "board.h" + +typedef enum { + start, keepgoing, +} DownloadAction; + +/**************************************************/ +/* OP_DFU states */ +/**************************************************/ + +typedef enum { + DFUidle, //0 + uploading, //1 + wrong_packet_received, //2 + too_many_packets, //3 + too_few_packets, //4 + Last_operation_Success, //5 + downloading, //6 + BLidle, //7 + Last_operation_failed, //8 + uploadingStarting, //9 + outsideDevCapabilities, //10 + CRC_Fail,//11 + failed_jump, +//12 +} DFUStates; +/**************************************************/ +/* OP_DFU commands */ +/**************************************************/ +typedef enum { + Reserved, //0 + Req_Capabilities, //1 + Rep_Capabilities, //2 + EnterDFU, //3 + JumpFW, //4 + Reset, //5 + Abort_Operation, //6 + Upload, //7 + Op_END, //8 + Download_Req, //9 + Download, //10 + Status_Request, //11 + Status_Rep +//12 +} DFUCommands; + +typedef enum { + High_Density, Medium_Density +} DeviceType; +/**************************************************/ +/* OP_DFU transfer types */ +/**************************************************/ +typedef enum { + FW, //0 + Descript +//2 +} DFUTransfer; +/**************************************************/ +/* OP_DFU transfer port */ +/**************************************************/ +typedef enum { + Usb, //0 + Serial +//2 +} DFUPort; +/**************************************************/ +/* OP_DFU programable programable HW types */ +/**************************************************/ +typedef enum { + Self_flash, //0 + Remote_flash_via_spi +//1 +} DFUProgType; +/**************************************************/ +/* OP_DFU programable sources */ +/**************************************************/ +#define USB 0 +#define SPI 1 + +#define DownloadDelay 100000 + +#define MAX_DEL_RETRYS 3 +#define MAX_WRI_RETRYS 3 + +#endif /* COMMON_H_ */ diff --git a/flight/targets/Bootloaders/PipXtreme/inc/op_dfu.h b/flight/targets/Bootloaders/PipXtreme/inc/op_dfu.h index e031c3364..262852fc4 100644 --- a/flight/targets/Bootloaders/PipXtreme/inc/op_dfu.h +++ b/flight/targets/Bootloaders/PipXtreme/inc/op_dfu.h @@ -1,60 +1,60 @@ -/** - ****************************************************************************** - * - * @file op_dfu.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __OP_DFU_H -#define __OP_DFU_H -#include "common.h" -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -typedef struct { - uint8_t programmingType; - uint8_t readWriteFlags; - uint32_t startOfUserCode; - uint32_t sizeOfCode; - uint8_t sizeOfDescription; - uint8_t BL_Version; - uint16_t devID; - DeviceType devType; - uint32_t FW_Crc; -} Device; - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported define -----------------------------------------------------------*/ -#define COMMAND 0 -#define COUNT 1 -#define DATA 5 - -/* Exported functions ------------------------------------------------------- */ -void processComand(uint8_t *Receive_Buffer); -uint32_t baseOfAdressType(uint8_t type); -uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); -void OPDfuIni(uint8_t discover); -void DataDownload(DownloadAction); -bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); -#endif /* __OP_DFU_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * + * @file op_dfu.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __OP_DFU_H +#define __OP_DFU_H +#include "common.h" +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef struct { + uint8_t programmingType; + uint8_t readWriteFlags; + uint32_t startOfUserCode; + uint32_t sizeOfCode; + uint8_t sizeOfDescription; + uint8_t BL_Version; + uint16_t devID; + DeviceType devType; + uint32_t FW_Crc; +} Device; + +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported define -----------------------------------------------------------*/ +#define COMMAND 0 +#define COUNT 1 +#define DATA 5 + +/* Exported functions ------------------------------------------------------- */ +void processComand(uint8_t *Receive_Buffer); +uint32_t baseOfAdressType(uint8_t type); +uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); +void OPDfuIni(uint8_t discover); +void DataDownload(DownloadAction); +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); +#endif /* __OP_DFU_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/targets/Bootloaders/PipXtreme/inc/pios_config.h b/flight/targets/Bootloaders/PipXtreme/inc/pios_config.h index f378c66b7..fbd493cc6 100644 --- a/flight/targets/Bootloaders/PipXtreme/inc/pios_config.h +++ b/flight/targets/Bootloaders/PipXtreme/inc/pios_config.h @@ -1,52 +1,52 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @{ - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * Central compile time config for the project. - * In particular, pios_config.h is where you define which PiOS libraries - * and features are included in the firmware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* Enable/Disable PiOS modules */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_COM_MSG -#define PIOS_INCLUDE_BL_HELPER -#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT - -#endif /* PIOS_CONFIG_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotBL OpenPilot BootLoader + * @{ + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * In particular, pios_config.h is where you define which PiOS libraries + * and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* Enable/Disable PiOS modules */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_COM_MSG +#define PIOS_INCLUDE_BL_HELPER +#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT + +#endif /* PIOS_CONFIG_H */ + +/** + * @} + * @} + */ diff --git a/flight/targets/Bootloaders/PipXtreme/main.c b/flight/targets/Bootloaders/PipXtreme/main.c index 840009b77..a7757f63b 100644 --- a/flight/targets/Bootloaders/PipXtreme/main.c +++ b/flight/targets/Bootloaders/PipXtreme/main.c @@ -1,205 +1,205 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @brief These files contain the code to the OpenPilot MB Bootloader. - * - * @{ - * @file main.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This is the file with the main function of the OpenPilot BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -/* Bootloader Includes */ -#include -#include -#include "op_dfu.h" -#include "usb_lib.h" -#include "pios_iap.h" -#include "fifo_buffer.h" -#include "pios_com_msg.h" -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void FLASH_Download(); -#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) - -/* Private typedef -----------------------------------------------------------*/ -typedef void (*pFunction)(void); -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -pFunction Jump_To_Application; -uint32_t JumpAddress; - -/// LEDs PWM -uint32_t period1 = 5000; // 5 mS -uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS -uint32_t period2 = 5000; // 5 mS -uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS - - -//////////////////////////////////////// -uint8_t tempcount = 0; - -/* Extern variables ----------------------------------------------------------*/ -DFUStates DeviceState; -int16_t status = 0; -uint8_t JumpToApp = FALSE; -uint8_t GO_dfu = FALSE; -uint8_t USB_connected = FALSE; -uint8_t User_DFU_request = FALSE; -static uint8_t mReceive_Buffer[63]; -/* Private function prototypes -----------------------------------------------*/ -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); -uint8_t processRX(); -void jump_to_app(); - -int main() { - PIOS_SYS_Init(); - PIOS_Board_Init(); - PIOS_IAP_Init(); - - USB_connected = PIOS_USB_CableConnected(0); - - if (PIOS_IAP_CheckRequest() == TRUE) { - PIOS_DELAY_WaitmS(1000); - User_DFU_request = TRUE; - PIOS_IAP_ClearRequest(); - } - - GO_dfu = (USB_connected == TRUE) || (User_DFU_request == TRUE); - - if (GO_dfu == TRUE) { - PIOS_Board_Init(); - if (User_DFU_request == TRUE) - DeviceState = DFUidle; - else - DeviceState = BLidle; - } else - JumpToApp = TRUE; - - uint32_t stopwatch = 0; - uint32_t prev_ticks = PIOS_DELAY_GetuS(); - while (TRUE) { - /* Update the stopwatch */ - uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); - prev_ticks += elapsed_ticks; - stopwatch += elapsed_ticks; - - if (JumpToApp == TRUE) - jump_to_app(); - - switch (DeviceState) { - case Last_operation_Success: - case uploadingStarting: - case DFUidle: - period1 = 5000; - sweep_steps1 = 100; - PIOS_LED_Off(PIOS_LED_ALARM); - period2 = 0; - break; - case uploading: - period1 = 5000; - sweep_steps1 = 100; - period2 = 2500; - sweep_steps2 = 50; - break; - case downloading: - period1 = 2500; - sweep_steps1 = 50; - PIOS_LED_Off(PIOS_LED_ALARM); - period2 = 0; - break; - case BLidle: - period1 = 0; - PIOS_LED_On(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - default://error - period1 = 5000; - sweep_steps1 = 100; - period2 = 5000; - sweep_steps2 = 100; - } - - if (period1 != 0) { - if (LedPWM(period1, sweep_steps1, stopwatch)) - PIOS_LED_On(PIOS_LED_HEARTBEAT); - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else - PIOS_LED_On(PIOS_LED_HEARTBEAT); - - if (period2 != 0) { - if (LedPWM(period2, sweep_steps2, stopwatch)) - PIOS_LED_On(PIOS_LED_ALARM); - else - PIOS_LED_Off(PIOS_LED_ALARM); - } else - PIOS_LED_Off(PIOS_LED_ALARM); - - if (stopwatch > 50 * 1000 * 1000) - stopwatch = 0; - if ((stopwatch > 6 * 1000 * 1000) && (DeviceState - == BLidle)) - JumpToApp = TRUE; - - processRX(); - DataDownload(start); - } -} - -void jump_to_app() { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - - if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ - FLASH_Lock(); - RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); - RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); - _SetCNTR(0); // clear interrupt mask - _SetISTR(0); // clear all requests - JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); - Jump_To_Application = (pFunction) JumpAddress; - /* Initialize user application's Stack Pointer */ - __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); - Jump_To_Application(); - } else { - DeviceState = failed_jump; - return; - } -} -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { - uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ - uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ - - uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ - if (curr_sweep & 1) { - pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ - } - return ((count % pwm_period) > pwm_duty) ? 1 : 0; -} - -uint8_t processRX() { - if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { - processComand(mReceive_Buffer); - } - return TRUE; -} - +/** + ****************************************************************************** + * @addtogroup OpenPilotBL OpenPilot BootLoader + * @brief These files contain the code to the OpenPilot MB Bootloader. + * + * @{ + * @file main.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This is the file with the main function of the OpenPilot BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/* Bootloader Includes */ +#include +#include +#include "op_dfu.h" +#include "usb_lib.h" +#include "pios_iap.h" +#include "fifo_buffer.h" +#include "pios_com_msg.h" +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void FLASH_Download(); +#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) + +/* Private typedef -----------------------------------------------------------*/ +typedef void (*pFunction)(void); +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +pFunction Jump_To_Application; +uint32_t JumpAddress; + +/// LEDs PWM +uint32_t period1 = 5000; // 5 mS +uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS +uint32_t period2 = 5000; // 5 mS +uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS + + +//////////////////////////////////////// +uint8_t tempcount = 0; + +/* Extern variables ----------------------------------------------------------*/ +DFUStates DeviceState; +int16_t status = 0; +uint8_t JumpToApp = FALSE; +uint8_t GO_dfu = FALSE; +uint8_t USB_connected = FALSE; +uint8_t User_DFU_request = FALSE; +static uint8_t mReceive_Buffer[63]; +/* Private function prototypes -----------------------------------------------*/ +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); +uint8_t processRX(); +void jump_to_app(); + +int main() { + PIOS_SYS_Init(); + PIOS_Board_Init(); + PIOS_IAP_Init(); + + USB_connected = PIOS_USB_CableConnected(0); + + if (PIOS_IAP_CheckRequest() == TRUE) { + PIOS_DELAY_WaitmS(1000); + User_DFU_request = TRUE; + PIOS_IAP_ClearRequest(); + } + + GO_dfu = (USB_connected == TRUE) || (User_DFU_request == TRUE); + + if (GO_dfu == TRUE) { + PIOS_Board_Init(); + if (User_DFU_request == TRUE) + DeviceState = DFUidle; + else + DeviceState = BLidle; + } else + JumpToApp = TRUE; + + uint32_t stopwatch = 0; + uint32_t prev_ticks = PIOS_DELAY_GetuS(); + while (TRUE) { + /* Update the stopwatch */ + uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); + prev_ticks += elapsed_ticks; + stopwatch += elapsed_ticks; + + if (JumpToApp == TRUE) + jump_to_app(); + + switch (DeviceState) { + case Last_operation_Success: + case uploadingStarting: + case DFUidle: + period1 = 5000; + sweep_steps1 = 100; + PIOS_LED_Off(PIOS_LED_ALARM); + period2 = 0; + break; + case uploading: + period1 = 5000; + sweep_steps1 = 100; + period2 = 2500; + sweep_steps2 = 50; + break; + case downloading: + period1 = 2500; + sweep_steps1 = 50; + PIOS_LED_Off(PIOS_LED_ALARM); + period2 = 0; + break; + case BLidle: + period1 = 0; + PIOS_LED_On(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + default://error + period1 = 5000; + sweep_steps1 = 100; + period2 = 5000; + sweep_steps2 = 100; + } + + if (period1 != 0) { + if (LedPWM(period1, sweep_steps1, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_On(PIOS_LED_HEARTBEAT); + + if (period2 != 0) { + if (LedPWM(period2, sweep_steps2, stopwatch)) + PIOS_LED_On(PIOS_LED_ALARM); + else + PIOS_LED_Off(PIOS_LED_ALARM); + } else + PIOS_LED_Off(PIOS_LED_ALARM); + + if (stopwatch > 50 * 1000 * 1000) + stopwatch = 0; + if ((stopwatch > 6 * 1000 * 1000) && (DeviceState + == BLidle)) + JumpToApp = TRUE; + + processRX(); + DataDownload(start); + } +} + +void jump_to_app() { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ + FLASH_Lock(); + RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); + RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); + _SetCNTR(0); // clear interrupt mask + _SetISTR(0); // clear all requests + JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); + Jump_To_Application = (pFunction) JumpAddress; + /* Initialize user application's Stack Pointer */ + __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); + Jump_To_Application(); + } else { + DeviceState = failed_jump; + return; + } +} +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { + uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ + uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ + + uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ + if (curr_sweep & 1) { + pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ + } + return ((count % pwm_period) > pwm_duty) ? 1 : 0; +} + +uint8_t processRX() { + if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { + processComand(mReceive_Buffer); + } + return TRUE; +} + diff --git a/flight/targets/Bootloaders/PipXtreme/op_dfu.c b/flight/targets/Bootloaders/PipXtreme/op_dfu.c index 249e3d320..009771f4a 100644 --- a/flight/targets/Bootloaders/PipXtreme/op_dfu.c +++ b/flight/targets/Bootloaders/PipXtreme/op_dfu.c @@ -1,467 +1,467 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotBL OpenPilot BootLoader - * @brief These files contain the code to the OpenPilot MB Bootloader. - * - * @{ - * @file op_dfu.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This file contains the DFU commands handling code - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Includes ------------------------------------------------------------------*/ -#include "pios.h" -#include "op_dfu.h" -#include "pios_bl_helper.h" -#include "pios_com_msg.h" -#include -//programmable devices -Device devicesTable[10]; -uint8_t numberOfDevices = 0; - -DFUProgType currentProgrammingDestination; //flash, flash_trough spi -uint8_t currentDeviceCanRead; -uint8_t currentDeviceCanWrite; -Device currentDevice; - -uint8_t Buffer[64]; -uint8_t echoBuffer[64]; -uint8_t SendBuffer[64]; -uint8_t Command = 0; -uint8_t EchoReqFlag = 0; -uint8_t EchoAnsFlag = 0; -uint8_t StartFlag = 0; -uint32_t Aditionals = 0; -uint32_t SizeOfTransfer = 0; -uint32_t Expected_CRC = 0; -uint8_t SizeOfLastPacket = 0; -uint32_t Next_Packet = 0; -uint8_t TransferType; -uint32_t Count = 0; -uint32_t Data; -uint8_t Data0; -uint8_t Data1; -uint8_t Data2; -uint8_t Data3; -uint8_t offset = 0; -uint32_t aux; -//Download vars -uint32_t downSizeOfLastPacket = 0; -uint32_t downPacketTotal = 0; -uint32_t downPacketCurrent = 0; -DFUTransfer downType = 0; -/* Extern variables ----------------------------------------------------------*/ -extern DFUStates DeviceState; -extern uint8_t JumpToApp; -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -void sendData(uint8_t * buf, uint16_t size); -uint32_t CalcFirmCRC(void); - -void DataDownload(DownloadAction action) { - if ((DeviceState == downloading)) { - - uint8_t packetSize; - uint32_t offset; - uint32_t partoffset; - SendBuffer[0] = 0x01; - SendBuffer[1] = Download; - SendBuffer[2] = downPacketCurrent >> 24; - SendBuffer[3] = downPacketCurrent >> 16; - SendBuffer[4] = downPacketCurrent >> 8; - SendBuffer[5] = downPacketCurrent; - if (downPacketCurrent == downPacketTotal - 1) { - packetSize = downSizeOfLastPacket; - } else { - packetSize = 14; - } - for (uint8_t x = 0; x < packetSize; ++x) { - partoffset = (downPacketCurrent * 14 * 4) + (x * 4); - offset = baseOfAdressType(downType) + partoffset; - if (!flash_read(SendBuffer + (6 + x * 4), offset, - currentProgrammingDestination)) { - DeviceState = Last_operation_failed; - } - } - downPacketCurrent = downPacketCurrent + 1; - if (downPacketCurrent > downPacketTotal - 1) { - DeviceState = Last_operation_Success; - Aditionals = (uint32_t) Download; - } - sendData(SendBuffer + 1, 63); - } -} -void processComand(uint8_t *xReceive_Buffer) { - - Command = xReceive_Buffer[COMMAND]; -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Received COMMAND:%d|",Command); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - EchoReqFlag = (Command >> 7); - EchoAnsFlag = (Command >> 6) & 0x01; - StartFlag = (Command >> 5) & 0x01; - Count = xReceive_Buffer[COUNT] << 24; - Count += xReceive_Buffer[COUNT + 1] << 16; - Count += xReceive_Buffer[COUNT + 2] << 8; - Count += xReceive_Buffer[COUNT + 3]; - - Data = xReceive_Buffer[DATA] << 24; - Data += xReceive_Buffer[DATA + 1] << 16; - Data += xReceive_Buffer[DATA + 2] << 8; - Data += xReceive_Buffer[DATA + 3]; - Data0 = xReceive_Buffer[DATA]; - Data1 = xReceive_Buffer[DATA + 1]; - Data2 = xReceive_Buffer[DATA + 2]; - Data3 = xReceive_Buffer[DATA + 3]; - Command = Command & 0b00011111; - - if (EchoReqFlag == 1) { - memcpy(echoBuffer, Buffer, 64); - } - switch (Command) { - case EnterDFU: - if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) - || (DeviceState == DFUidle)) { - if (Data0 > 0) - OPDfuIni(TRUE); - DeviceState = DFUidle; - currentProgrammingDestination = devicesTable[Data0].programmingType; - currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; - currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 - & 0x01; - currentDevice = devicesTable[Data0]; - uint8_t result = 0; - switch (currentProgrammingDestination) { - case Self_flash: - result = PIOS_BL_HELPER_FLASH_Ini(); - break; - case Remote_flash_via_spi: - result = TRUE; - break; - default: - DeviceState = Last_operation_failed; - Aditionals = (uint16_t) Command; - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - } - break; - case Upload: - if ((DeviceState == DFUidle) || (DeviceState == uploading)) { - if ((StartFlag == 1) && (Next_Packet == 0)) { - TransferType = Data0; - SizeOfTransfer = Count; - Next_Packet = 1; - Expected_CRC = Data2 << 24; - Expected_CRC += Data3 << 16; - Expected_CRC += xReceive_Buffer[DATA + 4] << 8; - Expected_CRC += xReceive_Buffer[DATA + 5]; - SizeOfLastPacket = Data1; - - if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) - * 14 * 4 + SizeOfLastPacket * 4) == TRUE) { - DeviceState = outsideDevCapabilities; - Aditionals = (uint32_t) Command; - } else { - uint8_t result = 1; - if (TransferType == FW) { - switch (currentProgrammingDestination) { - case Self_flash: - result = PIOS_BL_HELPER_FLASH_Start(); - break; - case Remote_flash_via_spi: - result = FALSE; - break; - default: - break; - } - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } else { - - DeviceState = uploading; - } - } - } else if ((StartFlag != 1) && (Next_Packet != 0)) { - if (Count > SizeOfTransfer) { - DeviceState = too_many_packets; - Aditionals = Count; - } else if (Count == Next_Packet - 1) { - uint8_t numberOfWords = 14; - if (Count == SizeOfTransfer - 1)//is this the last packet? - { - numberOfWords = SizeOfLastPacket; - } - uint8_t result = 0; - switch (currentProgrammingDestination) { - case Self_flash: - for (uint8_t x = 0; x < numberOfWords; ++x) { - offset = 4 * x; - Data = xReceive_Buffer[DATA + offset] << 24; - Data += xReceive_Buffer[DATA + 1 + offset] << 16; - Data += xReceive_Buffer[DATA + 2 + offset] << 8; - Data += xReceive_Buffer[DATA + 3 + offset]; - aux = baseOfAdressType(TransferType) + (uint32_t)( - Count * 14 * 4 + x * 4); - result = 0; - for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { - if (result == 0) { - result = (FLASH_ProgramWord(aux, Data) - == FLASH_COMPLETE) ? 1 : 0; - } - } - } - break; - case Remote_flash_via_spi: - result = FALSE; // No support for this for the PipX - break; - default: - result = 0; - break; - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - - ++Next_Packet; - } else { - DeviceState = wrong_packet_received; - Aditionals = Count; - } - } else { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - } - break; - case Req_Capabilities: - OPDfuIni(TRUE); - Buffer[0] = 0x01; - Buffer[1] = Rep_Capabilities; - if (Data0 == 0) { - Buffer[2] = 0; - Buffer[3] = 0; - Buffer[4] = 0; - Buffer[5] = 0; - Buffer[6] = 0; - Buffer[7] = numberOfDevices; - uint16_t WRFlags = 0; - for (int x = 0; x < numberOfDevices; ++x) { - WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) - | WRFlags); - } - Buffer[8] = WRFlags >> 8; - Buffer[9] = WRFlags; - } else { - Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; - Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; - Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; - Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; - Buffer[6] = Data0; - Buffer[7] = devicesTable[Data0 - 1].BL_Version; - Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; - Buffer[9] = devicesTable[Data0 - 1].devID; - Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; - Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; - Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; - Buffer[13] = devicesTable[Data0 - 1].FW_Crc; - Buffer[14] = devicesTable[Data0 - 1].devID >> 8; - Buffer[15] = devicesTable[Data0 - 1].devID; - } - sendData(Buffer + 1, 63); - break; - case JumpFW: - if (Data == 0x5AFE) { - /* Force board into safe mode */ - PIOS_IAP_WriteBootCount(0xFFFF); - } - FLASH_Lock(); - JumpToApp = 1; - break; - case Reset: - PIOS_SYS_Reset(); - break; - case Abort_Operation: - Next_Packet = 0; - DeviceState = DFUidle; - break; - - case Op_END: - if (DeviceState == uploading) { - if (Next_Packet - 1 == SizeOfTransfer) { - Next_Packet = 0; - if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { - DeviceState = Last_operation_Success; - } else { - DeviceState = CRC_Fail; - } - } - if (Next_Packet - 1 < SizeOfTransfer) { - Next_Packet = 0; - DeviceState = too_few_packets; - } - } - break; - case Download_Req: -#ifdef DEBUG_SSP - sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - if (DeviceState == DFUidle) { -#ifdef DEBUG_SSP - PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); -#endif - downType = Data0; - downPacketTotal = Count; - downSizeOfLastPacket = Data1; - if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 - + downSizeOfLastPacket) == 1) { - DeviceState = outsideDevCapabilities; - Aditionals = (uint32_t) Command; - - } else { - downPacketCurrent = 0; - DeviceState = downloading; - } - } else { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - break; - - case Status_Request: - Buffer[0] = 0x01; - Buffer[1] = Status_Rep; - if (DeviceState == wrong_packet_received) { - Buffer[2] = Aditionals >> 24; - Buffer[3] = Aditionals >> 16; - Buffer[4] = Aditionals >> 8; - Buffer[5] = Aditionals; - } else { - Buffer[2] = 0; - Buffer[3] = ((uint16_t) Aditionals) >> 8; - Buffer[4] = ((uint16_t) Aditionals); - Buffer[5] = 0; - } - Buffer[6] = DeviceState; - Buffer[7] = 0; - Buffer[8] = 0; - Buffer[9] = 0; - sendData(Buffer + 1, 63); - if (DeviceState == Last_operation_Success) { - DeviceState = DFUidle; - } - break; - case Status_Rep: - - break; - - } - if (EchoReqFlag == 1) { - echoBuffer[1] = echoBuffer[1] | EchoAnsFlag; - sendData(echoBuffer + 1, 63); - } - return; -} -void OPDfuIni(uint8_t discover) { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - Device dev; - - dev.programmingType = Self_flash; - dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); - dev.startOfUserCode = bdinfo->fw_base; - dev.sizeOfCode = bdinfo->fw_size; - dev.sizeOfDescription = bdinfo->desc_size; - dev.BL_Version = bdinfo->bl_rev; - dev.FW_Crc = CalcFirmCRC(); - dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); - dev.devType = bdinfo->hw_type; - numberOfDevices = 1; - devicesTable[0] = dev; - if (discover) { - //TODO check other devices trough spi or whatever - } -} -uint32_t baseOfAdressType(DFUTransfer type) { - switch (type) { - case FW: - return currentDevice.startOfUserCode; - break; - case Descript: - return currentDevice.startOfUserCode + currentDevice.sizeOfCode; - break; - default: - - return 0; - } -} -uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { - switch (type) { - case FW: - return (size > currentDevice.sizeOfCode) ? 1 : 0; - break; - case Descript: - return (size > currentDevice.sizeOfDescription) ? 1 : 0; - break; - default: - return TRUE; - } -} - -uint32_t CalcFirmCRC() { - switch (currentProgrammingDestination) { - case Self_flash: - return PIOS_BL_HELPER_CRC_Memory_Calc(); - break; - case Remote_flash_via_spi: - return 0; - break; - default: - return 0; - break; - } - -} -void sendData(uint8_t * buf, uint16_t size) { - PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); -} - -bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { - switch (type) { - case Remote_flash_via_spi: - return FALSE; // We should not get this for the PipX - break; - case Self_flash: - for (uint8_t x = 0; x < 4; ++x) { - buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); - } - return TRUE; - break; - default: - return FALSE; - } -} +/** + ****************************************************************************** + * @addtogroup OpenPilotBL OpenPilot BootLoader + * @brief These files contain the code to the OpenPilot MB Bootloader. + * + * @{ + * @file op_dfu.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains the DFU commands handling code + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Includes ------------------------------------------------------------------*/ +#include "pios.h" +#include "op_dfu.h" +#include "pios_bl_helper.h" +#include "pios_com_msg.h" +#include +//programmable devices +Device devicesTable[10]; +uint8_t numberOfDevices = 0; + +DFUProgType currentProgrammingDestination; //flash, flash_trough spi +uint8_t currentDeviceCanRead; +uint8_t currentDeviceCanWrite; +Device currentDevice; + +uint8_t Buffer[64]; +uint8_t echoBuffer[64]; +uint8_t SendBuffer[64]; +uint8_t Command = 0; +uint8_t EchoReqFlag = 0; +uint8_t EchoAnsFlag = 0; +uint8_t StartFlag = 0; +uint32_t Aditionals = 0; +uint32_t SizeOfTransfer = 0; +uint32_t Expected_CRC = 0; +uint8_t SizeOfLastPacket = 0; +uint32_t Next_Packet = 0; +uint8_t TransferType; +uint32_t Count = 0; +uint32_t Data; +uint8_t Data0; +uint8_t Data1; +uint8_t Data2; +uint8_t Data3; +uint8_t offset = 0; +uint32_t aux; +//Download vars +uint32_t downSizeOfLastPacket = 0; +uint32_t downPacketTotal = 0; +uint32_t downPacketCurrent = 0; +DFUTransfer downType = 0; +/* Extern variables ----------------------------------------------------------*/ +extern DFUStates DeviceState; +extern uint8_t JumpToApp; +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +void sendData(uint8_t * buf, uint16_t size); +uint32_t CalcFirmCRC(void); + +void DataDownload(DownloadAction action) { + if ((DeviceState == downloading)) { + + uint8_t packetSize; + uint32_t offset; + uint32_t partoffset; + SendBuffer[0] = 0x01; + SendBuffer[1] = Download; + SendBuffer[2] = downPacketCurrent >> 24; + SendBuffer[3] = downPacketCurrent >> 16; + SendBuffer[4] = downPacketCurrent >> 8; + SendBuffer[5] = downPacketCurrent; + if (downPacketCurrent == downPacketTotal - 1) { + packetSize = downSizeOfLastPacket; + } else { + packetSize = 14; + } + for (uint8_t x = 0; x < packetSize; ++x) { + partoffset = (downPacketCurrent * 14 * 4) + (x * 4); + offset = baseOfAdressType(downType) + partoffset; + if (!flash_read(SendBuffer + (6 + x * 4), offset, + currentProgrammingDestination)) { + DeviceState = Last_operation_failed; + } + } + downPacketCurrent = downPacketCurrent + 1; + if (downPacketCurrent > downPacketTotal - 1) { + DeviceState = Last_operation_Success; + Aditionals = (uint32_t) Download; + } + sendData(SendBuffer + 1, 63); + } +} +void processComand(uint8_t *xReceive_Buffer) { + + Command = xReceive_Buffer[COMMAND]; +#ifdef DEBUG_SSP + char str[63]= {0}; + sprintf(str,"Received COMMAND:%d|",Command); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + EchoReqFlag = (Command >> 7); + EchoAnsFlag = (Command >> 6) & 0x01; + StartFlag = (Command >> 5) & 0x01; + Count = xReceive_Buffer[COUNT] << 24; + Count += xReceive_Buffer[COUNT + 1] << 16; + Count += xReceive_Buffer[COUNT + 2] << 8; + Count += xReceive_Buffer[COUNT + 3]; + + Data = xReceive_Buffer[DATA] << 24; + Data += xReceive_Buffer[DATA + 1] << 16; + Data += xReceive_Buffer[DATA + 2] << 8; + Data += xReceive_Buffer[DATA + 3]; + Data0 = xReceive_Buffer[DATA]; + Data1 = xReceive_Buffer[DATA + 1]; + Data2 = xReceive_Buffer[DATA + 2]; + Data3 = xReceive_Buffer[DATA + 3]; + Command = Command & 0b00011111; + + if (EchoReqFlag == 1) { + memcpy(echoBuffer, Buffer, 64); + } + switch (Command) { + case EnterDFU: + if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) + || (DeviceState == DFUidle)) { + if (Data0 > 0) + OPDfuIni(TRUE); + DeviceState = DFUidle; + currentProgrammingDestination = devicesTable[Data0].programmingType; + currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; + currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 + & 0x01; + currentDevice = devicesTable[Data0]; + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Ini(); + break; + case Remote_flash_via_spi: + result = TRUE; + break; + default: + DeviceState = Last_operation_failed; + Aditionals = (uint16_t) Command; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Upload: + if ((DeviceState == DFUidle) || (DeviceState == uploading)) { + if ((StartFlag == 1) && (Next_Packet == 0)) { + TransferType = Data0; + SizeOfTransfer = Count; + Next_Packet = 1; + Expected_CRC = Data2 << 24; + Expected_CRC += Data3 << 16; + Expected_CRC += xReceive_Buffer[DATA + 4] << 8; + Expected_CRC += xReceive_Buffer[DATA + 5]; + SizeOfLastPacket = Data1; + + if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) + * 14 * 4 + SizeOfLastPacket * 4) == TRUE) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + } else { + uint8_t result = 1; + if (TransferType == FW) { + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Start(); + break; + case Remote_flash_via_spi: + result = FALSE; + break; + default: + break; + } + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } else { + + DeviceState = uploading; + } + } + } else if ((StartFlag != 1) && (Next_Packet != 0)) { + if (Count > SizeOfTransfer) { + DeviceState = too_many_packets; + Aditionals = Count; + } else if (Count == Next_Packet - 1) { + uint8_t numberOfWords = 14; + if (Count == SizeOfTransfer - 1)//is this the last packet? + { + numberOfWords = SizeOfLastPacket; + } + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + for (uint8_t x = 0; x < numberOfWords; ++x) { + offset = 4 * x; + Data = xReceive_Buffer[DATA + offset] << 24; + Data += xReceive_Buffer[DATA + 1 + offset] << 16; + Data += xReceive_Buffer[DATA + 2 + offset] << 8; + Data += xReceive_Buffer[DATA + 3 + offset]; + aux = baseOfAdressType(TransferType) + (uint32_t)( + Count * 14 * 4 + x * 4); + result = 0; + for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { + if (result == 0) { + result = (FLASH_ProgramWord(aux, Data) + == FLASH_COMPLETE) ? 1 : 0; + } + } + } + break; + case Remote_flash_via_spi: + result = FALSE; // No support for this for the PipX + break; + default: + result = 0; + break; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + + ++Next_Packet; + } else { + DeviceState = wrong_packet_received; + Aditionals = Count; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Req_Capabilities: + OPDfuIni(TRUE); + Buffer[0] = 0x01; + Buffer[1] = Rep_Capabilities; + if (Data0 == 0) { + Buffer[2] = 0; + Buffer[3] = 0; + Buffer[4] = 0; + Buffer[5] = 0; + Buffer[6] = 0; + Buffer[7] = numberOfDevices; + uint16_t WRFlags = 0; + for (int x = 0; x < numberOfDevices; ++x) { + WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) + | WRFlags); + } + Buffer[8] = WRFlags >> 8; + Buffer[9] = WRFlags; + } else { + Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; + Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; + Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; + Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; + Buffer[6] = Data0; + Buffer[7] = devicesTable[Data0 - 1].BL_Version; + Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; + Buffer[9] = devicesTable[Data0 - 1].devID; + Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; + Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; + Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; + Buffer[13] = devicesTable[Data0 - 1].FW_Crc; + Buffer[14] = devicesTable[Data0 - 1].devID >> 8; + Buffer[15] = devicesTable[Data0 - 1].devID; + } + sendData(Buffer + 1, 63); + break; + case JumpFW: + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); + } + FLASH_Lock(); + JumpToApp = 1; + break; + case Reset: + PIOS_SYS_Reset(); + break; + case Abort_Operation: + Next_Packet = 0; + DeviceState = DFUidle; + break; + + case Op_END: + if (DeviceState == uploading) { + if (Next_Packet - 1 == SizeOfTransfer) { + Next_Packet = 0; + if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { + DeviceState = Last_operation_Success; + } else { + DeviceState = CRC_Fail; + } + } + if (Next_Packet - 1 < SizeOfTransfer) { + Next_Packet = 0; + DeviceState = too_few_packets; + } + } + break; + case Download_Req: +#ifdef DEBUG_SSP + sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + if (DeviceState == DFUidle) { +#ifdef DEBUG_SSP + PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); +#endif + downType = Data0; + downPacketTotal = Count; + downSizeOfLastPacket = Data1; + if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 + + downSizeOfLastPacket) == 1) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + + } else { + downPacketCurrent = 0; + DeviceState = downloading; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + break; + + case Status_Request: + Buffer[0] = 0x01; + Buffer[1] = Status_Rep; + if (DeviceState == wrong_packet_received) { + Buffer[2] = Aditionals >> 24; + Buffer[3] = Aditionals >> 16; + Buffer[4] = Aditionals >> 8; + Buffer[5] = Aditionals; + } else { + Buffer[2] = 0; + Buffer[3] = ((uint16_t) Aditionals) >> 8; + Buffer[4] = ((uint16_t) Aditionals); + Buffer[5] = 0; + } + Buffer[6] = DeviceState; + Buffer[7] = 0; + Buffer[8] = 0; + Buffer[9] = 0; + sendData(Buffer + 1, 63); + if (DeviceState == Last_operation_Success) { + DeviceState = DFUidle; + } + break; + case Status_Rep: + + break; + + } + if (EchoReqFlag == 1) { + echoBuffer[1] = echoBuffer[1] | EchoAnsFlag; + sendData(echoBuffer + 1, 63); + } + return; +} +void OPDfuIni(uint8_t discover) { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + Device dev; + + dev.programmingType = Self_flash; + dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); + dev.startOfUserCode = bdinfo->fw_base; + dev.sizeOfCode = bdinfo->fw_size; + dev.sizeOfDescription = bdinfo->desc_size; + dev.BL_Version = bdinfo->bl_rev; + dev.FW_Crc = CalcFirmCRC(); + dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); + dev.devType = bdinfo->hw_type; + numberOfDevices = 1; + devicesTable[0] = dev; + if (discover) { + //TODO check other devices trough spi or whatever + } +} +uint32_t baseOfAdressType(DFUTransfer type) { + switch (type) { + case FW: + return currentDevice.startOfUserCode; + break; + case Descript: + return currentDevice.startOfUserCode + currentDevice.sizeOfCode; + break; + default: + + return 0; + } +} +uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { + switch (type) { + case FW: + return (size > currentDevice.sizeOfCode) ? 1 : 0; + break; + case Descript: + return (size > currentDevice.sizeOfDescription) ? 1 : 0; + break; + default: + return TRUE; + } +} + +uint32_t CalcFirmCRC() { + switch (currentProgrammingDestination) { + case Self_flash: + return PIOS_BL_HELPER_CRC_Memory_Calc(); + break; + case Remote_flash_via_spi: + return 0; + break; + default: + return 0; + break; + } + +} +void sendData(uint8_t * buf, uint16_t size) { + PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); +} + +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { + switch (type) { + case Remote_flash_via_spi: + return FALSE; // We should not get this for the PipX + break; + case Self_flash: + for (uint8_t x = 0; x < 4; ++x) { + buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); + } + return TRUE; + break; + default: + return FALSE; + } +} diff --git a/flight/targets/Bootloaders/RevoMini/inc/common.h b/flight/targets/Bootloaders/RevoMini/inc/common.h index 9ecff4079..9010fddd9 100644 --- a/flight/targets/Bootloaders/RevoMini/inc/common.h +++ b/flight/targets/Bootloaders/RevoMini/inc/common.h @@ -1,115 +1,115 @@ -/** - ****************************************************************************** - * @addtogroup CopterControlBL CopterControl BootLoader - * @brief These files contain the code to the CopterControl Bootloader. - * - * @{ - * @file common.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This file contains various common defines for the BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef COMMON_H_ -#define COMMON_H_ - -//#include "board.h" - -typedef enum { - start, keepgoing, -} DownloadAction; - -/**************************************************/ -/* OP_DFU states */ -/**************************************************/ - -typedef enum { - DFUidle, //0 - uploading, //1 - wrong_packet_received, //2 - too_many_packets, //3 - too_few_packets, //4 - Last_operation_Success, //5 - downloading, //6 - BLidle, //7 - Last_operation_failed, //8 - uploadingStarting, //9 - outsideDevCapabilities, //10 - CRC_Fail,//11 - failed_jump, -//12 -} DFUStates; -/**************************************************/ -/* OP_DFU commands */ -/**************************************************/ -typedef enum { - Reserved, //0 - Req_Capabilities, //1 - Rep_Capabilities, //2 - EnterDFU, //3 - JumpFW, //4 - Reset, //5 - Abort_Operation, //6 - Upload, //7 - Op_END, //8 - Download_Req, //9 - Download, //10 - Status_Request, //11 - Status_Rep -//12 -} DFUCommands; - -typedef enum { - High_Density, Medium_Density -} DeviceType; -/**************************************************/ -/* OP_DFU transfer types */ -/**************************************************/ -typedef enum { - FW, //0 - Descript -//2 -} DFUTransfer; -/**************************************************/ -/* OP_DFU transfer port */ -/**************************************************/ -typedef enum { - Usb, //0 - Serial -//2 -} DFUPort; -/**************************************************/ -/* OP_DFU programable programable HW types */ -/**************************************************/ -typedef enum { - Self_flash, //0 - Remote_flash_via_spi -//1 -} DFUProgType; -/**************************************************/ -/* OP_DFU programable sources */ -/**************************************************/ -#define USB 0 -#define SPI 1 - -#define DownloadDelay 100000 - -#define MAX_DEL_RETRYS 3 -#define MAX_WRI_RETRYS 3 - -#endif /* COMMON_H_ */ +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file common.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains various common defines for the BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef COMMON_H_ +#define COMMON_H_ + +//#include "board.h" + +typedef enum { + start, keepgoing, +} DownloadAction; + +/**************************************************/ +/* OP_DFU states */ +/**************************************************/ + +typedef enum { + DFUidle, //0 + uploading, //1 + wrong_packet_received, //2 + too_many_packets, //3 + too_few_packets, //4 + Last_operation_Success, //5 + downloading, //6 + BLidle, //7 + Last_operation_failed, //8 + uploadingStarting, //9 + outsideDevCapabilities, //10 + CRC_Fail,//11 + failed_jump, +//12 +} DFUStates; +/**************************************************/ +/* OP_DFU commands */ +/**************************************************/ +typedef enum { + Reserved, //0 + Req_Capabilities, //1 + Rep_Capabilities, //2 + EnterDFU, //3 + JumpFW, //4 + Reset, //5 + Abort_Operation, //6 + Upload, //7 + Op_END, //8 + Download_Req, //9 + Download, //10 + Status_Request, //11 + Status_Rep +//12 +} DFUCommands; + +typedef enum { + High_Density, Medium_Density +} DeviceType; +/**************************************************/ +/* OP_DFU transfer types */ +/**************************************************/ +typedef enum { + FW, //0 + Descript +//2 +} DFUTransfer; +/**************************************************/ +/* OP_DFU transfer port */ +/**************************************************/ +typedef enum { + Usb, //0 + Serial +//2 +} DFUPort; +/**************************************************/ +/* OP_DFU programable programable HW types */ +/**************************************************/ +typedef enum { + Self_flash, //0 + Remote_flash_via_spi +//1 +} DFUProgType; +/**************************************************/ +/* OP_DFU programable sources */ +/**************************************************/ +#define USB 0 +#define SPI 1 + +#define DownloadDelay 100000 + +#define MAX_DEL_RETRYS 3 +#define MAX_WRI_RETRYS 3 + +#endif /* COMMON_H_ */ diff --git a/flight/targets/Bootloaders/RevoMini/inc/op_dfu.h b/flight/targets/Bootloaders/RevoMini/inc/op_dfu.h index e031c3364..262852fc4 100644 --- a/flight/targets/Bootloaders/RevoMini/inc/op_dfu.h +++ b/flight/targets/Bootloaders/RevoMini/inc/op_dfu.h @@ -1,60 +1,60 @@ -/** - ****************************************************************************** - * - * @file op_dfu.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __OP_DFU_H -#define __OP_DFU_H -#include "common.h" -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -typedef struct { - uint8_t programmingType; - uint8_t readWriteFlags; - uint32_t startOfUserCode; - uint32_t sizeOfCode; - uint8_t sizeOfDescription; - uint8_t BL_Version; - uint16_t devID; - DeviceType devType; - uint32_t FW_Crc; -} Device; - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported define -----------------------------------------------------------*/ -#define COMMAND 0 -#define COUNT 1 -#define DATA 5 - -/* Exported functions ------------------------------------------------------- */ -void processComand(uint8_t *Receive_Buffer); -uint32_t baseOfAdressType(uint8_t type); -uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); -void OPDfuIni(uint8_t discover); -void DataDownload(DownloadAction); -bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); -#endif /* __OP_DFU_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * + * @file op_dfu.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __OP_DFU_H +#define __OP_DFU_H +#include "common.h" +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef struct { + uint8_t programmingType; + uint8_t readWriteFlags; + uint32_t startOfUserCode; + uint32_t sizeOfCode; + uint8_t sizeOfDescription; + uint8_t BL_Version; + uint16_t devID; + DeviceType devType; + uint32_t FW_Crc; +} Device; + +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported define -----------------------------------------------------------*/ +#define COMMAND 0 +#define COUNT 1 +#define DATA 5 + +/* Exported functions ------------------------------------------------------- */ +void processComand(uint8_t *Receive_Buffer); +uint32_t baseOfAdressType(uint8_t type); +uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); +void OPDfuIni(uint8_t discover); +void DataDownload(DownloadAction); +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); +#endif /* __OP_DFU_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/targets/Bootloaders/RevoMini/inc/pios_config.h b/flight/targets/Bootloaders/RevoMini/inc/pios_config.h index 91c131ed3..86fedc699 100644 --- a/flight/targets/Bootloaders/RevoMini/inc/pios_config.h +++ b/flight/targets/Bootloaders/RevoMini/inc/pios_config.h @@ -1,43 +1,43 @@ -/** - ****************************************************************************** - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * - Central compile time config for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - - -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_COM_MSG -#define PIOS_INCLUDE_BL_HELPER -#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT - -#endif /* PIOS_CONFIG_H */ +/** + ****************************************************************************** + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * - Central compile time config for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + + +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_COM_MSG +#define PIOS_INCLUDE_BL_HELPER +#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT + +#endif /* PIOS_CONFIG_H */ diff --git a/flight/targets/Bootloaders/RevoMini/main.c b/flight/targets/Bootloaders/RevoMini/main.c index 6fb4fd8e6..f644836f4 100644 --- a/flight/targets/Bootloaders/RevoMini/main.c +++ b/flight/targets/Bootloaders/RevoMini/main.c @@ -1,230 +1,230 @@ -/** - ****************************************************************************** - * @addtogroup RevolutionBL Revolution BootLoader - * @brief These files contain the code to the Revolution Bootloader. - * - * @{ - * @file main.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This is the file with the main function of the Revolution BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -/* Bootloader Includes */ -#include -#include -#include -#include "op_dfu.h" -#include "pios_iap.h" -#include "fifo_buffer.h" -#include "pios_com_msg.h" -#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void FLASH_Download(); -void check_bor(); -#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) - -/* Private typedef -----------------------------------------------------------*/ -typedef void (*pFunction)(void); -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -pFunction Jump_To_Application; -uint32_t JumpAddress; - -/// LEDs PWM -uint32_t period1 = 5000; // 5 mS -uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS -uint32_t period2 = 5000; // 5 mS -uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS - - -//////////////////////////////////////// -uint8_t tempcount = 0; - -/* Extern variables ----------------------------------------------------------*/ -DFUStates DeviceState; -int16_t status = 0; -bool JumpToApp = false; -bool GO_dfu = false; -bool USB_connected = false; -bool User_DFU_request = false; -static uint8_t mReceive_Buffer[63]; -/* Private function prototypes -----------------------------------------------*/ -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); -uint8_t processRX(); -void jump_to_app(); - -int main() { - PIOS_SYS_Init(); - PIOS_Board_Init(); - PIOS_IAP_Init(); - - // Make sure the brown out reset value for this chip - // is 2.7 volts - check_bor(); - - USB_connected = PIOS_USB_CheckAvailable(0); - - if (PIOS_IAP_CheckRequest() == true) { - PIOS_DELAY_WaitmS(1000); - User_DFU_request = true; - PIOS_IAP_ClearRequest(); - } - - GO_dfu = (USB_connected == true) || (User_DFU_request == true); - - if (GO_dfu == true) { - if (User_DFU_request == true) - DeviceState = DFUidle; - else - DeviceState = BLidle; - } else - JumpToApp = true; - - uint32_t stopwatch = 0; - uint32_t prev_ticks = PIOS_DELAY_GetuS(); - while (true) { - /* Update the stopwatch */ - uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); - prev_ticks += elapsed_ticks; - stopwatch += elapsed_ticks; - - if (JumpToApp == true) - jump_to_app(); - - switch (DeviceState) { - case Last_operation_Success: - case uploadingStarting: - case DFUidle: - period1 = 5000; - sweep_steps1 = 100; - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - case uploading: - period1 = 5000; - sweep_steps1 = 100; - period2 = 2500; - sweep_steps2 = 50; - break; - case downloading: - period1 = 2500; - sweep_steps1 = 50; - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - case BLidle: - period1 = 0; - PIOS_LED_On(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - default://error - period1 = 5000; - sweep_steps1 = 100; - period2 = 5000; - sweep_steps2 = 100; - } - - if (period1 != 0) { - if (LedPWM(period1, sweep_steps1, stopwatch)) - PIOS_LED_On(PIOS_LED_HEARTBEAT); - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else - PIOS_LED_On(PIOS_LED_HEARTBEAT); - - if (period2 != 0) { - if (LedPWM(period2, sweep_steps2, stopwatch)) - PIOS_LED_On(PIOS_LED_HEARTBEAT); - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - - if (stopwatch > 50 * 1000 * 1000) - stopwatch = 0; - if ((stopwatch > 6 * 1000 * 1000) && (DeviceState - == BLidle)) - JumpToApp = true; - - processRX(); - DataDownload(start); - } -} - -void jump_to_app() { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - - PIOS_LED_On(PIOS_LED_HEARTBEAT); - if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ - FLASH_Lock(); - RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); - RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); - - PIOS_USBHOOK_Deactivate(); - - JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); - Jump_To_Application = (pFunction) JumpAddress; - /* Initialize user application's Stack Pointer */ - __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); - Jump_To_Application(); - } else { - DeviceState = failed_jump; - return; - } -} -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { - uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ - uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ - - uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ - if (curr_sweep & 1) { - pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ - } - return ((count % pwm_period) > pwm_duty) ? 1 : 0; -} - -uint8_t processRX() { - if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { - processComand(mReceive_Buffer); - } - return true; -} - -/** - * Check the brown out reset threshold is 2.7 volts and if not - * resets it. This solves an issue that can prevent boards - * powering up with some BEC - */ -void check_bor() -{ - uint8_t bor = FLASH_OB_GetBOR(); - if(bor != OB_BOR_LEVEL3) { - FLASH_OB_Unlock(); - FLASH_OB_BORConfig(OB_BOR_LEVEL3); - FLASH_OB_Launch(); - while(FLASH_WaitForLastOperation() == FLASH_BUSY); - FLASH_OB_Lock(); - while(FLASH_WaitForLastOperation() == FLASH_BUSY); - } -} - +/** + ****************************************************************************** + * @addtogroup RevolutionBL Revolution BootLoader + * @brief These files contain the code to the Revolution Bootloader. + * + * @{ + * @file main.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This is the file with the main function of the Revolution BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/* Bootloader Includes */ +#include +#include +#include +#include "op_dfu.h" +#include "pios_iap.h" +#include "fifo_buffer.h" +#include "pios_com_msg.h" +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void FLASH_Download(); +void check_bor(); +#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) + +/* Private typedef -----------------------------------------------------------*/ +typedef void (*pFunction)(void); +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +pFunction Jump_To_Application; +uint32_t JumpAddress; + +/// LEDs PWM +uint32_t period1 = 5000; // 5 mS +uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS +uint32_t period2 = 5000; // 5 mS +uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS + + +//////////////////////////////////////// +uint8_t tempcount = 0; + +/* Extern variables ----------------------------------------------------------*/ +DFUStates DeviceState; +int16_t status = 0; +bool JumpToApp = false; +bool GO_dfu = false; +bool USB_connected = false; +bool User_DFU_request = false; +static uint8_t mReceive_Buffer[63]; +/* Private function prototypes -----------------------------------------------*/ +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); +uint8_t processRX(); +void jump_to_app(); + +int main() { + PIOS_SYS_Init(); + PIOS_Board_Init(); + PIOS_IAP_Init(); + + // Make sure the brown out reset value for this chip + // is 2.7 volts + check_bor(); + + USB_connected = PIOS_USB_CheckAvailable(0); + + if (PIOS_IAP_CheckRequest() == true) { + PIOS_DELAY_WaitmS(1000); + User_DFU_request = true; + PIOS_IAP_ClearRequest(); + } + + GO_dfu = (USB_connected == true) || (User_DFU_request == true); + + if (GO_dfu == true) { + if (User_DFU_request == true) + DeviceState = DFUidle; + else + DeviceState = BLidle; + } else + JumpToApp = true; + + uint32_t stopwatch = 0; + uint32_t prev_ticks = PIOS_DELAY_GetuS(); + while (true) { + /* Update the stopwatch */ + uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); + prev_ticks += elapsed_ticks; + stopwatch += elapsed_ticks; + + if (JumpToApp == true) + jump_to_app(); + + switch (DeviceState) { + case Last_operation_Success: + case uploadingStarting: + case DFUidle: + period1 = 5000; + sweep_steps1 = 100; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case uploading: + period1 = 5000; + sweep_steps1 = 100; + period2 = 2500; + sweep_steps2 = 50; + break; + case downloading: + period1 = 2500; + sweep_steps1 = 50; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case BLidle: + period1 = 0; + PIOS_LED_On(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + default://error + period1 = 5000; + sweep_steps1 = 100; + period2 = 5000; + sweep_steps2 = 100; + } + + if (period1 != 0) { + if (LedPWM(period1, sweep_steps1, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_On(PIOS_LED_HEARTBEAT); + + if (period2 != 0) { + if (LedPWM(period2, sweep_steps2, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + + if (stopwatch > 50 * 1000 * 1000) + stopwatch = 0; + if ((stopwatch > 6 * 1000 * 1000) && (DeviceState + == BLidle)) + JumpToApp = true; + + processRX(); + DataDownload(start); + } +} + +void jump_to_app() { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + PIOS_LED_On(PIOS_LED_HEARTBEAT); + if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ + FLASH_Lock(); + RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); + RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); + + PIOS_USBHOOK_Deactivate(); + + JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); + Jump_To_Application = (pFunction) JumpAddress; + /* Initialize user application's Stack Pointer */ + __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); + Jump_To_Application(); + } else { + DeviceState = failed_jump; + return; + } +} +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { + uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ + uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ + + uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ + if (curr_sweep & 1) { + pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ + } + return ((count % pwm_period) > pwm_duty) ? 1 : 0; +} + +uint8_t processRX() { + if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { + processComand(mReceive_Buffer); + } + return true; +} + +/** + * Check the brown out reset threshold is 2.7 volts and if not + * resets it. This solves an issue that can prevent boards + * powering up with some BEC + */ +void check_bor() +{ + uint8_t bor = FLASH_OB_GetBOR(); + if(bor != OB_BOR_LEVEL3) { + FLASH_OB_Unlock(); + FLASH_OB_BORConfig(OB_BOR_LEVEL3); + FLASH_OB_Launch(); + while(FLASH_WaitForLastOperation() == FLASH_BUSY); + FLASH_OB_Lock(); + while(FLASH_WaitForLastOperation() == FLASH_BUSY); + } +} + diff --git a/flight/targets/Bootloaders/RevoMini/op_dfu.c b/flight/targets/Bootloaders/RevoMini/op_dfu.c index 3aceedcfb..16281dd4d 100644 --- a/flight/targets/Bootloaders/RevoMini/op_dfu.c +++ b/flight/targets/Bootloaders/RevoMini/op_dfu.c @@ -1,468 +1,468 @@ -/** - ****************************************************************************** - * @addtogroup CopterControlBL CopterControl BootLoader - * @brief These files contain the code to the CopterControl Bootloader. - * - * @{ - * @file op_dfu.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This file contains the DFU commands handling code - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Includes ------------------------------------------------------------------*/ -#include "pios.h" -#include -#include "op_dfu.h" -#include "pios_bl_helper.h" -#include "pios_com_msg.h" -#include -//programmable devices -Device devicesTable[10]; -uint8_t numberOfDevices = 0; - -DFUProgType currentProgrammingDestination; //flash, flash_trough spi -uint8_t currentDeviceCanRead; -uint8_t currentDeviceCanWrite; -Device currentDevice; - -uint8_t Buffer[64]; -uint8_t echoBuffer[64]; -uint8_t SendBuffer[64]; -uint8_t Command = 0; -uint8_t EchoReqFlag = 0; -uint8_t EchoAnsFlag = 0; -uint8_t StartFlag = 0; -uint32_t Aditionals = 0; -uint32_t SizeOfTransfer = 0; -uint32_t Expected_CRC = 0; -uint8_t SizeOfLastPacket = 0; -uint32_t Next_Packet = 0; -uint8_t TransferType; -uint32_t Count = 0; -uint32_t Data; -uint8_t Data0; -uint8_t Data1; -uint8_t Data2; -uint8_t Data3; -uint8_t offset = 0; -uint32_t aux; -//Download vars -uint32_t downSizeOfLastPacket = 0; -uint32_t downPacketTotal = 0; -uint32_t downPacketCurrent = 0; -DFUTransfer downType = 0; -/* Extern variables ----------------------------------------------------------*/ -extern DFUStates DeviceState; -extern uint8_t JumpToApp; -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -void sendData(uint8_t * buf, uint16_t size); -uint32_t CalcFirmCRC(void); - -void DataDownload(DownloadAction action) { - if ((DeviceState == downloading)) { - - uint8_t packetSize; - uint32_t offset; - uint32_t partoffset; - SendBuffer[0] = 0x01; - SendBuffer[1] = Download; - SendBuffer[2] = downPacketCurrent >> 24; - SendBuffer[3] = downPacketCurrent >> 16; - SendBuffer[4] = downPacketCurrent >> 8; - SendBuffer[5] = downPacketCurrent; - if (downPacketCurrent == downPacketTotal - 1) { - packetSize = downSizeOfLastPacket; - } else { - packetSize = 14; - } - for (uint8_t x = 0; x < packetSize; ++x) { - partoffset = (downPacketCurrent * 14 * 4) + (x * 4); - offset = baseOfAdressType(downType) + partoffset; - if (!flash_read(SendBuffer + (6 + x * 4), offset, - currentProgrammingDestination)) { - DeviceState = Last_operation_failed; - } - } - downPacketCurrent = downPacketCurrent + 1; - if (downPacketCurrent > downPacketTotal - 1) { - DeviceState = Last_operation_Success; - Aditionals = (uint32_t) Download; - } - sendData(SendBuffer + 1, 63); - } -} -void processComand(uint8_t *xReceive_Buffer) { - - Command = xReceive_Buffer[COMMAND]; -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Received COMMAND:%d|",Command); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - EchoReqFlag = (Command >> 7); - EchoAnsFlag = (Command >> 6) & 0x01; - StartFlag = (Command >> 5) & 0x01; - Count = xReceive_Buffer[COUNT] << 24; - Count += xReceive_Buffer[COUNT + 1] << 16; - Count += xReceive_Buffer[COUNT + 2] << 8; - Count += xReceive_Buffer[COUNT + 3]; - - Data = xReceive_Buffer[DATA] << 24; - Data += xReceive_Buffer[DATA + 1] << 16; - Data += xReceive_Buffer[DATA + 2] << 8; - Data += xReceive_Buffer[DATA + 3]; - Data0 = xReceive_Buffer[DATA]; - Data1 = xReceive_Buffer[DATA + 1]; - Data2 = xReceive_Buffer[DATA + 2]; - Data3 = xReceive_Buffer[DATA + 3]; - Command = Command & 0b00011111; - - if (EchoReqFlag == 1) { - memcpy(echoBuffer, xReceive_Buffer, 64); - } - switch (Command) { - case EnterDFU: - if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) - || (DeviceState == DFUidle)) { - if (Data0 > 0) - OPDfuIni(true); - DeviceState = DFUidle; - currentProgrammingDestination = devicesTable[Data0].programmingType; - currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; - currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 - & 0x01; - currentDevice = devicesTable[Data0]; - uint8_t result = 0; - switch (currentProgrammingDestination) { - case Self_flash: - result = PIOS_BL_HELPER_FLASH_Ini(); - break; - case Remote_flash_via_spi: - result = true; - break; - default: - DeviceState = Last_operation_failed; - Aditionals = (uint16_t) Command; - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - } - break; - case Upload: - if ((DeviceState == DFUidle) || (DeviceState == uploading)) { - if ((StartFlag == 1) && (Next_Packet == 0)) { - TransferType = Data0; - SizeOfTransfer = Count; - Next_Packet = 1; - Expected_CRC = Data2 << 24; - Expected_CRC += Data3 << 16; - Expected_CRC += xReceive_Buffer[DATA + 4] << 8; - Expected_CRC += xReceive_Buffer[DATA + 5]; - SizeOfLastPacket = Data1; - - if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) - * 14 * 4 + SizeOfLastPacket * 4) == true) { - DeviceState = outsideDevCapabilities; - Aditionals = (uint32_t) Command; - } else { - uint8_t result = 1; - if (TransferType == FW) { - switch (currentProgrammingDestination) { - case Self_flash: - result = PIOS_BL_HELPER_FLASH_Start(); - break; - case Remote_flash_via_spi: - result = false; - break; - default: - break; - } - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } else { - - DeviceState = uploading; - } - } - } else if ((StartFlag != 1) && (Next_Packet != 0)) { - if (Count > SizeOfTransfer) { - DeviceState = too_many_packets; - Aditionals = Count; - } else if (Count == Next_Packet - 1) { - uint8_t numberOfWords = 14; - if (Count == SizeOfTransfer - 1)//is this the last packet? - { - numberOfWords = SizeOfLastPacket; - } - uint8_t result = 0; - switch (currentProgrammingDestination) { - case Self_flash: - for (uint8_t x = 0; x < numberOfWords; ++x) { - offset = 4 * x; - Data = xReceive_Buffer[DATA + offset] << 24; - Data += xReceive_Buffer[DATA + 1 + offset] << 16; - Data += xReceive_Buffer[DATA + 2 + offset] << 8; - Data += xReceive_Buffer[DATA + 3 + offset]; - aux = baseOfAdressType(TransferType) + (uint32_t)( - Count * 14 * 4 + x * 4); - result = 0; - for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { - if (result == 0) { - result = (FLASH_ProgramWord(aux, Data) - == FLASH_COMPLETE) ? 1 : 0; - } - } - } - break; - case Remote_flash_via_spi: - result = false; // No support for this for the PipX - break; - default: - result = 0; - break; - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - - ++Next_Packet; - } else { - DeviceState = wrong_packet_received; - Aditionals = Count; - } - } else { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - } - break; - case Req_Capabilities: - OPDfuIni(true); - Buffer[0] = 0x01; - Buffer[1] = Rep_Capabilities; - if (Data0 == 0) { - Buffer[2] = 0; - Buffer[3] = 0; - Buffer[4] = 0; - Buffer[5] = 0; - Buffer[6] = 0; - Buffer[7] = numberOfDevices; - uint16_t WRFlags = 0; - for (int x = 0; x < numberOfDevices; ++x) { - WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) - | WRFlags); - } - Buffer[8] = WRFlags >> 8; - Buffer[9] = WRFlags; - } else { - Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; - Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; - Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; - Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; - Buffer[6] = Data0; - Buffer[7] = devicesTable[Data0 - 1].BL_Version; - Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; - Buffer[9] = devicesTable[Data0 - 1].devID; - Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; - Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; - Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; - Buffer[13] = devicesTable[Data0 - 1].FW_Crc; - Buffer[14] = devicesTable[Data0 - 1].devID >> 8; - Buffer[15] = devicesTable[Data0 - 1].devID; - } - sendData(Buffer + 1, 63); - break; - case JumpFW: - if (Data == 0x5AFE) { - /* Force board into safe mode */ - PIOS_IAP_WriteBootCount(0xFFFF); - } - FLASH_Lock(); - JumpToApp = 1; - break; - case Reset: - PIOS_SYS_Reset(); - break; - case Abort_Operation: - Next_Packet = 0; - DeviceState = DFUidle; - break; - - case Op_END: - if (DeviceState == uploading) { - if (Next_Packet - 1 == SizeOfTransfer) { - Next_Packet = 0; - if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { - DeviceState = Last_operation_Success; - } else { - DeviceState = CRC_Fail; - } - } - if (Next_Packet - 1 < SizeOfTransfer) { - Next_Packet = 0; - DeviceState = too_few_packets; - } - } - break; - case Download_Req: -#ifdef DEBUG_SSP - sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - if (DeviceState == DFUidle) { -#ifdef DEBUG_SSP - PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); -#endif - downType = Data0; - downPacketTotal = Count; - downSizeOfLastPacket = Data1; - if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 * 4 - + downSizeOfLastPacket * 4) == 1) { - DeviceState = outsideDevCapabilities; - Aditionals = (uint32_t) Command; - - } else { - downPacketCurrent = 0; - DeviceState = downloading; - } - } else { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - break; - - case Status_Request: - Buffer[0] = 0x01; - Buffer[1] = Status_Rep; - if (DeviceState == wrong_packet_received) { - Buffer[2] = Aditionals >> 24; - Buffer[3] = Aditionals >> 16; - Buffer[4] = Aditionals >> 8; - Buffer[5] = Aditionals; - } else { - Buffer[2] = 0; - Buffer[3] = ((uint16_t) Aditionals) >> 8; - Buffer[4] = ((uint16_t) Aditionals); - Buffer[5] = 0; - } - Buffer[6] = DeviceState; - Buffer[7] = 0; - Buffer[8] = 0; - Buffer[9] = 0; - sendData(Buffer + 1, 63); - if (DeviceState == Last_operation_Success) { - DeviceState = DFUidle; - } - break; - case Status_Rep: - - break; - - } - if (EchoReqFlag == 1) { - echoBuffer[0] = echoBuffer[0] | (1 << 6); - sendData(echoBuffer, 63); - } - return; -} -void OPDfuIni(uint8_t discover) { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - Device dev; - - dev.programmingType = Self_flash; - dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); - dev.startOfUserCode = bdinfo->fw_base; - dev.sizeOfCode = bdinfo->fw_size; - dev.sizeOfDescription = bdinfo->desc_size; - dev.BL_Version = bdinfo->bl_rev; - dev.FW_Crc = CalcFirmCRC(); - dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); - dev.devType = bdinfo->hw_type; - numberOfDevices = 1; - devicesTable[0] = dev; - if (discover) { - //TODO check other devices trough spi or whatever - } -} -uint32_t baseOfAdressType(DFUTransfer type) { - switch (type) { - case FW: - return currentDevice.startOfUserCode; - break; - case Descript: - return currentDevice.startOfUserCode + currentDevice.sizeOfCode; - break; - default: - - return 0; - } -} -uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { - switch (type) { - case FW: - return (size > currentDevice.sizeOfCode) ? 1 : 0; - break; - case Descript: - return (size > currentDevice.sizeOfDescription) ? 1 : 0; - break; - default: - return true; - } -} - -uint32_t CalcFirmCRC() { - switch (currentProgrammingDestination) { - case Self_flash: - return PIOS_BL_HELPER_CRC_Memory_Calc(); - break; - case Remote_flash_via_spi: - return 0; - break; - default: - return 0; - break; - } - -} -void sendData(uint8_t * buf, uint16_t size) { - PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); -} - -bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { - switch (type) { - case Remote_flash_via_spi: - return false; // We should not get this for the PipX - break; - case Self_flash: - for (uint8_t x = 0; x < 4; ++x) { - buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); - } - return true; - break; - default: - return false; - } -} +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file op_dfu.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains the DFU commands handling code + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Includes ------------------------------------------------------------------*/ +#include "pios.h" +#include +#include "op_dfu.h" +#include "pios_bl_helper.h" +#include "pios_com_msg.h" +#include +//programmable devices +Device devicesTable[10]; +uint8_t numberOfDevices = 0; + +DFUProgType currentProgrammingDestination; //flash, flash_trough spi +uint8_t currentDeviceCanRead; +uint8_t currentDeviceCanWrite; +Device currentDevice; + +uint8_t Buffer[64]; +uint8_t echoBuffer[64]; +uint8_t SendBuffer[64]; +uint8_t Command = 0; +uint8_t EchoReqFlag = 0; +uint8_t EchoAnsFlag = 0; +uint8_t StartFlag = 0; +uint32_t Aditionals = 0; +uint32_t SizeOfTransfer = 0; +uint32_t Expected_CRC = 0; +uint8_t SizeOfLastPacket = 0; +uint32_t Next_Packet = 0; +uint8_t TransferType; +uint32_t Count = 0; +uint32_t Data; +uint8_t Data0; +uint8_t Data1; +uint8_t Data2; +uint8_t Data3; +uint8_t offset = 0; +uint32_t aux; +//Download vars +uint32_t downSizeOfLastPacket = 0; +uint32_t downPacketTotal = 0; +uint32_t downPacketCurrent = 0; +DFUTransfer downType = 0; +/* Extern variables ----------------------------------------------------------*/ +extern DFUStates DeviceState; +extern uint8_t JumpToApp; +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +void sendData(uint8_t * buf, uint16_t size); +uint32_t CalcFirmCRC(void); + +void DataDownload(DownloadAction action) { + if ((DeviceState == downloading)) { + + uint8_t packetSize; + uint32_t offset; + uint32_t partoffset; + SendBuffer[0] = 0x01; + SendBuffer[1] = Download; + SendBuffer[2] = downPacketCurrent >> 24; + SendBuffer[3] = downPacketCurrent >> 16; + SendBuffer[4] = downPacketCurrent >> 8; + SendBuffer[5] = downPacketCurrent; + if (downPacketCurrent == downPacketTotal - 1) { + packetSize = downSizeOfLastPacket; + } else { + packetSize = 14; + } + for (uint8_t x = 0; x < packetSize; ++x) { + partoffset = (downPacketCurrent * 14 * 4) + (x * 4); + offset = baseOfAdressType(downType) + partoffset; + if (!flash_read(SendBuffer + (6 + x * 4), offset, + currentProgrammingDestination)) { + DeviceState = Last_operation_failed; + } + } + downPacketCurrent = downPacketCurrent + 1; + if (downPacketCurrent > downPacketTotal - 1) { + DeviceState = Last_operation_Success; + Aditionals = (uint32_t) Download; + } + sendData(SendBuffer + 1, 63); + } +} +void processComand(uint8_t *xReceive_Buffer) { + + Command = xReceive_Buffer[COMMAND]; +#ifdef DEBUG_SSP + char str[63]= {0}; + sprintf(str,"Received COMMAND:%d|",Command); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + EchoReqFlag = (Command >> 7); + EchoAnsFlag = (Command >> 6) & 0x01; + StartFlag = (Command >> 5) & 0x01; + Count = xReceive_Buffer[COUNT] << 24; + Count += xReceive_Buffer[COUNT + 1] << 16; + Count += xReceive_Buffer[COUNT + 2] << 8; + Count += xReceive_Buffer[COUNT + 3]; + + Data = xReceive_Buffer[DATA] << 24; + Data += xReceive_Buffer[DATA + 1] << 16; + Data += xReceive_Buffer[DATA + 2] << 8; + Data += xReceive_Buffer[DATA + 3]; + Data0 = xReceive_Buffer[DATA]; + Data1 = xReceive_Buffer[DATA + 1]; + Data2 = xReceive_Buffer[DATA + 2]; + Data3 = xReceive_Buffer[DATA + 3]; + Command = Command & 0b00011111; + + if (EchoReqFlag == 1) { + memcpy(echoBuffer, xReceive_Buffer, 64); + } + switch (Command) { + case EnterDFU: + if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) + || (DeviceState == DFUidle)) { + if (Data0 > 0) + OPDfuIni(true); + DeviceState = DFUidle; + currentProgrammingDestination = devicesTable[Data0].programmingType; + currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; + currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 + & 0x01; + currentDevice = devicesTable[Data0]; + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Ini(); + break; + case Remote_flash_via_spi: + result = true; + break; + default: + DeviceState = Last_operation_failed; + Aditionals = (uint16_t) Command; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Upload: + if ((DeviceState == DFUidle) || (DeviceState == uploading)) { + if ((StartFlag == 1) && (Next_Packet == 0)) { + TransferType = Data0; + SizeOfTransfer = Count; + Next_Packet = 1; + Expected_CRC = Data2 << 24; + Expected_CRC += Data3 << 16; + Expected_CRC += xReceive_Buffer[DATA + 4] << 8; + Expected_CRC += xReceive_Buffer[DATA + 5]; + SizeOfLastPacket = Data1; + + if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) + * 14 * 4 + SizeOfLastPacket * 4) == true) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + } else { + uint8_t result = 1; + if (TransferType == FW) { + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Start(); + break; + case Remote_flash_via_spi: + result = false; + break; + default: + break; + } + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } else { + + DeviceState = uploading; + } + } + } else if ((StartFlag != 1) && (Next_Packet != 0)) { + if (Count > SizeOfTransfer) { + DeviceState = too_many_packets; + Aditionals = Count; + } else if (Count == Next_Packet - 1) { + uint8_t numberOfWords = 14; + if (Count == SizeOfTransfer - 1)//is this the last packet? + { + numberOfWords = SizeOfLastPacket; + } + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + for (uint8_t x = 0; x < numberOfWords; ++x) { + offset = 4 * x; + Data = xReceive_Buffer[DATA + offset] << 24; + Data += xReceive_Buffer[DATA + 1 + offset] << 16; + Data += xReceive_Buffer[DATA + 2 + offset] << 8; + Data += xReceive_Buffer[DATA + 3 + offset]; + aux = baseOfAdressType(TransferType) + (uint32_t)( + Count * 14 * 4 + x * 4); + result = 0; + for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { + if (result == 0) { + result = (FLASH_ProgramWord(aux, Data) + == FLASH_COMPLETE) ? 1 : 0; + } + } + } + break; + case Remote_flash_via_spi: + result = false; // No support for this for the PipX + break; + default: + result = 0; + break; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + + ++Next_Packet; + } else { + DeviceState = wrong_packet_received; + Aditionals = Count; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Req_Capabilities: + OPDfuIni(true); + Buffer[0] = 0x01; + Buffer[1] = Rep_Capabilities; + if (Data0 == 0) { + Buffer[2] = 0; + Buffer[3] = 0; + Buffer[4] = 0; + Buffer[5] = 0; + Buffer[6] = 0; + Buffer[7] = numberOfDevices; + uint16_t WRFlags = 0; + for (int x = 0; x < numberOfDevices; ++x) { + WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) + | WRFlags); + } + Buffer[8] = WRFlags >> 8; + Buffer[9] = WRFlags; + } else { + Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; + Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; + Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; + Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; + Buffer[6] = Data0; + Buffer[7] = devicesTable[Data0 - 1].BL_Version; + Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; + Buffer[9] = devicesTable[Data0 - 1].devID; + Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; + Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; + Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; + Buffer[13] = devicesTable[Data0 - 1].FW_Crc; + Buffer[14] = devicesTable[Data0 - 1].devID >> 8; + Buffer[15] = devicesTable[Data0 - 1].devID; + } + sendData(Buffer + 1, 63); + break; + case JumpFW: + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); + } + FLASH_Lock(); + JumpToApp = 1; + break; + case Reset: + PIOS_SYS_Reset(); + break; + case Abort_Operation: + Next_Packet = 0; + DeviceState = DFUidle; + break; + + case Op_END: + if (DeviceState == uploading) { + if (Next_Packet - 1 == SizeOfTransfer) { + Next_Packet = 0; + if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { + DeviceState = Last_operation_Success; + } else { + DeviceState = CRC_Fail; + } + } + if (Next_Packet - 1 < SizeOfTransfer) { + Next_Packet = 0; + DeviceState = too_few_packets; + } + } + break; + case Download_Req: +#ifdef DEBUG_SSP + sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + if (DeviceState == DFUidle) { +#ifdef DEBUG_SSP + PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); +#endif + downType = Data0; + downPacketTotal = Count; + downSizeOfLastPacket = Data1; + if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 * 4 + + downSizeOfLastPacket * 4) == 1) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + + } else { + downPacketCurrent = 0; + DeviceState = downloading; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + break; + + case Status_Request: + Buffer[0] = 0x01; + Buffer[1] = Status_Rep; + if (DeviceState == wrong_packet_received) { + Buffer[2] = Aditionals >> 24; + Buffer[3] = Aditionals >> 16; + Buffer[4] = Aditionals >> 8; + Buffer[5] = Aditionals; + } else { + Buffer[2] = 0; + Buffer[3] = ((uint16_t) Aditionals) >> 8; + Buffer[4] = ((uint16_t) Aditionals); + Buffer[5] = 0; + } + Buffer[6] = DeviceState; + Buffer[7] = 0; + Buffer[8] = 0; + Buffer[9] = 0; + sendData(Buffer + 1, 63); + if (DeviceState == Last_operation_Success) { + DeviceState = DFUidle; + } + break; + case Status_Rep: + + break; + + } + if (EchoReqFlag == 1) { + echoBuffer[0] = echoBuffer[0] | (1 << 6); + sendData(echoBuffer, 63); + } + return; +} +void OPDfuIni(uint8_t discover) { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + Device dev; + + dev.programmingType = Self_flash; + dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); + dev.startOfUserCode = bdinfo->fw_base; + dev.sizeOfCode = bdinfo->fw_size; + dev.sizeOfDescription = bdinfo->desc_size; + dev.BL_Version = bdinfo->bl_rev; + dev.FW_Crc = CalcFirmCRC(); + dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); + dev.devType = bdinfo->hw_type; + numberOfDevices = 1; + devicesTable[0] = dev; + if (discover) { + //TODO check other devices trough spi or whatever + } +} +uint32_t baseOfAdressType(DFUTransfer type) { + switch (type) { + case FW: + return currentDevice.startOfUserCode; + break; + case Descript: + return currentDevice.startOfUserCode + currentDevice.sizeOfCode; + break; + default: + + return 0; + } +} +uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { + switch (type) { + case FW: + return (size > currentDevice.sizeOfCode) ? 1 : 0; + break; + case Descript: + return (size > currentDevice.sizeOfDescription) ? 1 : 0; + break; + default: + return true; + } +} + +uint32_t CalcFirmCRC() { + switch (currentProgrammingDestination) { + case Self_flash: + return PIOS_BL_HELPER_CRC_Memory_Calc(); + break; + case Remote_flash_via_spi: + return 0; + break; + default: + return 0; + break; + } + +} +void sendData(uint8_t * buf, uint16_t size) { + PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); +} + +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { + switch (type) { + case Remote_flash_via_spi: + return false; // We should not get this for the PipX + break; + case Self_flash: + for (uint8_t x = 0; x < 4; ++x) { + buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); + } + return true; + break; + default: + return false; + } +} diff --git a/flight/targets/Bootloaders/Revolution/inc/common.h b/flight/targets/Bootloaders/Revolution/inc/common.h index 9ecff4079..9010fddd9 100644 --- a/flight/targets/Bootloaders/Revolution/inc/common.h +++ b/flight/targets/Bootloaders/Revolution/inc/common.h @@ -1,115 +1,115 @@ -/** - ****************************************************************************** - * @addtogroup CopterControlBL CopterControl BootLoader - * @brief These files contain the code to the CopterControl Bootloader. - * - * @{ - * @file common.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This file contains various common defines for the BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef COMMON_H_ -#define COMMON_H_ - -//#include "board.h" - -typedef enum { - start, keepgoing, -} DownloadAction; - -/**************************************************/ -/* OP_DFU states */ -/**************************************************/ - -typedef enum { - DFUidle, //0 - uploading, //1 - wrong_packet_received, //2 - too_many_packets, //3 - too_few_packets, //4 - Last_operation_Success, //5 - downloading, //6 - BLidle, //7 - Last_operation_failed, //8 - uploadingStarting, //9 - outsideDevCapabilities, //10 - CRC_Fail,//11 - failed_jump, -//12 -} DFUStates; -/**************************************************/ -/* OP_DFU commands */ -/**************************************************/ -typedef enum { - Reserved, //0 - Req_Capabilities, //1 - Rep_Capabilities, //2 - EnterDFU, //3 - JumpFW, //4 - Reset, //5 - Abort_Operation, //6 - Upload, //7 - Op_END, //8 - Download_Req, //9 - Download, //10 - Status_Request, //11 - Status_Rep -//12 -} DFUCommands; - -typedef enum { - High_Density, Medium_Density -} DeviceType; -/**************************************************/ -/* OP_DFU transfer types */ -/**************************************************/ -typedef enum { - FW, //0 - Descript -//2 -} DFUTransfer; -/**************************************************/ -/* OP_DFU transfer port */ -/**************************************************/ -typedef enum { - Usb, //0 - Serial -//2 -} DFUPort; -/**************************************************/ -/* OP_DFU programable programable HW types */ -/**************************************************/ -typedef enum { - Self_flash, //0 - Remote_flash_via_spi -//1 -} DFUProgType; -/**************************************************/ -/* OP_DFU programable sources */ -/**************************************************/ -#define USB 0 -#define SPI 1 - -#define DownloadDelay 100000 - -#define MAX_DEL_RETRYS 3 -#define MAX_WRI_RETRYS 3 - -#endif /* COMMON_H_ */ +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file common.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains various common defines for the BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef COMMON_H_ +#define COMMON_H_ + +//#include "board.h" + +typedef enum { + start, keepgoing, +} DownloadAction; + +/**************************************************/ +/* OP_DFU states */ +/**************************************************/ + +typedef enum { + DFUidle, //0 + uploading, //1 + wrong_packet_received, //2 + too_many_packets, //3 + too_few_packets, //4 + Last_operation_Success, //5 + downloading, //6 + BLidle, //7 + Last_operation_failed, //8 + uploadingStarting, //9 + outsideDevCapabilities, //10 + CRC_Fail,//11 + failed_jump, +//12 +} DFUStates; +/**************************************************/ +/* OP_DFU commands */ +/**************************************************/ +typedef enum { + Reserved, //0 + Req_Capabilities, //1 + Rep_Capabilities, //2 + EnterDFU, //3 + JumpFW, //4 + Reset, //5 + Abort_Operation, //6 + Upload, //7 + Op_END, //8 + Download_Req, //9 + Download, //10 + Status_Request, //11 + Status_Rep +//12 +} DFUCommands; + +typedef enum { + High_Density, Medium_Density +} DeviceType; +/**************************************************/ +/* OP_DFU transfer types */ +/**************************************************/ +typedef enum { + FW, //0 + Descript +//2 +} DFUTransfer; +/**************************************************/ +/* OP_DFU transfer port */ +/**************************************************/ +typedef enum { + Usb, //0 + Serial +//2 +} DFUPort; +/**************************************************/ +/* OP_DFU programable programable HW types */ +/**************************************************/ +typedef enum { + Self_flash, //0 + Remote_flash_via_spi +//1 +} DFUProgType; +/**************************************************/ +/* OP_DFU programable sources */ +/**************************************************/ +#define USB 0 +#define SPI 1 + +#define DownloadDelay 100000 + +#define MAX_DEL_RETRYS 3 +#define MAX_WRI_RETRYS 3 + +#endif /* COMMON_H_ */ diff --git a/flight/targets/Bootloaders/Revolution/inc/op_dfu.h b/flight/targets/Bootloaders/Revolution/inc/op_dfu.h index e031c3364..262852fc4 100644 --- a/flight/targets/Bootloaders/Revolution/inc/op_dfu.h +++ b/flight/targets/Bootloaders/Revolution/inc/op_dfu.h @@ -1,60 +1,60 @@ -/** - ****************************************************************************** - * - * @file op_dfu.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __OP_DFU_H -#define __OP_DFU_H -#include "common.h" -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -typedef struct { - uint8_t programmingType; - uint8_t readWriteFlags; - uint32_t startOfUserCode; - uint32_t sizeOfCode; - uint8_t sizeOfDescription; - uint8_t BL_Version; - uint16_t devID; - DeviceType devType; - uint32_t FW_Crc; -} Device; - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported define -----------------------------------------------------------*/ -#define COMMAND 0 -#define COUNT 1 -#define DATA 5 - -/* Exported functions ------------------------------------------------------- */ -void processComand(uint8_t *Receive_Buffer); -uint32_t baseOfAdressType(uint8_t type); -uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); -void OPDfuIni(uint8_t discover); -void DataDownload(DownloadAction); -bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); -#endif /* __OP_DFU_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ +/** + ****************************************************************************** + * + * @file op_dfu.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __OP_DFU_H +#define __OP_DFU_H +#include "common.h" +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +typedef struct { + uint8_t programmingType; + uint8_t readWriteFlags; + uint32_t startOfUserCode; + uint32_t sizeOfCode; + uint8_t sizeOfDescription; + uint8_t BL_Version; + uint16_t devID; + DeviceType devType; + uint32_t FW_Crc; +} Device; + +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported define -----------------------------------------------------------*/ +#define COMMAND 0 +#define COUNT 1 +#define DATA 5 + +/* Exported functions ------------------------------------------------------- */ +void processComand(uint8_t *Receive_Buffer); +uint32_t baseOfAdressType(uint8_t type); +uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size); +void OPDfuIni(uint8_t discover); +void DataDownload(DownloadAction); +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type); +#endif /* __OP_DFU_H */ + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/targets/Bootloaders/Revolution/main.c b/flight/targets/Bootloaders/Revolution/main.c index 6fb4fd8e6..f644836f4 100644 --- a/flight/targets/Bootloaders/Revolution/main.c +++ b/flight/targets/Bootloaders/Revolution/main.c @@ -1,230 +1,230 @@ -/** - ****************************************************************************** - * @addtogroup RevolutionBL Revolution BootLoader - * @brief These files contain the code to the Revolution Bootloader. - * - * @{ - * @file main.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This is the file with the main function of the Revolution BootLoader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -/* Bootloader Includes */ -#include -#include -#include -#include "op_dfu.h" -#include "pios_iap.h" -#include "fifo_buffer.h" -#include "pios_com_msg.h" -#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void FLASH_Download(); -void check_bor(); -#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) - -/* Private typedef -----------------------------------------------------------*/ -typedef void (*pFunction)(void); -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -pFunction Jump_To_Application; -uint32_t JumpAddress; - -/// LEDs PWM -uint32_t period1 = 5000; // 5 mS -uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS -uint32_t period2 = 5000; // 5 mS -uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS - - -//////////////////////////////////////// -uint8_t tempcount = 0; - -/* Extern variables ----------------------------------------------------------*/ -DFUStates DeviceState; -int16_t status = 0; -bool JumpToApp = false; -bool GO_dfu = false; -bool USB_connected = false; -bool User_DFU_request = false; -static uint8_t mReceive_Buffer[63]; -/* Private function prototypes -----------------------------------------------*/ -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); -uint8_t processRX(); -void jump_to_app(); - -int main() { - PIOS_SYS_Init(); - PIOS_Board_Init(); - PIOS_IAP_Init(); - - // Make sure the brown out reset value for this chip - // is 2.7 volts - check_bor(); - - USB_connected = PIOS_USB_CheckAvailable(0); - - if (PIOS_IAP_CheckRequest() == true) { - PIOS_DELAY_WaitmS(1000); - User_DFU_request = true; - PIOS_IAP_ClearRequest(); - } - - GO_dfu = (USB_connected == true) || (User_DFU_request == true); - - if (GO_dfu == true) { - if (User_DFU_request == true) - DeviceState = DFUidle; - else - DeviceState = BLidle; - } else - JumpToApp = true; - - uint32_t stopwatch = 0; - uint32_t prev_ticks = PIOS_DELAY_GetuS(); - while (true) { - /* Update the stopwatch */ - uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); - prev_ticks += elapsed_ticks; - stopwatch += elapsed_ticks; - - if (JumpToApp == true) - jump_to_app(); - - switch (DeviceState) { - case Last_operation_Success: - case uploadingStarting: - case DFUidle: - period1 = 5000; - sweep_steps1 = 100; - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - case uploading: - period1 = 5000; - sweep_steps1 = 100; - period2 = 2500; - sweep_steps2 = 50; - break; - case downloading: - period1 = 2500; - sweep_steps1 = 50; - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - case BLidle: - period1 = 0; - PIOS_LED_On(PIOS_LED_HEARTBEAT); - period2 = 0; - break; - default://error - period1 = 5000; - sweep_steps1 = 100; - period2 = 5000; - sweep_steps2 = 100; - } - - if (period1 != 0) { - if (LedPWM(period1, sweep_steps1, stopwatch)) - PIOS_LED_On(PIOS_LED_HEARTBEAT); - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else - PIOS_LED_On(PIOS_LED_HEARTBEAT); - - if (period2 != 0) { - if (LedPWM(period2, sweep_steps2, stopwatch)) - PIOS_LED_On(PIOS_LED_HEARTBEAT); - else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - } else - PIOS_LED_Off(PIOS_LED_HEARTBEAT); - - if (stopwatch > 50 * 1000 * 1000) - stopwatch = 0; - if ((stopwatch > 6 * 1000 * 1000) && (DeviceState - == BLidle)) - JumpToApp = true; - - processRX(); - DataDownload(start); - } -} - -void jump_to_app() { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - - PIOS_LED_On(PIOS_LED_HEARTBEAT); - if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ - FLASH_Lock(); - RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); - RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); - RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); - - PIOS_USBHOOK_Deactivate(); - - JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); - Jump_To_Application = (pFunction) JumpAddress; - /* Initialize user application's Stack Pointer */ - __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); - Jump_To_Application(); - } else { - DeviceState = failed_jump; - return; - } -} -uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { - uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ - uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ - - uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ - if (curr_sweep & 1) { - pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ - } - return ((count % pwm_period) > pwm_duty) ? 1 : 0; -} - -uint8_t processRX() { - if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { - processComand(mReceive_Buffer); - } - return true; -} - -/** - * Check the brown out reset threshold is 2.7 volts and if not - * resets it. This solves an issue that can prevent boards - * powering up with some BEC - */ -void check_bor() -{ - uint8_t bor = FLASH_OB_GetBOR(); - if(bor != OB_BOR_LEVEL3) { - FLASH_OB_Unlock(); - FLASH_OB_BORConfig(OB_BOR_LEVEL3); - FLASH_OB_Launch(); - while(FLASH_WaitForLastOperation() == FLASH_BUSY); - FLASH_OB_Lock(); - while(FLASH_WaitForLastOperation() == FLASH_BUSY); - } -} - +/** + ****************************************************************************** + * @addtogroup RevolutionBL Revolution BootLoader + * @brief These files contain the code to the Revolution Bootloader. + * + * @{ + * @file main.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This is the file with the main function of the Revolution BootLoader + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +/* Bootloader Includes */ +#include +#include +#include +#include "op_dfu.h" +#include "pios_iap.h" +#include "fifo_buffer.h" +#include "pios_com_msg.h" +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void FLASH_Download(); +void check_bor(); +#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1) + +/* Private typedef -----------------------------------------------------------*/ +typedef void (*pFunction)(void); +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +pFunction Jump_To_Application; +uint32_t JumpAddress; + +/// LEDs PWM +uint32_t period1 = 5000; // 5 mS +uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS +uint32_t period2 = 5000; // 5 mS +uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS + + +//////////////////////////////////////// +uint8_t tempcount = 0; + +/* Extern variables ----------------------------------------------------------*/ +DFUStates DeviceState; +int16_t status = 0; +bool JumpToApp = false; +bool GO_dfu = false; +bool USB_connected = false; +bool User_DFU_request = false; +static uint8_t mReceive_Buffer[63]; +/* Private function prototypes -----------------------------------------------*/ +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); +uint8_t processRX(); +void jump_to_app(); + +int main() { + PIOS_SYS_Init(); + PIOS_Board_Init(); + PIOS_IAP_Init(); + + // Make sure the brown out reset value for this chip + // is 2.7 volts + check_bor(); + + USB_connected = PIOS_USB_CheckAvailable(0); + + if (PIOS_IAP_CheckRequest() == true) { + PIOS_DELAY_WaitmS(1000); + User_DFU_request = true; + PIOS_IAP_ClearRequest(); + } + + GO_dfu = (USB_connected == true) || (User_DFU_request == true); + + if (GO_dfu == true) { + if (User_DFU_request == true) + DeviceState = DFUidle; + else + DeviceState = BLidle; + } else + JumpToApp = true; + + uint32_t stopwatch = 0; + uint32_t prev_ticks = PIOS_DELAY_GetuS(); + while (true) { + /* Update the stopwatch */ + uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks); + prev_ticks += elapsed_ticks; + stopwatch += elapsed_ticks; + + if (JumpToApp == true) + jump_to_app(); + + switch (DeviceState) { + case Last_operation_Success: + case uploadingStarting: + case DFUidle: + period1 = 5000; + sweep_steps1 = 100; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case uploading: + period1 = 5000; + sweep_steps1 = 100; + period2 = 2500; + sweep_steps2 = 50; + break; + case downloading: + period1 = 2500; + sweep_steps1 = 50; + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + case BLidle: + period1 = 0; + PIOS_LED_On(PIOS_LED_HEARTBEAT); + period2 = 0; + break; + default://error + period1 = 5000; + sweep_steps1 = 100; + period2 = 5000; + sweep_steps2 = 100; + } + + if (period1 != 0) { + if (LedPWM(period1, sweep_steps1, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_On(PIOS_LED_HEARTBEAT); + + if (period2 != 0) { + if (LedPWM(period2, sweep_steps2, stopwatch)) + PIOS_LED_On(PIOS_LED_HEARTBEAT); + else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + } else + PIOS_LED_Off(PIOS_LED_HEARTBEAT); + + if (stopwatch > 50 * 1000 * 1000) + stopwatch = 0; + if ((stopwatch > 6 * 1000 * 1000) && (DeviceState + == BLidle)) + JumpToApp = true; + + processRX(); + DataDownload(start); + } +} + +void jump_to_app() { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + + PIOS_LED_On(PIOS_LED_HEARTBEAT); + if (((*(__IO uint32_t*) bdinfo->fw_base) & 0x2FFE0000) == 0x20000000) { /* Jump to user application */ + FLASH_Lock(); + RCC_APB2PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB1PeriphResetCmd(0xffffffff, ENABLE); + RCC_APB2PeriphResetCmd(0xffffffff, DISABLE); + RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); + + PIOS_USBHOOK_Deactivate(); + + JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); + Jump_To_Application = (pFunction) JumpAddress; + /* Initialize user application's Stack Pointer */ + __set_MSP(*(__IO uint32_t*) bdinfo->fw_base); + Jump_To_Application(); + } else { + DeviceState = failed_jump; + return; + } +} +uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { + uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */ + uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */ + + uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */ + if (curr_sweep & 1) { + pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */ + } + return ((count % pwm_period) > pwm_duty) ? 1 : 0; +} + +uint8_t processRX() { + if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { + processComand(mReceive_Buffer); + } + return true; +} + +/** + * Check the brown out reset threshold is 2.7 volts and if not + * resets it. This solves an issue that can prevent boards + * powering up with some BEC + */ +void check_bor() +{ + uint8_t bor = FLASH_OB_GetBOR(); + if(bor != OB_BOR_LEVEL3) { + FLASH_OB_Unlock(); + FLASH_OB_BORConfig(OB_BOR_LEVEL3); + FLASH_OB_Launch(); + while(FLASH_WaitForLastOperation() == FLASH_BUSY); + FLASH_OB_Lock(); + while(FLASH_WaitForLastOperation() == FLASH_BUSY); + } +} + diff --git a/flight/targets/Bootloaders/Revolution/op_dfu.c b/flight/targets/Bootloaders/Revolution/op_dfu.c index 3aceedcfb..16281dd4d 100644 --- a/flight/targets/Bootloaders/Revolution/op_dfu.c +++ b/flight/targets/Bootloaders/Revolution/op_dfu.c @@ -1,468 +1,468 @@ -/** - ****************************************************************************** - * @addtogroup CopterControlBL CopterControl BootLoader - * @brief These files contain the code to the CopterControl Bootloader. - * - * @{ - * @file op_dfu.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief This file contains the DFU commands handling code - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Includes ------------------------------------------------------------------*/ -#include "pios.h" -#include -#include "op_dfu.h" -#include "pios_bl_helper.h" -#include "pios_com_msg.h" -#include -//programmable devices -Device devicesTable[10]; -uint8_t numberOfDevices = 0; - -DFUProgType currentProgrammingDestination; //flash, flash_trough spi -uint8_t currentDeviceCanRead; -uint8_t currentDeviceCanWrite; -Device currentDevice; - -uint8_t Buffer[64]; -uint8_t echoBuffer[64]; -uint8_t SendBuffer[64]; -uint8_t Command = 0; -uint8_t EchoReqFlag = 0; -uint8_t EchoAnsFlag = 0; -uint8_t StartFlag = 0; -uint32_t Aditionals = 0; -uint32_t SizeOfTransfer = 0; -uint32_t Expected_CRC = 0; -uint8_t SizeOfLastPacket = 0; -uint32_t Next_Packet = 0; -uint8_t TransferType; -uint32_t Count = 0; -uint32_t Data; -uint8_t Data0; -uint8_t Data1; -uint8_t Data2; -uint8_t Data3; -uint8_t offset = 0; -uint32_t aux; -//Download vars -uint32_t downSizeOfLastPacket = 0; -uint32_t downPacketTotal = 0; -uint32_t downPacketCurrent = 0; -DFUTransfer downType = 0; -/* Extern variables ----------------------------------------------------------*/ -extern DFUStates DeviceState; -extern uint8_t JumpToApp; -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -void sendData(uint8_t * buf, uint16_t size); -uint32_t CalcFirmCRC(void); - -void DataDownload(DownloadAction action) { - if ((DeviceState == downloading)) { - - uint8_t packetSize; - uint32_t offset; - uint32_t partoffset; - SendBuffer[0] = 0x01; - SendBuffer[1] = Download; - SendBuffer[2] = downPacketCurrent >> 24; - SendBuffer[3] = downPacketCurrent >> 16; - SendBuffer[4] = downPacketCurrent >> 8; - SendBuffer[5] = downPacketCurrent; - if (downPacketCurrent == downPacketTotal - 1) { - packetSize = downSizeOfLastPacket; - } else { - packetSize = 14; - } - for (uint8_t x = 0; x < packetSize; ++x) { - partoffset = (downPacketCurrent * 14 * 4) + (x * 4); - offset = baseOfAdressType(downType) + partoffset; - if (!flash_read(SendBuffer + (6 + x * 4), offset, - currentProgrammingDestination)) { - DeviceState = Last_operation_failed; - } - } - downPacketCurrent = downPacketCurrent + 1; - if (downPacketCurrent > downPacketTotal - 1) { - DeviceState = Last_operation_Success; - Aditionals = (uint32_t) Download; - } - sendData(SendBuffer + 1, 63); - } -} -void processComand(uint8_t *xReceive_Buffer) { - - Command = xReceive_Buffer[COMMAND]; -#ifdef DEBUG_SSP - char str[63]= {0}; - sprintf(str,"Received COMMAND:%d|",Command); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - EchoReqFlag = (Command >> 7); - EchoAnsFlag = (Command >> 6) & 0x01; - StartFlag = (Command >> 5) & 0x01; - Count = xReceive_Buffer[COUNT] << 24; - Count += xReceive_Buffer[COUNT + 1] << 16; - Count += xReceive_Buffer[COUNT + 2] << 8; - Count += xReceive_Buffer[COUNT + 3]; - - Data = xReceive_Buffer[DATA] << 24; - Data += xReceive_Buffer[DATA + 1] << 16; - Data += xReceive_Buffer[DATA + 2] << 8; - Data += xReceive_Buffer[DATA + 3]; - Data0 = xReceive_Buffer[DATA]; - Data1 = xReceive_Buffer[DATA + 1]; - Data2 = xReceive_Buffer[DATA + 2]; - Data3 = xReceive_Buffer[DATA + 3]; - Command = Command & 0b00011111; - - if (EchoReqFlag == 1) { - memcpy(echoBuffer, xReceive_Buffer, 64); - } - switch (Command) { - case EnterDFU: - if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) - || (DeviceState == DFUidle)) { - if (Data0 > 0) - OPDfuIni(true); - DeviceState = DFUidle; - currentProgrammingDestination = devicesTable[Data0].programmingType; - currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; - currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 - & 0x01; - currentDevice = devicesTable[Data0]; - uint8_t result = 0; - switch (currentProgrammingDestination) { - case Self_flash: - result = PIOS_BL_HELPER_FLASH_Ini(); - break; - case Remote_flash_via_spi: - result = true; - break; - default: - DeviceState = Last_operation_failed; - Aditionals = (uint16_t) Command; - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - } - break; - case Upload: - if ((DeviceState == DFUidle) || (DeviceState == uploading)) { - if ((StartFlag == 1) && (Next_Packet == 0)) { - TransferType = Data0; - SizeOfTransfer = Count; - Next_Packet = 1; - Expected_CRC = Data2 << 24; - Expected_CRC += Data3 << 16; - Expected_CRC += xReceive_Buffer[DATA + 4] << 8; - Expected_CRC += xReceive_Buffer[DATA + 5]; - SizeOfLastPacket = Data1; - - if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) - * 14 * 4 + SizeOfLastPacket * 4) == true) { - DeviceState = outsideDevCapabilities; - Aditionals = (uint32_t) Command; - } else { - uint8_t result = 1; - if (TransferType == FW) { - switch (currentProgrammingDestination) { - case Self_flash: - result = PIOS_BL_HELPER_FLASH_Start(); - break; - case Remote_flash_via_spi: - result = false; - break; - default: - break; - } - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } else { - - DeviceState = uploading; - } - } - } else if ((StartFlag != 1) && (Next_Packet != 0)) { - if (Count > SizeOfTransfer) { - DeviceState = too_many_packets; - Aditionals = Count; - } else if (Count == Next_Packet - 1) { - uint8_t numberOfWords = 14; - if (Count == SizeOfTransfer - 1)//is this the last packet? - { - numberOfWords = SizeOfLastPacket; - } - uint8_t result = 0; - switch (currentProgrammingDestination) { - case Self_flash: - for (uint8_t x = 0; x < numberOfWords; ++x) { - offset = 4 * x; - Data = xReceive_Buffer[DATA + offset] << 24; - Data += xReceive_Buffer[DATA + 1 + offset] << 16; - Data += xReceive_Buffer[DATA + 2 + offset] << 8; - Data += xReceive_Buffer[DATA + 3 + offset]; - aux = baseOfAdressType(TransferType) + (uint32_t)( - Count * 14 * 4 + x * 4); - result = 0; - for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { - if (result == 0) { - result = (FLASH_ProgramWord(aux, Data) - == FLASH_COMPLETE) ? 1 : 0; - } - } - } - break; - case Remote_flash_via_spi: - result = false; // No support for this for the PipX - break; - default: - result = 0; - break; - } - if (result != 1) { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - - ++Next_Packet; - } else { - DeviceState = wrong_packet_received; - Aditionals = Count; - } - } else { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - } - break; - case Req_Capabilities: - OPDfuIni(true); - Buffer[0] = 0x01; - Buffer[1] = Rep_Capabilities; - if (Data0 == 0) { - Buffer[2] = 0; - Buffer[3] = 0; - Buffer[4] = 0; - Buffer[5] = 0; - Buffer[6] = 0; - Buffer[7] = numberOfDevices; - uint16_t WRFlags = 0; - for (int x = 0; x < numberOfDevices; ++x) { - WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) - | WRFlags); - } - Buffer[8] = WRFlags >> 8; - Buffer[9] = WRFlags; - } else { - Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; - Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; - Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; - Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; - Buffer[6] = Data0; - Buffer[7] = devicesTable[Data0 - 1].BL_Version; - Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; - Buffer[9] = devicesTable[Data0 - 1].devID; - Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; - Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; - Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; - Buffer[13] = devicesTable[Data0 - 1].FW_Crc; - Buffer[14] = devicesTable[Data0 - 1].devID >> 8; - Buffer[15] = devicesTable[Data0 - 1].devID; - } - sendData(Buffer + 1, 63); - break; - case JumpFW: - if (Data == 0x5AFE) { - /* Force board into safe mode */ - PIOS_IAP_WriteBootCount(0xFFFF); - } - FLASH_Lock(); - JumpToApp = 1; - break; - case Reset: - PIOS_SYS_Reset(); - break; - case Abort_Operation: - Next_Packet = 0; - DeviceState = DFUidle; - break; - - case Op_END: - if (DeviceState == uploading) { - if (Next_Packet - 1 == SizeOfTransfer) { - Next_Packet = 0; - if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { - DeviceState = Last_operation_Success; - } else { - DeviceState = CRC_Fail; - } - } - if (Next_Packet - 1 < SizeOfTransfer) { - Next_Packet = 0; - DeviceState = too_few_packets; - } - } - break; - case Download_Req: -#ifdef DEBUG_SSP - sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); - PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); -#endif - if (DeviceState == DFUidle) { -#ifdef DEBUG_SSP - PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); -#endif - downType = Data0; - downPacketTotal = Count; - downSizeOfLastPacket = Data1; - if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 * 4 - + downSizeOfLastPacket * 4) == 1) { - DeviceState = outsideDevCapabilities; - Aditionals = (uint32_t) Command; - - } else { - downPacketCurrent = 0; - DeviceState = downloading; - } - } else { - DeviceState = Last_operation_failed; - Aditionals = (uint32_t) Command; - } - break; - - case Status_Request: - Buffer[0] = 0x01; - Buffer[1] = Status_Rep; - if (DeviceState == wrong_packet_received) { - Buffer[2] = Aditionals >> 24; - Buffer[3] = Aditionals >> 16; - Buffer[4] = Aditionals >> 8; - Buffer[5] = Aditionals; - } else { - Buffer[2] = 0; - Buffer[3] = ((uint16_t) Aditionals) >> 8; - Buffer[4] = ((uint16_t) Aditionals); - Buffer[5] = 0; - } - Buffer[6] = DeviceState; - Buffer[7] = 0; - Buffer[8] = 0; - Buffer[9] = 0; - sendData(Buffer + 1, 63); - if (DeviceState == Last_operation_Success) { - DeviceState = DFUidle; - } - break; - case Status_Rep: - - break; - - } - if (EchoReqFlag == 1) { - echoBuffer[0] = echoBuffer[0] | (1 << 6); - sendData(echoBuffer, 63); - } - return; -} -void OPDfuIni(uint8_t discover) { - const struct pios_board_info * bdinfo = &pios_board_info_blob; - Device dev; - - dev.programmingType = Self_flash; - dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); - dev.startOfUserCode = bdinfo->fw_base; - dev.sizeOfCode = bdinfo->fw_size; - dev.sizeOfDescription = bdinfo->desc_size; - dev.BL_Version = bdinfo->bl_rev; - dev.FW_Crc = CalcFirmCRC(); - dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); - dev.devType = bdinfo->hw_type; - numberOfDevices = 1; - devicesTable[0] = dev; - if (discover) { - //TODO check other devices trough spi or whatever - } -} -uint32_t baseOfAdressType(DFUTransfer type) { - switch (type) { - case FW: - return currentDevice.startOfUserCode; - break; - case Descript: - return currentDevice.startOfUserCode + currentDevice.sizeOfCode; - break; - default: - - return 0; - } -} -uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { - switch (type) { - case FW: - return (size > currentDevice.sizeOfCode) ? 1 : 0; - break; - case Descript: - return (size > currentDevice.sizeOfDescription) ? 1 : 0; - break; - default: - return true; - } -} - -uint32_t CalcFirmCRC() { - switch (currentProgrammingDestination) { - case Self_flash: - return PIOS_BL_HELPER_CRC_Memory_Calc(); - break; - case Remote_flash_via_spi: - return 0; - break; - default: - return 0; - break; - } - -} -void sendData(uint8_t * buf, uint16_t size) { - PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); -} - -bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { - switch (type) { - case Remote_flash_via_spi: - return false; // We should not get this for the PipX - break; - case Self_flash: - for (uint8_t x = 0; x < 4; ++x) { - buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); - } - return true; - break; - default: - return false; - } -} +/** + ****************************************************************************** + * @addtogroup CopterControlBL CopterControl BootLoader + * @brief These files contain the code to the CopterControl Bootloader. + * + * @{ + * @file op_dfu.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief This file contains the DFU commands handling code + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Includes ------------------------------------------------------------------*/ +#include "pios.h" +#include +#include "op_dfu.h" +#include "pios_bl_helper.h" +#include "pios_com_msg.h" +#include +//programmable devices +Device devicesTable[10]; +uint8_t numberOfDevices = 0; + +DFUProgType currentProgrammingDestination; //flash, flash_trough spi +uint8_t currentDeviceCanRead; +uint8_t currentDeviceCanWrite; +Device currentDevice; + +uint8_t Buffer[64]; +uint8_t echoBuffer[64]; +uint8_t SendBuffer[64]; +uint8_t Command = 0; +uint8_t EchoReqFlag = 0; +uint8_t EchoAnsFlag = 0; +uint8_t StartFlag = 0; +uint32_t Aditionals = 0; +uint32_t SizeOfTransfer = 0; +uint32_t Expected_CRC = 0; +uint8_t SizeOfLastPacket = 0; +uint32_t Next_Packet = 0; +uint8_t TransferType; +uint32_t Count = 0; +uint32_t Data; +uint8_t Data0; +uint8_t Data1; +uint8_t Data2; +uint8_t Data3; +uint8_t offset = 0; +uint32_t aux; +//Download vars +uint32_t downSizeOfLastPacket = 0; +uint32_t downPacketTotal = 0; +uint32_t downPacketCurrent = 0; +DFUTransfer downType = 0; +/* Extern variables ----------------------------------------------------------*/ +extern DFUStates DeviceState; +extern uint8_t JumpToApp; +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ +void sendData(uint8_t * buf, uint16_t size); +uint32_t CalcFirmCRC(void); + +void DataDownload(DownloadAction action) { + if ((DeviceState == downloading)) { + + uint8_t packetSize; + uint32_t offset; + uint32_t partoffset; + SendBuffer[0] = 0x01; + SendBuffer[1] = Download; + SendBuffer[2] = downPacketCurrent >> 24; + SendBuffer[3] = downPacketCurrent >> 16; + SendBuffer[4] = downPacketCurrent >> 8; + SendBuffer[5] = downPacketCurrent; + if (downPacketCurrent == downPacketTotal - 1) { + packetSize = downSizeOfLastPacket; + } else { + packetSize = 14; + } + for (uint8_t x = 0; x < packetSize; ++x) { + partoffset = (downPacketCurrent * 14 * 4) + (x * 4); + offset = baseOfAdressType(downType) + partoffset; + if (!flash_read(SendBuffer + (6 + x * 4), offset, + currentProgrammingDestination)) { + DeviceState = Last_operation_failed; + } + } + downPacketCurrent = downPacketCurrent + 1; + if (downPacketCurrent > downPacketTotal - 1) { + DeviceState = Last_operation_Success; + Aditionals = (uint32_t) Download; + } + sendData(SendBuffer + 1, 63); + } +} +void processComand(uint8_t *xReceive_Buffer) { + + Command = xReceive_Buffer[COMMAND]; +#ifdef DEBUG_SSP + char str[63]= {0}; + sprintf(str,"Received COMMAND:%d|",Command); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + EchoReqFlag = (Command >> 7); + EchoAnsFlag = (Command >> 6) & 0x01; + StartFlag = (Command >> 5) & 0x01; + Count = xReceive_Buffer[COUNT] << 24; + Count += xReceive_Buffer[COUNT + 1] << 16; + Count += xReceive_Buffer[COUNT + 2] << 8; + Count += xReceive_Buffer[COUNT + 3]; + + Data = xReceive_Buffer[DATA] << 24; + Data += xReceive_Buffer[DATA + 1] << 16; + Data += xReceive_Buffer[DATA + 2] << 8; + Data += xReceive_Buffer[DATA + 3]; + Data0 = xReceive_Buffer[DATA]; + Data1 = xReceive_Buffer[DATA + 1]; + Data2 = xReceive_Buffer[DATA + 2]; + Data3 = xReceive_Buffer[DATA + 3]; + Command = Command & 0b00011111; + + if (EchoReqFlag == 1) { + memcpy(echoBuffer, xReceive_Buffer, 64); + } + switch (Command) { + case EnterDFU: + if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) + || (DeviceState == DFUidle)) { + if (Data0 > 0) + OPDfuIni(true); + DeviceState = DFUidle; + currentProgrammingDestination = devicesTable[Data0].programmingType; + currentDeviceCanRead = devicesTable[Data0].readWriteFlags & 0x01; + currentDeviceCanWrite = devicesTable[Data0].readWriteFlags >> 1 + & 0x01; + currentDevice = devicesTable[Data0]; + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Ini(); + break; + case Remote_flash_via_spi: + result = true; + break; + default: + DeviceState = Last_operation_failed; + Aditionals = (uint16_t) Command; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Upload: + if ((DeviceState == DFUidle) || (DeviceState == uploading)) { + if ((StartFlag == 1) && (Next_Packet == 0)) { + TransferType = Data0; + SizeOfTransfer = Count; + Next_Packet = 1; + Expected_CRC = Data2 << 24; + Expected_CRC += Data3 << 16; + Expected_CRC += xReceive_Buffer[DATA + 4] << 8; + Expected_CRC += xReceive_Buffer[DATA + 5]; + SizeOfLastPacket = Data1; + + if (isBiggerThanAvailable(TransferType, (SizeOfTransfer - 1) + * 14 * 4 + SizeOfLastPacket * 4) == true) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + } else { + uint8_t result = 1; + if (TransferType == FW) { + switch (currentProgrammingDestination) { + case Self_flash: + result = PIOS_BL_HELPER_FLASH_Start(); + break; + case Remote_flash_via_spi: + result = false; + break; + default: + break; + } + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } else { + + DeviceState = uploading; + } + } + } else if ((StartFlag != 1) && (Next_Packet != 0)) { + if (Count > SizeOfTransfer) { + DeviceState = too_many_packets; + Aditionals = Count; + } else if (Count == Next_Packet - 1) { + uint8_t numberOfWords = 14; + if (Count == SizeOfTransfer - 1)//is this the last packet? + { + numberOfWords = SizeOfLastPacket; + } + uint8_t result = 0; + switch (currentProgrammingDestination) { + case Self_flash: + for (uint8_t x = 0; x < numberOfWords; ++x) { + offset = 4 * x; + Data = xReceive_Buffer[DATA + offset] << 24; + Data += xReceive_Buffer[DATA + 1 + offset] << 16; + Data += xReceive_Buffer[DATA + 2 + offset] << 8; + Data += xReceive_Buffer[DATA + 3 + offset]; + aux = baseOfAdressType(TransferType) + (uint32_t)( + Count * 14 * 4 + x * 4); + result = 0; + for (int retry = 0; retry < MAX_WRI_RETRYS; ++retry) { + if (result == 0) { + result = (FLASH_ProgramWord(aux, Data) + == FLASH_COMPLETE) ? 1 : 0; + } + } + } + break; + case Remote_flash_via_spi: + result = false; // No support for this for the PipX + break; + default: + result = 0; + break; + } + if (result != 1) { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + + ++Next_Packet; + } else { + DeviceState = wrong_packet_received; + Aditionals = Count; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + } + break; + case Req_Capabilities: + OPDfuIni(true); + Buffer[0] = 0x01; + Buffer[1] = Rep_Capabilities; + if (Data0 == 0) { + Buffer[2] = 0; + Buffer[3] = 0; + Buffer[4] = 0; + Buffer[5] = 0; + Buffer[6] = 0; + Buffer[7] = numberOfDevices; + uint16_t WRFlags = 0; + for (int x = 0; x < numberOfDevices; ++x) { + WRFlags = ((devicesTable[x].readWriteFlags << (x * 2)) + | WRFlags); + } + Buffer[8] = WRFlags >> 8; + Buffer[9] = WRFlags; + } else { + Buffer[2] = devicesTable[Data0 - 1].sizeOfCode >> 24; + Buffer[3] = devicesTable[Data0 - 1].sizeOfCode >> 16; + Buffer[4] = devicesTable[Data0 - 1].sizeOfCode >> 8; + Buffer[5] = devicesTable[Data0 - 1].sizeOfCode; + Buffer[6] = Data0; + Buffer[7] = devicesTable[Data0 - 1].BL_Version; + Buffer[8] = devicesTable[Data0 - 1].sizeOfDescription; + Buffer[9] = devicesTable[Data0 - 1].devID; + Buffer[10] = devicesTable[Data0 - 1].FW_Crc >> 24; + Buffer[11] = devicesTable[Data0 - 1].FW_Crc >> 16; + Buffer[12] = devicesTable[Data0 - 1].FW_Crc >> 8; + Buffer[13] = devicesTable[Data0 - 1].FW_Crc; + Buffer[14] = devicesTable[Data0 - 1].devID >> 8; + Buffer[15] = devicesTable[Data0 - 1].devID; + } + sendData(Buffer + 1, 63); + break; + case JumpFW: + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); + } + FLASH_Lock(); + JumpToApp = 1; + break; + case Reset: + PIOS_SYS_Reset(); + break; + case Abort_Operation: + Next_Packet = 0; + DeviceState = DFUidle; + break; + + case Op_END: + if (DeviceState == uploading) { + if (Next_Packet - 1 == SizeOfTransfer) { + Next_Packet = 0; + if ((TransferType != FW) || (Expected_CRC == CalcFirmCRC())) { + DeviceState = Last_operation_Success; + } else { + DeviceState = CRC_Fail; + } + } + if (Next_Packet - 1 < SizeOfTransfer) { + Next_Packet = 0; + DeviceState = too_few_packets; + } + } + break; + case Download_Req: +#ifdef DEBUG_SSP + sprintf(str,"COMMAND:DOWNLOAD_REQ 1 Status=%d|",DeviceState); + PIOS_COM_SendString(PIOS_COM_TELEM_USB,str); +#endif + if (DeviceState == DFUidle) { +#ifdef DEBUG_SSP + PIOS_COM_SendString(PIOS_COM_TELEM_USB,"COMMAND:DOWNLOAD_REQ 1|"); +#endif + downType = Data0; + downPacketTotal = Count; + downSizeOfLastPacket = Data1; + if (isBiggerThanAvailable(downType, (downPacketTotal - 1) * 14 * 4 + + downSizeOfLastPacket * 4) == 1) { + DeviceState = outsideDevCapabilities; + Aditionals = (uint32_t) Command; + + } else { + downPacketCurrent = 0; + DeviceState = downloading; + } + } else { + DeviceState = Last_operation_failed; + Aditionals = (uint32_t) Command; + } + break; + + case Status_Request: + Buffer[0] = 0x01; + Buffer[1] = Status_Rep; + if (DeviceState == wrong_packet_received) { + Buffer[2] = Aditionals >> 24; + Buffer[3] = Aditionals >> 16; + Buffer[4] = Aditionals >> 8; + Buffer[5] = Aditionals; + } else { + Buffer[2] = 0; + Buffer[3] = ((uint16_t) Aditionals) >> 8; + Buffer[4] = ((uint16_t) Aditionals); + Buffer[5] = 0; + } + Buffer[6] = DeviceState; + Buffer[7] = 0; + Buffer[8] = 0; + Buffer[9] = 0; + sendData(Buffer + 1, 63); + if (DeviceState == Last_operation_Success) { + DeviceState = DFUidle; + } + break; + case Status_Rep: + + break; + + } + if (EchoReqFlag == 1) { + echoBuffer[0] = echoBuffer[0] | (1 << 6); + sendData(echoBuffer, 63); + } + return; +} +void OPDfuIni(uint8_t discover) { + const struct pios_board_info * bdinfo = &pios_board_info_blob; + Device dev; + + dev.programmingType = Self_flash; + dev.readWriteFlags = (BOARD_READABLE | (BOARD_WRITABLE << 1)); + dev.startOfUserCode = bdinfo->fw_base; + dev.sizeOfCode = bdinfo->fw_size; + dev.sizeOfDescription = bdinfo->desc_size; + dev.BL_Version = bdinfo->bl_rev; + dev.FW_Crc = CalcFirmCRC(); + dev.devID = (bdinfo->board_type << 8) | (bdinfo->board_rev); + dev.devType = bdinfo->hw_type; + numberOfDevices = 1; + devicesTable[0] = dev; + if (discover) { + //TODO check other devices trough spi or whatever + } +} +uint32_t baseOfAdressType(DFUTransfer type) { + switch (type) { + case FW: + return currentDevice.startOfUserCode; + break; + case Descript: + return currentDevice.startOfUserCode + currentDevice.sizeOfCode; + break; + default: + + return 0; + } +} +uint8_t isBiggerThanAvailable(DFUTransfer type, uint32_t size) { + switch (type) { + case FW: + return (size > currentDevice.sizeOfCode) ? 1 : 0; + break; + case Descript: + return (size > currentDevice.sizeOfDescription) ? 1 : 0; + break; + default: + return true; + } +} + +uint32_t CalcFirmCRC() { + switch (currentProgrammingDestination) { + case Self_flash: + return PIOS_BL_HELPER_CRC_Memory_Calc(); + break; + case Remote_flash_via_spi: + return 0; + break; + default: + return 0; + break; + } + +} +void sendData(uint8_t * buf, uint16_t size) { + PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); +} + +bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { + switch (type) { + case Remote_flash_via_spi: + return false; // We should not get this for the PipX + break; + case Self_flash: + for (uint8_t x = 0; x < 4; ++x) { + buffer[x] = *PIOS_BL_HELPER_FLASH_If_Read(adr + x); + } + return true; + break; + default: + return false; + } +} diff --git a/flight/targets/CopterControl/System/alarms.c b/flight/targets/CopterControl/System/alarms.c index 01d79a1e5..a55cbd158 100644 --- a/flight/targets/CopterControl/System/alarms.c +++ b/flight/targets/CopterControl/System/alarms.c @@ -1,214 +1,214 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @brief OpenPilot System libraries are available to all OP modules. - * @{ - * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Library for setting and clearing system alarms - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "alarms.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; - -// Private functions -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); - -/** - * Initialize the alarms library - */ -int32_t AlarmsInitialize(void) -{ - SystemAlarmsInitialize(); - - lock = xSemaphoreCreateRecursiveMutex(); - //do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that - //AlarmsClearAll(); - //AlarmsDefaultAll(); - return 0; -} - -/** - * Set an alarm - * @param alarm The system alarm to be modified - * @param severity The alarm severity - * @return 0 if success, -1 if an error - */ -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } - - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; - -} - -/** - * Get an alarm - * @param alarm The system alarm to be read - * @return Alarm severity - */ -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } - - // Read alarm - SystemAlarmsGet(&alarms); - return alarms.Alarm[alarm]; -} - -/** - * Set an alarm to it's default value - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); -} - -/** - * Default all alarms - */ -void AlarmsDefaultAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); - } -} - -/** - * Clear an alarm - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); -} - -/** - * Clear all alarms - */ -void AlarmsClearAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); - } -} - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasWarnings() -{ - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); -} - -/** - * Check if there are any alarms with error or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasErrors() -{ - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; - -/** - * Check if there are any alarms with critical or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasCritical() -{ - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - uint32_t n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarms - SystemAlarmsGet(&alarms); - - // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } - } - - // If this point is reached then no alarms found - xSemaphoreGiveRecursive(lock); - return 0; -} -/** - * @} - * @} - */ - +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @brief OpenPilot System libraries are available to all OP modules. + * @{ + * @file alarms.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Library for setting and clearing system alarms + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "alarms.h" + +// Private constants + +// Private types + +// Private variables +static xSemaphoreHandle lock; + +// Private functions +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); + +/** + * Initialize the alarms library + */ +int32_t AlarmsInitialize(void) +{ + SystemAlarmsInitialize(); + + lock = xSemaphoreCreateRecursiveMutex(); + //do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that + //AlarmsClearAll(); + //AlarmsDefaultAll(); + return 0; +} + +/** + * Set an alarm + * @param alarm The system alarm to be modified + * @param severity The alarm severity + * @return 0 if success, -1 if an error + */ +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return -1; + } + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarm and update its severity only if it was changed + SystemAlarmsGet(&alarms); + if ( alarms.Alarm[alarm] != severity ) + { + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); + } + + // Release lock + xSemaphoreGiveRecursive(lock); + return 0; + +} + +/** + * Get an alarm + * @param alarm The system alarm to be read + * @return Alarm severity + */ +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return 0; + } + + // Read alarm + SystemAlarmsGet(&alarms); + return alarms.Alarm[alarm]; +} + +/** + * Set an alarm to it's default value + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); +} + +/** + * Default all alarms + */ +void AlarmsDefaultAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsDefault(n); + } +} + +/** + * Clear an alarm + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); +} + +/** + * Clear all alarms + */ +void AlarmsClearAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsClear(n); + } +} + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasWarnings() +{ + return hasSeverity(SYSTEMALARMS_ALARM_WARNING); +} + +/** + * Check if there are any alarms with error or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasErrors() +{ + return hasSeverity(SYSTEMALARMS_ALARM_ERROR); +}; + +/** + * Check if there are any alarms with critical or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasCritical() +{ + return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); +}; + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + uint32_t n; + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarms + SystemAlarmsGet(&alarms); + + // Go through alarms and check if any are of the given severity or higher + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + if ( alarms.Alarm[n] >= severity) + { + xSemaphoreGiveRecursive(lock); + return 1; + } + } + + // If this point is reached then no alarms found + xSemaphoreGiveRecursive(lock); + return 0; +} +/** + * @} + * @} + */ + diff --git a/flight/targets/CopterControl/System/inc/alarms.h b/flight/targets/CopterControl/System/inc/alarms.h index 9fb047dca..0f0faeb8f 100644 --- a/flight/targets/CopterControl/System/inc/alarms.h +++ b/flight/targets/CopterControl/System/inc/alarms.h @@ -1,50 +1,50 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the alarm library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef ALARMS_H -#define ALARMS_H - -#include "systemalarms.h" -#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED - -int32_t AlarmsInitialize(void); -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); -void AlarmsDefaultAll(); -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); -void AlarmsClearAll(); -int32_t AlarmsHasWarnings(); -int32_t AlarmsHasErrors(); -int32_t AlarmsHasCritical(); - -#endif // ALARMS_H - -/** - * @} - * @} +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file alarms.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the alarm library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ALARMS_H +#define ALARMS_H + +#include "systemalarms.h" +#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED + +int32_t AlarmsInitialize(void); +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); +void AlarmsDefaultAll(); +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); +void AlarmsClearAll(); +int32_t AlarmsHasWarnings(); +int32_t AlarmsHasErrors(); +int32_t AlarmsHasCritical(); + +#endif // ALARMS_H + +/** + * @} + * @} */ diff --git a/flight/targets/CopterControl/System/inc/openpilot.h b/flight/targets/CopterControl/System/inc/openpilot.h index 7f1ac3758..eb3cadcc7 100644 --- a/flight/targets/CopterControl/System/inc/openpilot.h +++ b/flight/targets/CopterControl/System/inc/openpilot.h @@ -1,52 +1,52 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file openpilot.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main OpenPilot header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef OPENPILOT_H -#define OPENPILOT_H - - -/* PIOS Includes */ -#include - -/* OpenPilot Libraries */ -#include "utlist.h" -#include "uavobjectmanager.h" -#include "eventdispatcher.h" -#include "alarms.h" -#include "taskmonitor.h" -#include "uavtalk.h" - -/* Global Functions */ -void OpenPilotInit(void); - -#endif /* OPENPILOT_H */ -/** - * @} - * @} +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file openpilot.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main OpenPilot header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OPENPILOT_H +#define OPENPILOT_H + + +/* PIOS Includes */ +#include + +/* OpenPilot Libraries */ +#include "utlist.h" +#include "uavobjectmanager.h" +#include "eventdispatcher.h" +#include "alarms.h" +#include "taskmonitor.h" +#include "uavtalk.h" + +/* Global Functions */ +void OpenPilotInit(void); + +#endif /* OPENPILOT_H */ +/** + * @} + * @} */ diff --git a/flight/targets/CopterControl/System/inc/pios_board_posix.h b/flight/targets/CopterControl/System/inc/pios_board_posix.h index 741f36ba7..84eadbeba 100644 --- a/flight/targets/CopterControl/System/inc/pios_board_posix.h +++ b/flight/targets/CopterControl/System/inc/pios_board_posix.h @@ -1,84 +1,84 @@ -/** - ****************************************************************************** - * - * @file pios_board.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_BOARD_H -#define PIOS_BOARD_H - - - - -//------------------------ -// PIOS_LED -//------------------------ -//#define PIOS_LED_LED1_GPIO_PORT GPIOC -//#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12 -//#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC -//#define PIOS_LED_LED2_GPIO_PORT GPIOC -//#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13 -//#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC -#define PIOS_LED_NUM 2 -//#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT } -//#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN } -//#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK } - - -//------------------------- -// COM -// -// See also pios_board_posix.c -//------------------------- -//#define PIOS_USART_TX_BUFFER_SIZE 256 -#define PIOS_COM_BUFFER_SIZE 1024 -#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE - -#define PIOS_COM_TELEM_RF 0 -#define PIOS_COM_GPS 1 -#define PIOS_COM_TELEM_USB 2 - -#ifdef PIOS_ENABLE_AUX_UART -#define PIOS_COM_AUX 3 -#define PIOS_COM_DEBUG PIOS_COM_AUX -#endif - -/** - * glue macros for file IO - * STM32 uses DOSFS for file IO - */ -#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL - -#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL - -#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length - -#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file) - - - -#define PIOS_FCLOSE(file) fclose(file) - -#define PIOS_FUNLINK(file) unlink((char*)filename) - -#endif /* PIOS_BOARD_H */ +/** + ****************************************************************************** + * + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_BOARD_H +#define PIOS_BOARD_H + + + + +//------------------------ +// PIOS_LED +//------------------------ +//#define PIOS_LED_LED1_GPIO_PORT GPIOC +//#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12 +//#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC +//#define PIOS_LED_LED2_GPIO_PORT GPIOC +//#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13 +//#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC +#define PIOS_LED_NUM 2 +//#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT } +//#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN } +//#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK } + + +//------------------------- +// COM +// +// See also pios_board_posix.c +//------------------------- +//#define PIOS_USART_TX_BUFFER_SIZE 256 +#define PIOS_COM_BUFFER_SIZE 1024 +#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE + +#define PIOS_COM_TELEM_RF 0 +#define PIOS_COM_GPS 1 +#define PIOS_COM_TELEM_USB 2 + +#ifdef PIOS_ENABLE_AUX_UART +#define PIOS_COM_AUX 3 +#define PIOS_COM_DEBUG PIOS_COM_AUX +#endif + +/** + * glue macros for file IO + * STM32 uses DOSFS for file IO + */ +#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL + +#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL + +#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length + +#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file) + + + +#define PIOS_FCLOSE(file) fclose(file) + +#define PIOS_FUNLINK(file) unlink((char*)filename) + +#endif /* PIOS_BOARD_H */ diff --git a/flight/targets/CopterControl/System/inc/pios_config.h b/flight/targets/CopterControl/System/inc/pios_config.h index 149f8490b..ea4f2ae1d 100644 --- a/flight/targets/CopterControl/System/inc/pios_config.h +++ b/flight/targets/CopterControl/System/inc/pios_config.h @@ -1,170 +1,170 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013. - * @brief PiOS configuration header, the compile time config file for the PIOS. - * Defines which PiOS libraries and features are included in the firmware. - * @see The GNU Public License (GPL) Version 3 - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* - * Below is a complete list of PIOS configurable options. - * Please do not remove or rearrange them. Only comment out - * unused options in the list. See main pios.h header for more - * details. - */ - -/* #define PIOS_INCLUDE_DEBUG_CONSOLE */ -/* #define DEBUG_LEVEL 0 */ - -/* PIOS FreeRTOS support */ -#define PIOS_INCLUDE_FREERTOS - -/* PIOS bootloader helper */ -#define PIOS_INCLUDE_BL_HELPER -/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */ - -/* PIOS system functions */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_INITCALL -#define PIOS_INCLUDE_SYS - -/* PIOS hardware peripherals */ -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_RTC -#define PIOS_INCLUDE_TIM -#define PIOS_INCLUDE_USART -#define PIOS_INCLUDE_ADC -/* #define PIOS_INCLUDE_I2C */ -#define PIOS_INCLUDE_SPI -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_EXTI -#define PIOS_INCLUDE_WDG - -/* PIOS USB functions */ -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_USB_CDC -#define PIOS_INCLUDE_USB_RCTX - -/* PIOS sensor interfaces */ -#define PIOS_INCLUDE_ADXL345 -/* #define PIOS_INCLUDE_BMA180 */ -/* #define PIOS_INCLUDE_L3GD20 */ -#define PIOS_INCLUDE_MPU6000 -#define PIOS_MPU6000_ACCEL -/* #define PIOS_INCLUDE_HMC5843 */ -/* #define PIOS_INCLUDE_HMC5883 */ -/* #define PIOS_HMC5883_HAS_GPIOS */ -/* #define PIOS_INCLUDE_BMP085 */ -/* #define PIOS_INCLUDE_MS5611 */ -/* #define PIOS_INCLUDE_MPXV */ -/* #define PIOS_INCLUDE_ETASV3 */ -/* #define PIOS_INCLUDE_HCSR04 */ - -/* PIOS receiver drivers */ -#define PIOS_INCLUDE_PWM -#define PIOS_INCLUDE_PPM -#define PIOS_INCLUDE_PPM_FLEXI -#define PIOS_INCLUDE_DSM -#define PIOS_INCLUDE_SBUS -#define PIOS_INCLUDE_GCSRCVR - -/* PIOS abstract receiver interface */ -#define PIOS_INCLUDE_RCVR - -/* PIOS common peripherals */ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_SERVO -/* #define PIOS_INCLUDE_I2C_ESC */ -/* #define PIOS_INCLUDE_OVERO */ -/* #define PIOS_OVERO_SPI */ -/* #define PIOS_INCLUDE_SDCARD */ -/* #define LOG_FILENAME "startup.log" */ -#define PIOS_INCLUDE_FLASH -#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS -/* #define FLASH_FREERTOS */ -/* #define PIOS_INCLUDE_FLASH_EEPROM */ - -/* PIOS radio modules */ -/* #define PIOS_INCLUDE_RFM22B */ -/* #define PIOS_INCLUDE_RFM22B_COM */ -/* #define PIOS_INCLUDE_RFM22B_RCVR */ -/* #define PIOS_INCLUDE_PPM_OUT */ -/* #define PIOS_RFM22B_DEBUG_ON_TELEM */ - -/* PIOS misc peripherals */ -/* #define PIOS_INCLUDE_VIDEO */ -/* #define PIOS_INCLUDE_WAVE */ -/* #define PIOS_INCLUDE_UDP */ - -/* PIOS abstract comms interface with options */ -#define PIOS_INCLUDE_COM -/* #define PIOS_INCLUDE_COM_MSG */ -#define PIOS_INCLUDE_TELEMETRY_RF -/* #define PIOS_INCLUDE_COM_TELEM */ -/* #define PIOS_INCLUDE_COM_FLEXI */ -/* #define PIOS_INCLUDE_COM_AUX */ -/* #define PIOS_TELEM_PRIORITY_QUEUE */ -#define PIOS_INCLUDE_GPS -#define PIOS_GPS_MINIMAL -#define PIOS_INCLUDE_GPS_NMEA_PARSER -#define PIOS_INCLUDE_GPS_UBX_PARSER -/* #define PIOS_GPS_SETS_HOMELOCATION */ - -/* Stabilization options */ -/* #define PIOS_QUATERNION_STABILIZATION */ - -/* Performance counters */ -#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998 - -/* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 220 -#define HEAP_LIMIT_CRITICAL 40 -#define IRQSTACK_LIMIT_WARNING 100 -#define IRQSTACK_LIMIT_CRITICAL 60 -#define CPULOAD_LIMIT_WARNING 85 -#define CPULOAD_LIMIT_CRITICAL 95 - -/* Task stack sizes */ -#define PIOS_ACTUATOR_STACK_SIZE 1020 -#define PIOS_MANUAL_STACK_SIZE 800 -#define PIOS_SYSTEM_STACK_SIZE 660 -#define PIOS_STABILIZATION_STACK_SIZE 524 -#define PIOS_TELEM_STACK_SIZE 500 -#define PIOS_EVENTDISPATCHER_STACK_SIZE 130 - -/* This can't be too high to stop eventdispatcher thread overflowing */ -#define PIOS_EVENTDISAPTCHER_QUEUE 10 - -/* Revolution series */ -/* #define REVOLUTION */ - -#endif /* PIOS_CONFIG_H */ -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013. + * @brief PiOS configuration header, the compile time config file for the PIOS. + * Defines which PiOS libraries and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* + * Below is a complete list of PIOS configurable options. + * Please do not remove or rearrange them. Only comment out + * unused options in the list. See main pios.h header for more + * details. + */ + +/* #define PIOS_INCLUDE_DEBUG_CONSOLE */ +/* #define DEBUG_LEVEL 0 */ + +/* PIOS FreeRTOS support */ +#define PIOS_INCLUDE_FREERTOS + +/* PIOS bootloader helper */ +#define PIOS_INCLUDE_BL_HELPER +/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */ + +/* PIOS system functions */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_INITCALL +#define PIOS_INCLUDE_SYS + +/* PIOS hardware peripherals */ +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_RTC +#define PIOS_INCLUDE_TIM +#define PIOS_INCLUDE_USART +#define PIOS_INCLUDE_ADC +/* #define PIOS_INCLUDE_I2C */ +#define PIOS_INCLUDE_SPI +#define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_WDG + +/* PIOS USB functions */ +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +#define PIOS_INCLUDE_USB_CDC +#define PIOS_INCLUDE_USB_RCTX + +/* PIOS sensor interfaces */ +#define PIOS_INCLUDE_ADXL345 +/* #define PIOS_INCLUDE_BMA180 */ +/* #define PIOS_INCLUDE_L3GD20 */ +#define PIOS_INCLUDE_MPU6000 +#define PIOS_MPU6000_ACCEL +/* #define PIOS_INCLUDE_HMC5843 */ +/* #define PIOS_INCLUDE_HMC5883 */ +/* #define PIOS_HMC5883_HAS_GPIOS */ +/* #define PIOS_INCLUDE_BMP085 */ +/* #define PIOS_INCLUDE_MS5611 */ +/* #define PIOS_INCLUDE_MPXV */ +/* #define PIOS_INCLUDE_ETASV3 */ +/* #define PIOS_INCLUDE_HCSR04 */ + +/* PIOS receiver drivers */ +#define PIOS_INCLUDE_PWM +#define PIOS_INCLUDE_PPM +#define PIOS_INCLUDE_PPM_FLEXI +#define PIOS_INCLUDE_DSM +#define PIOS_INCLUDE_SBUS +#define PIOS_INCLUDE_GCSRCVR + +/* PIOS abstract receiver interface */ +#define PIOS_INCLUDE_RCVR + +/* PIOS common peripherals */ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_SERVO +/* #define PIOS_INCLUDE_I2C_ESC */ +/* #define PIOS_INCLUDE_OVERO */ +/* #define PIOS_OVERO_SPI */ +/* #define PIOS_INCLUDE_SDCARD */ +/* #define LOG_FILENAME "startup.log" */ +#define PIOS_INCLUDE_FLASH +#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS +/* #define FLASH_FREERTOS */ +/* #define PIOS_INCLUDE_FLASH_EEPROM */ + +/* PIOS radio modules */ +/* #define PIOS_INCLUDE_RFM22B */ +/* #define PIOS_INCLUDE_RFM22B_COM */ +/* #define PIOS_INCLUDE_RFM22B_RCVR */ +/* #define PIOS_INCLUDE_PPM_OUT */ +/* #define PIOS_RFM22B_DEBUG_ON_TELEM */ + +/* PIOS misc peripherals */ +/* #define PIOS_INCLUDE_VIDEO */ +/* #define PIOS_INCLUDE_WAVE */ +/* #define PIOS_INCLUDE_UDP */ + +/* PIOS abstract comms interface with options */ +#define PIOS_INCLUDE_COM +/* #define PIOS_INCLUDE_COM_MSG */ +#define PIOS_INCLUDE_TELEMETRY_RF +/* #define PIOS_INCLUDE_COM_TELEM */ +/* #define PIOS_INCLUDE_COM_FLEXI */ +/* #define PIOS_INCLUDE_COM_AUX */ +/* #define PIOS_TELEM_PRIORITY_QUEUE */ +#define PIOS_INCLUDE_GPS +#define PIOS_GPS_MINIMAL +#define PIOS_INCLUDE_GPS_NMEA_PARSER +#define PIOS_INCLUDE_GPS_UBX_PARSER +/* #define PIOS_GPS_SETS_HOMELOCATION */ + +/* Stabilization options */ +/* #define PIOS_QUATERNION_STABILIZATION */ + +/* Performance counters */ +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998 + +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 220 +#define HEAP_LIMIT_CRITICAL 40 +#define IRQSTACK_LIMIT_WARNING 100 +#define IRQSTACK_LIMIT_CRITICAL 60 +#define CPULOAD_LIMIT_WARNING 85 +#define CPULOAD_LIMIT_CRITICAL 95 + +/* Task stack sizes */ +#define PIOS_ACTUATOR_STACK_SIZE 1020 +#define PIOS_MANUAL_STACK_SIZE 800 +#define PIOS_SYSTEM_STACK_SIZE 660 +#define PIOS_STABILIZATION_STACK_SIZE 524 +#define PIOS_TELEM_STACK_SIZE 500 +#define PIOS_EVENTDISPATCHER_STACK_SIZE 130 + +/* This can't be too high to stop eventdispatcher thread overflowing */ +#define PIOS_EVENTDISAPTCHER_QUEUE 10 + +/* Revolution series */ +/* #define REVOLUTION */ + +#endif /* PIOS_CONFIG_H */ +/** + * @} + * @} + */ diff --git a/flight/targets/CopterControl/System/inc/pios_config_posix.h b/flight/targets/CopterControl/System/inc/pios_config_posix.h index ed2351ea6..12dc1c6da 100644 --- a/flight/targets/CopterControl/System/inc/pios_config_posix.h +++ b/flight/targets/CopterControl/System/inc/pios_config_posix.h @@ -1,46 +1,46 @@ -/** - ****************************************************************************** - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * Central compile time config for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_CONFIG_POSIX_H -#define PIOS_CONFIG_POSIX_H - - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_FREERTOS -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_UDP -#define PIOS_INCLUDE_SERVO - - -/* Defaults for Logging */ -#define LOG_FILENAME "PIOS.LOG" -#define STARTUP_LOG_ENABLED 1 - -#endif /* PIOS_CONFIG_POSIX_H */ +/** + ****************************************************************************** + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_CONFIG_POSIX_H +#define PIOS_CONFIG_POSIX_H + + +/* Enable/Disable PiOS Modules */ +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_UDP +#define PIOS_INCLUDE_SERVO + + +/* Defaults for Logging */ +#define LOG_FILENAME "PIOS.LOG" +#define STARTUP_LOG_ENABLED 1 + +#endif /* PIOS_CONFIG_POSIX_H */ diff --git a/flight/targets/OSD/System/alarms.c b/flight/targets/OSD/System/alarms.c index e61c7c1ea..6ccd5fb62 100644 --- a/flight/targets/OSD/System/alarms.c +++ b/flight/targets/OSD/System/alarms.c @@ -1,210 +1,210 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @brief OpenPilot System libraries are available to all OP modules. - * @{ - * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Library for setting and clearing system alarms - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "alarms.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; - -// Private functions -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); - -/** - * Initialize the alarms library - */ -int32_t AlarmsInitialize(void) -{ - SystemAlarmsInitialize(); - lock = xSemaphoreCreateRecursiveMutex(); - return 0; -} - -/** - * Set an alarm - * @param alarm The system alarm to be modified - * @param severity The alarm severity - * @return 0 if success, -1 if an error - */ -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } - - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; - -} - -/** - * Get an alarm - * @param alarm The system alarm to be read - * @return Alarm severity - */ -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } - - // Read alarm - SystemAlarmsGet(&alarms); - return alarms.Alarm[alarm]; -} - -/** - * Set an alarm to it's default value - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); -} - -/** - * Default all alarms - */ -void AlarmsDefaultAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); - } -} - -/** - * Clear an alarm - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); -} - -/** - * Clear all alarms - */ -void AlarmsClearAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); - } -} - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasWarnings() -{ - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); -} - -/** - * Check if there are any alarms with error or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasErrors() -{ - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; - -/** - * Check if there are any alarms with critical or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasCritical() -{ - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - uint32_t n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarms - SystemAlarmsGet(&alarms); - - // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } - } - - // If this point is reached then no alarms found - xSemaphoreGiveRecursive(lock); - return 0; -} -/** - * @} - * @} - */ - +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @brief OpenPilot System libraries are available to all OP modules. + * @{ + * @file alarms.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Library for setting and clearing system alarms + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "alarms.h" + +// Private constants + +// Private types + +// Private variables +static xSemaphoreHandle lock; + +// Private functions +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); + +/** + * Initialize the alarms library + */ +int32_t AlarmsInitialize(void) +{ + SystemAlarmsInitialize(); + lock = xSemaphoreCreateRecursiveMutex(); + return 0; +} + +/** + * Set an alarm + * @param alarm The system alarm to be modified + * @param severity The alarm severity + * @return 0 if success, -1 if an error + */ +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return -1; + } + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarm and update its severity only if it was changed + SystemAlarmsGet(&alarms); + if ( alarms.Alarm[alarm] != severity ) + { + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); + } + + // Release lock + xSemaphoreGiveRecursive(lock); + return 0; + +} + +/** + * Get an alarm + * @param alarm The system alarm to be read + * @return Alarm severity + */ +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return 0; + } + + // Read alarm + SystemAlarmsGet(&alarms); + return alarms.Alarm[alarm]; +} + +/** + * Set an alarm to it's default value + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); +} + +/** + * Default all alarms + */ +void AlarmsDefaultAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsDefault(n); + } +} + +/** + * Clear an alarm + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); +} + +/** + * Clear all alarms + */ +void AlarmsClearAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsClear(n); + } +} + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasWarnings() +{ + return hasSeverity(SYSTEMALARMS_ALARM_WARNING); +} + +/** + * Check if there are any alarms with error or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasErrors() +{ + return hasSeverity(SYSTEMALARMS_ALARM_ERROR); +}; + +/** + * Check if there are any alarms with critical or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasCritical() +{ + return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); +}; + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + uint32_t n; + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarms + SystemAlarmsGet(&alarms); + + // Go through alarms and check if any are of the given severity or higher + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + if ( alarms.Alarm[n] >= severity) + { + xSemaphoreGiveRecursive(lock); + return 1; + } + } + + // If this point is reached then no alarms found + xSemaphoreGiveRecursive(lock); + return 0; +} +/** + * @} + * @} + */ + diff --git a/flight/targets/OSD/System/font_outlined8x14.c b/flight/targets/OSD/System/font_outlined8x14.c index 13b86e739..55b9a66dd 100644 --- a/flight/targets/OSD/System/font_outlined8x14.c +++ b/flight/targets/OSD/System/font_outlined8x14.c @@ -1,268 +1,268 @@ -/** - * Super OSD, software revision 3 - * Copyright (C) 2010 Thomas Oldbury - * - * Please note the font data here is covered under Creative - * Commons licenses (version 3.0 BY-SA) and *not* the GPL. - */ - -// This data is generated by a Python script from -// the original font .pngs. - -// 0xff = indicates character not present -// any other byte contains the index of the character. -const char font_lookup_outlined8x14[256] = { - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0x00, 0x01, 0x02, 0x03, 0xff, 0x04, 0x05, 0x06, - 0x07, 0x08, 0x09, 0x0a, 0x0b, 0x0c, 0x0d, 0x0e, - 0x0f, 0x10, 0x11, 0x12, 0x13, 0x14, 0x15, 0x16, - 0x17, 0x18, 0x19, 0x1a, 0x1b, 0x1c, 0x1d, 0x1e, - 0x1f, 0x20, 0x21, 0x22, 0x23, 0x24, 0x25, 0x26, - 0x27, 0x28, 0x29, 0x2a, 0x2b, 0x2c, 0x2d, 0x2e, - 0x2f, 0x30, 0x31, 0x32, 0x33, 0x34, 0x35, 0x36, - 0x37, 0x38, 0x39, 0x3a, 0x3b, 0x3c, 0x3d, 0x3e, - 0x3f, 0x40, 0x41, 0x42, 0x43, 0x44, 0x45, 0x46, - 0x47, 0x48, 0x49, 0x4a, 0x4b, 0x4c, 0x4d, 0x4e, - 0x4f, 0x50, 0x51, 0x52, 0x53, 0x54, 0x55, 0x56, - 0x57, 0x58, 0x59, 0x5a, 0x5b, 0x5c, 0x5d, 0xff, - 0x5e, 0x5f, 0x60, 0x61, 0x62, 0x63, 0x64, 0x65, - 0x66, 0x67, 0x68, 0x69, 0x6a, 0x6b, 0x6c, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff -}; - -const char font_data_outlined8x14[] = { - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x20 - 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, - 0x00, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x00, 0x00, 0x00, 0x18, 0x18, 0x00, 0x00, // 0x21 - 0x66, 0x66, 0x66, 0x66, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x24, 0x24, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x22 - 0x7e, 0xff, 0xff, 0xff, 0x7e, 0xff, 0xff, 0xff, 0x7e, 0xff, 0xff, 0xff, 0x7e, 0x00, - 0x00, 0x24, 0x7e, 0x24, 0x24, 0x24, 0x7e, 0x24, 0x24, 0x24, 0x7e, 0x24, 0x00, 0x00, // 0x23 - 0x00, 0x70, 0x70, 0x72, 0x07, 0x0e, 0x1c, 0x38, 0x70, 0xe0, 0x4e, 0x0e, 0x0e, 0x00, - 0x00, 0x00, 0x20, 0x00, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x00, 0x04, 0x00, 0x00, // 0x25 - 0x38, 0x3c, 0x7c, 0x7c, 0x7c, 0xfc, 0xee, 0xef, 0xef, 0xff, 0xff, 0x7e, 0x00, 0x00, - 0x00, 0x18, 0x28, 0x10, 0x28, 0x28, 0x44, 0x44, 0x46, 0x44, 0x3a, 0x00, 0x00, 0x00, // 0x26 - 0x38, 0x38, 0x38, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x10, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x27 - 0x1e, 0x3e, 0x7e, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x7e, 0x3e, 0x1e, 0x00, - 0x00, 0x1c, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x1c, 0x00, 0x00, // 0x28 - 0x78, 0x7c, 0x7e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x7e, 0x7c, 0x78, 0x00, - 0x00, 0x38, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x38, 0x00, 0x00, // 0x29 - 0x38, 0x7c, 0xfe, 0xfe, 0xfe, 0xee, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x10, 0x7c, 0x28, 0x44, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x2a - 0x00, 0x00, 0x00, 0x38, 0x38, 0xfe, 0xfe, 0xfe, 0x38, 0x38, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x10, 0x10, 0x7c, 0x10, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x2b - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x38, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x18, 0x10, 0x00, 0x00, // 0x2c - 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x2d - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x18, 0x00, 0x00, // 0x2e - 0x00, 0x07, 0x07, 0x0f, 0x0e, 0x1c, 0x1c, 0x38, 0x38, 0x70, 0xf0, 0xe0, 0xe0, 0x00, - 0x00, 0x00, 0x02, 0x04, 0x04, 0x08, 0x08, 0x10, 0x10, 0x20, 0x20, 0x40, 0x00, 0x00, // 0x2f - 0x7e, 0xff, 0xff, 0xe7, 0xef, 0xff, 0xff, 0xf7, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x00, - 0x00, 0x3c, 0x42, 0x42, 0x46, 0x4a, 0x52, 0x62, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x30 - 0x3c, 0x7c, 0xfc, 0xfc, 0x5c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0xff, 0xff, 0xff, 0x00, - 0x00, 0x38, 0x68, 0x48, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x7e, 0x00, 0x00, // 0x31 - 0x3e, 0x7f, 0xff, 0xe7, 0x47, 0x07, 0x0e, 0x1c, 0x38, 0x70, 0xff, 0xff, 0xff, 0x00, - 0x00, 0x3c, 0x62, 0x42, 0x02, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x7e, 0x00, 0x00, // 0x32 - 0xfe, 0xff, 0xff, 0x07, 0x07, 0x7f, 0x7e, 0x7f, 0x07, 0x07, 0xff, 0xff, 0xfe, 0x00, - 0x00, 0x7c, 0x02, 0x02, 0x02, 0x04, 0x38, 0x04, 0x02, 0x02, 0x02, 0x7c, 0x00, 0x00, // 0x33 - 0x04, 0x0e, 0x1e, 0x3e, 0x7e, 0xff, 0xff, 0xff, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x00, - 0x00, 0x04, 0x0c, 0x14, 0x24, 0x44, 0x7e, 0x04, 0x04, 0x04, 0x04, 0x04, 0x00, 0x00, // 0x34 - 0xff, 0xff, 0xff, 0xe0, 0xfc, 0xfe, 0xff, 0x0f, 0x07, 0x0f, 0xff, 0xfe, 0xfc, 0x00, - 0x00, 0x7e, 0x40, 0x40, 0x40, 0x78, 0x04, 0x02, 0x02, 0x02, 0x04, 0x78, 0x00, 0x00, // 0x35 - 0xfe, 0xfe, 0xfe, 0xe0, 0xe0, 0xfe, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x00, - 0x00, 0x3c, 0x40, 0x40, 0x40, 0x40, 0x7c, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x36 - 0xff, 0xff, 0xff, 0x07, 0x07, 0x0e, 0x0e, 0x1c, 0x1c, 0x38, 0x38, 0x70, 0x70, 0x00, - 0x00, 0x7e, 0x02, 0x02, 0x02, 0x04, 0x04, 0x08, 0x08, 0x10, 0x10, 0x20, 0x00, 0x00, // 0x37 - 0x3c, 0x7e, 0xff, 0xe7, 0xe7, 0xff, 0x7e, 0xff, 0xe7, 0xe7, 0xff, 0x7e, 0x3c, 0x00, - 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x38 - 0x7e, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0x7f, 0x07, 0x07, 0x7f, 0x7f, 0x7f, 0x00, - 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x3e, 0x02, 0x02, 0x02, 0x02, 0x3c, 0x00, 0x00, // 0x39 - 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x18, 0x18, 0x00, 0x00, 0x00, 0x00, 0x18, 0x18, 0x00, 0x00, 0x00, // 0x3a - 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x38, 0x00, - 0x00, 0x00, 0x00, 0x18, 0x18, 0x00, 0x00, 0x00, 0x00, 0x18, 0x18, 0x10, 0x00, 0x00, // 0x3b - 0x00, 0x00, 0x04, 0x0e, 0x1c, 0x38, 0x70, 0xe0, 0x70, 0x38, 0x1c, 0x0e, 0x04, 0x00, - 0x00, 0x00, 0x00, 0x04, 0x08, 0x10, 0x20, 0x40, 0x20, 0x10, 0x08, 0x04, 0x00, 0x00, // 0x3c - 0x00, 0x00, 0x00, 0x7e, 0x7e, 0x7e, 0x00, 0x7e, 0x7e, 0x7e, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x3d - 0x00, 0x00, 0x20, 0x70, 0x38, 0x1c, 0x0e, 0x07, 0x0e, 0x1c, 0x38, 0x70, 0x20, 0x00, - 0x00, 0x00, 0x00, 0x20, 0x10, 0x08, 0x04, 0x02, 0x04, 0x08, 0x10, 0x20, 0x00, 0x00, // 0x3e - 0x3c, 0xfe, 0xff, 0xe7, 0xe7, 0x0e, 0x1c, 0x38, 0x38, 0x00, 0x38, 0x38, 0x38, 0x00, - 0x00, 0x3c, 0x42, 0x42, 0x02, 0x04, 0x08, 0x10, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, // 0x3f - 0x18, 0x3c, 0x7e, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0x7c, 0x3e, 0x1e, 0x00, - 0x00, 0x18, 0x24, 0x42, 0x42, 0x42, 0x4a, 0x52, 0x52, 0x4c, 0x20, 0x1e, 0x00, 0x00, // 0x40 - 0x7e, 0xff, 0xff, 0xff, 0xe7, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, - 0x00, 0x3c, 0x66, 0x42, 0x42, 0x42, 0x7e, 0x42, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x41 - 0xfe, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0xfe, 0x00, - 0x00, 0x7c, 0x46, 0x42, 0x42, 0x42, 0x7c, 0x42, 0x42, 0x42, 0x46, 0x7c, 0x00, 0x00, // 0x42 - 0x7f, 0xff, 0xff, 0xf7, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xf7, 0xff, 0xff, 0x7f, 0x00, - 0x00, 0x3e, 0x62, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x62, 0x3e, 0x00, 0x00, // 0x43 - 0xfe, 0xff, 0xff, 0xef, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xef, 0xff, 0xff, 0xfe, 0x00, - 0x00, 0x7c, 0x46, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x46, 0x7c, 0x00, 0x00, // 0x44 - 0xff, 0xff, 0xff, 0xe0, 0xe0, 0xfe, 0xfe, 0xfe, 0xe0, 0xe0, 0xff, 0xff, 0xff, 0x00, - 0x00, 0x7e, 0x40, 0x40, 0x40, 0x40, 0x7c, 0x40, 0x40, 0x40, 0x40, 0x7e, 0x00, 0x00, // 0x45 - 0xff, 0xff, 0xff, 0xe0, 0xe0, 0xfe, 0xfe, 0xfe, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0x00, - 0x00, 0x7e, 0x40, 0x40, 0x40, 0x40, 0x7c, 0x40, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, // 0x46 - 0x7f, 0xff, 0xff, 0xf0, 0xe0, 0xef, 0xef, 0xef, 0xe7, 0xf7, 0xff, 0xff, 0x7f, 0x00, - 0x00, 0x3e, 0x60, 0x40, 0x40, 0x40, 0x46, 0x42, 0x42, 0x42, 0x62, 0x3e, 0x00, 0x00, // 0x47 - 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, - 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x7e, 0x42, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x48 - 0xfe, 0xfe, 0xfe, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x7c, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x7c, 0x00, 0x00, // 0x49 - 0xff, 0xff, 0xff, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x3c, 0xfc, 0xfc, 0xf8, 0x00, - 0x00, 0x7e, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x18, 0x70, 0x00, 0x00, // 0x4a - 0xe7, 0xef, 0xff, 0xfe, 0xfc, 0xf8, 0xf0, 0xf8, 0xfc, 0xfe, 0xff, 0xef, 0xe7, 0x00, - 0x00, 0x42, 0x44, 0x48, 0x50, 0x60, 0x40, 0x60, 0x50, 0x48, 0x44, 0x42, 0x00, 0x00, // 0x4b - 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xff, 0xff, 0xff, 0x00, - 0x00, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x7e, 0x00, 0x00, // 0x4c - 0xe7, 0xff, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, - 0x00, 0x42, 0x66, 0x5a, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x4d - 0xe7, 0xf7, 0xff, 0xff, 0xff, 0xff, 0xef, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, - 0x00, 0x42, 0x62, 0x52, 0x4a, 0x46, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x4e - 0x7e, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x00, - 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x4f - 0xfe, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0xfe, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0x00, - 0x00, 0x7e, 0x42, 0x42, 0x42, 0x42, 0x7e, 0x40, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, // 0x50 - 0x7e, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0x7f, 0x07, 0x07, 0x00, - 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x02, 0x02, 0x00, 0x00, // 0x51 - 0xfe, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0xfe, 0xf8, 0xfc, 0xee, 0xe7, 0xe3, 0x00, - 0x00, 0x7e, 0x42, 0x42, 0x42, 0x42, 0x7e, 0x60, 0x50, 0x48, 0x44, 0x42, 0x00, 0x00, // 0x52 - 0xff, 0xff, 0xff, 0xe0, 0xf0, 0xfe, 0xff, 0x7f, 0x0f, 0x07, 0xff, 0xff, 0xff, 0x00, - 0x00, 0x7e, 0x40, 0x40, 0x40, 0x60, 0x3c, 0x06, 0x02, 0x02, 0x02, 0x7e, 0x00, 0x00, // 0x53 - 0xfe, 0xfe, 0xfe, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x00, - 0x00, 0x7c, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x00, 0x00, // 0x54 - 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0x7e, 0x3c, 0x00, - 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x55 - 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xfe, 0x7e, 0x7e, 0x7e, 0x3c, 0x3c, 0x00, - 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x24, 0x24, 0x24, 0x18, 0x18, 0x00, 0x00, // 0x56 - 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xe7, 0x00, - 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x5a, 0x66, 0x42, 0x00, 0x00, // 0x57 - 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0x7f, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0x00, - 0x00, 0x42, 0x42, 0x42, 0x66, 0x3c, 0x18, 0x3c, 0x66, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x58 - 0xee, 0xee, 0xfe, 0xfe, 0x7c, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x00, - 0x00, 0x44, 0x44, 0x28, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x00, 0x00, // 0x59 - 0xff, 0xff, 0xff, 0x07, 0x07, 0x0e, 0x1c, 0x38, 0x70, 0xe0, 0xff, 0xff, 0xff, 0x00, - 0x00, 0x7e, 0x02, 0x02, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x40, 0x7e, 0x00, 0x00, // 0x5a - 0x7e, 0x7e, 0x7e, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x3c, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x3c, 0x00, 0x00, // 0x5b - 0x00, 0xe0, 0xe0, 0xf0, 0x70, 0x38, 0x38, 0x1c, 0x1c, 0x0e, 0x0f, 0x07, 0x07, 0x00, - 0x00, 0x00, 0x40, 0x20, 0x20, 0x10, 0x10, 0x08, 0x08, 0x04, 0x04, 0x02, 0x00, 0x00, // 0x5c - 0x7e, 0x7e, 0x7e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x3c, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x3c, 0x00, 0x00, // 0x5d - 0x3c, 0x7e, 0x7e, 0x7e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x18, 0x24, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x5e - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x00, // 0x5f - 0x30, 0x38, 0x1c, 0x0c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x10, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x60 - 0x00, 0x00, 0x00, 0x00, 0x7c, 0xfc, 0xfe, 0xee, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x44, 0x04, 0x04, 0x3c, 0x44, 0x7a, 0x00, 0x00, // 0x61 - 0x00, 0xe0, 0xe0, 0xe0, 0xe0, 0xfe, 0xff, 0xff, 0xf7, 0xe7, 0xff, 0xff, 0x7e, 0x00, - 0x00, 0x00, 0x40, 0x40, 0x40, 0x40, 0x5c, 0x62, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x62 - 0x00, 0x00, 0x00, 0x00, 0x3f, 0x7f, 0xff, 0xf0, 0xe0, 0xf0, 0xff, 0x7f, 0x3f, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x1e, 0x20, 0x40, 0x40, 0x40, 0x20, 0x1e, 0x00, 0x00, // 0x63 - 0x00, 0x07, 0x07, 0x07, 0x07, 0x7f, 0xff, 0xff, 0xef, 0xe7, 0xff, 0xff, 0x7e, 0x00, - 0x00, 0x00, 0x02, 0x02, 0x02, 0x02, 0x3a, 0x46, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x64 - 0x00, 0x00, 0x00, 0x00, 0x7e, 0xff, 0xff, 0xe7, 0xff, 0xff, 0xff, 0xff, 0x7f, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x42, 0x42, 0x42, 0x5c, 0x40, 0x3e, 0x00, 0x00, // 0x65 - 0x3f, 0x7f, 0xff, 0xf0, 0xe0, 0xfe, 0xfe, 0xfe, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0x00, - 0x00, 0x1e, 0x20, 0x40, 0x40, 0x40, 0x7c, 0x40, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, // 0x66 - 0x7c, 0xfe, 0xff, 0xef, 0xe7, 0xff, 0xff, 0x7f, 0x07, 0x0f, 0xff, 0xfe, 0xfc, 0x00, - 0x00, 0x38, 0x44, 0x42, 0x42, 0x42, 0x3e, 0x02, 0x02, 0x02, 0x04, 0x78, 0x00, 0x00, // 0x67 - 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xfc, 0xfe, 0xff, 0xef, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, - 0x00, 0x40, 0x40, 0x40, 0x40, 0x40, 0x78, 0x44, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x68 - 0x1c, 0x1c, 0x1c, 0x00, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x00, - 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x00, 0x00, // 0x69 - 0x1c, 0x1c, 0x1c, 0x00, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x3c, 0xfc, 0xfc, 0xf0, 0x00, - 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x08, 0x08, 0x08, 0x08, 0x10, 0x60, 0x00, 0x00, // 0x6a - 0x00, 0xe2, 0xe7, 0xee, 0xfc, 0xf8, 0xf0, 0xf0, 0xf8, 0xfc, 0xee, 0xe7, 0xe2, 0x00, - 0x00, 0x00, 0x42, 0x44, 0x48, 0x50, 0x60, 0x60, 0x50, 0x48, 0x44, 0x42, 0x00, 0x00, // 0x6b - 0xf0, 0xf0, 0xf0, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x78, 0x7f, 0x3f, 0x1f, 0x00, - 0x00, 0x60, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x10, 0x0e, 0x00, 0x00, // 0x6c - 0x00, 0x00, 0x00, 0x00, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x66, 0x5a, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x6d - 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x6e - 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x6f - 0x3c, 0x7e, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0xfe, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0x00, - 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x7c, 0x40, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, // 0x70 - 0x3c, 0x7e, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0x7f, 0x07, 0x07, 0x07, 0x07, 0x07, 0x00, - 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x3e, 0x02, 0x02, 0x02, 0x03, 0x02, 0x00, 0x00, // 0x71 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x3f, 0x7f, 0xff, 0xf0, 0xe0, 0xe0, 0xe0, 0xe0, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1e, 0x20, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, // 0x72 - 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0xff, 0xfe, 0xff, 0x7f, 0xff, 0xff, 0xff, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x3e, 0x40, 0x40, 0x3c, 0x02, 0x02, 0x7e, 0x00, 0x00, // 0x73 - 0x00, 0xe0, 0xe0, 0xe0, 0xe0, 0xfc, 0xfc, 0xfc, 0xe0, 0xf0, 0xfe, 0xfe, 0x7e, 0x00, - 0x00, 0x00, 0x40, 0x40, 0x40, 0x40, 0x78, 0x40, 0x40, 0x40, 0x60, 0x3c, 0x00, 0x00, // 0x74 - 0x00, 0x00, 0x00, 0x00, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x75 - 0x00, 0x00, 0x00, 0x00, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x3c, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x24, 0x18, 0x00, 0x00, // 0x76 - 0x00, 0x00, 0x00, 0x00, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xe7, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x42, 0x42, 0x42, 0x5a, 0x66, 0x42, 0x00, 0x00, // 0x77 - 0x00, 0x00, 0x00, 0x00, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0xff, 0xe7, 0xe7, 0xe7, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x42, 0x24, 0x18, 0x24, 0x42, 0x42, 0x00, 0x00, // 0x78 - 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0x07, 0x07, 0x0f, 0xff, 0xfe, 0xfc, 0x00, - 0x00, 0x42, 0x42, 0x42, 0x42, 0x7c, 0x02, 0x02, 0x02, 0x02, 0x04, 0x78, 0x00, 0x00, // 0x79 - 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0x0e, 0x1c, 0x38, 0x70, 0xff, 0xff, 0xff, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x7e, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x7e, 0x00, 0x00, // 0x7a - 0x00, 0x3f, 0x7f, 0x7f, 0x70, 0xf0, 0xf0, 0xf0, 0xf0, 0x70, 0x7f, 0x7f, 0x3f, 0x00, - 0x00, 0x00, 0x1e, 0x20, 0x20, 0x20, 0x40, 0x40, 0x20, 0x20, 0x20, 0x1e, 0x00, 0x00, // 0x7b - 0x00, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x00, - 0x00, 0x00, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x00, 0x00, // 0x7c - 0x00, 0xfc, 0xfe, 0xfe, 0x0e, 0x0f, 0x0f, 0x0f, 0x0f, 0x0e, 0xfe, 0xfe, 0xfc, 0x00, - 0x00, 0x00, 0x78, 0x04, 0x04, 0x04, 0x02, 0x02, 0x04, 0x04, 0x04, 0x78, 0x00, 0x00, // 0x7d - 0x00, 0x10, 0x3a, 0x7f, 0x2e, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x10, 0x2a, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x7e - 0x00, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x80 - 0x00, 0x00, 0x00, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x81 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x82 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x83 - 0x00, 0x18, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x84 - 0x00, 0x00, 0x00, 0x18, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x85 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x86 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x87 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x00, 0x00, // 0x88 - 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x7e, 0x7e, 0x3c, 0x00, - 0x00, 0x00, 0x18, 0x08, 0x18, 0x08, 0x18, 0x08, 0x18, 0x08, 0x3c, 0x3c, 0x00, 0x00, // 0x89 - 0x00, 0xff, 0xff, 0xff, 0xff, 0x1f, 0x1f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x6e, 0x68, 0x08, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x8a - 0x00, 0xff, 0xff, 0xff, 0xff, 0x1f, 0x1f, 0x1f, 0x1f, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x69, 0x6a, 0x0c, 0x0c, 0x0a, 0x09, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x8b - 0x00, 0xff, 0xff, 0xff, 0xff, 0x1f, 0x1f, 0x1c, 0x1c, 0x1c, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x6e, 0x68, 0x08, 0x0e, 0x08, 0x08, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x8c - 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0x7c, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x8d - 0x00, 0x00, 0x00, 0x3e, 0x7f, 0x7f, 0x7f, 0x7f, 0x7f, 0x3e, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x36, 0x36, 0x32, 0x3e, 0x3e, 0x00, 0x00, 0x00, 0x00, 0x00 // 0x8e -}; +/** + * Super OSD, software revision 3 + * Copyright (C) 2010 Thomas Oldbury + * + * Please note the font data here is covered under Creative + * Commons licenses (version 3.0 BY-SA) and *not* the GPL. + */ + +// This data is generated by a Python script from +// the original font .pngs. + +// 0xff = indicates character not present +// any other byte contains the index of the character. +const char font_lookup_outlined8x14[256] = { + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0x00, 0x01, 0x02, 0x03, 0xff, 0x04, 0x05, 0x06, + 0x07, 0x08, 0x09, 0x0a, 0x0b, 0x0c, 0x0d, 0x0e, + 0x0f, 0x10, 0x11, 0x12, 0x13, 0x14, 0x15, 0x16, + 0x17, 0x18, 0x19, 0x1a, 0x1b, 0x1c, 0x1d, 0x1e, + 0x1f, 0x20, 0x21, 0x22, 0x23, 0x24, 0x25, 0x26, + 0x27, 0x28, 0x29, 0x2a, 0x2b, 0x2c, 0x2d, 0x2e, + 0x2f, 0x30, 0x31, 0x32, 0x33, 0x34, 0x35, 0x36, + 0x37, 0x38, 0x39, 0x3a, 0x3b, 0x3c, 0x3d, 0x3e, + 0x3f, 0x40, 0x41, 0x42, 0x43, 0x44, 0x45, 0x46, + 0x47, 0x48, 0x49, 0x4a, 0x4b, 0x4c, 0x4d, 0x4e, + 0x4f, 0x50, 0x51, 0x52, 0x53, 0x54, 0x55, 0x56, + 0x57, 0x58, 0x59, 0x5a, 0x5b, 0x5c, 0x5d, 0xff, + 0x5e, 0x5f, 0x60, 0x61, 0x62, 0x63, 0x64, 0x65, + 0x66, 0x67, 0x68, 0x69, 0x6a, 0x6b, 0x6c, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff +}; + +const char font_data_outlined8x14[] = { + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x20 + 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, + 0x00, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x00, 0x00, 0x00, 0x18, 0x18, 0x00, 0x00, // 0x21 + 0x66, 0x66, 0x66, 0x66, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x24, 0x24, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x22 + 0x7e, 0xff, 0xff, 0xff, 0x7e, 0xff, 0xff, 0xff, 0x7e, 0xff, 0xff, 0xff, 0x7e, 0x00, + 0x00, 0x24, 0x7e, 0x24, 0x24, 0x24, 0x7e, 0x24, 0x24, 0x24, 0x7e, 0x24, 0x00, 0x00, // 0x23 + 0x00, 0x70, 0x70, 0x72, 0x07, 0x0e, 0x1c, 0x38, 0x70, 0xe0, 0x4e, 0x0e, 0x0e, 0x00, + 0x00, 0x00, 0x20, 0x00, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x00, 0x04, 0x00, 0x00, // 0x25 + 0x38, 0x3c, 0x7c, 0x7c, 0x7c, 0xfc, 0xee, 0xef, 0xef, 0xff, 0xff, 0x7e, 0x00, 0x00, + 0x00, 0x18, 0x28, 0x10, 0x28, 0x28, 0x44, 0x44, 0x46, 0x44, 0x3a, 0x00, 0x00, 0x00, // 0x26 + 0x38, 0x38, 0x38, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x10, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x27 + 0x1e, 0x3e, 0x7e, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x7e, 0x3e, 0x1e, 0x00, + 0x00, 0x1c, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x1c, 0x00, 0x00, // 0x28 + 0x78, 0x7c, 0x7e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x7e, 0x7c, 0x78, 0x00, + 0x00, 0x38, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x38, 0x00, 0x00, // 0x29 + 0x38, 0x7c, 0xfe, 0xfe, 0xfe, 0xee, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x10, 0x7c, 0x28, 0x44, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x2a + 0x00, 0x00, 0x00, 0x38, 0x38, 0xfe, 0xfe, 0xfe, 0x38, 0x38, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x10, 0x10, 0x7c, 0x10, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x2b + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x38, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x18, 0x10, 0x00, 0x00, // 0x2c + 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x2d + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x18, 0x00, 0x00, // 0x2e + 0x00, 0x07, 0x07, 0x0f, 0x0e, 0x1c, 0x1c, 0x38, 0x38, 0x70, 0xf0, 0xe0, 0xe0, 0x00, + 0x00, 0x00, 0x02, 0x04, 0x04, 0x08, 0x08, 0x10, 0x10, 0x20, 0x20, 0x40, 0x00, 0x00, // 0x2f + 0x7e, 0xff, 0xff, 0xe7, 0xef, 0xff, 0xff, 0xf7, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x00, + 0x00, 0x3c, 0x42, 0x42, 0x46, 0x4a, 0x52, 0x62, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x30 + 0x3c, 0x7c, 0xfc, 0xfc, 0x5c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0xff, 0xff, 0xff, 0x00, + 0x00, 0x38, 0x68, 0x48, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x7e, 0x00, 0x00, // 0x31 + 0x3e, 0x7f, 0xff, 0xe7, 0x47, 0x07, 0x0e, 0x1c, 0x38, 0x70, 0xff, 0xff, 0xff, 0x00, + 0x00, 0x3c, 0x62, 0x42, 0x02, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x7e, 0x00, 0x00, // 0x32 + 0xfe, 0xff, 0xff, 0x07, 0x07, 0x7f, 0x7e, 0x7f, 0x07, 0x07, 0xff, 0xff, 0xfe, 0x00, + 0x00, 0x7c, 0x02, 0x02, 0x02, 0x04, 0x38, 0x04, 0x02, 0x02, 0x02, 0x7c, 0x00, 0x00, // 0x33 + 0x04, 0x0e, 0x1e, 0x3e, 0x7e, 0xff, 0xff, 0xff, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x00, + 0x00, 0x04, 0x0c, 0x14, 0x24, 0x44, 0x7e, 0x04, 0x04, 0x04, 0x04, 0x04, 0x00, 0x00, // 0x34 + 0xff, 0xff, 0xff, 0xe0, 0xfc, 0xfe, 0xff, 0x0f, 0x07, 0x0f, 0xff, 0xfe, 0xfc, 0x00, + 0x00, 0x7e, 0x40, 0x40, 0x40, 0x78, 0x04, 0x02, 0x02, 0x02, 0x04, 0x78, 0x00, 0x00, // 0x35 + 0xfe, 0xfe, 0xfe, 0xe0, 0xe0, 0xfe, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x00, + 0x00, 0x3c, 0x40, 0x40, 0x40, 0x40, 0x7c, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x36 + 0xff, 0xff, 0xff, 0x07, 0x07, 0x0e, 0x0e, 0x1c, 0x1c, 0x38, 0x38, 0x70, 0x70, 0x00, + 0x00, 0x7e, 0x02, 0x02, 0x02, 0x04, 0x04, 0x08, 0x08, 0x10, 0x10, 0x20, 0x00, 0x00, // 0x37 + 0x3c, 0x7e, 0xff, 0xe7, 0xe7, 0xff, 0x7e, 0xff, 0xe7, 0xe7, 0xff, 0x7e, 0x3c, 0x00, + 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x38 + 0x7e, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0x7f, 0x07, 0x07, 0x7f, 0x7f, 0x7f, 0x00, + 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x3e, 0x02, 0x02, 0x02, 0x02, 0x3c, 0x00, 0x00, // 0x39 + 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x18, 0x18, 0x00, 0x00, 0x00, 0x00, 0x18, 0x18, 0x00, 0x00, 0x00, // 0x3a + 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x38, 0x00, + 0x00, 0x00, 0x00, 0x18, 0x18, 0x00, 0x00, 0x00, 0x00, 0x18, 0x18, 0x10, 0x00, 0x00, // 0x3b + 0x00, 0x00, 0x04, 0x0e, 0x1c, 0x38, 0x70, 0xe0, 0x70, 0x38, 0x1c, 0x0e, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x04, 0x08, 0x10, 0x20, 0x40, 0x20, 0x10, 0x08, 0x04, 0x00, 0x00, // 0x3c + 0x00, 0x00, 0x00, 0x7e, 0x7e, 0x7e, 0x00, 0x7e, 0x7e, 0x7e, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x3c, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x3d + 0x00, 0x00, 0x20, 0x70, 0x38, 0x1c, 0x0e, 0x07, 0x0e, 0x1c, 0x38, 0x70, 0x20, 0x00, + 0x00, 0x00, 0x00, 0x20, 0x10, 0x08, 0x04, 0x02, 0x04, 0x08, 0x10, 0x20, 0x00, 0x00, // 0x3e + 0x3c, 0xfe, 0xff, 0xe7, 0xe7, 0x0e, 0x1c, 0x38, 0x38, 0x00, 0x38, 0x38, 0x38, 0x00, + 0x00, 0x3c, 0x42, 0x42, 0x02, 0x04, 0x08, 0x10, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, // 0x3f + 0x18, 0x3c, 0x7e, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0x7c, 0x3e, 0x1e, 0x00, + 0x00, 0x18, 0x24, 0x42, 0x42, 0x42, 0x4a, 0x52, 0x52, 0x4c, 0x20, 0x1e, 0x00, 0x00, // 0x40 + 0x7e, 0xff, 0xff, 0xff, 0xe7, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, + 0x00, 0x3c, 0x66, 0x42, 0x42, 0x42, 0x7e, 0x42, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x41 + 0xfe, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0xfe, 0x00, + 0x00, 0x7c, 0x46, 0x42, 0x42, 0x42, 0x7c, 0x42, 0x42, 0x42, 0x46, 0x7c, 0x00, 0x00, // 0x42 + 0x7f, 0xff, 0xff, 0xf7, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xf7, 0xff, 0xff, 0x7f, 0x00, + 0x00, 0x3e, 0x62, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x62, 0x3e, 0x00, 0x00, // 0x43 + 0xfe, 0xff, 0xff, 0xef, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xef, 0xff, 0xff, 0xfe, 0x00, + 0x00, 0x7c, 0x46, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x46, 0x7c, 0x00, 0x00, // 0x44 + 0xff, 0xff, 0xff, 0xe0, 0xe0, 0xfe, 0xfe, 0xfe, 0xe0, 0xe0, 0xff, 0xff, 0xff, 0x00, + 0x00, 0x7e, 0x40, 0x40, 0x40, 0x40, 0x7c, 0x40, 0x40, 0x40, 0x40, 0x7e, 0x00, 0x00, // 0x45 + 0xff, 0xff, 0xff, 0xe0, 0xe0, 0xfe, 0xfe, 0xfe, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0x00, + 0x00, 0x7e, 0x40, 0x40, 0x40, 0x40, 0x7c, 0x40, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, // 0x46 + 0x7f, 0xff, 0xff, 0xf0, 0xe0, 0xef, 0xef, 0xef, 0xe7, 0xf7, 0xff, 0xff, 0x7f, 0x00, + 0x00, 0x3e, 0x60, 0x40, 0x40, 0x40, 0x46, 0x42, 0x42, 0x42, 0x62, 0x3e, 0x00, 0x00, // 0x47 + 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, + 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x7e, 0x42, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x48 + 0xfe, 0xfe, 0xfe, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x7c, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x7c, 0x00, 0x00, // 0x49 + 0xff, 0xff, 0xff, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x3c, 0xfc, 0xfc, 0xf8, 0x00, + 0x00, 0x7e, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x18, 0x70, 0x00, 0x00, // 0x4a + 0xe7, 0xef, 0xff, 0xfe, 0xfc, 0xf8, 0xf0, 0xf8, 0xfc, 0xfe, 0xff, 0xef, 0xe7, 0x00, + 0x00, 0x42, 0x44, 0x48, 0x50, 0x60, 0x40, 0x60, 0x50, 0x48, 0x44, 0x42, 0x00, 0x00, // 0x4b + 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xff, 0xff, 0xff, 0x00, + 0x00, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x7e, 0x00, 0x00, // 0x4c + 0xe7, 0xff, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, + 0x00, 0x42, 0x66, 0x5a, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x4d + 0xe7, 0xf7, 0xff, 0xff, 0xff, 0xff, 0xef, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, + 0x00, 0x42, 0x62, 0x52, 0x4a, 0x46, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x4e + 0x7e, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x00, + 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x4f + 0xfe, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0xfe, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0x00, + 0x00, 0x7e, 0x42, 0x42, 0x42, 0x42, 0x7e, 0x40, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, // 0x50 + 0x7e, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0x7f, 0x07, 0x07, 0x00, + 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x02, 0x02, 0x00, 0x00, // 0x51 + 0xfe, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0xfe, 0xf8, 0xfc, 0xee, 0xe7, 0xe3, 0x00, + 0x00, 0x7e, 0x42, 0x42, 0x42, 0x42, 0x7e, 0x60, 0x50, 0x48, 0x44, 0x42, 0x00, 0x00, // 0x52 + 0xff, 0xff, 0xff, 0xe0, 0xf0, 0xfe, 0xff, 0x7f, 0x0f, 0x07, 0xff, 0xff, 0xff, 0x00, + 0x00, 0x7e, 0x40, 0x40, 0x40, 0x60, 0x3c, 0x06, 0x02, 0x02, 0x02, 0x7e, 0x00, 0x00, // 0x53 + 0xfe, 0xfe, 0xfe, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x00, + 0x00, 0x7c, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x00, 0x00, // 0x54 + 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0x7e, 0x3c, 0x00, + 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x55 + 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xfe, 0x7e, 0x7e, 0x7e, 0x3c, 0x3c, 0x00, + 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x24, 0x24, 0x24, 0x18, 0x18, 0x00, 0x00, // 0x56 + 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xe7, 0x00, + 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x5a, 0x66, 0x42, 0x00, 0x00, // 0x57 + 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0x7f, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0x00, + 0x00, 0x42, 0x42, 0x42, 0x66, 0x3c, 0x18, 0x3c, 0x66, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x58 + 0xee, 0xee, 0xfe, 0xfe, 0x7c, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x00, + 0x00, 0x44, 0x44, 0x28, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x00, 0x00, // 0x59 + 0xff, 0xff, 0xff, 0x07, 0x07, 0x0e, 0x1c, 0x38, 0x70, 0xe0, 0xff, 0xff, 0xff, 0x00, + 0x00, 0x7e, 0x02, 0x02, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x40, 0x7e, 0x00, 0x00, // 0x5a + 0x7e, 0x7e, 0x7e, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x3c, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x3c, 0x00, 0x00, // 0x5b + 0x00, 0xe0, 0xe0, 0xf0, 0x70, 0x38, 0x38, 0x1c, 0x1c, 0x0e, 0x0f, 0x07, 0x07, 0x00, + 0x00, 0x00, 0x40, 0x20, 0x20, 0x10, 0x10, 0x08, 0x08, 0x04, 0x04, 0x02, 0x00, 0x00, // 0x5c + 0x7e, 0x7e, 0x7e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x0e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x3c, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x3c, 0x00, 0x00, // 0x5d + 0x3c, 0x7e, 0x7e, 0x7e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x18, 0x24, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x5e + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x00, 0x00, // 0x5f + 0x30, 0x38, 0x1c, 0x0c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x10, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x60 + 0x00, 0x00, 0x00, 0x00, 0x7c, 0xfc, 0xfe, 0xee, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x44, 0x04, 0x04, 0x3c, 0x44, 0x7a, 0x00, 0x00, // 0x61 + 0x00, 0xe0, 0xe0, 0xe0, 0xe0, 0xfe, 0xff, 0xff, 0xf7, 0xe7, 0xff, 0xff, 0x7e, 0x00, + 0x00, 0x00, 0x40, 0x40, 0x40, 0x40, 0x5c, 0x62, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x62 + 0x00, 0x00, 0x00, 0x00, 0x3f, 0x7f, 0xff, 0xf0, 0xe0, 0xf0, 0xff, 0x7f, 0x3f, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x1e, 0x20, 0x40, 0x40, 0x40, 0x20, 0x1e, 0x00, 0x00, // 0x63 + 0x00, 0x07, 0x07, 0x07, 0x07, 0x7f, 0xff, 0xff, 0xef, 0xe7, 0xff, 0xff, 0x7e, 0x00, + 0x00, 0x00, 0x02, 0x02, 0x02, 0x02, 0x3a, 0x46, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x64 + 0x00, 0x00, 0x00, 0x00, 0x7e, 0xff, 0xff, 0xe7, 0xff, 0xff, 0xff, 0xff, 0x7f, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x42, 0x42, 0x42, 0x5c, 0x40, 0x3e, 0x00, 0x00, // 0x65 + 0x3f, 0x7f, 0xff, 0xf0, 0xe0, 0xfe, 0xfe, 0xfe, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0x00, + 0x00, 0x1e, 0x20, 0x40, 0x40, 0x40, 0x7c, 0x40, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, // 0x66 + 0x7c, 0xfe, 0xff, 0xef, 0xe7, 0xff, 0xff, 0x7f, 0x07, 0x0f, 0xff, 0xfe, 0xfc, 0x00, + 0x00, 0x38, 0x44, 0x42, 0x42, 0x42, 0x3e, 0x02, 0x02, 0x02, 0x04, 0x78, 0x00, 0x00, // 0x67 + 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0xfc, 0xfe, 0xff, 0xef, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, + 0x00, 0x40, 0x40, 0x40, 0x40, 0x40, 0x78, 0x44, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x68 + 0x1c, 0x1c, 0x1c, 0x00, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x00, + 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x00, 0x00, // 0x69 + 0x1c, 0x1c, 0x1c, 0x00, 0x1c, 0x1c, 0x1c, 0x1c, 0x1c, 0x3c, 0xfc, 0xfc, 0xf0, 0x00, + 0x00, 0x08, 0x00, 0x00, 0x00, 0x08, 0x08, 0x08, 0x08, 0x08, 0x10, 0x60, 0x00, 0x00, // 0x6a + 0x00, 0xe2, 0xe7, 0xee, 0xfc, 0xf8, 0xf0, 0xf0, 0xf8, 0xfc, 0xee, 0xe7, 0xe2, 0x00, + 0x00, 0x00, 0x42, 0x44, 0x48, 0x50, 0x60, 0x60, 0x50, 0x48, 0x44, 0x42, 0x00, 0x00, // 0x6b + 0xf0, 0xf0, 0xf0, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x78, 0x7f, 0x3f, 0x1f, 0x00, + 0x00, 0x60, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x10, 0x0e, 0x00, 0x00, // 0x6c + 0x00, 0x00, 0x00, 0x00, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x66, 0x5a, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x6d + 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0xff, 0xff, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x42, 0x00, 0x00, // 0x6e + 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0xff, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x6f + 0x3c, 0x7e, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0xfe, 0xe0, 0xe0, 0xe0, 0xe0, 0xe0, 0x00, + 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x7c, 0x40, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, // 0x70 + 0x3c, 0x7e, 0xff, 0xe7, 0xe7, 0xff, 0xff, 0x7f, 0x07, 0x07, 0x07, 0x07, 0x07, 0x00, + 0x00, 0x3c, 0x42, 0x42, 0x42, 0x42, 0x3e, 0x02, 0x02, 0x02, 0x03, 0x02, 0x00, 0x00, // 0x71 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x3f, 0x7f, 0xff, 0xf0, 0xe0, 0xe0, 0xe0, 0xe0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1e, 0x20, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00, // 0x72 + 0x00, 0x00, 0x00, 0x00, 0x7f, 0xff, 0xff, 0xfe, 0xff, 0x7f, 0xff, 0xff, 0xff, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x3e, 0x40, 0x40, 0x3c, 0x02, 0x02, 0x7e, 0x00, 0x00, // 0x73 + 0x00, 0xe0, 0xe0, 0xe0, 0xe0, 0xfc, 0xfc, 0xfc, 0xe0, 0xf0, 0xfe, 0xfe, 0x7e, 0x00, + 0x00, 0x00, 0x40, 0x40, 0x40, 0x40, 0x78, 0x40, 0x40, 0x40, 0x60, 0x3c, 0x00, 0x00, // 0x74 + 0x00, 0x00, 0x00, 0x00, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x42, 0x3c, 0x00, 0x00, // 0x75 + 0x00, 0x00, 0x00, 0x00, 0xe7, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0x3c, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x42, 0x42, 0x42, 0x42, 0x24, 0x18, 0x00, 0x00, // 0x76 + 0x00, 0x00, 0x00, 0x00, 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xe7, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x42, 0x42, 0x42, 0x5a, 0x66, 0x42, 0x00, 0x00, // 0x77 + 0x00, 0x00, 0x00, 0x00, 0xe7, 0xe7, 0xff, 0xff, 0x7e, 0xff, 0xe7, 0xe7, 0xe7, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x42, 0x42, 0x24, 0x18, 0x24, 0x42, 0x42, 0x00, 0x00, // 0x78 + 0xe7, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0x07, 0x07, 0x0f, 0xff, 0xfe, 0xfc, 0x00, + 0x00, 0x42, 0x42, 0x42, 0x42, 0x7c, 0x02, 0x02, 0x02, 0x02, 0x04, 0x78, 0x00, 0x00, // 0x79 + 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0x0e, 0x1c, 0x38, 0x70, 0xff, 0xff, 0xff, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x7e, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x7e, 0x00, 0x00, // 0x7a + 0x00, 0x3f, 0x7f, 0x7f, 0x70, 0xf0, 0xf0, 0xf0, 0xf0, 0x70, 0x7f, 0x7f, 0x3f, 0x00, + 0x00, 0x00, 0x1e, 0x20, 0x20, 0x20, 0x40, 0x40, 0x20, 0x20, 0x20, 0x1e, 0x00, 0x00, // 0x7b + 0x00, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x00, + 0x00, 0x00, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x10, 0x00, 0x00, // 0x7c + 0x00, 0xfc, 0xfe, 0xfe, 0x0e, 0x0f, 0x0f, 0x0f, 0x0f, 0x0e, 0xfe, 0xfe, 0xfc, 0x00, + 0x00, 0x00, 0x78, 0x04, 0x04, 0x04, 0x02, 0x02, 0x04, 0x04, 0x04, 0x78, 0x00, 0x00, // 0x7d + 0x00, 0x10, 0x3a, 0x7f, 0x2e, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x10, 0x2a, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x7e + 0x00, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x80 + 0x00, 0x00, 0x00, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x81 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x82 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x83 + 0x00, 0x18, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x84 + 0x00, 0x00, 0x00, 0x18, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x85 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x86 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x87 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3c, 0x3c, 0x00, 0x00, // 0x88 + 0x00, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x7e, 0x7e, 0x3c, 0x00, + 0x00, 0x00, 0x18, 0x08, 0x18, 0x08, 0x18, 0x08, 0x18, 0x08, 0x3c, 0x3c, 0x00, 0x00, // 0x89 + 0x00, 0xff, 0xff, 0xff, 0xff, 0x1f, 0x1f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x6e, 0x68, 0x08, 0x0e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x8a + 0x00, 0xff, 0xff, 0xff, 0xff, 0x1f, 0x1f, 0x1f, 0x1f, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x69, 0x6a, 0x0c, 0x0c, 0x0a, 0x09, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x8b + 0x00, 0xff, 0xff, 0xff, 0xff, 0x1f, 0x1f, 0x1c, 0x1c, 0x1c, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x6e, 0x68, 0x08, 0x0e, 0x08, 0x08, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x8c + 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0x7c, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x7e, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x00, 0x00, // 0x8d + 0x00, 0x00, 0x00, 0x3e, 0x7f, 0x7f, 0x7f, 0x7f, 0x7f, 0x3e, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x36, 0x36, 0x32, 0x3e, 0x3e, 0x00, 0x00, 0x00, 0x00, 0x00 // 0x8e +}; diff --git a/flight/targets/OSD/System/font_outlined8x8.c b/flight/targets/OSD/System/font_outlined8x8.c index e3f4ae115..78561fb48 100644 --- a/flight/targets/OSD/System/font_outlined8x8.c +++ b/flight/targets/OSD/System/font_outlined8x8.c @@ -1,182 +1,182 @@ -/** - * Super OSD, software revision 3 - * Copyright (C) 2010 Thomas Oldbury - * - * Please note the font data here is covered under Creative - * Commons licenses (version 3.0 BY-SA) and *not* the GPL. - */ - -// This data is generated by a Python script from -// the original font .pngs. - -// 0xff = indicates character not present -// any other byte contains the index of the character. -const char font_lookup_outlined8x8[256] = { - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0x00, 0x01, 0x02, 0x03, 0xff, 0xff, 0xff, 0x04, - 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, 0x0c, - 0x0d, 0x0e, 0x0f, 0x10, 0x11, 0x12, 0x13, 0x14, - 0x15, 0x16, 0x17, 0xff, 0x18, 0x19, 0x1a, 0x1b, - 0xff, 0x1c, 0x1d, 0x1e, 0x1f, 0x20, 0x21, 0x22, - 0x23, 0x24, 0x25, 0x26, 0x27, 0x28, 0x29, 0x2a, - 0x2b, 0x2c, 0x2d, 0x2e, 0x2f, 0x30, 0x31, 0x32, - 0x33, 0x34, 0x35, 0x36, 0x37, 0x38, 0xff, 0x39, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0x3a, 0x3b, 0x3c, 0x3d, 0x3e, 0x3f, 0x40, 0x41, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff -}; - -const char font_data_outlined8x8[] = { - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x20 - 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x00, - 0x00, 0x10, 0x10, 0x10, 0x00, 0x10, 0x00, 0x00, // 0x21 - 0x44, 0xee, 0xee, 0x44, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x44, 0x44, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x22 - 0x28, 0x7c, 0xfe, 0x7c, 0xfe, 0x7c, 0x28, 0x00, - 0x00, 0x28, 0x7c, 0x28, 0x7c, 0x28, 0x00, 0x00, // 0x23 - 0x10, 0x38, 0x38, 0x10, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x10, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x27 - 0x10, 0x38, 0x70, 0x70, 0x70, 0x38, 0x10, 0x00, - 0x00, 0x10, 0x20, 0x20, 0x20, 0x10, 0x00, 0x00, // 0x28 - 0x20, 0x70, 0x38, 0x38, 0x38, 0x70, 0x20, 0x00, - 0x00, 0x20, 0x10, 0x10, 0x10, 0x20, 0x00, 0x00, // 0x29 - 0x28, 0x7c, 0x38, 0x7c, 0x28, 0x00, 0x00, 0x00, - 0x00, 0x28, 0x10, 0x28, 0x00, 0x00, 0x00, 0x00, // 0x2a - 0x38, 0x38, 0xfe, 0xfe, 0xfe, 0x38, 0x38, 0x00, - 0x00, 0x10, 0x10, 0x7c, 0x10, 0x10, 0x00, 0x00, // 0x2b - 0x00, 0x00, 0x78, 0x78, 0x78, 0x78, 0x38, 0x00, - 0x00, 0x00, 0x00, 0x30, 0x30, 0x10, 0x00, 0x00, // 0x2c - 0x00, 0x00, 0xfe, 0xfe, 0xfe, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x7c, 0x00, 0x00, 0x00, 0x00, // 0x2d - 0x00, 0x00, 0x00, 0x78, 0x78, 0x78, 0x78, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x30, 0x30, 0x00, 0x00, // 0x2e - 0x04, 0x0e, 0x1c, 0x38, 0x70, 0xe0, 0x40, 0x00, - 0x00, 0x04, 0x08, 0x10, 0x20, 0x40, 0x00, 0x00, // 0x2f - 0x7c, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x7c, 0x00, - 0x00, 0x38, 0x44, 0x54, 0x44, 0x38, 0x00, 0x00, // 0x30 - 0x3c, 0x7c, 0xfc, 0xfc, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x18, 0x28, 0x48, 0x08, 0x7c, 0x00, 0x00, // 0x31 - 0xfc, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x78, 0x04, 0x78, 0x40, 0x7c, 0x00, 0x00, // 0x32 - 0xfe, 0xfe, 0xfe, 0x7e, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x7c, 0x04, 0x3c, 0x04, 0x7c, 0x00, 0x00, // 0x33 - 0xee, 0xee, 0xfe, 0xfe, 0x7e, 0x0e, 0x0e, 0x00, - 0x00, 0x44, 0x44, 0x3c, 0x04, 0x04, 0x00, 0x00, // 0x34 - 0xfc, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfc, 0x00, - 0x00, 0x7c, 0x40, 0x78, 0x04, 0x78, 0x00, 0x00, // 0x35 - 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x7c, 0x40, 0x7c, 0x44, 0x7c, 0x00, 0x00, // 0x36 - 0xfe, 0xfe, 0xfe, 0x38, 0x70, 0xe0, 0xc0, 0x00, - 0x00, 0x7c, 0x08, 0x10, 0x20, 0x40, 0x00, 0x00, // 0x37 - 0x7c, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x7c, 0x00, - 0x00, 0x38, 0x44, 0x7c, 0x44, 0x38, 0x00, 0x00, // 0x38 - 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x7e, 0x7e, 0x00, - 0x00, 0x7c, 0x44, 0x7c, 0x04, 0x3c, 0x00, 0x00, // 0x39 - 0x78, 0x78, 0x78, 0x78, 0x78, 0x78, 0x78, 0x00, - 0x00, 0x30, 0x30, 0x00, 0x30, 0x30, 0x00, 0x00, // 0x3a - 0x08, 0x1c, 0x38, 0x70, 0x38, 0x1c, 0x08, 0x00, - 0x00, 0x08, 0x10, 0x20, 0x10, 0x08, 0x00, 0x00, // 0x3c - 0xfe, 0xfe, 0xfe, 0x00, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x7c, 0x00, 0x00, 0x00, 0x7c, 0x00, 0x00, // 0x3d - 0x20, 0x70, 0x38, 0x1c, 0x38, 0x70, 0x20, 0x00, - 0x00, 0x20, 0x10, 0x08, 0x10, 0x20, 0x00, 0x00, // 0x3e - 0x7c, 0xfe, 0xfe, 0xfe, 0x3c, 0x38, 0x38, 0x00, - 0x00, 0x38, 0x44, 0x18, 0x00, 0x10, 0x00, 0x00, // 0x3f - 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xee, 0xee, 0x00, - 0x00, 0x7c, 0x44, 0x7c, 0x44, 0x44, 0x00, 0x00, // 0x41 - 0xfc, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfc, 0x00, - 0x00, 0x78, 0x44, 0x7c, 0x44, 0x78, 0x00, 0x00, // 0x42 - 0xfe, 0xfe, 0xfe, 0xe0, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x7c, 0x40, 0x40, 0x40, 0x7c, 0x00, 0x00, // 0x43 - 0xfc, 0xfe, 0xfe, 0xee, 0xfe, 0xfe, 0xfc, 0x00, - 0x00, 0x78, 0x44, 0x44, 0x44, 0x78, 0x00, 0x00, // 0x44 - 0xfe, 0xfe, 0xfe, 0xfc, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x7c, 0x40, 0x78, 0x40, 0x7c, 0x00, 0x00, // 0x45 - 0xfe, 0xfe, 0xfe, 0xfc, 0xfc, 0xe0, 0xe0, 0x00, - 0x00, 0x7c, 0x40, 0x78, 0x40, 0x40, 0x00, 0x00, // 0x46 - 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x7c, 0x40, 0x5c, 0x44, 0x7c, 0x00, 0x00, // 0x47 - 0xee, 0xee, 0xfe, 0xfe, 0xfe, 0xee, 0xee, 0x00, - 0x00, 0x44, 0x44, 0x7c, 0x44, 0x44, 0x00, 0x00, // 0x48 - 0xfe, 0xfe, 0xfe, 0x38, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x7c, 0x10, 0x10, 0x10, 0x7c, 0x00, 0x00, // 0x49 - 0xfe, 0xfe, 0xfe, 0x1c, 0xfc, 0xfc, 0xfc, 0x00, - 0x00, 0x7c, 0x08, 0x08, 0x08, 0x78, 0x00, 0x00, // 0x4a - 0xe6, 0xee, 0xfc, 0xf8, 0xfc, 0xee, 0xe6, 0x00, - 0x00, 0x44, 0x48, 0x70, 0x48, 0x44, 0x00, 0x00, // 0x4b - 0xe0, 0xe0, 0xe0, 0xe0, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x40, 0x40, 0x40, 0x40, 0x7c, 0x00, 0x00, // 0x4c - 0x6c, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xee, 0x00, - 0x00, 0x28, 0x54, 0x54, 0x54, 0x44, 0x00, 0x00, // 0x4d - 0xee, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xee, 0x00, - 0x00, 0x44, 0x64, 0x54, 0x4c, 0x44, 0x00, 0x00, // 0x4e - 0xfe, 0xfe, 0xfe, 0xee, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x7c, 0x44, 0x44, 0x44, 0x7c, 0x00, 0x00, // 0x4f - 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xe0, 0xe0, 0x00, - 0x00, 0x7c, 0x44, 0x7c, 0x40, 0x40, 0x00, 0x00, // 0x50 - 0xfe, 0xfe, 0xfe, 0xee, 0xfc, 0xfe, 0xf6, 0x00, - 0x00, 0x7c, 0x44, 0x44, 0x48, 0x74, 0x00, 0x00, // 0x51 - 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfc, 0xe8, 0x00, - 0x00, 0x7c, 0x44, 0x7c, 0x50, 0x48, 0x00, 0x00, // 0x52 - 0x7e, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfc, 0x00, - 0x00, 0x3c, 0x40, 0x7c, 0x04, 0x78, 0x00, 0x00, // 0x53 - 0xfe, 0xfe, 0xfe, 0x38, 0x38, 0x38, 0x38, 0x00, - 0x00, 0x7c, 0x10, 0x10, 0x10, 0x10, 0x00, 0x00, // 0x54 - 0xee, 0xee, 0xee, 0xee, 0xfe, 0xfe, 0x7c, 0x00, - 0x00, 0x44, 0x44, 0x44, 0x44, 0x38, 0x00, 0x00, // 0x55 - 0xee, 0xee, 0xee, 0xfe, 0xfe, 0x7c, 0x38, 0x00, - 0x00, 0x44, 0x44, 0x44, 0x28, 0x10, 0x00, 0x00, // 0x56 - 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x6c, 0x00, - 0x00, 0x54, 0x54, 0x54, 0x54, 0x28, 0x00, 0x00, // 0x57 - 0xee, 0xfe, 0xfe, 0x7c, 0xfe, 0xfe, 0xee, 0x00, - 0x00, 0x44, 0x28, 0x10, 0x28, 0x44, 0x00, 0x00, // 0x58 - 0xee, 0xfe, 0xfe, 0x7c, 0x38, 0x38, 0x38, 0x00, - 0x00, 0x44, 0x28, 0x10, 0x10, 0x10, 0x00, 0x00, // 0x59 - 0xfe, 0xfe, 0xfe, 0x78, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x7c, 0x08, 0x10, 0x20, 0x7c, 0x00, 0x00, // 0x5a - 0x38, 0x7c, 0x78, 0x70, 0x78, 0x7c, 0x38, 0x00, - 0x00, 0x38, 0x20, 0x20, 0x20, 0x38, 0x00, 0x00, // 0x5b - 0x40, 0xe0, 0x70, 0x38, 0x1c, 0x0e, 0x04, 0x00, - 0x00, 0x40, 0x20, 0x10, 0x08, 0x04, 0x00, 0x00, // 0x5c - 0x38, 0x7c, 0x3c, 0x1c, 0x3c, 0x7c, 0x38, 0x00, - 0x00, 0x38, 0x08, 0x08, 0x08, 0x38, 0x00, 0x00, // 0x5d - 0x00, 0x00, 0x00, 0x00, 0xfe, 0xfe, 0xfe, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x7c, 0x00, 0x00, // 0x5f - 0x10, 0x38, 0x7c, 0xfe, 0xfe, 0x38, 0x38, 0x00, - 0x00, 0x10, 0x38, 0x54, 0x10, 0x10, 0x00, 0x00, // 0x80 - 0x3e, 0x3e, 0x1e, 0x3e, 0x76, 0xe0, 0x40, 0x00, - 0x00, 0x1c, 0x0c, 0x14, 0x20, 0x40, 0x00, 0x00, // 0x81 - 0x10, 0x38, 0xfc, 0xfe, 0xfc, 0x38, 0x10, 0x00, - 0x00, 0x10, 0x08, 0x7c, 0x08, 0x10, 0x00, 0x00, // 0x82 - 0x40, 0xe0, 0x76, 0x3e, 0x1e, 0x3e, 0x3e, 0x00, - 0x00, 0x40, 0x20, 0x14, 0x0c, 0x1c, 0x00, 0x00, // 0x83 - 0x38, 0x38, 0xfe, 0xfe, 0x7c, 0x38, 0x10, 0x00, - 0x00, 0x10, 0x10, 0x54, 0x38, 0x10, 0x00, 0x00, // 0x84 - 0x04, 0x0e, 0xdc, 0xf8, 0xf0, 0xf8, 0xf8, 0x00, - 0x00, 0x04, 0x08, 0x50, 0x60, 0x70, 0x00, 0x00, // 0x85 - 0x10, 0x38, 0x7e, 0xfe, 0x7e, 0x38, 0x10, 0x00, - 0x00, 0x10, 0x20, 0x7c, 0x20, 0x10, 0x00, 0x00, // 0x86 - 0xf8, 0xf8, 0xf0, 0xf8, 0xdc, 0x0e, 0x04, 0x00, - 0x00, 0x70, 0x60, 0x50, 0x08, 0x04, 0x00, 0x00 // 0x87 -}; +/** + * Super OSD, software revision 3 + * Copyright (C) 2010 Thomas Oldbury + * + * Please note the font data here is covered under Creative + * Commons licenses (version 3.0 BY-SA) and *not* the GPL. + */ + +// This data is generated by a Python script from +// the original font .pngs. + +// 0xff = indicates character not present +// any other byte contains the index of the character. +const char font_lookup_outlined8x8[256] = { + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0x00, 0x01, 0x02, 0x03, 0xff, 0xff, 0xff, 0x04, + 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, 0x0c, + 0x0d, 0x0e, 0x0f, 0x10, 0x11, 0x12, 0x13, 0x14, + 0x15, 0x16, 0x17, 0xff, 0x18, 0x19, 0x1a, 0x1b, + 0xff, 0x1c, 0x1d, 0x1e, 0x1f, 0x20, 0x21, 0x22, + 0x23, 0x24, 0x25, 0x26, 0x27, 0x28, 0x29, 0x2a, + 0x2b, 0x2c, 0x2d, 0x2e, 0x2f, 0x30, 0x31, 0x32, + 0x33, 0x34, 0x35, 0x36, 0x37, 0x38, 0xff, 0x39, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0x3a, 0x3b, 0x3c, 0x3d, 0x3e, 0x3f, 0x40, 0x41, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, + 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff +}; + +const char font_data_outlined8x8[] = { + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x20 + 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x00, + 0x00, 0x10, 0x10, 0x10, 0x00, 0x10, 0x00, 0x00, // 0x21 + 0x44, 0xee, 0xee, 0x44, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x44, 0x44, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x22 + 0x28, 0x7c, 0xfe, 0x7c, 0xfe, 0x7c, 0x28, 0x00, + 0x00, 0x28, 0x7c, 0x28, 0x7c, 0x28, 0x00, 0x00, // 0x23 + 0x10, 0x38, 0x38, 0x10, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x10, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, // 0x27 + 0x10, 0x38, 0x70, 0x70, 0x70, 0x38, 0x10, 0x00, + 0x00, 0x10, 0x20, 0x20, 0x20, 0x10, 0x00, 0x00, // 0x28 + 0x20, 0x70, 0x38, 0x38, 0x38, 0x70, 0x20, 0x00, + 0x00, 0x20, 0x10, 0x10, 0x10, 0x20, 0x00, 0x00, // 0x29 + 0x28, 0x7c, 0x38, 0x7c, 0x28, 0x00, 0x00, 0x00, + 0x00, 0x28, 0x10, 0x28, 0x00, 0x00, 0x00, 0x00, // 0x2a + 0x38, 0x38, 0xfe, 0xfe, 0xfe, 0x38, 0x38, 0x00, + 0x00, 0x10, 0x10, 0x7c, 0x10, 0x10, 0x00, 0x00, // 0x2b + 0x00, 0x00, 0x78, 0x78, 0x78, 0x78, 0x38, 0x00, + 0x00, 0x00, 0x00, 0x30, 0x30, 0x10, 0x00, 0x00, // 0x2c + 0x00, 0x00, 0xfe, 0xfe, 0xfe, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x7c, 0x00, 0x00, 0x00, 0x00, // 0x2d + 0x00, 0x00, 0x00, 0x78, 0x78, 0x78, 0x78, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x30, 0x30, 0x00, 0x00, // 0x2e + 0x04, 0x0e, 0x1c, 0x38, 0x70, 0xe0, 0x40, 0x00, + 0x00, 0x04, 0x08, 0x10, 0x20, 0x40, 0x00, 0x00, // 0x2f + 0x7c, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x7c, 0x00, + 0x00, 0x38, 0x44, 0x54, 0x44, 0x38, 0x00, 0x00, // 0x30 + 0x3c, 0x7c, 0xfc, 0xfc, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x18, 0x28, 0x48, 0x08, 0x7c, 0x00, 0x00, // 0x31 + 0xfc, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x78, 0x04, 0x78, 0x40, 0x7c, 0x00, 0x00, // 0x32 + 0xfe, 0xfe, 0xfe, 0x7e, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x7c, 0x04, 0x3c, 0x04, 0x7c, 0x00, 0x00, // 0x33 + 0xee, 0xee, 0xfe, 0xfe, 0x7e, 0x0e, 0x0e, 0x00, + 0x00, 0x44, 0x44, 0x3c, 0x04, 0x04, 0x00, 0x00, // 0x34 + 0xfc, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfc, 0x00, + 0x00, 0x7c, 0x40, 0x78, 0x04, 0x78, 0x00, 0x00, // 0x35 + 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x7c, 0x40, 0x7c, 0x44, 0x7c, 0x00, 0x00, // 0x36 + 0xfe, 0xfe, 0xfe, 0x38, 0x70, 0xe0, 0xc0, 0x00, + 0x00, 0x7c, 0x08, 0x10, 0x20, 0x40, 0x00, 0x00, // 0x37 + 0x7c, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x7c, 0x00, + 0x00, 0x38, 0x44, 0x7c, 0x44, 0x38, 0x00, 0x00, // 0x38 + 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x7e, 0x7e, 0x00, + 0x00, 0x7c, 0x44, 0x7c, 0x04, 0x3c, 0x00, 0x00, // 0x39 + 0x78, 0x78, 0x78, 0x78, 0x78, 0x78, 0x78, 0x00, + 0x00, 0x30, 0x30, 0x00, 0x30, 0x30, 0x00, 0x00, // 0x3a + 0x08, 0x1c, 0x38, 0x70, 0x38, 0x1c, 0x08, 0x00, + 0x00, 0x08, 0x10, 0x20, 0x10, 0x08, 0x00, 0x00, // 0x3c + 0xfe, 0xfe, 0xfe, 0x00, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x7c, 0x00, 0x00, 0x00, 0x7c, 0x00, 0x00, // 0x3d + 0x20, 0x70, 0x38, 0x1c, 0x38, 0x70, 0x20, 0x00, + 0x00, 0x20, 0x10, 0x08, 0x10, 0x20, 0x00, 0x00, // 0x3e + 0x7c, 0xfe, 0xfe, 0xfe, 0x3c, 0x38, 0x38, 0x00, + 0x00, 0x38, 0x44, 0x18, 0x00, 0x10, 0x00, 0x00, // 0x3f + 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xee, 0xee, 0x00, + 0x00, 0x7c, 0x44, 0x7c, 0x44, 0x44, 0x00, 0x00, // 0x41 + 0xfc, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfc, 0x00, + 0x00, 0x78, 0x44, 0x7c, 0x44, 0x78, 0x00, 0x00, // 0x42 + 0xfe, 0xfe, 0xfe, 0xe0, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x7c, 0x40, 0x40, 0x40, 0x7c, 0x00, 0x00, // 0x43 + 0xfc, 0xfe, 0xfe, 0xee, 0xfe, 0xfe, 0xfc, 0x00, + 0x00, 0x78, 0x44, 0x44, 0x44, 0x78, 0x00, 0x00, // 0x44 + 0xfe, 0xfe, 0xfe, 0xfc, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x7c, 0x40, 0x78, 0x40, 0x7c, 0x00, 0x00, // 0x45 + 0xfe, 0xfe, 0xfe, 0xfc, 0xfc, 0xe0, 0xe0, 0x00, + 0x00, 0x7c, 0x40, 0x78, 0x40, 0x40, 0x00, 0x00, // 0x46 + 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x7c, 0x40, 0x5c, 0x44, 0x7c, 0x00, 0x00, // 0x47 + 0xee, 0xee, 0xfe, 0xfe, 0xfe, 0xee, 0xee, 0x00, + 0x00, 0x44, 0x44, 0x7c, 0x44, 0x44, 0x00, 0x00, // 0x48 + 0xfe, 0xfe, 0xfe, 0x38, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x7c, 0x10, 0x10, 0x10, 0x7c, 0x00, 0x00, // 0x49 + 0xfe, 0xfe, 0xfe, 0x1c, 0xfc, 0xfc, 0xfc, 0x00, + 0x00, 0x7c, 0x08, 0x08, 0x08, 0x78, 0x00, 0x00, // 0x4a + 0xe6, 0xee, 0xfc, 0xf8, 0xfc, 0xee, 0xe6, 0x00, + 0x00, 0x44, 0x48, 0x70, 0x48, 0x44, 0x00, 0x00, // 0x4b + 0xe0, 0xe0, 0xe0, 0xe0, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x40, 0x40, 0x40, 0x40, 0x7c, 0x00, 0x00, // 0x4c + 0x6c, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xee, 0x00, + 0x00, 0x28, 0x54, 0x54, 0x54, 0x44, 0x00, 0x00, // 0x4d + 0xee, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xee, 0x00, + 0x00, 0x44, 0x64, 0x54, 0x4c, 0x44, 0x00, 0x00, // 0x4e + 0xfe, 0xfe, 0xfe, 0xee, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x7c, 0x44, 0x44, 0x44, 0x7c, 0x00, 0x00, // 0x4f + 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xe0, 0xe0, 0x00, + 0x00, 0x7c, 0x44, 0x7c, 0x40, 0x40, 0x00, 0x00, // 0x50 + 0xfe, 0xfe, 0xfe, 0xee, 0xfc, 0xfe, 0xf6, 0x00, + 0x00, 0x7c, 0x44, 0x44, 0x48, 0x74, 0x00, 0x00, // 0x51 + 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfc, 0xe8, 0x00, + 0x00, 0x7c, 0x44, 0x7c, 0x50, 0x48, 0x00, 0x00, // 0x52 + 0x7e, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfc, 0x00, + 0x00, 0x3c, 0x40, 0x7c, 0x04, 0x78, 0x00, 0x00, // 0x53 + 0xfe, 0xfe, 0xfe, 0x38, 0x38, 0x38, 0x38, 0x00, + 0x00, 0x7c, 0x10, 0x10, 0x10, 0x10, 0x00, 0x00, // 0x54 + 0xee, 0xee, 0xee, 0xee, 0xfe, 0xfe, 0x7c, 0x00, + 0x00, 0x44, 0x44, 0x44, 0x44, 0x38, 0x00, 0x00, // 0x55 + 0xee, 0xee, 0xee, 0xfe, 0xfe, 0x7c, 0x38, 0x00, + 0x00, 0x44, 0x44, 0x44, 0x28, 0x10, 0x00, 0x00, // 0x56 + 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0xfe, 0x6c, 0x00, + 0x00, 0x54, 0x54, 0x54, 0x54, 0x28, 0x00, 0x00, // 0x57 + 0xee, 0xfe, 0xfe, 0x7c, 0xfe, 0xfe, 0xee, 0x00, + 0x00, 0x44, 0x28, 0x10, 0x28, 0x44, 0x00, 0x00, // 0x58 + 0xee, 0xfe, 0xfe, 0x7c, 0x38, 0x38, 0x38, 0x00, + 0x00, 0x44, 0x28, 0x10, 0x10, 0x10, 0x00, 0x00, // 0x59 + 0xfe, 0xfe, 0xfe, 0x78, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x7c, 0x08, 0x10, 0x20, 0x7c, 0x00, 0x00, // 0x5a + 0x38, 0x7c, 0x78, 0x70, 0x78, 0x7c, 0x38, 0x00, + 0x00, 0x38, 0x20, 0x20, 0x20, 0x38, 0x00, 0x00, // 0x5b + 0x40, 0xe0, 0x70, 0x38, 0x1c, 0x0e, 0x04, 0x00, + 0x00, 0x40, 0x20, 0x10, 0x08, 0x04, 0x00, 0x00, // 0x5c + 0x38, 0x7c, 0x3c, 0x1c, 0x3c, 0x7c, 0x38, 0x00, + 0x00, 0x38, 0x08, 0x08, 0x08, 0x38, 0x00, 0x00, // 0x5d + 0x00, 0x00, 0x00, 0x00, 0xfe, 0xfe, 0xfe, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x7c, 0x00, 0x00, // 0x5f + 0x10, 0x38, 0x7c, 0xfe, 0xfe, 0x38, 0x38, 0x00, + 0x00, 0x10, 0x38, 0x54, 0x10, 0x10, 0x00, 0x00, // 0x80 + 0x3e, 0x3e, 0x1e, 0x3e, 0x76, 0xe0, 0x40, 0x00, + 0x00, 0x1c, 0x0c, 0x14, 0x20, 0x40, 0x00, 0x00, // 0x81 + 0x10, 0x38, 0xfc, 0xfe, 0xfc, 0x38, 0x10, 0x00, + 0x00, 0x10, 0x08, 0x7c, 0x08, 0x10, 0x00, 0x00, // 0x82 + 0x40, 0xe0, 0x76, 0x3e, 0x1e, 0x3e, 0x3e, 0x00, + 0x00, 0x40, 0x20, 0x14, 0x0c, 0x1c, 0x00, 0x00, // 0x83 + 0x38, 0x38, 0xfe, 0xfe, 0x7c, 0x38, 0x10, 0x00, + 0x00, 0x10, 0x10, 0x54, 0x38, 0x10, 0x00, 0x00, // 0x84 + 0x04, 0x0e, 0xdc, 0xf8, 0xf0, 0xf8, 0xf8, 0x00, + 0x00, 0x04, 0x08, 0x50, 0x60, 0x70, 0x00, 0x00, // 0x85 + 0x10, 0x38, 0x7e, 0xfe, 0x7e, 0x38, 0x10, 0x00, + 0x00, 0x10, 0x20, 0x7c, 0x20, 0x10, 0x00, 0x00, // 0x86 + 0xf8, 0xf8, 0xf0, 0xf8, 0xdc, 0x0e, 0x04, 0x00, + 0x00, 0x70, 0x60, 0x50, 0x08, 0x04, 0x00, 0x00 // 0x87 +}; diff --git a/flight/targets/OSD/System/fonts.c b/flight/targets/OSD/System/fonts.c index 21cdc4179..8f1805bc9 100644 --- a/flight/targets/OSD/System/fonts.c +++ b/flight/targets/OSD/System/fonts.c @@ -1,35 +1,35 @@ -/** - * Super OSD, software revision 3 - * Copyright (C) 2010 Thomas Oldbury - * - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. - */ - -#include "fonts.h" - -// Font table. Add new fonts here. The table must end with a -1 for the id. -struct FontEntry fonts[NUM_FONTS + 1] = { - { 0, 8, 14, "Outlined8x14", - font_lookup_outlined8x14, - font_data_outlined8x14, - 0 }, - { 1, 8, 8, "Outlined8x8", - font_lookup_outlined8x8, - font_data_outlined8x8, - FONT_UPPERCASE_ONLY }, - { 2, 8, 10, "font8x10", 0, 0, 0 }, - { 3, 12, 18, "font12x18", 0, 0, 0 }, - { -1 } // ends font table -}; +/** + * Super OSD, software revision 3 + * Copyright (C) 2010 Thomas Oldbury + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. + */ + +#include "fonts.h" + +// Font table. Add new fonts here. The table must end with a -1 for the id. +struct FontEntry fonts[NUM_FONTS + 1] = { + { 0, 8, 14, "Outlined8x14", + font_lookup_outlined8x14, + font_data_outlined8x14, + 0 }, + { 1, 8, 8, "Outlined8x8", + font_lookup_outlined8x8, + font_data_outlined8x8, + FONT_UPPERCASE_ONLY }, + { 2, 8, 10, "font8x10", 0, 0, 0 }, + { 3, 12, 18, "font12x18", 0, 0, 0 }, + { -1 } // ends font table +}; diff --git a/flight/targets/OSD/System/inc/alarms.h b/flight/targets/OSD/System/inc/alarms.h index b62bc531b..0f0faeb8f 100644 --- a/flight/targets/OSD/System/inc/alarms.h +++ b/flight/targets/OSD/System/inc/alarms.h @@ -1,50 +1,50 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the alarm library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef ALARMS_H -#define ALARMS_H - -#include "systemalarms.h" -#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED - -int32_t AlarmsInitialize(void); -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); -void AlarmsDefaultAll(); -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); -void AlarmsClearAll(); -int32_t AlarmsHasWarnings(); -int32_t AlarmsHasErrors(); -int32_t AlarmsHasCritical(); - -#endif // ALARMS_H - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file alarms.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the alarm library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ALARMS_H +#define ALARMS_H + +#include "systemalarms.h" +#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED + +int32_t AlarmsInitialize(void); +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); +void AlarmsDefaultAll(); +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); +void AlarmsClearAll(); +int32_t AlarmsHasWarnings(); +int32_t AlarmsHasErrors(); +int32_t AlarmsHasCritical(); + +#endif // ALARMS_H + +/** + * @} + * @} + */ diff --git a/flight/targets/OSD/System/inc/font12x18.h b/flight/targets/OSD/System/inc/font12x18.h index fcd4482e3..ef0a45e27 100644 --- a/flight/targets/OSD/System/inc/font12x18.h +++ b/flight/targets/OSD/System/inc/font12x18.h @@ -1,9745 +1,9745 @@ -/* - * font12x18.h - * - * Created on: 3.1.2012 - * Author: Samba - */ - -#ifndef FONT12X18_H_ -#define FONT12X18_H_ - -static const uint16_t font_frame12x18[] = { - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x03C0, - 0x0660, - 0x0460, - 0x00C0, - 0x0180, - 0x0300, - 0x07E0, - 0x0000, - 0x0078, - 0x006C, - 0x0066, - 0x0066, - 0x0066, - 0x0066, - 0x006C, - 0x0078, - 0x0000, - - 0x0000, - 0x07C0, - 0x0060, - 0x0060, - 0x03C0, - 0x0060, - 0x0060, - 0x07C0, - 0x0000, - 0x0078, - 0x006C, - 0x0066, - 0x0066, - 0x0066, - 0x0066, - 0x006C, - 0x0078, - 0x0000, - - 0x0000, - 0x0001, - 0x0001, - 0x0001, - 0x0001, - 0x0001, - 0x0001, - 0x0001, - 0x0003, - 0x0007, - 0x001F, - 0x0038, - 0x0060, - 0x00C0, - 0x00C0, - 0x0180, - 0x0180, - 0x0181, - - 0x0000, - 0x0800, - 0x0800, - 0x0800, - 0x0800, - 0x0800, - 0x0800, - 0x0800, - 0x0C00, - 0x0E00, - 0x0F80, - 0x01C0, - 0x0060, - 0x0030, - 0x0030, - 0x0018, - 0x0018, - 0x0818, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x07FE, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0700, - 0x08C6, - 0x0826, - 0x0818, - 0x0C18, - 0x0C24, - 0x0642, - 0x0382, - 0x0381, - 0x03C1, - 0x00F1, - 0x00BE, - 0x0080, - 0x0080, - 0x01C0, - 0x03E0, - 0x07F0, - 0x0000, - - 0x0000, - 0x01F8, - 0x030C, - 0x0606, - 0x0402, - 0x0002, - 0x0002, - 0x0002, - 0x0002, - 0x0000, - 0x07FE, - 0x0606, - 0x06FE, - 0x06C6, - 0x06F6, - 0x0606, - 0x07FE, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x030C, - 0x0606, - 0x0402, - 0x0402, - 0x0000, - 0x07FE, - 0x0606, - 0x06FE, - 0x06C6, - 0x06F6, - 0x0606, - 0x07FE, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0208, - 0x030C, - 0x0390, - 0x03E0, - 0x03E0, - 0x01F0, - 0x00F8, - 0x007C, - 0x0080, - 0x0180, - 0x0280, - 0x0480, - 0x0000, - 0x07F8, - 0x0000, - - 0x0181, - 0x0180, - 0x0180, - 0x00C0, - 0x00C0, - 0x0060, - 0x0038, - 0x001F, - 0x0007, - 0x0003, - 0x0001, - 0x0001, - 0x0001, - 0x0001, - 0x0001, - 0x0001, - 0x0001, - 0x0000, - - 0x0818, - 0x0018, - 0x0018, - 0x0030, - 0x0030, - 0x0060, - 0x01C0, - 0x0F80, - 0x0E00, - 0x0C00, - 0x0800, - 0x0800, - 0x0800, - 0x0800, - 0x0800, - 0x0800, - 0x0800, - 0x0000, - - 0x07FE, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x00F0, - 0x0108, - 0x0108, - 0x0008, - 0x0008, - 0x0008, - 0x0000, - 0x01F8, - 0x030C, - 0x037C, - 0x030C, - 0x037C, - 0x037C, - 0x01F8, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x00F0, - 0x0108, - 0x0108, - 0x0108, - 0x0000, - 0x01F8, - 0x030C, - 0x037C, - 0x030C, - 0x037C, - 0x037C, - 0x01F8, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x00FF, - 0x01FF, - 0x0387, - 0x0387, - 0x0387, - 0x03FF, - 0x03FF, - 0x03FF, - 0x03FF, - 0x03FF, - 0x03FF, - 0x01FF, - 0x00FF, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FF8, - 0x0FFC, - 0x0FF2, - 0x0C32, - 0x081E, - 0x000E, - 0x000E, - 0x000E, - 0x000E, - 0x081E, - 0x0C3E, - 0x0FFC, - 0x0FF8, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FF8, - 0x0FFC, - 0x0FF2, - 0x0C32, - 0x081E, - 0x000E, - 0x03CE, - 0x07EE, - 0x07EE, - 0x07EE, - 0x07EE, - 0x0BDC, - 0x0C38, - 0x0000, - 0x0000, - 0x0000, - - 0x03F8, - 0x0030, - 0x0060, - 0x01C0, - 0x03F8, - 0x0000, - 0x03F8, - 0x0318, - 0x03F8, - 0x0000, - 0x03F8, - 0x0318, - 0x03F8, - 0x0000, - 0x03B8, - 0x0358, - 0x0318, - 0x0318, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0001, - 0x0003, - 0x0007, - 0x000F, - 0x001F, - 0x003F, - 0x003F, - 0x003F, - 0x003F, - 0x0030, - 0x0030, - 0x0030, - 0x0030, - 0x0030, - 0x0030, - 0x0000, - - 0x0000, - 0x0000, - 0x0800, - 0x0C00, - 0x0E00, - 0x0F00, - 0x0F80, - 0x00C0, - 0x00C0, - 0x00C0, - 0x0FC0, - 0x00C0, - 0x00C0, - 0x00C0, - 0x00C0, - 0x00C0, - 0x00C0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x00F0, - 0x01F8, - 0x03FC, - 0x0000, - 0x07FE, - 0x07E2, - 0x07E2, - 0x0422, - 0x043E, - 0x043E, - 0x043E, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0108, - 0x039C, - 0x018C, - 0x0084, - 0x0084, - 0x0108, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0198, - 0x0198, - 0x0198, - 0x07FE, - 0x07FE, - 0x0198, - 0x0198, - 0x07FE, - 0x07FE, - 0x0198, - 0x0198, - 0x0198, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x01F8, - 0x03FC, - 0x036C, - 0x0360, - 0x03F0, - 0x01F8, - 0x006C, - 0x036C, - 0x03FC, - 0x01F8, - 0x0060, - 0x0060, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x031C, - 0x0038, - 0x0070, - 0x00E0, - 0x01C0, - 0x038C, - 0x030C, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x00E0, - 0x0190, - 0x0110, - 0x0110, - 0x0120, - 0x00C0, - 0x00C0, - 0x0120, - 0x0214, - 0x0208, - 0x0214, - 0x01E2, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0020, - 0x0070, - 0x0030, - 0x0010, - 0x0010, - 0x0020, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x000C, - 0x0018, - 0x0030, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0030, - 0x0018, - 0x000C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0180, - 0x00C0, - 0x0060, - 0x0030, - 0x0030, - 0x0030, - 0x0030, - 0x0030, - 0x0030, - 0x0030, - 0x0060, - 0x00C0, - 0x0180, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0402, - 0x0606, - 0x030C, - 0x0198, - 0x00F0, - 0x07FE, - 0x00F0, - 0x0198, - 0x030C, - 0x0606, - 0x0402, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x01F8, - 0x01F8, - 0x0060, - 0x0060, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x00C0, - 0x0180, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x01F8, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0006, - 0x000E, - 0x001C, - 0x0038, - 0x0070, - 0x00E0, - 0x01C0, - 0x0380, - 0x0700, - 0x0600, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03FC, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x03FC, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x00E0, - 0x01E0, - 0x01E0, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x01F8, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03FC, - 0x030C, - 0x031C, - 0x0038, - 0x0070, - 0x00E0, - 0x01C0, - 0x03FC, - 0x03FC, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03F8, - 0x03FC, - 0x000C, - 0x000C, - 0x00F8, - 0x00F8, - 0x000C, - 0x000C, - 0x03FC, - 0x03F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0038, - 0x0078, - 0x00D8, - 0x0198, - 0x0318, - 0x03FC, - 0x03FC, - 0x0018, - 0x0018, - 0x0018, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x03FC, - 0x0300, - 0x03F8, - 0x03FC, - 0x000C, - 0x000C, - 0x030C, - 0x03FC, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03F8, - 0x0300, - 0x0300, - 0x03F8, - 0x03FC, - 0x030C, - 0x030C, - 0x03FC, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x03FC, - 0x000C, - 0x001C, - 0x0038, - 0x0070, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03FC, - 0x030C, - 0x030C, - 0x01F8, - 0x01F8, - 0x030C, - 0x030C, - 0x03FC, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03FC, - 0x030C, - 0x030C, - 0x03FC, - 0x01FC, - 0x000C, - 0x000C, - 0x03FC, - 0x03F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x00C0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0018, - 0x0030, - 0x0060, - 0x00C0, - 0x0180, - 0x0180, - 0x00C0, - 0x0060, - 0x0030, - 0x0018, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x01F8, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x01F8, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0300, - 0x0180, - 0x00C0, - 0x0060, - 0x0030, - 0x0030, - 0x0060, - 0x00C0, - 0x0180, - 0x0300, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03FC, - 0x070E, - 0x0606, - 0x0006, - 0x000E, - 0x001C, - 0x0038, - 0x0070, - 0x0060, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x00F0, - 0x0108, - 0x0204, - 0x04D2, - 0x0532, - 0x0512, - 0x0532, - 0x04D4, - 0x0408, - 0x0200, - 0x0104, - 0x00F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x00F0, - 0x01F8, - 0x03FC, - 0x039C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x03FC, - 0x03FC, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x03F0, - 0x03F8, - 0x031C, - 0x030C, - 0x030C, - 0x031C, - 0x03F8, - 0x03F8, - 0x031C, - 0x030C, - 0x030C, - 0x031C, - 0x03F8, - 0x03F0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x00F0, - 0x01F8, - 0x039C, - 0x030C, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x030C, - 0x039C, - 0x01F8, - 0x00F0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x03F0, - 0x03F8, - 0x031C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x031C, - 0x03F8, - 0x03F0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x03FC, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x03F0, - 0x03F0, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x03FC, - 0x03FC, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x03FC, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x03F0, - 0x03F0, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x01F0, - 0x03F8, - 0x039C, - 0x030C, - 0x030C, - 0x0300, - 0x0300, - 0x033C, - 0x033C, - 0x030C, - 0x030C, - 0x030C, - 0x03FC, - 0x01FC, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x03FC, - 0x03FC, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x01F8, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x01F8, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x00FC, - 0x00FC, - 0x0030, - 0x0030, - 0x0030, - 0x0030, - 0x0030, - 0x0330, - 0x0330, - 0x0330, - 0x0330, - 0x0330, - 0x03F0, - 0x01E0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0300, - 0x030C, - 0x031C, - 0x0338, - 0x0370, - 0x03E0, - 0x03C0, - 0x0380, - 0x03C0, - 0x03E0, - 0x0370, - 0x0338, - 0x031C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x03FC, - 0x03FC, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x039C, - 0x03FC, - 0x03FC, - 0x036C, - 0x036C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x038C, - 0x038C, - 0x03CC, - 0x03EC, - 0x037C, - 0x033C, - 0x031C, - 0x031C, - 0x030C, - 0x030C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x00F0, - 0x01F8, - 0x039C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x039C, - 0x01F8, - 0x00F0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x03F0, - 0x03F8, - 0x031C, - 0x030C, - 0x030C, - 0x031C, - 0x03F8, - 0x03F0, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x00F0, - 0x01F8, - 0x039C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x036C, - 0x037C, - 0x03B8, - 0x01FC, - 0x00EC, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x03F0, - 0x03F8, - 0x031C, - 0x030C, - 0x030C, - 0x031C, - 0x03F8, - 0x03E0, - 0x03E0, - 0x0370, - 0x0338, - 0x031C, - 0x030C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x00F8, - 0x01FC, - 0x038C, - 0x0300, - 0x0300, - 0x0380, - 0x01F0, - 0x00F8, - 0x001C, - 0x000C, - 0x000C, - 0x031C, - 0x03F8, - 0x01F0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x03FC, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x039C, - 0x01F8, - 0x00F0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x039C, - 0x0198, - 0x01F8, - 0x00F0, - 0x0060, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x036C, - 0x036C, - 0x036C, - 0x036C, - 0x036C, - 0x036C, - 0x03FC, - 0x01F8, - 0x0198, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x0198, - 0x00F0, - 0x0060, - 0x0060, - 0x00F0, - 0x0198, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x039C, - 0x01F8, - 0x00F0, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x03FC, - 0x000C, - 0x000C, - 0x001C, - 0x0038, - 0x0070, - 0x00E0, - 0x01C0, - 0x0380, - 0x0300, - 0x0300, - 0x03FC, - 0x03FC, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0078, - 0x0078, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0078, - 0x0078, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0600, - 0x0700, - 0x0380, - 0x01C0, - 0x00E0, - 0x0070, - 0x0038, - 0x001C, - 0x000E, - 0x0006, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x01E0, - 0x01E0, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x01E0, - 0x01E0, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x00F0, - 0x0198, - 0x0108, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x07FE, - 0x07FE, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0300, - 0x0180, - 0x00C0, - 0x0060, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x00F0, - 0x01F8, - 0x039C, - 0x030C, - 0x030C, - 0x03FC, - 0x03FC, - 0x030C, - 0x030C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03F8, - 0x03FC, - 0x030C, - 0x030C, - 0x03F8, - 0x03F8, - 0x030C, - 0x030C, - 0x03FC, - 0x03F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03FC, - 0x030C, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x030C, - 0x03FC, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03F0, - 0x03F8, - 0x031C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x031C, - 0x03F8, - 0x03F0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x03FC, - 0x0300, - 0x0300, - 0x03F0, - 0x03F0, - 0x0300, - 0x0300, - 0x03FC, - 0x03FC, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x03FC, - 0x0300, - 0x0300, - 0x03F8, - 0x03F8, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03FC, - 0x038C, - 0x0300, - 0x033C, - 0x033C, - 0x030C, - 0x038C, - 0x03FC, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x03FC, - 0x03FC, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x00F0, - 0x00F0, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x00F0, - 0x00F0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x007C, - 0x007C, - 0x0018, - 0x0018, - 0x0018, - 0x0018, - 0x0018, - 0x0198, - 0x01F8, - 0x00F0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x031C, - 0x0338, - 0x0370, - 0x03E0, - 0x03E0, - 0x03F0, - 0x0338, - 0x031C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x03FC, - 0x03FC, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x039C, - 0x03FC, - 0x036C, - 0x036C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x038C, - 0x03CC, - 0x03EC, - 0x037C, - 0x033C, - 0x031C, - 0x030C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03FC, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x03FC, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03F8, - 0x03FC, - 0x030C, - 0x030C, - 0x03FC, - 0x03F8, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03FC, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x033C, - 0x0338, - 0x03FC, - 0x01EC, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03F8, - 0x03FC, - 0x030C, - 0x030C, - 0x03F8, - 0x03E0, - 0x0370, - 0x0338, - 0x031C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x03FC, - 0x030C, - 0x0300, - 0x03F8, - 0x01FC, - 0x000C, - 0x030C, - 0x03FC, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x03FC, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x03FC, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x039C, - 0x01F8, - 0x00F0, - 0x0060, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x036C, - 0x036C, - 0x03FC, - 0x01F8, - 0x0198, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x039C, - 0x01F8, - 0x00F0, - 0x0060, - 0x0060, - 0x00F0, - 0x01F8, - 0x039C, - 0x030C, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x039C, - 0x01F8, - 0x00F0, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x03FC, - 0x001C, - 0x0038, - 0x0070, - 0x00E0, - 0x01C0, - 0x0380, - 0x03FC, - 0x03FC, - 0x0000, - - 0x0000, - 0x0000, - 0x0038, - 0x0038, - 0x0078, - 0x0060, - 0x0060, - 0x0060, - 0x00C0, - 0x00C0, - 0x0060, - 0x0060, - 0x0060, - 0x0078, - 0x0038, - 0x0038, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x01C0, - 0x01E0, - 0x01E0, - 0x0060, - 0x0060, - 0x0060, - 0x0030, - 0x0030, - 0x0060, - 0x0060, - 0x0060, - 0x01E0, - 0x01E0, - 0x01C0, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x00C2, - 0x01E6, - 0x033C, - 0x0618, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0280, - 0x02C0, - 0x02E0, - 0x02F0, - 0x02F8, - 0x02F0, - 0x02E0, - 0x02C0, - 0x0280, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0700, - 0x0000, - - 0x0000, - 0x0660, - 0x06C0, - 0x0700, - 0x06C0, - 0x0660, - 0x0000, - 0x06BE, - 0x0688, - 0x0588, - 0x0588, - 0x0000, - 0x0066, - 0x0066, - 0x007E, - 0x0066, - 0x0066, - 0x0000, - - 0x0000, - 0x0660, - 0x06C0, - 0x0700, - 0x06C0, - 0x0660, - 0x0000, - 0x01DC, - 0x01AC, - 0x01AC, - 0x018C, - 0x0000, - 0x0066, - 0x0066, - 0x007E, - 0x0066, - 0x0066, - 0x0000, - - 0x0000, - 0x07F0, - 0x06B0, - 0x06B0, - 0x0630, - 0x0000, - 0x0078, - 0x0048, - 0x00FC, - 0x00CC, - 0x00CC, - 0x0000, - 0x0066, - 0x0066, - 0x007E, - 0x0066, - 0x0066, - 0x0000, - - 0x0000, - 0x0600, - 0x0600, - 0x0600, - 0x07E0, - 0x07E0, - 0x0000, - 0x00F8, - 0x018C, - 0x01FC, - 0x018C, - 0x0000, - 0x007E, - 0x007E, - 0x0018, - 0x0018, - 0x0018, - 0x0000, - - 0x0000, - 0x0600, - 0x0600, - 0x0600, - 0x07E0, - 0x07E0, - 0x0000, - 0x01F8, - 0x039C, - 0x039C, - 0x01F8, - 0x0000, - 0x00E6, - 0x00F6, - 0x00FE, - 0x00DE, - 0x00CE, - 0x0000, - - 0x0000, - 0x03E0, - 0x0630, - 0x07F0, - 0x0630, - 0x0000, - 0x0180, - 0x0180, - 0x0180, - 0x01F8, - 0x01F8, - 0x0000, - 0x007E, - 0x007E, - 0x0018, - 0x0018, - 0x0018, - 0x0000, - - 0x0000, - 0x0660, - 0x0660, - 0x03C0, - 0x0180, - 0x0000, - 0x01F8, - 0x0180, - 0x01F0, - 0x0180, - 0x01F8, - 0x0000, - 0x0030, - 0x0030, - 0x0030, - 0x003E, - 0x003E, - 0x0000, - - 0x0000, - 0x07E0, - 0x07E0, - 0x0180, - 0x0180, - 0x0180, - 0x0000, - 0x00D8, - 0x00F8, - 0x00D8, - 0x00D8, - 0x0000, - 0x003C, - 0x0022, - 0x0026, - 0x003C, - 0x0036, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0660, - 0x07E0, - 0x05A0, - 0x0420, - 0x0000, - 0x07E0, - 0x0000, - 0x07E0, - 0x0400, - 0x07E0, - 0x0020, - 0x07E0, - 0x0000, - - 0x0000, - 0x03E0, - 0x0630, - 0x07F0, - 0x0630, - 0x0000, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0000, - 0x007E, - 0x0046, - 0x0078, - 0x006C, - 0x0066, - 0x0000, - - 0x0000, - 0x0770, - 0x06B0, - 0x06B0, - 0x06B0, - 0x06B0, - 0x0000, - 0x00F8, - 0x018C, - 0x01FC, - 0x018C, - 0x0000, - 0x0066, - 0x0066, - 0x0066, - 0x003C, - 0x0018, - 0x0000, - - 0x0000, - 0x0200, - 0x020C, - 0x0212, - 0x0012, - 0x0712, - 0x0012, - 0x070C, - 0x0700, - 0x0700, - 0x0712, - 0x0712, - 0x0014, - 0x0218, - 0x0214, - 0x0212, - 0x0212, - 0x0200, - - 0x0000, - 0x0210, - 0x0210, - 0x0210, - 0x001E, - 0x0700, - 0x000C, - 0x0712, - 0x0712, - 0x0712, - 0x070C, - 0x0700, - 0x001E, - 0x0210, - 0x021E, - 0x0202, - 0x021E, - 0x0200, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0618, - 0x0738, - 0x07F8, - 0x06D8, - 0x06D8, - 0x0618, - 0x0618, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0630, - 0x0630, - 0x0630, - 0x0630, - 0x0360, - 0x03E0, - 0x01C0, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01C0, - 0x03E0, - 0x0220, - 0x0630, - 0x07F0, - 0x0630, - 0x0630, - 0x0000, - - 0x0000, - 0x0000, - 0x0003, - 0x001F, - 0x000F, - 0x000F, - 0x000F, - 0x000F, - 0x000F, - 0x000F, - 0x000F, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0800, - 0x0F00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0007, - 0x0003, - 0x0007, - 0x000F, - 0x001F, - 0x003F, - 0x003F, - 0x0007, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0E00, - 0x0F00, - 0x0F80, - 0x0E00, - 0x0E00, - 0x0C00, - 0x0C00, - 0x0800, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0001, - 0x0003, - 0x001F, - 0x007F, - 0x00FF, - 0x007F, - 0x001C, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0E60, - 0x0800, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0001, - 0x003F, - 0x00FF, - 0x007F, - 0x0078, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0700, - 0x0FF0, - 0x0FE0, - 0x0FE0, - 0x08C0, - 0x0040, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x007F, - 0x007F, - 0x007F, - 0x007F, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0300, - 0x0FC0, - 0x0FF8, - 0x0FF0, - 0x0FE0, - 0x0180, - 0x0100, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0010, - 0x003F, - 0x007F, - 0x001F, - 0x0001, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0880, - 0x0FE0, - 0x0FF0, - 0x0FF8, - 0x07F0, - 0x0700, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x000C, - 0x001F, - 0x003F, - 0x001F, - 0x0007, - 0x0001, - 0x0001, - 0x0003, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0C00, - 0x0FC0, - 0x0FE0, - 0x0FE0, - 0x0FF0, - 0x0FF0, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x001F, - 0x000F, - 0x0007, - 0x0007, - 0x0003, - 0x0007, - 0x000F, - 0x0001, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0800, - 0x0C00, - 0x0E00, - 0x0F60, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0180, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0007, - 0x0007, - 0x0007, - 0x0007, - 0x000F, - 0x003F, - 0x000F, - 0x0007, - 0x0003, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0F00, - 0x0FC0, - 0x0E00, - 0x0C00, - 0x0800, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0001, - 0x0003, - 0x0007, - 0x006F, - 0x003F, - 0x003F, - 0x003F, - 0x003F, - 0x0018, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0F80, - 0x0F00, - 0x0E00, - 0x0E00, - 0x0C00, - 0x0E00, - 0x0F00, - 0x0800, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0003, - 0x003F, - 0x007F, - 0x007F, - 0x00FF, - 0x00FF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0300, - 0x0F80, - 0x0FC0, - 0x0F80, - 0x0E00, - 0x0800, - 0x0800, - 0x0C00, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0011, - 0x007F, - 0x00FF, - 0x01FF, - 0x00FE, - 0x000E, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0080, - 0x0FC0, - 0x0FE0, - 0x0F80, - 0x0800, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x000C, - 0x003F, - 0x01FF, - 0x00FF, - 0x007F, - 0x0018, - 0x0008, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FE0, - 0x0FE0, - 0x0FE0, - 0x0FE0, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x000E, - 0x00FF, - 0x007F, - 0x007F, - 0x0031, - 0x0020, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0800, - 0x0FC0, - 0x0FF0, - 0x0FE0, - 0x01E0, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x003F, - 0x003F, - 0x003F, - 0x0067, - 0x0001, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0800, - 0x0C00, - 0x0F80, - 0x0FE0, - 0x0FF0, - 0x0FE0, - 0x0380, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0007, - 0x000F, - 0x001F, - 0x0007, - 0x0007, - 0x0003, - 0x0003, - 0x0001, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0E00, - 0x0C00, - 0x0E00, - 0x0F00, - 0x0F80, - 0x0FC0, - 0x0FC0, - 0x0E00, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0180, - 0x0240, - 0x0240, - 0x0180, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0060, - 0x00F0, - 0x01F8, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x01F8, - 0x00F0, - 0x0060, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0100, - 0x0300, - 0x07C0, - 0x07F0, - 0x0330, - 0x0118, - 0x0018, - 0x0018, - 0x0118, - 0x0330, - 0x07F0, - 0x07C0, - 0x0300, - 0x0100, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x00F0, - 0x07FE, - 0x0606, - 0x0462, - 0x0462, - 0x0462, - 0x0462, - 0x0462, - 0x0462, - 0x0462, - 0x0402, - 0x0462, - 0x0462, - 0x0402, - 0x0606, - 0x07FE, - 0x0000, - - 0x0000, - 0x00F0, - 0x07FE, - 0x070E, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x07FE, - 0x07FE, - 0x0000, - - 0x0000, - 0x00F0, - 0x07FE, - 0x070E, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x0000, - - 0x0000, - 0x00F0, - 0x07FE, - 0x070E, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x0000, - - 0x0000, - 0x00F0, - 0x07FE, - 0x070E, - 0x0606, - 0x0606, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x0000, - - 0x0000, - 0x00F0, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x07FE, - 0x0000, - - 0x0000, - 0x0000, - 0x03FF, - 0x03FF, - 0x0300, - 0x0300, - 0x033C, - 0x033C, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - 0x0300, - - 0x0000, - 0x0000, - 0x0FFF, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x00F0, - 0x01F8, - 0x030C, - 0x0606, - 0x0606, - 0x0606, - 0x0606, - 0x030C, - 0x01F8, - 0x00F0, - - 0x0000, - 0x0000, - 0x0F00, - 0x0F00, - 0x033F, - 0x033F, - 0x0333, - 0x0333, - 0x0333, - 0x0333, - 0x03F3, - 0x03F3, - 0x0303, - 0x0303, - 0x0303, - 0x0303, - 0x0303, - 0x0303, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x000F, - 0x000F, - 0x03FC, - 0x03FC, - 0x030F, - 0x030F, - 0x0300, - 0x0300, - 0x0F00, - 0x0F00, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0F00, - 0x0F00, - 0x0000, - 0x0000, - 0x0F00, - 0x0F00, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0060, - 0x0060, - 0x00F0, - 0x00F0, - 0x01F8, - 0x01F8, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0040, - 0x0040, - 0x0E4F, - 0x0040, - 0x0040, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x038C, - 0x038C, - 0x03CC, - 0x036C, - 0x0B6D, - 0x033C, - 0x031C, - 0x030C, - 0x030C, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x00F0, - 0x01F8, - 0x0188, - 0x0180, - 0x01F0, - 0x0EFB, - 0x0018, - 0x0118, - 0x01F8, - 0x00F0, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x01F8, - 0x01F8, - 0x0180, - 0x0180, - 0x01E0, - 0x0DEF, - 0x0180, - 0x0180, - 0x01F8, - 0x01F8, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x030C, - 0x030C, - 0x030C, - 0x030C, - 0x036C, - 0x0D6B, - 0x01F8, - 0x0198, - 0x0198, - 0x0198, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0E0F, - 0x0318, - 0x01B0, - 0x00E0, - 0x0040, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0070, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x007F, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x00E0, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FE0, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0300, - 0x0300, - 0x03FF, - 0x03FF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FFF, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0300, - 0x0300, - 0x0F00, - 0x0F00, - 0x0000, - 0x0000, - 0x0066, - 0x0066, - 0x0066, - 0x0066, - 0x0066, - 0x007E, - 0x003C, - 0x0018, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0180, - 0x0380, - 0x0380, - 0x0180, - 0x0180, - 0x0180, - 0x03C6, - 0x03C6, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03C0, - 0x0660, - 0x0660, - 0x03E0, - 0x0060, - 0x0260, - 0x07E0, - 0x03C0, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x01F8, - 0x01F8, - 0x00F0, - 0x00F0, - 0x0060, - 0x0060, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - 0x0004, - - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - 0x0200, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0004, - 0x0004, - 0x0007, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0007, - 0x0004, - 0x0004, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0E00, - 0x0200, - 0x0200, - - 0x0200, - 0x0200, - 0x0E00, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0070, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0010, - 0x0018, - 0x001C, - 0x001E, - 0x001C, - 0x0018, - 0x0010, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x00E0, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0080, - 0x0180, - 0x0380, - 0x0780, - 0x0380, - 0x0180, - 0x0080, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0030, - 0x0030, - 0x0030, - 0x0030, - 0x003F, - 0x003F, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x003F, - 0x003F, - 0x0030, - 0x0030, - 0x0030, - 0x0030, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FC0, - 0x0FC0, - 0x00C0, - 0x00C0, - 0x00C0, - 0x00C0, - - 0x00C0, - 0x00C0, - 0x00C0, - 0x00C0, - 0x0FC0, - 0x0FC0, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0660, - 0x07E0, - 0x05A0, - 0x0420, - 0x0004, - 0x03C4, - 0x0664, - 0x0660, - 0x0660, - 0x03C4, - 0x0004, - 0x07C4, - 0x0660, - 0x0660, - 0x0660, - 0x07C0, - 0x0000, - - 0x0000, - 0x0040, - 0x0040, - 0x0040, - 0x07FC, - 0x0444, - 0x0550, - 0x0446, - 0x07F4, - 0x0604, - 0x0014, - 0x0054, - 0x0054, - 0x0154, - 0x0154, - 0x0554, - 0x0556, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0660, - 0x0660, - 0x0660, - 0x03C0, - 0x0186, - 0x0004, - 0x0004, - 0x03C4, - 0x0664, - 0x0664, - 0x07E4, - 0x0664, - 0x0004, - 0x0006, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0660, - 0x0660, - 0x0660, - 0x03C0, - 0x0186, - 0x0004, - 0x0004, - 0x07C4, - 0x0664, - 0x0784, - 0x0664, - 0x07C4, - 0x0004, - 0x0006, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x03C0, - 0x0600, - 0x0600, - 0x0600, - 0x03C6, - 0x0004, - 0x0004, - 0x03C4, - 0x0664, - 0x0664, - 0x07E4, - 0x0664, - 0x0004, - 0x0006, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x03C0, - 0x0600, - 0x0600, - 0x0600, - 0x03C6, - 0x0004, - 0x0004, - 0x07C4, - 0x0664, - 0x0784, - 0x0664, - 0x07C4, - 0x0004, - 0x0006, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0660, - 0x07E0, - 0x05A0, - 0x0420, - 0x0004, - 0x03C4, - 0x0664, - 0x0660, - 0x07E0, - 0x0664, - 0x0004, - 0x0664, - 0x0660, - 0x0660, - 0x03C0, - 0x0180, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x070E, - 0x0606, - 0x0402, - 0x0402, - 0x0402, - 0x0402, - 0x0606, - 0x070E, - 0x03FC, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x03FC, - 0x070E, - 0x0606, - 0x04F2, - 0x04F2, - 0x04F2, - 0x04F2, - 0x0606, - 0x070E, - 0x03FC, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0003, - 0x0002, - 0x0002, - 0x0002, - 0x0002, - 0x0002, - 0x0002, - 0x0002, - 0x0002, - 0x0002, - 0x0002, - 0x0002, - 0x0002, - 0x0003, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0FF8, - 0x0FF8, - 0x0FF8, - 0x0FF8, - 0x0FF8, - 0x0FF8, - 0x0FF8, - 0x0FF8, - 0x0FF8, - 0x0FF8, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0FC0, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0E00, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0FFF, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0C00, - 0x0400, - 0x0400, - 0x0400, - 0x0400, - 0x0400, - 0x0400, - 0x0400, - 0x0400, - 0x0400, - 0x0400, - 0x0400, - 0x0400, - 0x0C00, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0FFE, - 0x0402, - 0x050A, - 0x058A, - 0x05CA, - 0x05EA, - 0x05FA, - 0x05FA, - 0x05EA, - 0x05CA, - 0x058A, - 0x050A, - 0x0402, - 0x0FFE, - 0x0000, - 0x0000, - - 0x0000, - 0x0001, - 0x0001, - 0x0030, - 0x0033, - 0x0007, - 0x000C, - 0x0018, - 0x00D8, - 0x00D8, - 0x0018, - 0x000C, - 0x0007, - 0x0033, - 0x0030, - 0x0001, - 0x0001, - 0x0000, - - 0x0000, - 0x0800, - 0x0800, - 0x00C0, - 0x0CC0, - 0x0E00, - 0x0300, - 0x0180, - 0x01B0, - 0x01B0, - 0x0180, - 0x0300, - 0x0E00, - 0x0CC0, - 0x00C0, - 0x0800, - 0x0800, - 0x0000, - - 0x0000, - 0x0000, - 0x0003, - 0x000F, - 0x001C, - 0x0030, - 0x0030, - 0x0060, - 0x0060, - 0x0060, - 0x0060, - 0x0030, - 0x0030, - 0x001C, - 0x000F, - 0x0003, - 0x0000, - 0x0000, - - 0x0000, - 0x0000, - 0x0C00, - 0x0F00, - 0x0F80, - 0x0FC0, - 0x0FC0, - 0x0FE0, - 0x0FE0, - 0x0FE0, - 0x0FE0, - 0x0FC0, - 0x0FC0, - 0x0F80, - 0x0F00, - 0x0C00, - 0x0000, - 0x0000, - - 0x0000, - 0x0006, - 0x000E, - 0x001A, - 0x0032, - 0x07E2, - 0x04C2, - 0x04C2, - 0x04C2, - 0x04C2, - 0x04C2, - 0x07E2, - 0x0032, - 0x001A, - 0x000E, - 0x0006, - 0x0000, - 0x0000, - - 0x0000, - 0x0060, - 0x0030, - 0x0010, - 0x0190, - 0x0098, - 0x04C8, - 0x0648, - 0x0248, - 0x0648, - 0x04C8, - 0x0098, - 0x0190, - 0x0010, - 0x0030, - 0x0060, - 0x0000, - 0x0000, - - 0x0000, - 0x07FE, - 0x03FC, - 0x030C, - 0x030C, - 0x030C, - 0x0198, - 0x00F0, - 0x0060, - 0x0060, - 0x00F0, - 0x0198, - 0x030C, - 0x030C, - 0x030C, - 0x03FC, - 0x07FE, - 0x0000, - - 0x0000, - 0x0000, - 0x0100, - 0x0180, - 0x01C0, - 0x01E0, - 0x01F0, - 0x01F8, - 0x01FC, - 0x01FE, - 0x01F0, - 0x01F0, - 0x0138, - 0x0038, - 0x001C, - 0x001C, - 0x0008, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0322, - 0x04B6, - 0x04AA, - 0x04AA, - 0x07A2, - 0x04A2, - 0x04A2, - 0x04A2, - 0x04A2, - 0x0000, - - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0000, - 0x0722, - 0x04B6, - 0x04AA, - 0x04AA, - 0x0722, - 0x0422, - 0x0422, - 0x0422, - 0x0422, - 0x0000, - - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - 0x0FFF, - -}; - -static const uint16_t font_mask12x18[] = { -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FFF, -0x0FFF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, - -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FFF, -0x0FFF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, - -0x0001, -0x0003, -0x0003, -0x0003, -0x0003, -0x0003, -0x0003, -0x0003, -0x0007, -0x001F, -0x003F, -0x007F, -0x00F8, -0x01E0, -0x01E0, -0x03C0, -0x03C1, -0x03C3, - -0x0800, -0x0C00, -0x0C00, -0x0C00, -0x0C00, -0x0C00, -0x0C00, -0x0C00, -0x0E00, -0x0F80, -0x0FC0, -0x0FE0, -0x01F0, -0x0078, -0x0078, -0x003C, -0x083C, -0x0C3C, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0FC6, -0x0FEF, -0x0FFF, -0x0FFE, -0x0FFC, -0x0FFE, -0x0FFF, -0x07FF, -0x07FF, -0x07FF, -0x03FF, -0x01FF, -0x01FE, -0x01C0, -0x03E0, -0x07F0, -0x0FFC, -0x0FFE, - -0x01F8, -0x03FC, -0x07FE, -0x0F0F, -0x0E07, -0x0407, -0x0007, -0x0007, -0x0007, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, - -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x0F0F, -0x0E07, -0x0E07, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, - -0x0000, -0x0000, -0x0208, -0x071C, -0x079E, -0x07FC, -0x07F0, -0x07F0, -0x03F8, -0x01FC, -0x00FE, -0x01FC, -0x03C0, -0x07C0, -0x0FC0, -0x0FF8, -0x0FFC, -0x0FFC, - -0x03C3, -0x03C1, -0x03C0, -0x01E0, -0x01E0, -0x00F8, -0x007F, -0x003F, -0x001F, -0x0007, -0x0003, -0x0003, -0x0003, -0x0003, -0x0003, -0x0003, -0x0003, -0x0001, - -0x0C3C, -0x083C, -0x003C, -0x0078, -0x0078, -0x01F0, -0x0FE0, -0x0FC0, -0x0F80, -0x0E00, -0x0C00, -0x0C00, -0x0C00, -0x0C00, -0x0C00, -0x0C00, -0x0C00, -0x0800, - -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x00F0, -0x03FC, -0x03FC, -0x039C, -0x011C, -0x001C, -0x001C, -0x01FC, -0x03FC, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x03FC, -0x0000, - -0x0000, -0x0000, -0x0000, -0x00F0, -0x03FC, -0x03FC, -0x039C, -0x039C, -0x03FC, -0x03FC, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x03FC, -0x0000, - -0x0000, -0x01FF, -0x03FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x03FF, -0x01FF, -0x0000, -0x0000, - -0x0000, -0x0FFC, -0x0FFE, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFE, -0x0FFC, -0x0000, -0x0000, - -0x0000, -0x0FFC, -0x0FFE, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFE, -0x0FFC, -0x0000, -0x0000, - -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0001, -0x0003, -0x0007, -0x000F, -0x001F, -0x003F, -0x007F, -0x00FF, -0x01FF, -0x037F, -0x027F, -0x007F, -0x007F, -0x007F, -0x007F, -0x007F, -0x007F, -0x007F, - -0x0800, -0x0C00, -0x0E00, -0x0F00, -0x0F80, -0x0FC0, -0x0FE0, -0x0FF0, -0x0FF8, -0x0FEC, -0x0FE4, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, - -0x0000, -0x0000, -0x0060, -0x01F8, -0x03FC, -0x07FE, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0060, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x0060, -0x0060, -0x00F0, -0x00F0, -0x0060, -0x0000, - -0x0000, -0x0108, -0x039C, -0x07FE, -0x03DE, -0x01CE, -0x01CE, -0x039C, -0x0108, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0198, -0x03FC, -0x03FC, -0x07FE, -0x0FFF, -0x0FFF, -0x07FE, -0x07FE, -0x0FFF, -0x0FFF, -0x07FE, -0x03FC, -0x03FC, -0x0198, -0x0000, -0x0000, - -0x0000, -0x0060, -0x00F0, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x07FC, -0x07F8, -0x03FC, -0x03FE, -0x07FE, -0x07FE, -0x03FC, -0x01F8, -0x00F0, -0x0060, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x07BE, -0x037C, -0x00F8, -0x01F0, -0x03EC, -0x07DE, -0x079E, -0x030C, -0x0000, - -0x0000, -0x0000, -0x0000, -0x00E0, -0x01F0, -0x03F8, -0x03B8, -0x03B8, -0x03F0, -0x01E0, -0x01E0, -0x03FC, -0x073E, -0x071C, -0x07FE, -0x03F7, -0x01E2, -0x0000, - -0x0000, -0x0020, -0x0070, -0x00F8, -0x0078, -0x0038, -0x0038, -0x0070, -0x0020, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x000C, -0x001E, -0x003C, -0x0078, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x0078, -0x003C, -0x001E, -0x000C, - -0x0000, -0x0000, -0x0000, -0x0180, -0x03C0, -0x01E0, -0x00F0, -0x0078, -0x0078, -0x0078, -0x0078, -0x0078, -0x0078, -0x0078, -0x00F0, -0x01E0, -0x03C0, -0x0180, - -0x0000, -0x0000, -0x0402, -0x0E07, -0x0F0F, -0x079E, -0x03FC, -0x07FE, -0x0FFF, -0x07FE, -0x03FC, -0x079E, -0x0F0F, -0x0E07, -0x0402, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0060, -0x00F0, -0x01F8, -0x03FC, -0x03FC, -0x01F8, -0x00F0, -0x0060, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0060, -0x00F0, -0x00F0, -0x01E0, -0x03C0, -0x0180, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x03FC, -0x01F8, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0060, -0x00F0, -0x00F0, -0x0060, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0006, -0x000F, -0x001F, -0x003E, -0x007C, -0x00F8, -0x01F0, -0x03E0, -0x07C0, -0x0F80, -0x0F00, -0x0600, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FE, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0060, -0x00F0, -0x01F0, -0x03F0, -0x03F0, -0x01F0, -0x00F0, -0x00F0, -0x01F8, -0x03FC, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x07BE, -0x037C, -0x00F8, -0x01F0, -0x03FC, -0x07FE, -0x07FE, -0x03FC, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03F8, -0x07FC, -0x07FE, -0x03FE, -0x00FE, -0x01FC, -0x01FC, -0x00FE, -0x03FE, -0x07FE, -0x07FC, -0x03F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0038, -0x007C, -0x00FC, -0x01FC, -0x03FC, -0x07FC, -0x07FE, -0x07FE, -0x03FC, -0x003C, -0x003C, -0x0018, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03FC, -0x07FE, -0x07FE, -0x07FC, -0x07FC, -0x07FE, -0x03FE, -0x031E, -0x07FE, -0x07FE, -0x07FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FC, -0x07F8, -0x07F8, -0x07FC, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03FC, -0x07FE, -0x07FE, -0x03FE, -0x003E, -0x007C, -0x00F8, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x0060, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x07FE, -0x03FC, -0x03FC, -0x07FE, -0x07FE, -0x07FE, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x03FE, -0x01FE, -0x03FE, -0x07FE, -0x07FC, -0x03F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0060, -0x00F0, -0x00F0, -0x0060, -0x0000, -0x0000, -0x0060, -0x00F0, -0x00F0, -0x0060, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0060, -0x00F0, -0x00F0, -0x0060, -0x0000, -0x0000, -0x0060, -0x00F0, -0x00F0, -0x01E0, -0x00C0, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0018, -0x003C, -0x0078, -0x00F0, -0x01E0, -0x03C0, -0x03C0, -0x01E0, -0x00F0, -0x0078, -0x003C, -0x0018, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x03FC, -0x01F8, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x03FC, -0x01F8, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0300, -0x0780, -0x03C0, -0x01E0, -0x00F0, -0x0078, -0x0078, -0x00F0, -0x01E0, -0x03C0, -0x0780, -0x0300, - -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x0FFF, -0x0F0F, -0x060F, -0x001F, -0x003E, -0x007C, -0x00F8, -0x00F0, -0x0060, -0x0060, -0x00F0, -0x00F0, -0x0060, - -0x0000, -0x0000, -0x0000, -0x0000, -0x00F0, -0x01F8, -0x03FC, -0x07DE, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFE, -0x0EDC, -0x070C, -0x03FE, -0x01FC, -0x00F8, - -0x0000, -0x0000, -0x00F0, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x079E, -0x030C, - -0x0000, -0x0000, -0x03F0, -0x07F8, -0x07FC, -0x07FE, -0x079E, -0x079E, -0x07FE, -0x07FC, -0x07FC, -0x07FE, -0x079E, -0x079E, -0x07FE, -0x07FC, -0x07F8, -0x03F0, - -0x0000, -0x0000, -0x00F0, -0x01F8, -0x03FC, -0x07FE, -0x079E, -0x078C, -0x0780, -0x0780, -0x0780, -0x0780, -0x078C, -0x079E, -0x07FE, -0x03FC, -0x01F8, -0x00F0, - -0x0000, -0x0000, -0x03F0, -0x07F8, -0x07FC, -0x07FE, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FC, -0x07F8, -0x03F0, - -0x0000, -0x0000, -0x03FC, -0x07FE, -0x07FE, -0x07FC, -0x0780, -0x0780, -0x07F0, -0x07F8, -0x07F8, -0x07F0, -0x0780, -0x0780, -0x07FC, -0x07FE, -0x07FE, -0x03FC, - -0x0000, -0x0000, -0x03FC, -0x07FE, -0x07FE, -0x07FC, -0x0780, -0x0780, -0x07F0, -0x07F8, -0x07F8, -0x07F0, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0300, - -0x0000, -0x0000, -0x01F0, -0x03F8, -0x07FC, -0x07FE, -0x079E, -0x079E, -0x078C, -0x07BC, -0x07FE, -0x07FE, -0x07BE, -0x079E, -0x07FE, -0x07FE, -0x03FE, -0x01FC, - -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x030C, - -0x0000, -0x0000, -0x01F8, -0x03FC, -0x03FC, -0x01F8, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x01F8, -0x03FC, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x00FC, -0x01FE, -0x01FE, -0x00FC, -0x0078, -0x0078, -0x0078, -0x0378, -0x07F8, -0x07F8, -0x07F8, -0x07F8, -0x07F8, -0x07F8, -0x03F0, -0x01E0, - -0x0000, -0x0000, -0x0300, -0x078C, -0x079E, -0x07BE, -0x07FC, -0x07F8, -0x07F0, -0x07E0, -0x07C0, -0x07E0, -0x07F0, -0x07F8, -0x07FC, -0x07BE, -0x079E, -0x030C, - -0x0000, -0x0000, -0x0300, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x07FC, -0x07FE, -0x07FE, -0x03FC, - -0x0000, -0x0000, -0x030C, -0x079E, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x030C, - -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x07DE, -0x07DE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07BE, -0x07BE, -0x079E, -0x079E, -0x079E, -0x030C, - -0x0000, -0x0000, -0x00F0, -0x01F8, -0x03FC, -0x07FE, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x03FC, -0x01F8, -0x00F0, - -0x0000, -0x0000, -0x03F0, -0x07F8, -0x07FC, -0x07FE, -0x079E, -0x079E, -0x07FE, -0x07FC, -0x07F8, -0x07F0, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0300, - -0x0000, -0x0000, -0x00F0, -0x01F8, -0x03FC, -0x07FE, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FE, -0x07FE, -0x07FC, -0x03FE, -0x01FE, -0x00EC, - -0x0000, -0x0000, -0x03F0, -0x07F8, -0x07FC, -0x07FE, -0x079E, -0x079E, -0x07FE, -0x07FC, -0x07F8, -0x07F0, -0x07F8, -0x07FC, -0x07BE, -0x079E, -0x079E, -0x030C, - -0x0000, -0x0000, -0x00F8, -0x01FC, -0x03FE, -0x07FE, -0x078C, -0x0780, -0x07F0, -0x03F8, -0x01FC, -0x00FE, -0x001E, -0x031E, -0x07FE, -0x07FC, -0x03F8, -0x01F0, - -0x0000, -0x0000, -0x03FC, -0x07FE, -0x07FE, -0x03FC, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x0060, - -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x03FC, -0x01F8, -0x00F0, - -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x03FC, -0x03FC, -0x01F8, -0x00F0, -0x0060, - -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x03FC, -0x03FC, -0x0198, - -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x079E, -0x03FC, -0x01F8, -0x00F0, -0x00F0, -0x01F8, -0x03FC, -0x079E, -0x079E, -0x079E, -0x079E, -0x030C, - -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x03FC, -0x01F8, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x0060, - -0x0000, -0x0000, -0x03FC, -0x07FE, -0x07FE, -0x03FE, -0x001E, -0x003E, -0x007C, -0x00F8, -0x01F0, -0x03E0, -0x07C0, -0x0780, -0x07FC, -0x07FE, -0x07FE, -0x03FC, - -0x0000, -0x0000, -0x0078, -0x00FC, -0x00FC, -0x00F8, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F8, -0x00FC, -0x00FC, -0x0078, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0600, -0x0F00, -0x0F80, -0x07C0, -0x03E0, -0x01F0, -0x00F8, -0x007C, -0x003E, -0x001F, -0x000F, -0x0006, -0x0000, -0x0000, - -0x0000, -0x0000, -0x01E0, -0x03F0, -0x03F0, -0x01F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x01F0, -0x03F0, -0x03F0, -0x01E0, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0060, -0x00F0, -0x01F8, -0x03FC, -0x039C, -0x030C, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x07FE, -0x0FFF, -0x0FFF, -0x07FE, -0x0000, - -0x0000, -0x0300, -0x0780, -0x03C0, -0x01E0, -0x00F0, -0x0060, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x00F0, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x030C, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03F8, -0x07FC, -0x07FE, -0x07FE, -0x07FE, -0x07FC, -0x07FC, -0x07FE, -0x07FE, -0x07FE, -0x07FC, -0x03F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x078C, -0x0780, -0x0780, -0x078C, -0x07FE, -0x07FE, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03F0, -0x07F8, -0x07FC, -0x07FE, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FC, -0x07F8, -0x03F0, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03FC, -0x07FE, -0x07FE, -0x07FC, -0x07F0, -0x07F8, -0x07F8, -0x07F0, -0x07FC, -0x07FE, -0x07FE, -0x03FC, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03FC, -0x07FE, -0x07FE, -0x07FC, -0x07F8, -0x07FC, -0x07FC, -0x07F8, -0x0780, -0x0780, -0x0780, -0x0300, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x07FC, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x079E, -0x030C, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x00F0, -0x01F8, -0x01F8, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x01F8, -0x01F8, -0x00F0, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x007C, -0x00FE, -0x00FE, -0x007C, -0x003C, -0x003C, -0x003C, -0x01BC, -0x03FC, -0x03FC, -0x01F8, -0x00F0, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x07BE, -0x07FC, -0x07F8, -0x07F0, -0x07F0, -0x07F8, -0x07FC, -0x07BE, -0x079E, -0x030C, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0300, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x07FC, -0x07FE, -0x07FE, -0x03FC, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x079E, -0x079E, -0x030C, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x07DE, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07BE, -0x079E, -0x079E, -0x030C, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FE, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03F8, -0x07FC, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x07FC, -0x07F8, -0x0780, -0x0780, -0x0780, -0x0300, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x07BE, -0x07FE, -0x07FC, -0x07FE, -0x03FE, -0x01EC, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03F8, -0x07FC, -0x07FE, -0x07FE, -0x07FE, -0x07FC, -0x07F8, -0x07F8, -0x07FC, -0x07BE, -0x079E, -0x030C, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x07FE, -0x07FE, -0x07FC, -0x07FC, -0x03FE, -0x03FE, -0x07FE, -0x07FE, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03FC, -0x07FE, -0x07FE, -0x03FC, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x0060, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FE, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x03FC, -0x01F8, -0x00F0, -0x0060, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x079E, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x03FC, -0x03FC, -0x0198, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x07FE, -0x03FC, -0x01F8, -0x00F0, -0x00F0, -0x01F8, -0x03FC, -0x07FE, -0x079E, -0x030C, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x07FE, -0x03FC, -0x01F8, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x0060, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03FC, -0x07FE, -0x07FE, -0x03FE, -0x007C, -0x00F8, -0x01F0, -0x03E0, -0x07FC, -0x07FE, -0x07FE, -0x03FC, - -0x0000, -0x0038, -0x007C, -0x007C, -0x00FC, -0x00F8, -0x00F0, -0x00F0, -0x01E0, -0x01E0, -0x00F0, -0x00F0, -0x00F8, -0x00FC, -0x007C, -0x007C, -0x0038, -0x0000, - -0x0000, -0x0000, -0x0060, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x0060, -0x0000, -0x0000, - -0x0000, -0x01C0, -0x03E0, -0x03F0, -0x03F0, -0x01F0, -0x00F0, -0x00F0, -0x0078, -0x0078, -0x00F0, -0x00F0, -0x01F0, -0x03F0, -0x03F0, -0x03E0, -0x01C0, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x00C2, -0x01E7, -0x03FF, -0x07FE, -0x0F3C, -0x0618, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0780, -0x07C0, -0x07E0, -0x07F0, -0x07F8, -0x07FC, -0x07F8, -0x07F0, -0x07E0, -0x07C0, -0x0780, -0x0700, -0x0700, -0x0700, -0x0F80, -0x0F80, -0x0F80, - -0x07E0, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FF0, -0x07FE, -0x0FFF, -0x0FFE, -0x0FFC, -0x0FFC, -0x07FE, -0x00FF, -0x00FF, -0x00FF, -0x00FF, -0x00FF, -0x007E, - -0x0660, -0x0FF0, -0x0FE0, -0x0FC0, -0x0FE0, -0x0FF0, -0x07FC, -0x03FE, -0x03FE, -0x03FE, -0x03FE, -0x01FE, -0x00E7, -0x00FF, -0x00FF, -0x00FF, -0x00FF, -0x0066, - -0x07F0, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x07F8, -0x00FC, -0x00FC, -0x01FE, -0x01FE, -0x01FE, -0x00FE, -0x00FF, -0x00FF, -0x00FF, -0x00FF, -0x00FF, -0x0066, - -0x0600, -0x0F00, -0x0F00, -0x0FE0, -0x0FF0, -0x0FF0, -0x07F8, -0x01FC, -0x03FE, -0x03FE, -0x03FE, -0x01FF, -0x00FF, -0x00FF, -0x007E, -0x003C, -0x003C, -0x0018, - -0x0600, -0x0F00, -0x0F00, -0x0FE0, -0x0FF0, -0x0FF0, -0x07F8, -0x03FC, -0x07FE, -0x07FE, -0x03FC, -0x01FE, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x00FE, - -0x07F0, -0x0FF0, -0x0FF8, -0x0FF8, -0x0FF8, -0x07F0, -0x03C0, -0x03C0, -0x03F8, -0x03FC, -0x03FC, -0x01FE, -0x00FF, -0x00FF, -0x007E, -0x003C, -0x003C, -0x0018, - -0x0660, -0x0FF0, -0x0FF0, -0x07E0, -0x03C0, -0x01F8, -0x03FC, -0x03F8, -0x03F0, -0x03F8, -0x03FC, -0x01F8, -0x0078, -0x0078, -0x007E, -0x007F, -0x007F, -0x003E, - -0x07E0, -0x0FF0, -0x0FF0, -0x07E0, -0x03C0, -0x03C0, -0x01D8, -0x01FC, -0x01FC, -0x01FC, -0x01FC, -0x00FC, -0x007E, -0x007F, -0x007F, -0x007F, -0x007F, -0x0037, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0660, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FF0, -0x07E0, -0x0FF0, -0x07E0, -0x0FF0, -0x0FE0, -0x0FF0, -0x07F0, -0x0FF0, -0x07E0, - -0x03E0, -0x07F0, -0x0FF8, -0x0FF8, -0x0FF8, -0x06F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00FE, -0x00FF, -0x00FF, -0x00FE, -0x00FE, -0x00FF, -0x0066, - -0x0770, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x01FC, -0x03FE, -0x03FE, -0x03FE, -0x03FE, -0x00FF, -0x00FF, -0x00FF, -0x007E, -0x003C, -0x0018, - -0x023F, -0x073F, -0x073F, -0x073F, -0x0FBF, -0x0FBF, -0x0FBF, -0x0FBF, -0x0FBF, -0x0FBF, -0x0FBF, -0x0FBF, -0x073F, -0x073F, -0x073F, -0x073F, -0x073F, -0x073F, - -0x023F, -0x073F, -0x073F, -0x073F, -0x0FBF, -0x0FBF, -0x0FBF, -0x0FBF, -0x0FBF, -0x0FBF, -0x0FBF, -0x0FBF, -0x073F, -0x073F, -0x073F, -0x073F, -0x073F, -0x073F, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0618, -0x0F3C, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0F3C, -0x0618, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0630, -0x0F78, -0x0F78, -0x0F78, -0x0F78, -0x07F0, -0x07F0, -0x03E0, -0x01C0, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x01C0, -0x03E0, -0x07F0, -0x07F0, -0x0FF8, -0x0FF8, -0x0FF8, -0x0F78, -0x0630, - -0x0001, -0x0007, -0x001F, -0x007F, -0x01FF, -0x03FF, -0x03FF, -0x01FF, -0x003F, -0x003F, -0x003F, -0x003F, -0x003F, -0x003F, -0x001F, -0x0000, -0x0000, -0x0000, - -0x0C00, -0x0F80, -0x0FE0, -0x0FF8, -0x0FFC, -0x0FFC, -0x0FF8, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0001, -0x001F, -0x00FF, -0x00FF, -0x00FF, -0x003F, -0x007F, -0x00FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x001F, -0x0003, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0F80, -0x0FC0, -0x0FE0, -0x0FF0, -0x0FF8, -0x0FFC, -0x0FFC, -0x0FFC, -0x0F0C, -0x0F00, -0x0E00, -0x0E00, -0x0C00, -0x0800, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x001F, -0x001F, -0x001F, -0x007F, -0x01FF, -0x03FF, -0x03FF, -0x03FF, -0x01FF, -0x00FF, -0x007F, -0x003E, -0x0018, -0x0000, -0x0000, -0x0000, - -0x0000, -0x00E0, -0x0FE0, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0E78, -0x0818, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0003, -0x0007, -0x0007, -0x00FF, -0x03FF, -0x03FF, -0x03FF, -0x01FF, -0x01FF, -0x01FF, -0x00FE, -0x00F0, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0FC0, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FF8, -0x0FF8, -0x0FF0, -0x0FF0, -0x0FF0, -0x01E0, -0x00E0, -0x0040, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x00FF, -0x01FF, -0x01FF, -0x01FF, -0x03FF, -0x03FF, -0x03FF, -0x03FF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0400, -0x0780, -0x0FE0, -0x0FFC, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFE, -0x0FFC, -0x0FF0, -0x07E0, -0x07C0, -0x0700, -0x0600, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x003C, -0x007F, -0x01FF, -0x03FF, -0x03FF, -0x03FF, -0x03FF, -0x007F, -0x0007, -0x0007, -0x000F, -0x000F, -0x000E, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0180, -0x0FE0, -0x0FF0, -0x0FF8, -0x0FFC, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFC, -0x0FE0, -0x0E00, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x001E, -0x003F, -0x00FF, -0x01FF, -0x01FF, -0x01FF, -0x007F, -0x003F, -0x001F, -0x007F, -0x00FF, -0x00FF, -0x007F, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0800, -0x0E60, -0x0FF0, -0x0FF0, -0x0FF8, -0x0FF8, -0x0FFC, -0x0FFC, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFC, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0003, -0x003F, -0x007F, -0x007F, -0x003F, -0x003F, -0x003F, -0x01FF, -0x03FF, -0x03FF, -0x01FF, -0x003F, -0x0007, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0C00, -0x0C00, -0x0E00, -0x0F18, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FE0, -0x0FE0, -0x0FE0, -0x01E0, -0x0000, -0x0000, - -0x0000, -0x000F, -0x000F, -0x001F, -0x001F, -0x001F, -0x03FF, -0x03FF, -0x03FF, -0x01FF, -0x00FF, -0x007F, -0x003F, -0x001F, -0x0007, -0x0003, -0x0001, -0x0000, - -0x0000, -0x0F00, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FF8, -0x0FF0, -0x0FE0, -0x0FC0, -0x0F80, -0x0F00, -0x0E00, -0x0C00, -0x0000, - -0x0000, -0x0003, -0x0003, -0x0007, -0x018F, -0x01FF, -0x01FF, -0x01FF, -0x00FF, -0x00FF, -0x00FF, -0x00FF, -0x007F, -0x007F, -0x007F, -0x0078, -0x0000, -0x0000, - -0x0000, -0x0C00, -0x0FC0, -0x0FE0, -0x0FE0, -0x0FC0, -0x0FC0, -0x0FC0, -0x0FF8, -0x0FFC, -0x0FFC, -0x0FF8, -0x0FC0, -0x0E00, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0001, -0x0067, -0x00FF, -0x00FF, -0x01FF, -0x01FF, -0x03FF, -0x03FF, -0x07FF, -0x07FF, -0x07FF, -0x03FF, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0780, -0x0FC0, -0x0FF0, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FE0, -0x0FC0, -0x0F80, -0x0FE0, -0x0FF0, -0x0FF0, -0x0FE0, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0018, -0x007F, -0x00FF, -0x01FF, -0x03FF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x03FF, -0x007F, -0x0007, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x03C0, -0x0FE0, -0x0FF8, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FE0, -0x0E00, -0x0E00, -0x0F00, -0x0F00, -0x0700, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0002, -0x001E, -0x007F, -0x03FF, -0x0FFF, -0x0FFF, -0x0FFF, -0x07FF, -0x03FF, -0x00FF, -0x007E, -0x003E, -0x000E, -0x0006, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0FF0, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x003F, -0x03FF, -0x03FF, -0x03FF, -0x01FF, -0x01FF, -0x00FF, -0x00FF, -0x00FF, -0x0078, -0x0070, -0x0020, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0C00, -0x0E00, -0x0E00, -0x0FF0, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FF8, -0x0FF8, -0x0FF8, -0x07F0, -0x00F0, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0070, -0x007F, -0x00FF, -0x00FF, -0x00FF, -0x01FF, -0x01FF, -0x01FF, -0x01FF, -0x01E7, -0x0181, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0F80, -0x0F80, -0x0F80, -0x0FE0, -0x0FF8, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FF8, -0x0FF0, -0x0FE0, -0x07C0, -0x0180, -0x0000, -0x0000, -0x0000, - -0x0000, -0x001F, -0x003F, -0x007F, -0x00FF, -0x01FF, -0x03FF, -0x03FF, -0x03FF, -0x030F, -0x000F, -0x0007, -0x0007, -0x0003, -0x0001, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0800, -0x0F80, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FC0, -0x0FE0, -0x0FF0, -0x0FF8, -0x0FF8, -0x0FF8, -0x0FF8, -0x0F80, -0x0C00, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0180, -0x03C0, -0x07E0, -0x07E0, -0x03C0, -0x0180, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0060, -0x00F0, -0x01F8, -0x03FC, -0x01F8, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x00F0, -0x01F8, -0x03FC, -0x01F8, -0x00F0, -0x0060, -0x0000, - -0x0000, -0x0100, -0x0380, -0x07C0, -0x0FF0, -0x0FF8, -0x07F8, -0x03BC, -0x013C, -0x013C, -0x033C, -0x07F8, -0x0FF8, -0x0FF0, -0x07C0, -0x0380, -0x0100, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x01F8, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, - -0x01F8, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, - -0x01F8, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, - -0x01F8, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, - -0x01F8, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, - -0x01F8, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, - -0x0000, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FE, -0x07FE, -0x07FE, -0x07FE, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, -0x0780, - -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x00F0, -0x01F8, -0x03FC, -0x07FE, -0x0F0F, -0x0F0F, -0x0F0F, -0x0F0F, -0x07FE, -0x03FC, -0x01F8, - -0x0000, -0x0F80, -0x0F80, -0x0FFF, -0x0FFF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x0787, -0x0787, -0x0787, -0x0787, -0x0787, - -0x0000, -0x0000, -0x0000, -0x0800, -0x0800, -0x0800, -0x0800, -0x081F, -0x081F, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0F9F, -0x0F9F, -0x0F80, -0x0F80, -0x0F80, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0060, -0x00F0, -0x00F0, -0x01F8, -0x01F8, -0x03FC, -0x03FC, -0x01F8, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0040, -0x00E0, -0x0EEF, -0x0FFF, -0x0EEF, -0x00E0, -0x0040, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x07DE, -0x07FE, -0x07FE, -0x0FFF, -0x0FFF, -0x0FFF, -0x07FE, -0x07BE, -0x079E, -0x030C, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x00F0, -0x01F8, -0x03FC, -0x03FC, -0x03C0, -0x0FFF, -0x0FFF, -0x0FFF, -0x03FC, -0x03FC, -0x03FC, -0x00F8, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x01F8, -0x03FC, -0x03FC, -0x03F8, -0x03C0, -0x0FFF, -0x0FFF, -0x0FFF, -0x03F0, -0x03FC, -0x03FC, -0x01F8, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x030C, -0x079E, -0x079E, -0x079E, -0x07FE, -0x0FFF, -0x0FFF, -0x0FFF, -0x03FC, -0x03FC, -0x03FC, -0x01F8, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0000, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0E0F, -0x0F1F, -0x0FBF, -0x03F8, -0x01F0, -0x00E0, -0x0040, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0070, -0x00F8, -0x0070, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x007F, -0x00FF, -0x007F, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x00E0, -0x01F0, -0x00E0, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FE0, -0x0FF0, -0x0FE0, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0780, -0x07FF, -0x07FF, -0x07FF, -0x07FF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x00F0, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0787, -0x0F80, -0x0F80, -0x0F80, -0x0F80, -0x0066, -0x00FF, -0x00FF, -0x00FF, -0x00FF, -0x00FF, -0x00FF, -0x007E, -0x003C, -0x0018, -0x0000, -0x0000, -0x0000, - -0x0F80, -0x0000, -0x0000, -0x0000, -0x0000, -0x0180, -0x03C0, -0x07C0, -0x07C0, -0x03C0, -0x03C0, -0x03C6, -0x07EF, -0x07EF, -0x03C6, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x03C0, -0x07E0, -0x0FF0, -0x0FF0, -0x07E0, -0x03F0, -0x0FF0, -0x0FF0, -0x07E0, -0x03C0, -0x0000, -0x0000, -0x0000, - -0x01F8, -0x03FC, -0x03FC, -0x01F8, -0x01F8, -0x00F0, -0x00F0, -0x0060, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, -0x000E, - -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, -0x0700, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, - -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x000E, -0x000F, -0x000F, -0x000F, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x000F, -0x000F, -0x000F, -0x000E, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0F00, -0x0F00, -0x0F00, -0x0700, - -0x0700, -0x0F00, -0x0F00, -0x0F00, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0070, -0x00F8, -0x0070, -0x0000, -0x0000, -0x0000, -0x0010, -0x0038, -0x003C, -0x003E, -0x003F, -0x003E, -0x003C, -0x0038, -0x0010, -0x0000, - -0x0000, -0x0000, -0x00E0, -0x01F0, -0x00E0, -0x0000, -0x0000, -0x0000, -0x0080, -0x01C0, -0x03C0, -0x07C0, -0x0FC0, -0x07C0, -0x03C0, -0x01C0, -0x0080, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0078, -0x0078, -0x0078, -0x007F, -0x007F, -0x007F, -0x007F, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x007F, -0x007F, -0x007F, -0x007F, -0x0078, -0x0078, -0x0078, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x01E0, -0x01E0, -0x01E0, - -0x01E0, -0x01E0, -0x01E0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0660, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FF4, -0x07EE, -0x07EE, -0x0FFE, -0x0FF4, -0x0FF4, -0x07EE, -0x07EE, -0x0FEE, -0x0FF4, -0x0FF0, -0x0FF0, -0x0FE0, -0x07C0, - -0x0040, -0x00E0, -0x00E0, -0x07FC, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFF, -0x0FFE, -0x0FFE, -0x07FE, -0x00FE, -0x01FE, -0x03FE, -0x07FE, -0x0FFE, -0x0FFF, -0x0556, - -0x0000, -0x0000, -0x0660, -0x0FF0, -0x0FF0, -0x0FF0, -0x07E6, -0x03CF, -0x018E, -0x03CE, -0x07EE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x066E, -0x000F, -0x0006, - -0x0000, -0x0000, -0x0660, -0x0FF0, -0x0FF0, -0x0FF0, -0x07E6, -0x03CF, -0x018E, -0x07CE, -0x0FEE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FEE, -0x07CE, -0x000F, -0x0006, - -0x0000, -0x0000, -0x03C0, -0x07E0, -0x0FC0, -0x0F00, -0x0FC6, -0x07EF, -0x03CE, -0x03CE, -0x07EE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FFE, -0x07EE, -0x000F, -0x0006, - -0x0000, -0x0000, -0x03C0, -0x07E0, -0x0FC0, -0x0F00, -0x0FC6, -0x07EF, -0x03CE, -0x07CE, -0x0FEE, -0x0FFE, -0x0FFE, -0x0FFE, -0x0FEE, -0x07CE, -0x000F, -0x0006, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, - -0x0660, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FF4, -0x07FE, -0x07FE, -0x0FFE, -0x0FF4, -0x0FF4, -0x0FFE, -0x067E, -0x0FFE, -0x0FF4, -0x0FF0, -0x07E0, -0x03C0, -0x0180, - -0x0000, -0x0000, -0x0000, -0x03FC, -0x07FE, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x07FE, -0x03FC, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0000, -0x0000, -0x03FC, -0x07FE, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x07FE, -0x03FC, -0x0000, -0x0000, -0x0000, - -0x0000, -0x0003, -0x0007, -0x0007, -0x0007, -0x0007, -0x0007, -0x0007, -0x0007, -0x0007, -0x0007, -0x0007, -0x0007, -0x0007, -0x0007, -0x0007, -0x0003, -0x0000, - -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, - -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFC, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, - -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FE0, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, - -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0F00, -0x0F00, -0x0F00, -0x0F00, -0x0F00, -0x0F00, -0x0F00, -0x0F00, -0x0F00, -0x0F00, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, - -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0FFF, -0x0FFF, -0x0FFF, -0x0000, - -0x0000, -0x0C00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0E00, -0x0C00, -0x0000, - -0x0000, -0x0FFE, -0x0FFF, -0x0FFF, -0x0F9F, -0x0FDF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FDF, -0x0F9F, -0x0FFF, -0x0FFF, -0x0FFE, -0x0000, - -0x0001, -0x0003, -0x0033, -0x007B, -0x007F, -0x003F, -0x001F, -0x00FC, -0x01FC, -0x01FC, -0x00FC, -0x001F, -0x003F, -0x007F, -0x007B, -0x0033, -0x0003, -0x0003, - -0x0800, -0x0C00, -0x0CC0, -0x0DE0, -0x0FE0, -0x0FC0, -0x0F80, -0x03F0, -0x03F8, -0x03F8, -0x03F0, -0x0F80, -0x0FC0, -0x0FE0, -0x0DE0, -0x0CC0, -0x0C00, -0x0800, - -0x0000, -0x0003, -0x000F, -0x001F, -0x003F, -0x007D, -0x0079, -0x00F1, -0x00F1, -0x00F1, -0x00F1, -0x0079, -0x007D, -0x003F, -0x001F, -0x000F, -0x0003, -0x0000, - -0x0000, -0x0C00, -0x0F00, -0x0F80, -0x0FC0, -0x0FE0, -0x0FE0, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FF0, -0x0FE0, -0x0FE0, -0x0FC0, -0x0F80, -0x0F00, -0x0C00, -0x0000, - -0x0006, -0x000F, -0x001F, -0x003F, -0x07FF, -0x0FF7, -0x0FE7, -0x0FE7, -0x0FE7, -0x0FE7, -0x0FE7, -0x0FF7, -0x07FF, -0x003F, -0x001F, -0x000F, -0x0006, -0x0000, - -0x0020, -0x0070, -0x0038, -0x01B8, -0x03F8, -0x05FC, -0x0FFC, -0x0FFC, -0x07FC, -0x0FFC, -0x0FFC, -0x05FC, -0x03F8, -0x01B8, -0x0038, -0x0070, -0x0020, -0x0000, - -0x07FE, -0x0FFF, -0x07FE, -0x07FE, -0x079E, -0x079E, -0x03FC, -0x01F8, -0x00F0, -0x00F0, -0x01F8, -0x03FC, -0x079E, -0x079E, -0x07FE, -0x07FE, -0x0FFF, -0x07FE, - -0x0000, -0x0300, -0x0380, -0x03C0, -0x03E0, -0x03F0, -0x03F8, -0x03FC, -0x03FE, -0x03FF, -0x03FF, -0x03FC, -0x03FC, -0x03FE, -0x003E, -0x003E, -0x003E, -0x0008, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0322, -0x07F7, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FF7, -0x0FF7, -0x0FF7, -0x0FF7, -0x04A2, - -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0000, -0x0722, -0x0FF7, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0F77, -0x0E77, -0x0E77, -0x0E77, -0x0422, - -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, -0x0FFF, - -}; - -#endif /* FONT12X18_H_ */ +/* + * font12x18.h + * + * Created on: 3.1.2012 + * Author: Samba + */ + +#ifndef FONT12X18_H_ +#define FONT12X18_H_ + +static const uint16_t font_frame12x18[] = { + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x03C0, + 0x0660, + 0x0460, + 0x00C0, + 0x0180, + 0x0300, + 0x07E0, + 0x0000, + 0x0078, + 0x006C, + 0x0066, + 0x0066, + 0x0066, + 0x0066, + 0x006C, + 0x0078, + 0x0000, + + 0x0000, + 0x07C0, + 0x0060, + 0x0060, + 0x03C0, + 0x0060, + 0x0060, + 0x07C0, + 0x0000, + 0x0078, + 0x006C, + 0x0066, + 0x0066, + 0x0066, + 0x0066, + 0x006C, + 0x0078, + 0x0000, + + 0x0000, + 0x0001, + 0x0001, + 0x0001, + 0x0001, + 0x0001, + 0x0001, + 0x0001, + 0x0003, + 0x0007, + 0x001F, + 0x0038, + 0x0060, + 0x00C0, + 0x00C0, + 0x0180, + 0x0180, + 0x0181, + + 0x0000, + 0x0800, + 0x0800, + 0x0800, + 0x0800, + 0x0800, + 0x0800, + 0x0800, + 0x0C00, + 0x0E00, + 0x0F80, + 0x01C0, + 0x0060, + 0x0030, + 0x0030, + 0x0018, + 0x0018, + 0x0818, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x07FE, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0700, + 0x08C6, + 0x0826, + 0x0818, + 0x0C18, + 0x0C24, + 0x0642, + 0x0382, + 0x0381, + 0x03C1, + 0x00F1, + 0x00BE, + 0x0080, + 0x0080, + 0x01C0, + 0x03E0, + 0x07F0, + 0x0000, + + 0x0000, + 0x01F8, + 0x030C, + 0x0606, + 0x0402, + 0x0002, + 0x0002, + 0x0002, + 0x0002, + 0x0000, + 0x07FE, + 0x0606, + 0x06FE, + 0x06C6, + 0x06F6, + 0x0606, + 0x07FE, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x030C, + 0x0606, + 0x0402, + 0x0402, + 0x0000, + 0x07FE, + 0x0606, + 0x06FE, + 0x06C6, + 0x06F6, + 0x0606, + 0x07FE, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0208, + 0x030C, + 0x0390, + 0x03E0, + 0x03E0, + 0x01F0, + 0x00F8, + 0x007C, + 0x0080, + 0x0180, + 0x0280, + 0x0480, + 0x0000, + 0x07F8, + 0x0000, + + 0x0181, + 0x0180, + 0x0180, + 0x00C0, + 0x00C0, + 0x0060, + 0x0038, + 0x001F, + 0x0007, + 0x0003, + 0x0001, + 0x0001, + 0x0001, + 0x0001, + 0x0001, + 0x0001, + 0x0001, + 0x0000, + + 0x0818, + 0x0018, + 0x0018, + 0x0030, + 0x0030, + 0x0060, + 0x01C0, + 0x0F80, + 0x0E00, + 0x0C00, + 0x0800, + 0x0800, + 0x0800, + 0x0800, + 0x0800, + 0x0800, + 0x0800, + 0x0000, + + 0x07FE, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x00F0, + 0x0108, + 0x0108, + 0x0008, + 0x0008, + 0x0008, + 0x0000, + 0x01F8, + 0x030C, + 0x037C, + 0x030C, + 0x037C, + 0x037C, + 0x01F8, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x00F0, + 0x0108, + 0x0108, + 0x0108, + 0x0000, + 0x01F8, + 0x030C, + 0x037C, + 0x030C, + 0x037C, + 0x037C, + 0x01F8, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x00FF, + 0x01FF, + 0x0387, + 0x0387, + 0x0387, + 0x03FF, + 0x03FF, + 0x03FF, + 0x03FF, + 0x03FF, + 0x03FF, + 0x01FF, + 0x00FF, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FF8, + 0x0FFC, + 0x0FF2, + 0x0C32, + 0x081E, + 0x000E, + 0x000E, + 0x000E, + 0x000E, + 0x081E, + 0x0C3E, + 0x0FFC, + 0x0FF8, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FF8, + 0x0FFC, + 0x0FF2, + 0x0C32, + 0x081E, + 0x000E, + 0x03CE, + 0x07EE, + 0x07EE, + 0x07EE, + 0x07EE, + 0x0BDC, + 0x0C38, + 0x0000, + 0x0000, + 0x0000, + + 0x03F8, + 0x0030, + 0x0060, + 0x01C0, + 0x03F8, + 0x0000, + 0x03F8, + 0x0318, + 0x03F8, + 0x0000, + 0x03F8, + 0x0318, + 0x03F8, + 0x0000, + 0x03B8, + 0x0358, + 0x0318, + 0x0318, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0001, + 0x0003, + 0x0007, + 0x000F, + 0x001F, + 0x003F, + 0x003F, + 0x003F, + 0x003F, + 0x0030, + 0x0030, + 0x0030, + 0x0030, + 0x0030, + 0x0030, + 0x0000, + + 0x0000, + 0x0000, + 0x0800, + 0x0C00, + 0x0E00, + 0x0F00, + 0x0F80, + 0x00C0, + 0x00C0, + 0x00C0, + 0x0FC0, + 0x00C0, + 0x00C0, + 0x00C0, + 0x00C0, + 0x00C0, + 0x00C0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x00F0, + 0x01F8, + 0x03FC, + 0x0000, + 0x07FE, + 0x07E2, + 0x07E2, + 0x0422, + 0x043E, + 0x043E, + 0x043E, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0108, + 0x039C, + 0x018C, + 0x0084, + 0x0084, + 0x0108, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0198, + 0x0198, + 0x0198, + 0x07FE, + 0x07FE, + 0x0198, + 0x0198, + 0x07FE, + 0x07FE, + 0x0198, + 0x0198, + 0x0198, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x01F8, + 0x03FC, + 0x036C, + 0x0360, + 0x03F0, + 0x01F8, + 0x006C, + 0x036C, + 0x03FC, + 0x01F8, + 0x0060, + 0x0060, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x031C, + 0x0038, + 0x0070, + 0x00E0, + 0x01C0, + 0x038C, + 0x030C, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x00E0, + 0x0190, + 0x0110, + 0x0110, + 0x0120, + 0x00C0, + 0x00C0, + 0x0120, + 0x0214, + 0x0208, + 0x0214, + 0x01E2, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0020, + 0x0070, + 0x0030, + 0x0010, + 0x0010, + 0x0020, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x000C, + 0x0018, + 0x0030, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0030, + 0x0018, + 0x000C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0180, + 0x00C0, + 0x0060, + 0x0030, + 0x0030, + 0x0030, + 0x0030, + 0x0030, + 0x0030, + 0x0030, + 0x0060, + 0x00C0, + 0x0180, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0402, + 0x0606, + 0x030C, + 0x0198, + 0x00F0, + 0x07FE, + 0x00F0, + 0x0198, + 0x030C, + 0x0606, + 0x0402, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x01F8, + 0x01F8, + 0x0060, + 0x0060, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x00C0, + 0x0180, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x01F8, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0006, + 0x000E, + 0x001C, + 0x0038, + 0x0070, + 0x00E0, + 0x01C0, + 0x0380, + 0x0700, + 0x0600, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03FC, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x03FC, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x00E0, + 0x01E0, + 0x01E0, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x01F8, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03FC, + 0x030C, + 0x031C, + 0x0038, + 0x0070, + 0x00E0, + 0x01C0, + 0x03FC, + 0x03FC, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03F8, + 0x03FC, + 0x000C, + 0x000C, + 0x00F8, + 0x00F8, + 0x000C, + 0x000C, + 0x03FC, + 0x03F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0038, + 0x0078, + 0x00D8, + 0x0198, + 0x0318, + 0x03FC, + 0x03FC, + 0x0018, + 0x0018, + 0x0018, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x03FC, + 0x0300, + 0x03F8, + 0x03FC, + 0x000C, + 0x000C, + 0x030C, + 0x03FC, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03F8, + 0x0300, + 0x0300, + 0x03F8, + 0x03FC, + 0x030C, + 0x030C, + 0x03FC, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x03FC, + 0x000C, + 0x001C, + 0x0038, + 0x0070, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03FC, + 0x030C, + 0x030C, + 0x01F8, + 0x01F8, + 0x030C, + 0x030C, + 0x03FC, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03FC, + 0x030C, + 0x030C, + 0x03FC, + 0x01FC, + 0x000C, + 0x000C, + 0x03FC, + 0x03F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x00C0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0018, + 0x0030, + 0x0060, + 0x00C0, + 0x0180, + 0x0180, + 0x00C0, + 0x0060, + 0x0030, + 0x0018, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x01F8, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x01F8, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0300, + 0x0180, + 0x00C0, + 0x0060, + 0x0030, + 0x0030, + 0x0060, + 0x00C0, + 0x0180, + 0x0300, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03FC, + 0x070E, + 0x0606, + 0x0006, + 0x000E, + 0x001C, + 0x0038, + 0x0070, + 0x0060, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x00F0, + 0x0108, + 0x0204, + 0x04D2, + 0x0532, + 0x0512, + 0x0532, + 0x04D4, + 0x0408, + 0x0200, + 0x0104, + 0x00F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x00F0, + 0x01F8, + 0x03FC, + 0x039C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x03FC, + 0x03FC, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x03F0, + 0x03F8, + 0x031C, + 0x030C, + 0x030C, + 0x031C, + 0x03F8, + 0x03F8, + 0x031C, + 0x030C, + 0x030C, + 0x031C, + 0x03F8, + 0x03F0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x00F0, + 0x01F8, + 0x039C, + 0x030C, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x030C, + 0x039C, + 0x01F8, + 0x00F0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x03F0, + 0x03F8, + 0x031C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x031C, + 0x03F8, + 0x03F0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x03FC, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x03F0, + 0x03F0, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x03FC, + 0x03FC, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x03FC, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x03F0, + 0x03F0, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x01F0, + 0x03F8, + 0x039C, + 0x030C, + 0x030C, + 0x0300, + 0x0300, + 0x033C, + 0x033C, + 0x030C, + 0x030C, + 0x030C, + 0x03FC, + 0x01FC, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x03FC, + 0x03FC, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x01F8, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x01F8, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x00FC, + 0x00FC, + 0x0030, + 0x0030, + 0x0030, + 0x0030, + 0x0030, + 0x0330, + 0x0330, + 0x0330, + 0x0330, + 0x0330, + 0x03F0, + 0x01E0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0300, + 0x030C, + 0x031C, + 0x0338, + 0x0370, + 0x03E0, + 0x03C0, + 0x0380, + 0x03C0, + 0x03E0, + 0x0370, + 0x0338, + 0x031C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x03FC, + 0x03FC, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x039C, + 0x03FC, + 0x03FC, + 0x036C, + 0x036C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x038C, + 0x038C, + 0x03CC, + 0x03EC, + 0x037C, + 0x033C, + 0x031C, + 0x031C, + 0x030C, + 0x030C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x00F0, + 0x01F8, + 0x039C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x039C, + 0x01F8, + 0x00F0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x03F0, + 0x03F8, + 0x031C, + 0x030C, + 0x030C, + 0x031C, + 0x03F8, + 0x03F0, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x00F0, + 0x01F8, + 0x039C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x036C, + 0x037C, + 0x03B8, + 0x01FC, + 0x00EC, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x03F0, + 0x03F8, + 0x031C, + 0x030C, + 0x030C, + 0x031C, + 0x03F8, + 0x03E0, + 0x03E0, + 0x0370, + 0x0338, + 0x031C, + 0x030C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x00F8, + 0x01FC, + 0x038C, + 0x0300, + 0x0300, + 0x0380, + 0x01F0, + 0x00F8, + 0x001C, + 0x000C, + 0x000C, + 0x031C, + 0x03F8, + 0x01F0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x03FC, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x039C, + 0x01F8, + 0x00F0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x039C, + 0x0198, + 0x01F8, + 0x00F0, + 0x0060, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x036C, + 0x036C, + 0x036C, + 0x036C, + 0x036C, + 0x036C, + 0x03FC, + 0x01F8, + 0x0198, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x0198, + 0x00F0, + 0x0060, + 0x0060, + 0x00F0, + 0x0198, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x039C, + 0x01F8, + 0x00F0, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x03FC, + 0x000C, + 0x000C, + 0x001C, + 0x0038, + 0x0070, + 0x00E0, + 0x01C0, + 0x0380, + 0x0300, + 0x0300, + 0x03FC, + 0x03FC, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0078, + 0x0078, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0078, + 0x0078, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0600, + 0x0700, + 0x0380, + 0x01C0, + 0x00E0, + 0x0070, + 0x0038, + 0x001C, + 0x000E, + 0x0006, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x01E0, + 0x01E0, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x01E0, + 0x01E0, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x00F0, + 0x0198, + 0x0108, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x07FE, + 0x07FE, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0300, + 0x0180, + 0x00C0, + 0x0060, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x00F0, + 0x01F8, + 0x039C, + 0x030C, + 0x030C, + 0x03FC, + 0x03FC, + 0x030C, + 0x030C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03F8, + 0x03FC, + 0x030C, + 0x030C, + 0x03F8, + 0x03F8, + 0x030C, + 0x030C, + 0x03FC, + 0x03F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03FC, + 0x030C, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x030C, + 0x03FC, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03F0, + 0x03F8, + 0x031C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x031C, + 0x03F8, + 0x03F0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x03FC, + 0x0300, + 0x0300, + 0x03F0, + 0x03F0, + 0x0300, + 0x0300, + 0x03FC, + 0x03FC, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x03FC, + 0x0300, + 0x0300, + 0x03F8, + 0x03F8, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03FC, + 0x038C, + 0x0300, + 0x033C, + 0x033C, + 0x030C, + 0x038C, + 0x03FC, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x03FC, + 0x03FC, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x00F0, + 0x00F0, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x00F0, + 0x00F0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x007C, + 0x007C, + 0x0018, + 0x0018, + 0x0018, + 0x0018, + 0x0018, + 0x0198, + 0x01F8, + 0x00F0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x031C, + 0x0338, + 0x0370, + 0x03E0, + 0x03E0, + 0x03F0, + 0x0338, + 0x031C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x03FC, + 0x03FC, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x039C, + 0x03FC, + 0x036C, + 0x036C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x038C, + 0x03CC, + 0x03EC, + 0x037C, + 0x033C, + 0x031C, + 0x030C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03FC, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x03FC, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03F8, + 0x03FC, + 0x030C, + 0x030C, + 0x03FC, + 0x03F8, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03FC, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x033C, + 0x0338, + 0x03FC, + 0x01EC, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03F8, + 0x03FC, + 0x030C, + 0x030C, + 0x03F8, + 0x03E0, + 0x0370, + 0x0338, + 0x031C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x03FC, + 0x030C, + 0x0300, + 0x03F8, + 0x01FC, + 0x000C, + 0x030C, + 0x03FC, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x03FC, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x03FC, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x039C, + 0x01F8, + 0x00F0, + 0x0060, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x036C, + 0x036C, + 0x03FC, + 0x01F8, + 0x0198, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x039C, + 0x01F8, + 0x00F0, + 0x0060, + 0x0060, + 0x00F0, + 0x01F8, + 0x039C, + 0x030C, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x039C, + 0x01F8, + 0x00F0, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x03FC, + 0x001C, + 0x0038, + 0x0070, + 0x00E0, + 0x01C0, + 0x0380, + 0x03FC, + 0x03FC, + 0x0000, + + 0x0000, + 0x0000, + 0x0038, + 0x0038, + 0x0078, + 0x0060, + 0x0060, + 0x0060, + 0x00C0, + 0x00C0, + 0x0060, + 0x0060, + 0x0060, + 0x0078, + 0x0038, + 0x0038, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x01C0, + 0x01E0, + 0x01E0, + 0x0060, + 0x0060, + 0x0060, + 0x0030, + 0x0030, + 0x0060, + 0x0060, + 0x0060, + 0x01E0, + 0x01E0, + 0x01C0, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x00C2, + 0x01E6, + 0x033C, + 0x0618, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0280, + 0x02C0, + 0x02E0, + 0x02F0, + 0x02F8, + 0x02F0, + 0x02E0, + 0x02C0, + 0x0280, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0700, + 0x0000, + + 0x0000, + 0x0660, + 0x06C0, + 0x0700, + 0x06C0, + 0x0660, + 0x0000, + 0x06BE, + 0x0688, + 0x0588, + 0x0588, + 0x0000, + 0x0066, + 0x0066, + 0x007E, + 0x0066, + 0x0066, + 0x0000, + + 0x0000, + 0x0660, + 0x06C0, + 0x0700, + 0x06C0, + 0x0660, + 0x0000, + 0x01DC, + 0x01AC, + 0x01AC, + 0x018C, + 0x0000, + 0x0066, + 0x0066, + 0x007E, + 0x0066, + 0x0066, + 0x0000, + + 0x0000, + 0x07F0, + 0x06B0, + 0x06B0, + 0x0630, + 0x0000, + 0x0078, + 0x0048, + 0x00FC, + 0x00CC, + 0x00CC, + 0x0000, + 0x0066, + 0x0066, + 0x007E, + 0x0066, + 0x0066, + 0x0000, + + 0x0000, + 0x0600, + 0x0600, + 0x0600, + 0x07E0, + 0x07E0, + 0x0000, + 0x00F8, + 0x018C, + 0x01FC, + 0x018C, + 0x0000, + 0x007E, + 0x007E, + 0x0018, + 0x0018, + 0x0018, + 0x0000, + + 0x0000, + 0x0600, + 0x0600, + 0x0600, + 0x07E0, + 0x07E0, + 0x0000, + 0x01F8, + 0x039C, + 0x039C, + 0x01F8, + 0x0000, + 0x00E6, + 0x00F6, + 0x00FE, + 0x00DE, + 0x00CE, + 0x0000, + + 0x0000, + 0x03E0, + 0x0630, + 0x07F0, + 0x0630, + 0x0000, + 0x0180, + 0x0180, + 0x0180, + 0x01F8, + 0x01F8, + 0x0000, + 0x007E, + 0x007E, + 0x0018, + 0x0018, + 0x0018, + 0x0000, + + 0x0000, + 0x0660, + 0x0660, + 0x03C0, + 0x0180, + 0x0000, + 0x01F8, + 0x0180, + 0x01F0, + 0x0180, + 0x01F8, + 0x0000, + 0x0030, + 0x0030, + 0x0030, + 0x003E, + 0x003E, + 0x0000, + + 0x0000, + 0x07E0, + 0x07E0, + 0x0180, + 0x0180, + 0x0180, + 0x0000, + 0x00D8, + 0x00F8, + 0x00D8, + 0x00D8, + 0x0000, + 0x003C, + 0x0022, + 0x0026, + 0x003C, + 0x0036, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0660, + 0x07E0, + 0x05A0, + 0x0420, + 0x0000, + 0x07E0, + 0x0000, + 0x07E0, + 0x0400, + 0x07E0, + 0x0020, + 0x07E0, + 0x0000, + + 0x0000, + 0x03E0, + 0x0630, + 0x07F0, + 0x0630, + 0x0000, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0000, + 0x007E, + 0x0046, + 0x0078, + 0x006C, + 0x0066, + 0x0000, + + 0x0000, + 0x0770, + 0x06B0, + 0x06B0, + 0x06B0, + 0x06B0, + 0x0000, + 0x00F8, + 0x018C, + 0x01FC, + 0x018C, + 0x0000, + 0x0066, + 0x0066, + 0x0066, + 0x003C, + 0x0018, + 0x0000, + + 0x0000, + 0x0200, + 0x020C, + 0x0212, + 0x0012, + 0x0712, + 0x0012, + 0x070C, + 0x0700, + 0x0700, + 0x0712, + 0x0712, + 0x0014, + 0x0218, + 0x0214, + 0x0212, + 0x0212, + 0x0200, + + 0x0000, + 0x0210, + 0x0210, + 0x0210, + 0x001E, + 0x0700, + 0x000C, + 0x0712, + 0x0712, + 0x0712, + 0x070C, + 0x0700, + 0x001E, + 0x0210, + 0x021E, + 0x0202, + 0x021E, + 0x0200, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0618, + 0x0738, + 0x07F8, + 0x06D8, + 0x06D8, + 0x0618, + 0x0618, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0630, + 0x0630, + 0x0630, + 0x0630, + 0x0360, + 0x03E0, + 0x01C0, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01C0, + 0x03E0, + 0x0220, + 0x0630, + 0x07F0, + 0x0630, + 0x0630, + 0x0000, + + 0x0000, + 0x0000, + 0x0003, + 0x001F, + 0x000F, + 0x000F, + 0x000F, + 0x000F, + 0x000F, + 0x000F, + 0x000F, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0800, + 0x0F00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0007, + 0x0003, + 0x0007, + 0x000F, + 0x001F, + 0x003F, + 0x003F, + 0x0007, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0E00, + 0x0F00, + 0x0F80, + 0x0E00, + 0x0E00, + 0x0C00, + 0x0C00, + 0x0800, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0001, + 0x0003, + 0x001F, + 0x007F, + 0x00FF, + 0x007F, + 0x001C, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0E60, + 0x0800, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0001, + 0x003F, + 0x00FF, + 0x007F, + 0x0078, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0700, + 0x0FF0, + 0x0FE0, + 0x0FE0, + 0x08C0, + 0x0040, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x007F, + 0x007F, + 0x007F, + 0x007F, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0300, + 0x0FC0, + 0x0FF8, + 0x0FF0, + 0x0FE0, + 0x0180, + 0x0100, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0010, + 0x003F, + 0x007F, + 0x001F, + 0x0001, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0880, + 0x0FE0, + 0x0FF0, + 0x0FF8, + 0x07F0, + 0x0700, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x000C, + 0x001F, + 0x003F, + 0x001F, + 0x0007, + 0x0001, + 0x0001, + 0x0003, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0C00, + 0x0FC0, + 0x0FE0, + 0x0FE0, + 0x0FF0, + 0x0FF0, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x001F, + 0x000F, + 0x0007, + 0x0007, + 0x0003, + 0x0007, + 0x000F, + 0x0001, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0800, + 0x0C00, + 0x0E00, + 0x0F60, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0180, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0007, + 0x0007, + 0x0007, + 0x0007, + 0x000F, + 0x003F, + 0x000F, + 0x0007, + 0x0003, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0F00, + 0x0FC0, + 0x0E00, + 0x0C00, + 0x0800, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0001, + 0x0003, + 0x0007, + 0x006F, + 0x003F, + 0x003F, + 0x003F, + 0x003F, + 0x0018, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0F80, + 0x0F00, + 0x0E00, + 0x0E00, + 0x0C00, + 0x0E00, + 0x0F00, + 0x0800, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0003, + 0x003F, + 0x007F, + 0x007F, + 0x00FF, + 0x00FF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0300, + 0x0F80, + 0x0FC0, + 0x0F80, + 0x0E00, + 0x0800, + 0x0800, + 0x0C00, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0011, + 0x007F, + 0x00FF, + 0x01FF, + 0x00FE, + 0x000E, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0080, + 0x0FC0, + 0x0FE0, + 0x0F80, + 0x0800, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x000C, + 0x003F, + 0x01FF, + 0x00FF, + 0x007F, + 0x0018, + 0x0008, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FE0, + 0x0FE0, + 0x0FE0, + 0x0FE0, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x000E, + 0x00FF, + 0x007F, + 0x007F, + 0x0031, + 0x0020, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0800, + 0x0FC0, + 0x0FF0, + 0x0FE0, + 0x01E0, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x003F, + 0x003F, + 0x003F, + 0x0067, + 0x0001, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0800, + 0x0C00, + 0x0F80, + 0x0FE0, + 0x0FF0, + 0x0FE0, + 0x0380, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0007, + 0x000F, + 0x001F, + 0x0007, + 0x0007, + 0x0003, + 0x0003, + 0x0001, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0E00, + 0x0C00, + 0x0E00, + 0x0F00, + 0x0F80, + 0x0FC0, + 0x0FC0, + 0x0E00, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0180, + 0x0240, + 0x0240, + 0x0180, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0060, + 0x00F0, + 0x01F8, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x01F8, + 0x00F0, + 0x0060, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0100, + 0x0300, + 0x07C0, + 0x07F0, + 0x0330, + 0x0118, + 0x0018, + 0x0018, + 0x0118, + 0x0330, + 0x07F0, + 0x07C0, + 0x0300, + 0x0100, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x00F0, + 0x07FE, + 0x0606, + 0x0462, + 0x0462, + 0x0462, + 0x0462, + 0x0462, + 0x0462, + 0x0462, + 0x0402, + 0x0462, + 0x0462, + 0x0402, + 0x0606, + 0x07FE, + 0x0000, + + 0x0000, + 0x00F0, + 0x07FE, + 0x070E, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x07FE, + 0x07FE, + 0x0000, + + 0x0000, + 0x00F0, + 0x07FE, + 0x070E, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x0000, + + 0x0000, + 0x00F0, + 0x07FE, + 0x070E, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x0000, + + 0x0000, + 0x00F0, + 0x07FE, + 0x070E, + 0x0606, + 0x0606, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x0000, + + 0x0000, + 0x00F0, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x07FE, + 0x0000, + + 0x0000, + 0x0000, + 0x03FF, + 0x03FF, + 0x0300, + 0x0300, + 0x033C, + 0x033C, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + 0x0300, + + 0x0000, + 0x0000, + 0x0FFF, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x00F0, + 0x01F8, + 0x030C, + 0x0606, + 0x0606, + 0x0606, + 0x0606, + 0x030C, + 0x01F8, + 0x00F0, + + 0x0000, + 0x0000, + 0x0F00, + 0x0F00, + 0x033F, + 0x033F, + 0x0333, + 0x0333, + 0x0333, + 0x0333, + 0x03F3, + 0x03F3, + 0x0303, + 0x0303, + 0x0303, + 0x0303, + 0x0303, + 0x0303, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x000F, + 0x000F, + 0x03FC, + 0x03FC, + 0x030F, + 0x030F, + 0x0300, + 0x0300, + 0x0F00, + 0x0F00, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0F00, + 0x0F00, + 0x0000, + 0x0000, + 0x0F00, + 0x0F00, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0060, + 0x0060, + 0x00F0, + 0x00F0, + 0x01F8, + 0x01F8, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0040, + 0x0040, + 0x0E4F, + 0x0040, + 0x0040, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x038C, + 0x038C, + 0x03CC, + 0x036C, + 0x0B6D, + 0x033C, + 0x031C, + 0x030C, + 0x030C, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x00F0, + 0x01F8, + 0x0188, + 0x0180, + 0x01F0, + 0x0EFB, + 0x0018, + 0x0118, + 0x01F8, + 0x00F0, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x01F8, + 0x01F8, + 0x0180, + 0x0180, + 0x01E0, + 0x0DEF, + 0x0180, + 0x0180, + 0x01F8, + 0x01F8, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x030C, + 0x030C, + 0x030C, + 0x030C, + 0x036C, + 0x0D6B, + 0x01F8, + 0x0198, + 0x0198, + 0x0198, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0E0F, + 0x0318, + 0x01B0, + 0x00E0, + 0x0040, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0070, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x007F, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x00E0, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FE0, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0300, + 0x0300, + 0x03FF, + 0x03FF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FFF, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0300, + 0x0300, + 0x0F00, + 0x0F00, + 0x0000, + 0x0000, + 0x0066, + 0x0066, + 0x0066, + 0x0066, + 0x0066, + 0x007E, + 0x003C, + 0x0018, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0180, + 0x0380, + 0x0380, + 0x0180, + 0x0180, + 0x0180, + 0x03C6, + 0x03C6, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03C0, + 0x0660, + 0x0660, + 0x03E0, + 0x0060, + 0x0260, + 0x07E0, + 0x03C0, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x01F8, + 0x01F8, + 0x00F0, + 0x00F0, + 0x0060, + 0x0060, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + 0x0004, + + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + 0x0200, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0004, + 0x0004, + 0x0007, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0007, + 0x0004, + 0x0004, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0E00, + 0x0200, + 0x0200, + + 0x0200, + 0x0200, + 0x0E00, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0070, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0010, + 0x0018, + 0x001C, + 0x001E, + 0x001C, + 0x0018, + 0x0010, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x00E0, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0080, + 0x0180, + 0x0380, + 0x0780, + 0x0380, + 0x0180, + 0x0080, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0030, + 0x0030, + 0x0030, + 0x0030, + 0x003F, + 0x003F, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x003F, + 0x003F, + 0x0030, + 0x0030, + 0x0030, + 0x0030, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FC0, + 0x0FC0, + 0x00C0, + 0x00C0, + 0x00C0, + 0x00C0, + + 0x00C0, + 0x00C0, + 0x00C0, + 0x00C0, + 0x0FC0, + 0x0FC0, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0660, + 0x07E0, + 0x05A0, + 0x0420, + 0x0004, + 0x03C4, + 0x0664, + 0x0660, + 0x0660, + 0x03C4, + 0x0004, + 0x07C4, + 0x0660, + 0x0660, + 0x0660, + 0x07C0, + 0x0000, + + 0x0000, + 0x0040, + 0x0040, + 0x0040, + 0x07FC, + 0x0444, + 0x0550, + 0x0446, + 0x07F4, + 0x0604, + 0x0014, + 0x0054, + 0x0054, + 0x0154, + 0x0154, + 0x0554, + 0x0556, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0660, + 0x0660, + 0x0660, + 0x03C0, + 0x0186, + 0x0004, + 0x0004, + 0x03C4, + 0x0664, + 0x0664, + 0x07E4, + 0x0664, + 0x0004, + 0x0006, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0660, + 0x0660, + 0x0660, + 0x03C0, + 0x0186, + 0x0004, + 0x0004, + 0x07C4, + 0x0664, + 0x0784, + 0x0664, + 0x07C4, + 0x0004, + 0x0006, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x03C0, + 0x0600, + 0x0600, + 0x0600, + 0x03C6, + 0x0004, + 0x0004, + 0x03C4, + 0x0664, + 0x0664, + 0x07E4, + 0x0664, + 0x0004, + 0x0006, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x03C0, + 0x0600, + 0x0600, + 0x0600, + 0x03C6, + 0x0004, + 0x0004, + 0x07C4, + 0x0664, + 0x0784, + 0x0664, + 0x07C4, + 0x0004, + 0x0006, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0660, + 0x07E0, + 0x05A0, + 0x0420, + 0x0004, + 0x03C4, + 0x0664, + 0x0660, + 0x07E0, + 0x0664, + 0x0004, + 0x0664, + 0x0660, + 0x0660, + 0x03C0, + 0x0180, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x070E, + 0x0606, + 0x0402, + 0x0402, + 0x0402, + 0x0402, + 0x0606, + 0x070E, + 0x03FC, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x03FC, + 0x070E, + 0x0606, + 0x04F2, + 0x04F2, + 0x04F2, + 0x04F2, + 0x0606, + 0x070E, + 0x03FC, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0003, + 0x0002, + 0x0002, + 0x0002, + 0x0002, + 0x0002, + 0x0002, + 0x0002, + 0x0002, + 0x0002, + 0x0002, + 0x0002, + 0x0002, + 0x0003, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0FF8, + 0x0FF8, + 0x0FF8, + 0x0FF8, + 0x0FF8, + 0x0FF8, + 0x0FF8, + 0x0FF8, + 0x0FF8, + 0x0FF8, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0FC0, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0E00, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0FFF, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0C00, + 0x0400, + 0x0400, + 0x0400, + 0x0400, + 0x0400, + 0x0400, + 0x0400, + 0x0400, + 0x0400, + 0x0400, + 0x0400, + 0x0400, + 0x0C00, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0FFE, + 0x0402, + 0x050A, + 0x058A, + 0x05CA, + 0x05EA, + 0x05FA, + 0x05FA, + 0x05EA, + 0x05CA, + 0x058A, + 0x050A, + 0x0402, + 0x0FFE, + 0x0000, + 0x0000, + + 0x0000, + 0x0001, + 0x0001, + 0x0030, + 0x0033, + 0x0007, + 0x000C, + 0x0018, + 0x00D8, + 0x00D8, + 0x0018, + 0x000C, + 0x0007, + 0x0033, + 0x0030, + 0x0001, + 0x0001, + 0x0000, + + 0x0000, + 0x0800, + 0x0800, + 0x00C0, + 0x0CC0, + 0x0E00, + 0x0300, + 0x0180, + 0x01B0, + 0x01B0, + 0x0180, + 0x0300, + 0x0E00, + 0x0CC0, + 0x00C0, + 0x0800, + 0x0800, + 0x0000, + + 0x0000, + 0x0000, + 0x0003, + 0x000F, + 0x001C, + 0x0030, + 0x0030, + 0x0060, + 0x0060, + 0x0060, + 0x0060, + 0x0030, + 0x0030, + 0x001C, + 0x000F, + 0x0003, + 0x0000, + 0x0000, + + 0x0000, + 0x0000, + 0x0C00, + 0x0F00, + 0x0F80, + 0x0FC0, + 0x0FC0, + 0x0FE0, + 0x0FE0, + 0x0FE0, + 0x0FE0, + 0x0FC0, + 0x0FC0, + 0x0F80, + 0x0F00, + 0x0C00, + 0x0000, + 0x0000, + + 0x0000, + 0x0006, + 0x000E, + 0x001A, + 0x0032, + 0x07E2, + 0x04C2, + 0x04C2, + 0x04C2, + 0x04C2, + 0x04C2, + 0x07E2, + 0x0032, + 0x001A, + 0x000E, + 0x0006, + 0x0000, + 0x0000, + + 0x0000, + 0x0060, + 0x0030, + 0x0010, + 0x0190, + 0x0098, + 0x04C8, + 0x0648, + 0x0248, + 0x0648, + 0x04C8, + 0x0098, + 0x0190, + 0x0010, + 0x0030, + 0x0060, + 0x0000, + 0x0000, + + 0x0000, + 0x07FE, + 0x03FC, + 0x030C, + 0x030C, + 0x030C, + 0x0198, + 0x00F0, + 0x0060, + 0x0060, + 0x00F0, + 0x0198, + 0x030C, + 0x030C, + 0x030C, + 0x03FC, + 0x07FE, + 0x0000, + + 0x0000, + 0x0000, + 0x0100, + 0x0180, + 0x01C0, + 0x01E0, + 0x01F0, + 0x01F8, + 0x01FC, + 0x01FE, + 0x01F0, + 0x01F0, + 0x0138, + 0x0038, + 0x001C, + 0x001C, + 0x0008, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0322, + 0x04B6, + 0x04AA, + 0x04AA, + 0x07A2, + 0x04A2, + 0x04A2, + 0x04A2, + 0x04A2, + 0x0000, + + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0000, + 0x0722, + 0x04B6, + 0x04AA, + 0x04AA, + 0x0722, + 0x0422, + 0x0422, + 0x0422, + 0x0422, + 0x0000, + + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + 0x0FFF, + +}; + +static const uint16_t font_mask12x18[] = { +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FFF, +0x0FFF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, + +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FFF, +0x0FFF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, + +0x0001, +0x0003, +0x0003, +0x0003, +0x0003, +0x0003, +0x0003, +0x0003, +0x0007, +0x001F, +0x003F, +0x007F, +0x00F8, +0x01E0, +0x01E0, +0x03C0, +0x03C1, +0x03C3, + +0x0800, +0x0C00, +0x0C00, +0x0C00, +0x0C00, +0x0C00, +0x0C00, +0x0C00, +0x0E00, +0x0F80, +0x0FC0, +0x0FE0, +0x01F0, +0x0078, +0x0078, +0x003C, +0x083C, +0x0C3C, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0FC6, +0x0FEF, +0x0FFF, +0x0FFE, +0x0FFC, +0x0FFE, +0x0FFF, +0x07FF, +0x07FF, +0x07FF, +0x03FF, +0x01FF, +0x01FE, +0x01C0, +0x03E0, +0x07F0, +0x0FFC, +0x0FFE, + +0x01F8, +0x03FC, +0x07FE, +0x0F0F, +0x0E07, +0x0407, +0x0007, +0x0007, +0x0007, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, + +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x0F0F, +0x0E07, +0x0E07, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, + +0x0000, +0x0000, +0x0208, +0x071C, +0x079E, +0x07FC, +0x07F0, +0x07F0, +0x03F8, +0x01FC, +0x00FE, +0x01FC, +0x03C0, +0x07C0, +0x0FC0, +0x0FF8, +0x0FFC, +0x0FFC, + +0x03C3, +0x03C1, +0x03C0, +0x01E0, +0x01E0, +0x00F8, +0x007F, +0x003F, +0x001F, +0x0007, +0x0003, +0x0003, +0x0003, +0x0003, +0x0003, +0x0003, +0x0003, +0x0001, + +0x0C3C, +0x083C, +0x003C, +0x0078, +0x0078, +0x01F0, +0x0FE0, +0x0FC0, +0x0F80, +0x0E00, +0x0C00, +0x0C00, +0x0C00, +0x0C00, +0x0C00, +0x0C00, +0x0C00, +0x0800, + +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x00F0, +0x03FC, +0x03FC, +0x039C, +0x011C, +0x001C, +0x001C, +0x01FC, +0x03FC, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x03FC, +0x0000, + +0x0000, +0x0000, +0x0000, +0x00F0, +0x03FC, +0x03FC, +0x039C, +0x039C, +0x03FC, +0x03FC, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x03FC, +0x0000, + +0x0000, +0x01FF, +0x03FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x03FF, +0x01FF, +0x0000, +0x0000, + +0x0000, +0x0FFC, +0x0FFE, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFE, +0x0FFC, +0x0000, +0x0000, + +0x0000, +0x0FFC, +0x0FFE, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFE, +0x0FFC, +0x0000, +0x0000, + +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0001, +0x0003, +0x0007, +0x000F, +0x001F, +0x003F, +0x007F, +0x00FF, +0x01FF, +0x037F, +0x027F, +0x007F, +0x007F, +0x007F, +0x007F, +0x007F, +0x007F, +0x007F, + +0x0800, +0x0C00, +0x0E00, +0x0F00, +0x0F80, +0x0FC0, +0x0FE0, +0x0FF0, +0x0FF8, +0x0FEC, +0x0FE4, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, + +0x0000, +0x0000, +0x0060, +0x01F8, +0x03FC, +0x07FE, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0060, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x0060, +0x0060, +0x00F0, +0x00F0, +0x0060, +0x0000, + +0x0000, +0x0108, +0x039C, +0x07FE, +0x03DE, +0x01CE, +0x01CE, +0x039C, +0x0108, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0198, +0x03FC, +0x03FC, +0x07FE, +0x0FFF, +0x0FFF, +0x07FE, +0x07FE, +0x0FFF, +0x0FFF, +0x07FE, +0x03FC, +0x03FC, +0x0198, +0x0000, +0x0000, + +0x0000, +0x0060, +0x00F0, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x07FC, +0x07F8, +0x03FC, +0x03FE, +0x07FE, +0x07FE, +0x03FC, +0x01F8, +0x00F0, +0x0060, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x07BE, +0x037C, +0x00F8, +0x01F0, +0x03EC, +0x07DE, +0x079E, +0x030C, +0x0000, + +0x0000, +0x0000, +0x0000, +0x00E0, +0x01F0, +0x03F8, +0x03B8, +0x03B8, +0x03F0, +0x01E0, +0x01E0, +0x03FC, +0x073E, +0x071C, +0x07FE, +0x03F7, +0x01E2, +0x0000, + +0x0000, +0x0020, +0x0070, +0x00F8, +0x0078, +0x0038, +0x0038, +0x0070, +0x0020, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x000C, +0x001E, +0x003C, +0x0078, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x0078, +0x003C, +0x001E, +0x000C, + +0x0000, +0x0000, +0x0000, +0x0180, +0x03C0, +0x01E0, +0x00F0, +0x0078, +0x0078, +0x0078, +0x0078, +0x0078, +0x0078, +0x0078, +0x00F0, +0x01E0, +0x03C0, +0x0180, + +0x0000, +0x0000, +0x0402, +0x0E07, +0x0F0F, +0x079E, +0x03FC, +0x07FE, +0x0FFF, +0x07FE, +0x03FC, +0x079E, +0x0F0F, +0x0E07, +0x0402, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0060, +0x00F0, +0x01F8, +0x03FC, +0x03FC, +0x01F8, +0x00F0, +0x0060, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0060, +0x00F0, +0x00F0, +0x01E0, +0x03C0, +0x0180, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x03FC, +0x01F8, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0060, +0x00F0, +0x00F0, +0x0060, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0006, +0x000F, +0x001F, +0x003E, +0x007C, +0x00F8, +0x01F0, +0x03E0, +0x07C0, +0x0F80, +0x0F00, +0x0600, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FE, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0060, +0x00F0, +0x01F0, +0x03F0, +0x03F0, +0x01F0, +0x00F0, +0x00F0, +0x01F8, +0x03FC, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x07BE, +0x037C, +0x00F8, +0x01F0, +0x03FC, +0x07FE, +0x07FE, +0x03FC, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03F8, +0x07FC, +0x07FE, +0x03FE, +0x00FE, +0x01FC, +0x01FC, +0x00FE, +0x03FE, +0x07FE, +0x07FC, +0x03F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0038, +0x007C, +0x00FC, +0x01FC, +0x03FC, +0x07FC, +0x07FE, +0x07FE, +0x03FC, +0x003C, +0x003C, +0x0018, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03FC, +0x07FE, +0x07FE, +0x07FC, +0x07FC, +0x07FE, +0x03FE, +0x031E, +0x07FE, +0x07FE, +0x07FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FC, +0x07F8, +0x07F8, +0x07FC, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03FC, +0x07FE, +0x07FE, +0x03FE, +0x003E, +0x007C, +0x00F8, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x0060, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x07FE, +0x03FC, +0x03FC, +0x07FE, +0x07FE, +0x07FE, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x03FE, +0x01FE, +0x03FE, +0x07FE, +0x07FC, +0x03F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0060, +0x00F0, +0x00F0, +0x0060, +0x0000, +0x0000, +0x0060, +0x00F0, +0x00F0, +0x0060, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0060, +0x00F0, +0x00F0, +0x0060, +0x0000, +0x0000, +0x0060, +0x00F0, +0x00F0, +0x01E0, +0x00C0, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0018, +0x003C, +0x0078, +0x00F0, +0x01E0, +0x03C0, +0x03C0, +0x01E0, +0x00F0, +0x0078, +0x003C, +0x0018, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x03FC, +0x01F8, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x03FC, +0x01F8, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0300, +0x0780, +0x03C0, +0x01E0, +0x00F0, +0x0078, +0x0078, +0x00F0, +0x01E0, +0x03C0, +0x0780, +0x0300, + +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x0FFF, +0x0F0F, +0x060F, +0x001F, +0x003E, +0x007C, +0x00F8, +0x00F0, +0x0060, +0x0060, +0x00F0, +0x00F0, +0x0060, + +0x0000, +0x0000, +0x0000, +0x0000, +0x00F0, +0x01F8, +0x03FC, +0x07DE, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFE, +0x0EDC, +0x070C, +0x03FE, +0x01FC, +0x00F8, + +0x0000, +0x0000, +0x00F0, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x079E, +0x030C, + +0x0000, +0x0000, +0x03F0, +0x07F8, +0x07FC, +0x07FE, +0x079E, +0x079E, +0x07FE, +0x07FC, +0x07FC, +0x07FE, +0x079E, +0x079E, +0x07FE, +0x07FC, +0x07F8, +0x03F0, + +0x0000, +0x0000, +0x00F0, +0x01F8, +0x03FC, +0x07FE, +0x079E, +0x078C, +0x0780, +0x0780, +0x0780, +0x0780, +0x078C, +0x079E, +0x07FE, +0x03FC, +0x01F8, +0x00F0, + +0x0000, +0x0000, +0x03F0, +0x07F8, +0x07FC, +0x07FE, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FC, +0x07F8, +0x03F0, + +0x0000, +0x0000, +0x03FC, +0x07FE, +0x07FE, +0x07FC, +0x0780, +0x0780, +0x07F0, +0x07F8, +0x07F8, +0x07F0, +0x0780, +0x0780, +0x07FC, +0x07FE, +0x07FE, +0x03FC, + +0x0000, +0x0000, +0x03FC, +0x07FE, +0x07FE, +0x07FC, +0x0780, +0x0780, +0x07F0, +0x07F8, +0x07F8, +0x07F0, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0300, + +0x0000, +0x0000, +0x01F0, +0x03F8, +0x07FC, +0x07FE, +0x079E, +0x079E, +0x078C, +0x07BC, +0x07FE, +0x07FE, +0x07BE, +0x079E, +0x07FE, +0x07FE, +0x03FE, +0x01FC, + +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x030C, + +0x0000, +0x0000, +0x01F8, +0x03FC, +0x03FC, +0x01F8, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x01F8, +0x03FC, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x00FC, +0x01FE, +0x01FE, +0x00FC, +0x0078, +0x0078, +0x0078, +0x0378, +0x07F8, +0x07F8, +0x07F8, +0x07F8, +0x07F8, +0x07F8, +0x03F0, +0x01E0, + +0x0000, +0x0000, +0x0300, +0x078C, +0x079E, +0x07BE, +0x07FC, +0x07F8, +0x07F0, +0x07E0, +0x07C0, +0x07E0, +0x07F0, +0x07F8, +0x07FC, +0x07BE, +0x079E, +0x030C, + +0x0000, +0x0000, +0x0300, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x07FC, +0x07FE, +0x07FE, +0x03FC, + +0x0000, +0x0000, +0x030C, +0x079E, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x030C, + +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x07DE, +0x07DE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07BE, +0x07BE, +0x079E, +0x079E, +0x079E, +0x030C, + +0x0000, +0x0000, +0x00F0, +0x01F8, +0x03FC, +0x07FE, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x03FC, +0x01F8, +0x00F0, + +0x0000, +0x0000, +0x03F0, +0x07F8, +0x07FC, +0x07FE, +0x079E, +0x079E, +0x07FE, +0x07FC, +0x07F8, +0x07F0, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0300, + +0x0000, +0x0000, +0x00F0, +0x01F8, +0x03FC, +0x07FE, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FE, +0x07FE, +0x07FC, +0x03FE, +0x01FE, +0x00EC, + +0x0000, +0x0000, +0x03F0, +0x07F8, +0x07FC, +0x07FE, +0x079E, +0x079E, +0x07FE, +0x07FC, +0x07F8, +0x07F0, +0x07F8, +0x07FC, +0x07BE, +0x079E, +0x079E, +0x030C, + +0x0000, +0x0000, +0x00F8, +0x01FC, +0x03FE, +0x07FE, +0x078C, +0x0780, +0x07F0, +0x03F8, +0x01FC, +0x00FE, +0x001E, +0x031E, +0x07FE, +0x07FC, +0x03F8, +0x01F0, + +0x0000, +0x0000, +0x03FC, +0x07FE, +0x07FE, +0x03FC, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x0060, + +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x03FC, +0x01F8, +0x00F0, + +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x03FC, +0x03FC, +0x01F8, +0x00F0, +0x0060, + +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x03FC, +0x03FC, +0x0198, + +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x079E, +0x03FC, +0x01F8, +0x00F0, +0x00F0, +0x01F8, +0x03FC, +0x079E, +0x079E, +0x079E, +0x079E, +0x030C, + +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x03FC, +0x01F8, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x0060, + +0x0000, +0x0000, +0x03FC, +0x07FE, +0x07FE, +0x03FE, +0x001E, +0x003E, +0x007C, +0x00F8, +0x01F0, +0x03E0, +0x07C0, +0x0780, +0x07FC, +0x07FE, +0x07FE, +0x03FC, + +0x0000, +0x0000, +0x0078, +0x00FC, +0x00FC, +0x00F8, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F8, +0x00FC, +0x00FC, +0x0078, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0600, +0x0F00, +0x0F80, +0x07C0, +0x03E0, +0x01F0, +0x00F8, +0x007C, +0x003E, +0x001F, +0x000F, +0x0006, +0x0000, +0x0000, + +0x0000, +0x0000, +0x01E0, +0x03F0, +0x03F0, +0x01F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x01F0, +0x03F0, +0x03F0, +0x01E0, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0060, +0x00F0, +0x01F8, +0x03FC, +0x039C, +0x030C, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x07FE, +0x0FFF, +0x0FFF, +0x07FE, +0x0000, + +0x0000, +0x0300, +0x0780, +0x03C0, +0x01E0, +0x00F0, +0x0060, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x00F0, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x030C, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03F8, +0x07FC, +0x07FE, +0x07FE, +0x07FE, +0x07FC, +0x07FC, +0x07FE, +0x07FE, +0x07FE, +0x07FC, +0x03F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x078C, +0x0780, +0x0780, +0x078C, +0x07FE, +0x07FE, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03F0, +0x07F8, +0x07FC, +0x07FE, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FC, +0x07F8, +0x03F0, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03FC, +0x07FE, +0x07FE, +0x07FC, +0x07F0, +0x07F8, +0x07F8, +0x07F0, +0x07FC, +0x07FE, +0x07FE, +0x03FC, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03FC, +0x07FE, +0x07FE, +0x07FC, +0x07F8, +0x07FC, +0x07FC, +0x07F8, +0x0780, +0x0780, +0x0780, +0x0300, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x07FC, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x079E, +0x030C, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x00F0, +0x01F8, +0x01F8, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x01F8, +0x01F8, +0x00F0, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x007C, +0x00FE, +0x00FE, +0x007C, +0x003C, +0x003C, +0x003C, +0x01BC, +0x03FC, +0x03FC, +0x01F8, +0x00F0, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x07BE, +0x07FC, +0x07F8, +0x07F0, +0x07F0, +0x07F8, +0x07FC, +0x07BE, +0x079E, +0x030C, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0300, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x07FC, +0x07FE, +0x07FE, +0x03FC, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x079E, +0x079E, +0x030C, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x07DE, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07BE, +0x079E, +0x079E, +0x030C, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FE, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03F8, +0x07FC, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x07FC, +0x07F8, +0x0780, +0x0780, +0x0780, +0x0300, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x07BE, +0x07FE, +0x07FC, +0x07FE, +0x03FE, +0x01EC, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03F8, +0x07FC, +0x07FE, +0x07FE, +0x07FE, +0x07FC, +0x07F8, +0x07F8, +0x07FC, +0x07BE, +0x079E, +0x030C, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x07FE, +0x07FE, +0x07FC, +0x07FC, +0x03FE, +0x03FE, +0x07FE, +0x07FE, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03FC, +0x07FE, +0x07FE, +0x03FC, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x0060, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FE, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x03FC, +0x01F8, +0x00F0, +0x0060, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x079E, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x03FC, +0x03FC, +0x0198, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x07FE, +0x03FC, +0x01F8, +0x00F0, +0x00F0, +0x01F8, +0x03FC, +0x07FE, +0x079E, +0x030C, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x07FE, +0x03FC, +0x01F8, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x0060, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03FC, +0x07FE, +0x07FE, +0x03FE, +0x007C, +0x00F8, +0x01F0, +0x03E0, +0x07FC, +0x07FE, +0x07FE, +0x03FC, + +0x0000, +0x0038, +0x007C, +0x007C, +0x00FC, +0x00F8, +0x00F0, +0x00F0, +0x01E0, +0x01E0, +0x00F0, +0x00F0, +0x00F8, +0x00FC, +0x007C, +0x007C, +0x0038, +0x0000, + +0x0000, +0x0000, +0x0060, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x0060, +0x0000, +0x0000, + +0x0000, +0x01C0, +0x03E0, +0x03F0, +0x03F0, +0x01F0, +0x00F0, +0x00F0, +0x0078, +0x0078, +0x00F0, +0x00F0, +0x01F0, +0x03F0, +0x03F0, +0x03E0, +0x01C0, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x00C2, +0x01E7, +0x03FF, +0x07FE, +0x0F3C, +0x0618, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0780, +0x07C0, +0x07E0, +0x07F0, +0x07F8, +0x07FC, +0x07F8, +0x07F0, +0x07E0, +0x07C0, +0x0780, +0x0700, +0x0700, +0x0700, +0x0F80, +0x0F80, +0x0F80, + +0x07E0, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FF0, +0x07FE, +0x0FFF, +0x0FFE, +0x0FFC, +0x0FFC, +0x07FE, +0x00FF, +0x00FF, +0x00FF, +0x00FF, +0x00FF, +0x007E, + +0x0660, +0x0FF0, +0x0FE0, +0x0FC0, +0x0FE0, +0x0FF0, +0x07FC, +0x03FE, +0x03FE, +0x03FE, +0x03FE, +0x01FE, +0x00E7, +0x00FF, +0x00FF, +0x00FF, +0x00FF, +0x0066, + +0x07F0, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x07F8, +0x00FC, +0x00FC, +0x01FE, +0x01FE, +0x01FE, +0x00FE, +0x00FF, +0x00FF, +0x00FF, +0x00FF, +0x00FF, +0x0066, + +0x0600, +0x0F00, +0x0F00, +0x0FE0, +0x0FF0, +0x0FF0, +0x07F8, +0x01FC, +0x03FE, +0x03FE, +0x03FE, +0x01FF, +0x00FF, +0x00FF, +0x007E, +0x003C, +0x003C, +0x0018, + +0x0600, +0x0F00, +0x0F00, +0x0FE0, +0x0FF0, +0x0FF0, +0x07F8, +0x03FC, +0x07FE, +0x07FE, +0x03FC, +0x01FE, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x00FE, + +0x07F0, +0x0FF0, +0x0FF8, +0x0FF8, +0x0FF8, +0x07F0, +0x03C0, +0x03C0, +0x03F8, +0x03FC, +0x03FC, +0x01FE, +0x00FF, +0x00FF, +0x007E, +0x003C, +0x003C, +0x0018, + +0x0660, +0x0FF0, +0x0FF0, +0x07E0, +0x03C0, +0x01F8, +0x03FC, +0x03F8, +0x03F0, +0x03F8, +0x03FC, +0x01F8, +0x0078, +0x0078, +0x007E, +0x007F, +0x007F, +0x003E, + +0x07E0, +0x0FF0, +0x0FF0, +0x07E0, +0x03C0, +0x03C0, +0x01D8, +0x01FC, +0x01FC, +0x01FC, +0x01FC, +0x00FC, +0x007E, +0x007F, +0x007F, +0x007F, +0x007F, +0x0037, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0660, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FF0, +0x07E0, +0x0FF0, +0x07E0, +0x0FF0, +0x0FE0, +0x0FF0, +0x07F0, +0x0FF0, +0x07E0, + +0x03E0, +0x07F0, +0x0FF8, +0x0FF8, +0x0FF8, +0x06F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00FE, +0x00FF, +0x00FF, +0x00FE, +0x00FE, +0x00FF, +0x0066, + +0x0770, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x01FC, +0x03FE, +0x03FE, +0x03FE, +0x03FE, +0x00FF, +0x00FF, +0x00FF, +0x007E, +0x003C, +0x0018, + +0x023F, +0x073F, +0x073F, +0x073F, +0x0FBF, +0x0FBF, +0x0FBF, +0x0FBF, +0x0FBF, +0x0FBF, +0x0FBF, +0x0FBF, +0x073F, +0x073F, +0x073F, +0x073F, +0x073F, +0x073F, + +0x023F, +0x073F, +0x073F, +0x073F, +0x0FBF, +0x0FBF, +0x0FBF, +0x0FBF, +0x0FBF, +0x0FBF, +0x0FBF, +0x0FBF, +0x073F, +0x073F, +0x073F, +0x073F, +0x073F, +0x073F, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0618, +0x0F3C, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0F3C, +0x0618, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0630, +0x0F78, +0x0F78, +0x0F78, +0x0F78, +0x07F0, +0x07F0, +0x03E0, +0x01C0, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x01C0, +0x03E0, +0x07F0, +0x07F0, +0x0FF8, +0x0FF8, +0x0FF8, +0x0F78, +0x0630, + +0x0001, +0x0007, +0x001F, +0x007F, +0x01FF, +0x03FF, +0x03FF, +0x01FF, +0x003F, +0x003F, +0x003F, +0x003F, +0x003F, +0x003F, +0x001F, +0x0000, +0x0000, +0x0000, + +0x0C00, +0x0F80, +0x0FE0, +0x0FF8, +0x0FFC, +0x0FFC, +0x0FF8, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0001, +0x001F, +0x00FF, +0x00FF, +0x00FF, +0x003F, +0x007F, +0x00FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x001F, +0x0003, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0F80, +0x0FC0, +0x0FE0, +0x0FF0, +0x0FF8, +0x0FFC, +0x0FFC, +0x0FFC, +0x0F0C, +0x0F00, +0x0E00, +0x0E00, +0x0C00, +0x0800, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x001F, +0x001F, +0x001F, +0x007F, +0x01FF, +0x03FF, +0x03FF, +0x03FF, +0x01FF, +0x00FF, +0x007F, +0x003E, +0x0018, +0x0000, +0x0000, +0x0000, + +0x0000, +0x00E0, +0x0FE0, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0E78, +0x0818, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0003, +0x0007, +0x0007, +0x00FF, +0x03FF, +0x03FF, +0x03FF, +0x01FF, +0x01FF, +0x01FF, +0x00FE, +0x00F0, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0FC0, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FF8, +0x0FF8, +0x0FF0, +0x0FF0, +0x0FF0, +0x01E0, +0x00E0, +0x0040, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x00FF, +0x01FF, +0x01FF, +0x01FF, +0x03FF, +0x03FF, +0x03FF, +0x03FF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0400, +0x0780, +0x0FE0, +0x0FFC, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFE, +0x0FFC, +0x0FF0, +0x07E0, +0x07C0, +0x0700, +0x0600, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x003C, +0x007F, +0x01FF, +0x03FF, +0x03FF, +0x03FF, +0x03FF, +0x007F, +0x0007, +0x0007, +0x000F, +0x000F, +0x000E, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0180, +0x0FE0, +0x0FF0, +0x0FF8, +0x0FFC, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFC, +0x0FE0, +0x0E00, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x001E, +0x003F, +0x00FF, +0x01FF, +0x01FF, +0x01FF, +0x007F, +0x003F, +0x001F, +0x007F, +0x00FF, +0x00FF, +0x007F, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0800, +0x0E60, +0x0FF0, +0x0FF0, +0x0FF8, +0x0FF8, +0x0FFC, +0x0FFC, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFC, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0003, +0x003F, +0x007F, +0x007F, +0x003F, +0x003F, +0x003F, +0x01FF, +0x03FF, +0x03FF, +0x01FF, +0x003F, +0x0007, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0C00, +0x0C00, +0x0E00, +0x0F18, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FE0, +0x0FE0, +0x0FE0, +0x01E0, +0x0000, +0x0000, + +0x0000, +0x000F, +0x000F, +0x001F, +0x001F, +0x001F, +0x03FF, +0x03FF, +0x03FF, +0x01FF, +0x00FF, +0x007F, +0x003F, +0x001F, +0x0007, +0x0003, +0x0001, +0x0000, + +0x0000, +0x0F00, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FF8, +0x0FF0, +0x0FE0, +0x0FC0, +0x0F80, +0x0F00, +0x0E00, +0x0C00, +0x0000, + +0x0000, +0x0003, +0x0003, +0x0007, +0x018F, +0x01FF, +0x01FF, +0x01FF, +0x00FF, +0x00FF, +0x00FF, +0x00FF, +0x007F, +0x007F, +0x007F, +0x0078, +0x0000, +0x0000, + +0x0000, +0x0C00, +0x0FC0, +0x0FE0, +0x0FE0, +0x0FC0, +0x0FC0, +0x0FC0, +0x0FF8, +0x0FFC, +0x0FFC, +0x0FF8, +0x0FC0, +0x0E00, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0001, +0x0067, +0x00FF, +0x00FF, +0x01FF, +0x01FF, +0x03FF, +0x03FF, +0x07FF, +0x07FF, +0x07FF, +0x03FF, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0780, +0x0FC0, +0x0FF0, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FE0, +0x0FC0, +0x0F80, +0x0FE0, +0x0FF0, +0x0FF0, +0x0FE0, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0018, +0x007F, +0x00FF, +0x01FF, +0x03FF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x03FF, +0x007F, +0x0007, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x03C0, +0x0FE0, +0x0FF8, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FE0, +0x0E00, +0x0E00, +0x0F00, +0x0F00, +0x0700, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0002, +0x001E, +0x007F, +0x03FF, +0x0FFF, +0x0FFF, +0x0FFF, +0x07FF, +0x03FF, +0x00FF, +0x007E, +0x003E, +0x000E, +0x0006, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0FF0, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x003F, +0x03FF, +0x03FF, +0x03FF, +0x01FF, +0x01FF, +0x00FF, +0x00FF, +0x00FF, +0x0078, +0x0070, +0x0020, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0C00, +0x0E00, +0x0E00, +0x0FF0, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FF8, +0x0FF8, +0x0FF8, +0x07F0, +0x00F0, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0070, +0x007F, +0x00FF, +0x00FF, +0x00FF, +0x01FF, +0x01FF, +0x01FF, +0x01FF, +0x01E7, +0x0181, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0F80, +0x0F80, +0x0F80, +0x0FE0, +0x0FF8, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FF8, +0x0FF0, +0x0FE0, +0x07C0, +0x0180, +0x0000, +0x0000, +0x0000, + +0x0000, +0x001F, +0x003F, +0x007F, +0x00FF, +0x01FF, +0x03FF, +0x03FF, +0x03FF, +0x030F, +0x000F, +0x0007, +0x0007, +0x0003, +0x0001, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0800, +0x0F80, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FC0, +0x0FE0, +0x0FF0, +0x0FF8, +0x0FF8, +0x0FF8, +0x0FF8, +0x0F80, +0x0C00, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0180, +0x03C0, +0x07E0, +0x07E0, +0x03C0, +0x0180, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0060, +0x00F0, +0x01F8, +0x03FC, +0x01F8, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x00F0, +0x01F8, +0x03FC, +0x01F8, +0x00F0, +0x0060, +0x0000, + +0x0000, +0x0100, +0x0380, +0x07C0, +0x0FF0, +0x0FF8, +0x07F8, +0x03BC, +0x013C, +0x013C, +0x033C, +0x07F8, +0x0FF8, +0x0FF0, +0x07C0, +0x0380, +0x0100, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x01F8, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, + +0x01F8, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, + +0x01F8, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, + +0x01F8, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, + +0x01F8, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, + +0x01F8, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, + +0x0000, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FE, +0x07FE, +0x07FE, +0x07FE, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, +0x0780, + +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x00F0, +0x01F8, +0x03FC, +0x07FE, +0x0F0F, +0x0F0F, +0x0F0F, +0x0F0F, +0x07FE, +0x03FC, +0x01F8, + +0x0000, +0x0F80, +0x0F80, +0x0FFF, +0x0FFF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x0787, +0x0787, +0x0787, +0x0787, +0x0787, + +0x0000, +0x0000, +0x0000, +0x0800, +0x0800, +0x0800, +0x0800, +0x081F, +0x081F, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0F9F, +0x0F9F, +0x0F80, +0x0F80, +0x0F80, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0060, +0x00F0, +0x00F0, +0x01F8, +0x01F8, +0x03FC, +0x03FC, +0x01F8, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0040, +0x00E0, +0x0EEF, +0x0FFF, +0x0EEF, +0x00E0, +0x0040, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x07DE, +0x07FE, +0x07FE, +0x0FFF, +0x0FFF, +0x0FFF, +0x07FE, +0x07BE, +0x079E, +0x030C, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x00F0, +0x01F8, +0x03FC, +0x03FC, +0x03C0, +0x0FFF, +0x0FFF, +0x0FFF, +0x03FC, +0x03FC, +0x03FC, +0x00F8, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x01F8, +0x03FC, +0x03FC, +0x03F8, +0x03C0, +0x0FFF, +0x0FFF, +0x0FFF, +0x03F0, +0x03FC, +0x03FC, +0x01F8, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x030C, +0x079E, +0x079E, +0x079E, +0x07FE, +0x0FFF, +0x0FFF, +0x0FFF, +0x03FC, +0x03FC, +0x03FC, +0x01F8, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0000, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0E0F, +0x0F1F, +0x0FBF, +0x03F8, +0x01F0, +0x00E0, +0x0040, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0070, +0x00F8, +0x0070, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x007F, +0x00FF, +0x007F, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x00E0, +0x01F0, +0x00E0, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FE0, +0x0FF0, +0x0FE0, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0780, +0x07FF, +0x07FF, +0x07FF, +0x07FF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x00F0, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0787, +0x0F80, +0x0F80, +0x0F80, +0x0F80, +0x0066, +0x00FF, +0x00FF, +0x00FF, +0x00FF, +0x00FF, +0x00FF, +0x007E, +0x003C, +0x0018, +0x0000, +0x0000, +0x0000, + +0x0F80, +0x0000, +0x0000, +0x0000, +0x0000, +0x0180, +0x03C0, +0x07C0, +0x07C0, +0x03C0, +0x03C0, +0x03C6, +0x07EF, +0x07EF, +0x03C6, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x03C0, +0x07E0, +0x0FF0, +0x0FF0, +0x07E0, +0x03F0, +0x0FF0, +0x0FF0, +0x07E0, +0x03C0, +0x0000, +0x0000, +0x0000, + +0x01F8, +0x03FC, +0x03FC, +0x01F8, +0x01F8, +0x00F0, +0x00F0, +0x0060, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, +0x000E, + +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, +0x0700, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, + +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x000E, +0x000F, +0x000F, +0x000F, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x000F, +0x000F, +0x000F, +0x000E, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0F00, +0x0F00, +0x0F00, +0x0700, + +0x0700, +0x0F00, +0x0F00, +0x0F00, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0070, +0x00F8, +0x0070, +0x0000, +0x0000, +0x0000, +0x0010, +0x0038, +0x003C, +0x003E, +0x003F, +0x003E, +0x003C, +0x0038, +0x0010, +0x0000, + +0x0000, +0x0000, +0x00E0, +0x01F0, +0x00E0, +0x0000, +0x0000, +0x0000, +0x0080, +0x01C0, +0x03C0, +0x07C0, +0x0FC0, +0x07C0, +0x03C0, +0x01C0, +0x0080, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0078, +0x0078, +0x0078, +0x007F, +0x007F, +0x007F, +0x007F, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x007F, +0x007F, +0x007F, +0x007F, +0x0078, +0x0078, +0x0078, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x01E0, +0x01E0, +0x01E0, + +0x01E0, +0x01E0, +0x01E0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0660, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FF4, +0x07EE, +0x07EE, +0x0FFE, +0x0FF4, +0x0FF4, +0x07EE, +0x07EE, +0x0FEE, +0x0FF4, +0x0FF0, +0x0FF0, +0x0FE0, +0x07C0, + +0x0040, +0x00E0, +0x00E0, +0x07FC, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFF, +0x0FFE, +0x0FFE, +0x07FE, +0x00FE, +0x01FE, +0x03FE, +0x07FE, +0x0FFE, +0x0FFF, +0x0556, + +0x0000, +0x0000, +0x0660, +0x0FF0, +0x0FF0, +0x0FF0, +0x07E6, +0x03CF, +0x018E, +0x03CE, +0x07EE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x066E, +0x000F, +0x0006, + +0x0000, +0x0000, +0x0660, +0x0FF0, +0x0FF0, +0x0FF0, +0x07E6, +0x03CF, +0x018E, +0x07CE, +0x0FEE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FEE, +0x07CE, +0x000F, +0x0006, + +0x0000, +0x0000, +0x03C0, +0x07E0, +0x0FC0, +0x0F00, +0x0FC6, +0x07EF, +0x03CE, +0x03CE, +0x07EE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FFE, +0x07EE, +0x000F, +0x0006, + +0x0000, +0x0000, +0x03C0, +0x07E0, +0x0FC0, +0x0F00, +0x0FC6, +0x07EF, +0x03CE, +0x07CE, +0x0FEE, +0x0FFE, +0x0FFE, +0x0FFE, +0x0FEE, +0x07CE, +0x000F, +0x0006, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, + +0x0660, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FF4, +0x07FE, +0x07FE, +0x0FFE, +0x0FF4, +0x0FF4, +0x0FFE, +0x067E, +0x0FFE, +0x0FF4, +0x0FF0, +0x07E0, +0x03C0, +0x0180, + +0x0000, +0x0000, +0x0000, +0x03FC, +0x07FE, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x07FE, +0x03FC, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0000, +0x0000, +0x03FC, +0x07FE, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x07FE, +0x03FC, +0x0000, +0x0000, +0x0000, + +0x0000, +0x0003, +0x0007, +0x0007, +0x0007, +0x0007, +0x0007, +0x0007, +0x0007, +0x0007, +0x0007, +0x0007, +0x0007, +0x0007, +0x0007, +0x0007, +0x0003, +0x0000, + +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, + +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFC, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, + +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FE0, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, + +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0F00, +0x0F00, +0x0F00, +0x0F00, +0x0F00, +0x0F00, +0x0F00, +0x0F00, +0x0F00, +0x0F00, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, + +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0FFF, +0x0FFF, +0x0FFF, +0x0000, + +0x0000, +0x0C00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0E00, +0x0C00, +0x0000, + +0x0000, +0x0FFE, +0x0FFF, +0x0FFF, +0x0F9F, +0x0FDF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FDF, +0x0F9F, +0x0FFF, +0x0FFF, +0x0FFE, +0x0000, + +0x0001, +0x0003, +0x0033, +0x007B, +0x007F, +0x003F, +0x001F, +0x00FC, +0x01FC, +0x01FC, +0x00FC, +0x001F, +0x003F, +0x007F, +0x007B, +0x0033, +0x0003, +0x0003, + +0x0800, +0x0C00, +0x0CC0, +0x0DE0, +0x0FE0, +0x0FC0, +0x0F80, +0x03F0, +0x03F8, +0x03F8, +0x03F0, +0x0F80, +0x0FC0, +0x0FE0, +0x0DE0, +0x0CC0, +0x0C00, +0x0800, + +0x0000, +0x0003, +0x000F, +0x001F, +0x003F, +0x007D, +0x0079, +0x00F1, +0x00F1, +0x00F1, +0x00F1, +0x0079, +0x007D, +0x003F, +0x001F, +0x000F, +0x0003, +0x0000, + +0x0000, +0x0C00, +0x0F00, +0x0F80, +0x0FC0, +0x0FE0, +0x0FE0, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FF0, +0x0FE0, +0x0FE0, +0x0FC0, +0x0F80, +0x0F00, +0x0C00, +0x0000, + +0x0006, +0x000F, +0x001F, +0x003F, +0x07FF, +0x0FF7, +0x0FE7, +0x0FE7, +0x0FE7, +0x0FE7, +0x0FE7, +0x0FF7, +0x07FF, +0x003F, +0x001F, +0x000F, +0x0006, +0x0000, + +0x0020, +0x0070, +0x0038, +0x01B8, +0x03F8, +0x05FC, +0x0FFC, +0x0FFC, +0x07FC, +0x0FFC, +0x0FFC, +0x05FC, +0x03F8, +0x01B8, +0x0038, +0x0070, +0x0020, +0x0000, + +0x07FE, +0x0FFF, +0x07FE, +0x07FE, +0x079E, +0x079E, +0x03FC, +0x01F8, +0x00F0, +0x00F0, +0x01F8, +0x03FC, +0x079E, +0x079E, +0x07FE, +0x07FE, +0x0FFF, +0x07FE, + +0x0000, +0x0300, +0x0380, +0x03C0, +0x03E0, +0x03F0, +0x03F8, +0x03FC, +0x03FE, +0x03FF, +0x03FF, +0x03FC, +0x03FC, +0x03FE, +0x003E, +0x003E, +0x003E, +0x0008, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0322, +0x07F7, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FF7, +0x0FF7, +0x0FF7, +0x0FF7, +0x04A2, + +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0000, +0x0722, +0x0FF7, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0F77, +0x0E77, +0x0E77, +0x0E77, +0x0422, + +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, +0x0FFF, + +}; + +#endif /* FONT12X18_H_ */ diff --git a/flight/targets/OSD/System/inc/font8x10.h b/flight/targets/OSD/System/inc/font8x10.h index 621cf13af..f199499de 100644 --- a/flight/targets/OSD/System/inc/font8x10.h +++ b/flight/targets/OSD/System/inc/font8x10.h @@ -1,5648 +1,5648 @@ -/* - * font8x10.h - * - * Created on: 3.1.2012 - * Author: Samba - */ - -#ifndef FONT8X10_H_ -#define FONT8X10_H_ - -static const uint8_t font_frame8x10[] = { -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x60, -0x10, -0x20, -0x4C, -0x7A, -0x0A, -0x0C, -0x00, -0x00, - -0x00, -0x60, -0x20, -0x60, -0x2C, -0x6A, -0x0A, -0x0C, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x10, -0x10, -0x10, -0x10, -0x10, -0x00, -0x10, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x28, -0x28, -0x7C, -0x28, -0x7C, -0x28, -0x28, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x7C, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x30, -0x30, -0x00, -0x00, - -0x00, -0x00, -0x04, -0x08, -0x10, -0x20, -0x40, -0x00, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x4C, -0x54, -0x64, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x10, -0x30, -0x10, -0x10, -0x10, -0x10, -0x38, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x04, -0x08, -0x10, -0x20, -0x7C, -0x00, -0x00, - -0x00, -0x7C, -0x08, -0x10, -0x08, -0x04, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x08, -0x18, -0x28, -0x48, -0x7C, -0x08, -0x08, -0x00, -0x00, - -0x00, -0x7C, -0x40, -0x78, -0x04, -0x04, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x18, -0x20, -0x40, -0x78, -0x44, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x7C, -0x04, -0x08, -0x10, -0x20, -0x20, -0x20, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x44, -0x38, -0x44, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x44, -0x3C, -0x04, -0x08, -0x30, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x30, -0x30, -0x00, -0x30, -0x30, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x7C, -0x00, -0x7C, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x04, -0x34, -0x54, -0x54, -0x38, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x44, -0x44, -0x7C, -0x44, -0x44, -0x00, -0x00, - -0x00, -0x78, -0x44, -0x44, -0x78, -0x44, -0x44, -0x78, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x40, -0x40, -0x40, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x70, -0x48, -0x44, -0x44, -0x44, -0x48, -0x70, -0x00, -0x00, - -0x00, -0x7C, -0x40, -0x40, -0x78, -0x40, -0x40, -0x7C, -0x00, -0x00, - -0x00, -0x7C, -0x40, -0x40, -0x78, -0x40, -0x40, -0x40, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x40, -0x58, -0x44, -0x44, -0x3C, -0x00, -0x00, - -0x00, -0x44, -0x44, -0x44, -0x7C, -0x44, -0x44, -0x44, -0x00, -0x00, - -0x00, -0x38, -0x10, -0x10, -0x10, -0x10, -0x10, -0x38, -0x00, -0x00, - -0x00, -0x1C, -0x08, -0x08, -0x08, -0x08, -0x48, -0x30, -0x00, -0x00, - -0x00, -0x44, -0x48, -0x50, -0x60, -0x50, -0x48, -0x44, -0x00, -0x00, - -0x00, -0x40, -0x40, -0x40, -0x40, -0x40, -0x40, -0x7C, -0x00, -0x00, - -0x00, -0x44, -0x6C, -0x54, -0x54, -0x44, -0x44, -0x44, -0x00, -0x00, - -0x00, -0x44, -0x44, -0x64, -0x54, -0x4C, -0x44, -0x44, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x44, -0x44, -0x44, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x78, -0x44, -0x44, -0x78, -0x40, -0x40, -0x40, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x44, -0x44, -0x54, -0x48, -0x34, -0x00, -0x00, - -0x00, -0x78, -0x44, -0x44, -0x78, -0x50, -0x48, -0x44, -0x00, -0x00, - -0x00, -0x38, -0x44, -0x40, -0x38, -0x04, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x7C, -0x10, -0x10, -0x10, -0x10, -0x10, -0x10, -0x00, -0x00, - -0x00, -0x44, -0x44, -0x44, -0x44, -0x44, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x44, -0x44, -0x44, -0x44, -0x44, -0x28, -0x10, -0x00, -0x00, - -0x00, -0x44, -0x44, -0x44, -0x54, -0x54, -0x54, -0x28, -0x00, -0x00, - -0x00, -0x44, -0x44, -0x28, -0x10, -0x28, -0x44, -0x44, -0x00, -0x00, - -0x00, -0x44, -0x44, -0x44, -0x28, -0x10, -0x10, -0x10, -0x00, -0x00, - -0x00, -0x7C, -0x04, -0x08, -0x10, -0x20, -0x40, -0x7C, -0x00, -0x00, - -0x00, -0x38, -0x20, -0x20, -0x20, -0x20, -0x20, -0x38, -0x00, -0x00, - -0x00, -0x00, -0x40, -0x20, -0x10, -0x08, -0x04, -0x00, -0x00, -0x00, - -0x00, -0x38, -0x08, -0x08, -0x08, -0x08, -0x08, -0x38, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x38, -0x04, -0x3C, -0x44, -0x3C, -0x00, -0x00, - -0x00, -0x40, -0x40, -0x40, -0x78, -0x44, -0x44, -0x78, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x3C, -0x40, -0x40, -0x40, -0x3C, -0x00, -0x00, - -0x00, -0x04, -0x04, -0x04, -0x3C, -0x44, -0x44, -0x3C, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x38, -0x44, -0x7C, -0x40, -0x3C, -0x00, -0x00, - -0x00, -0x08, -0x14, -0x10, -0x7C, -0x10, -0x10, -0x10, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x3C, -0x44, -0x3C, -0x04, -0x78, -0x00, -0x00, - -0x00, -0x40, -0x40, -0x40, -0x78, -0x44, -0x44, -0x44, -0x00, -0x00, - -0x00, -0x00, -0x10, -0x00, -0x10, -0x10, -0x10, -0x10, -0x00, -0x00, - -0x00, -0x08, -0x00, -0x08, -0x08, -0x08, -0x48, -0x30, -0x00, -0x00, - -0x00, -0x20, -0x20, -0x24, -0x28, -0x30, -0x28, -0x24, -0x00, -0x00, - -0x00, -0x30, -0x10, -0x10, -0x10, -0x10, -0x10, -0x38, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x68, -0x54, -0x54, -0x44, -0x44, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x58, -0x64, -0x44, -0x44, -0x44, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x38, -0x44, -0x44, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x78, -0x44, -0x78, -0x40, -0x40, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x3C, -0x44, -0x3C, -0x04, -0x04, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x58, -0x64, -0x40, -0x40, -0x40, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x3C, -0x40, -0x38, -0x04, -0x78, -0x00, -0x00, - -0x00, -0x10, -0x10, -0x7C, -0x10, -0x10, -0x14, -0x08, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x44, -0x44, -0x44, -0x44, -0x38, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x44, -0x44, -0x44, -0x28, -0x10, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x44, -0x44, -0x54, -0x54, -0x28, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x44, -0x28, -0x10, -0x28, -0x44, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x44, -0x28, -0x10, -0x10, -0x20, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x7C, -0x08, -0x10, -0x20, -0x7C, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x10, -0x10, -0x10, -0x10, -0x10, -0x10, -0x10, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x38, -0x54, -0x54, -0x54, -0x44, -0x54, -0x44, -0x7C, -0x00, - -0x00, -0x38, -0x44, -0x44, -0x44, -0x44, -0x44, -0x44, -0x7C, -0x00, - -0x00, -0x38, -0x44, -0x44, -0x44, -0x44, -0x7C, -0x7C, -0x7C, -0x00, - -0x00, -0x38, -0x44, -0x44, -0x7C, -0x7C, -0x7C, -0x7C, -0x7C, -0x00, - -0x00, -0x38, -0x44, -0x7C, -0x7C, -0x7C, -0x7C, -0x7C, -0x7C, -0x00, - -0x00, -0x38, -0x7C, -0x7C, -0x7C, -0x7C, -0x7C, -0x7C, -0x7C, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0xFF, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x18, -0x18, -0xFF, -0x18, -0x18, -0x00, -0x00, - -0x00, -0x42, -0x42, -0x62, -0x52, -0xCB, -0x46, -0x42, -0x42, -0x00, - -0x00, -0x3C, -0x42, -0x40, -0x30, -0xCF, -0x02, -0x42, -0x3C, -0x00, - -0x00, -0x3E, -0x20, -0x20, -0x38, -0xA3, -0x20, -0x20, -0x3E, -0x00, - -0x00, -0x42, -0x42, -0x42, -0x42, -0xDB, -0x5A, -0x5A, -0x24, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x81, -0x42, -0x24, -0x18, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x18, -0x7E, -0x5E, -0x9F, -0x8F, -0x4E, -0x6E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0x9F, -0x8F, -0x46, -0x66, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0x8F, -0x42, -0x66, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xF1, -0x42, -0x66, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xF9, -0xF1, -0x62, -0x66, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7A, -0xF9, -0xF1, -0x72, -0x76, -0x18, -0x00, - -0x00, -0x18, -0x76, -0x72, -0xF1, -0xF9, -0x7A, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x66, -0x62, -0xF1, -0xF9, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x66, -0x42, -0xF1, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x66, -0x42, -0x8F, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x66, -0x46, -0x8F, -0x9F, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x6E, -0x4E, -0x8F, -0x9F, -0x5E, -0x7E, -0x18, -0x00, - -0x00, -0x07, -0x06, -0x04, -0x44, -0x3C, -0x3C, -0x24, -0x24, -0x00, - -0x00, -0xE0, -0x60, -0x20, -0x22, -0x3C, -0x3C, -0x24, -0x24, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -}; -static const uint8_t font_mask8x10[] = { -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0xF0, -0xF8, -0xFC, -0xFE, -0xFF, -0xFF, -0x7F, -0x3F, -0x1F, -0x00, - -0xF0, -0xF8, -0xFC, -0xFE, -0xFF, -0xFF, -0xFF, -0x3F, -0x1F, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x10, -0x38, -0x38, -0x38, -0x38, -0x38, -0x10, -0x38, -0x10, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x28, -0x7C, -0x7C, -0xFE, -0x7C, -0xFE, -0x7C, -0x7C, -0x28, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x7C, -0xFE, -0x7C, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x30, -0x78, -0x78, -0x30, -0x00, - -0x00, -0x04, -0x0E, -0x1C, -0x38, -0x70, -0xE0, -0x40, -0x00, -0x00, - -0x38, -0x7C, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0x7C, -0x38, -0x00, - -0x10, -0x38, -0x78, -0x38, -0x38, -0x38, -0x38, -0x7C, -0x38, -0x00, - -0x38, -0x7C, -0xFE, -0x4E, -0x1C, -0x38, -0x7C, -0xFE, -0x7C, -0x00, - -0x7C, -0xFE, -0x7C, -0x38, -0x1C, -0x4E, -0xFE, -0x7C, -0x38, -0x00, - -0x08, -0x1C, -0x3C, -0x7C, -0xFC, -0xFE, -0x7C, -0x1C, -0x08, -0x00, - -0x7C, -0xFE, -0xFC, -0xFC, -0x7E, -0x4E, -0xFE, -0x7C, -0x38, -0x00, - -0x18, -0x3C, -0x78, -0xF8, -0xFC, -0xFE, -0xFE, -0x7C, -0x38, -0x00, - -0x7C, -0xFE, -0x7E, -0x1C, -0x38, -0x70, -0x70, -0x70, -0x20, -0x00, - -0x38, -0x7C, -0xFE, -0xFE, -0x7C, -0xFE, -0xFE, -0x7C, -0x38, -0x00, - -0x38, -0x7C, -0xFE, -0xFE, -0x7E, -0x3E, -0x3C, -0x78, -0x30, -0x00, - -0x00, -0x00, -0x30, -0x78, -0x78, -0x30, -0x78, -0x78, -0x30, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x7C, -0xFE, -0x7C, -0xFE, -0x7C, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x38, -0x7C, -0xFE, -0x7E, -0x7E, -0xFE, -0xFE, -0x7C, -0x38, -0x00, - -0x38, -0x7C, -0xFE, -0xEE, -0xFE, -0xFE, -0xFE, -0xEE, -0x44, -0x00, - -0x78, -0xFC, -0xFE, -0xFE, -0xFC, -0xFE, -0xFE, -0xFC, -0x78, -0x00, - -0x38, -0x7C, -0xFE, -0xE4, -0xE0, -0xE4, -0xFE, -0x7C, -0x38, -0x00, - -0x70, -0xF8, -0xFC, -0xEE, -0xEE, -0xEE, -0xFC, -0xF8, -0x70, -0x00, - -0x7C, -0xFE, -0xFC, -0xF8, -0xFC, -0xF8, -0xFC, -0xFE, -0x7C, -0x00, - -0x7C, -0xFE, -0xFC, -0xF8, -0xFC, -0xF8, -0xE0, -0xE0, -0x40, -0x00, - -0x38, -0x7C, -0xFE, -0xFC, -0xFC, -0xFE, -0xFE, -0x7E, -0x3C, -0x00, - -0x44, -0xEE, -0xEE, -0xFE, -0xFE, -0xFE, -0xEE, -0xEE, -0x44, -0x00, - -0x38, -0x7C, -0x38, -0x38, -0x38, -0x38, -0x38, -0x7C, -0x38, -0x00, - -0x1C, -0x3E, -0x1C, -0x1C, -0x1C, -0x5C, -0xFC, -0x78, -0x30, -0x00, - -0x44, -0xEE, -0xFC, -0xF8, -0xF0, -0xF8, -0xFC, -0xEE, -0x44, -0x00, - -0x40, -0xE0, -0xE0, -0xE0, -0xE0, -0xE0, -0xFC, -0xFE, -0x7C, -0x00, - -0x44, -0xEE, -0xFE, -0xFE, -0xFE, -0xFE, -0xEE, -0xEE, -0x44, -0x00, - -0x44, -0xEE, -0xEE, -0xFE, -0xFE, -0xFE, -0xEE, -0xEE, -0x44, -0x00, - -0x38, -0x7C, -0xFE, -0xEE, -0xEE, -0xEE, -0xFE, -0x7C, -0x38, -0x00, - -0x78, -0xFC, -0xFE, -0xFE, -0xFC, -0xF8, -0xE0, -0xE0, -0x40, -0x00, - -0x38, -0x7C, -0xFE, -0xEE, -0xEE, -0xFE, -0xFC, -0x7E, -0x34, -0x00, - -0x78, -0xFC, -0xFE, -0xFE, -0xFC, -0xF8, -0xFC, -0xEE, -0x44, -0x00, - -0x38, -0x7C, -0xFE, -0xFC, -0x7C, -0x7E, -0xFE, -0x7C, -0x38, -0x00, - -0x7C, -0xFE, -0x7C, -0x38, -0x38, -0x38, -0x38, -0x38, -0x10, -0x00, - -0x44, -0xEE, -0xEE, -0xEE, -0xEE, -0xEE, -0xFE, -0x7C, -0x38, -0x00, - -0x44, -0xEE, -0xEE, -0xEE, -0xEE, -0xEE, -0x7C, -0x38, -0x10, -0x00, - -0x44, -0xEE, -0xEE, -0xFE, -0xFE, -0xFE, -0xFE, -0x7C, -0x28, -0x00, - -0x44, -0xEE, -0xEE, -0x7C, -0x38, -0x7C, -0xEE, -0xEE, -0x44, -0x00, - -0x44, -0xEE, -0xEE, -0xEE, -0x7C, -0x38, -0x38, -0x38, -0x10, -0x00, - -0x7C, -0xFE, -0x7E, -0x1C, -0x38, -0x70, -0xFC, -0xFE, -0x7C, -0x00, - -0x38, -0x7C, -0x78, -0x70, -0x70, -0x70, -0x78, -0x7C, -0x38, -0x00, - -0x00, -0x40, -0xE0, -0x70, -0x38, -0x1C, -0x0E, -0x04, -0x00, -0x00, - -0x38, -0x7C, -0x3C, -0x1C, -0x1C, -0x1C, -0x3C, -0x7C, -0x38, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x38, -0x7C, -0x3E, -0x7E, -0xFE, -0x7E, -0x3C, -0x00, - -0x40, -0xE0, -0xE0, -0xF8, -0xFC, -0xFE, -0xFE, -0xFC, -0x78, -0x00, - -0x00, -0x00, -0x3C, -0x7E, -0xFC, -0xE0, -0xFC, -0x7E, -0x3C, -0x00, - -0x04, -0x0E, -0x0E, -0x3E, -0x7E, -0xFE, -0xFE, -0x7E, -0x3C, -0x00, - -0x00, -0x00, -0x38, -0x7C, -0xFE, -0xFE, -0xFC, -0x7E, -0x3C, -0x00, - -0x08, -0x1C, -0x3E, -0x7C, -0xFE, -0x7C, -0x38, -0x38, -0x10, -0x00, - -0x00, -0x00, -0x3C, -0x7E, -0xFE, -0x7E, -0x7E, -0xFC, -0x78, -0x00, - -0x40, -0xE0, -0xE0, -0xF8, -0xFC, -0xFE, -0xEE, -0xEE, -0x44, -0x00, - -0x00, -0x10, -0x38, -0x10, -0x38, -0x38, -0x38, -0x38, -0x10, -0x00, - -0x08, -0x1C, -0x08, -0x1C, -0x1C, -0x5C, -0xFC, -0x78, -0x30, -0x00, - -0x20, -0x70, -0x74, -0x7E, -0x7C, -0x78, -0x7C, -0x7E, -0x24, -0x00, - -0x30, -0x78, -0x38, -0x38, -0x38, -0x38, -0x38, -0x7C, -0x38, -0x00, - -0x00, -0x00, -0x68, -0xFC, -0xFE, -0xFE, -0xFE, -0xEE, -0x6C, -0x00, - -0x00, -0x00, -0x58, -0xFC, -0xFE, -0xEE, -0xEE, -0xEE, -0x44, -0x00, - -0x00, -0x00, -0x38, -0x7C, -0xFE, -0xEE, -0xFE, -0x7C, -0x38, -0x00, - -0x00, -0x00, -0x78, -0xFC, -0xFE, -0xFC, -0xF8, -0xE0, -0x40, -0x00, - -0x00, -0x00, -0x3C, -0x7E, -0xFE, -0x7E, -0x3E, -0x0E, -0x04, -0x00, - -0x00, -0x00, -0x58, -0xFC, -0xFE, -0xE4, -0xE0, -0xE0, -0x40, -0x00, - -0x00, -0x00, -0x3C, -0x7E, -0xFC, -0x7C, -0x7E, -0xFC, -0x78, -0x00, - -0x10, -0x38, -0x7C, -0xFE, -0x7C, -0x3C, -0x3E, -0x1C, -0x08, -0x00, - -0x00, -0x00, -0x44, -0xEE, -0xEE, -0xEE, -0xFE, -0x7C, -0x38, -0x00, - -0x00, -0x00, -0x44, -0xEE, -0xEE, -0xEE, -0x7C, -0x38, -0x10, -0x00, - -0x00, -0x00, -0x44, -0xEE, -0xFE, -0xFE, -0xFE, -0x7C, -0x28, -0x00, - -0x00, -0x00, -0x44, -0xEE, -0x7C, -0x38, -0x7C, -0xEE, -0x44, -0x00, - -0x00, -0x00, -0x44, -0xEE, -0x7C, -0x38, -0x38, -0x70, -0x20, -0x00, - -0x00, -0x00, -0x7C, -0xFE, -0x7C, -0x38, -0x7C, -0xFE, -0x7C, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x10, -0x38, -0x38, -0x38, -0x38, -0x38, -0x38, -0x38, -0x10, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x38, -0x7C, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0x7C, - -0x38, -0x7C, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0x7C, - -0x38, -0x7C, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0x7C, - -0x38, -0x7C, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0x7C, - -0x38, -0x7C, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0x7C, - -0x38, -0x7C, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0xFE, -0x7C, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0xFF, -0xFF, -0xFF, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x18, -0x3C, -0xFF, -0xFF, -0xFF, -0x3C, -0x18, -0x00, - -0x42, -0xE7, -0xE7, -0xF7, -0xFF, -0xFF, -0xEF, -0xE7, -0xE7, -0x42, - -0x3C, -0x7E, -0xFF, -0xF2, -0xFD, -0xFF, -0xCF, -0xFF, -0x7E, -0x3C, - -0x3E, -0x7F, -0x7E, -0x78, -0xFF, -0xFF, -0xF3, -0x7E, -0x7F, -0x3E, - -0x42, -0xE7, -0xE7, -0xE7, -0xFF, -0xFF, -0xFF, -0xFF, -0x7E, -0x24, - -0x00, -0x00, -0x00, -0x00, -0xFF, -0x00, -0xFF, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x81, -0xC3, -0xE7, -0x7E, -0x3C, -0x18, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x00, -0x18, -0x7E, -0x7E, -0xFF, -0xFF, -0x7E, -0x7E, -0x18, -0x00, - -0x07, -0x0F, -0x0F, -0x4E, -0xFE, -0x7E, -0x7E, -0x7E, -0x7E, -0x24, - -0xE0, -0xF0, -0xF0, -0x72, -0x7F, -0x7E, -0x7E, -0x7E, -0x7E, -0x24, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, -0x00, - -}; - -#endif /* FONT8X10_H_ */ +/* + * font8x10.h + * + * Created on: 3.1.2012 + * Author: Samba + */ + +#ifndef FONT8X10_H_ +#define FONT8X10_H_ + +static const uint8_t font_frame8x10[] = { +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x60, +0x10, +0x20, +0x4C, +0x7A, +0x0A, +0x0C, +0x00, +0x00, + +0x00, +0x60, +0x20, +0x60, +0x2C, +0x6A, +0x0A, +0x0C, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x10, +0x10, +0x10, +0x10, +0x10, +0x00, +0x10, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x28, +0x28, +0x7C, +0x28, +0x7C, +0x28, +0x28, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x7C, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x30, +0x30, +0x00, +0x00, + +0x00, +0x00, +0x04, +0x08, +0x10, +0x20, +0x40, +0x00, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x4C, +0x54, +0x64, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x10, +0x30, +0x10, +0x10, +0x10, +0x10, +0x38, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x04, +0x08, +0x10, +0x20, +0x7C, +0x00, +0x00, + +0x00, +0x7C, +0x08, +0x10, +0x08, +0x04, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x08, +0x18, +0x28, +0x48, +0x7C, +0x08, +0x08, +0x00, +0x00, + +0x00, +0x7C, +0x40, +0x78, +0x04, +0x04, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x18, +0x20, +0x40, +0x78, +0x44, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x7C, +0x04, +0x08, +0x10, +0x20, +0x20, +0x20, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x44, +0x38, +0x44, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x44, +0x3C, +0x04, +0x08, +0x30, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x30, +0x30, +0x00, +0x30, +0x30, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x7C, +0x00, +0x7C, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x04, +0x34, +0x54, +0x54, +0x38, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x44, +0x44, +0x7C, +0x44, +0x44, +0x00, +0x00, + +0x00, +0x78, +0x44, +0x44, +0x78, +0x44, +0x44, +0x78, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x40, +0x40, +0x40, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x70, +0x48, +0x44, +0x44, +0x44, +0x48, +0x70, +0x00, +0x00, + +0x00, +0x7C, +0x40, +0x40, +0x78, +0x40, +0x40, +0x7C, +0x00, +0x00, + +0x00, +0x7C, +0x40, +0x40, +0x78, +0x40, +0x40, +0x40, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x40, +0x58, +0x44, +0x44, +0x3C, +0x00, +0x00, + +0x00, +0x44, +0x44, +0x44, +0x7C, +0x44, +0x44, +0x44, +0x00, +0x00, + +0x00, +0x38, +0x10, +0x10, +0x10, +0x10, +0x10, +0x38, +0x00, +0x00, + +0x00, +0x1C, +0x08, +0x08, +0x08, +0x08, +0x48, +0x30, +0x00, +0x00, + +0x00, +0x44, +0x48, +0x50, +0x60, +0x50, +0x48, +0x44, +0x00, +0x00, + +0x00, +0x40, +0x40, +0x40, +0x40, +0x40, +0x40, +0x7C, +0x00, +0x00, + +0x00, +0x44, +0x6C, +0x54, +0x54, +0x44, +0x44, +0x44, +0x00, +0x00, + +0x00, +0x44, +0x44, +0x64, +0x54, +0x4C, +0x44, +0x44, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x44, +0x44, +0x44, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x78, +0x44, +0x44, +0x78, +0x40, +0x40, +0x40, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x44, +0x44, +0x54, +0x48, +0x34, +0x00, +0x00, + +0x00, +0x78, +0x44, +0x44, +0x78, +0x50, +0x48, +0x44, +0x00, +0x00, + +0x00, +0x38, +0x44, +0x40, +0x38, +0x04, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x7C, +0x10, +0x10, +0x10, +0x10, +0x10, +0x10, +0x00, +0x00, + +0x00, +0x44, +0x44, +0x44, +0x44, +0x44, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x44, +0x44, +0x44, +0x44, +0x44, +0x28, +0x10, +0x00, +0x00, + +0x00, +0x44, +0x44, +0x44, +0x54, +0x54, +0x54, +0x28, +0x00, +0x00, + +0x00, +0x44, +0x44, +0x28, +0x10, +0x28, +0x44, +0x44, +0x00, +0x00, + +0x00, +0x44, +0x44, +0x44, +0x28, +0x10, +0x10, +0x10, +0x00, +0x00, + +0x00, +0x7C, +0x04, +0x08, +0x10, +0x20, +0x40, +0x7C, +0x00, +0x00, + +0x00, +0x38, +0x20, +0x20, +0x20, +0x20, +0x20, +0x38, +0x00, +0x00, + +0x00, +0x00, +0x40, +0x20, +0x10, +0x08, +0x04, +0x00, +0x00, +0x00, + +0x00, +0x38, +0x08, +0x08, +0x08, +0x08, +0x08, +0x38, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x38, +0x04, +0x3C, +0x44, +0x3C, +0x00, +0x00, + +0x00, +0x40, +0x40, +0x40, +0x78, +0x44, +0x44, +0x78, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x3C, +0x40, +0x40, +0x40, +0x3C, +0x00, +0x00, + +0x00, +0x04, +0x04, +0x04, +0x3C, +0x44, +0x44, +0x3C, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x38, +0x44, +0x7C, +0x40, +0x3C, +0x00, +0x00, + +0x00, +0x08, +0x14, +0x10, +0x7C, +0x10, +0x10, +0x10, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x3C, +0x44, +0x3C, +0x04, +0x78, +0x00, +0x00, + +0x00, +0x40, +0x40, +0x40, +0x78, +0x44, +0x44, +0x44, +0x00, +0x00, + +0x00, +0x00, +0x10, +0x00, +0x10, +0x10, +0x10, +0x10, +0x00, +0x00, + +0x00, +0x08, +0x00, +0x08, +0x08, +0x08, +0x48, +0x30, +0x00, +0x00, + +0x00, +0x20, +0x20, +0x24, +0x28, +0x30, +0x28, +0x24, +0x00, +0x00, + +0x00, +0x30, +0x10, +0x10, +0x10, +0x10, +0x10, +0x38, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x68, +0x54, +0x54, +0x44, +0x44, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x58, +0x64, +0x44, +0x44, +0x44, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x38, +0x44, +0x44, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x78, +0x44, +0x78, +0x40, +0x40, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x3C, +0x44, +0x3C, +0x04, +0x04, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x58, +0x64, +0x40, +0x40, +0x40, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x3C, +0x40, +0x38, +0x04, +0x78, +0x00, +0x00, + +0x00, +0x10, +0x10, +0x7C, +0x10, +0x10, +0x14, +0x08, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x44, +0x44, +0x44, +0x44, +0x38, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x44, +0x44, +0x44, +0x28, +0x10, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x44, +0x44, +0x54, +0x54, +0x28, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x44, +0x28, +0x10, +0x28, +0x44, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x44, +0x28, +0x10, +0x10, +0x20, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x7C, +0x08, +0x10, +0x20, +0x7C, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x10, +0x10, +0x10, +0x10, +0x10, +0x10, +0x10, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x38, +0x54, +0x54, +0x54, +0x44, +0x54, +0x44, +0x7C, +0x00, + +0x00, +0x38, +0x44, +0x44, +0x44, +0x44, +0x44, +0x44, +0x7C, +0x00, + +0x00, +0x38, +0x44, +0x44, +0x44, +0x44, +0x7C, +0x7C, +0x7C, +0x00, + +0x00, +0x38, +0x44, +0x44, +0x7C, +0x7C, +0x7C, +0x7C, +0x7C, +0x00, + +0x00, +0x38, +0x44, +0x7C, +0x7C, +0x7C, +0x7C, +0x7C, +0x7C, +0x00, + +0x00, +0x38, +0x7C, +0x7C, +0x7C, +0x7C, +0x7C, +0x7C, +0x7C, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0xFF, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x18, +0x18, +0xFF, +0x18, +0x18, +0x00, +0x00, + +0x00, +0x42, +0x42, +0x62, +0x52, +0xCB, +0x46, +0x42, +0x42, +0x00, + +0x00, +0x3C, +0x42, +0x40, +0x30, +0xCF, +0x02, +0x42, +0x3C, +0x00, + +0x00, +0x3E, +0x20, +0x20, +0x38, +0xA3, +0x20, +0x20, +0x3E, +0x00, + +0x00, +0x42, +0x42, +0x42, +0x42, +0xDB, +0x5A, +0x5A, +0x24, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x81, +0x42, +0x24, +0x18, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x18, +0x7E, +0x5E, +0x9F, +0x8F, +0x4E, +0x6E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0x9F, +0x8F, +0x46, +0x66, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0x8F, +0x42, +0x66, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xF1, +0x42, +0x66, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xF9, +0xF1, +0x62, +0x66, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7A, +0xF9, +0xF1, +0x72, +0x76, +0x18, +0x00, + +0x00, +0x18, +0x76, +0x72, +0xF1, +0xF9, +0x7A, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x66, +0x62, +0xF1, +0xF9, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x66, +0x42, +0xF1, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x66, +0x42, +0x8F, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x66, +0x46, +0x8F, +0x9F, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x6E, +0x4E, +0x8F, +0x9F, +0x5E, +0x7E, +0x18, +0x00, + +0x00, +0x07, +0x06, +0x04, +0x44, +0x3C, +0x3C, +0x24, +0x24, +0x00, + +0x00, +0xE0, +0x60, +0x20, +0x22, +0x3C, +0x3C, +0x24, +0x24, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +}; +static const uint8_t font_mask8x10[] = { +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0xF0, +0xF8, +0xFC, +0xFE, +0xFF, +0xFF, +0x7F, +0x3F, +0x1F, +0x00, + +0xF0, +0xF8, +0xFC, +0xFE, +0xFF, +0xFF, +0xFF, +0x3F, +0x1F, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x10, +0x38, +0x38, +0x38, +0x38, +0x38, +0x10, +0x38, +0x10, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x28, +0x7C, +0x7C, +0xFE, +0x7C, +0xFE, +0x7C, +0x7C, +0x28, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x7C, +0xFE, +0x7C, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x30, +0x78, +0x78, +0x30, +0x00, + +0x00, +0x04, +0x0E, +0x1C, +0x38, +0x70, +0xE0, +0x40, +0x00, +0x00, + +0x38, +0x7C, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0x7C, +0x38, +0x00, + +0x10, +0x38, +0x78, +0x38, +0x38, +0x38, +0x38, +0x7C, +0x38, +0x00, + +0x38, +0x7C, +0xFE, +0x4E, +0x1C, +0x38, +0x7C, +0xFE, +0x7C, +0x00, + +0x7C, +0xFE, +0x7C, +0x38, +0x1C, +0x4E, +0xFE, +0x7C, +0x38, +0x00, + +0x08, +0x1C, +0x3C, +0x7C, +0xFC, +0xFE, +0x7C, +0x1C, +0x08, +0x00, + +0x7C, +0xFE, +0xFC, +0xFC, +0x7E, +0x4E, +0xFE, +0x7C, +0x38, +0x00, + +0x18, +0x3C, +0x78, +0xF8, +0xFC, +0xFE, +0xFE, +0x7C, +0x38, +0x00, + +0x7C, +0xFE, +0x7E, +0x1C, +0x38, +0x70, +0x70, +0x70, +0x20, +0x00, + +0x38, +0x7C, +0xFE, +0xFE, +0x7C, +0xFE, +0xFE, +0x7C, +0x38, +0x00, + +0x38, +0x7C, +0xFE, +0xFE, +0x7E, +0x3E, +0x3C, +0x78, +0x30, +0x00, + +0x00, +0x00, +0x30, +0x78, +0x78, +0x30, +0x78, +0x78, +0x30, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x7C, +0xFE, +0x7C, +0xFE, +0x7C, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x38, +0x7C, +0xFE, +0x7E, +0x7E, +0xFE, +0xFE, +0x7C, +0x38, +0x00, + +0x38, +0x7C, +0xFE, +0xEE, +0xFE, +0xFE, +0xFE, +0xEE, +0x44, +0x00, + +0x78, +0xFC, +0xFE, +0xFE, +0xFC, +0xFE, +0xFE, +0xFC, +0x78, +0x00, + +0x38, +0x7C, +0xFE, +0xE4, +0xE0, +0xE4, +0xFE, +0x7C, +0x38, +0x00, + +0x70, +0xF8, +0xFC, +0xEE, +0xEE, +0xEE, +0xFC, +0xF8, +0x70, +0x00, + +0x7C, +0xFE, +0xFC, +0xF8, +0xFC, +0xF8, +0xFC, +0xFE, +0x7C, +0x00, + +0x7C, +0xFE, +0xFC, +0xF8, +0xFC, +0xF8, +0xE0, +0xE0, +0x40, +0x00, + +0x38, +0x7C, +0xFE, +0xFC, +0xFC, +0xFE, +0xFE, +0x7E, +0x3C, +0x00, + +0x44, +0xEE, +0xEE, +0xFE, +0xFE, +0xFE, +0xEE, +0xEE, +0x44, +0x00, + +0x38, +0x7C, +0x38, +0x38, +0x38, +0x38, +0x38, +0x7C, +0x38, +0x00, + +0x1C, +0x3E, +0x1C, +0x1C, +0x1C, +0x5C, +0xFC, +0x78, +0x30, +0x00, + +0x44, +0xEE, +0xFC, +0xF8, +0xF0, +0xF8, +0xFC, +0xEE, +0x44, +0x00, + +0x40, +0xE0, +0xE0, +0xE0, +0xE0, +0xE0, +0xFC, +0xFE, +0x7C, +0x00, + +0x44, +0xEE, +0xFE, +0xFE, +0xFE, +0xFE, +0xEE, +0xEE, +0x44, +0x00, + +0x44, +0xEE, +0xEE, +0xFE, +0xFE, +0xFE, +0xEE, +0xEE, +0x44, +0x00, + +0x38, +0x7C, +0xFE, +0xEE, +0xEE, +0xEE, +0xFE, +0x7C, +0x38, +0x00, + +0x78, +0xFC, +0xFE, +0xFE, +0xFC, +0xF8, +0xE0, +0xE0, +0x40, +0x00, + +0x38, +0x7C, +0xFE, +0xEE, +0xEE, +0xFE, +0xFC, +0x7E, +0x34, +0x00, + +0x78, +0xFC, +0xFE, +0xFE, +0xFC, +0xF8, +0xFC, +0xEE, +0x44, +0x00, + +0x38, +0x7C, +0xFE, +0xFC, +0x7C, +0x7E, +0xFE, +0x7C, +0x38, +0x00, + +0x7C, +0xFE, +0x7C, +0x38, +0x38, +0x38, +0x38, +0x38, +0x10, +0x00, + +0x44, +0xEE, +0xEE, +0xEE, +0xEE, +0xEE, +0xFE, +0x7C, +0x38, +0x00, + +0x44, +0xEE, +0xEE, +0xEE, +0xEE, +0xEE, +0x7C, +0x38, +0x10, +0x00, + +0x44, +0xEE, +0xEE, +0xFE, +0xFE, +0xFE, +0xFE, +0x7C, +0x28, +0x00, + +0x44, +0xEE, +0xEE, +0x7C, +0x38, +0x7C, +0xEE, +0xEE, +0x44, +0x00, + +0x44, +0xEE, +0xEE, +0xEE, +0x7C, +0x38, +0x38, +0x38, +0x10, +0x00, + +0x7C, +0xFE, +0x7E, +0x1C, +0x38, +0x70, +0xFC, +0xFE, +0x7C, +0x00, + +0x38, +0x7C, +0x78, +0x70, +0x70, +0x70, +0x78, +0x7C, +0x38, +0x00, + +0x00, +0x40, +0xE0, +0x70, +0x38, +0x1C, +0x0E, +0x04, +0x00, +0x00, + +0x38, +0x7C, +0x3C, +0x1C, +0x1C, +0x1C, +0x3C, +0x7C, +0x38, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x38, +0x7C, +0x3E, +0x7E, +0xFE, +0x7E, +0x3C, +0x00, + +0x40, +0xE0, +0xE0, +0xF8, +0xFC, +0xFE, +0xFE, +0xFC, +0x78, +0x00, + +0x00, +0x00, +0x3C, +0x7E, +0xFC, +0xE0, +0xFC, +0x7E, +0x3C, +0x00, + +0x04, +0x0E, +0x0E, +0x3E, +0x7E, +0xFE, +0xFE, +0x7E, +0x3C, +0x00, + +0x00, +0x00, +0x38, +0x7C, +0xFE, +0xFE, +0xFC, +0x7E, +0x3C, +0x00, + +0x08, +0x1C, +0x3E, +0x7C, +0xFE, +0x7C, +0x38, +0x38, +0x10, +0x00, + +0x00, +0x00, +0x3C, +0x7E, +0xFE, +0x7E, +0x7E, +0xFC, +0x78, +0x00, + +0x40, +0xE0, +0xE0, +0xF8, +0xFC, +0xFE, +0xEE, +0xEE, +0x44, +0x00, + +0x00, +0x10, +0x38, +0x10, +0x38, +0x38, +0x38, +0x38, +0x10, +0x00, + +0x08, +0x1C, +0x08, +0x1C, +0x1C, +0x5C, +0xFC, +0x78, +0x30, +0x00, + +0x20, +0x70, +0x74, +0x7E, +0x7C, +0x78, +0x7C, +0x7E, +0x24, +0x00, + +0x30, +0x78, +0x38, +0x38, +0x38, +0x38, +0x38, +0x7C, +0x38, +0x00, + +0x00, +0x00, +0x68, +0xFC, +0xFE, +0xFE, +0xFE, +0xEE, +0x6C, +0x00, + +0x00, +0x00, +0x58, +0xFC, +0xFE, +0xEE, +0xEE, +0xEE, +0x44, +0x00, + +0x00, +0x00, +0x38, +0x7C, +0xFE, +0xEE, +0xFE, +0x7C, +0x38, +0x00, + +0x00, +0x00, +0x78, +0xFC, +0xFE, +0xFC, +0xF8, +0xE0, +0x40, +0x00, + +0x00, +0x00, +0x3C, +0x7E, +0xFE, +0x7E, +0x3E, +0x0E, +0x04, +0x00, + +0x00, +0x00, +0x58, +0xFC, +0xFE, +0xE4, +0xE0, +0xE0, +0x40, +0x00, + +0x00, +0x00, +0x3C, +0x7E, +0xFC, +0x7C, +0x7E, +0xFC, +0x78, +0x00, + +0x10, +0x38, +0x7C, +0xFE, +0x7C, +0x3C, +0x3E, +0x1C, +0x08, +0x00, + +0x00, +0x00, +0x44, +0xEE, +0xEE, +0xEE, +0xFE, +0x7C, +0x38, +0x00, + +0x00, +0x00, +0x44, +0xEE, +0xEE, +0xEE, +0x7C, +0x38, +0x10, +0x00, + +0x00, +0x00, +0x44, +0xEE, +0xFE, +0xFE, +0xFE, +0x7C, +0x28, +0x00, + +0x00, +0x00, +0x44, +0xEE, +0x7C, +0x38, +0x7C, +0xEE, +0x44, +0x00, + +0x00, +0x00, +0x44, +0xEE, +0x7C, +0x38, +0x38, +0x70, +0x20, +0x00, + +0x00, +0x00, +0x7C, +0xFE, +0x7C, +0x38, +0x7C, +0xFE, +0x7C, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x10, +0x38, +0x38, +0x38, +0x38, +0x38, +0x38, +0x38, +0x10, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x38, +0x7C, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0x7C, + +0x38, +0x7C, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0x7C, + +0x38, +0x7C, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0x7C, + +0x38, +0x7C, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0x7C, + +0x38, +0x7C, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0x7C, + +0x38, +0x7C, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0xFE, +0x7C, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0xFF, +0xFF, +0xFF, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x18, +0x3C, +0xFF, +0xFF, +0xFF, +0x3C, +0x18, +0x00, + +0x42, +0xE7, +0xE7, +0xF7, +0xFF, +0xFF, +0xEF, +0xE7, +0xE7, +0x42, + +0x3C, +0x7E, +0xFF, +0xF2, +0xFD, +0xFF, +0xCF, +0xFF, +0x7E, +0x3C, + +0x3E, +0x7F, +0x7E, +0x78, +0xFF, +0xFF, +0xF3, +0x7E, +0x7F, +0x3E, + +0x42, +0xE7, +0xE7, +0xE7, +0xFF, +0xFF, +0xFF, +0xFF, +0x7E, +0x24, + +0x00, +0x00, +0x00, +0x00, +0xFF, +0x00, +0xFF, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x81, +0xC3, +0xE7, +0x7E, +0x3C, +0x18, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x00, +0x18, +0x7E, +0x7E, +0xFF, +0xFF, +0x7E, +0x7E, +0x18, +0x00, + +0x07, +0x0F, +0x0F, +0x4E, +0xFE, +0x7E, +0x7E, +0x7E, +0x7E, +0x24, + +0xE0, +0xF0, +0xF0, +0x72, +0x7F, +0x7E, +0x7E, +0x7E, +0x7E, +0x24, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, +0x00, + +}; + +#endif /* FONT8X10_H_ */ diff --git a/flight/targets/OSD/System/inc/font_outlined8x14.h b/flight/targets/OSD/System/inc/font_outlined8x14.h index 614940bb3..95e94fa3b 100644 --- a/flight/targets/OSD/System/inc/font_outlined8x14.h +++ b/flight/targets/OSD/System/inc/font_outlined8x14.h @@ -1,12 +1,12 @@ -/** - * Super OSD, software revision 3 - * Copyright (C) 2010 Thomas Oldbury - * - * Please note the font data here is covered under Creative - * Commons licenses (version 3.0 BY-SA) and *not* the GPL. - */ - -// Lookup table. -extern const char font_lookup_outlined8x14[256]; -// Data. -extern const char font_data_outlined8x14[]; +/** + * Super OSD, software revision 3 + * Copyright (C) 2010 Thomas Oldbury + * + * Please note the font data here is covered under Creative + * Commons licenses (version 3.0 BY-SA) and *not* the GPL. + */ + +// Lookup table. +extern const char font_lookup_outlined8x14[256]; +// Data. +extern const char font_data_outlined8x14[]; diff --git a/flight/targets/OSD/System/inc/font_outlined8x8.h b/flight/targets/OSD/System/inc/font_outlined8x8.h index c6f65f943..337ab8591 100644 --- a/flight/targets/OSD/System/inc/font_outlined8x8.h +++ b/flight/targets/OSD/System/inc/font_outlined8x8.h @@ -1,12 +1,12 @@ -/** - * Super OSD, software revision 3 - * Copyright (C) 2010 Thomas Oldbury - * - * Please note the font data here is covered under Creative - * Commons licenses (version 3.0 BY-SA) and *not* the GPL. - */ - -// Lookup table. -extern const char font_lookup_outlined8x8[256]; -// Data. -extern const char font_data_outlined8x8[]; +/** + * Super OSD, software revision 3 + * Copyright (C) 2010 Thomas Oldbury + * + * Please note the font data here is covered under Creative + * Commons licenses (version 3.0 BY-SA) and *not* the GPL. + */ + +// Lookup table. +extern const char font_lookup_outlined8x8[256]; +// Data. +extern const char font_data_outlined8x8[]; diff --git a/flight/targets/OSD/System/inc/fonts.h b/flight/targets/OSD/System/inc/fonts.h index 613401e32..8b7d35650 100644 --- a/flight/targets/OSD/System/inc/fonts.h +++ b/flight/targets/OSD/System/inc/fonts.h @@ -1,48 +1,48 @@ -/** - * Super OSD, software revision 3 - * Copyright (C) 2010 Thomas Oldbury - * - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. - */ - -#ifndef FONTS_H -#define FONTS_H - -// New fonts need a .c file (with the data) and a .h file with -// the definitions. Add the .h files here only. -#include "font_outlined8x14.h" -#include "font_outlined8x8.h" - -// This number must also be incremented for each new font. -#define NUM_FONTS 4 - -// Flags for fonts. -#define FONT_LOWERCASE_ONLY 1 -#define FONT_UPPERCASE_ONLY 2 - -// Font table. (Actual list of fonts in fonts.c.) -struct FontEntry -{ - int id; - unsigned char width, height; - const char *name; - const char *lookup; - const char *data; - int flags; -}; - -extern struct FontEntry fonts[NUM_FONTS + 1]; - -#endif // FONTS_H +/** + * Super OSD, software revision 3 + * Copyright (C) 2010 Thomas Oldbury + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA. + */ + +#ifndef FONTS_H +#define FONTS_H + +// New fonts need a .c file (with the data) and a .h file with +// the definitions. Add the .h files here only. +#include "font_outlined8x14.h" +#include "font_outlined8x8.h" + +// This number must also be incremented for each new font. +#define NUM_FONTS 4 + +// Flags for fonts. +#define FONT_LOWERCASE_ONLY 1 +#define FONT_UPPERCASE_ONLY 2 + +// Font table. (Actual list of fonts in fonts.c.) +struct FontEntry +{ + int id; + unsigned char width, height; + const char *name; + const char *lookup; + const char *data; + int flags; +}; + +extern struct FontEntry fonts[NUM_FONTS + 1]; + +#endif // FONTS_H diff --git a/flight/targets/OSD/System/inc/openpilot.h b/flight/targets/OSD/System/inc/openpilot.h index 7f1ac3758..eb3cadcc7 100644 --- a/flight/targets/OSD/System/inc/openpilot.h +++ b/flight/targets/OSD/System/inc/openpilot.h @@ -1,52 +1,52 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file openpilot.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main OpenPilot header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef OPENPILOT_H -#define OPENPILOT_H - - -/* PIOS Includes */ -#include - -/* OpenPilot Libraries */ -#include "utlist.h" -#include "uavobjectmanager.h" -#include "eventdispatcher.h" -#include "alarms.h" -#include "taskmonitor.h" -#include "uavtalk.h" - -/* Global Functions */ -void OpenPilotInit(void); - -#endif /* OPENPILOT_H */ -/** - * @} - * @} +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file openpilot.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main OpenPilot header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OPENPILOT_H +#define OPENPILOT_H + + +/* PIOS Includes */ +#include + +/* OpenPilot Libraries */ +#include "utlist.h" +#include "uavobjectmanager.h" +#include "eventdispatcher.h" +#include "alarms.h" +#include "taskmonitor.h" +#include "uavtalk.h" + +/* Global Functions */ +void OpenPilotInit(void); + +#endif /* OPENPILOT_H */ +/** + * @} + * @} */ diff --git a/flight/targets/OSD/System/inc/pios_config.h b/flight/targets/OSD/System/inc/pios_config.h index cda229055..56cfb9a5b 100644 --- a/flight/targets/OSD/System/inc/pios_config.h +++ b/flight/targets/OSD/System/inc/pios_config.h @@ -1,170 +1,170 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013. - * @brief PiOS configuration header, the compile time config file for the PIOS. - * Defines which PiOS libraries and features are included in the firmware. - * @see The GNU Public License (GPL) Version 3 - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* - * Below is a complete list of PIOS configurable options. - * Please do not remove or rearrange them. Only comment out - * unused options in the list. See main pios.h header for more - * details. - */ - -/* #define PIOS_INCLUDE_DEBUG_CONSOLE */ -/* #define DEBUG_LEVEL 0 */ - -/* PIOS FreeRTOS support */ -#define PIOS_INCLUDE_FREERTOS - -/* PIOS bootloader helper */ -#define PIOS_INCLUDE_BL_HELPER -/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */ - -/* PIOS system functions */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_INITCALL -#define PIOS_INCLUDE_SYS - -/* PIOS hardware peripherals */ -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_RTC -#define PIOS_INCLUDE_TIM -#define PIOS_INCLUDE_USART -#define PIOS_INCLUDE_ADC -#define PIOS_INCLUDE_I2C -#define PIOS_INCLUDE_SPI -/* #define PIOS_INCLUDE_GPIO */ -#define PIOS_INCLUDE_EXTI -#define PIOS_INCLUDE_WDG - -/* PIOS USB functions */ -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -/* #define PIOS_INCLUDE_USB_CDC */ -/* #define PIOS_INCLUDE_USB_RCTX */ - -/* PIOS sensor interfaces */ -/* #define PIOS_INCLUDE_ADXL345 */ -/* #define PIOS_INCLUDE_BMA180 */ -/* #define PIOS_INCLUDE_L3GD20 */ -/* #define PIOS_INCLUDE_MPU6000 */ -/* #define PIOS_MPU6000_ACCEL */ -/* #define PIOS_INCLUDE_HMC5843 */ -#define PIOS_INCLUDE_HMC5883 -/* #define PIOS_HMC5883_HAS_GPIOS */ -#define PIOS_INCLUDE_BMP085 -/* #define PIOS_INCLUDE_MS5611 */ -/* #define PIOS_INCLUDE_MPXV */ -/* #define PIOS_INCLUDE_ETASV3 */ -/* #define PIOS_INCLUDE_HCSR04 */ - -/* PIOS receiver drivers */ -/* #define PIOS_INCLUDE_PWM */ -/* #define PIOS_INCLUDE_PPM */ -/* #define PIOS_INCLUDE_PPM_FLEXI */ -/* #define PIOS_INCLUDE_DSM */ -/* #define PIOS_INCLUDE_SBUS */ -/* #define PIOS_INCLUDE_GCSRCVR */ - -/* PIOS abstract receiver interface */ -/* #define PIOS_INCLUDE_RCVR */ - -/* PIOS common peripherals */ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_SERVO -/* #define PIOS_INCLUDE_I2C_ESC */ -/* #define PIOS_INCLUDE_OVERO */ -/* #define PIOS_OVERO_SPI */ -#define PIOS_INCLUDE_SDCARD -#define LOG_FILENAME "startup.log" -/* #define PIOS_INCLUDE_FLASH */ -/* #define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS */ -/* #define FLASH_FREERTOS */ -/* #define PIOS_INCLUDE_FLASH_EEPROM */ - -/* PIOS radio modules */ -/* #define PIOS_INCLUDE_RFM22B */ -/* #define PIOS_INCLUDE_RFM22B_COM */ -/* #define PIOS_INCLUDE_RFM22B_RCVR */ -/* #define PIOS_INCLUDE_PPM_OUT */ -/* #define PIOS_RFM22B_DEBUG_ON_TELEM */ - -#define PIOS_INCLUDE_VIDEO -/* #define PIOS_INCLUDE_WAVE */ -/* #define PIOS_INCLUDE_UDP */ - -/* PIOS abstract comms interface with options */ -#define PIOS_INCLUDE_COM -/* #define PIOS_INCLUDE_COM_MSG */ -/* #define PIOS_INCLUDE_TELEMETRY_RF */ -#define PIOS_INCLUDE_COM_TELEM -/* #define PIOS_INCLUDE_COM_FLEXI */ -#define PIOS_INCLUDE_COM_AUX -#define PIOS_TELEM_PRIORITY_QUEUE -#define PIOS_INCLUDE_GPS -/* #define PIOS_GPS_MINIMAL */ -#define PIOS_INCLUDE_GPS_NMEA_PARSER -#define PIOS_INCLUDE_GPS_UBX_PARSER -#define PIOS_GPS_SETS_HOMELOCATION - -/* Stabilization options */ -#define PIOS_QUATERNION_STABILIZATION - -/* Performance counters */ -#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 8379692 - -/* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 4000 -#define HEAP_LIMIT_CRITICAL 1000 -#define IRQSTACK_LIMIT_WARNING 150 -#define IRQSTACK_LIMIT_CRITICAL 80 -#define CPULOAD_LIMIT_WARNING 80 -#define CPULOAD_LIMIT_CRITICAL 95 - -/* Task stack sizes */ -/* #define PIOS_ACTUATOR_STACK_SIZE 1020 */ -/* #define PIOS_MANUAL_STACK_SIZE 800 */ -/* #define PIOS_SYSTEM_STACK_SIZE 660 */ -/* #define PIOS_STABILIZATION_STACK_SIZE 524 */ -/* #define PIOS_TELEM_STACK_SIZE 500 */ -/* #define PIOS_EVENTDISPATCHER_STACK_SIZE 130 */ - -/* This can't be too high to stop eventdispatcher thread overflowing */ -/* #define PIOS_EVENTDISAPTCHER_QUEUE 10 */ - -/* Revolution series */ -/* #define REVOLUTION */ - -#endif /* PIOS_CONFIG_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013. + * @brief PiOS configuration header, the compile time config file for the PIOS. + * Defines which PiOS libraries and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* + * Below is a complete list of PIOS configurable options. + * Please do not remove or rearrange them. Only comment out + * unused options in the list. See main pios.h header for more + * details. + */ + +/* #define PIOS_INCLUDE_DEBUG_CONSOLE */ +/* #define DEBUG_LEVEL 0 */ + +/* PIOS FreeRTOS support */ +#define PIOS_INCLUDE_FREERTOS + +/* PIOS bootloader helper */ +#define PIOS_INCLUDE_BL_HELPER +/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */ + +/* PIOS system functions */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_INITCALL +#define PIOS_INCLUDE_SYS + +/* PIOS hardware peripherals */ +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_RTC +#define PIOS_INCLUDE_TIM +#define PIOS_INCLUDE_USART +#define PIOS_INCLUDE_ADC +#define PIOS_INCLUDE_I2C +#define PIOS_INCLUDE_SPI +/* #define PIOS_INCLUDE_GPIO */ +#define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_WDG + +/* PIOS USB functions */ +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +/* #define PIOS_INCLUDE_USB_CDC */ +/* #define PIOS_INCLUDE_USB_RCTX */ + +/* PIOS sensor interfaces */ +/* #define PIOS_INCLUDE_ADXL345 */ +/* #define PIOS_INCLUDE_BMA180 */ +/* #define PIOS_INCLUDE_L3GD20 */ +/* #define PIOS_INCLUDE_MPU6000 */ +/* #define PIOS_MPU6000_ACCEL */ +/* #define PIOS_INCLUDE_HMC5843 */ +#define PIOS_INCLUDE_HMC5883 +/* #define PIOS_HMC5883_HAS_GPIOS */ +#define PIOS_INCLUDE_BMP085 +/* #define PIOS_INCLUDE_MS5611 */ +/* #define PIOS_INCLUDE_MPXV */ +/* #define PIOS_INCLUDE_ETASV3 */ +/* #define PIOS_INCLUDE_HCSR04 */ + +/* PIOS receiver drivers */ +/* #define PIOS_INCLUDE_PWM */ +/* #define PIOS_INCLUDE_PPM */ +/* #define PIOS_INCLUDE_PPM_FLEXI */ +/* #define PIOS_INCLUDE_DSM */ +/* #define PIOS_INCLUDE_SBUS */ +/* #define PIOS_INCLUDE_GCSRCVR */ + +/* PIOS abstract receiver interface */ +/* #define PIOS_INCLUDE_RCVR */ + +/* PIOS common peripherals */ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_SERVO +/* #define PIOS_INCLUDE_I2C_ESC */ +/* #define PIOS_INCLUDE_OVERO */ +/* #define PIOS_OVERO_SPI */ +#define PIOS_INCLUDE_SDCARD +#define LOG_FILENAME "startup.log" +/* #define PIOS_INCLUDE_FLASH */ +/* #define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS */ +/* #define FLASH_FREERTOS */ +/* #define PIOS_INCLUDE_FLASH_EEPROM */ + +/* PIOS radio modules */ +/* #define PIOS_INCLUDE_RFM22B */ +/* #define PIOS_INCLUDE_RFM22B_COM */ +/* #define PIOS_INCLUDE_RFM22B_RCVR */ +/* #define PIOS_INCLUDE_PPM_OUT */ +/* #define PIOS_RFM22B_DEBUG_ON_TELEM */ + +#define PIOS_INCLUDE_VIDEO +/* #define PIOS_INCLUDE_WAVE */ +/* #define PIOS_INCLUDE_UDP */ + +/* PIOS abstract comms interface with options */ +#define PIOS_INCLUDE_COM +/* #define PIOS_INCLUDE_COM_MSG */ +/* #define PIOS_INCLUDE_TELEMETRY_RF */ +#define PIOS_INCLUDE_COM_TELEM +/* #define PIOS_INCLUDE_COM_FLEXI */ +#define PIOS_INCLUDE_COM_AUX +#define PIOS_TELEM_PRIORITY_QUEUE +#define PIOS_INCLUDE_GPS +/* #define PIOS_GPS_MINIMAL */ +#define PIOS_INCLUDE_GPS_NMEA_PARSER +#define PIOS_INCLUDE_GPS_UBX_PARSER +#define PIOS_GPS_SETS_HOMELOCATION + +/* Stabilization options */ +#define PIOS_QUATERNION_STABILIZATION + +/* Performance counters */ +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 8379692 + +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 4000 +#define HEAP_LIMIT_CRITICAL 1000 +#define IRQSTACK_LIMIT_WARNING 150 +#define IRQSTACK_LIMIT_CRITICAL 80 +#define CPULOAD_LIMIT_WARNING 80 +#define CPULOAD_LIMIT_CRITICAL 95 + +/* Task stack sizes */ +/* #define PIOS_ACTUATOR_STACK_SIZE 1020 */ +/* #define PIOS_MANUAL_STACK_SIZE 800 */ +/* #define PIOS_SYSTEM_STACK_SIZE 660 */ +/* #define PIOS_STABILIZATION_STACK_SIZE 524 */ +/* #define PIOS_TELEM_STACK_SIZE 500 */ +/* #define PIOS_EVENTDISPATCHER_STACK_SIZE 130 */ + +/* This can't be too high to stop eventdispatcher thread overflowing */ +/* #define PIOS_EVENTDISAPTCHER_QUEUE 10 */ + +/* Revolution series */ +/* #define REVOLUTION */ + +#endif /* PIOS_CONFIG_H */ + +/** + * @} + * @} + */ diff --git a/flight/targets/OSD/System/inc/splash.h b/flight/targets/OSD/System/inc/splash.h index 3e9202a3d..6cbd41357 100644 --- a/flight/targets/OSD/System/inc/splash.h +++ b/flight/targets/OSD/System/inc/splash.h @@ -1,1449 +1,1449 @@ -/* - * splash.h - * - * Created on: 16.3.2012 - * Author: Samba - */ - -#ifndef SPLASH_H_ -#define SPLASH_H_ - -#define oplogo_width 144 -#define oplogo_height 144 -const static unsigned short oplogo_bits[] = { - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x001e, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, 0x01ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0x07ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0x0fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0x3fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0x7fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0x0003, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0x0007, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0x000f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x001f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x00ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x07ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x0fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x1fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x3fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0x03ff, 0xffff, 0x0001, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0x03ff, 0xfffe, 0x0003, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0x01ff, 0xfff8, 0x000f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0x01ff, 0xffe0, 0x001f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0x01ff, 0xffc0, 0x003f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0x01ff, 0xff00, 0x007f, 0x0000, - 0x0000, 0x0000, 0x01f0, 0x0000, 0xff80, 0x00ff, 0xfe00, 0x01ff, 0x0000, - 0x0070, 0x0000, 0x07fc, 0x0000, 0xff80, 0x00ff, 0xf800, 0x03ff, 0x0000, - 0x07c0, 0x0000, 0x1fff, 0x0000, 0xffc0, 0x00ff, 0xf000, 0x07ff, 0x0000, - 0x7f80, 0xe000, 0x3fff, 0x0000, 0xffc0, 0x00ff, 0xc000, 0x0fff, 0x0000, - 0xfe00, 0xf803, 0x3fff, 0x0000, 0xffc0, 0x007f, 0x8000, 0x3fff, 0x0000, - 0xfc00, 0xfe3f, 0x1fff, 0x0000, 0xffc0, 0x007f, 0x0000, 0x7ffe, 0x0000, - 0xf000, 0xffff, 0x1fff, 0x0000, 0xffe0, 0x007f, 0x0000, 0xfffc, 0x0000, - 0xe000, 0xffff, 0x1fff, 0x0060, 0xffe0, 0x007f, 0x0000, 0xfff0, 0x0000, - 0x8000, 0xffff, 0x1fff, 0x01e0, 0xffe0, 0x003f, 0x0000, 0xffe0, 0x0001, - 0x0000, 0xffff, 0x0fff, 0x07f0, 0xfff0, 0x003f, 0x0000, 0xff80, 0x0003, - 0x0000, 0xfffc, 0x0fff, 0x1ff0, 0xfff0, 0x003f, 0x0000, 0xff00, 0x0003, - 0x0000, 0xfff8, 0x0fff, 0x7ff0, 0xfff0, 0x001f, 0x0000, 0xfe00, 0x0007, - 0x0000, 0xfff0, 0x0fff, 0xfff0, 0xfff0, 0x001f, 0x0000, 0xfc00, 0x0007, - 0x0000, 0xffc0, 0x0fff, 0xfff8, 0xffc3, 0x001f, 0x0000, 0xf800, 0x0007, - 0x0000, 0xffc0, 0x1fff, 0xfff8, 0xff0f, 0x001f, 0x0000, 0xf800, 0x0007, - 0x0000, 0xffc0, 0x3fff, 0xfff8, 0xfc3f, 0x000f, 0x0000, 0xf800, 0x0007, - 0x0000, 0xff80, 0x3fff, 0xfff8, 0xf8ff, 0x000f, 0x0000, 0xf800, 0x000f, - 0x0000, 0xff80, 0x3fff, 0xfffc, 0xe1ff, 0x000f, 0x0000, 0xf800, 0x000f, - 0x0000, 0xff00, 0x3fff, 0xfffc, 0x87ff, 0x000f, 0x0000, 0xf800, 0x000f, - 0x0000, 0xff00, 0x1fff, 0xfffc, 0x1fff, 0x0006, 0x0000, 0xf800, 0x000f, - 0x0000, 0xff00, 0x1fff, 0xfffc, 0x7fff, 0x0000, 0x0000, 0xf800, 0x000f, - 0x0000, 0xfe00, 0x1fff, 0xfffe, 0xffff, 0x0001, 0x0000, 0xf800, 0x000f, - 0x0000, 0xfe00, 0x0fff, 0xfffe, 0xffff, 0x0003, 0x0000, 0xf800, 0x000f, - 0x0000, 0xfc00, 0x01ff, 0xfffe, 0xffff, 0x000f, 0x0000, 0xf800, 0x000f, - 0x0000, 0xfc00, 0x01ff, 0xfffe, 0xffff, 0x003f, 0x0000, 0xf800, 0x000f, - 0x0000, 0xf800, 0x01ff, 0xffff, 0xffff, 0x00ff, 0x0000, 0xf800, 0x000f, - 0x0000, 0xf800, 0x00ff, 0xffff, 0xffff, 0x03ff, 0x0000, 0xf800, 0x000f, - 0x0000, 0xf800, 0x00ff, 0xffff, 0xffff, 0x0fff, 0x0000, 0xf800, 0x000f, - 0x0000, 0xf000, 0x00ff, 0xffff, 0xffff, 0x3fff, 0x0000, 0xf800, 0x000f, - 0x0000, 0xf000, 0x807f, 0xffff, 0xffff, 0x7fff, 0x0000, 0xf800, 0x000f, - 0x0000, 0xe000, 0x807f, 0xffff, 0xffff, 0xffff, 0x0001, 0xf800, 0x000f, - 0x0000, 0x8000, 0x807f, 0xffff, 0xffff, 0xffff, 0x0007, 0xfc00, 0x000f, - 0x0000, 0x0000, 0x807c, 0xffff, 0xffff, 0xffff, 0x001f, 0xfc00, 0x000f, - 0x0000, 0x0000, 0xc020, 0xffff, 0xffff, 0xffff, 0x007f, 0xfc00, 0x000f, - 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0x00ff, 0xfc00, 0x000f, - 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0x03ff, 0xfc00, 0x000f, - 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0x0fff, 0xfc00, 0x000f, - 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, 0xffff, 0x3fff, 0xfc00, 0x000f, - 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xfc00, 0x000f, - 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xfc03, 0x000f, - 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xfe0f, 0x000f, - 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0xfe1f, 0x000f, - 0x0000, 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0x0600, 0xc000, 0xffff, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0x3e00, 0x0000, 0xfffe, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0xff00, 0x0001, 0xfff8, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0xff00, 0x000f, 0xffc0, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0xff00, 0x007f, 0xfe00, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0xff00, 0x03ff, 0xf000, 0xffff, 0xffff, 0x0007, - 0x0000, 0x0000, 0x0000, 0xff80, 0x03ff, 0xc000, 0xffff, 0xffff, 0x0007, - 0x0000, 0x0000, 0x0000, 0xff80, 0x03ff, 0x0000, 0xfffe, 0xffff, 0x0007, - 0x0000, 0x0000, 0x0000, 0xff80, 0x03ff, 0x0000, 0xfff0, 0xffff, 0x0007, - 0x0000, 0x0000, 0x0000, 0xffc0, 0x03ff, 0x0000, 0xff80, 0xffff, 0x0007, - 0x0000, 0x0000, 0x0000, 0xffc0, 0x01ff, 0x0000, 0xfe00, 0xffff, 0x0003, - 0x0000, 0x0000, 0x0000, 0xffc0, 0x01ff, 0x0000, 0xf000, 0xffff, 0x0003, - 0x0000, 0x0000, 0x0000, 0xffc0, 0x01ff, 0x0000, 0x8000, 0xffff, 0x0001, - 0x0000, 0x0000, 0x0000, 0xffe0, 0x01ff, 0x0000, 0x0000, 0xfffc, 0x0001, - 0x0000, 0x0000, 0x0000, 0xffe0, 0x00ff, 0x0000, 0x0000, 0xfff0, 0x0000, - 0x0000, 0x0000, 0x0000, 0xffe0, 0x00ff, 0x0000, 0x0000, 0x7f80, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff0, 0x00ff, 0x0000, 0x0000, 0x0c00, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff0, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff0, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff8, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff8, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff8, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff8, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xffe0, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xffc0, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff00, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfc00, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf000, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xc000, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x8000, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x000e, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1980, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x39c0, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3980, 0x0000, 0x0060, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3800, 0x0000, 0x0060, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3800, 0x0000, 0x00f0, - 0x0000, 0x03ff, 0x0ffc, 0x3ff0, 0xffc0, 0xff80, 0x3983, 0x7fe0, 0x07f8, - 0xc000, 0x07ff, 0x1fff, 0x7ffc, 0xfff0, 0xffc1, 0x39c7, 0xfff0, 0x07f9, - 0xe000, 0x8fff, 0x3fff, 0xfffe, 0xfff8, 0xffe3, 0x39cf, 0xfff8, 0x0063, - 0xe000, 0x9c00, 0x7003, 0xc00e, 0x8038, 0x00e3, 0x39ce, 0x801c, 0x0063, - 0x6000, 0x9c00, 0x7001, 0xc006, 0x0019, 0x0077, 0x39dc, 0x001c, 0x0063, - 0x6000, 0x9c00, 0x7001, 0xfffe, 0x0019, 0x0077, 0x39dc, 0x001c, 0x0063, - 0x6000, 0x9c00, 0x7001, 0xfffe, 0x0019, 0x0077, 0x39dc, 0x001c, 0x0063, - 0x6000, 0x9c00, 0x7001, 0x000e, 0x0018, 0x0077, 0x39dc, 0x001c, 0x0063, - 0xe000, 0x9c00, 0x7001, 0x000e, 0x0018, 0x0077, 0x39ce, 0x801c, 0x00e3, - 0xe000, 0xff8f, 0x3fff, 0x7ffe, 0x0018, 0xffff, 0xf1cf, 0xe0f8, 0x07e3, - 0xc000, 0xffff, 0x1fff, 0x7ffc, 0x0018, 0xffff, 0xf1c7, 0xfff0, 0x07c1, - 0x8000, 0xffff, 0x0fff, 0x7ff8, 0x0018, 0xffff, 0xc183, 0xffe0, 0x0780, - 0x0000, 0xc000, 0x0001, 0x0000, 0x0000, 0x0070, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8000, 0x0001, 0x0000, 0x0000, 0x0070, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8000, 0x0001, 0x0000, 0x0000, 0x0070, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8000, 0x0001, 0x0000, 0x0000, 0x0070, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8000, 0x0001, 0x0000, 0x0000, 0x0060, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000 }; - -const static unsigned short oplogo_mask_bits[] = { - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x003f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0x03ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0x0fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0x1fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0x7fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x0001, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x0007, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x000f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x001f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x003f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x00ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x03ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x0fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0x1fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0x3fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0x7fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x0001, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x0003, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x0007, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x001f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, 0x003f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0x8fff, 0xffff, 0x007f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0x07ff, 0xffff, 0x00ff, 0x0000, - 0x0000, 0x0000, 0x03f8, 0x0000, 0xffe0, 0x07ff, 0xfffc, 0x03ff, 0x0000, - 0x00f8, 0x0000, 0x0ffe, 0x0000, 0xffe0, 0x07ff, 0xfff0, 0x07ff, 0x0000, - 0x0ffc, 0x8000, 0x3fff, 0x0000, 0xffe0, 0x07ff, 0xffe0, 0x0fff, 0x0000, - 0xfffc, 0xf000, 0x7fff, 0x0000, 0xfff0, 0x03ff, 0xff80, 0x1fff, 0x0000, - 0xfffc, 0xfc07, 0xffff, 0x0000, 0xfff0, 0x03ff, 0xff00, 0x7fff, 0x0000, - 0xfff8, 0xff7f, 0xffff, 0x0000, 0xfff0, 0x03ff, 0xfc00, 0xffff, 0x0000, - 0xffe0, 0xffff, 0xffff, 0x0000, 0xfff0, 0x03ff, 0xf800, 0xffff, 0x0001, - 0xffc0, 0xffff, 0xffff, 0x00f0, 0xfff8, 0x01ff, 0xe000, 0xffff, 0x0003, - 0xff00, 0xffff, 0x7fff, 0x03f8, 0xfff8, 0x01ff, 0xc000, 0xffff, 0x0003, - 0xfe00, 0xffff, 0x7fff, 0x0ff8, 0xfff8, 0x01ff, 0x0000, 0xffff, 0x0007, - 0xf800, 0xffff, 0x7fff, 0x3ffc, 0xfffc, 0x01ff, 0x0000, 0xfffe, 0x000f, - 0xf000, 0xffff, 0x7fff, 0xfffc, 0xfffc, 0x00ff, 0x0000, 0xfff8, 0x000f, - 0xc000, 0xffff, 0x3fff, 0xfffc, 0xfffd, 0x00ff, 0x0000, 0xfff0, 0x001f, - 0x8000, 0xffff, 0x3fff, 0xfffc, 0xffff, 0x00ff, 0x0000, 0xffc0, 0x001f, - 0x0000, 0xfffe, 0x3fff, 0xfffe, 0xffff, 0x007f, 0x0000, 0xff80, 0x001f, - 0x0000, 0xfffc, 0x7fff, 0xfffe, 0xffff, 0x007f, 0x0000, 0xff00, 0x001f, - 0x0000, 0xfff8, 0xffff, 0xfffe, 0xffff, 0x007f, 0x0000, 0xfe00, 0x001f, - 0x0000, 0xfff0, 0xffff, 0xfffe, 0xffff, 0x007f, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0x001f, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0x001f, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xff80, 0xbfff, 0xffff, 0xffff, 0x01ff, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xff00, 0xdfff, 0xffff, 0xffff, 0x07ff, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xff00, 0xc7ff, 0xffff, 0xffff, 0x1fff, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xfe00, 0xc7ff, 0xffff, 0xffff, 0x7fff, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xfe00, 0xc3ff, 0xffff, 0xffff, 0xffff, 0x0000, 0xfe00, 0x003f, - 0x0000, 0xfe00, 0xe3ff, 0xffff, 0xffff, 0xffff, 0x0003, 0xfe00, 0x003f, - 0x0000, 0xfc00, 0xe3ff, 0xffff, 0xffff, 0xffff, 0x000f, 0xfe00, 0x003f, - 0x0000, 0xfc00, 0xe1ff, 0xffff, 0xffff, 0xffff, 0x003f, 0xff00, 0x003f, - 0x0000, 0xf800, 0xe1ff, 0xffff, 0xffff, 0xffff, 0x00ff, 0xff00, 0x003f, - 0x0000, 0xf000, 0xf1ff, 0xffff, 0xffff, 0xffff, 0x01ff, 0xff00, 0x003f, - 0x0000, 0xc000, 0xf1ff, 0xffff, 0xffff, 0xffff, 0x07ff, 0xff00, 0x003f, - 0x0000, 0x0000, 0xf0fe, 0xffff, 0xffff, 0xffff, 0x1fff, 0xff00, 0x003f, - 0x0000, 0x0000, 0xf070, 0xffff, 0xffff, 0xffff, 0x7fff, 0xff00, 0x003f, - 0x0000, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0xff01, 0x003f, - 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0xff07, 0x003f, - 0x0000, 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0xffff, 0xff1f, 0x003f, - 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, 0xffff, 0xffbf, 0x003f, - 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0x0f00, 0xfffc, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0x7f80, 0xffe0, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0xff80, 0xff83, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0xffc0, 0xfc1f, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0xffc0, 0xe0ff, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0xffc0, 0x07ff, 0xffff, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0xffc0, 0x0fff, 0xfffc, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0xffe0, 0x0fff, 0xffe0, 0xffff, 0xffff, 0x003f, - 0x0000, 0x0000, 0x0000, 0xffe0, 0x0fff, 0xff00, 0xffff, 0xffff, 0x001f, - 0x0000, 0x0000, 0x0000, 0xffe0, 0x0fff, 0xf800, 0xffff, 0xffff, 0x001f, - 0x0000, 0x0000, 0x0000, 0xfff0, 0x0fff, 0xe000, 0xffff, 0xffff, 0x001f, - 0x0000, 0x0000, 0x0000, 0xfff0, 0x0fff, 0x0000, 0xffff, 0xffff, 0x001f, - 0x0000, 0x0000, 0x0000, 0xfff0, 0x0fff, 0x0000, 0xfff8, 0xffff, 0x001f, - 0x0000, 0x0000, 0x0000, 0xfff0, 0x07ff, 0x0000, 0xffc0, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0xfff8, 0x07ff, 0x0000, 0xff00, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0xfff8, 0x07ff, 0x0000, 0xf800, 0xffff, 0x0007, - 0x0000, 0x0000, 0x0000, 0xfff8, 0x07ff, 0x0000, 0xc000, 0xffff, 0x0007, - 0x0000, 0x0000, 0x0000, 0xfffc, 0x03ff, 0x0000, 0x0000, 0xfffe, 0x0003, - 0x0000, 0x0000, 0x0000, 0xfffc, 0x03ff, 0x0000, 0x0000, 0xfff8, 0x0001, - 0x0000, 0x0000, 0x0000, 0xfffc, 0x03ff, 0x0000, 0x0000, 0xffc0, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffe, 0x01ff, 0x0000, 0x0000, 0x1e00, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffe, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffe, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffe, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffe, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffe, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffc, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff0, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xffe0, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff80, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfe00, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf800, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xe000, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xc000, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3fc0, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7fe0, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0x0000, 0x00f0, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0x0000, 0x01f8, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0x0000, 0x01f8, - 0x8000, 0x07ff, 0x1ffe, 0x7ff8, 0xffe0, 0xffc1, 0xffe7, 0xfff0, 0x0ffc, - 0xe000, 0x8fff, 0x3fff, 0xfffe, 0xfff8, 0xffe3, 0xffef, 0xfff8, 0x1fff, - 0xf000, 0xdfff, 0x7fff, 0xffff, 0xfffd, 0xfff7, 0xffff, 0xfffc, 0x1fff, - 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xfffe, 0x1fff, - 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x1fff, - 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0fff, - 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, - 0xf800, 0xff01, 0xfc07, 0xffff, 0xc07f, 0x01ff, 0xffff, 0xc07f, 0x01ff, - 0xf800, 0xff01, 0xfc07, 0xffff, 0xc07f, 0x01ff, 0xffff, 0xc07f, 0x01ff, - 0xf800, 0xffdf, 0xffff, 0xffff, 0xc07f, 0xffff, 0xffff, 0xf1ff, 0x0fff, - 0xf800, 0xffff, 0xffff, 0xffff, 0xc07f, 0xffff, 0xffff, 0xffff, 0x1fff, - 0xf800, 0xffff, 0xffff, 0xffff, 0xc07f, 0xffff, 0xffff, 0xffff, 0x1fff, - 0xf800, 0xffff, 0xffff, 0xffff, 0xc07f, 0xffff, 0xffff, 0xffff, 0x1fff, - 0xf000, 0xffff, 0x7fff, 0xffff, 0xc07f, 0xffff, 0xffff, 0xffff, 0x1ff7, - 0xe000, 0xffff, 0x3fff, 0xfffe, 0xc07f, 0xffff, 0xffef, 0xfffb, 0x1fe3, - 0xc000, 0xffff, 0x1fff, 0xfffc, 0x803c, 0xffff, 0xe3c7, 0xfff1, 0x0fc1, - 0x0000, 0xe000, 0x0007, 0x0000, 0x0000, 0x01fc, 0x0000, 0x0000, 0x0000, - 0x0000, 0xe000, 0x0007, 0x0000, 0x0000, 0x01fc, 0x0000, 0x0000, 0x0000, - 0x0000, 0xe000, 0x0007, 0x0000, 0x0000, 0x01fc, 0x0000, 0x0000, 0x0000, - 0x0000, 0xe000, 0x0007, 0x0000, 0x0000, 0x01f8, 0x0000, 0x0000, 0x0000, - 0x0000, 0xc000, 0x0003, 0x0000, 0x0000, 0x00f0, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000 }; - - -#define level_width 144 -#define level_height 129 -const static unsigned short level_bits[] = { - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf800, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff8, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xe000, 0xffff, 0x1e01, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfe00, 0x7fef, 0x7ff8, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xff00, 0x83c0, 0xffff, 0x0001, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x3f80, 0xcffe, 0xfffd, 0x0007, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x9fc0, 0xffff, 0xb07f, 0x001f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xcfe0, 0xffff, 0xcfce, 0x007e, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xe7f8, 0xffff, 0x9ff7, 0x00fd, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xf7fc, 0xffe7, 0xbff7, 0x01ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xf3fe, 0xfffb, 0xb9ff, 0x03ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfbff, 0xfe03, 0xb9f7, 0x07ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8000, 0xf9ff, 0xebfd, 0xb9e7, 0x0fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xc000, 0xffff, 0xd7fe, 0xcfdf, 0x0fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xe000, 0x7fff, 0xf7ff, 0xf037, 0x1fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xe000, 0x7fff, 0xf7ff, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf000, 0xefff, 0xf73e, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf000, 0xefff, 0xf73e, 0xefff, 0x7fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf000, 0xefff, 0xf939, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf800, 0x87ff, 0xfe07, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf800, 0xffff, 0xdffe, 0xffff, 0xffdf, 0x0001, 0x0000, 0x0000, - 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, - 0x0000, 0xfe00, 0xffff, 0xefff, 0x1fff, 0xfff8, 0x0003, 0x0000, 0x0000, - 0x0000, 0xfe00, 0xffff, 0xffff, 0x81ff, 0xfff1, 0x0007, 0x0000, 0x0000, - 0x0000, 0xfe00, 0xffff, 0xffff, 0xfc3f, 0xfff3, 0x000f, 0x0000, 0x0000, - 0x0000, 0xfe00, 0xffff, 0xffff, 0xff9f, 0xfff0, 0x000f, 0x0000, 0x0000, - 0x0000, 0xfe00, 0xffff, 0xffff, 0x3fcf, 0xfff6, 0x001f, 0x0000, 0x0000, - 0x0000, 0xff00, 0xffff, 0xffff, 0x0ee7, 0xfff7, 0x003f, 0x0000, 0x0000, - 0x0000, 0xff00, 0xffff, 0xffff, 0xe003, 0xfff7, 0x003f, 0x0000, 0x0000, - 0x0000, 0xff00, 0xffff, 0xffff, 0xf371, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff00, 0xffff, 0xffff, 0xfff9, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff00, 0xffff, 0xffff, 0xfffe, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0x7fff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0x7fff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xdfff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xdfff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xfdff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xbfff, 0xffff, 0xfdff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0x7fff, 0xfffb, 0xfdff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xfeff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xf3ff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xcfff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xbeff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xfeff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0x7fff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xbfff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xbeff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xdeff, 0x007f, 0x0000, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xdeff, 0x003f, 0x0000, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xefff, 0x003f, 0x0000, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xfb7f, 0x003f, 0x0000, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffbf, 0x003f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffbf, 0x003f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffdf, 0x013f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffef, 0x003f, 0x0000, 0x0000, - 0x0000, 0xff00, 0xffff, 0xffff, 0x3fff, 0xfff9, 0x003f, 0x0000, 0x0000, - 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, 0x0000, 0x0000, - 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, 0x0000, 0x0000, - 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, - 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, - 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, - 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, - 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x0001, 0x0000, 0x0000, - 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0x001f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000 }; - -#define level_mask_width 144 -#define level_mask_height 129 -const static unsigned short level_mask_bits[] = { - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7c00, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0200, 0xfe00, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0740, 0xdc00, 0x0001, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03fe, 0xce00, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x01ff, 0xde1f, 0x0001, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x802e, 0xfe1f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x4000, 0x0044, 0xc000, 0xc007, 0x7c1d, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfee8, 0x00ff, 0x8000, 0xc00f, 0x0e38, 0x0000, - 0x0000, 0x0000, 0x0000, 0xffff, 0x17ff, 0x0000, 0xc3df, 0x1c3f, 0x0000, - 0x0000, 0x0000, 0xa000, 0xffff, 0x3fff, 0x0000, 0xe3ff, 0x0e3f, 0x0000, - 0x0000, 0x0000, 0xff00, 0xffff, 0x7fff, 0x0000, 0xc07f, 0x1c7d, 0x0000, - 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x0000, 0xe03e, 0x0e30, 0x0000, - 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, 0x0017, 0xc03e, 0x1c71, 0x0000, - 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0x001f, 0x8038, 0x0020, 0x0000, - 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0x007f, 0x003c, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfff8, 0xffff, 0xffff, 0x00ff, 0x0020, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, - 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0001, 0x0000, 0x0000, - 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, - 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, - 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, - 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, 0x0150, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x03f0, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x1ff8, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x1ef8, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x147c, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0038, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x707c, 0x0054, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0xf0fc, 0x00fc, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0xf1fc, 0x01fc, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0xf80e, 0x00ee, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0xf00e, 0x00fc, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0xf808, 0x00fe, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x7800, 0x007e, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0xe000, 0x000e, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x4000, 0x0006, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x000e, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0004, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0020, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0054, 0x007c, - 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x00f8, 0x00f8, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x117c, 0x01fc, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x3818, 0x00fc, - 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x7c5c, 0x00fc, - 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0xfef8, 0x000c, - 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x7ff8, 0x001c, - 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, 0xfe38, 0x000c, - 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x7e30, 0x001c, - 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0xee30, 0x000c, - 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0x5e70, 0x001c, - 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, 0x0e20, 0x000c, - 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, 0x0c60, 0x000c, - 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0800, 0x0000, - 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x3c00, 0xfffe, 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, - 0xd000, 0x7e41, 0xfffc, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, - 0xf800, 0xeee3, 0xfff8, 0xffff, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, - 0xff00, 0x6cfd, 0xfff0, 0xffff, 0xffff, 0x001f, 0x0000, 0x0000, 0x0000, - 0x3f80, 0xecf8, 0xff80, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, - 0x3f00, 0x7fdc, 0xff00, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, - 0xbe00, 0x3ffb, 0xa000, 0xbfbb, 0x2bbf, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfe00, 0x1ffb, 0x0000, 0x1f00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfc00, 0x1fbb, 0x0000, 0x3e00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x7c00, 0x1d39, 0x0000, 0x7c00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x3800, 0x1838, 0x0000, 0xf800, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x7000, 0x0018, 0x0000, 0xfc00, 0x0001, 0x07c0, 0x0000, 0x0000, 0x0000, - 0x6000, 0x0000, 0x0000, 0xf800, 0x0003, 0x0e80, 0x0000, 0x0000, 0x0000, - 0x7000, 0x0000, 0x0100, 0xfc00, 0x0007, 0x1d00, 0x0000, 0x0000, 0x0000, - 0x6000, 0x0000, 0x0080, 0x7800, 0x000e, 0x3800, 0x0000, 0x0000, 0x0000, - 0x4000, 0x0000, 0x00c0, 0xfc00, 0x001c, 0x7000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x00e0, 0xc800, 0x0038, 0xe000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x1060, 0xdc00, 0x0071, 0x4000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x3860, 0x8800, 0x00e0, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x1c60, 0x9c00, 0x01c1, 0x1c00, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0860, 0x8800, 0x0383, 0x3800, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x9c40, 0x1c01, 0x1f03, 0x7100, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x8e00, 0x1801, 0x1a03, 0x6300, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xcc00, 0x1c00, 0x3c07, 0x4700, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xec00, 0x0800, 0x2002, 0xc600, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x7000, 0x1c00, 0x3007, 0xc600, 0x0001, 0x0000, 0x0000, - 0x0000, 0x0000, 0x6000, 0x0c00, 0x3002, 0x8c00, 0x0201, 0x0000, 0x0000, - 0x0000, 0x0000, 0x6000, 0x0c00, 0x3006, 0x9c00, 0x0701, 0x0000, 0x0000, - 0x0000, 0x0000, 0xe000, 0x0e00, 0x2002, 0x1800, 0x0600, 0x0000, 0x0000, - 0x0000, 0x0000, 0x4000, 0x0700, 0x3007, 0x3800, 0x0700, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0300, 0x3802, 0x3800, 0x0600, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0780, 0x1806, 0x1000, 0x0400, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0380, 0x0806, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x01c0, 0x1c06, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0180, 0x0806, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x05c0, 0x1c06, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0f80, 0x080e, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x1f00, 0x0406, 0x0000, 0x0000, 0x0000, 0x0000 }; - -#define llama_width 240 -#define llama_height 260 -const static unsigned short llama_bits[] = { - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8400, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0800, 0x0000, 0x0004, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0680, 0xf000, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0600, 0xe000, 0x000f, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0700, 0xe000, 0x021f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x1780, 0xc000, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x07c0, 0x8000, 0x21ff, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x07c0, 0x8000, 0x07ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0fe0, 0x0000, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x07e4, 0x0000, 0x3ffe, - 0x0002, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0ff0, 0x0000, 0x7ffc, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x07f0, 0x0000, 0xfff8, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x2ff0, 0x0000, 0xfff1, - 0x0023, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0ff8, 0x0000, 0xfff0, 0x0007, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0ff8, 0x0000, 0xffe0, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0ff8, 0x0000, 0xffc0, - 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0ff8, 0x0000, 0xff80, 0x003f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0ffc, 0x0000, 0xff00, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0ffc, 0x0000, 0xfe00, - 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x4ff8, 0x0000, 0xfc00, 0x01ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0dfc, 0x0000, 0xfc80, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1bf8, 0x0000, 0xf800, - 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x93f8, 0x0000, 0xf000, 0x03ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x17f8, 0x0000, 0xe000, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0ff0, 0x0001, 0xc010, - 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x1ff0, 0x0000, 0xc000, 0x0fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x3fe0, 0x0800, 0x8000, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7fc4, 0x2082, 0x0040, - 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff88, 0x0c00, 0x0000, 0x0fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xff00, 0x7103, 0x0000, 0x0ffe, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xe003, 0x0028, - 0x07fc, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x7800, 0x81f8, 0x0087, 0x07f8, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x3000, 0x9f00, 0x400f, 0x07f8, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0x7e00, 0x004e, - 0x23fa, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfbfe, 0x005f, 0x03f6, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x8400, 0xf7ff, 0x003f, 0x03f6, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0x80ff, - 0x11e6, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf080, 0xffff, 0x80ff, 0x01e6, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfc00, 0xffff, 0x01ff, 0x08ee, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x01ff, - 0x00ee, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0x03ff, 0x056e, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xff80, 0xffff, 0x07ff, 0x00ae, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xdfc0, 0xffff, 0x0fff, - 0x008e, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xe1e0, 0xffff, 0x4ffe, 0x00ce, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xf0e0, 0x07ff, 0x9ff0, 0x016e, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf874, 0x40ff, 0x3fe1, - 0x0066, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x3d30, 0x3f20, 0x7f8c, 0x0027, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0c08, 0x0f82, 0x6f90, 0x00b7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x2208, 0x01c0, 0x1e40, - 0x0017, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0002, 0x00a8, 0xbe80, 0x0017, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0404, 0x0020, 0x7900, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe018, 0xf20f, - 0x000b, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf01c, 0xf63b, 0x000e, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x4002, 0x3c1e, 0xcc84, 0x0125, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x2800, 0xdf1f, 0xd93f, - 0x0073, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xc000, 0xe7df, 0xb67f, 0x00f7, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xc000, 0xf3ff, 0x3cff, 0x04f7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe500, 0xfbff, 0x7dff, - 0x01f7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf200, 0xfdff, 0xfbff, 0x13fe, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xf940, 0xfeff, 0xf7ff, 0x03fe, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc80, 0xff7f, 0xffff, - 0x27fd, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfe10, 0xff7f, 0xefff, 0x0ffb, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfe00, 0x3fbf, 0xeff8, 0x0ffb, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0x01ff, 0xfe00, - 0x9fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff80, 0x007f, 0xd808, 0x1ff7, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xffc0, 0x0c07, 0xe7dc, 0x3ff7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe4, 0x0f0f, 0xdfc0, - 0x7fef, 0x0002, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff0, 0x1f7f, 0xfff0, 0x7fef, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfff0, 0x7fff, 0xfffc, 0xffef, 0x0004, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff9, 0xffff, 0xffff, - 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffc, 0xfeff, 0xffff, 0xffff, 0x0001, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfffc, 0xfdff, 0xffff, 0xffdf, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, - 0xffdf, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x2000, 0xffff, 0xfbff, 0xdfff, 0xffdf, 0x0003, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xffff, 0xfbff, 0xdfff, 0xfddf, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, 0xffff, 0xe7ff, 0xefff, - 0xffdf, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x8000, 0xffff, 0xdfff, 0xf7ff, 0xff9f, 0x004f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, - 0xffff, 0xbfff, 0xf1ff, 0xff9f, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0x6fff, 0xfc7c, - 0xff9f, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xfe01, 0xfb9f, 0x001f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe200, - 0xffff, 0x9fff, 0xffff, 0xfb9f, 0x011f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0x7fff, 0xffff, - 0xfb9f, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xf100, 0xffff, 0xffff, 0xfff8, 0xfbdf, 0x003f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, - 0xfbff, 0xffff, 0xfe03, 0xf7df, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xfe7f, 0xfff9, 0xffff, - 0xf7cf, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xf800, 0xffbf, 0xfffb, 0xffff, 0xf7c7, 0x007f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, - 0xffcf, 0xffff, 0xffff, 0xf7e3, 0x04ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xfff7, 0xfff7, 0x3fff, - 0xf7e0, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xe200, 0xfffb, 0xfff7, 0x07ff, 0xf7f8, 0x01ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, - 0xfffc, 0xfff7, 0xc07f, 0xf7ff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xfffe, 0xfff7, 0xf81f, - 0xf7ff, 0x09ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x2400, 0xffff, 0xfffb, 0xff07, 0xe7ff, 0x01ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7000, - 0xffff, 0xfff9, 0xfff0, 0xf7ff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xb800, 0xffff, 0x7ff8, 0xfffc, - 0xe7ff, 0x13ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x9c00, 0x3fff, 0x9ffe, 0xffff, 0xf7ff, 0x07ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xdc00, - 0x1fff, 0xe7ff, 0xffff, 0xe7ff, 0x05ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xef00, 0xc1ff, 0xf9ff, 0xffff, - 0xf7ff, 0x05ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xef80, 0xf01f, 0xfcff, 0xffff, 0xf1ff, 0x03ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x37c0, - 0xfc00, 0xff5f, 0xffff, 0xf1ff, 0x0bff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffaf, 0xffff, - 0xf1ff, 0x0bfb, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xff80, 0xffff, 0xffd7, 0xffff, 0xf3ff, 0x1ffb, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8800, 0xffff, - 0xffff, 0x0077, 0xfff8, 0xf2ff, 0x17fb, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xf03b, 0xffef, - 0xf2ff, 0x97fb, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8800, 0xffff, 0xffff, 0xfc01, 0xffff, 0xf2ff, 0x27fb, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, - 0xffff, 0xe001, 0xffff, 0xf97f, 0x2ff3, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0xfffe, 0xffff, 0xc380, 0xffff, - 0xf97f, 0x0ff7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfff8, 0xffff, 0x3fa0, 0xffff, 0xfc7f, 0x4ff7, 0x0001, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, - 0x7fff, 0x7f80, 0xfffe, 0xfc3f, 0x0ff7, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc4, 0x3fff, 0xffc1, 0xfffd, - 0xfcbf, 0x1ff7, 0x0002, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xff80, 0x3fff, 0xffc0, 0xffff, 0xfe9f, 0x1ff7, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff10, - 0xbfff, 0xffe0, 0xffff, 0xfe9f, 0x1ff7, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0x1fff, 0xfff0, 0xffff, - 0xffdf, 0x3ffb, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xf800, 0x4fff, 0xfff8, 0xffff, 0xffcf, 0x3fef, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe100, - 0x07ff, 0xfff8, 0xffff, 0xffcf, 0x3fe9, 0x0001, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0x87ff, 0xffdc, 0xffff, - 0xffe7, 0x3fef, 0x0008, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x03ff, 0xfffe, 0xffff, 0xffe7, 0x3fe9, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x00f8, 0xfff7, 0xffff, 0xffe7, 0x7fe9, 0x0002, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x2000, 0xfff7, 0xffff, - 0xffe7, 0x7fe9, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x8000, 0xfff9, 0xffff, 0xfff3, 0xffe9, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xc002, 0xfff8, 0xffff, 0xfff3, 0xffe9, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x4008, 0xfffc, 0xffff, - 0xfff1, 0xffc9, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, 0xfff9, 0xffc9, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xffff, 0xffff, 0xfff8, 0xffc9, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, 0xfffe, 0xffff, - 0xfff8, 0x3fd9, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x4000, 0xfffe, 0xffff, 0xfffc, 0x07d9, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xa000, 0xffff, 0x7fff, 0xfffc, 0xf0d9, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xd000, 0xffff, 0x7fff, - 0xfffc, 0xf859, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xc200, 0xffff, 0x7fff, 0xfffe, 0x7e19, 0x0008, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xf000, 0xffff, 0x3fff, 0xfffe, 0x1f81, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x3fff, - 0xfffe, 0x07d1, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x3fff, 0xffff, 0x01f9, 0x0000, - 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x7e80, 0xfffe, 0x3fff, 0xffff, 0x0078, 0x8000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3c00, 0xffff, 0x3fff, - 0x7fff, 0x0008, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xbe00, 0xffff, 0x9fff, 0x1fff, 0x0000, 0x8000, - 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x9e00, 0xffff, 0x9fff, 0x07ff, 0x0200, 0x2000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xce00, 0xffff, 0x9fff, - 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xce00, 0xffff, 0xcfff, 0x001f, 0x0002, 0x4000, - 0x8010, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xc600, 0xffff, 0x0fff, 0x0000, 0x0000, 0x4000, 0x1fc0, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xa200, 0xffff, 0x0fff, - 0x0000, 0x0000, 0x4000, 0x79f0, 0x0002, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xa000, 0xffff, 0x0fff, 0x0080, 0x0000, 0x6800, - 0x8ff0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xe000, 0xffff, 0x0fff, 0x0000, 0x0000, 0x6000, 0xfff2, 0x0004, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xd400, 0xffff, 0x0fff, - 0x0000, 0x0000, 0x6000, 0xfff9, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xd000, 0xfffb, 0x0fff, 0x0000, 0x0000, 0x6000, - 0xfbf8, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xc200, 0xfffd, 0x07ff, 0x0000, 0x0000, 0x6000, 0x81fc, 0x001f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xfffd, 0x07ff, - 0x0000, 0x0000, 0x6000, 0x007c, 0x001c, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xc000, 0xfffd, 0x17ff, 0x0000, 0x0000, 0x6000, - 0x023c, 0x0060, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x8000, 0xfffd, 0x17ff, 0x0000, 0x0000, 0xe000, 0x003e, 0x0084, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xfffe, 0x07ff, - 0x0000, 0x0000, 0xc000, 0x001e, 0x0040, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xe000, 0xfffe, 0x17ff, 0x0000, 0x0000, 0xc000, - 0x200e, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xe000, 0xfffe, 0x0fff, 0x0000, 0x0000, 0xc000, 0x000f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xfffe, 0x0fff, - 0x0000, 0x0000, 0xc000, 0x07e7, 0x0801, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xe000, 0xfffe, 0x0fff, 0x0000, 0x0000, 0xc000, - 0x1ff7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x6000, 0xfffa, 0x0fff, 0x0000, 0x0000, 0xc000, 0x7e3b, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0xfffa, 0x5fff, - 0x0000, 0x0000, 0x8000, 0xf00f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfffa, 0x0fff, 0x0000, 0x0000, 0x8000, - 0xc007, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xfffa, 0x1fff, 0x0000, 0x0000, 0x9000, 0x1003, 0x0013, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1000, 0xfffa, 0x1fff, - 0x0000, 0x0000, 0x8000, 0x000b, 0x0002, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfff8, 0x1fff, 0x0000, 0x0000, 0x8000, - 0x0001, 0x0004, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x8000, 0xfff0, 0x9fff, 0x0000, 0x0000, 0xa000, 0x0001, 0x002a, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0x1fff, - 0x0000, 0x0000, 0x0000, 0x0005, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0x1fff, 0x0000, 0x0000, 0x0000, - 0x0005, 0x0010, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xffe0, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0001, 0x0040, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0x1fff, - 0x0000, 0x0000, 0x4000, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xffc4, 0x3fff, 0x0000, 0x0000, 0x0000, - 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xffc0, 0x3fff, 0x0001, 0x0000, 0x0000, 0x0003, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe88, 0x3fff, - 0x0000, 0x0000, 0x0000, 0x0100, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfd80, 0x3fff, 0x0000, 0x0000, 0x0000, - 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xfb00, 0x3fff, 0x0000, 0x0000, 0x8000, 0x41ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfa00, 0x3fff, - 0x0000, 0x0000, 0xc800, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0x7fff, 0x0000, 0x0000, 0xe000, - 0x1fff, 0x0004, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xe000, 0x7fff, 0x0004, 0x0000, 0xf000, 0x7fff, 0x0010, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe080, 0xffff, - 0x0000, 0x0000, 0xf000, 0xffff, 0x0040, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xc900, 0xffff, 0x2000, 0x0000, 0xf000, - 0xffff, 0x0083, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8800, 0xffff, 0x0001, 0x0000, 0xf800, 0xffff, 0x0007, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, 0xffff, - 0x0001, 0x0002, 0xfc80, 0xffff, 0x041f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x2000, 0xffff, 0x0003, 0x0004, 0xfc00, - 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x7200, 0xffff, 0x1f87, 0x0000, 0xf440, 0xffff, 0x107f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7000, 0xfffe, - 0x3fc7, 0x0020, 0xf800, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x7800, 0xfffc, 0xffe3, 0x0001, 0xfc00, - 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x7c00, 0xfffc, 0xffe3, 0x0003, 0xfe00, 0xffff, 0x03ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7c00, 0xfffc, - 0xffe3, 0x000f, 0xff08, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x7e00, 0xfffa, 0xfff1, 0x083f, 0xffc0, - 0xffff, 0x07ff, 0x0010, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x7f00, 0xfffa, 0xfff9, 0x007f, 0xfff0, 0xffff, 0x07ff, 0x0040, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7f84, 0xfff2, - 0xfff8, 0x01ff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x7fc0, 0xfff6, 0xfffc, 0xc7ff, 0xffff, - 0xffff, 0x0fff, 0x0060, 0x0000, 0x2000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x7fe0, 0xfffe, 0xfffc, 0x1fff, 0xffff, 0xffff, 0x0fff, 0x00e0, - 0x0000, 0x0100, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7ff0, 0x7fee, - 0xfffe, 0xffff, 0xfffc, 0xffff, 0x0fff, 0x07c0, 0x0000, 0x0000, 0x0020, - 0x0000, 0x0000, 0x0000, 0x0000, 0x7ff8, 0x3fee, 0xfffe, 0xffff, 0xfff3, - 0xffff, 0x9fff, 0x07c0, 0x0000, 0xf020, 0x0007, 0x0000, 0x0000, 0x0000, - 0x0000, 0x7ffc, 0x3fde, 0xffff, 0xffff, 0xffff, 0xffff, 0x1fff, 0x3fc1, - 0x0002, 0xff00, 0x0021, 0x0000, 0x0000, 0x0000, 0x0000, 0x7ffe, 0x3fff, - 0xffff, 0xffff, 0xffff, 0xffff, 0x3fff, 0x7ec0, 0x0000, 0x3f88, 0x0084, - 0x0000, 0x0000, 0x0000, 0x8000, 0x3fff, 0x9fff, 0xffff, 0xffff, 0xffff, - 0xffff, 0x7fff, 0x8006, 0x0001, 0x6080, 0x003e, 0x0000, 0x0000, 0x0000, - 0xc080, 0xbfff, 0x9fff, 0xffff, 0xffff, 0xffff, 0xbfff, 0x7fff, 0x00fe, - 0x0003, 0xbff0, 0x003f, 0x0000, 0x0000, 0x0000, 0xf000, 0x9fff, 0xdffd, - 0xffff, 0xffff, 0xffff, 0xe7ff, 0xffff, 0x1ffc, 0x0004, 0xdff8, 0x001f, - 0x0000, 0x0000, 0x0000, 0xfc00, 0x9fff, 0xcffd, 0xffff, 0xffff, 0xffff, - 0xf9ff, 0xffff, 0xfff9, 0x1019, 0xe7f8, 0x004f, 0x0000, 0x0000, 0x0000, - 0xfe04, 0xdfff, 0xeffe, 0xffff, 0xffff, 0xffff, 0xfcff, 0xffff, 0x0fd3, - 0x0070, 0xf7fc, 0x002f, 0x0000, 0x0000, 0x0000, 0xff80, 0x4fff, 0xf7fe, - 0xffff, 0xffff, 0xffff, 0xfe3f, 0xffff, 0xffe7, 0xf0fc, 0xfbfd, 0x0033, - 0x0000, 0x0000, 0x4000, 0xffe0, 0x6fff, 0xf7fe, 0xffff, 0xffff, 0xffff, - 0xfd9f, 0xffff, 0xff9f, 0xfffb, 0xfbfd, 0x003b, 0x0000, 0x0000, 0x0000, - 0xfff8, 0x27ff, 0xf3ff, 0xffff, 0xffff, 0xffff, 0xf9cf, 0xffff, 0xffbf, - 0xffe3, 0xfbfe, 0x001c, 0x0000, 0x0000, 0x0140, 0xffff, 0x13ff, 0xf9ff, - 0xffff, 0xffff, 0xffff, 0xe7e3, 0xffff, 0xffff, 0xffcf, 0x7bfe, 0x009f, - 0x0000, 0x0000, 0xe000, 0xffff, 0x8bff, 0xfdff, 0xffff, 0xffff, 0xffff, - 0xc7f1, 0xffff, 0xffff, 0x7f1f, 0x97fe, 0x000f, 0x0000, 0x8000, 0xff78, - 0xffff, 0x91ff, 0xfeff, 0xffff, 0xffff, 0xffff, 0xcff8, 0xffff, 0xffff, - 0xf87f, 0x30c3, 0x000f, 0x0000, 0x0000, 0xc1fc, 0xffff, 0xd9ff, 0xfe03, - 0xffff, 0xffff, 0x7fff, 0x9ff8, 0xffff, 0xffff, 0xe07f, 0xffbf, 0x0006, - 0x0000, 0x0000, 0x007e, 0xffff, 0xccff, 0xfc00, 0xffff, 0xffff, 0x7fff, - 0x9ffc, 0xffff, 0xffff, 0xc1ff, 0xffff, 0x0001, 0x0000, 0x9000, 0x3e1f, - 0xfffc, 0x07ff, 0xf0f8, 0xffff, 0xfff7, 0x3fff, 0x3ffe, 0xffff, 0xffff, - 0x01ff, 0xfffc, 0x0000, 0x0000, 0x8000, 0xff8f, 0xfff8, 0x07ff, 0xe1ff, - 0xffff, 0xffff, 0x1fff, 0x3ffe, 0xffff, 0xffff, 0x03ff, 0x7ff0, 0x0000, - 0x0000, 0xc000, 0xffe3, 0xffe3, 0xe07f, 0xc7ff, 0xffff, 0xfffb, 0x0fff, - 0x3dfb, 0xffff, 0xffff, 0x8fdf, 0x0000, 0x0000, 0x0000, 0xe000, 0xfff3, - 0xffc7, 0xf80f, 0x8fff, 0xffff, 0xfffb, 0x8fff, 0x33cf, 0xfffe, 0xffff, - 0x8fbf, 0x0000, 0x0004, 0x0000, 0xf000, 0xeff9, 0x0b1f, 0xffc0, 0x3fff, - 0xffff, 0xfffb, 0x07ff, 0x081c, 0xfffe, 0xffff, 0x18ff, 0x0001, 0x0001, - 0x0000, 0xf900, 0x9ffe, 0x007f, 0xfffe, 0x7fff, 0xfffe, 0xfffb, 0x07ff, - 0x0030, 0xfffe, 0xffff, 0x03ff, 0x2080, 0x0000, 0x0000, 0x7c80, 0x3ffe, - 0xfcff, 0xffff, 0x7fff, 0xfffe, 0xfffb, 0x03ff, 0x0001, 0xfffe, 0xffff, - 0x0f81, 0x0001, 0x0000, 0x0000, 0x7c00, 0x3801, 0xf3fc, 0xffff, 0xffff, - 0xfffc, 0xfffb, 0x03ff, 0x4020, 0xfffe, 0xffff, 0xe03f, 0x0002, 0x0000, - 0x0000, 0x3e00, 0x03f8, 0xcff9, 0xf77f, 0xffff, 0xfff9, 0xfffb, 0x11ff, - 0x0000, 0xffdf, 0xfffc, 0x00ff, 0x0002, 0x0000, 0x0000, 0x8f00, 0xbfff, - 0x3fe3, 0xfb7c, 0x3fff, 0xfffa, 0xfffb, 0x01ff, 0x4000, 0xf07e, 0x0003, - 0x1000, 0x0001, 0x0000, 0x0000, 0xc380, 0xffff, 0xffcf, 0xff82, 0xbfe5, - 0xfff1, 0xfff3, 0x00ff, 0x4000, 0x00fc, 0x0000, 0x0400, 0x0000, 0x0000, - 0x0000, 0xf3c0, 0xffff, 0xff8f, 0xfd9f, 0xbfde, 0xfff7, 0xfffb, 0x08ff, - 0x8000, 0x43e0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfce0, 0xffff, - 0xff00, 0xbcbf, 0xdfbf, 0xffc7, 0xfff3, 0x00ff, 0x0000, 0x0000, 0xa0d0, - 0x0006, 0x0000, 0x0000, 0x0000, 0xfe70, 0x1fff, 0xfe7c, 0xbc3f, 0xdfff, - 0x7fcf, 0xfff3, 0x047f, 0x0000, 0x0004, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xff3c, 0xc0ff, 0xf8fe, 0xddff, 0xde7f, 0x7f1f, 0xfff3, 0x003f, - 0x0000, 0x0480, 0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0xff9e, 0xf81f, - 0xf1fe, 0xec07, 0xdeff, 0x7f3f, 0xfff3, 0x003f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x7fcd, 0x0ec0, 0x47fe, 0xe5e0, 0xdeff, - 0xfe3f, 0xfff2, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xc000, 0x07ee, 0x77f8, 0x0ffe, 0xf5fc, 0xddff, 0xfe7f, 0xfff6, 0x003f, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x6000, 0x0007, 0x79ff, - 0x0ffe, 0xf0ff, 0xddff, 0xfcff, 0xfff4, 0x001f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xbe17, 0x7f7f, 0xe7ff, 0xf8ff, 0xd9ff, - 0xfcff, 0xfff4, 0x011f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xc000, 0xdf3b, 0x7f7f, 0x11ff, 0xf8fe, 0xdbff, 0xf8ff, 0xffe4, 0x001f, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe200, 0xefbf, 0x3fbf, - 0xb1ff, 0xfcff, 0xd3ff, 0xf9ff, 0xffed, 0x001f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf800, 0xf79f, 0xbfdf, 0xcfff, 0xfcff, 0xd7ff, - 0xf1ff, 0xffe9, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfc40, 0xf79f, 0xdfdf, 0xe3ff, 0xfcff, 0xd7ff, 0xf3ff, 0xffe9, 0x000f, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff90, 0xfb9f, 0xcfe7, - 0xf800, 0xfeff, 0xd7ff, 0xf3ff, 0xffc3, 0x000f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfc00, 0xfd85, 0x07f3, 0xfc00, 0xfc7f, 0xafff, - 0xe3ff, 0xffd3, 0x0083, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0010, 0xfd80, 0x03f9, 0xde00, 0xfc7f, 0xafff, 0xe7ff, 0x7fc3, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0080, 0x7e80, 0x00fc, - 0xe700, 0xfc7f, 0xafff, 0xe7ff, 0x07c3, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x2000, 0x1e80, 0x203e, 0xf1c0, 0xfc7f, 0x8fff, - 0xe7ff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0300, 0x001e, 0xfc60, 0xf87f, 0x8fff, 0xe7ff, 0x0003, 0x0010, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0100, - 0xfe08, 0xf8ff, 0x4fff, 0xcfff, 0xc003, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe4, 0xe0ff, 0x4fff, - 0xcfff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff2, 0xc1ff, 0x4fff, 0xcfff, 0x0187, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0040, 0x0000, - 0xfffc, 0x83ff, 0x0fff, 0xcfff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0xfffc, 0x0fff, 0x1ffe, - 0xcffe, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffe, 0x1fff, 0x0ffc, 0xc7f8, 0x0007, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, - 0xf80f, 0x7fff, 0xcfe0, 0xe381, 0x004f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0xffc0, 0xffff, 0xcf80, - 0xe007, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff00, 0xf7ff, 0xe007, 0xc00f, 0x0007, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0200, - 0xc000, 0xfc2f, 0xe01f, 0x303f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xf83d, - 0x003f, 0x0100, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0020, 0x8000, 0xff81, 0x0201, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x1fe0, 0x2040, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0001, - 0x0008, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x2000, 0x0000, 0x0002, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x4000, 0x2000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0202, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000 }; - -#define llama_mask_width 240 -#define llama_mask_height 260 -const static unsigned short llama_mask_bits[] = { - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0e00, 0xfc00, 0x0007, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0f80, 0xfc00, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0f80, 0xfc00, 0x00ff, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0fc0, 0xfc00, 0x03ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x1fe0, 0xf800, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1ff0, 0xf000, 0x3fff, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x1ff0, 0xe000, 0x7fff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x1ff8, 0xe000, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1ffc, 0xc000, 0xffff, - 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x1ffc, 0x8000, 0xffff, 0x0007, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x1ffc, 0x8000, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3ffe, 0x0000, 0xffff, - 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x3ffe, 0x0000, 0xfffe, 0x007f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x3fff, 0x0000, 0xfffc, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3fff, 0x0000, 0xfff8, - 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x3fff, 0x0000, 0xfff0, 0x03ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x3fff, 0x0000, 0xffe0, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3fff, 0x0000, 0xffc0, - 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x7fff, 0x0000, 0xff80, 0x1fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x7fff, 0x0000, 0xff80, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7fff, 0x0000, 0xff00, - 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xffff, 0x0000, 0xfe00, 0x7fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xffff, 0x0000, 0xfc20, 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0x0001, 0xf830, - 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffe, 0x00c1, 0xf030, 0x7fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfffc, 0x6f81, 0xe030, 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xff83, 0xe071, - 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff8, 0xff07, 0xc073, 0x7fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xffe0, 0xfdff, 0xc077, 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0xc07f, - 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xc0ff, 0x3fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfe00, 0xffff, 0xc0ff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x80ff, - 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0x81ff, 0x1fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfc00, 0xffff, 0x81ff, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x83ff, - 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0x83ff, 0x0fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xff80, 0xffff, 0x07ff, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0x0fff, - 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0x0fff, 0x07ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfff0, 0xffff, 0x1fff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0xffff, 0x3fff, - 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, 0x7fff, 0x01ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfff8, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, - 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xff7c, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3fbc, 0xfff0, 0xffff, - 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0f9e, 0xfff9, 0xffff, 0x003f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x878e, 0xfffb, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc186, 0xffff, 0xffff, - 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xe082, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xf002, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, - 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfe00, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, - 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xffc0, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, - 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfffc, 0xffff, 0xffff, 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, - 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, 0xffff, 0xffff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfff8, 0xffff, 0xffff, 0xffff, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, - 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfffe, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, - 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, - 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, - 0xffff, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, - 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, - 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, - 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, - 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, - 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, - 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, - 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, - 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x03ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, - 0xffff, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, - 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, - 0xffff, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, - 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0fff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, - 0xffff, 0xffff, 0xffff, 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, - 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x1fff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, - 0xffff, 0xffff, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, - 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff8, - 0xffff, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0xffff, - 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffcf, 0xffff, - 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xffff, 0xffff, 0xffe3, 0xffff, 0xffff, 0xffff, 0x0001, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, - 0xffff, 0xffe1, 0xffff, 0xffff, 0xffff, 0x0001, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xfff1, 0xffff, - 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfff8, 0xffff, 0xfff8, 0xffff, 0xffff, 0xffff, 0x0003, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, - 0xffff, 0xfff8, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0x7fff, 0xfffc, 0xffff, - 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xff80, 0x7fff, 0xfffe, 0xffff, 0xffff, 0xffff, 0x0007, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, - 0x3fff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xbfff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x000d, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xf800, 0x9fff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0009, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, - 0xcfff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0013, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xefff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xe7ff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xf3fe, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf1f8, 0xffff, 0xffff, - 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, - 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, - 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, - 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, - 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xff80, 0xffff, 0xffff, 0xffff, 0x7fff, 0x8000, 0x0001, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, - 0xffff, 0x3fff, 0x8000, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0x07ff, 0xc000, - 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xff80, 0xffff, 0xffff, 0xffff, 0x03ff, 0xe000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, - 0xffff, 0x003f, 0xe000, 0x3fc0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0x0003, 0xf000, - 0xfff0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xff80, 0xffff, 0xffff, 0x1fff, 0x0000, 0xf000, 0xfff8, 0x0001, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, - 0x07ff, 0x0000, 0xf000, 0xfff8, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x00ff, 0x0000, 0xf800, - 0xfffc, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xff80, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, 0xfffe, 0x0007, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0x3fff, - 0x0000, 0x0000, 0xf800, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, - 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xff80, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, 0xffff, 0x007f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfd80, 0xffff, 0x3fff, - 0x0000, 0x0000, 0xf800, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfd00, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, - 0x03ff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfc00, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, 0x01ff, 0x03fc, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x3fff, - 0x0000, 0x0000, 0xf800, 0x007f, 0x07c0, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, - 0x3fff, 0x0f00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfc00, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, 0xffff, 0x0c00, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x3fff, - 0x0000, 0x0000, 0xf000, 0xffff, 0x0801, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf000, - 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xf800, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf000, 0xffff, 0x0003, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x7fff, - 0x0000, 0x0000, 0xf000, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x7fff, 0x0000, 0x0000, 0xf000, - 0xfc3f, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xf800, 0xffff, 0x7fff, 0x0000, 0x0000, 0xf000, 0xf00f, 0x001f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0x7fff, - 0x0000, 0x0000, 0xe000, 0xc00f, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x8000, 0xffff, 0x7fff, 0x0000, 0x0000, 0xe000, - 0x0007, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x8000, 0xffff, 0xffff, 0x0000, 0x0000, 0xe000, 0x0007, 0x003e, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, - 0x0000, 0x0000, 0xc000, 0x0007, 0x0038, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0x0000, 0x0000, 0xc000, - 0x0007, 0x0030, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xfffe, 0xffff, 0x0000, 0x0000, 0xc000, 0x0007, 0x0060, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, - 0x0000, 0x0000, 0xc000, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0x0000, 0x0000, 0x8000, - 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xfff8, 0xffff, 0x0001, 0x0000, 0x8000, 0x000f, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, - 0x0001, 0x0000, 0x8000, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0xffff, 0x0001, 0x0000, 0xe000, - 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xffe0, 0xffff, 0x0001, 0x0000, 0xf000, 0x7fff, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, - 0x0003, 0x0000, 0xf800, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0x0003, 0x0000, 0xfc00, - 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xffc0, 0xffff, 0x0007, 0x0000, 0xfc00, 0xffff, 0x001f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, - 0x0fc7, 0x0000, 0xfe00, 0xffff, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0x3fe7, 0x0000, 0xff00, - 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xfc00, 0xffff, 0x7fe7, 0x0000, 0xff00, 0xffff, 0x01ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, - 0xffff, 0x0003, 0xff80, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0x0007, 0xff80, - 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xfe00, 0xffff, 0xffff, 0x000f, 0xffc0, 0xffff, 0x1fff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, - 0xffff, 0x003f, 0xffc0, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0x007f, 0xffc0, - 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xff80, 0xffff, 0xffff, 0x00ff, 0xffc0, 0xffff, 0x3fff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, - 0xffff, 0x01ff, 0xfff8, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0x7fff, 0x001c, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x007c, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x01fc, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0x7fff, 0x07fc, 0x0000, 0x2000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xfffe, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0ff8, - 0x0000, 0xff00, 0x0007, 0x0000, 0x0000, 0x0000, 0x8000, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x3ff8, 0x0000, 0xffc0, 0x003f, - 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xfff8, 0x0000, 0xffe0, 0x003f, 0x0000, 0x0000, 0x0000, - 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xfff1, - 0x0003, 0xfff0, 0x003f, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0xfff8, 0x00ff, - 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0x001f, 0xfff8, 0x00ff, 0x0000, 0x0000, 0x0000, - 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0x003f, 0xfffc, 0x00ff, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0xfffc, 0x00ff, - 0x0000, 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xf1ff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, - 0xfffc, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, - 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0xe000, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0xff7c, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, - 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x8000, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x007f, 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, - 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0xf000, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x001f, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, - 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0xfc00, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xfffe, 0x0007, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xfff1, 0x0001, - 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0x3f81, 0x0000, 0x0000, 0xff80, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x3fff, 0xf9ff, 0xffff, 0xffff, - 0xffff, 0x0001, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x1fff, 0xc1e0, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, - 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x1fff, - 0x8000, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0xffe0, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0fff, 0xc000, 0xffff, 0xffff, - 0xffff, 0x0001, 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x0fff, 0xc000, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, - 0x0000, 0xfff8, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0fff, - 0x8000, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0xfffe, 0xe0f0, - 0x0007, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x07ff, 0x0000, 0x7ffc, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x03ff, - 0x0000, 0x0f80, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, - 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, - 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, - 0xffe7, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0x3fff, 0xfff0, 0xffff, 0xffff, - 0xffff, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xffe0, 0x03ff, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0x01ff, - 0xfff8, 0xffff, 0xffff, 0xffff, 0xffef, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x8fe0, 0x007f, 0xfffc, 0xffff, 0xffff, - 0xffff, 0x00df, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x87e0, 0x003f, 0xfffe, 0xffff, 0xffff, 0xffff, 0x019f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8040, 0x0007, - 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, - 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, - 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, - 0xffff, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1e00, - 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0200, 0xfffc, 0xffff, 0xffff, - 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xffff, 0xffff, 0xe07f, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, - 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0xbf00, 0xffff, 0x0003, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0xc000, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03fe, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, - 0x0000, 0x0000, 0x0000 }; - - -#endif /* SPLASH_H_ */ +/* + * splash.h + * + * Created on: 16.3.2012 + * Author: Samba + */ + +#ifndef SPLASH_H_ +#define SPLASH_H_ + +#define oplogo_width 144 +#define oplogo_height 144 +const static unsigned short oplogo_bits[] = { + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x001e, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, 0x01ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0x07ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0x0fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0x3fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0x7fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0x0003, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0x0007, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0x000f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x001f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x00ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x07ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x0fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x1fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x3fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0x03ff, 0xffff, 0x0001, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0x03ff, 0xfffe, 0x0003, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0x01ff, 0xfff8, 0x000f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0x01ff, 0xffe0, 0x001f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0x01ff, 0xffc0, 0x003f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0x01ff, 0xff00, 0x007f, 0x0000, + 0x0000, 0x0000, 0x01f0, 0x0000, 0xff80, 0x00ff, 0xfe00, 0x01ff, 0x0000, + 0x0070, 0x0000, 0x07fc, 0x0000, 0xff80, 0x00ff, 0xf800, 0x03ff, 0x0000, + 0x07c0, 0x0000, 0x1fff, 0x0000, 0xffc0, 0x00ff, 0xf000, 0x07ff, 0x0000, + 0x7f80, 0xe000, 0x3fff, 0x0000, 0xffc0, 0x00ff, 0xc000, 0x0fff, 0x0000, + 0xfe00, 0xf803, 0x3fff, 0x0000, 0xffc0, 0x007f, 0x8000, 0x3fff, 0x0000, + 0xfc00, 0xfe3f, 0x1fff, 0x0000, 0xffc0, 0x007f, 0x0000, 0x7ffe, 0x0000, + 0xf000, 0xffff, 0x1fff, 0x0000, 0xffe0, 0x007f, 0x0000, 0xfffc, 0x0000, + 0xe000, 0xffff, 0x1fff, 0x0060, 0xffe0, 0x007f, 0x0000, 0xfff0, 0x0000, + 0x8000, 0xffff, 0x1fff, 0x01e0, 0xffe0, 0x003f, 0x0000, 0xffe0, 0x0001, + 0x0000, 0xffff, 0x0fff, 0x07f0, 0xfff0, 0x003f, 0x0000, 0xff80, 0x0003, + 0x0000, 0xfffc, 0x0fff, 0x1ff0, 0xfff0, 0x003f, 0x0000, 0xff00, 0x0003, + 0x0000, 0xfff8, 0x0fff, 0x7ff0, 0xfff0, 0x001f, 0x0000, 0xfe00, 0x0007, + 0x0000, 0xfff0, 0x0fff, 0xfff0, 0xfff0, 0x001f, 0x0000, 0xfc00, 0x0007, + 0x0000, 0xffc0, 0x0fff, 0xfff8, 0xffc3, 0x001f, 0x0000, 0xf800, 0x0007, + 0x0000, 0xffc0, 0x1fff, 0xfff8, 0xff0f, 0x001f, 0x0000, 0xf800, 0x0007, + 0x0000, 0xffc0, 0x3fff, 0xfff8, 0xfc3f, 0x000f, 0x0000, 0xf800, 0x0007, + 0x0000, 0xff80, 0x3fff, 0xfff8, 0xf8ff, 0x000f, 0x0000, 0xf800, 0x000f, + 0x0000, 0xff80, 0x3fff, 0xfffc, 0xe1ff, 0x000f, 0x0000, 0xf800, 0x000f, + 0x0000, 0xff00, 0x3fff, 0xfffc, 0x87ff, 0x000f, 0x0000, 0xf800, 0x000f, + 0x0000, 0xff00, 0x1fff, 0xfffc, 0x1fff, 0x0006, 0x0000, 0xf800, 0x000f, + 0x0000, 0xff00, 0x1fff, 0xfffc, 0x7fff, 0x0000, 0x0000, 0xf800, 0x000f, + 0x0000, 0xfe00, 0x1fff, 0xfffe, 0xffff, 0x0001, 0x0000, 0xf800, 0x000f, + 0x0000, 0xfe00, 0x0fff, 0xfffe, 0xffff, 0x0003, 0x0000, 0xf800, 0x000f, + 0x0000, 0xfc00, 0x01ff, 0xfffe, 0xffff, 0x000f, 0x0000, 0xf800, 0x000f, + 0x0000, 0xfc00, 0x01ff, 0xfffe, 0xffff, 0x003f, 0x0000, 0xf800, 0x000f, + 0x0000, 0xf800, 0x01ff, 0xffff, 0xffff, 0x00ff, 0x0000, 0xf800, 0x000f, + 0x0000, 0xf800, 0x00ff, 0xffff, 0xffff, 0x03ff, 0x0000, 0xf800, 0x000f, + 0x0000, 0xf800, 0x00ff, 0xffff, 0xffff, 0x0fff, 0x0000, 0xf800, 0x000f, + 0x0000, 0xf000, 0x00ff, 0xffff, 0xffff, 0x3fff, 0x0000, 0xf800, 0x000f, + 0x0000, 0xf000, 0x807f, 0xffff, 0xffff, 0x7fff, 0x0000, 0xf800, 0x000f, + 0x0000, 0xe000, 0x807f, 0xffff, 0xffff, 0xffff, 0x0001, 0xf800, 0x000f, + 0x0000, 0x8000, 0x807f, 0xffff, 0xffff, 0xffff, 0x0007, 0xfc00, 0x000f, + 0x0000, 0x0000, 0x807c, 0xffff, 0xffff, 0xffff, 0x001f, 0xfc00, 0x000f, + 0x0000, 0x0000, 0xc020, 0xffff, 0xffff, 0xffff, 0x007f, 0xfc00, 0x000f, + 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0x00ff, 0xfc00, 0x000f, + 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0x03ff, 0xfc00, 0x000f, + 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0x0fff, 0xfc00, 0x000f, + 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, 0xffff, 0x3fff, 0xfc00, 0x000f, + 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xfc00, 0x000f, + 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xfc03, 0x000f, + 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xfe0f, 0x000f, + 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0xfe1f, 0x000f, + 0x0000, 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0x0600, 0xc000, 0xffff, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0x3e00, 0x0000, 0xfffe, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0xff00, 0x0001, 0xfff8, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0xff00, 0x000f, 0xffc0, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0xff00, 0x007f, 0xfe00, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0xff00, 0x03ff, 0xf000, 0xffff, 0xffff, 0x0007, + 0x0000, 0x0000, 0x0000, 0xff80, 0x03ff, 0xc000, 0xffff, 0xffff, 0x0007, + 0x0000, 0x0000, 0x0000, 0xff80, 0x03ff, 0x0000, 0xfffe, 0xffff, 0x0007, + 0x0000, 0x0000, 0x0000, 0xff80, 0x03ff, 0x0000, 0xfff0, 0xffff, 0x0007, + 0x0000, 0x0000, 0x0000, 0xffc0, 0x03ff, 0x0000, 0xff80, 0xffff, 0x0007, + 0x0000, 0x0000, 0x0000, 0xffc0, 0x01ff, 0x0000, 0xfe00, 0xffff, 0x0003, + 0x0000, 0x0000, 0x0000, 0xffc0, 0x01ff, 0x0000, 0xf000, 0xffff, 0x0003, + 0x0000, 0x0000, 0x0000, 0xffc0, 0x01ff, 0x0000, 0x8000, 0xffff, 0x0001, + 0x0000, 0x0000, 0x0000, 0xffe0, 0x01ff, 0x0000, 0x0000, 0xfffc, 0x0001, + 0x0000, 0x0000, 0x0000, 0xffe0, 0x00ff, 0x0000, 0x0000, 0xfff0, 0x0000, + 0x0000, 0x0000, 0x0000, 0xffe0, 0x00ff, 0x0000, 0x0000, 0x7f80, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff0, 0x00ff, 0x0000, 0x0000, 0x0c00, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff0, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff0, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff8, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff8, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff8, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff8, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xffe0, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xffc0, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff00, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfc00, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf000, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xc000, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x8000, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x000e, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1980, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x39c0, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3980, 0x0000, 0x0060, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3800, 0x0000, 0x0060, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3800, 0x0000, 0x00f0, + 0x0000, 0x03ff, 0x0ffc, 0x3ff0, 0xffc0, 0xff80, 0x3983, 0x7fe0, 0x07f8, + 0xc000, 0x07ff, 0x1fff, 0x7ffc, 0xfff0, 0xffc1, 0x39c7, 0xfff0, 0x07f9, + 0xe000, 0x8fff, 0x3fff, 0xfffe, 0xfff8, 0xffe3, 0x39cf, 0xfff8, 0x0063, + 0xe000, 0x9c00, 0x7003, 0xc00e, 0x8038, 0x00e3, 0x39ce, 0x801c, 0x0063, + 0x6000, 0x9c00, 0x7001, 0xc006, 0x0019, 0x0077, 0x39dc, 0x001c, 0x0063, + 0x6000, 0x9c00, 0x7001, 0xfffe, 0x0019, 0x0077, 0x39dc, 0x001c, 0x0063, + 0x6000, 0x9c00, 0x7001, 0xfffe, 0x0019, 0x0077, 0x39dc, 0x001c, 0x0063, + 0x6000, 0x9c00, 0x7001, 0x000e, 0x0018, 0x0077, 0x39dc, 0x001c, 0x0063, + 0xe000, 0x9c00, 0x7001, 0x000e, 0x0018, 0x0077, 0x39ce, 0x801c, 0x00e3, + 0xe000, 0xff8f, 0x3fff, 0x7ffe, 0x0018, 0xffff, 0xf1cf, 0xe0f8, 0x07e3, + 0xc000, 0xffff, 0x1fff, 0x7ffc, 0x0018, 0xffff, 0xf1c7, 0xfff0, 0x07c1, + 0x8000, 0xffff, 0x0fff, 0x7ff8, 0x0018, 0xffff, 0xc183, 0xffe0, 0x0780, + 0x0000, 0xc000, 0x0001, 0x0000, 0x0000, 0x0070, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8000, 0x0001, 0x0000, 0x0000, 0x0070, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8000, 0x0001, 0x0000, 0x0000, 0x0070, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8000, 0x0001, 0x0000, 0x0000, 0x0070, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8000, 0x0001, 0x0000, 0x0000, 0x0060, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000 }; + +const static unsigned short oplogo_mask_bits[] = { + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x003f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0x03ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0x0fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0x1fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0x7fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x0001, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x0007, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x000f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x001f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x003f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x00ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x03ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x0fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0x1fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0x3fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0x7fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x0001, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x0003, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x0007, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x001f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, 0x003f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0x8fff, 0xffff, 0x007f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0x07ff, 0xffff, 0x00ff, 0x0000, + 0x0000, 0x0000, 0x03f8, 0x0000, 0xffe0, 0x07ff, 0xfffc, 0x03ff, 0x0000, + 0x00f8, 0x0000, 0x0ffe, 0x0000, 0xffe0, 0x07ff, 0xfff0, 0x07ff, 0x0000, + 0x0ffc, 0x8000, 0x3fff, 0x0000, 0xffe0, 0x07ff, 0xffe0, 0x0fff, 0x0000, + 0xfffc, 0xf000, 0x7fff, 0x0000, 0xfff0, 0x03ff, 0xff80, 0x1fff, 0x0000, + 0xfffc, 0xfc07, 0xffff, 0x0000, 0xfff0, 0x03ff, 0xff00, 0x7fff, 0x0000, + 0xfff8, 0xff7f, 0xffff, 0x0000, 0xfff0, 0x03ff, 0xfc00, 0xffff, 0x0000, + 0xffe0, 0xffff, 0xffff, 0x0000, 0xfff0, 0x03ff, 0xf800, 0xffff, 0x0001, + 0xffc0, 0xffff, 0xffff, 0x00f0, 0xfff8, 0x01ff, 0xe000, 0xffff, 0x0003, + 0xff00, 0xffff, 0x7fff, 0x03f8, 0xfff8, 0x01ff, 0xc000, 0xffff, 0x0003, + 0xfe00, 0xffff, 0x7fff, 0x0ff8, 0xfff8, 0x01ff, 0x0000, 0xffff, 0x0007, + 0xf800, 0xffff, 0x7fff, 0x3ffc, 0xfffc, 0x01ff, 0x0000, 0xfffe, 0x000f, + 0xf000, 0xffff, 0x7fff, 0xfffc, 0xfffc, 0x00ff, 0x0000, 0xfff8, 0x000f, + 0xc000, 0xffff, 0x3fff, 0xfffc, 0xfffd, 0x00ff, 0x0000, 0xfff0, 0x001f, + 0x8000, 0xffff, 0x3fff, 0xfffc, 0xffff, 0x00ff, 0x0000, 0xffc0, 0x001f, + 0x0000, 0xfffe, 0x3fff, 0xfffe, 0xffff, 0x007f, 0x0000, 0xff80, 0x001f, + 0x0000, 0xfffc, 0x7fff, 0xfffe, 0xffff, 0x007f, 0x0000, 0xff00, 0x001f, + 0x0000, 0xfff8, 0xffff, 0xfffe, 0xffff, 0x007f, 0x0000, 0xfe00, 0x001f, + 0x0000, 0xfff0, 0xffff, 0xfffe, 0xffff, 0x007f, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0x001f, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0x001f, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xff80, 0xbfff, 0xffff, 0xffff, 0x01ff, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xff00, 0xdfff, 0xffff, 0xffff, 0x07ff, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xff00, 0xc7ff, 0xffff, 0xffff, 0x1fff, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xfe00, 0xc7ff, 0xffff, 0xffff, 0x7fff, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xfe00, 0xc3ff, 0xffff, 0xffff, 0xffff, 0x0000, 0xfe00, 0x003f, + 0x0000, 0xfe00, 0xe3ff, 0xffff, 0xffff, 0xffff, 0x0003, 0xfe00, 0x003f, + 0x0000, 0xfc00, 0xe3ff, 0xffff, 0xffff, 0xffff, 0x000f, 0xfe00, 0x003f, + 0x0000, 0xfc00, 0xe1ff, 0xffff, 0xffff, 0xffff, 0x003f, 0xff00, 0x003f, + 0x0000, 0xf800, 0xe1ff, 0xffff, 0xffff, 0xffff, 0x00ff, 0xff00, 0x003f, + 0x0000, 0xf000, 0xf1ff, 0xffff, 0xffff, 0xffff, 0x01ff, 0xff00, 0x003f, + 0x0000, 0xc000, 0xf1ff, 0xffff, 0xffff, 0xffff, 0x07ff, 0xff00, 0x003f, + 0x0000, 0x0000, 0xf0fe, 0xffff, 0xffff, 0xffff, 0x1fff, 0xff00, 0x003f, + 0x0000, 0x0000, 0xf070, 0xffff, 0xffff, 0xffff, 0x7fff, 0xff00, 0x003f, + 0x0000, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0xff01, 0x003f, + 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0xff07, 0x003f, + 0x0000, 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0xffff, 0xff1f, 0x003f, + 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, 0xffff, 0xffbf, 0x003f, + 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0x0f00, 0xfffc, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0x7f80, 0xffe0, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0xff80, 0xff83, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0xffc0, 0xfc1f, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0xffc0, 0xe0ff, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0xffc0, 0x07ff, 0xffff, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0xffc0, 0x0fff, 0xfffc, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0xffe0, 0x0fff, 0xffe0, 0xffff, 0xffff, 0x003f, + 0x0000, 0x0000, 0x0000, 0xffe0, 0x0fff, 0xff00, 0xffff, 0xffff, 0x001f, + 0x0000, 0x0000, 0x0000, 0xffe0, 0x0fff, 0xf800, 0xffff, 0xffff, 0x001f, + 0x0000, 0x0000, 0x0000, 0xfff0, 0x0fff, 0xe000, 0xffff, 0xffff, 0x001f, + 0x0000, 0x0000, 0x0000, 0xfff0, 0x0fff, 0x0000, 0xffff, 0xffff, 0x001f, + 0x0000, 0x0000, 0x0000, 0xfff0, 0x0fff, 0x0000, 0xfff8, 0xffff, 0x001f, + 0x0000, 0x0000, 0x0000, 0xfff0, 0x07ff, 0x0000, 0xffc0, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0xfff8, 0x07ff, 0x0000, 0xff00, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0xfff8, 0x07ff, 0x0000, 0xf800, 0xffff, 0x0007, + 0x0000, 0x0000, 0x0000, 0xfff8, 0x07ff, 0x0000, 0xc000, 0xffff, 0x0007, + 0x0000, 0x0000, 0x0000, 0xfffc, 0x03ff, 0x0000, 0x0000, 0xfffe, 0x0003, + 0x0000, 0x0000, 0x0000, 0xfffc, 0x03ff, 0x0000, 0x0000, 0xfff8, 0x0001, + 0x0000, 0x0000, 0x0000, 0xfffc, 0x03ff, 0x0000, 0x0000, 0xffc0, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffe, 0x01ff, 0x0000, 0x0000, 0x1e00, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffe, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffe, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffe, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffe, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffe, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffc, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff0, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xffe0, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff80, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfe00, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf800, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xe000, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xc000, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3fc0, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7fe0, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0x0000, 0x00f0, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0x0000, 0x01f8, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0x0000, 0x01f8, + 0x8000, 0x07ff, 0x1ffe, 0x7ff8, 0xffe0, 0xffc1, 0xffe7, 0xfff0, 0x0ffc, + 0xe000, 0x8fff, 0x3fff, 0xfffe, 0xfff8, 0xffe3, 0xffef, 0xfff8, 0x1fff, + 0xf000, 0xdfff, 0x7fff, 0xffff, 0xfffd, 0xfff7, 0xffff, 0xfffc, 0x1fff, + 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xfffe, 0x1fff, + 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x1fff, + 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0fff, + 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, + 0xf800, 0xff01, 0xfc07, 0xffff, 0xc07f, 0x01ff, 0xffff, 0xc07f, 0x01ff, + 0xf800, 0xff01, 0xfc07, 0xffff, 0xc07f, 0x01ff, 0xffff, 0xc07f, 0x01ff, + 0xf800, 0xffdf, 0xffff, 0xffff, 0xc07f, 0xffff, 0xffff, 0xf1ff, 0x0fff, + 0xf800, 0xffff, 0xffff, 0xffff, 0xc07f, 0xffff, 0xffff, 0xffff, 0x1fff, + 0xf800, 0xffff, 0xffff, 0xffff, 0xc07f, 0xffff, 0xffff, 0xffff, 0x1fff, + 0xf800, 0xffff, 0xffff, 0xffff, 0xc07f, 0xffff, 0xffff, 0xffff, 0x1fff, + 0xf000, 0xffff, 0x7fff, 0xffff, 0xc07f, 0xffff, 0xffff, 0xffff, 0x1ff7, + 0xe000, 0xffff, 0x3fff, 0xfffe, 0xc07f, 0xffff, 0xffef, 0xfffb, 0x1fe3, + 0xc000, 0xffff, 0x1fff, 0xfffc, 0x803c, 0xffff, 0xe3c7, 0xfff1, 0x0fc1, + 0x0000, 0xe000, 0x0007, 0x0000, 0x0000, 0x01fc, 0x0000, 0x0000, 0x0000, + 0x0000, 0xe000, 0x0007, 0x0000, 0x0000, 0x01fc, 0x0000, 0x0000, 0x0000, + 0x0000, 0xe000, 0x0007, 0x0000, 0x0000, 0x01fc, 0x0000, 0x0000, 0x0000, + 0x0000, 0xe000, 0x0007, 0x0000, 0x0000, 0x01f8, 0x0000, 0x0000, 0x0000, + 0x0000, 0xc000, 0x0003, 0x0000, 0x0000, 0x00f0, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000 }; + + +#define level_width 144 +#define level_height 129 +const static unsigned short level_bits[] = { + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf800, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff8, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xe000, 0xffff, 0x1e01, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfe00, 0x7fef, 0x7ff8, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xff00, 0x83c0, 0xffff, 0x0001, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x3f80, 0xcffe, 0xfffd, 0x0007, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x9fc0, 0xffff, 0xb07f, 0x001f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xcfe0, 0xffff, 0xcfce, 0x007e, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xe7f8, 0xffff, 0x9ff7, 0x00fd, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xf7fc, 0xffe7, 0xbff7, 0x01ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xf3fe, 0xfffb, 0xb9ff, 0x03ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfbff, 0xfe03, 0xb9f7, 0x07ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8000, 0xf9ff, 0xebfd, 0xb9e7, 0x0fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xc000, 0xffff, 0xd7fe, 0xcfdf, 0x0fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xe000, 0x7fff, 0xf7ff, 0xf037, 0x1fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xe000, 0x7fff, 0xf7ff, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf000, 0xefff, 0xf73e, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf000, 0xefff, 0xf73e, 0xefff, 0x7fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf000, 0xefff, 0xf939, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf800, 0x87ff, 0xfe07, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf800, 0xffff, 0xdffe, 0xffff, 0xffdf, 0x0001, 0x0000, 0x0000, + 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, + 0x0000, 0xfe00, 0xffff, 0xefff, 0x1fff, 0xfff8, 0x0003, 0x0000, 0x0000, + 0x0000, 0xfe00, 0xffff, 0xffff, 0x81ff, 0xfff1, 0x0007, 0x0000, 0x0000, + 0x0000, 0xfe00, 0xffff, 0xffff, 0xfc3f, 0xfff3, 0x000f, 0x0000, 0x0000, + 0x0000, 0xfe00, 0xffff, 0xffff, 0xff9f, 0xfff0, 0x000f, 0x0000, 0x0000, + 0x0000, 0xfe00, 0xffff, 0xffff, 0x3fcf, 0xfff6, 0x001f, 0x0000, 0x0000, + 0x0000, 0xff00, 0xffff, 0xffff, 0x0ee7, 0xfff7, 0x003f, 0x0000, 0x0000, + 0x0000, 0xff00, 0xffff, 0xffff, 0xe003, 0xfff7, 0x003f, 0x0000, 0x0000, + 0x0000, 0xff00, 0xffff, 0xffff, 0xf371, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff00, 0xffff, 0xffff, 0xfff9, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff00, 0xffff, 0xffff, 0xfffe, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0x7fff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0x7fff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xdfff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xdfff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xfdff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xbfff, 0xffff, 0xfdff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0x7fff, 0xfffb, 0xfdff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xfeff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xf3ff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xcfff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xbeff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xfeff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0x7fff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xbfff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xbeff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xdeff, 0x007f, 0x0000, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xdeff, 0x003f, 0x0000, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xefff, 0x003f, 0x0000, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xfb7f, 0x003f, 0x0000, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffbf, 0x003f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffbf, 0x003f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffdf, 0x013f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffef, 0x003f, 0x0000, 0x0000, + 0x0000, 0xff00, 0xffff, 0xffff, 0x3fff, 0xfff9, 0x003f, 0x0000, 0x0000, + 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, 0x0000, 0x0000, + 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, 0x0000, 0x0000, + 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, + 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, + 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, + 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, + 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x0001, 0x0000, 0x0000, + 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0x001f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000 }; + +#define level_mask_width 144 +#define level_mask_height 129 +const static unsigned short level_mask_bits[] = { + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7c00, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0200, 0xfe00, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0740, 0xdc00, 0x0001, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03fe, 0xce00, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x01ff, 0xde1f, 0x0001, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x802e, 0xfe1f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x4000, 0x0044, 0xc000, 0xc007, 0x7c1d, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfee8, 0x00ff, 0x8000, 0xc00f, 0x0e38, 0x0000, + 0x0000, 0x0000, 0x0000, 0xffff, 0x17ff, 0x0000, 0xc3df, 0x1c3f, 0x0000, + 0x0000, 0x0000, 0xa000, 0xffff, 0x3fff, 0x0000, 0xe3ff, 0x0e3f, 0x0000, + 0x0000, 0x0000, 0xff00, 0xffff, 0x7fff, 0x0000, 0xc07f, 0x1c7d, 0x0000, + 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x0000, 0xe03e, 0x0e30, 0x0000, + 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, 0x0017, 0xc03e, 0x1c71, 0x0000, + 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0x001f, 0x8038, 0x0020, 0x0000, + 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0x007f, 0x003c, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfff8, 0xffff, 0xffff, 0x00ff, 0x0020, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, + 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0001, 0x0000, 0x0000, + 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, + 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, + 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, + 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, 0x0150, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x03f0, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x1ff8, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x1ef8, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x147c, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0038, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x707c, 0x0054, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0xf0fc, 0x00fc, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0xf1fc, 0x01fc, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0xf80e, 0x00ee, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0xf00e, 0x00fc, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0xf808, 0x00fe, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x7800, 0x007e, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0xe000, 0x000e, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x4000, 0x0006, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x000e, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0004, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0020, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0054, 0x007c, + 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x00f8, 0x00f8, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x117c, 0x01fc, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x3818, 0x00fc, + 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x7c5c, 0x00fc, + 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0xfef8, 0x000c, + 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x7ff8, 0x001c, + 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, 0xfe38, 0x000c, + 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x7e30, 0x001c, + 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0xee30, 0x000c, + 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, 0x5e70, 0x001c, + 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, 0x0e20, 0x000c, + 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, 0x0c60, 0x000c, + 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0800, 0x0000, + 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x3c00, 0xfffe, 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, + 0xd000, 0x7e41, 0xfffc, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, + 0xf800, 0xeee3, 0xfff8, 0xffff, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, + 0xff00, 0x6cfd, 0xfff0, 0xffff, 0xffff, 0x001f, 0x0000, 0x0000, 0x0000, + 0x3f80, 0xecf8, 0xff80, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, + 0x3f00, 0x7fdc, 0xff00, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, + 0xbe00, 0x3ffb, 0xa000, 0xbfbb, 0x2bbf, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfe00, 0x1ffb, 0x0000, 0x1f00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfc00, 0x1fbb, 0x0000, 0x3e00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x7c00, 0x1d39, 0x0000, 0x7c00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x3800, 0x1838, 0x0000, 0xf800, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x7000, 0x0018, 0x0000, 0xfc00, 0x0001, 0x07c0, 0x0000, 0x0000, 0x0000, + 0x6000, 0x0000, 0x0000, 0xf800, 0x0003, 0x0e80, 0x0000, 0x0000, 0x0000, + 0x7000, 0x0000, 0x0100, 0xfc00, 0x0007, 0x1d00, 0x0000, 0x0000, 0x0000, + 0x6000, 0x0000, 0x0080, 0x7800, 0x000e, 0x3800, 0x0000, 0x0000, 0x0000, + 0x4000, 0x0000, 0x00c0, 0xfc00, 0x001c, 0x7000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x00e0, 0xc800, 0x0038, 0xe000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x1060, 0xdc00, 0x0071, 0x4000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x3860, 0x8800, 0x00e0, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x1c60, 0x9c00, 0x01c1, 0x1c00, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0860, 0x8800, 0x0383, 0x3800, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x9c40, 0x1c01, 0x1f03, 0x7100, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x8e00, 0x1801, 0x1a03, 0x6300, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xcc00, 0x1c00, 0x3c07, 0x4700, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xec00, 0x0800, 0x2002, 0xc600, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x7000, 0x1c00, 0x3007, 0xc600, 0x0001, 0x0000, 0x0000, + 0x0000, 0x0000, 0x6000, 0x0c00, 0x3002, 0x8c00, 0x0201, 0x0000, 0x0000, + 0x0000, 0x0000, 0x6000, 0x0c00, 0x3006, 0x9c00, 0x0701, 0x0000, 0x0000, + 0x0000, 0x0000, 0xe000, 0x0e00, 0x2002, 0x1800, 0x0600, 0x0000, 0x0000, + 0x0000, 0x0000, 0x4000, 0x0700, 0x3007, 0x3800, 0x0700, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0300, 0x3802, 0x3800, 0x0600, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0780, 0x1806, 0x1000, 0x0400, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0380, 0x0806, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x01c0, 0x1c06, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0180, 0x0806, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x05c0, 0x1c06, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0f80, 0x080e, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x1f00, 0x0406, 0x0000, 0x0000, 0x0000, 0x0000 }; + +#define llama_width 240 +#define llama_height 260 +const static unsigned short llama_bits[] = { + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8400, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0800, 0x0000, 0x0004, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0680, 0xf000, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0600, 0xe000, 0x000f, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0700, 0xe000, 0x021f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x1780, 0xc000, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x07c0, 0x8000, 0x21ff, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x07c0, 0x8000, 0x07ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0fe0, 0x0000, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x07e4, 0x0000, 0x3ffe, + 0x0002, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0ff0, 0x0000, 0x7ffc, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x07f0, 0x0000, 0xfff8, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x2ff0, 0x0000, 0xfff1, + 0x0023, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0ff8, 0x0000, 0xfff0, 0x0007, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0ff8, 0x0000, 0xffe0, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0ff8, 0x0000, 0xffc0, + 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0ff8, 0x0000, 0xff80, 0x003f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0ffc, 0x0000, 0xff00, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0ffc, 0x0000, 0xfe00, + 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x4ff8, 0x0000, 0xfc00, 0x01ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0dfc, 0x0000, 0xfc80, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1bf8, 0x0000, 0xf800, + 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x93f8, 0x0000, 0xf000, 0x03ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x17f8, 0x0000, 0xe000, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0ff0, 0x0001, 0xc010, + 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x1ff0, 0x0000, 0xc000, 0x0fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x3fe0, 0x0800, 0x8000, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7fc4, 0x2082, 0x0040, + 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff88, 0x0c00, 0x0000, 0x0fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xff00, 0x7103, 0x0000, 0x0ffe, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xe003, 0x0028, + 0x07fc, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x7800, 0x81f8, 0x0087, 0x07f8, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x3000, 0x9f00, 0x400f, 0x07f8, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0x7e00, 0x004e, + 0x23fa, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfbfe, 0x005f, 0x03f6, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x8400, 0xf7ff, 0x003f, 0x03f6, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0x80ff, + 0x11e6, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf080, 0xffff, 0x80ff, 0x01e6, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfc00, 0xffff, 0x01ff, 0x08ee, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x01ff, + 0x00ee, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0x03ff, 0x056e, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xff80, 0xffff, 0x07ff, 0x00ae, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xdfc0, 0xffff, 0x0fff, + 0x008e, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xe1e0, 0xffff, 0x4ffe, 0x00ce, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xf0e0, 0x07ff, 0x9ff0, 0x016e, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf874, 0x40ff, 0x3fe1, + 0x0066, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x3d30, 0x3f20, 0x7f8c, 0x0027, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0c08, 0x0f82, 0x6f90, 0x00b7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x2208, 0x01c0, 0x1e40, + 0x0017, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0002, 0x00a8, 0xbe80, 0x0017, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0404, 0x0020, 0x7900, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe018, 0xf20f, + 0x000b, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf01c, 0xf63b, 0x000e, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x4002, 0x3c1e, 0xcc84, 0x0125, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x2800, 0xdf1f, 0xd93f, + 0x0073, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xc000, 0xe7df, 0xb67f, 0x00f7, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xc000, 0xf3ff, 0x3cff, 0x04f7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe500, 0xfbff, 0x7dff, + 0x01f7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf200, 0xfdff, 0xfbff, 0x13fe, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xf940, 0xfeff, 0xf7ff, 0x03fe, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc80, 0xff7f, 0xffff, + 0x27fd, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfe10, 0xff7f, 0xefff, 0x0ffb, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfe00, 0x3fbf, 0xeff8, 0x0ffb, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0x01ff, 0xfe00, + 0x9fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff80, 0x007f, 0xd808, 0x1ff7, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xffc0, 0x0c07, 0xe7dc, 0x3ff7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe4, 0x0f0f, 0xdfc0, + 0x7fef, 0x0002, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff0, 0x1f7f, 0xfff0, 0x7fef, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfff0, 0x7fff, 0xfffc, 0xffef, 0x0004, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff9, 0xffff, 0xffff, + 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffc, 0xfeff, 0xffff, 0xffff, 0x0001, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfffc, 0xfdff, 0xffff, 0xffdf, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, + 0xffdf, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x2000, 0xffff, 0xfbff, 0xdfff, 0xffdf, 0x0003, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xffff, 0xfbff, 0xdfff, 0xfddf, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, 0xffff, 0xe7ff, 0xefff, + 0xffdf, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x8000, 0xffff, 0xdfff, 0xf7ff, 0xff9f, 0x004f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, + 0xffff, 0xbfff, 0xf1ff, 0xff9f, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0x6fff, 0xfc7c, + 0xff9f, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xfe01, 0xfb9f, 0x001f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe200, + 0xffff, 0x9fff, 0xffff, 0xfb9f, 0x011f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0x7fff, 0xffff, + 0xfb9f, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xf100, 0xffff, 0xffff, 0xfff8, 0xfbdf, 0x003f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, + 0xfbff, 0xffff, 0xfe03, 0xf7df, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xfe7f, 0xfff9, 0xffff, + 0xf7cf, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xf800, 0xffbf, 0xfffb, 0xffff, 0xf7c7, 0x007f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, + 0xffcf, 0xffff, 0xffff, 0xf7e3, 0x04ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xfff7, 0xfff7, 0x3fff, + 0xf7e0, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xe200, 0xfffb, 0xfff7, 0x07ff, 0xf7f8, 0x01ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, + 0xfffc, 0xfff7, 0xc07f, 0xf7ff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xfffe, 0xfff7, 0xf81f, + 0xf7ff, 0x09ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x2400, 0xffff, 0xfffb, 0xff07, 0xe7ff, 0x01ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7000, + 0xffff, 0xfff9, 0xfff0, 0xf7ff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xb800, 0xffff, 0x7ff8, 0xfffc, + 0xe7ff, 0x13ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x9c00, 0x3fff, 0x9ffe, 0xffff, 0xf7ff, 0x07ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xdc00, + 0x1fff, 0xe7ff, 0xffff, 0xe7ff, 0x05ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xef00, 0xc1ff, 0xf9ff, 0xffff, + 0xf7ff, 0x05ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xef80, 0xf01f, 0xfcff, 0xffff, 0xf1ff, 0x03ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x37c0, + 0xfc00, 0xff5f, 0xffff, 0xf1ff, 0x0bff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffaf, 0xffff, + 0xf1ff, 0x0bfb, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xff80, 0xffff, 0xffd7, 0xffff, 0xf3ff, 0x1ffb, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8800, 0xffff, + 0xffff, 0x0077, 0xfff8, 0xf2ff, 0x17fb, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xf03b, 0xffef, + 0xf2ff, 0x97fb, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8800, 0xffff, 0xffff, 0xfc01, 0xffff, 0xf2ff, 0x27fb, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, + 0xffff, 0xe001, 0xffff, 0xf97f, 0x2ff3, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0xfffe, 0xffff, 0xc380, 0xffff, + 0xf97f, 0x0ff7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfff8, 0xffff, 0x3fa0, 0xffff, 0xfc7f, 0x4ff7, 0x0001, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, + 0x7fff, 0x7f80, 0xfffe, 0xfc3f, 0x0ff7, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc4, 0x3fff, 0xffc1, 0xfffd, + 0xfcbf, 0x1ff7, 0x0002, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xff80, 0x3fff, 0xffc0, 0xffff, 0xfe9f, 0x1ff7, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff10, + 0xbfff, 0xffe0, 0xffff, 0xfe9f, 0x1ff7, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0x1fff, 0xfff0, 0xffff, + 0xffdf, 0x3ffb, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xf800, 0x4fff, 0xfff8, 0xffff, 0xffcf, 0x3fef, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe100, + 0x07ff, 0xfff8, 0xffff, 0xffcf, 0x3fe9, 0x0001, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0x87ff, 0xffdc, 0xffff, + 0xffe7, 0x3fef, 0x0008, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x03ff, 0xfffe, 0xffff, 0xffe7, 0x3fe9, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x00f8, 0xfff7, 0xffff, 0xffe7, 0x7fe9, 0x0002, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x2000, 0xfff7, 0xffff, + 0xffe7, 0x7fe9, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x8000, 0xfff9, 0xffff, 0xfff3, 0xffe9, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xc002, 0xfff8, 0xffff, 0xfff3, 0xffe9, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x4008, 0xfffc, 0xffff, + 0xfff1, 0xffc9, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, 0xfff9, 0xffc9, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xffff, 0xffff, 0xfff8, 0xffc9, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, 0xfffe, 0xffff, + 0xfff8, 0x3fd9, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x4000, 0xfffe, 0xffff, 0xfffc, 0x07d9, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xa000, 0xffff, 0x7fff, 0xfffc, 0xf0d9, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xd000, 0xffff, 0x7fff, + 0xfffc, 0xf859, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xc200, 0xffff, 0x7fff, 0xfffe, 0x7e19, 0x0008, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xf000, 0xffff, 0x3fff, 0xfffe, 0x1f81, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x3fff, + 0xfffe, 0x07d1, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x3fff, 0xffff, 0x01f9, 0x0000, + 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x7e80, 0xfffe, 0x3fff, 0xffff, 0x0078, 0x8000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3c00, 0xffff, 0x3fff, + 0x7fff, 0x0008, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xbe00, 0xffff, 0x9fff, 0x1fff, 0x0000, 0x8000, + 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x9e00, 0xffff, 0x9fff, 0x07ff, 0x0200, 0x2000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xce00, 0xffff, 0x9fff, + 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xce00, 0xffff, 0xcfff, 0x001f, 0x0002, 0x4000, + 0x8010, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xc600, 0xffff, 0x0fff, 0x0000, 0x0000, 0x4000, 0x1fc0, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xa200, 0xffff, 0x0fff, + 0x0000, 0x0000, 0x4000, 0x79f0, 0x0002, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xa000, 0xffff, 0x0fff, 0x0080, 0x0000, 0x6800, + 0x8ff0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xe000, 0xffff, 0x0fff, 0x0000, 0x0000, 0x6000, 0xfff2, 0x0004, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xd400, 0xffff, 0x0fff, + 0x0000, 0x0000, 0x6000, 0xfff9, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xd000, 0xfffb, 0x0fff, 0x0000, 0x0000, 0x6000, + 0xfbf8, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xc200, 0xfffd, 0x07ff, 0x0000, 0x0000, 0x6000, 0x81fc, 0x001f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xfffd, 0x07ff, + 0x0000, 0x0000, 0x6000, 0x007c, 0x001c, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xc000, 0xfffd, 0x17ff, 0x0000, 0x0000, 0x6000, + 0x023c, 0x0060, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x8000, 0xfffd, 0x17ff, 0x0000, 0x0000, 0xe000, 0x003e, 0x0084, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xfffe, 0x07ff, + 0x0000, 0x0000, 0xc000, 0x001e, 0x0040, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xe000, 0xfffe, 0x17ff, 0x0000, 0x0000, 0xc000, + 0x200e, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xe000, 0xfffe, 0x0fff, 0x0000, 0x0000, 0xc000, 0x000f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xfffe, 0x0fff, + 0x0000, 0x0000, 0xc000, 0x07e7, 0x0801, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xe000, 0xfffe, 0x0fff, 0x0000, 0x0000, 0xc000, + 0x1ff7, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x6000, 0xfffa, 0x0fff, 0x0000, 0x0000, 0xc000, 0x7e3b, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0xfffa, 0x5fff, + 0x0000, 0x0000, 0x8000, 0xf00f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfffa, 0x0fff, 0x0000, 0x0000, 0x8000, + 0xc007, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xfffa, 0x1fff, 0x0000, 0x0000, 0x9000, 0x1003, 0x0013, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1000, 0xfffa, 0x1fff, + 0x0000, 0x0000, 0x8000, 0x000b, 0x0002, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfff8, 0x1fff, 0x0000, 0x0000, 0x8000, + 0x0001, 0x0004, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x8000, 0xfff0, 0x9fff, 0x0000, 0x0000, 0xa000, 0x0001, 0x002a, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0x1fff, + 0x0000, 0x0000, 0x0000, 0x0005, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0x1fff, 0x0000, 0x0000, 0x0000, + 0x0005, 0x0010, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xffe0, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0001, 0x0040, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0x1fff, + 0x0000, 0x0000, 0x4000, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xffc4, 0x3fff, 0x0000, 0x0000, 0x0000, + 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xffc0, 0x3fff, 0x0001, 0x0000, 0x0000, 0x0003, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe88, 0x3fff, + 0x0000, 0x0000, 0x0000, 0x0100, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfd80, 0x3fff, 0x0000, 0x0000, 0x0000, + 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xfb00, 0x3fff, 0x0000, 0x0000, 0x8000, 0x41ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfa00, 0x3fff, + 0x0000, 0x0000, 0xc800, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0x7fff, 0x0000, 0x0000, 0xe000, + 0x1fff, 0x0004, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xe000, 0x7fff, 0x0004, 0x0000, 0xf000, 0x7fff, 0x0010, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe080, 0xffff, + 0x0000, 0x0000, 0xf000, 0xffff, 0x0040, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xc900, 0xffff, 0x2000, 0x0000, 0xf000, + 0xffff, 0x0083, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8800, 0xffff, 0x0001, 0x0000, 0xf800, 0xffff, 0x0007, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, 0xffff, + 0x0001, 0x0002, 0xfc80, 0xffff, 0x041f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x2000, 0xffff, 0x0003, 0x0004, 0xfc00, + 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x7200, 0xffff, 0x1f87, 0x0000, 0xf440, 0xffff, 0x107f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7000, 0xfffe, + 0x3fc7, 0x0020, 0xf800, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x7800, 0xfffc, 0xffe3, 0x0001, 0xfc00, + 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x7c00, 0xfffc, 0xffe3, 0x0003, 0xfe00, 0xffff, 0x03ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7c00, 0xfffc, + 0xffe3, 0x000f, 0xff08, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x7e00, 0xfffa, 0xfff1, 0x083f, 0xffc0, + 0xffff, 0x07ff, 0x0010, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x7f00, 0xfffa, 0xfff9, 0x007f, 0xfff0, 0xffff, 0x07ff, 0x0040, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7f84, 0xfff2, + 0xfff8, 0x01ff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x7fc0, 0xfff6, 0xfffc, 0xc7ff, 0xffff, + 0xffff, 0x0fff, 0x0060, 0x0000, 0x2000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x7fe0, 0xfffe, 0xfffc, 0x1fff, 0xffff, 0xffff, 0x0fff, 0x00e0, + 0x0000, 0x0100, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7ff0, 0x7fee, + 0xfffe, 0xffff, 0xfffc, 0xffff, 0x0fff, 0x07c0, 0x0000, 0x0000, 0x0020, + 0x0000, 0x0000, 0x0000, 0x0000, 0x7ff8, 0x3fee, 0xfffe, 0xffff, 0xfff3, + 0xffff, 0x9fff, 0x07c0, 0x0000, 0xf020, 0x0007, 0x0000, 0x0000, 0x0000, + 0x0000, 0x7ffc, 0x3fde, 0xffff, 0xffff, 0xffff, 0xffff, 0x1fff, 0x3fc1, + 0x0002, 0xff00, 0x0021, 0x0000, 0x0000, 0x0000, 0x0000, 0x7ffe, 0x3fff, + 0xffff, 0xffff, 0xffff, 0xffff, 0x3fff, 0x7ec0, 0x0000, 0x3f88, 0x0084, + 0x0000, 0x0000, 0x0000, 0x8000, 0x3fff, 0x9fff, 0xffff, 0xffff, 0xffff, + 0xffff, 0x7fff, 0x8006, 0x0001, 0x6080, 0x003e, 0x0000, 0x0000, 0x0000, + 0xc080, 0xbfff, 0x9fff, 0xffff, 0xffff, 0xffff, 0xbfff, 0x7fff, 0x00fe, + 0x0003, 0xbff0, 0x003f, 0x0000, 0x0000, 0x0000, 0xf000, 0x9fff, 0xdffd, + 0xffff, 0xffff, 0xffff, 0xe7ff, 0xffff, 0x1ffc, 0x0004, 0xdff8, 0x001f, + 0x0000, 0x0000, 0x0000, 0xfc00, 0x9fff, 0xcffd, 0xffff, 0xffff, 0xffff, + 0xf9ff, 0xffff, 0xfff9, 0x1019, 0xe7f8, 0x004f, 0x0000, 0x0000, 0x0000, + 0xfe04, 0xdfff, 0xeffe, 0xffff, 0xffff, 0xffff, 0xfcff, 0xffff, 0x0fd3, + 0x0070, 0xf7fc, 0x002f, 0x0000, 0x0000, 0x0000, 0xff80, 0x4fff, 0xf7fe, + 0xffff, 0xffff, 0xffff, 0xfe3f, 0xffff, 0xffe7, 0xf0fc, 0xfbfd, 0x0033, + 0x0000, 0x0000, 0x4000, 0xffe0, 0x6fff, 0xf7fe, 0xffff, 0xffff, 0xffff, + 0xfd9f, 0xffff, 0xff9f, 0xfffb, 0xfbfd, 0x003b, 0x0000, 0x0000, 0x0000, + 0xfff8, 0x27ff, 0xf3ff, 0xffff, 0xffff, 0xffff, 0xf9cf, 0xffff, 0xffbf, + 0xffe3, 0xfbfe, 0x001c, 0x0000, 0x0000, 0x0140, 0xffff, 0x13ff, 0xf9ff, + 0xffff, 0xffff, 0xffff, 0xe7e3, 0xffff, 0xffff, 0xffcf, 0x7bfe, 0x009f, + 0x0000, 0x0000, 0xe000, 0xffff, 0x8bff, 0xfdff, 0xffff, 0xffff, 0xffff, + 0xc7f1, 0xffff, 0xffff, 0x7f1f, 0x97fe, 0x000f, 0x0000, 0x8000, 0xff78, + 0xffff, 0x91ff, 0xfeff, 0xffff, 0xffff, 0xffff, 0xcff8, 0xffff, 0xffff, + 0xf87f, 0x30c3, 0x000f, 0x0000, 0x0000, 0xc1fc, 0xffff, 0xd9ff, 0xfe03, + 0xffff, 0xffff, 0x7fff, 0x9ff8, 0xffff, 0xffff, 0xe07f, 0xffbf, 0x0006, + 0x0000, 0x0000, 0x007e, 0xffff, 0xccff, 0xfc00, 0xffff, 0xffff, 0x7fff, + 0x9ffc, 0xffff, 0xffff, 0xc1ff, 0xffff, 0x0001, 0x0000, 0x9000, 0x3e1f, + 0xfffc, 0x07ff, 0xf0f8, 0xffff, 0xfff7, 0x3fff, 0x3ffe, 0xffff, 0xffff, + 0x01ff, 0xfffc, 0x0000, 0x0000, 0x8000, 0xff8f, 0xfff8, 0x07ff, 0xe1ff, + 0xffff, 0xffff, 0x1fff, 0x3ffe, 0xffff, 0xffff, 0x03ff, 0x7ff0, 0x0000, + 0x0000, 0xc000, 0xffe3, 0xffe3, 0xe07f, 0xc7ff, 0xffff, 0xfffb, 0x0fff, + 0x3dfb, 0xffff, 0xffff, 0x8fdf, 0x0000, 0x0000, 0x0000, 0xe000, 0xfff3, + 0xffc7, 0xf80f, 0x8fff, 0xffff, 0xfffb, 0x8fff, 0x33cf, 0xfffe, 0xffff, + 0x8fbf, 0x0000, 0x0004, 0x0000, 0xf000, 0xeff9, 0x0b1f, 0xffc0, 0x3fff, + 0xffff, 0xfffb, 0x07ff, 0x081c, 0xfffe, 0xffff, 0x18ff, 0x0001, 0x0001, + 0x0000, 0xf900, 0x9ffe, 0x007f, 0xfffe, 0x7fff, 0xfffe, 0xfffb, 0x07ff, + 0x0030, 0xfffe, 0xffff, 0x03ff, 0x2080, 0x0000, 0x0000, 0x7c80, 0x3ffe, + 0xfcff, 0xffff, 0x7fff, 0xfffe, 0xfffb, 0x03ff, 0x0001, 0xfffe, 0xffff, + 0x0f81, 0x0001, 0x0000, 0x0000, 0x7c00, 0x3801, 0xf3fc, 0xffff, 0xffff, + 0xfffc, 0xfffb, 0x03ff, 0x4020, 0xfffe, 0xffff, 0xe03f, 0x0002, 0x0000, + 0x0000, 0x3e00, 0x03f8, 0xcff9, 0xf77f, 0xffff, 0xfff9, 0xfffb, 0x11ff, + 0x0000, 0xffdf, 0xfffc, 0x00ff, 0x0002, 0x0000, 0x0000, 0x8f00, 0xbfff, + 0x3fe3, 0xfb7c, 0x3fff, 0xfffa, 0xfffb, 0x01ff, 0x4000, 0xf07e, 0x0003, + 0x1000, 0x0001, 0x0000, 0x0000, 0xc380, 0xffff, 0xffcf, 0xff82, 0xbfe5, + 0xfff1, 0xfff3, 0x00ff, 0x4000, 0x00fc, 0x0000, 0x0400, 0x0000, 0x0000, + 0x0000, 0xf3c0, 0xffff, 0xff8f, 0xfd9f, 0xbfde, 0xfff7, 0xfffb, 0x08ff, + 0x8000, 0x43e0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfce0, 0xffff, + 0xff00, 0xbcbf, 0xdfbf, 0xffc7, 0xfff3, 0x00ff, 0x0000, 0x0000, 0xa0d0, + 0x0006, 0x0000, 0x0000, 0x0000, 0xfe70, 0x1fff, 0xfe7c, 0xbc3f, 0xdfff, + 0x7fcf, 0xfff3, 0x047f, 0x0000, 0x0004, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xff3c, 0xc0ff, 0xf8fe, 0xddff, 0xde7f, 0x7f1f, 0xfff3, 0x003f, + 0x0000, 0x0480, 0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0xff9e, 0xf81f, + 0xf1fe, 0xec07, 0xdeff, 0x7f3f, 0xfff3, 0x003f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x7fcd, 0x0ec0, 0x47fe, 0xe5e0, 0xdeff, + 0xfe3f, 0xfff2, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xc000, 0x07ee, 0x77f8, 0x0ffe, 0xf5fc, 0xddff, 0xfe7f, 0xfff6, 0x003f, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x6000, 0x0007, 0x79ff, + 0x0ffe, 0xf0ff, 0xddff, 0xfcff, 0xfff4, 0x001f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xbe17, 0x7f7f, 0xe7ff, 0xf8ff, 0xd9ff, + 0xfcff, 0xfff4, 0x011f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xc000, 0xdf3b, 0x7f7f, 0x11ff, 0xf8fe, 0xdbff, 0xf8ff, 0xffe4, 0x001f, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe200, 0xefbf, 0x3fbf, + 0xb1ff, 0xfcff, 0xd3ff, 0xf9ff, 0xffed, 0x001f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf800, 0xf79f, 0xbfdf, 0xcfff, 0xfcff, 0xd7ff, + 0xf1ff, 0xffe9, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfc40, 0xf79f, 0xdfdf, 0xe3ff, 0xfcff, 0xd7ff, 0xf3ff, 0xffe9, 0x000f, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff90, 0xfb9f, 0xcfe7, + 0xf800, 0xfeff, 0xd7ff, 0xf3ff, 0xffc3, 0x000f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfc00, 0xfd85, 0x07f3, 0xfc00, 0xfc7f, 0xafff, + 0xe3ff, 0xffd3, 0x0083, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0010, 0xfd80, 0x03f9, 0xde00, 0xfc7f, 0xafff, 0xe7ff, 0x7fc3, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0080, 0x7e80, 0x00fc, + 0xe700, 0xfc7f, 0xafff, 0xe7ff, 0x07c3, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x2000, 0x1e80, 0x203e, 0xf1c0, 0xfc7f, 0x8fff, + 0xe7ff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0300, 0x001e, 0xfc60, 0xf87f, 0x8fff, 0xe7ff, 0x0003, 0x0010, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0100, + 0xfe08, 0xf8ff, 0x4fff, 0xcfff, 0xc003, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe4, 0xe0ff, 0x4fff, + 0xcfff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff2, 0xc1ff, 0x4fff, 0xcfff, 0x0187, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0040, 0x0000, + 0xfffc, 0x83ff, 0x0fff, 0xcfff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0xfffc, 0x0fff, 0x1ffe, + 0xcffe, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffe, 0x1fff, 0x0ffc, 0xc7f8, 0x0007, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, + 0xf80f, 0x7fff, 0xcfe0, 0xe381, 0x004f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x4000, 0xffc0, 0xffff, 0xcf80, + 0xe007, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff00, 0xf7ff, 0xe007, 0xc00f, 0x0007, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0200, + 0xc000, 0xfc2f, 0xe01f, 0x303f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xf83d, + 0x003f, 0x0100, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0020, 0x8000, 0xff81, 0x0201, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x1fe0, 0x2040, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0001, + 0x0008, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x2000, 0x0000, 0x0002, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x4000, 0x2000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0202, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000 }; + +#define llama_mask_width 240 +#define llama_mask_height 260 +const static unsigned short llama_mask_bits[] = { + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0e00, 0xfc00, 0x0007, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0f80, 0xfc00, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0f80, 0xfc00, 0x00ff, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0fc0, 0xfc00, 0x03ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x1fe0, 0xf800, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1ff0, 0xf000, 0x3fff, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x1ff0, 0xe000, 0x7fff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x1ff8, 0xe000, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1ffc, 0xc000, 0xffff, + 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x1ffc, 0x8000, 0xffff, 0x0007, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x1ffc, 0x8000, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3ffe, 0x0000, 0xffff, + 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x3ffe, 0x0000, 0xfffe, 0x007f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x3fff, 0x0000, 0xfffc, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3fff, 0x0000, 0xfff8, + 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x3fff, 0x0000, 0xfff0, 0x03ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x3fff, 0x0000, 0xffe0, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3fff, 0x0000, 0xffc0, + 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x7fff, 0x0000, 0xff80, 0x1fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x7fff, 0x0000, 0xff80, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x7fff, 0x0000, 0xff00, + 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xffff, 0x0000, 0xfe00, 0x7fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xffff, 0x0000, 0xfc20, 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0x0001, 0xf830, + 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffe, 0x00c1, 0xf030, 0x7fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfffc, 0x6f81, 0xe030, 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xff83, 0xe071, + 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff8, 0xff07, 0xc073, 0x7fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xffe0, 0xfdff, 0xc077, 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0xc07f, + 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xc0ff, 0x3fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfe00, 0xffff, 0xc0ff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x80ff, + 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0x81ff, 0x1fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfc00, 0xffff, 0x81ff, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0x83ff, + 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0x83ff, 0x0fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xff80, 0xffff, 0x07ff, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0x0fff, + 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0x0fff, 0x07ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfff0, 0xffff, 0x1fff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0xffff, 0x3fff, + 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, 0x7fff, 0x01ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfff8, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, + 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xff7c, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x3fbc, 0xfff0, 0xffff, + 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0f9e, 0xfff9, 0xffff, 0x003f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x878e, 0xfffb, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc186, 0xffff, 0xffff, + 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xe082, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xf002, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, + 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfe00, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, + 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xffc0, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, + 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfffc, 0xffff, 0xffff, 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, + 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, 0xffff, 0xffff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfff8, 0xffff, 0xffff, 0xffff, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, + 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfffe, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, + 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8000, + 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, + 0xffff, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, + 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, + 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, + 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, + 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, + 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, + 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, + 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, + 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x03ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, + 0xffff, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, + 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, + 0xffff, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, + 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0fff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, + 0xffff, 0xffff, 0xffff, 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, + 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0x1fff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, + 0xffff, 0xffff, 0xffff, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, + 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff8, + 0xffff, 0xffff, 0xffff, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0xffff, + 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffcf, 0xffff, + 0xffff, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xffff, 0xffff, 0xffe3, 0xffff, 0xffff, 0xffff, 0x0001, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, + 0xffff, 0xffe1, 0xffff, 0xffff, 0xffff, 0x0001, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0xfff1, 0xffff, + 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfff8, 0xffff, 0xfff8, 0xffff, 0xffff, 0xffff, 0x0003, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, + 0xffff, 0xfff8, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0x7fff, 0xfffc, 0xffff, + 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xff80, 0x7fff, 0xfffe, 0xffff, 0xffff, 0xffff, 0x0007, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, + 0x3fff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xbfff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x000d, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xf800, 0x9fff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0009, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, + 0xcfff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0013, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xefff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xe7ff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0003, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xf3fe, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf1f8, 0xffff, 0xffff, + 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, + 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, + 0xffff, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, + 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0x0000, + 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xff80, 0xffff, 0xffff, 0xffff, 0x7fff, 0x8000, 0x0001, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, + 0xffff, 0x3fff, 0x8000, 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0x07ff, 0xc000, + 0x0001, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xff80, 0xffff, 0xffff, 0xffff, 0x03ff, 0xe000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, + 0xffff, 0x003f, 0xe000, 0x3fc0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0x0003, 0xf000, + 0xfff0, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xff80, 0xffff, 0xffff, 0x1fff, 0x0000, 0xf000, 0xfff8, 0x0001, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, + 0x07ff, 0x0000, 0xf000, 0xfff8, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0x00ff, 0x0000, 0xf800, + 0xfffc, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xff80, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, 0xfffe, 0x0007, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0x3fff, + 0x0000, 0x0000, 0xf800, 0xffff, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, + 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xff80, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, 0xffff, 0x007f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfd80, 0xffff, 0x3fff, + 0x0000, 0x0000, 0xf800, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfd00, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, + 0x03ff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfc00, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, 0x01ff, 0x03fc, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x3fff, + 0x0000, 0x0000, 0xf800, 0x007f, 0x07c0, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, + 0x3fff, 0x0f00, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfc00, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf800, 0xffff, 0x0c00, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x3fff, + 0x0000, 0x0000, 0xf000, 0xffff, 0x0801, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf000, + 0xffff, 0x0003, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xf800, 0xffff, 0x3fff, 0x0000, 0x0000, 0xf000, 0xffff, 0x0003, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x7fff, + 0x0000, 0x0000, 0xf000, 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0x7fff, 0x0000, 0x0000, 0xf000, + 0xfc3f, 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xf800, 0xffff, 0x7fff, 0x0000, 0x0000, 0xf000, 0xf00f, 0x001f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, 0xffff, 0x7fff, + 0x0000, 0x0000, 0xe000, 0xc00f, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x8000, 0xffff, 0x7fff, 0x0000, 0x0000, 0xe000, + 0x0007, 0x001f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x8000, 0xffff, 0xffff, 0x0000, 0x0000, 0xe000, 0x0007, 0x003e, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, + 0x0000, 0x0000, 0xc000, 0x0007, 0x0038, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0x0000, 0x0000, 0xc000, + 0x0007, 0x0030, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xfffe, 0xffff, 0x0000, 0x0000, 0xc000, 0x0007, 0x0060, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, + 0x0000, 0x0000, 0xc000, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, 0x0000, 0x0000, 0x8000, + 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xfff8, 0xffff, 0x0001, 0x0000, 0x8000, 0x000f, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, + 0x0001, 0x0000, 0x8000, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0xffff, 0x0001, 0x0000, 0xe000, + 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xffe0, 0xffff, 0x0001, 0x0000, 0xf000, 0x7fff, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, + 0x0003, 0x0000, 0xf800, 0xffff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0x0003, 0x0000, 0xfc00, + 0xffff, 0x0007, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xffc0, 0xffff, 0x0007, 0x0000, 0xfc00, 0xffff, 0x001f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, + 0x0fc7, 0x0000, 0xfe00, 0xffff, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0x3fe7, 0x0000, 0xff00, + 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xfc00, 0xffff, 0x7fe7, 0x0000, 0xff00, 0xffff, 0x01ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, + 0xffff, 0x0003, 0xff80, 0xffff, 0x07ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0x0007, 0xff80, + 0xffff, 0x0fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xfe00, 0xffff, 0xffff, 0x000f, 0xffc0, 0xffff, 0x1fff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, + 0xffff, 0x003f, 0xffc0, 0xffff, 0x1fff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0x007f, 0xffc0, + 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xff80, 0xffff, 0xffff, 0x00ff, 0xffc0, 0xffff, 0x3fff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, + 0xffff, 0x01ff, 0xfff8, 0xffff, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0x7fff, 0x001c, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x007c, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x01fc, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0x7fff, 0x07fc, 0x0000, 0x2000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xfffe, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x0ff8, + 0x0000, 0xff00, 0x0007, 0x0000, 0x0000, 0x0000, 0x8000, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0x7fff, 0x3ff8, 0x0000, 0xffc0, 0x003f, + 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xfff8, 0x0000, 0xffe0, 0x003f, 0x0000, 0x0000, 0x0000, + 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xfff1, + 0x0003, 0xfff0, 0x003f, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0007, 0xfff8, 0x00ff, + 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0x001f, 0xfff8, 0x00ff, 0x0000, 0x0000, 0x0000, + 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0x003f, 0xfffc, 0x00ff, 0x0000, 0x0000, 0x0000, 0xffc0, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0xfffc, 0x00ff, + 0x0000, 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xf1ff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, + 0xfffc, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, + 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0xe000, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0xff7c, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, + 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x8000, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x007f, 0x0000, 0x8000, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, + 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0xf000, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x001f, 0x0000, 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, + 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x000f, 0x0000, 0xfc00, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xfffe, 0x0007, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xfff1, 0x0001, + 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0x3f81, 0x0000, 0x0000, 0xff80, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x3fff, 0xf9ff, 0xffff, 0xffff, + 0xffff, 0x0001, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x1fff, 0xc1e0, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, + 0x0000, 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x1fff, + 0x8000, 0xffff, 0xffff, 0xffff, 0x0003, 0x0000, 0x0000, 0xffe0, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0fff, 0xc000, 0xffff, 0xffff, + 0xffff, 0x0001, 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x0fff, 0xc000, 0xffff, 0xffff, 0x07ff, 0x0000, 0x0000, + 0x0000, 0xfff8, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x0fff, + 0x8000, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0xfffc, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x07ff, 0x0000, 0xfffe, 0xe0f0, + 0x0007, 0x0000, 0x0000, 0x0000, 0xfffe, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x07ff, 0x0000, 0x7ffc, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x03ff, + 0x0000, 0x0f80, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x03ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xf000, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfe00, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xffc0, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xfff0, 0xffff, 0xffff, + 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xfff8, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, + 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff80, 0xffff, 0xffff, + 0xffe7, 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xe000, 0xffff, 0x3fff, 0xfff0, 0xffff, 0xffff, + 0xffff, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xffe0, 0x03ff, 0xfff0, 0xffff, 0xffff, 0xffff, 0xffff, 0x001f, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xffe0, 0x01ff, + 0xfff8, 0xffff, 0xffff, 0xffff, 0xffef, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x8fe0, 0x007f, 0xfffc, 0xffff, 0xffff, + 0xffff, 0x00df, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x87e0, 0x003f, 0xfffe, 0xffff, 0xffff, 0xffff, 0x019f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x8040, 0x0007, + 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xc000, 0xffff, 0xffff, 0xffff, + 0xffff, 0x003f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xe000, 0xffff, 0xffff, 0xffff, 0xffff, 0x003f, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf000, + 0xffff, 0xffff, 0xffff, 0xffff, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xf800, 0xffff, 0xffff, 0xffff, + 0xffff, 0x007f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0xfc00, 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x1e00, + 0xffff, 0xffff, 0xffff, 0xffff, 0x00ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0200, 0xfffc, 0xffff, 0xffff, + 0xffff, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0xffe0, 0xffff, 0xffff, 0xffff, 0x01ff, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xffff, 0xffff, 0xe07f, 0x01ff, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0xff00, 0xffff, + 0x000f, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0xbf00, 0xffff, 0x0003, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0xc000, 0x3fff, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x03fe, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, + 0x0000, 0x0000, 0x0000 }; + + +#endif /* SPLASH_H_ */ diff --git a/flight/targets/OSD/System/osd.c b/flight/targets/OSD/System/osd.c index f0d48a769..90b7ab7b0 100644 --- a/flight/targets/OSD/System/osd.c +++ b/flight/targets/OSD/System/osd.c @@ -1,240 +1,240 @@ - -/** - ****************************************************************************** - * - * @file main.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main modem functions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -// ***************************************************************************** - -//#define USE_WATCHDOG // comment this out if you don't want to use the watchdog - -// ***************************************************************************** -// OpenPilot Includes - -#include - -#include "openpilot.h" -#include "systemmod.h" - -/* Task Priorities */ -#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) - -/* Global Variables */ - -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void Stack_Change(void); -static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change"))); - - -/* Function Prototypes */ -static void initTask(void *parameters); -/* Local Variables */ -#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority -#define INIT_TASK_STACK (1024 / 4) // XXX this seems excessive -static xTaskHandle initTaskHandle; - -// ***************************************************************************** -// Global Variables - -// ***************************************************************************** -// Local Variables - -#if defined(USE_WATCHDOG) - volatile uint16_t watchdog_timer; - uint16_t watchdog_delay; -#endif - -// ***************************************************************************** - -#if defined(USE_WATCHDOG) - - void processWatchdog(void) - { - // random32 = UpdateCRC32(random32, IWDG->SR); - - if (watchdog_timer < watchdog_delay) - return; - - // the watchdog needs resetting - - watchdog_timer = 0; - - watchdog_Clear(); - } - - void enableWatchdog(void) - { // enable a watchdog - watchdog_timer = 0; - watchdog_delay = watchdog_Init(1000); // 1 second watchdog timeout - } - -#endif - -// ***************************************************************************** - -void sequenceLEDs(void) -{ - for (int i = 0; i < 2; i++) - { - //USB_LED_ON; - PIOS_DELAY_WaitmS(100); - //USB_LED_OFF; - PIOS_DELAY_WaitmS(100); - - #if defined(USE_WATCHDOG) - processWatchdog(); // process the watchdog - #endif - } -} - -// ***************************************************************************** -// find out what caused our reset and act on it - -void processReset(void) -{ - if (RCC_GetFlagStatus(RCC_FLAG_IWDGRST) != RESET) - { // Independant Watchdog Reset - - #if defined(PIOS_COM_DEBUG_CONSOLE) - DEBUG_PRINTF(0, "\r\nINDEPENDANT WATCHDOG CAUSED A RESET\r\n"); - #endif - - // all led's ON - //USB_LED_ON; - - - PIOS_DELAY_WaitmS(500); // delay a bit - - // all led's OFF - //USB_LED_OFF; - - - } -/* - if (RCC_GetFlagStatus(RCC_FLAG_WWDGRST) != RESET) - { // Window Watchdog Reset - - DEBUG_PRINTF(0, "\r\nWINDOW WATCHDOG CAUSED A REBOOT\r\n"); - - // all led's ON - USB_LED_ON; - LINK_LED_ON; - RX_LED_ON; - TX_LED_ON; - - PIOS_DELAY_WaitmS(500); // delay a bit - - // all led's OFF - USB_LED_OFF; - LINK_LED_OFF; - RX_LED_OFF; - TX_LED_OFF; - } -*/ - if (RCC_GetFlagStatus(RCC_FLAG_PORRST) != RESET) - { // Power-On Reset - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF(0, "\r\nPOWER-ON-RESET\r\n"); - #endif - } - - if (RCC_GetFlagStatus(RCC_FLAG_SFTRST) != RESET) - { // Software Reset - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF(0, "\r\nSOFTWARE RESET\r\n"); - #endif - } - - if (RCC_GetFlagStatus(RCC_FLAG_LPWRRST) != RESET) - { // Low-Power Reset - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF(0, "\r\nLOW POWER RESET\r\n"); - #endif - } - - if (RCC_GetFlagStatus(RCC_FLAG_PINRST) != RESET) - { // Pin Reset - #if defined(PIOS_COM_DEBUG) - DEBUG_PRINTF("0, \r\nPIN RESET\r\n"); - #endif - } - - // Clear reset flags - //RCC_ClearFlag(); -} - -int main() -{ - int result; - // ************* - // init various variables - // ************* - /* NOTE: Do NOT modify the following start-up sequence */ - /* Any new initialization functions should be added in OpenPilotInit() */ - vPortInitialiseBlocks(); - - // Bring up System using CMSIS functions, enables the LEDs. - PIOS_SYS_Init(); - - /* For Revolution we use a FreeRTOS task to bring up the system so we can */ - /* always rely on FreeRTOS primitive */ - result = xTaskCreate(initTask, (const signed char *)"init", - INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY, - &initTaskHandle); - PIOS_Assert(result == pdPASS); - - /* Start the FreeRTOS scheduler which should never returns.*/ - vTaskStartScheduler(); - - /* If all is well we will never reach here as the scheduler will now be running. */ - /* Do some indication to user that something bad just happened */ - PIOS_LED_Off(PIOS_LED_HEARTBEAT); \ - for(;;) { \ - PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ - PIOS_DELAY_WaitmS(100); \ - }; - - return 0; -} - -/** - * Initialisation task. - * - * Runs board and module initialisation, then terminates. - */ -void -initTask(void *parameters) -{ - /* board driver init */ - PIOS_Board_Init(); - - /* Initialize modules */ - MODULE_INITIALISE_ALL; - - /* terminate this task */ - vTaskDelete(NULL); -} - -// ***************************************************************************** + +/** + ****************************************************************************** + * + * @file main.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main modem functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +// ***************************************************************************** + +//#define USE_WATCHDOG // comment this out if you don't want to use the watchdog + +// ***************************************************************************** +// OpenPilot Includes + +#include + +#include "openpilot.h" +#include "systemmod.h" + +/* Task Priorities */ +#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) + +/* Global Variables */ + +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void Stack_Change(void); +static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change"))); + + +/* Function Prototypes */ +static void initTask(void *parameters); +/* Local Variables */ +#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority +#define INIT_TASK_STACK (1024 / 4) // XXX this seems excessive +static xTaskHandle initTaskHandle; + +// ***************************************************************************** +// Global Variables + +// ***************************************************************************** +// Local Variables + +#if defined(USE_WATCHDOG) + volatile uint16_t watchdog_timer; + uint16_t watchdog_delay; +#endif + +// ***************************************************************************** + +#if defined(USE_WATCHDOG) + + void processWatchdog(void) + { + // random32 = UpdateCRC32(random32, IWDG->SR); + + if (watchdog_timer < watchdog_delay) + return; + + // the watchdog needs resetting + + watchdog_timer = 0; + + watchdog_Clear(); + } + + void enableWatchdog(void) + { // enable a watchdog + watchdog_timer = 0; + watchdog_delay = watchdog_Init(1000); // 1 second watchdog timeout + } + +#endif + +// ***************************************************************************** + +void sequenceLEDs(void) +{ + for (int i = 0; i < 2; i++) + { + //USB_LED_ON; + PIOS_DELAY_WaitmS(100); + //USB_LED_OFF; + PIOS_DELAY_WaitmS(100); + + #if defined(USE_WATCHDOG) + processWatchdog(); // process the watchdog + #endif + } +} + +// ***************************************************************************** +// find out what caused our reset and act on it + +void processReset(void) +{ + if (RCC_GetFlagStatus(RCC_FLAG_IWDGRST) != RESET) + { // Independant Watchdog Reset + + #if defined(PIOS_COM_DEBUG_CONSOLE) + DEBUG_PRINTF(0, "\r\nINDEPENDANT WATCHDOG CAUSED A RESET\r\n"); + #endif + + // all led's ON + //USB_LED_ON; + + + PIOS_DELAY_WaitmS(500); // delay a bit + + // all led's OFF + //USB_LED_OFF; + + + } +/* + if (RCC_GetFlagStatus(RCC_FLAG_WWDGRST) != RESET) + { // Window Watchdog Reset + + DEBUG_PRINTF(0, "\r\nWINDOW WATCHDOG CAUSED A REBOOT\r\n"); + + // all led's ON + USB_LED_ON; + LINK_LED_ON; + RX_LED_ON; + TX_LED_ON; + + PIOS_DELAY_WaitmS(500); // delay a bit + + // all led's OFF + USB_LED_OFF; + LINK_LED_OFF; + RX_LED_OFF; + TX_LED_OFF; + } +*/ + if (RCC_GetFlagStatus(RCC_FLAG_PORRST) != RESET) + { // Power-On Reset + #if defined(PIOS_COM_DEBUG) + DEBUG_PRINTF(0, "\r\nPOWER-ON-RESET\r\n"); + #endif + } + + if (RCC_GetFlagStatus(RCC_FLAG_SFTRST) != RESET) + { // Software Reset + #if defined(PIOS_COM_DEBUG) + DEBUG_PRINTF(0, "\r\nSOFTWARE RESET\r\n"); + #endif + } + + if (RCC_GetFlagStatus(RCC_FLAG_LPWRRST) != RESET) + { // Low-Power Reset + #if defined(PIOS_COM_DEBUG) + DEBUG_PRINTF(0, "\r\nLOW POWER RESET\r\n"); + #endif + } + + if (RCC_GetFlagStatus(RCC_FLAG_PINRST) != RESET) + { // Pin Reset + #if defined(PIOS_COM_DEBUG) + DEBUG_PRINTF("0, \r\nPIN RESET\r\n"); + #endif + } + + // Clear reset flags + //RCC_ClearFlag(); +} + +int main() +{ + int result; + // ************* + // init various variables + // ************* + /* NOTE: Do NOT modify the following start-up sequence */ + /* Any new initialization functions should be added in OpenPilotInit() */ + vPortInitialiseBlocks(); + + // Bring up System using CMSIS functions, enables the LEDs. + PIOS_SYS_Init(); + + /* For Revolution we use a FreeRTOS task to bring up the system so we can */ + /* always rely on FreeRTOS primitive */ + result = xTaskCreate(initTask, (const signed char *)"init", + INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY, + &initTaskHandle); + PIOS_Assert(result == pdPASS); + + /* Start the FreeRTOS scheduler which should never returns.*/ + vTaskStartScheduler(); + + /* If all is well we will never reach here as the scheduler will now be running. */ + /* Do some indication to user that something bad just happened */ + PIOS_LED_Off(PIOS_LED_HEARTBEAT); \ + for(;;) { \ + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ + PIOS_DELAY_WaitmS(100); \ + }; + + return 0; +} + +/** + * Initialisation task. + * + * Runs board and module initialisation, then terminates. + */ +void +initTask(void *parameters) +{ + /* board driver init */ + PIOS_Board_Init(); + + /* Initialize modules */ + MODULE_INITIALISE_ALL; + + /* terminate this task */ + vTaskDelete(NULL); +} + +// ***************************************************************************** diff --git a/flight/targets/PipXtreme/System/alarms.c b/flight/targets/PipXtreme/System/alarms.c index 01d79a1e5..a55cbd158 100755 --- a/flight/targets/PipXtreme/System/alarms.c +++ b/flight/targets/PipXtreme/System/alarms.c @@ -1,214 +1,214 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @brief OpenPilot System libraries are available to all OP modules. - * @{ - * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Library for setting and clearing system alarms - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "alarms.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; - -// Private functions -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); - -/** - * Initialize the alarms library - */ -int32_t AlarmsInitialize(void) -{ - SystemAlarmsInitialize(); - - lock = xSemaphoreCreateRecursiveMutex(); - //do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that - //AlarmsClearAll(); - //AlarmsDefaultAll(); - return 0; -} - -/** - * Set an alarm - * @param alarm The system alarm to be modified - * @param severity The alarm severity - * @return 0 if success, -1 if an error - */ -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } - - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; - -} - -/** - * Get an alarm - * @param alarm The system alarm to be read - * @return Alarm severity - */ -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } - - // Read alarm - SystemAlarmsGet(&alarms); - return alarms.Alarm[alarm]; -} - -/** - * Set an alarm to it's default value - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); -} - -/** - * Default all alarms - */ -void AlarmsDefaultAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); - } -} - -/** - * Clear an alarm - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); -} - -/** - * Clear all alarms - */ -void AlarmsClearAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); - } -} - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasWarnings() -{ - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); -} - -/** - * Check if there are any alarms with error or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasErrors() -{ - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; - -/** - * Check if there are any alarms with critical or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasCritical() -{ - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - uint32_t n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarms - SystemAlarmsGet(&alarms); - - // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } - } - - // If this point is reached then no alarms found - xSemaphoreGiveRecursive(lock); - return 0; -} -/** - * @} - * @} - */ - +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @brief OpenPilot System libraries are available to all OP modules. + * @{ + * @file alarms.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Library for setting and clearing system alarms + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "alarms.h" + +// Private constants + +// Private types + +// Private variables +static xSemaphoreHandle lock; + +// Private functions +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); + +/** + * Initialize the alarms library + */ +int32_t AlarmsInitialize(void) +{ + SystemAlarmsInitialize(); + + lock = xSemaphoreCreateRecursiveMutex(); + //do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that + //AlarmsClearAll(); + //AlarmsDefaultAll(); + return 0; +} + +/** + * Set an alarm + * @param alarm The system alarm to be modified + * @param severity The alarm severity + * @return 0 if success, -1 if an error + */ +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return -1; + } + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarm and update its severity only if it was changed + SystemAlarmsGet(&alarms); + if ( alarms.Alarm[alarm] != severity ) + { + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); + } + + // Release lock + xSemaphoreGiveRecursive(lock); + return 0; + +} + +/** + * Get an alarm + * @param alarm The system alarm to be read + * @return Alarm severity + */ +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return 0; + } + + // Read alarm + SystemAlarmsGet(&alarms); + return alarms.Alarm[alarm]; +} + +/** + * Set an alarm to it's default value + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); +} + +/** + * Default all alarms + */ +void AlarmsDefaultAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsDefault(n); + } +} + +/** + * Clear an alarm + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); +} + +/** + * Clear all alarms + */ +void AlarmsClearAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsClear(n); + } +} + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasWarnings() +{ + return hasSeverity(SYSTEMALARMS_ALARM_WARNING); +} + +/** + * Check if there are any alarms with error or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasErrors() +{ + return hasSeverity(SYSTEMALARMS_ALARM_ERROR); +}; + +/** + * Check if there are any alarms with critical or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasCritical() +{ + return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); +}; + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + uint32_t n; + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarms + SystemAlarmsGet(&alarms); + + // Go through alarms and check if any are of the given severity or higher + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + if ( alarms.Alarm[n] >= severity) + { + xSemaphoreGiveRecursive(lock); + return 1; + } + } + + // If this point is reached then no alarms found + xSemaphoreGiveRecursive(lock); + return 0; +} +/** + * @} + * @} + */ + diff --git a/flight/targets/PipXtreme/System/inc/alarms.h b/flight/targets/PipXtreme/System/inc/alarms.h index 9fb047dca..0f0faeb8f 100755 --- a/flight/targets/PipXtreme/System/inc/alarms.h +++ b/flight/targets/PipXtreme/System/inc/alarms.h @@ -1,50 +1,50 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the alarm library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef ALARMS_H -#define ALARMS_H - -#include "systemalarms.h" -#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED - -int32_t AlarmsInitialize(void); -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); -void AlarmsDefaultAll(); -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); -void AlarmsClearAll(); -int32_t AlarmsHasWarnings(); -int32_t AlarmsHasErrors(); -int32_t AlarmsHasCritical(); - -#endif // ALARMS_H - -/** - * @} - * @} +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file alarms.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the alarm library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ALARMS_H +#define ALARMS_H + +#include "systemalarms.h" +#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED + +int32_t AlarmsInitialize(void); +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); +void AlarmsDefaultAll(); +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); +void AlarmsClearAll(); +int32_t AlarmsHasWarnings(); +int32_t AlarmsHasErrors(); +int32_t AlarmsHasCritical(); + +#endif // ALARMS_H + +/** + * @} + * @} */ diff --git a/flight/targets/PipXtreme/System/inc/openpilot.h b/flight/targets/PipXtreme/System/inc/openpilot.h index 7f1ac3758..eb3cadcc7 100755 --- a/flight/targets/PipXtreme/System/inc/openpilot.h +++ b/flight/targets/PipXtreme/System/inc/openpilot.h @@ -1,52 +1,52 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file openpilot.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main OpenPilot header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef OPENPILOT_H -#define OPENPILOT_H - - -/* PIOS Includes */ -#include - -/* OpenPilot Libraries */ -#include "utlist.h" -#include "uavobjectmanager.h" -#include "eventdispatcher.h" -#include "alarms.h" -#include "taskmonitor.h" -#include "uavtalk.h" - -/* Global Functions */ -void OpenPilotInit(void); - -#endif /* OPENPILOT_H */ -/** - * @} - * @} +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file openpilot.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main OpenPilot header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OPENPILOT_H +#define OPENPILOT_H + + +/* PIOS Includes */ +#include + +/* OpenPilot Libraries */ +#include "utlist.h" +#include "uavobjectmanager.h" +#include "eventdispatcher.h" +#include "alarms.h" +#include "taskmonitor.h" +#include "uavtalk.h" + +/* Global Functions */ +void OpenPilotInit(void); + +#endif /* OPENPILOT_H */ +/** + * @} + * @} */ diff --git a/flight/targets/PipXtreme/System/inc/pios_board_posix.h b/flight/targets/PipXtreme/System/inc/pios_board_posix.h index 741f36ba7..84eadbeba 100755 --- a/flight/targets/PipXtreme/System/inc/pios_board_posix.h +++ b/flight/targets/PipXtreme/System/inc/pios_board_posix.h @@ -1,84 +1,84 @@ -/** - ****************************************************************************** - * - * @file pios_board.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_BOARD_H -#define PIOS_BOARD_H - - - - -//------------------------ -// PIOS_LED -//------------------------ -//#define PIOS_LED_LED1_GPIO_PORT GPIOC -//#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12 -//#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC -//#define PIOS_LED_LED2_GPIO_PORT GPIOC -//#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13 -//#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC -#define PIOS_LED_NUM 2 -//#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT } -//#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN } -//#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK } - - -//------------------------- -// COM -// -// See also pios_board_posix.c -//------------------------- -//#define PIOS_USART_TX_BUFFER_SIZE 256 -#define PIOS_COM_BUFFER_SIZE 1024 -#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE - -#define PIOS_COM_TELEM_RF 0 -#define PIOS_COM_GPS 1 -#define PIOS_COM_TELEM_USB 2 - -#ifdef PIOS_ENABLE_AUX_UART -#define PIOS_COM_AUX 3 -#define PIOS_COM_DEBUG PIOS_COM_AUX -#endif - -/** - * glue macros for file IO - * STM32 uses DOSFS for file IO - */ -#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL - -#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL - -#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length - -#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file) - - - -#define PIOS_FCLOSE(file) fclose(file) - -#define PIOS_FUNLINK(file) unlink((char*)filename) - -#endif /* PIOS_BOARD_H */ +/** + ****************************************************************************** + * + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_BOARD_H +#define PIOS_BOARD_H + + + + +//------------------------ +// PIOS_LED +//------------------------ +//#define PIOS_LED_LED1_GPIO_PORT GPIOC +//#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12 +//#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC +//#define PIOS_LED_LED2_GPIO_PORT GPIOC +//#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13 +//#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC +#define PIOS_LED_NUM 2 +//#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT } +//#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN } +//#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK } + + +//------------------------- +// COM +// +// See also pios_board_posix.c +//------------------------- +//#define PIOS_USART_TX_BUFFER_SIZE 256 +#define PIOS_COM_BUFFER_SIZE 1024 +#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE + +#define PIOS_COM_TELEM_RF 0 +#define PIOS_COM_GPS 1 +#define PIOS_COM_TELEM_USB 2 + +#ifdef PIOS_ENABLE_AUX_UART +#define PIOS_COM_AUX 3 +#define PIOS_COM_DEBUG PIOS_COM_AUX +#endif + +/** + * glue macros for file IO + * STM32 uses DOSFS for file IO + */ +#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL + +#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL + +#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length + +#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file) + + + +#define PIOS_FCLOSE(file) fclose(file) + +#define PIOS_FUNLINK(file) unlink((char*)filename) + +#endif /* PIOS_BOARD_H */ diff --git a/flight/targets/PipXtreme/System/inc/pios_config.h b/flight/targets/PipXtreme/System/inc/pios_config.h index 88feadc80..b7e7551fa 100755 --- a/flight/targets/PipXtreme/System/inc/pios_config.h +++ b/flight/targets/PipXtreme/System/inc/pios_config.h @@ -1,167 +1,167 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013. - * @brief PiOS configuration header, the compile time config file for the PIOS. - * Defines which PiOS libraries and features are included in the firmware. - * @see The GNU Public License (GPL) Version 3 - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* - * Below is a complete list of PIOS configurable options. - * Please do not remove or rearrange them. Only comment out - * unused options in the list. See main pios.h header for more - * details. - */ - -/* #define PIOS_INCLUDE_DEBUG_CONSOLE */ -/* #define DEBUG_LEVEL 0 */ - -/* PIOS FreeRTOS support */ -#define PIOS_INCLUDE_FREERTOS - -/* PIOS bootloader helper */ -#define PIOS_INCLUDE_BL_HELPER -/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */ - -/* PIOS system functions */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_INITCALL -#define PIOS_INCLUDE_SYS - -/* PIOS hardware peripherals */ -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_RTC -#define PIOS_INCLUDE_TIM -#define PIOS_INCLUDE_USART -/* #define PIOS_INCLUDE_ADC */ -/* #define PIOS_INCLUDE_I2C */ -#define PIOS_INCLUDE_SPI -#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_EXTI -#define PIOS_INCLUDE_WDG - -/* PIOS USB functions */ -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_USB_CDC -/* #define PIOS_INCLUDE_USB_RCTX */ - -/* PIOS sensor interfaces */ -/* #define PIOS_INCLUDE_ADXL345 */ -/* #define PIOS_INCLUDE_BMA180 */ -/* #define PIOS_INCLUDE_L3GD20 */ -/* #define PIOS_INCLUDE_MPU6000 */ -/* #define PIOS_MPU6000_ACCEL */ -/* #define PIOS_INCLUDE_HMC5843 */ -/* #define PIOS_INCLUDE_HMC5883 */ -/* #define PIOS_HMC5883_HAS_GPIOS */ -/* #define PIOS_INCLUDE_BMP085 */ -/* #define PIOS_INCLUDE_MS5611 */ -/* #define PIOS_INCLUDE_MPXV */ -/* #define PIOS_INCLUDE_ETASV3 */ -/* #define PIOS_INCLUDE_HCSR04 */ - -/* PIOS receiver drivers */ -/* #define PIOS_INCLUDE_PWM */ -#define PIOS_INCLUDE_PPM -/* #define PIOS_INCLUDE_PPM_FLEXI */ -/* #define PIOS_INCLUDE_DSM */ -/* #define PIOS_INCLUDE_SBUS */ -/* #define PIOS_INCLUDE_GCSRCVR */ - -/* PIOS abstract receiver interface */ -#define PIOS_INCLUDE_RCVR - -/* PIOS common peripherals */ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_IAP -/* #define PIOS_INCLUDE_SERVO */ -/* #define PIOS_INCLUDE_I2C_ESC */ -/* #define PIOS_INCLUDE_OVERO */ -/* #define PIOS_OVERO_SPI */ -/* #define PIOS_INCLUDE_SDCARD */ -/* #define LOG_FILENAME "startup.log" */ -/* #define PIOS_INCLUDE_FLASH */ -/* #define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS */ -/* #define FLASH_FREERTOS */ -#define PIOS_INCLUDE_FLASH_EEPROM - -/* PIOS radio modules */ -#define PIOS_INCLUDE_RFM22B -#define PIOS_INCLUDE_RFM22B_COM -/* #define PIOS_INCLUDE_RFM22B_RCVR */ -#define PIOS_INCLUDE_PPM_OUT -/* #define PIOS_RFM22B_DEBUG_ON_TELEM */ - -/* PIOS misc peripherals */ -/* #define PIOS_INCLUDE_VIDEO */ -/* #define PIOS_INCLUDE_WAVE */ -/* #define PIOS_INCLUDE_UDP */ - -/* PIOS abstract comms interface with options */ -#define PIOS_INCLUDE_COM -/* #define PIOS_INCLUDE_COM_MSG */ -/* #define PIOS_INCLUDE_TELEMETRY_RF */ -/* #define PIOS_INCLUDE_COM_TELEM */ -/* #define PIOS_INCLUDE_COM_FLEXI */ -/* #define PIOS_INCLUDE_COM_AUX */ -/* #define PIOS_TELEM_PRIORITY_QUEUE */ -/* #define PIOS_INCLUDE_GPS */ -/* #define PIOS_GPS_MINIMAL */ -/* #define PIOS_INCLUDE_GPS_NMEA_PARSER */ -/* #define PIOS_INCLUDE_GPS_UBX_PARSER */ -/* #define PIOS_GPS_SETS_HOMELOCATION */ - -/* Stabilization options */ -/* #define PIOS_QUATERNION_STABILIZATION */ - -/* Performance counters */ -#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998 - -/* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 220 -#define HEAP_LIMIT_CRITICAL 40 -#define IRQSTACK_LIMIT_WARNING 100 -#define IRQSTACK_LIMIT_CRITICAL 60 -#define CPULOAD_LIMIT_WARNING 85 -#define CPULOAD_LIMIT_CRITICAL 95 - -/* Task stack sizes */ -#define PIOS_ACTUATOR_STACK_SIZE 1020 -#define PIOS_MANUAL_STACK_SIZE 724 -#define PIOS_SYSTEM_STACK_SIZE 460 -#define PIOS_STABILIZATION_STACK_SIZE 524 -#define PIOS_TELEM_STACK_SIZE 500 -#define PIOS_EVENTDISPATCHER_STACK_SIZE 130 - -/* This can't be too high to stop eventdispatcher thread overflowing */ -#define PIOS_EVENTDISAPTCHER_QUEUE 10 - -#endif /* PIOS_CONFIG_H */ -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013. + * @brief PiOS configuration header, the compile time config file for the PIOS. + * Defines which PiOS libraries and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* + * Below is a complete list of PIOS configurable options. + * Please do not remove or rearrange them. Only comment out + * unused options in the list. See main pios.h header for more + * details. + */ + +/* #define PIOS_INCLUDE_DEBUG_CONSOLE */ +/* #define DEBUG_LEVEL 0 */ + +/* PIOS FreeRTOS support */ +#define PIOS_INCLUDE_FREERTOS + +/* PIOS bootloader helper */ +#define PIOS_INCLUDE_BL_HELPER +/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */ + +/* PIOS system functions */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_INITCALL +#define PIOS_INCLUDE_SYS + +/* PIOS hardware peripherals */ +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_RTC +#define PIOS_INCLUDE_TIM +#define PIOS_INCLUDE_USART +/* #define PIOS_INCLUDE_ADC */ +/* #define PIOS_INCLUDE_I2C */ +#define PIOS_INCLUDE_SPI +#define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_WDG + +/* PIOS USB functions */ +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +#define PIOS_INCLUDE_USB_CDC +/* #define PIOS_INCLUDE_USB_RCTX */ + +/* PIOS sensor interfaces */ +/* #define PIOS_INCLUDE_ADXL345 */ +/* #define PIOS_INCLUDE_BMA180 */ +/* #define PIOS_INCLUDE_L3GD20 */ +/* #define PIOS_INCLUDE_MPU6000 */ +/* #define PIOS_MPU6000_ACCEL */ +/* #define PIOS_INCLUDE_HMC5843 */ +/* #define PIOS_INCLUDE_HMC5883 */ +/* #define PIOS_HMC5883_HAS_GPIOS */ +/* #define PIOS_INCLUDE_BMP085 */ +/* #define PIOS_INCLUDE_MS5611 */ +/* #define PIOS_INCLUDE_MPXV */ +/* #define PIOS_INCLUDE_ETASV3 */ +/* #define PIOS_INCLUDE_HCSR04 */ + +/* PIOS receiver drivers */ +/* #define PIOS_INCLUDE_PWM */ +#define PIOS_INCLUDE_PPM +/* #define PIOS_INCLUDE_PPM_FLEXI */ +/* #define PIOS_INCLUDE_DSM */ +/* #define PIOS_INCLUDE_SBUS */ +/* #define PIOS_INCLUDE_GCSRCVR */ + +/* PIOS abstract receiver interface */ +#define PIOS_INCLUDE_RCVR + +/* PIOS common peripherals */ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +/* #define PIOS_INCLUDE_SERVO */ +/* #define PIOS_INCLUDE_I2C_ESC */ +/* #define PIOS_INCLUDE_OVERO */ +/* #define PIOS_OVERO_SPI */ +/* #define PIOS_INCLUDE_SDCARD */ +/* #define LOG_FILENAME "startup.log" */ +/* #define PIOS_INCLUDE_FLASH */ +/* #define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS */ +/* #define FLASH_FREERTOS */ +#define PIOS_INCLUDE_FLASH_EEPROM + +/* PIOS radio modules */ +#define PIOS_INCLUDE_RFM22B +#define PIOS_INCLUDE_RFM22B_COM +/* #define PIOS_INCLUDE_RFM22B_RCVR */ +#define PIOS_INCLUDE_PPM_OUT +/* #define PIOS_RFM22B_DEBUG_ON_TELEM */ + +/* PIOS misc peripherals */ +/* #define PIOS_INCLUDE_VIDEO */ +/* #define PIOS_INCLUDE_WAVE */ +/* #define PIOS_INCLUDE_UDP */ + +/* PIOS abstract comms interface with options */ +#define PIOS_INCLUDE_COM +/* #define PIOS_INCLUDE_COM_MSG */ +/* #define PIOS_INCLUDE_TELEMETRY_RF */ +/* #define PIOS_INCLUDE_COM_TELEM */ +/* #define PIOS_INCLUDE_COM_FLEXI */ +/* #define PIOS_INCLUDE_COM_AUX */ +/* #define PIOS_TELEM_PRIORITY_QUEUE */ +/* #define PIOS_INCLUDE_GPS */ +/* #define PIOS_GPS_MINIMAL */ +/* #define PIOS_INCLUDE_GPS_NMEA_PARSER */ +/* #define PIOS_INCLUDE_GPS_UBX_PARSER */ +/* #define PIOS_GPS_SETS_HOMELOCATION */ + +/* Stabilization options */ +/* #define PIOS_QUATERNION_STABILIZATION */ + +/* Performance counters */ +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998 + +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 220 +#define HEAP_LIMIT_CRITICAL 40 +#define IRQSTACK_LIMIT_WARNING 100 +#define IRQSTACK_LIMIT_CRITICAL 60 +#define CPULOAD_LIMIT_WARNING 85 +#define CPULOAD_LIMIT_CRITICAL 95 + +/* Task stack sizes */ +#define PIOS_ACTUATOR_STACK_SIZE 1020 +#define PIOS_MANUAL_STACK_SIZE 724 +#define PIOS_SYSTEM_STACK_SIZE 460 +#define PIOS_STABILIZATION_STACK_SIZE 524 +#define PIOS_TELEM_STACK_SIZE 500 +#define PIOS_EVENTDISPATCHER_STACK_SIZE 130 + +/* This can't be too high to stop eventdispatcher thread overflowing */ +#define PIOS_EVENTDISAPTCHER_QUEUE 10 + +#endif /* PIOS_CONFIG_H */ +/** + * @} + * @} + */ diff --git a/flight/targets/PipXtreme/System/inc/pios_config_posix.h b/flight/targets/PipXtreme/System/inc/pios_config_posix.h index 9d589d634..5747c0e3b 100755 --- a/flight/targets/PipXtreme/System/inc/pios_config_posix.h +++ b/flight/targets/PipXtreme/System/inc/pios_config_posix.h @@ -1,53 +1,53 @@ -/** - ****************************************************************************** - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * Central compile time config for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_CONFIG_POSIX_H -#define PIOS_CONFIG_POSIX_H - - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_FREERTOS -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_UDP -#define PIOS_INCLUDE_SERVO - - -/* Defaults for Logging */ -#define LOG_FILENAME "PIOS.LOG" -#define STARTUP_LOG_ENABLED 1 - -/* COM Module */ -#define GPS_BAUDRATE 19200 -#define TELEM_BAUDRATE 19200 -#define AUXUART_ENABLED 0 -#define AUXUART_BAUDRATE 19200 - - -#endif /* PIOS_CONFIG_POSIX_H */ +/** + ****************************************************************************** + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_CONFIG_POSIX_H +#define PIOS_CONFIG_POSIX_H + + +/* Enable/Disable PiOS Modules */ +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_UDP +#define PIOS_INCLUDE_SERVO + + +/* Defaults for Logging */ +#define LOG_FILENAME "PIOS.LOG" +#define STARTUP_LOG_ENABLED 1 + +/* COM Module */ +#define GPS_BAUDRATE 19200 +#define TELEM_BAUDRATE 19200 +#define AUXUART_ENABLED 0 +#define AUXUART_BAUDRATE 19200 + + +#endif /* PIOS_CONFIG_POSIX_H */ diff --git a/flight/targets/RevoMini/Makefile.osx b/flight/targets/RevoMini/Makefile.osx index 8786bd7c1..8dec4a2e5 100644 --- a/flight/targets/RevoMini/Makefile.osx +++ b/flight/targets/RevoMini/Makefile.osx @@ -1,658 +1,658 @@ - ##### - # Project: RevoMini - # - # - # Makefile for OpenPilot project build PiOS and the AP. - # - # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. - # - # - # This program is free software; you can redistribute it and/or modify - # it under the terms of the GNU General Public License as published by - # the Free Software Foundation; either version 3 of the License, or - # (at your option) any later version. - # - # This program is distributed in the hope that it will be useful, but - # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - # for more details. - # - # You should have received a copy of the GNU General Public License along - # with this program; if not, write to the Free Software Foundation, Inc., - # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - ##### - - -# Set developer code and compile options -# Set to YES to compile for debugging -DEBUG ?= YES - -# Set to YES to use the Servo output pins for debugging via scope or logic analyser -ENABLE_DEBUG_PINS ?= NO - -# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs -ENABLE_AUX_UART ?= NO - -# -USE_BOOTLOADER ?= NO - - -# Set to YES when using Code Sourcery toolchain -CODE_SOURCERY ?= NO - -# Remove command is different for Code Sourcery on Windows -REMOVE_CMD ?= rm - -FLASH_TOOL = OPENOCD - -# YES enables -mthumb option to flags for source-files listed -# in SRC and CPPSRC -USE_THUMB_MODE = YES - -# List of modules to include -MODULES += Actuator ManualControl Stabilization -MODULES += AltitudeHold FixedWingPathFollower PathPlanner -#MODULES += VtolPathFollower ## OP-700: VtolPathFollower disabled because its currently unsafe - remove this line once Sambas code has been merged -MODULES += Attitude/revolution -#MODULES += OveroSync/simulated - -# To run simulation instead of connect to SITL -MODULES += Sensors/simulated - -MODULES += Telemetry - -# MCU name, submodel and board -# - MCU used for compiler-option (-mtune) -# - MODEL used for linker-script name (-T) and passed as define -# - BOARD just passed as define (optional) -MCU = i686 -#CHIP = STM32F103RET -#BOARD = STM3210E_OP -MODEL = HD -ifeq ($(USE_BOOTLOADER), YES) -BOOT_MODEL = $(MODEL)_BL - -else -BOOT_MODEL = $(MODEL)_NB -endif - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR = ../../build/sim_osx - -# Target file name (without extension). -TARGET = RevoMini - -# Paths -OPSYSTEM = ./System -OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../UAVTalk -OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../UAVObjects -OPUAVOBJINC = $(OPUAVOBJ)/inc -OPTESTS = ./Tests -OPMODULEDIR = ../Modules -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = $(FLIGHTLIB)/inc -PIOS = ../PiOS.osx -PIOSINC = $(PIOS)/inc -PIOSPOSIX = $(PIOS)/osx -APPLIBDIR = $(PIOSPOSIX)/Libraries -RTOSDIR = $(APPLIBDIR)/FreeRTOS -RTOSSRCDIR = $(RTOSDIR)/Source -RTOSINCDIR = $(RTOSSRCDIR)/include -DOXYGENDIR = ../Doc/Doxygen -PYMITE = $(FLIGHTLIB)/PyMite -PYMITELIB = $(PYMITE)/lib -PYMITEPLAT = $(PYMITE)/platform/openpilot_sitl -PYMITETOOLS = $(PYMITE)/tools -PYMITEVM = $(PYMITE)/vm -PYMITEINC = $(PYMITEVM) -PYMITEINC += $(PYMITEPLAT) -PYMITEINC += $(OUTDIR) -FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib -FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans - -UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight -UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python - -# List C source files here. (C dependencies are automatically generated.) -# use file-extension c for "c-only"-files - -MODNAMES = $(notdir ${MODULES}) - -ifndef TESTAPP - -## PyMite files -SRC += $(OUTDIR)/pmlib_img.c -SRC += $(OUTDIR)/pmlib_nat.c -SRC += $(OUTDIR)/pmlibusr_img.c -SRC += $(OUTDIR)/pmlibusr_nat.c -SRC += $(wildcard ${PYMITEVM}/*.c) -SRC += $(wildcard ${PYMITEPLAT}/*.c) - -## MODULES -SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} -SRC += ${OUTDIR}/InitMods.c -## OPENPILOT CORE: -SRC += ${OPMODULEDIR}/System/systemmod.c -SRC += $(OPSYSTEM)/revolution.c -SRC += $(OPSYSTEM)/pios_board_sim.c -SRC += $(OPSYSTEM)/alarms.c -SRC += $(OPUAVTALK)/uavtalk.c -SRC += $(OPUAVOBJ)/uavobjectmanager.c -SRC += $(OPUAVOBJ)/eventdispatcher.c -SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c -else -## TESTCODE -SRC += $(OPTESTS)/test_common.c -SRC += $(OPTESTS)/$(TESTAPP).c -endif - - - -## UAVOBJECTS -ifndef TESTAPP -#include $(UAVOBJSYNTHDIR)/Makefile.inc -include ./UAVObjects.inc - -UAVOBJSRCFILENAMES += attitudesimulated -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) - -SRC += $(UAVOBJSRC) -CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) -endif - -## PIOS Hardware (posix) -SRC += $(PIOSPOSIX)/pios_crc.c -SRC += $(PIOSPOSIX)/pios_sys.c -SRC += $(PIOSPOSIX)/pios_led.c -SRC += $(PIOSPOSIX)/pios_irq.c -SRC += $(PIOSPOSIX)/pios_delay.c -SRC += $(PIOSPOSIX)/pios_sdcard.c -SRC += $(PIOSPOSIX)/pios_udp.c -SRC += $(PIOSPOSIX)/pios_tcp.c -SRC += $(PIOSPOSIX)/pios_com.c -SRC += $(PIOSPOSIX)/pios_servo.c -SRC += $(PIOSPOSIX)/pios_wdg.c -SRC += $(PIOSPOSIX)/pios_debug.c - -SRC += $(PIOSPOSIX)/pios_rcvr.c -SRC += $(PIOSPOSIX)/pios_gcsrcvr.c - -## Libraries for flight calculations -SRC += $(FLIGHTLIB)/fifo_buffer.c -SRC += $(FLIGHTLIB)/WorldMagModel.c -SRC += $(FLIGHTLIB)/CoordinateConversions.c -SRC += $(FLIGHTLIB)/paths.c -SRC += $(FLIGHTLIB)/insgps13state.c -SRC += $(FLIGHTLIB)/taskmonitor.c - -## RTOS and RTOS Portable -SRC += $(RTOSSRCDIR)/list.c -SRC += $(RTOSSRCDIR)/queue.c -UNAME := $(shell uname) -SRC += $(RTOSSRCDIR)/task.c -SRC += $(RTOSSRCDIR)/timers.c -SRC += $(RTOSSRCDIR)/portable/GCC/Posix/port.c -SRC += $(RTOSSRCDIR)/portable/MemMang/heap_3.c - - - -# List C source files here which must be compiled in ARM-Mode (no -mthumb). -# use file-extension c for "c-only"-files -## just for testing, timer.c could be compiled in thumb-mode too -SRCARM = - -# List C++ source files here. -# use file-extension .cpp for C++-files (not .C) -CPPSRC = - -# List C++ source files here which must be compiled in ARM-Mode. -# use file-extension .cpp for C++-files (not .C) -#CPPSRCARM = $(TARGET).cpp -CPPSRCARM = - - -# List any extra directories to look for include files here. -# Each directory must be seperated by a space. -EXTRAINCDIRS = $(OPSYSTEM) -EXTRAINCDIRS += $(OPSYSTEMINC) -EXTRAINCDIRS += $(OPUAVTALK) -EXTRAINCDIRS += $(OPUAVTALKINC) -EXTRAINCDIRS += $(OPUAVOBJ) -EXTRAINCDIRS += $(OPUAVOBJINC) -EXTRAINCDIRS += $(UAVOBJSYNTHDIR) -EXTRAINCDIRS += $(PIOS) -EXTRAINCDIRS += $(PIOSINC) -EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(PIOSPOSIX) -EXTRAINCDIRS += $(RTOSINCDIR) -EXTRAINCDIRS += $(APPLIBDIR) -EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Posix -EXTRAINCDIRS += $(PYMITEINC) - -EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc - - -# List any extra directories to look for library files here. -# Also add directories where the linker should search for -# includes from linker-script to the list -# Each directory must be seperated by a space. -EXTRA_LIBDIRS = - -# Extra Libraries -# Each library-name must be seperated by a space. -# i.e. to link with libxyz.a, libabc.a and libefsl.a: -# EXTRA_LIBS = xyz abc efsl -# for newlib-lpc (file: libnewlibc-lpc.a): -# EXTRA_LIBS = newlib-lpc -EXTRA_LIBS = - -# Path to Linker-Scripts -LINKERSCRIPTPATH = $(PIOSSTM32F10X) - -# Optimization level, can be [0, 1, 2, 3, s]. -# 0 = turn off optimization. s = optimize for size. -# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) - -ifeq ($(DEBUG),YES) -OPT = 0 -else -OPT = s -endif - -# Output format. (can be ihex or binary or both) -# binary to create a load-image in raw-binary format i.e. for SAM-BA, -# ihex to create a load-image in Intel hex format -#LOADFORMAT = ihex -#LOADFORMAT = binary -LOADFORMAT = both - -# Debugging format. -#DEBUGF = dwarf-2 - -# Place project-specific -D (define) and/or -# -U options for C here. -ifeq ($(ENABLE_DEBUG_PINS), YES) -CDEFS += -DPIOS_ENABLE_DEBUG_PINS -endif -ifeq ($(ENABLE_AUX_UART), YES) -CDEFS += -DPIOS_ENABLE_AUX_UART -endif -ifeq ($(USE_BOOTLOADER), YES) -CDEFS += -DUSE_BOOTLOADER -endif - -# Compiler flag to set the C Standard level. -# c89 - "ANSI" C -# gnu89 - c89 plus GCC extensions -# c99 - ISO C99 standard (not yet fully implemented) -# gnu99 - c99 plus GCC extensions -CSTANDARD = -std=gnu99 - -#----- - -# Compiler flags. - -# -g*: generate debugging information -# -O*: optimization level -# -f...: tuning, see GCC manual and avr-libc documentation -# -Wall...: warning level -# -Wa,...: tell GCC to pass this to the assembler. -# -adhlns...: create assembler listing -# -# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) - -ifeq ($(DEBUG),YES) -CFLAGS = -g$(DEBUGF) -DDEBUG -endif - -CFLAGS += -DDIAG_TASKS - -CFLAGS += $(CFLAGS_UAVOBJECTS) -CFLAGS += -DARCH_POSIX -CFLAGS += -O$(OPT) -CFLAGS += -mtune=$(MCU) -CFLAGS += $(CDEFS) -CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. - -#CFLAGS += ARCH=arm -#CROSS_COMPILE=/usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- - -CFLAGS += -fomit-frame-pointer -ifeq ($(CODE_SOURCERY), YES) -CFLAGS += -fpromote-loop-indices -endif - -CFLAGS += -Wall -CFLAGS += -Werror -# Compiler flags to generate dependency files: -CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d - -# flags only for C -#CONLYFLAGS += -Wnested-externs -CONLYFLAGS += $(CSTANDARD) - -# Assembler flags. -# -Wa,...: tell GCC to pass this to the assembler. -# -ahlns: create listing -ASFLAGS = -mtune=$(MCU) -I. -x assembler-with-cpp -ASFLAGS += $(ADEFS) -ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) -ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) - -MATH_LIB = -lm - -# Linker flags. -# -Wl,...: tell GCC to pass this to linker. -# -Map: create map file -# --cref: add cross reference to map file -LDFLAGS += -lpthread -LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) -LDFLAGS += -lc -LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) -LDFLAGS += $(MATH_LIB) -LDFLAGS += -lc -lgcc - -# To include simulation model -LDFLAGS += -L$(OUTDIR) -#LDFLAGS += -lsimmodel - - -# Define programs and commands. -CC = $(ARM_SDK_PREFIX)gcc -CPP = $(ARM_SDK_PREFIX)g++ -AR = $(ARM_SDK_PREFIX)ar -OBJCOPY = $(ARM_SDK_PREFIX)objcopy -OBJDUMP = $(ARM_SDK_PREFIX)objdump -SIZE = $(ARM_SDK_PREFIX)size -NM = $(ARM_SDK_PREFIX)nm -REMOVE = $(RM) -f - - - -# Define Messages -# English -MSG_ERRORS_NONE = Errors: none -MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote} -MSG_END = ${quote}-------- end --------${quote} -MSG_MODINIT = ${quote}**** Generating ModInit.c${quote} -MSG_SIZE_BEFORE = ${quote}Size before:${quote} -MSG_SIZE_AFTER = ${quote}Size after build:${quote} -MSG_LOAD_FILE = ${quote}Creating load file:${quote} -MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote} -MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote} -MSG_LINKING = ${quote}**** Linking :${quote} -MSG_COMPILING = ${quote}**** Compiling C :${quote} -MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote} -MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote} -MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote} -MSG_ASSEMBLING = ${quote}**** Assembling:${quote} -MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote} -MSG_CLEANING = ${quote}Cleaning project:${quote} -MSG_FORMATERROR = ${quote}Can not handle output-format${quote} -MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote} -MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote} -MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote} - -# List of all source files. -ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) -# List of all source files without directory and file-extension. -ALLSRCBASE = $(notdir $(basename $(ALLSRC))) - -# Define all object files. -ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) - -# Define all listing files (used for make clean). -LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) -# Define all depedency-files (used for make clean). -DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) - -elf: $(OUTDIR)/$(TARGET).elf -lss: $(OUTDIR)/$(TARGET).lss -sym: $(OUTDIR)/$(TARGET).sym -hex: $(OUTDIR)/$(TARGET).hex -bin: $(OUTDIR)/$(TARGET).bin - -# Default target. -#all: begin gccversion sizebefore build sizeafter finished end -#all: begin gencode gccversion build sizeafter finished end -all: elf - -ifeq ($(LOADFORMAT),ihex) -build: elf hex lss sym -else -ifeq ($(LOADFORMAT),binary) -build: elf bin lss sym -else -ifeq ($(LOADFORMAT),both) -build: elf hex bin lss sym -else -$(error "$(MSG_FORMATERROR) $(FORMAT)") -endif -endif -endif - -# Generate intermediate code -gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h - -getmodname = $(firstword $(subst /, ,$1)) - -MOD_GEN := $(foreach MOD,$(MODULES),$(call getmodname,$(MOD))) - -# Generate code for module initialization -${OUTDIR}/InitMods.c: Makefile.osx - echo ${MOD_GEN} - @echo ${MSG_MODINIT} - @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Start(void);}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c - -# Generate code for PyMite -${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) - @echo ${MSG_PYMITEINIT} - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) - @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py - -# Eye candy. -begin: -## @echo - @echo $(MSG_BEGIN) - -finished: -## @echo $(MSG_ERRORS_NONE) - -end: - @echo $(MSG_END) -## @echo - -# Display sizes of sections. -ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf -##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf -sizebefore: -# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi - -sizeafter: -# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi - @echo $(MSG_SIZE_AFTER) - $(ELFSIZE) - -# Display compiler version information. -gccversion : - @$(CC) --version -# @echo $(ALLOBJ) - -# Program the device. -ifeq ($(USE_BOOTLOADER), YES) -# Program the device with OP Upload Tool". -program: $(OUTDIR)/$(TARGET).bin - @echo ${quote}Programming with OP Upload Tool${quote} - ../../ground/src/experimental/upload-build-desktop/debug/OPUploadTool -d 0 -p $(OUTDIR)/$(TARGET).bin -else -ifeq ($(FLASH_TOOL),OPENOCD) -# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script". -program: $(OUTDIR)/$(TARGET).elf - @echo ${quote}Programming with OPENOCD${quote} - $(OOCD_EXE) $(OOCD_CL) -endif -endif - -# Create final output file (.hex) from ELF output file. -%.hex: %.elf -## @echo - @echo $(MSG_LOAD_FILE) $@ - $(OBJCOPY) -O ihex $< $@ - -# Create final output file (.bin) from ELF output file. -%.bin: %.elf -## @echo - @echo $(MSG_LOAD_FILE) $@ - $(OBJCOPY) -O binary $< $@ - -# Create extended listing file/disassambly from ELF output file. -# using objdump testing: option -C -%.lss: %.elf -## @echo - @echo $(MSG_EXTENDED_LISTING) $@ - $(OBJDUMP) -h -S -C -r $< > $@ -# $(OBJDUMP) -x -S $< > $@ - -# Create a symbol table from ELF output file. -%.sym: %.elf -## @echo - @echo $(MSG_SYMBOL_TABLE) $@ - $(NM) -n $< > $@ - -# Link: create ELF output file from object files. -.SECONDARY : $(TARGET).elf -.PRECIOUS : $(ALLOBJ) -%.elf: $(ALLOBJ) - @echo $(MSG_LINKING) $@ -# use $(CC) for C-only projects or $(CPP) for C++-projects: - $(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) -# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) - - -# Assemble: create object files from assembler source files. -define ASSEMBLE_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_ASSEMBLING) $$< to $$@ - $(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@ -endef -$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) - -# Assemble: create object files from assembler source files. ARM-only -define ASSEMBLE_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_ASSEMBLING_ARM) $$< to $$@ - $(CC) -c $$(ASFLAGS) $$< -o $$@ -endef -$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) - - -# Compile: create object files from C source files. -define COMPILE_C_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILING) $$< to $$@ - $(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ -endef -$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) - -# Compile: create object files from C source files. ARM-only -define COMPILE_C_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILING_ARM) $$< to $$@ - $(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ -endef -$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) - - -# Compile: create object files from C++ source files. -define COMPILE_CPP_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILINGCPP) $$< to $$@ - $(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ -endef -$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) - -# Compile: create object files from C++ source files. ARM-only -define COMPILE_CPP_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILINGCPP_ARM) $$< to $$@ - $(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ -endef -$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) - - -# Compile: create assembler files from C source files. ARM/Thumb -$(SRC:.c=.s) : %.s : %.c - @echo $(MSG_ASMFROMC) $< to $@ - $(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ - -# Compile: create assembler files from C source files. ARM only -$(SRCARM:.c=.s) : %.s : %.c - @echo $(MSG_ASMFROMC_ARM) $< to $@ - $(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ - -# Generate Doxygen documents -docs: - doxygen $(DOXYGENDIR)/doxygen.cfg - -# Target: clean project. -clean: begin clean_list finished end - -clean_list : -## @echo - @echo $(MSG_CLEANING) - $(REMOVE) $(OUTDIR)/$(TARGET).map - $(REMOVE) $(OUTDIR)/$(TARGET).elf - $(REMOVE) $(OUTDIR)/$(TARGET).hex - $(REMOVE) $(OUTDIR)/$(TARGET).bin - $(REMOVE) $(OUTDIR)/$(TARGET).sym - $(REMOVE) $(OUTDIR)/$(TARGET).lss - $(REMOVE) $(wildcard $(OUTDIR)/*.c) - $(REMOVE) $(wildcard $(OUTDIR)/*.h) - $(REMOVE) $(ALLOBJ) - $(REMOVE) $(LSTFILES) - $(REMOVE) $(DEPFILES) - $(REMOVE) $(SRC:.c=.s) - $(REMOVE) $(SRCARM:.c=.s) - $(REMOVE) $(CPPSRC:.cpp=.s) - $(REMOVE) $(CPPSRCARM:.cpp=.s) - - -# Create output files directory -# all known MS Windows OS define the ComSpec environment variable -ifdef ComSpec -$(shell md $(OUTDIR) 2>NUL) -else -$(shell mkdir $(OUTDIR) 2>/dev/null) -endif - -# Include the dependency files. -ifdef ComSpec --include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) -else --include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) -endif - - - -# Listing of phony targets. -.PHONY : all begin finish end sizebefore sizeafter gccversion \ -build elf hex bin lss sym clean clean_list program gencode - + ##### + # Project: RevoMini + # + # + # Makefile for OpenPilot project build PiOS and the AP. + # + # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. + # + # + # This program is free software; you can redistribute it and/or modify + # it under the terms of the GNU General Public License as published by + # the Free Software Foundation; either version 3 of the License, or + # (at your option) any later version. + # + # This program is distributed in the hope that it will be useful, but + # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + # for more details. + # + # You should have received a copy of the GNU General Public License along + # with this program; if not, write to the Free Software Foundation, Inc., + # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + ##### + + +# Set developer code and compile options +# Set to YES to compile for debugging +DEBUG ?= YES + +# Set to YES to use the Servo output pins for debugging via scope or logic analyser +ENABLE_DEBUG_PINS ?= NO + +# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs +ENABLE_AUX_UART ?= NO + +# +USE_BOOTLOADER ?= NO + + +# Set to YES when using Code Sourcery toolchain +CODE_SOURCERY ?= NO + +# Remove command is different for Code Sourcery on Windows +REMOVE_CMD ?= rm + +FLASH_TOOL = OPENOCD + +# YES enables -mthumb option to flags for source-files listed +# in SRC and CPPSRC +USE_THUMB_MODE = YES + +# List of modules to include +MODULES += Actuator ManualControl Stabilization +MODULES += AltitudeHold FixedWingPathFollower PathPlanner +#MODULES += VtolPathFollower ## OP-700: VtolPathFollower disabled because its currently unsafe - remove this line once Sambas code has been merged +MODULES += Attitude/revolution +#MODULES += OveroSync/simulated + +# To run simulation instead of connect to SITL +MODULES += Sensors/simulated + +MODULES += Telemetry + +# MCU name, submodel and board +# - MCU used for compiler-option (-mtune) +# - MODEL used for linker-script name (-T) and passed as define +# - BOARD just passed as define (optional) +MCU = i686 +#CHIP = STM32F103RET +#BOARD = STM3210E_OP +MODEL = HD +ifeq ($(USE_BOOTLOADER), YES) +BOOT_MODEL = $(MODEL)_BL + +else +BOOT_MODEL = $(MODEL)_NB +endif + +# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) +OUTDIR = ../../build/sim_osx + +# Target file name (without extension). +TARGET = RevoMini + +# Paths +OPSYSTEM = ./System +OPSYSTEMINC = $(OPSYSTEM)/inc +OPUAVTALK = ../UAVTalk +OPUAVTALKINC = $(OPUAVTALK)/inc +OPUAVOBJ = ../UAVObjects +OPUAVOBJINC = $(OPUAVOBJ)/inc +OPTESTS = ./Tests +OPMODULEDIR = ../Modules +FLIGHTLIB = ../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc +PIOS = ../PiOS.osx +PIOSINC = $(PIOS)/inc +PIOSPOSIX = $(PIOS)/osx +APPLIBDIR = $(PIOSPOSIX)/Libraries +RTOSDIR = $(APPLIBDIR)/FreeRTOS +RTOSSRCDIR = $(RTOSDIR)/Source +RTOSINCDIR = $(RTOSSRCDIR)/include +DOXYGENDIR = ../Doc/Doxygen +PYMITE = $(FLIGHTLIB)/PyMite +PYMITELIB = $(PYMITE)/lib +PYMITEPLAT = $(PYMITE)/platform/openpilot_sitl +PYMITETOOLS = $(PYMITE)/tools +PYMITEVM = $(PYMITE)/vm +PYMITEINC = $(PYMITEVM) +PYMITEINC += $(PYMITEPLAT) +PYMITEINC += $(OUTDIR) +FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib +FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans + +UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight +UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python + +# List C source files here. (C dependencies are automatically generated.) +# use file-extension c for "c-only"-files + +MODNAMES = $(notdir ${MODULES}) + +ifndef TESTAPP + +## PyMite files +SRC += $(OUTDIR)/pmlib_img.c +SRC += $(OUTDIR)/pmlib_nat.c +SRC += $(OUTDIR)/pmlibusr_img.c +SRC += $(OUTDIR)/pmlibusr_nat.c +SRC += $(wildcard ${PYMITEVM}/*.c) +SRC += $(wildcard ${PYMITEPLAT}/*.c) + +## MODULES +SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += ${OUTDIR}/InitMods.c +## OPENPILOT CORE: +SRC += ${OPMODULEDIR}/System/systemmod.c +SRC += $(OPSYSTEM)/revolution.c +SRC += $(OPSYSTEM)/pios_board_sim.c +SRC += $(OPSYSTEM)/alarms.c +SRC += $(OPUAVTALK)/uavtalk.c +SRC += $(OPUAVOBJ)/uavobjectmanager.c +SRC += $(OPUAVOBJ)/eventdispatcher.c +SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c +else +## TESTCODE +SRC += $(OPTESTS)/test_common.c +SRC += $(OPTESTS)/$(TESTAPP).c +endif + + + +## UAVOBJECTS +ifndef TESTAPP +#include $(UAVOBJSYNTHDIR)/Makefile.inc +include ./UAVObjects.inc + +UAVOBJSRCFILENAMES += attitudesimulated +UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) +UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) + +SRC += $(UAVOBJSRC) +CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) +endif + +## PIOS Hardware (posix) +SRC += $(PIOSPOSIX)/pios_crc.c +SRC += $(PIOSPOSIX)/pios_sys.c +SRC += $(PIOSPOSIX)/pios_led.c +SRC += $(PIOSPOSIX)/pios_irq.c +SRC += $(PIOSPOSIX)/pios_delay.c +SRC += $(PIOSPOSIX)/pios_sdcard.c +SRC += $(PIOSPOSIX)/pios_udp.c +SRC += $(PIOSPOSIX)/pios_tcp.c +SRC += $(PIOSPOSIX)/pios_com.c +SRC += $(PIOSPOSIX)/pios_servo.c +SRC += $(PIOSPOSIX)/pios_wdg.c +SRC += $(PIOSPOSIX)/pios_debug.c + +SRC += $(PIOSPOSIX)/pios_rcvr.c +SRC += $(PIOSPOSIX)/pios_gcsrcvr.c + +## Libraries for flight calculations +SRC += $(FLIGHTLIB)/fifo_buffer.c +SRC += $(FLIGHTLIB)/WorldMagModel.c +SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += $(FLIGHTLIB)/paths.c +SRC += $(FLIGHTLIB)/insgps13state.c +SRC += $(FLIGHTLIB)/taskmonitor.c + +## RTOS and RTOS Portable +SRC += $(RTOSSRCDIR)/list.c +SRC += $(RTOSSRCDIR)/queue.c +UNAME := $(shell uname) +SRC += $(RTOSSRCDIR)/task.c +SRC += $(RTOSSRCDIR)/timers.c +SRC += $(RTOSSRCDIR)/portable/GCC/Posix/port.c +SRC += $(RTOSSRCDIR)/portable/MemMang/heap_3.c + + + +# List C source files here which must be compiled in ARM-Mode (no -mthumb). +# use file-extension c for "c-only"-files +## just for testing, timer.c could be compiled in thumb-mode too +SRCARM = + +# List C++ source files here. +# use file-extension .cpp for C++-files (not .C) +CPPSRC = + +# List C++ source files here which must be compiled in ARM-Mode. +# use file-extension .cpp for C++-files (not .C) +#CPPSRCARM = $(TARGET).cpp +CPPSRCARM = + + +# List any extra directories to look for include files here. +# Each directory must be seperated by a space. +EXTRAINCDIRS = $(OPSYSTEM) +EXTRAINCDIRS += $(OPSYSTEMINC) +EXTRAINCDIRS += $(OPUAVTALK) +EXTRAINCDIRS += $(OPUAVTALKINC) +EXTRAINCDIRS += $(OPUAVOBJ) +EXTRAINCDIRS += $(OPUAVOBJINC) +EXTRAINCDIRS += $(UAVOBJSYNTHDIR) +EXTRAINCDIRS += $(PIOS) +EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(PIOSPOSIX) +EXTRAINCDIRS += $(RTOSINCDIR) +EXTRAINCDIRS += $(APPLIBDIR) +EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Posix +EXTRAINCDIRS += $(PYMITEINC) + +EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc + + +# List any extra directories to look for library files here. +# Also add directories where the linker should search for +# includes from linker-script to the list +# Each directory must be seperated by a space. +EXTRA_LIBDIRS = + +# Extra Libraries +# Each library-name must be seperated by a space. +# i.e. to link with libxyz.a, libabc.a and libefsl.a: +# EXTRA_LIBS = xyz abc efsl +# for newlib-lpc (file: libnewlibc-lpc.a): +# EXTRA_LIBS = newlib-lpc +EXTRA_LIBS = + +# Path to Linker-Scripts +LINKERSCRIPTPATH = $(PIOSSTM32F10X) + +# Optimization level, can be [0, 1, 2, 3, s]. +# 0 = turn off optimization. s = optimize for size. +# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) + +ifeq ($(DEBUG),YES) +OPT = 0 +else +OPT = s +endif + +# Output format. (can be ihex or binary or both) +# binary to create a load-image in raw-binary format i.e. for SAM-BA, +# ihex to create a load-image in Intel hex format +#LOADFORMAT = ihex +#LOADFORMAT = binary +LOADFORMAT = both + +# Debugging format. +#DEBUGF = dwarf-2 + +# Place project-specific -D (define) and/or +# -U options for C here. +ifeq ($(ENABLE_DEBUG_PINS), YES) +CDEFS += -DPIOS_ENABLE_DEBUG_PINS +endif +ifeq ($(ENABLE_AUX_UART), YES) +CDEFS += -DPIOS_ENABLE_AUX_UART +endif +ifeq ($(USE_BOOTLOADER), YES) +CDEFS += -DUSE_BOOTLOADER +endif + +# Compiler flag to set the C Standard level. +# c89 - "ANSI" C +# gnu89 - c89 plus GCC extensions +# c99 - ISO C99 standard (not yet fully implemented) +# gnu99 - c99 plus GCC extensions +CSTANDARD = -std=gnu99 + +#----- + +# Compiler flags. + +# -g*: generate debugging information +# -O*: optimization level +# -f...: tuning, see GCC manual and avr-libc documentation +# -Wall...: warning level +# -Wa,...: tell GCC to pass this to the assembler. +# -adhlns...: create assembler listing +# +# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) + +ifeq ($(DEBUG),YES) +CFLAGS = -g$(DEBUGF) -DDEBUG +endif + +CFLAGS += -DDIAG_TASKS + +CFLAGS += $(CFLAGS_UAVOBJECTS) +CFLAGS += -DARCH_POSIX +CFLAGS += -O$(OPT) +CFLAGS += -mtune=$(MCU) +CFLAGS += $(CDEFS) +CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. + +#CFLAGS += ARCH=arm +#CROSS_COMPILE=/usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- + +CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) +CFLAGS += -fpromote-loop-indices +endif + +CFLAGS += -Wall +CFLAGS += -Werror +# Compiler flags to generate dependency files: +CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d + +# flags only for C +#CONLYFLAGS += -Wnested-externs +CONLYFLAGS += $(CSTANDARD) + +# Assembler flags. +# -Wa,...: tell GCC to pass this to the assembler. +# -ahlns: create listing +ASFLAGS = -mtune=$(MCU) -I. -x assembler-with-cpp +ASFLAGS += $(ADEFS) +ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) + +MATH_LIB = -lm + +# Linker flags. +# -Wl,...: tell GCC to pass this to linker. +# -Map: create map file +# --cref: add cross reference to map file +LDFLAGS += -lpthread +LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) +LDFLAGS += -lc +LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) +LDFLAGS += $(MATH_LIB) +LDFLAGS += -lc -lgcc + +# To include simulation model +LDFLAGS += -L$(OUTDIR) +#LDFLAGS += -lsimmodel + + +# Define programs and commands. +CC = $(ARM_SDK_PREFIX)gcc +CPP = $(ARM_SDK_PREFIX)g++ +AR = $(ARM_SDK_PREFIX)ar +OBJCOPY = $(ARM_SDK_PREFIX)objcopy +OBJDUMP = $(ARM_SDK_PREFIX)objdump +SIZE = $(ARM_SDK_PREFIX)size +NM = $(ARM_SDK_PREFIX)nm +REMOVE = $(RM) -f + + + +# Define Messages +# English +MSG_ERRORS_NONE = Errors: none +MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote} +MSG_END = ${quote}-------- end --------${quote} +MSG_MODINIT = ${quote}**** Generating ModInit.c${quote} +MSG_SIZE_BEFORE = ${quote}Size before:${quote} +MSG_SIZE_AFTER = ${quote}Size after build:${quote} +MSG_LOAD_FILE = ${quote}Creating load file:${quote} +MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote} +MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote} +MSG_LINKING = ${quote}**** Linking :${quote} +MSG_COMPILING = ${quote}**** Compiling C :${quote} +MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote} +MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote} +MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote} +MSG_ASSEMBLING = ${quote}**** Assembling:${quote} +MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote} +MSG_CLEANING = ${quote}Cleaning project:${quote} +MSG_FORMATERROR = ${quote}Can not handle output-format${quote} +MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote} +MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote} +MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote} + +# List of all source files. +ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) +# List of all source files without directory and file-extension. +ALLSRCBASE = $(notdir $(basename $(ALLSRC))) + +# Define all object files. +ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) + +# Define all listing files (used for make clean). +LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) +# Define all depedency-files (used for make clean). +DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) + +elf: $(OUTDIR)/$(TARGET).elf +lss: $(OUTDIR)/$(TARGET).lss +sym: $(OUTDIR)/$(TARGET).sym +hex: $(OUTDIR)/$(TARGET).hex +bin: $(OUTDIR)/$(TARGET).bin + +# Default target. +#all: begin gccversion sizebefore build sizeafter finished end +#all: begin gencode gccversion build sizeafter finished end +all: elf + +ifeq ($(LOADFORMAT),ihex) +build: elf hex lss sym +else +ifeq ($(LOADFORMAT),binary) +build: elf bin lss sym +else +ifeq ($(LOADFORMAT),both) +build: elf hex bin lss sym +else +$(error "$(MSG_FORMATERROR) $(FORMAT)") +endif +endif +endif + +# Generate intermediate code +gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h + +getmodname = $(firstword $(subst /, ,$1)) + +MOD_GEN := $(foreach MOD,$(MODULES),$(call getmodname,$(MOD))) + +# Generate code for module initialization +${OUTDIR}/InitMods.c: Makefile.osx + echo ${MOD_GEN} + @echo ${MSG_MODINIT} + @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Start(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + +# Generate code for PyMite +${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) + @echo ${MSG_PYMITEINIT} + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) + @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py + +# Eye candy. +begin: +## @echo + @echo $(MSG_BEGIN) + +finished: +## @echo $(MSG_ERRORS_NONE) + +end: + @echo $(MSG_END) +## @echo + +# Display sizes of sections. +ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf +##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf +sizebefore: +# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi + +sizeafter: +# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi + @echo $(MSG_SIZE_AFTER) + $(ELFSIZE) + +# Display compiler version information. +gccversion : + @$(CC) --version +# @echo $(ALLOBJ) + +# Program the device. +ifeq ($(USE_BOOTLOADER), YES) +# Program the device with OP Upload Tool". +program: $(OUTDIR)/$(TARGET).bin + @echo ${quote}Programming with OP Upload Tool${quote} + ../../ground/src/experimental/upload-build-desktop/debug/OPUploadTool -d 0 -p $(OUTDIR)/$(TARGET).bin +else +ifeq ($(FLASH_TOOL),OPENOCD) +# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script". +program: $(OUTDIR)/$(TARGET).elf + @echo ${quote}Programming with OPENOCD${quote} + $(OOCD_EXE) $(OOCD_CL) +endif +endif + +# Create final output file (.hex) from ELF output file. +%.hex: %.elf +## @echo + @echo $(MSG_LOAD_FILE) $@ + $(OBJCOPY) -O ihex $< $@ + +# Create final output file (.bin) from ELF output file. +%.bin: %.elf +## @echo + @echo $(MSG_LOAD_FILE) $@ + $(OBJCOPY) -O binary $< $@ + +# Create extended listing file/disassambly from ELF output file. +# using objdump testing: option -C +%.lss: %.elf +## @echo + @echo $(MSG_EXTENDED_LISTING) $@ + $(OBJDUMP) -h -S -C -r $< > $@ +# $(OBJDUMP) -x -S $< > $@ + +# Create a symbol table from ELF output file. +%.sym: %.elf +## @echo + @echo $(MSG_SYMBOL_TABLE) $@ + $(NM) -n $< > $@ + +# Link: create ELF output file from object files. +.SECONDARY : $(TARGET).elf +.PRECIOUS : $(ALLOBJ) +%.elf: $(ALLOBJ) + @echo $(MSG_LINKING) $@ +# use $(CC) for C-only projects or $(CPP) for C++-projects: + $(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) +# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) + + +# Assemble: create object files from assembler source files. +define ASSEMBLE_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_ASSEMBLING) $$< to $$@ + $(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@ +endef +$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) + +# Assemble: create object files from assembler source files. ARM-only +define ASSEMBLE_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_ASSEMBLING_ARM) $$< to $$@ + $(CC) -c $$(ASFLAGS) $$< -o $$@ +endef +$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) + + +# Compile: create object files from C source files. +define COMPILE_C_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILING) $$< to $$@ + $(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ +endef +$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) + +# Compile: create object files from C source files. ARM-only +define COMPILE_C_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILING_ARM) $$< to $$@ + $(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ +endef +$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) + + +# Compile: create object files from C++ source files. +define COMPILE_CPP_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILINGCPP) $$< to $$@ + $(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ +endef +$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) + +# Compile: create object files from C++ source files. ARM-only +define COMPILE_CPP_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILINGCPP_ARM) $$< to $$@ + $(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ +endef +$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) + + +# Compile: create assembler files from C source files. ARM/Thumb +$(SRC:.c=.s) : %.s : %.c + @echo $(MSG_ASMFROMC) $< to $@ + $(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ + +# Compile: create assembler files from C source files. ARM only +$(SRCARM:.c=.s) : %.s : %.c + @echo $(MSG_ASMFROMC_ARM) $< to $@ + $(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ + +# Generate Doxygen documents +docs: + doxygen $(DOXYGENDIR)/doxygen.cfg + +# Target: clean project. +clean: begin clean_list finished end + +clean_list : +## @echo + @echo $(MSG_CLEANING) + $(REMOVE) $(OUTDIR)/$(TARGET).map + $(REMOVE) $(OUTDIR)/$(TARGET).elf + $(REMOVE) $(OUTDIR)/$(TARGET).hex + $(REMOVE) $(OUTDIR)/$(TARGET).bin + $(REMOVE) $(OUTDIR)/$(TARGET).sym + $(REMOVE) $(OUTDIR)/$(TARGET).lss + $(REMOVE) $(wildcard $(OUTDIR)/*.c) + $(REMOVE) $(wildcard $(OUTDIR)/*.h) + $(REMOVE) $(ALLOBJ) + $(REMOVE) $(LSTFILES) + $(REMOVE) $(DEPFILES) + $(REMOVE) $(SRC:.c=.s) + $(REMOVE) $(SRCARM:.c=.s) + $(REMOVE) $(CPPSRC:.cpp=.s) + $(REMOVE) $(CPPSRCARM:.cpp=.s) + + +# Create output files directory +# all known MS Windows OS define the ComSpec environment variable +ifdef ComSpec +$(shell md $(OUTDIR) 2>NUL) +else +$(shell mkdir $(OUTDIR) 2>/dev/null) +endif + +# Include the dependency files. +ifdef ComSpec +-include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) +else +-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) +endif + + + +# Listing of phony targets. +.PHONY : all begin finish end sizebefore sizeafter gccversion \ +build elf hex bin lss sym clean clean_list program gencode + diff --git a/flight/targets/RevoMini/System/alarms.c b/flight/targets/RevoMini/System/alarms.c index e61c7c1ea..6ccd5fb62 100644 --- a/flight/targets/RevoMini/System/alarms.c +++ b/flight/targets/RevoMini/System/alarms.c @@ -1,210 +1,210 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @brief OpenPilot System libraries are available to all OP modules. - * @{ - * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Library for setting and clearing system alarms - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "alarms.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; - -// Private functions -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); - -/** - * Initialize the alarms library - */ -int32_t AlarmsInitialize(void) -{ - SystemAlarmsInitialize(); - lock = xSemaphoreCreateRecursiveMutex(); - return 0; -} - -/** - * Set an alarm - * @param alarm The system alarm to be modified - * @param severity The alarm severity - * @return 0 if success, -1 if an error - */ -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } - - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; - -} - -/** - * Get an alarm - * @param alarm The system alarm to be read - * @return Alarm severity - */ -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } - - // Read alarm - SystemAlarmsGet(&alarms); - return alarms.Alarm[alarm]; -} - -/** - * Set an alarm to it's default value - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); -} - -/** - * Default all alarms - */ -void AlarmsDefaultAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); - } -} - -/** - * Clear an alarm - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); -} - -/** - * Clear all alarms - */ -void AlarmsClearAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); - } -} - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasWarnings() -{ - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); -} - -/** - * Check if there are any alarms with error or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasErrors() -{ - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; - -/** - * Check if there are any alarms with critical or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasCritical() -{ - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - uint32_t n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarms - SystemAlarmsGet(&alarms); - - // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } - } - - // If this point is reached then no alarms found - xSemaphoreGiveRecursive(lock); - return 0; -} -/** - * @} - * @} - */ - +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @brief OpenPilot System libraries are available to all OP modules. + * @{ + * @file alarms.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Library for setting and clearing system alarms + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "alarms.h" + +// Private constants + +// Private types + +// Private variables +static xSemaphoreHandle lock; + +// Private functions +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); + +/** + * Initialize the alarms library + */ +int32_t AlarmsInitialize(void) +{ + SystemAlarmsInitialize(); + lock = xSemaphoreCreateRecursiveMutex(); + return 0; +} + +/** + * Set an alarm + * @param alarm The system alarm to be modified + * @param severity The alarm severity + * @return 0 if success, -1 if an error + */ +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return -1; + } + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarm and update its severity only if it was changed + SystemAlarmsGet(&alarms); + if ( alarms.Alarm[alarm] != severity ) + { + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); + } + + // Release lock + xSemaphoreGiveRecursive(lock); + return 0; + +} + +/** + * Get an alarm + * @param alarm The system alarm to be read + * @return Alarm severity + */ +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return 0; + } + + // Read alarm + SystemAlarmsGet(&alarms); + return alarms.Alarm[alarm]; +} + +/** + * Set an alarm to it's default value + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); +} + +/** + * Default all alarms + */ +void AlarmsDefaultAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsDefault(n); + } +} + +/** + * Clear an alarm + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); +} + +/** + * Clear all alarms + */ +void AlarmsClearAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsClear(n); + } +} + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasWarnings() +{ + return hasSeverity(SYSTEMALARMS_ALARM_WARNING); +} + +/** + * Check if there are any alarms with error or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasErrors() +{ + return hasSeverity(SYSTEMALARMS_ALARM_ERROR); +}; + +/** + * Check if there are any alarms with critical or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasCritical() +{ + return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); +}; + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + uint32_t n; + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarms + SystemAlarmsGet(&alarms); + + // Go through alarms and check if any are of the given severity or higher + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + if ( alarms.Alarm[n] >= severity) + { + xSemaphoreGiveRecursive(lock); + return 1; + } + } + + // If this point is reached then no alarms found + xSemaphoreGiveRecursive(lock); + return 0; +} +/** + * @} + * @} + */ + diff --git a/flight/targets/RevoMini/System/inc/alarms.h b/flight/targets/RevoMini/System/inc/alarms.h index 9fb047dca..0f0faeb8f 100644 --- a/flight/targets/RevoMini/System/inc/alarms.h +++ b/flight/targets/RevoMini/System/inc/alarms.h @@ -1,50 +1,50 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the alarm library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef ALARMS_H -#define ALARMS_H - -#include "systemalarms.h" -#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED - -int32_t AlarmsInitialize(void); -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); -void AlarmsDefaultAll(); -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); -void AlarmsClearAll(); -int32_t AlarmsHasWarnings(); -int32_t AlarmsHasErrors(); -int32_t AlarmsHasCritical(); - -#endif // ALARMS_H - -/** - * @} - * @} +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file alarms.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the alarm library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ALARMS_H +#define ALARMS_H + +#include "systemalarms.h" +#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED + +int32_t AlarmsInitialize(void); +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); +void AlarmsDefaultAll(); +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); +void AlarmsClearAll(); +int32_t AlarmsHasWarnings(); +int32_t AlarmsHasErrors(); +int32_t AlarmsHasCritical(); + +#endif // ALARMS_H + +/** + * @} + * @} */ diff --git a/flight/targets/RevoMini/System/inc/openpilot.h b/flight/targets/RevoMini/System/inc/openpilot.h index 7f1ac3758..eb3cadcc7 100644 --- a/flight/targets/RevoMini/System/inc/openpilot.h +++ b/flight/targets/RevoMini/System/inc/openpilot.h @@ -1,52 +1,52 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file openpilot.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main OpenPilot header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef OPENPILOT_H -#define OPENPILOT_H - - -/* PIOS Includes */ -#include - -/* OpenPilot Libraries */ -#include "utlist.h" -#include "uavobjectmanager.h" -#include "eventdispatcher.h" -#include "alarms.h" -#include "taskmonitor.h" -#include "uavtalk.h" - -/* Global Functions */ -void OpenPilotInit(void); - -#endif /* OPENPILOT_H */ -/** - * @} - * @} +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file openpilot.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main OpenPilot header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OPENPILOT_H +#define OPENPILOT_H + + +/* PIOS Includes */ +#include + +/* OpenPilot Libraries */ +#include "utlist.h" +#include "uavobjectmanager.h" +#include "eventdispatcher.h" +#include "alarms.h" +#include "taskmonitor.h" +#include "uavtalk.h" + +/* Global Functions */ +void OpenPilotInit(void); + +#endif /* OPENPILOT_H */ +/** + * @} + * @} */ diff --git a/flight/targets/RevoMini/System/inc/pios_board_sim.h b/flight/targets/RevoMini/System/inc/pios_board_sim.h index 8f551cab9..e3625f583 100644 --- a/flight/targets/RevoMini/System/inc/pios_board_sim.h +++ b/flight/targets/RevoMini/System/inc/pios_board_sim.h @@ -1,85 +1,85 @@ -/** - ****************************************************************************** - * - * @file pios_board.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_BOARD_H -#define PIOS_BOARD_H - - - - -//------------------------ -// PIOS_LED -//------------------------ -#define PIOS_LED_ALARM 0 -#define PIOS_LED_HEARTBEAT 1 -#define PIOS_LED_NUM 2 - -//------------------------- -// COM -// -// See also pios_board_posix.c -//------------------------- -//#define PIOS_USART_TX_BUFFER_SIZE 256 -#define PIOS_COM_BUFFER_SIZE 1024 -#define PIOS_COM_MAX_DEVS 255 -#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE -#define PIOS_TCP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE - -extern uint32_t pios_com_telem_rf_id; -extern uint32_t pios_com_telem_usb_id; -extern uint32_t pios_com_gps_id; -extern uint32_t pios_com_aux_id; -extern uint32_t pios_com_spectrum_id; - -#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) -#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#define PIOS_COM_GPS (pios_com_gps_id) - -#ifdef PIOS_ENABLE_AUX_UART -#define PIOS_COM_AUX (pios_com_aux_id) -#define PIOS_COM_DEBUG (PIOS_COM_AUX) -#endif - -#define PIOS_GCSRCVR_TIMEOUT_MS 200 -/** - * glue macros for file IO - * STM32 uses DOSFS for file IO - */ -#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL - -#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL - -#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length - -#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file) - - - -#define PIOS_FCLOSE(file) fclose(file) - -#define PIOS_FUNLINK(file) unlink((char*)filename) - -#endif /* PIOS_BOARD_H */ +/** + ****************************************************************************** + * + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_BOARD_H +#define PIOS_BOARD_H + + + + +//------------------------ +// PIOS_LED +//------------------------ +#define PIOS_LED_ALARM 0 +#define PIOS_LED_HEARTBEAT 1 +#define PIOS_LED_NUM 2 + +//------------------------- +// COM +// +// See also pios_board_posix.c +//------------------------- +//#define PIOS_USART_TX_BUFFER_SIZE 256 +#define PIOS_COM_BUFFER_SIZE 1024 +#define PIOS_COM_MAX_DEVS 255 +#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE +#define PIOS_TCP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE + +extern uint32_t pios_com_telem_rf_id; +extern uint32_t pios_com_telem_usb_id; +extern uint32_t pios_com_gps_id; +extern uint32_t pios_com_aux_id; +extern uint32_t pios_com_spectrum_id; + +#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) +#define PIOS_COM_GPS (pios_com_gps_id) + +#ifdef PIOS_ENABLE_AUX_UART +#define PIOS_COM_AUX (pios_com_aux_id) +#define PIOS_COM_DEBUG (PIOS_COM_AUX) +#endif + +#define PIOS_GCSRCVR_TIMEOUT_MS 200 +/** + * glue macros for file IO + * STM32 uses DOSFS for file IO + */ +#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL + +#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL + +#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length + +#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file) + + + +#define PIOS_FCLOSE(file) fclose(file) + +#define PIOS_FUNLINK(file) unlink((char*)filename) + +#endif /* PIOS_BOARD_H */ diff --git a/flight/targets/RevoMini/System/inc/pios_config.h b/flight/targets/RevoMini/System/inc/pios_config.h index 4a92e7965..1df7180b3 100644 --- a/flight/targets/RevoMini/System/inc/pios_config.h +++ b/flight/targets/RevoMini/System/inc/pios_config.h @@ -1,171 +1,171 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013. - * @brief PiOS configuration header, the compile time config file for the PIOS. - * Defines which PiOS libraries and features are included in the firmware. - * @see The GNU Public License (GPL) Version 3 - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* - * Below is a complete list of PIOS configurable options. - * Please do not remove or rearrange them. Only comment out - * unused options in the list. See main pios.h header for more - * details. - */ - -/* #define PIOS_INCLUDE_DEBUG_CONSOLE */ -/* #define DEBUG_LEVEL 0 */ - -/* PIOS FreeRTOS support */ -#define PIOS_INCLUDE_FREERTOS - -/* PIOS bootloader helper */ -#define PIOS_INCLUDE_BL_HELPER -/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */ - -/* PIOS system functions */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_INITCALL -#define PIOS_INCLUDE_SYS - -/* PIOS hardware peripherals */ -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_RTC -#define PIOS_INCLUDE_TIM -#define PIOS_INCLUDE_USART -#define PIOS_INCLUDE_ADC -#define PIOS_INCLUDE_I2C -#define PIOS_INCLUDE_SPI -/* #define PIOS_INCLUDE_GPIO */ -#define PIOS_INCLUDE_EXTI -#define PIOS_INCLUDE_WDG - -/* PIOS USB functions */ -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -/* #define PIOS_INCLUDE_USB_CDC */ -/* #define PIOS_INCLUDE_USB_RCTX */ - -/* PIOS sensor interfaces */ -/* #define PIOS_INCLUDE_ADXL345 */ -/* #define PIOS_INCLUDE_BMA180 */ -/* #define PIOS_INCLUDE_L3GD20 */ -#define PIOS_INCLUDE_MPU6000 -#define PIOS_MPU6000_ACCEL -/* #define PIOS_INCLUDE_HMC5843 */ -#define PIOS_INCLUDE_HMC5883 -#define PIOS_HMC5883_HAS_GPIOS -/* #define PIOS_INCLUDE_BMP085 */ -#define PIOS_INCLUDE_MS5611 -#define PIOS_INCLUDE_MPXV -#define PIOS_INCLUDE_ETASV3 -/* #define PIOS_INCLUDE_HCSR04 */ - -/* PIOS receiver drivers */ -#define PIOS_INCLUDE_PWM -#define PIOS_INCLUDE_PPM -/* #define PIOS_INCLUDE_PPM_FLEXI */ -#define PIOS_INCLUDE_DSM -#define PIOS_INCLUDE_SBUS -#define PIOS_INCLUDE_GCSRCVR - -/* PIOS abstract receiver interface */ -#define PIOS_INCLUDE_RCVR - -/* PIOS common peripherals */ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_SERVO -/* #define PIOS_INCLUDE_I2C_ESC */ -/* #define PIOS_INCLUDE_OVERO */ -/* #define PIOS_OVERO_SPI */ -/* #define PIOS_INCLUDE_SDCARD */ -/* #define LOG_FILENAME "startup.log" */ -#define PIOS_INCLUDE_FLASH -#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS -#define FLASH_FREERTOS -/* #define PIOS_INCLUDE_FLASH_EEPROM */ - -/* PIOS radio modules */ -#define PIOS_INCLUDE_RFM22B -#define PIOS_INCLUDE_RFM22B_COM -#define PIOS_INCLUDE_RFM22B_RCVR -/* #define PIOS_INCLUDE_PPM_OUT */ -/* #define PIOS_RFM22B_DEBUG_ON_TELEM */ - -/* PIOS misc peripherals */ -/* #define PIOS_INCLUDE_VIDEO */ -/* #define PIOS_INCLUDE_WAVE */ -/* #define PIOS_INCLUDE_UDP */ - -/* PIOS abstract comms interface with options */ -#define PIOS_INCLUDE_COM -/* #define PIOS_INCLUDE_COM_MSG */ -/* #define PIOS_INCLUDE_TELEMETRY_RF */ -#define PIOS_INCLUDE_COM_TELEM -#define PIOS_INCLUDE_COM_FLEXI -/* #define PIOS_INCLUDE_COM_AUX */ -#define PIOS_TELEM_PRIORITY_QUEUE -#define PIOS_INCLUDE_GPS -/* #define PIOS_GPS_MINIMAL */ -#define PIOS_INCLUDE_GPS_NMEA_PARSER -#define PIOS_INCLUDE_GPS_UBX_PARSER -#define PIOS_GPS_SETS_HOMELOCATION - -/* Stabilization options */ -/* #define PIOS_QUATERNION_STABILIZATION */ - -/* Performance counters */ -#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 8379692 - -/* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 1000 -#define HEAP_LIMIT_CRITICAL 500 -#define IRQSTACK_LIMIT_WARNING 150 -#define IRQSTACK_LIMIT_CRITICAL 80 -#define CPULOAD_LIMIT_WARNING 80 -#define CPULOAD_LIMIT_CRITICAL 95 - -/* Task stack sizes */ -/* #define PIOS_ACTUATOR_STACK_SIZE 1020 */ -/* #define PIOS_MANUAL_STACK_SIZE 800 */ -/* #define PIOS_SYSTEM_STACK_SIZE 660 */ -/* #define PIOS_STABILIZATION_STACK_SIZE 524 */ -/* #define PIOS_TELEM_STACK_SIZE 500 */ -/* #define PIOS_EVENTDISPATCHER_STACK_SIZE 130 */ - -/* This can't be too high to stop eventdispatcher thread overflowing */ -#define PIOS_EVENTDISAPTCHER_QUEUE 10 - -/* Revolution series */ -#define REVOLUTION - -#endif /* PIOS_CONFIG_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013. + * @brief PiOS configuration header, the compile time config file for the PIOS. + * Defines which PiOS libraries and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* + * Below is a complete list of PIOS configurable options. + * Please do not remove or rearrange them. Only comment out + * unused options in the list. See main pios.h header for more + * details. + */ + +/* #define PIOS_INCLUDE_DEBUG_CONSOLE */ +/* #define DEBUG_LEVEL 0 */ + +/* PIOS FreeRTOS support */ +#define PIOS_INCLUDE_FREERTOS + +/* PIOS bootloader helper */ +#define PIOS_INCLUDE_BL_HELPER +/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */ + +/* PIOS system functions */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_INITCALL +#define PIOS_INCLUDE_SYS + +/* PIOS hardware peripherals */ +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_RTC +#define PIOS_INCLUDE_TIM +#define PIOS_INCLUDE_USART +#define PIOS_INCLUDE_ADC +#define PIOS_INCLUDE_I2C +#define PIOS_INCLUDE_SPI +/* #define PIOS_INCLUDE_GPIO */ +#define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_WDG + +/* PIOS USB functions */ +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +/* #define PIOS_INCLUDE_USB_CDC */ +/* #define PIOS_INCLUDE_USB_RCTX */ + +/* PIOS sensor interfaces */ +/* #define PIOS_INCLUDE_ADXL345 */ +/* #define PIOS_INCLUDE_BMA180 */ +/* #define PIOS_INCLUDE_L3GD20 */ +#define PIOS_INCLUDE_MPU6000 +#define PIOS_MPU6000_ACCEL +/* #define PIOS_INCLUDE_HMC5843 */ +#define PIOS_INCLUDE_HMC5883 +#define PIOS_HMC5883_HAS_GPIOS +/* #define PIOS_INCLUDE_BMP085 */ +#define PIOS_INCLUDE_MS5611 +#define PIOS_INCLUDE_MPXV +#define PIOS_INCLUDE_ETASV3 +/* #define PIOS_INCLUDE_HCSR04 */ + +/* PIOS receiver drivers */ +#define PIOS_INCLUDE_PWM +#define PIOS_INCLUDE_PPM +/* #define PIOS_INCLUDE_PPM_FLEXI */ +#define PIOS_INCLUDE_DSM +#define PIOS_INCLUDE_SBUS +#define PIOS_INCLUDE_GCSRCVR + +/* PIOS abstract receiver interface */ +#define PIOS_INCLUDE_RCVR + +/* PIOS common peripherals */ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_SERVO +/* #define PIOS_INCLUDE_I2C_ESC */ +/* #define PIOS_INCLUDE_OVERO */ +/* #define PIOS_OVERO_SPI */ +/* #define PIOS_INCLUDE_SDCARD */ +/* #define LOG_FILENAME "startup.log" */ +#define PIOS_INCLUDE_FLASH +#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS +#define FLASH_FREERTOS +/* #define PIOS_INCLUDE_FLASH_EEPROM */ + +/* PIOS radio modules */ +#define PIOS_INCLUDE_RFM22B +#define PIOS_INCLUDE_RFM22B_COM +#define PIOS_INCLUDE_RFM22B_RCVR +/* #define PIOS_INCLUDE_PPM_OUT */ +/* #define PIOS_RFM22B_DEBUG_ON_TELEM */ + +/* PIOS misc peripherals */ +/* #define PIOS_INCLUDE_VIDEO */ +/* #define PIOS_INCLUDE_WAVE */ +/* #define PIOS_INCLUDE_UDP */ + +/* PIOS abstract comms interface with options */ +#define PIOS_INCLUDE_COM +/* #define PIOS_INCLUDE_COM_MSG */ +/* #define PIOS_INCLUDE_TELEMETRY_RF */ +#define PIOS_INCLUDE_COM_TELEM +#define PIOS_INCLUDE_COM_FLEXI +/* #define PIOS_INCLUDE_COM_AUX */ +#define PIOS_TELEM_PRIORITY_QUEUE +#define PIOS_INCLUDE_GPS +/* #define PIOS_GPS_MINIMAL */ +#define PIOS_INCLUDE_GPS_NMEA_PARSER +#define PIOS_INCLUDE_GPS_UBX_PARSER +#define PIOS_GPS_SETS_HOMELOCATION + +/* Stabilization options */ +/* #define PIOS_QUATERNION_STABILIZATION */ + +/* Performance counters */ +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 8379692 + +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 1000 +#define HEAP_LIMIT_CRITICAL 500 +#define IRQSTACK_LIMIT_WARNING 150 +#define IRQSTACK_LIMIT_CRITICAL 80 +#define CPULOAD_LIMIT_WARNING 80 +#define CPULOAD_LIMIT_CRITICAL 95 + +/* Task stack sizes */ +/* #define PIOS_ACTUATOR_STACK_SIZE 1020 */ +/* #define PIOS_MANUAL_STACK_SIZE 800 */ +/* #define PIOS_SYSTEM_STACK_SIZE 660 */ +/* #define PIOS_STABILIZATION_STACK_SIZE 524 */ +/* #define PIOS_TELEM_STACK_SIZE 500 */ +/* #define PIOS_EVENTDISPATCHER_STACK_SIZE 130 */ + +/* This can't be too high to stop eventdispatcher thread overflowing */ +#define PIOS_EVENTDISAPTCHER_QUEUE 10 + +/* Revolution series */ +#define REVOLUTION + +#endif /* PIOS_CONFIG_H */ + +/** + * @} + * @} + */ diff --git a/flight/targets/RevoMini/System/inc/pios_config_sim.h b/flight/targets/RevoMini/System/inc/pios_config_sim.h index e7f7aed82..79dba8ef8 100644 --- a/flight/targets/RevoMini/System/inc/pios_config_sim.h +++ b/flight/targets/RevoMini/System/inc/pios_config_sim.h @@ -1,79 +1,79 @@ -/** - ****************************************************************************** - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * Central compile time config for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_CONFIG_POSIX_H -#define PIOS_CONFIG_POSIX_H - - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SDCARD -#define PIOS_INCLUDE_FREERTOS -#define PIOS_INCLUDE_COM -//#define PIOS_INCLUDE_GPS -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_TELEMETRY_RF -#define PIOS_INCLUDE_TCP -#define PIOS_INCLUDE_UDP -#define PIOS_INCLUDE_SERVO -#define PIOS_INCLUDE_RCVR -#define PIOS_INCLUDE_GCSRCVR - -#define PIOS_RCVR_MAX_CHANNELS 12 -#define PIOS_RCVR_MAX_DEVS 3 - -/* Defaults for Logging */ -#define LOG_FILENAME "PIOS.LOG" -#define STARTUP_LOG_ENABLED 1 - -/* COM Module */ -#define GPS_BAUDRATE 19200 -#define TELEM_BAUDRATE 19200 -#define AUXUART_ENABLED 0 -#define AUXUART_BAUDRATE 19200 - -#define TELEM_QUEUE_SIZE 20 -#define PIOS_TELEM_STACK_SIZE 2048 - -/* Stabilization options */ -#define PIOS_QUATERNION_STABILIZATION - -/* GPS options */ -#define PIOS_GPS_SETS_HOMELOCATION - -#define HEAP_LIMIT_WARNING 4000 -#define HEAP_LIMIT_CRITICAL 1000 -#define IRQSTACK_LIMIT_WARNING 150 -#define IRQSTACK_LIMIT_CRITICAL 80 -#define CPULOAD_LIMIT_WARNING 80 -#define CPULOAD_LIMIT_CRITICAL 95 - -#define REVOLUTION - -#endif /* PIOS_CONFIG_POSIX_H */ +/** + ****************************************************************************** + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_CONFIG_POSIX_H +#define PIOS_CONFIG_POSIX_H + + +/* Enable/Disable PiOS Modules */ +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_SDCARD +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_COM +//#define PIOS_INCLUDE_GPS +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_TELEMETRY_RF +#define PIOS_INCLUDE_TCP +#define PIOS_INCLUDE_UDP +#define PIOS_INCLUDE_SERVO +#define PIOS_INCLUDE_RCVR +#define PIOS_INCLUDE_GCSRCVR + +#define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_RCVR_MAX_DEVS 3 + +/* Defaults for Logging */ +#define LOG_FILENAME "PIOS.LOG" +#define STARTUP_LOG_ENABLED 1 + +/* COM Module */ +#define GPS_BAUDRATE 19200 +#define TELEM_BAUDRATE 19200 +#define AUXUART_ENABLED 0 +#define AUXUART_BAUDRATE 19200 + +#define TELEM_QUEUE_SIZE 20 +#define PIOS_TELEM_STACK_SIZE 2048 + +/* Stabilization options */ +#define PIOS_QUATERNION_STABILIZATION + +/* GPS options */ +#define PIOS_GPS_SETS_HOMELOCATION + +#define HEAP_LIMIT_WARNING 4000 +#define HEAP_LIMIT_CRITICAL 1000 +#define IRQSTACK_LIMIT_WARNING 150 +#define IRQSTACK_LIMIT_CRITICAL 80 +#define CPULOAD_LIMIT_WARNING 80 +#define CPULOAD_LIMIT_CRITICAL 95 + +#define REVOLUTION + +#endif /* PIOS_CONFIG_POSIX_H */ diff --git a/flight/targets/RevoMini/System/revolution.c b/flight/targets/RevoMini/System/revolution.c index ff2814fbd..7adcbf8d6 100644 --- a/flight/targets/RevoMini/System/revolution.c +++ b/flight/targets/RevoMini/System/revolution.c @@ -1,142 +1,142 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @brief These files are the core system files of OpenPilot. - * They are the ground layer just above PiOS. In practice, OpenPilot actually starts - * in the main() function of openpilot.c - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @brief This is where the OP firmware starts. Those files also define the compile-time - * options of the firmware. - * @{ - * @file openpilot.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sets up and runs main OpenPilot tasks. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* OpenPilot Includes */ -#include "openpilot.h" -#include "uavobjectsinit.h" -#include "systemmod.h" - -/* Task Priorities */ -#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) - -/* Global Variables */ - -/* Local Variables */ -#define INCLUDE_TEST_TASKS 0 -#if INCLUDE_TEST_TASKS -static uint8_t sdcard_available; -#endif -char Buffer[1024]; -uint32_t Cache; - -/* Function Prototypes */ -#if INCLUDE_TEST_TASKS -static void TaskTick(void *pvParameters); -static void TaskTesting(void *pvParameters); -static void TaskHIDTest(void *pvParameters); -static void TaskServos(void *pvParameters); -static void TaskSDCard(void *pvParameters); -#endif -int32_t CONSOLE_Parse(uint8_t port, char c); -void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value); - -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void Stack_Change(void); -static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change"))); - -/* Local Variables */ -#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority -#define INIT_TASK_STACK (1024 / 4) // XXX this seems excessive -static xTaskHandle initTaskHandle; - -/* Function Prototypes */ -static void initTask(void *parameters); - -/* Prototype of generated InitModules() function */ -extern void InitModules(void); - -/** -* OpenPilot Main function: -* -* Initialize PiOS
-* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
-* Start FreeRTOS Scheduler (vTaskStartScheduler)
-* If something goes wrong, blink LED1 and LED2 every 100ms -* -*/ -int main() -{ - int result; - - /* NOTE: Do NOT modify the following start-up sequence */ - /* Any new initialization functions should be added in OpenPilotInit() */ - vPortInitialiseBlocks(); - - /* Brings up System using CMSIS functions, enables the LEDs. */ - PIOS_SYS_Init(); - - /* For Revolution we use a FreeRTOS task to bring up the system so we can */ - /* always rely on FreeRTOS primitive */ - result = xTaskCreate(initTask, (const signed char *)"init", - INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY, - &initTaskHandle); - PIOS_Assert(result == pdPASS); - - /* Start the FreeRTOS scheduler */ - vTaskStartScheduler(); - - /* If all is well we will never reach here as the scheduler will now be running. */ - /* Do some PIOS_LED_HEARTBEAT to user that something bad just happened */ - PIOS_LED_Off(PIOS_LED_HEARTBEAT); \ - for(;;) { \ - PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ - PIOS_DELAY_WaitmS(100); \ - }; - - return 0; -} -/** - * Initialisation task. - * - * Runs board and module initialisation, then terminates. - */ -void -initTask(void *parameters) -{ - /* board driver init */ - PIOS_Board_Init(); - - /* Initialize modules */ - MODULE_INITIALISE_ALL; - - /* terminate this task */ - vTaskDelete(NULL); -} - -/** - * @} - * @} - */ - +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @brief These files are the core system files of OpenPilot. + * They are the ground layer just above PiOS. In practice, OpenPilot actually starts + * in the main() function of openpilot.c + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @brief This is where the OP firmware starts. Those files also define the compile-time + * options of the firmware. + * @{ + * @file openpilot.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Sets up and runs main OpenPilot tasks. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* OpenPilot Includes */ +#include "openpilot.h" +#include "uavobjectsinit.h" +#include "systemmod.h" + +/* Task Priorities */ +#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) + +/* Global Variables */ + +/* Local Variables */ +#define INCLUDE_TEST_TASKS 0 +#if INCLUDE_TEST_TASKS +static uint8_t sdcard_available; +#endif +char Buffer[1024]; +uint32_t Cache; + +/* Function Prototypes */ +#if INCLUDE_TEST_TASKS +static void TaskTick(void *pvParameters); +static void TaskTesting(void *pvParameters); +static void TaskHIDTest(void *pvParameters); +static void TaskServos(void *pvParameters); +static void TaskSDCard(void *pvParameters); +#endif +int32_t CONSOLE_Parse(uint8_t port, char c); +void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value); + +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void Stack_Change(void); +static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change"))); + +/* Local Variables */ +#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority +#define INIT_TASK_STACK (1024 / 4) // XXX this seems excessive +static xTaskHandle initTaskHandle; + +/* Function Prototypes */ +static void initTask(void *parameters); + +/* Prototype of generated InitModules() function */ +extern void InitModules(void); + +/** +* OpenPilot Main function: +* +* Initialize PiOS
+* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
+* Start FreeRTOS Scheduler (vTaskStartScheduler)
+* If something goes wrong, blink LED1 and LED2 every 100ms +* +*/ +int main() +{ + int result; + + /* NOTE: Do NOT modify the following start-up sequence */ + /* Any new initialization functions should be added in OpenPilotInit() */ + vPortInitialiseBlocks(); + + /* Brings up System using CMSIS functions, enables the LEDs. */ + PIOS_SYS_Init(); + + /* For Revolution we use a FreeRTOS task to bring up the system so we can */ + /* always rely on FreeRTOS primitive */ + result = xTaskCreate(initTask, (const signed char *)"init", + INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY, + &initTaskHandle); + PIOS_Assert(result == pdPASS); + + /* Start the FreeRTOS scheduler */ + vTaskStartScheduler(); + + /* If all is well we will never reach here as the scheduler will now be running. */ + /* Do some PIOS_LED_HEARTBEAT to user that something bad just happened */ + PIOS_LED_Off(PIOS_LED_HEARTBEAT); \ + for(;;) { \ + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ + PIOS_DELAY_WaitmS(100); \ + }; + + return 0; +} +/** + * Initialisation task. + * + * Runs board and module initialisation, then terminates. + */ +void +initTask(void *parameters) +{ + /* board driver init */ + PIOS_Board_Init(); + + /* Initialize modules */ + MODULE_INITIALISE_ALL; + + /* terminate this task */ + vTaskDelete(NULL); +} + +/** + * @} + * @} + */ + diff --git a/flight/targets/Revolution/Makefile.osx b/flight/targets/Revolution/Makefile.osx index 180b3b3df..cd1ed731c 100644 --- a/flight/targets/Revolution/Makefile.osx +++ b/flight/targets/Revolution/Makefile.osx @@ -1,655 +1,655 @@ - ##### - # Project: Revolution - # - # - # Makefile for OpenPilot project build PiOS and the AP. - # - # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. - # - # - # This program is free software; you can redistribute it and/or modify - # it under the terms of the GNU General Public License as published by - # the Free Software Foundation; either version 3 of the License, or - # (at your option) any later version. - # - # This program is distributed in the hope that it will be useful, but - # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - # for more details. - # - # You should have received a copy of the GNU General Public License along - # with this program; if not, write to the Free Software Foundation, Inc., - # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - ##### - -BOARD_NAME=revolution -ARM_SDK_PREFIX ?= -WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../) -include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk - - -# Set developer code and compile options -# Set to YES to compile for debugging -DEBUG ?= YES - -# Set to YES to use the Servo output pins for debugging via scope or logic analyser -ENABLE_DEBUG_PINS ?= NO - -# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs -ENABLE_AUX_UART ?= NO - -# -USE_BOOTLOADER ?= NO - - -# Set to YES when using Code Sourcery toolchain -CODE_SOURCERY ?= NO - -# Remove command is different for Code Sourcery on Windows -REMOVE_CMD ?= rm - -FLASH_TOOL = OPENOCD - -# YES enables -mthumb option to flags for source-files listed -# in SRC and CPPSRC -USE_THUMB_MODE = YES - -# List of modules to include -MODULES += Actuator ManualControl Stabilization -MODULES += AltitudeHold FixedWingPathFollower PathPlanner -#MODULES += VtolPathFollower ## OP-700: VtolPathFollower disabled because its currently unsafe - remove this line once Sambas code has been merged -MODULES += Attitude/revolution -MODULES += FirmwareIAP -#MODULES += OveroSync/simulated - -# To run simulation instead of connect to SITL -MODULES += Sensors/simulated - -MODULES += Telemetry - -BLONLY_CDEFS += -DBOARD_TYPE=$(BOARD_TYPE) -BLONLY_CDEFS += -DBOARD_REVISION=$(BOARD_REVISION) -BLONLY_CDEFS += -DHW_TYPE=$(HW_TYPE) -BLONLY_CDEFS += -DBOOTLOADER_VERSION=$(BOOTLOADER_VERSION) -BLONLY_CDEFS += -DFW_BANK_BASE=$(FW_BANK_BASE) -BLONLY_CDEFS += -DFW_BANK_SIZE=$(FW_BANK_SIZE) -BLONLY_CDEFS += -DFW_DESC_SIZE=$(FW_DESC_SIZE) - -# Since we are simulating all this firmware the code needs to know what the BL would -# normally contain -CFLAGS += $(BLONLY_CDEFS) - -# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) -OUTDIR = ../../build/sim_osx - -# Target file name (without extension). -TARGET = Revolution - -# Paths -OPSYSTEM = ./System -OPSYSTEMINC = $(OPSYSTEM)/inc -OPUAVTALK = ../UAVTalk -OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJ = ../UAVObjects -OPUAVOBJINC = $(OPUAVOBJ)/inc -OPTESTS = ./Tests -OPMODULEDIR = ../Modules -FLIGHTLIB = ../Libraries -FLIGHTLIBINC = $(FLIGHTLIB)/inc -MATHLIB = ../Libraries/math -MATHLIBINC = ../Libraries/math -PIOS = ../PiOS.osx -PIOSINC = $(PIOS)/inc -PIOSPOSIX = $(PIOS)/osx -APPLIBDIR = $(PIOSPOSIX)/Libraries -RTOSDIR = $(APPLIBDIR)/FreeRTOS -RTOSSRCDIR = $(RTOSDIR)/Source -RTOSINCDIR = $(RTOSSRCDIR)/include -DOXYGENDIR = ../Doc/Doxygen -PYMITE = $(FLIGHTLIB)/PyMite -PYMITELIB = $(PYMITE)/lib -PYMITEPLAT = $(PYMITE)/platform/openpilot_sitl -PYMITETOOLS = $(PYMITE)/tools -PYMITEVM = $(PYMITE)/vm -PYMITEINC = $(PYMITEVM) -PYMITEINC += $(PYMITEPLAT) -PYMITEINC += $(OUTDIR) -FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib -FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans - -UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight -UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python - -# List C source files here. (C dependencies are automatically generated.) -# use file-extension c for "c-only"-files - -MODNAMES = $(notdir ${MODULES}) - -## PyMite files -SRC += $(OUTDIR)/pmlib_img.c -SRC += $(OUTDIR)/pmlib_nat.c -SRC += $(OUTDIR)/pmlibusr_img.c -SRC += $(OUTDIR)/pmlibusr_nat.c -SRC += $(wildcard ${PYMITEVM}/*.c) -SRC += $(wildcard ${PYMITEPLAT}/*.c) - -## MODULES -SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} -SRC += ${OUTDIR}/InitMods.c -## OPENPILOT CORE: -SRC += ${OPMODULEDIR}/System/systemmod.c -SRC += $(OPSYSTEM)/revolution.c -SRC += $(OPSYSTEM)/pios_board_sim.c -SRC += $(OPSYSTEM)/alarms.c -SRC += $(OPUAVTALK)/uavtalk.c -SRC += $(OPUAVOBJ)/uavobjectmanager.c -SRC += $(OPUAVOBJ)/eventdispatcher.c -SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c - - - -include $(WHEREAMI)/UAVObjects.inc - -UAVOBJSRCFILENAMES += attitudesimulated -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) - -SRC += $(UAVOBJSRC) -CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) - -## PIOS Hardware (posix) -SRC += $(PIOSPOSIX)/pios_crc.c -SRC += $(PIOSPOSIX)/pios_sys.c -SRC += $(PIOSPOSIX)/pios_led.c -SRC += $(PIOSPOSIX)/pios_irq.c -SRC += $(PIOSPOSIX)/pios_delay.c -SRC += $(PIOSPOSIX)/pios_sdcard.c -SRC += $(PIOSPOSIX)/pios_udp.c -SRC += $(PIOSPOSIX)/pios_tcp.c -SRC += $(PIOSPOSIX)/pios_com.c -SRC += $(PIOSPOSIX)/pios_servo.c -SRC += $(PIOSPOSIX)/pios_wdg.c -SRC += $(PIOSPOSIX)/pios_debug.c -SRC += $(PIOSPOSIX)/pios_bl_helper.c -SRC += $(PIOSPOSIX)/pios_iap.c -SRC += $(PIOSPOSIX)/pios_board_info.c - -SRC += $(PIOSPOSIX)/pios_rcvr.c -SRC += $(PIOSPOSIX)/pios_gcsrcvr.c - -## Libraries for flight calculations -SRC += $(FLIGHTLIB)/fifo_buffer.c -SRC += $(FLIGHTLIB)/WorldMagModel.c -SRC += $(FLIGHTLIB)/CoordinateConversions.c -SRC += $(FLIGHTLIB)/paths.c -SRC += $(FLIGHTLIB)/insgps13state.c -SRC += $(FLIGHTLIB)/taskmonitor.c -SRC += $(MATHLIB)/pid.c -SRC += $(MATHLIB)/sin_lookup.c - - -## RTOS and RTOS Portable -SRC += $(RTOSSRCDIR)/list.c -SRC += $(RTOSSRCDIR)/queue.c -UNAME := $(shell uname) -SRC += $(RTOSSRCDIR)/task.c -SRC += $(RTOSSRCDIR)/timers.c -SRC += $(RTOSSRCDIR)/portable/GCC/Posix/port.c -SRC += $(RTOSSRCDIR)/portable/MemMang/heap_3.c - - - -# List C source files here which must be compiled in ARM-Mode (no -mthumb). -# use file-extension c for "c-only"-files -## just for testing, timer.c could be compiled in thumb-mode too -SRCARM = - -# List C++ source files here. -# use file-extension .cpp for C++-files (not .C) -CPPSRC = - -# List C++ source files here which must be compiled in ARM-Mode. -# use file-extension .cpp for C++-files (not .C) -#CPPSRCARM = $(TARGET).cpp -CPPSRCARM = - - -# List any extra directories to look for include files here. -# Each directory must be seperated by a space. -EXTRAINCDIRS = $(OPSYSTEM) -EXTRAINCDIRS += $(OPSYSTEMINC) -EXTRAINCDIRS += $(OPUAVTALK) -EXTRAINCDIRS += $(OPUAVTALKINC) -EXTRAINCDIRS += $(OPUAVOBJ) -EXTRAINCDIRS += $(OPUAVOBJINC) -EXTRAINCDIRS += $(UAVOBJSYNTHDIR) -EXTRAINCDIRS += $(PIOS) -EXTRAINCDIRS += $(PIOSINC) -EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(MATHLIBINC) -EXTRAINCDIRS += $(FLIGTH) -EXTRAINCDIRS += $(PIOSPOSIX) -EXTRAINCDIRS += $(RTOSINCDIR) -EXTRAINCDIRS += $(APPLIBDIR) -EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Posix -EXTRAINCDIRS += $(PYMITEINC) - -EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc - - -# List any extra directories to look for library files here. -# Also add directories where the linker should search for -# includes from linker-script to the list -# Each directory must be seperated by a space. -EXTRA_LIBDIRS = - -# Extra Libraries -# Each library-name must be seperated by a space. -# i.e. to link with libxyz.a, libabc.a and libefsl.a: -# EXTRA_LIBS = xyz abc efsl -# for newlib-lpc (file: libnewlibc-lpc.a): -# EXTRA_LIBS = newlib-lpc -EXTRA_LIBS = - -# Path to Linker-Scripts -LINKERSCRIPTPATH = $(PIOSSTM32F10X) - -# Optimization level, can be [0, 1, 2, 3, s]. -# 0 = turn off optimization. s = optimize for size. -# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) - -ifeq ($(DEBUG),YES) -OPT = 0 -else -OPT = s -endif - -# Output format. (can be ihex or binary or both) -# binary to create a load-image in raw-binary format i.e. for SAM-BA, -# ihex to create a load-image in Intel hex format -#LOADFORMAT = ihex -#LOADFORMAT = binary -LOADFORMAT = both - -# Debugging format. -#DEBUGF = dwarf-2 - -# Place project-specific -D (define) and/or -# -U options for C here. -ifeq ($(ENABLE_DEBUG_PINS), YES) -CDEFS += -DPIOS_ENABLE_DEBUG_PINS -endif -ifeq ($(ENABLE_AUX_UART), YES) -CDEFS += -DPIOS_ENABLE_AUX_UART -endif -ifeq ($(USE_BOOTLOADER), YES) -CDEFS += -DUSE_BOOTLOADER -endif - -# Compiler flag to set the C Standard level. -# c89 - "ANSI" C -# gnu89 - c89 plus GCC extensions -# c99 - ISO C99 standard (not yet fully implemented) -# gnu99 - c99 plus GCC extensions -CSTANDARD = -std=gnu99 - -#----- - -# Compiler flags. - -# -g*: generate debugging information -# -O*: optimization level -# -f...: tuning, see GCC manual and avr-libc documentation -# -Wall...: warning level -# -Wa,...: tell GCC to pass this to the assembler. -# -adhlns...: create assembler listing -# -# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) - -ifeq ($(DEBUG),YES) -CFLAGS += -g$(DEBUGF) -DDEBUG -endif - -CFLAGS += -DDIAG_TASKS - -CFLAGS += $(CFLAGS_UAVOBJECTS) -CFLAGS += -DARCH_POSIX -CFLAGS += -O$(OPT) -CFLAGS += $(CDEFS) -CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. - -#CFLAGS += ARCH=arm -#CROSS_COMPILE=/usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- - -CFLAGS += -fomit-frame-pointer -ifeq ($(CODE_SOURCERY), YES) -CFLAGS += -fpromote-loop-indices -endif - -CFLAGS += -Wall -CFLAGS += -Werror -# Compiler flags to generate dependency files: -CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d - -# flags only for C -#CONLYFLAGS += -Wnested-externs -CONLYFLAGS += $(CSTANDARD) - -# Assembler flags. -# -Wa,...: tell GCC to pass this to the assembler. -# -ahlns: create listing -ASFLAGS = -mtune=$(MCU) -I. -x assembler-with-cpp -ASFLAGS += $(ADEFS) -ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) -ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) - -MATH_LIB = -lm - -# Linker flags. -# -Wl,...: tell GCC to pass this to linker. -# -Map: create map file -# --cref: add cross reference to map file -LDFLAGS += -lpthread -LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) -LDFLAGS += -lc -LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) -LDFLAGS += $(MATH_LIB) -LDFLAGS += -lc -lgcc - -# To include simulation model -LDFLAGS += -L$(OUTDIR) -#LDFLAGS += -lsimmodel - - -# Define programs and commands. -CC = $(ARM_SDK_PREFIX)gcc -CPP = $(ARM_SDK_PREFIX)g++ -AR = $(ARM_SDK_PREFIX)ar -OBJCOPY = $(ARM_SDK_PREFIX)objcopy -OBJDUMP = $(ARM_SDK_PREFIX)objdump -SIZE = $(ARM_SDK_PREFIX)size -NM = $(ARM_SDK_PREFIX)nm -REMOVE = $(RM) -f - - - -# Define Messages -# English -MSG_ERRORS_NONE = Errors: none -MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote} -MSG_END = ${quote}-------- end --------${quote} -MSG_MODINIT = ${quote}**** Generating ModInit.c${quote} -MSG_SIZE_BEFORE = ${quote}Size before:${quote} -MSG_SIZE_AFTER = ${quote}Size after build:${quote} -MSG_LOAD_FILE = ${quote}Creating load file:${quote} -MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote} -MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote} -MSG_LINKING = ${quote}**** Linking :${quote} -MSG_COMPILING = ${quote}**** Compiling C :${quote} -MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote} -MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote} -MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote} -MSG_ASSEMBLING = ${quote}**** Assembling:${quote} -MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote} -MSG_CLEANING = ${quote}Cleaning project:${quote} -MSG_FORMATERROR = ${quote}Can not handle output-format${quote} -MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote} -MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote} -MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote} - -$(OUTDIR)/sim_osx_firmwareinfo.c: $(TOP)/make/templates/firmwareinfotemplate_sim.c - $(V1) python $(TOP)/make/scripts/version-info.py \ - --path=$(TOP) \ - --template=$(TOP)/make/templates/firmwareinfotemplate_sim.c \ - --outfile=$(TOP)/build/sim_osx/sim_osx_firmwareinfo.c \ - --image=$(TOP)/build/fw_revolution/fw_revolution.elf \ - --type=9 \ - --revision=1 \ - --uavodir=$(TOP)/shared/uavobjectdefinition - -# List of all source files. -ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) $(OUTDIR)/sim_osx_firmwareinfo.c -# List of all source files without directory and file-extension. -ALLSRCBASE = $(notdir $(basename $(ALLSRC))) - -# Define all object files. -ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) - -# Define all listing files (used for make clean). -LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) -# Define all depedency-files (used for make clean). -DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) - -elf: $(OUTDIR)/$(TARGET).elf -lss: $(OUTDIR)/$(TARGET).lss -sym: $(OUTDIR)/$(TARGET).sym -hex: $(OUTDIR)/$(TARGET).hex -bin: $(OUTDIR)/$(TARGET).bin - -# Default target. -#all: begin gccversion sizebefore build sizeafter finished end -#all: begin gencode gccversion build sizeafter finished end -all: elf - -ifeq ($(LOADFORMAT),ihex) -build: elf hex lss sym -else -ifeq ($(LOADFORMAT),binary) -build: elf bin lss sym -else -ifeq ($(LOADFORMAT),both) -build: elf hex bin lss sym -else -$(error "$(MSG_FORMATERROR) $(FORMAT)") -endif -endif -endif - -# Generate intermediate code -gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h - -getmodname = $(firstword $(subst /, ,$1)) - -MOD_GEN := $(foreach MOD,$(MODULES),$(call getmodname,$(MOD))) - -# Generate code for module initialization -${OUTDIR}/InitMods.c: Makefile.osx - echo ${MOD_GEN} - @echo ${MSG_MODINIT} - @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Start(void);}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c - @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c - -# Generate code for PyMite -${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) - @echo ${MSG_PYMITEINIT} - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) - @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py - -# Eye candy. -begin: -## @echo - @echo $(MSG_BEGIN) - -finished: -## @echo $(MSG_ERRORS_NONE) - -end: - @echo $(MSG_END) -## @echo - -# Display sizes of sections. -ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf -##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf -sizebefore: -# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi - -sizeafter: -# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi - @echo $(MSG_SIZE_AFTER) - $(ELFSIZE) - -# Display compiler version information. -gccversion : - @$(CC) --version -# @echo $(ALLOBJ) - -# Create final output file (.hex) from ELF output file. -%.hex: %.elf -## @echo - @echo $(MSG_LOAD_FILE) $@ - $(OBJCOPY) -O ihex $< $@ - -# Create final output file (.bin) from ELF output file. -%.bin: %.elf -## @echo - @echo $(MSG_LOAD_FILE) $@ - $(OBJCOPY) -O binary $< $@ - -# Create extended listing file/disassambly from ELF output file. -# using objdump testing: option -C -%.lss: %.elf -## @echo - @echo $(MSG_EXTENDED_LISTING) $@ - $(OBJDUMP) -h -S -C -r $< > $@ -# $(OBJDUMP) -x -S $< > $@ - -# Create a symbol table from ELF output file. -%.sym: %.elf -## @echo - @echo $(MSG_SYMBOL_TABLE) $@ - $(NM) -n $< > $@ - -# Link: create ELF output file from object files. -.SECONDARY : $(TARGET).elf -.PRECIOUS : $(ALLOBJ) -%.elf: $(ALLOBJ) - @echo $(MSG_LINKING) $@ -# use $(CC) for C-only projects or $(CPP) for C++-projects: - $(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) -# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) - - -# Assemble: create object files from assembler source files. -define ASSEMBLE_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_ASSEMBLING) $$< to $$@ - $(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@ -endef -$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) - -# Assemble: create object files from assembler source files. ARM-only -define ASSEMBLE_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_ASSEMBLING_ARM) $$< to $$@ - $(CC) -c $$(ASFLAGS) $$< -o $$@ -endef -$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) - - -# Compile: create object files from C source files. -define COMPILE_C_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILING) $$< to $$@ - $(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ -endef -$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) - -# Compile: create object files from C source files. ARM-only -define COMPILE_C_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILING_ARM) $$< to $$@ - $(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ -endef -$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) - - -# Compile: create object files from C++ source files. -define COMPILE_CPP_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILINGCPP) $$< to $$@ - $(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ -endef -$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) - -# Compile: create object files from C++ source files. ARM-only -define COMPILE_CPP_ARM_TEMPLATE -$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) -## @echo - @echo $(MSG_COMPILINGCPP_ARM) $$< to $$@ - $(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ -endef -$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) - - -# Compile: create assembler files from C source files. ARM/Thumb -$(SRC:.c=.s) : %.s : %.c - @echo $(MSG_ASMFROMC) $< to $@ - $(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ - -# Compile: create assembler files from C source files. ARM only -$(SRCARM:.c=.s) : %.s : %.c - @echo $(MSG_ASMFROMC_ARM) $< to $@ - $(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ - -# Generate Doxygen documents -docs: - doxygen $(DOXYGENDIR)/doxygen.cfg - -# Target: clean project. -clean: begin clean_list finished end - -clean_list : -## @echo - @echo $(MSG_CLEANING) - $(REMOVE) $(OUTDIR)/$(TARGET).map - $(REMOVE) $(OUTDIR)/$(TARGET).elf - $(REMOVE) $(OUTDIR)/$(TARGET).hex - $(REMOVE) $(OUTDIR)/$(TARGET).bin - $(REMOVE) $(OUTDIR)/$(TARGET).sym - $(REMOVE) $(OUTDIR)/$(TARGET).lss - $(REMOVE) $(wildcard $(OUTDIR)/*.c) - $(REMOVE) $(wildcard $(OUTDIR)/*.h) - $(REMOVE) $(ALLOBJ) - $(REMOVE) $(LSTFILES) - $(REMOVE) $(DEPFILES) - $(REMOVE) $(SRC:.c=.s) - $(REMOVE) $(SRCARM:.c=.s) - $(REMOVE) $(CPPSRC:.cpp=.s) - $(REMOVE) $(CPPSRCARM:.cpp=.s) - - -# Create output files directory -# all known MS Windows OS define the ComSpec environment variable -ifdef ComSpec -$(shell md $(OUTDIR) 2>NUL) -else -$(shell mkdir $(OUTDIR) 2>/dev/null) -endif - -# Include the dependency files. -ifdef ComSpec --include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) -else --include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) -endif - - - -# Listing of phony targets. -.PHONY : all begin finish end sizebefore sizeafter gccversion \ -build elf hex bin lss sym clean clean_list program gencode - + ##### + # Project: Revolution + # + # + # Makefile for OpenPilot project build PiOS and the AP. + # + # The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. + # + # + # This program is free software; you can redistribute it and/or modify + # it under the terms of the GNU General Public License as published by + # the Free Software Foundation; either version 3 of the License, or + # (at your option) any later version. + # + # This program is distributed in the hope that it will be useful, but + # WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + # or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + # for more details. + # + # You should have received a copy of the GNU General Public License along + # with this program; if not, write to the Free Software Foundation, Inc., + # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + ##### + +BOARD_NAME=revolution +ARM_SDK_PREFIX ?= +WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) +TOP := $(realpath $(WHEREAMI)/../../) +include $(TOP)/make/boards/$(BOARD_NAME)/board-info.mk + + +# Set developer code and compile options +# Set to YES to compile for debugging +DEBUG ?= YES + +# Set to YES to use the Servo output pins for debugging via scope or logic analyser +ENABLE_DEBUG_PINS ?= NO + +# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs +ENABLE_AUX_UART ?= NO + +# +USE_BOOTLOADER ?= NO + + +# Set to YES when using Code Sourcery toolchain +CODE_SOURCERY ?= NO + +# Remove command is different for Code Sourcery on Windows +REMOVE_CMD ?= rm + +FLASH_TOOL = OPENOCD + +# YES enables -mthumb option to flags for source-files listed +# in SRC and CPPSRC +USE_THUMB_MODE = YES + +# List of modules to include +MODULES += Actuator ManualControl Stabilization +MODULES += AltitudeHold FixedWingPathFollower PathPlanner +#MODULES += VtolPathFollower ## OP-700: VtolPathFollower disabled because its currently unsafe - remove this line once Sambas code has been merged +MODULES += Attitude/revolution +MODULES += FirmwareIAP +#MODULES += OveroSync/simulated + +# To run simulation instead of connect to SITL +MODULES += Sensors/simulated + +MODULES += Telemetry + +BLONLY_CDEFS += -DBOARD_TYPE=$(BOARD_TYPE) +BLONLY_CDEFS += -DBOARD_REVISION=$(BOARD_REVISION) +BLONLY_CDEFS += -DHW_TYPE=$(HW_TYPE) +BLONLY_CDEFS += -DBOOTLOADER_VERSION=$(BOOTLOADER_VERSION) +BLONLY_CDEFS += -DFW_BANK_BASE=$(FW_BANK_BASE) +BLONLY_CDEFS += -DFW_BANK_SIZE=$(FW_BANK_SIZE) +BLONLY_CDEFS += -DFW_DESC_SIZE=$(FW_DESC_SIZE) + +# Since we are simulating all this firmware the code needs to know what the BL would +# normally contain +CFLAGS += $(BLONLY_CDEFS) + +# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.) +OUTDIR = ../../build/sim_osx + +# Target file name (without extension). +TARGET = Revolution + +# Paths +OPSYSTEM = ./System +OPSYSTEMINC = $(OPSYSTEM)/inc +OPUAVTALK = ../UAVTalk +OPUAVTALKINC = $(OPUAVTALK)/inc +OPUAVOBJ = ../UAVObjects +OPUAVOBJINC = $(OPUAVOBJ)/inc +OPTESTS = ./Tests +OPMODULEDIR = ../Modules +FLIGHTLIB = ../Libraries +FLIGHTLIBINC = $(FLIGHTLIB)/inc +MATHLIB = ../Libraries/math +MATHLIBINC = ../Libraries/math +PIOS = ../PiOS.osx +PIOSINC = $(PIOS)/inc +PIOSPOSIX = $(PIOS)/osx +APPLIBDIR = $(PIOSPOSIX)/Libraries +RTOSDIR = $(APPLIBDIR)/FreeRTOS +RTOSSRCDIR = $(RTOSDIR)/Source +RTOSINCDIR = $(RTOSSRCDIR)/include +DOXYGENDIR = ../Doc/Doxygen +PYMITE = $(FLIGHTLIB)/PyMite +PYMITELIB = $(PYMITE)/lib +PYMITEPLAT = $(PYMITE)/platform/openpilot_sitl +PYMITETOOLS = $(PYMITE)/tools +PYMITEVM = $(PYMITE)/vm +PYMITEINC = $(PYMITEVM) +PYMITEINC += $(PYMITEPLAT) +PYMITEINC += $(OUTDIR) +FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib +FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans + +UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight +UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python + +# List C source files here. (C dependencies are automatically generated.) +# use file-extension c for "c-only"-files + +MODNAMES = $(notdir ${MODULES}) + +## PyMite files +SRC += $(OUTDIR)/pmlib_img.c +SRC += $(OUTDIR)/pmlib_nat.c +SRC += $(OUTDIR)/pmlibusr_img.c +SRC += $(OUTDIR)/pmlibusr_nat.c +SRC += $(wildcard ${PYMITEVM}/*.c) +SRC += $(wildcard ${PYMITEPLAT}/*.c) + +## MODULES +SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += ${OUTDIR}/InitMods.c +## OPENPILOT CORE: +SRC += ${OPMODULEDIR}/System/systemmod.c +SRC += $(OPSYSTEM)/revolution.c +SRC += $(OPSYSTEM)/pios_board_sim.c +SRC += $(OPSYSTEM)/alarms.c +SRC += $(OPUAVTALK)/uavtalk.c +SRC += $(OPUAVOBJ)/uavobjectmanager.c +SRC += $(OPUAVOBJ)/eventdispatcher.c +SRC += $(UAVOBJSYNTHDIR)/uavobjectsinit.c + + + +include $(WHEREAMI)/UAVObjects.inc + +UAVOBJSRCFILENAMES += attitudesimulated +UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) +UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) + +SRC += $(UAVOBJSRC) +CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) + +## PIOS Hardware (posix) +SRC += $(PIOSPOSIX)/pios_crc.c +SRC += $(PIOSPOSIX)/pios_sys.c +SRC += $(PIOSPOSIX)/pios_led.c +SRC += $(PIOSPOSIX)/pios_irq.c +SRC += $(PIOSPOSIX)/pios_delay.c +SRC += $(PIOSPOSIX)/pios_sdcard.c +SRC += $(PIOSPOSIX)/pios_udp.c +SRC += $(PIOSPOSIX)/pios_tcp.c +SRC += $(PIOSPOSIX)/pios_com.c +SRC += $(PIOSPOSIX)/pios_servo.c +SRC += $(PIOSPOSIX)/pios_wdg.c +SRC += $(PIOSPOSIX)/pios_debug.c +SRC += $(PIOSPOSIX)/pios_bl_helper.c +SRC += $(PIOSPOSIX)/pios_iap.c +SRC += $(PIOSPOSIX)/pios_board_info.c + +SRC += $(PIOSPOSIX)/pios_rcvr.c +SRC += $(PIOSPOSIX)/pios_gcsrcvr.c + +## Libraries for flight calculations +SRC += $(FLIGHTLIB)/fifo_buffer.c +SRC += $(FLIGHTLIB)/WorldMagModel.c +SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += $(FLIGHTLIB)/paths.c +SRC += $(FLIGHTLIB)/insgps13state.c +SRC += $(FLIGHTLIB)/taskmonitor.c +SRC += $(MATHLIB)/pid.c +SRC += $(MATHLIB)/sin_lookup.c + + +## RTOS and RTOS Portable +SRC += $(RTOSSRCDIR)/list.c +SRC += $(RTOSSRCDIR)/queue.c +UNAME := $(shell uname) +SRC += $(RTOSSRCDIR)/task.c +SRC += $(RTOSSRCDIR)/timers.c +SRC += $(RTOSSRCDIR)/portable/GCC/Posix/port.c +SRC += $(RTOSSRCDIR)/portable/MemMang/heap_3.c + + + +# List C source files here which must be compiled in ARM-Mode (no -mthumb). +# use file-extension c for "c-only"-files +## just for testing, timer.c could be compiled in thumb-mode too +SRCARM = + +# List C++ source files here. +# use file-extension .cpp for C++-files (not .C) +CPPSRC = + +# List C++ source files here which must be compiled in ARM-Mode. +# use file-extension .cpp for C++-files (not .C) +#CPPSRCARM = $(TARGET).cpp +CPPSRCARM = + + +# List any extra directories to look for include files here. +# Each directory must be seperated by a space. +EXTRAINCDIRS = $(OPSYSTEM) +EXTRAINCDIRS += $(OPSYSTEMINC) +EXTRAINCDIRS += $(OPUAVTALK) +EXTRAINCDIRS += $(OPUAVTALKINC) +EXTRAINCDIRS += $(OPUAVOBJ) +EXTRAINCDIRS += $(OPUAVOBJINC) +EXTRAINCDIRS += $(UAVOBJSYNTHDIR) +EXTRAINCDIRS += $(PIOS) +EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(MATHLIBINC) +EXTRAINCDIRS += $(FLIGTH) +EXTRAINCDIRS += $(PIOSPOSIX) +EXTRAINCDIRS += $(RTOSINCDIR) +EXTRAINCDIRS += $(APPLIBDIR) +EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Posix +EXTRAINCDIRS += $(PYMITEINC) + +EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc + + +# List any extra directories to look for library files here. +# Also add directories where the linker should search for +# includes from linker-script to the list +# Each directory must be seperated by a space. +EXTRA_LIBDIRS = + +# Extra Libraries +# Each library-name must be seperated by a space. +# i.e. to link with libxyz.a, libabc.a and libefsl.a: +# EXTRA_LIBS = xyz abc efsl +# for newlib-lpc (file: libnewlibc-lpc.a): +# EXTRA_LIBS = newlib-lpc +EXTRA_LIBS = + +# Path to Linker-Scripts +LINKERSCRIPTPATH = $(PIOSSTM32F10X) + +# Optimization level, can be [0, 1, 2, 3, s]. +# 0 = turn off optimization. s = optimize for size. +# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) + +ifeq ($(DEBUG),YES) +OPT = 0 +else +OPT = s +endif + +# Output format. (can be ihex or binary or both) +# binary to create a load-image in raw-binary format i.e. for SAM-BA, +# ihex to create a load-image in Intel hex format +#LOADFORMAT = ihex +#LOADFORMAT = binary +LOADFORMAT = both + +# Debugging format. +#DEBUGF = dwarf-2 + +# Place project-specific -D (define) and/or +# -U options for C here. +ifeq ($(ENABLE_DEBUG_PINS), YES) +CDEFS += -DPIOS_ENABLE_DEBUG_PINS +endif +ifeq ($(ENABLE_AUX_UART), YES) +CDEFS += -DPIOS_ENABLE_AUX_UART +endif +ifeq ($(USE_BOOTLOADER), YES) +CDEFS += -DUSE_BOOTLOADER +endif + +# Compiler flag to set the C Standard level. +# c89 - "ANSI" C +# gnu89 - c89 plus GCC extensions +# c99 - ISO C99 standard (not yet fully implemented) +# gnu99 - c99 plus GCC extensions +CSTANDARD = -std=gnu99 + +#----- + +# Compiler flags. + +# -g*: generate debugging information +# -O*: optimization level +# -f...: tuning, see GCC manual and avr-libc documentation +# -Wall...: warning level +# -Wa,...: tell GCC to pass this to the assembler. +# -adhlns...: create assembler listing +# +# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) + +ifeq ($(DEBUG),YES) +CFLAGS += -g$(DEBUGF) -DDEBUG +endif + +CFLAGS += -DDIAG_TASKS + +CFLAGS += $(CFLAGS_UAVOBJECTS) +CFLAGS += -DARCH_POSIX +CFLAGS += -O$(OPT) +CFLAGS += $(CDEFS) +CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. + +#CFLAGS += ARCH=arm +#CROSS_COMPILE=/usr/local/android-ndk-r5/toolchains/arm-linux-androideabi-4.4.3/prebuilt/darwin-x86/bin/arm-linux-androideabi- + +CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) +CFLAGS += -fpromote-loop-indices +endif + +CFLAGS += -Wall +CFLAGS += -Werror +# Compiler flags to generate dependency files: +CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d + +# flags only for C +#CONLYFLAGS += -Wnested-externs +CONLYFLAGS += $(CSTANDARD) + +# Assembler flags. +# -Wa,...: tell GCC to pass this to the assembler. +# -ahlns: create listing +ASFLAGS = -mtune=$(MCU) -I. -x assembler-with-cpp +ASFLAGS += $(ADEFS) +ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) + +MATH_LIB = -lm + +# Linker flags. +# -Wl,...: tell GCC to pass this to linker. +# -Map: create map file +# --cref: add cross reference to map file +LDFLAGS += -lpthread +LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) +LDFLAGS += -lc +LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) +LDFLAGS += $(MATH_LIB) +LDFLAGS += -lc -lgcc + +# To include simulation model +LDFLAGS += -L$(OUTDIR) +#LDFLAGS += -lsimmodel + + +# Define programs and commands. +CC = $(ARM_SDK_PREFIX)gcc +CPP = $(ARM_SDK_PREFIX)g++ +AR = $(ARM_SDK_PREFIX)ar +OBJCOPY = $(ARM_SDK_PREFIX)objcopy +OBJDUMP = $(ARM_SDK_PREFIX)objdump +SIZE = $(ARM_SDK_PREFIX)size +NM = $(ARM_SDK_PREFIX)nm +REMOVE = $(RM) -f + + + +# Define Messages +# English +MSG_ERRORS_NONE = Errors: none +MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote} +MSG_END = ${quote}-------- end --------${quote} +MSG_MODINIT = ${quote}**** Generating ModInit.c${quote} +MSG_SIZE_BEFORE = ${quote}Size before:${quote} +MSG_SIZE_AFTER = ${quote}Size after build:${quote} +MSG_LOAD_FILE = ${quote}Creating load file:${quote} +MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote} +MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote} +MSG_LINKING = ${quote}**** Linking :${quote} +MSG_COMPILING = ${quote}**** Compiling C :${quote} +MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote} +MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote} +MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote} +MSG_ASSEMBLING = ${quote}**** Assembling:${quote} +MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote} +MSG_CLEANING = ${quote}Cleaning project:${quote} +MSG_FORMATERROR = ${quote}Can not handle output-format${quote} +MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote} +MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote} +MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote} + +$(OUTDIR)/sim_osx_firmwareinfo.c: $(TOP)/make/templates/firmwareinfotemplate_sim.c + $(V1) python $(TOP)/make/scripts/version-info.py \ + --path=$(TOP) \ + --template=$(TOP)/make/templates/firmwareinfotemplate_sim.c \ + --outfile=$(TOP)/build/sim_osx/sim_osx_firmwareinfo.c \ + --image=$(TOP)/build/fw_revolution/fw_revolution.elf \ + --type=9 \ + --revision=1 \ + --uavodir=$(TOP)/shared/uavobjectdefinition + +# List of all source files. +ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) $(OUTDIR)/sim_osx_firmwareinfo.c +# List of all source files without directory and file-extension. +ALLSRCBASE = $(notdir $(basename $(ALLSRC))) + +# Define all object files. +ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) + +# Define all listing files (used for make clean). +LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) +# Define all depedency-files (used for make clean). +DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) + +elf: $(OUTDIR)/$(TARGET).elf +lss: $(OUTDIR)/$(TARGET).lss +sym: $(OUTDIR)/$(TARGET).sym +hex: $(OUTDIR)/$(TARGET).hex +bin: $(OUTDIR)/$(TARGET).bin + +# Default target. +#all: begin gccversion sizebefore build sizeafter finished end +#all: begin gencode gccversion build sizeafter finished end +all: elf + +ifeq ($(LOADFORMAT),ihex) +build: elf hex lss sym +else +ifeq ($(LOADFORMAT),binary) +build: elf bin lss sym +else +ifeq ($(LOADFORMAT),both) +build: elf hex bin lss sym +else +$(error "$(MSG_FORMATERROR) $(FORMAT)") +endif +endif +endif + +# Generate intermediate code +gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h + +getmodname = $(firstword $(subst /, ,$1)) + +MOD_GEN := $(foreach MOD,$(MODULES),$(call getmodname,$(MOD))) + +# Generate code for module initialization +${OUTDIR}/InitMods.c: Makefile.osx + echo ${MOD_GEN} + @echo ${MSG_MODINIT} + @echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, extern unsigned int ${MOD}Start(void);}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c + @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c + +# Generate code for PyMite +${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h: $(wildcard ${PYMITELIB}/*.py) $(wildcard ${PYMITEPLAT}/*.py) $(wildcard ${FLIGHTPLANLIB}/*.py) $(wildcard ${FLIGHTPLANS}/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) + @echo ${MSG_PYMITEINIT} + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) + @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py + +# Eye candy. +begin: +## @echo + @echo $(MSG_BEGIN) + +finished: +## @echo $(MSG_ERRORS_NONE) + +end: + @echo $(MSG_END) +## @echo + +# Display sizes of sections. +ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf +##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf +sizebefore: +# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi + +sizeafter: +# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi + @echo $(MSG_SIZE_AFTER) + $(ELFSIZE) + +# Display compiler version information. +gccversion : + @$(CC) --version +# @echo $(ALLOBJ) + +# Create final output file (.hex) from ELF output file. +%.hex: %.elf +## @echo + @echo $(MSG_LOAD_FILE) $@ + $(OBJCOPY) -O ihex $< $@ + +# Create final output file (.bin) from ELF output file. +%.bin: %.elf +## @echo + @echo $(MSG_LOAD_FILE) $@ + $(OBJCOPY) -O binary $< $@ + +# Create extended listing file/disassambly from ELF output file. +# using objdump testing: option -C +%.lss: %.elf +## @echo + @echo $(MSG_EXTENDED_LISTING) $@ + $(OBJDUMP) -h -S -C -r $< > $@ +# $(OBJDUMP) -x -S $< > $@ + +# Create a symbol table from ELF output file. +%.sym: %.elf +## @echo + @echo $(MSG_SYMBOL_TABLE) $@ + $(NM) -n $< > $@ + +# Link: create ELF output file from object files. +.SECONDARY : $(TARGET).elf +.PRECIOUS : $(ALLOBJ) +%.elf: $(ALLOBJ) + @echo $(MSG_LINKING) $@ +# use $(CC) for C-only projects or $(CPP) for C++-projects: + $(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) +# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS) + + +# Assemble: create object files from assembler source files. +define ASSEMBLE_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_ASSEMBLING) $$< to $$@ + $(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@ +endef +$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) + +# Assemble: create object files from assembler source files. ARM-only +define ASSEMBLE_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_ASSEMBLING_ARM) $$< to $$@ + $(CC) -c $$(ASFLAGS) $$< -o $$@ +endef +$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src)))) + + +# Compile: create object files from C source files. +define COMPILE_C_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILING) $$< to $$@ + $(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ +endef +$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) + +# Compile: create object files from C source files. ARM-only +define COMPILE_C_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILING_ARM) $$< to $$@ + $(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@ +endef +$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src)))) + + +# Compile: create object files from C++ source files. +define COMPILE_CPP_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILINGCPP) $$< to $$@ + $(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ +endef +$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) + +# Compile: create object files from C++ source files. ARM-only +define COMPILE_CPP_ARM_TEMPLATE +$(OUTDIR)/$(notdir $(basename $(1))).o : $(1) +## @echo + @echo $(MSG_COMPILINGCPP_ARM) $$< to $$@ + $(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@ +endef +$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src)))) + + +# Compile: create assembler files from C source files. ARM/Thumb +$(SRC:.c=.s) : %.s : %.c + @echo $(MSG_ASMFROMC) $< to $@ + $(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ + +# Compile: create assembler files from C source files. ARM only +$(SRCARM:.c=.s) : %.s : %.c + @echo $(MSG_ASMFROMC_ARM) $< to $@ + $(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@ + +# Generate Doxygen documents +docs: + doxygen $(DOXYGENDIR)/doxygen.cfg + +# Target: clean project. +clean: begin clean_list finished end + +clean_list : +## @echo + @echo $(MSG_CLEANING) + $(REMOVE) $(OUTDIR)/$(TARGET).map + $(REMOVE) $(OUTDIR)/$(TARGET).elf + $(REMOVE) $(OUTDIR)/$(TARGET).hex + $(REMOVE) $(OUTDIR)/$(TARGET).bin + $(REMOVE) $(OUTDIR)/$(TARGET).sym + $(REMOVE) $(OUTDIR)/$(TARGET).lss + $(REMOVE) $(wildcard $(OUTDIR)/*.c) + $(REMOVE) $(wildcard $(OUTDIR)/*.h) + $(REMOVE) $(ALLOBJ) + $(REMOVE) $(LSTFILES) + $(REMOVE) $(DEPFILES) + $(REMOVE) $(SRC:.c=.s) + $(REMOVE) $(SRCARM:.c=.s) + $(REMOVE) $(CPPSRC:.cpp=.s) + $(REMOVE) $(CPPSRCARM:.cpp=.s) + + +# Create output files directory +# all known MS Windows OS define the ComSpec environment variable +ifdef ComSpec +$(shell md $(OUTDIR) 2>NUL) +else +$(shell mkdir $(OUTDIR) 2>/dev/null) +endif + +# Include the dependency files. +ifdef ComSpec +-include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) +else +-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) +endif + + + +# Listing of phony targets. +.PHONY : all begin finish end sizebefore sizeafter gccversion \ +build elf hex bin lss sym clean clean_list program gencode + diff --git a/flight/targets/Revolution/System/alarms.c b/flight/targets/Revolution/System/alarms.c index e61c7c1ea..6ccd5fb62 100644 --- a/flight/targets/Revolution/System/alarms.c +++ b/flight/targets/Revolution/System/alarms.c @@ -1,210 +1,210 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @brief OpenPilot System libraries are available to all OP modules. - * @{ - * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Library for setting and clearing system alarms - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "alarms.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; - -// Private functions -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); - -/** - * Initialize the alarms library - */ -int32_t AlarmsInitialize(void) -{ - SystemAlarmsInitialize(); - lock = xSemaphoreCreateRecursiveMutex(); - return 0; -} - -/** - * Set an alarm - * @param alarm The system alarm to be modified - * @param severity The alarm severity - * @return 0 if success, -1 if an error - */ -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarm and update its severity only if it was changed - SystemAlarmsGet(&alarms); - if ( alarms.Alarm[alarm] != severity ) - { - alarms.Alarm[alarm] = severity; - SystemAlarmsSet(&alarms); - } - - // Release lock - xSemaphoreGiveRecursive(lock); - return 0; - -} - -/** - * Get an alarm - * @param alarm The system alarm to be read - * @return Alarm severity - */ -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) -{ - SystemAlarmsData alarms; - - // Check that this is a valid alarm - if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) - { - return 0; - } - - // Read alarm - SystemAlarmsGet(&alarms); - return alarms.Alarm[alarm]; -} - -/** - * Set an alarm to it's default value - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); -} - -/** - * Default all alarms - */ -void AlarmsDefaultAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsDefault(n); - } -} - -/** - * Clear an alarm - * @param alarm The system alarm to be modified - * @return 0 if success, -1 if an error - */ -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) -{ - return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); -} - -/** - * Clear all alarms - */ -void AlarmsClearAll() -{ - uint32_t n; - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - AlarmsClear(n); - } -} - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasWarnings() -{ - return hasSeverity(SYSTEMALARMS_ALARM_WARNING); -} - -/** - * Check if there are any alarms with error or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasErrors() -{ - return hasSeverity(SYSTEMALARMS_ALARM_ERROR); -}; - -/** - * Check if there are any alarms with critical or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -int32_t AlarmsHasCritical() -{ - return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); -}; - -/** - * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found - */ -static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) -{ - SystemAlarmsData alarms; - uint32_t n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - - // Read alarms - SystemAlarmsGet(&alarms); - - // Go through alarms and check if any are of the given severity or higher - for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) - { - if ( alarms.Alarm[n] >= severity) - { - xSemaphoreGiveRecursive(lock); - return 1; - } - } - - // If this point is reached then no alarms found - xSemaphoreGiveRecursive(lock); - return 0; -} -/** - * @} - * @} - */ - +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @brief OpenPilot System libraries are available to all OP modules. + * @{ + * @file alarms.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Library for setting and clearing system alarms + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "alarms.h" + +// Private constants + +// Private types + +// Private variables +static xSemaphoreHandle lock; + +// Private functions +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); + +/** + * Initialize the alarms library + */ +int32_t AlarmsInitialize(void) +{ + SystemAlarmsInitialize(); + lock = xSemaphoreCreateRecursiveMutex(); + return 0; +} + +/** + * Set an alarm + * @param alarm The system alarm to be modified + * @param severity The alarm severity + * @return 0 if success, -1 if an error + */ +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return -1; + } + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarm and update its severity only if it was changed + SystemAlarmsGet(&alarms); + if ( alarms.Alarm[alarm] != severity ) + { + alarms.Alarm[alarm] = severity; + SystemAlarmsSet(&alarms); + } + + // Release lock + xSemaphoreGiveRecursive(lock); + return 0; + +} + +/** + * Get an alarm + * @param alarm The system alarm to be read + * @return Alarm severity + */ +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) +{ + SystemAlarmsData alarms; + + // Check that this is a valid alarm + if (alarm >= SYSTEMALARMS_ALARM_NUMELEM) + { + return 0; + } + + // Read alarm + SystemAlarmsGet(&alarms); + return alarms.Alarm[alarm]; +} + +/** + * Set an alarm to it's default value + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT); +} + +/** + * Default all alarms + */ +void AlarmsDefaultAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsDefault(n); + } +} + +/** + * Clear an alarm + * @param alarm The system alarm to be modified + * @return 0 if success, -1 if an error + */ +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm) +{ + return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK); +} + +/** + * Clear all alarms + */ +void AlarmsClearAll() +{ + uint32_t n; + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + AlarmsClear(n); + } +} + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasWarnings() +{ + return hasSeverity(SYSTEMALARMS_ALARM_WARNING); +} + +/** + * Check if there are any alarms with error or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasErrors() +{ + return hasSeverity(SYSTEMALARMS_ALARM_ERROR); +}; + +/** + * Check if there are any alarms with critical or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +int32_t AlarmsHasCritical() +{ + return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL); +}; + +/** + * Check if there are any alarms with the given or higher severity + * @return 0 if no alarms are found, 1 if at least one alarm is found + */ +static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) +{ + SystemAlarmsData alarms; + uint32_t n; + + // Lock + xSemaphoreTakeRecursive(lock, portMAX_DELAY); + + // Read alarms + SystemAlarmsGet(&alarms); + + // Go through alarms and check if any are of the given severity or higher + for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) + { + if ( alarms.Alarm[n] >= severity) + { + xSemaphoreGiveRecursive(lock); + return 1; + } + } + + // If this point is reached then no alarms found + xSemaphoreGiveRecursive(lock); + return 0; +} +/** + * @} + * @} + */ + diff --git a/flight/targets/Revolution/System/inc/alarms.h b/flight/targets/Revolution/System/inc/alarms.h index 9fb047dca..0f0faeb8f 100644 --- a/flight/targets/Revolution/System/inc/alarms.h +++ b/flight/targets/Revolution/System/inc/alarms.h @@ -1,50 +1,50 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the alarm library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef ALARMS_H -#define ALARMS_H - -#include "systemalarms.h" -#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED - -int32_t AlarmsInitialize(void); -int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); -SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); -int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); -void AlarmsDefaultAll(); -int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); -void AlarmsClearAll(); -int32_t AlarmsHasWarnings(); -int32_t AlarmsHasErrors(); -int32_t AlarmsHasCritical(); - -#endif // ALARMS_H - -/** - * @} - * @} +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file alarms.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include file of the alarm library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef ALARMS_H +#define ALARMS_H + +#include "systemalarms.h" +#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED + +int32_t AlarmsInitialize(void); +int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity); +SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm); +int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm); +void AlarmsDefaultAll(); +int32_t AlarmsClear(SystemAlarmsAlarmElem alarm); +void AlarmsClearAll(); +int32_t AlarmsHasWarnings(); +int32_t AlarmsHasErrors(); +int32_t AlarmsHasCritical(); + +#endif // ALARMS_H + +/** + * @} + * @} */ diff --git a/flight/targets/Revolution/System/inc/openpilot.h b/flight/targets/Revolution/System/inc/openpilot.h index 7f1ac3758..eb3cadcc7 100644 --- a/flight/targets/Revolution/System/inc/openpilot.h +++ b/flight/targets/Revolution/System/inc/openpilot.h @@ -1,52 +1,52 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file openpilot.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main OpenPilot header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef OPENPILOT_H -#define OPENPILOT_H - - -/* PIOS Includes */ -#include - -/* OpenPilot Libraries */ -#include "utlist.h" -#include "uavobjectmanager.h" -#include "eventdispatcher.h" -#include "alarms.h" -#include "taskmonitor.h" -#include "uavtalk.h" - -/* Global Functions */ -void OpenPilotInit(void); - -#endif /* OPENPILOT_H */ -/** - * @} - * @} +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file openpilot.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main OpenPilot header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OPENPILOT_H +#define OPENPILOT_H + + +/* PIOS Includes */ +#include + +/* OpenPilot Libraries */ +#include "utlist.h" +#include "uavobjectmanager.h" +#include "eventdispatcher.h" +#include "alarms.h" +#include "taskmonitor.h" +#include "uavtalk.h" + +/* Global Functions */ +void OpenPilotInit(void); + +#endif /* OPENPILOT_H */ +/** + * @} + * @} */ diff --git a/flight/targets/Revolution/System/inc/pios_board_sim.h b/flight/targets/Revolution/System/inc/pios_board_sim.h index 30a3d3d37..3c960b03e 100644 --- a/flight/targets/Revolution/System/inc/pios_board_sim.h +++ b/flight/targets/Revolution/System/inc/pios_board_sim.h @@ -1,85 +1,85 @@ -/** - ****************************************************************************** - * - * @file pios_board.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_BOARD_H -#define PIOS_BOARD_H - - - - -//------------------------ -// PIOS_LED -//------------------------ -#define PIOS_LED_ALARM 0 -#define PIOS_LED_HEARTBEAT 1 -#define PIOS_LED_NUM 2 - -//------------------------- -// COM -// -// See also pios_board_posix.c -//------------------------- -//#define PIOS_USART_TX_BUFFER_SIZE 256 -#define PIOS_COM_BUFFER_SIZE 1024 -#define PIOS_COM_MAX_DEVS 255 -#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE -#define PIOS_TCP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE - -extern uint32_t pios_com_telem_rf_id; -extern uint32_t pios_com_telem_usb_id; -extern uint32_t pios_com_gps_id; -extern uint32_t pios_com_aux_id; -extern uint32_t pios_com_spectrum_id; - -#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) -#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#define PIOS_COM_GPS (pios_com_gps_id) - -#ifdef PIOS_ENABLE_AUX_UART -#define PIOS_COM_AUX (pios_com_aux_id) -#define PIOS_COM_DEBUG (PIOS_COM_AUX -#endif - -#define PIOS_GCSRCVR_TIMEOUT_MS 200 -/** - * glue macros for file IO - * STM32 uses DOSFS for file IO - */ -#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL - -#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL - -#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length - -#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file) - - - -#define PIOS_FCLOSE(file) fclose(file) - -#define PIOS_FUNLINK(file) unlink((char*)filename) - -#endif /* PIOS_BOARD_H */ +/** + ****************************************************************************** + * + * @file pios_board.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_BOARD_H +#define PIOS_BOARD_H + + + + +//------------------------ +// PIOS_LED +//------------------------ +#define PIOS_LED_ALARM 0 +#define PIOS_LED_HEARTBEAT 1 +#define PIOS_LED_NUM 2 + +//------------------------- +// COM +// +// See also pios_board_posix.c +//------------------------- +//#define PIOS_USART_TX_BUFFER_SIZE 256 +#define PIOS_COM_BUFFER_SIZE 1024 +#define PIOS_COM_MAX_DEVS 255 +#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE +#define PIOS_TCP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE + +extern uint32_t pios_com_telem_rf_id; +extern uint32_t pios_com_telem_usb_id; +extern uint32_t pios_com_gps_id; +extern uint32_t pios_com_aux_id; +extern uint32_t pios_com_spectrum_id; + +#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) +#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) +#define PIOS_COM_GPS (pios_com_gps_id) + +#ifdef PIOS_ENABLE_AUX_UART +#define PIOS_COM_AUX (pios_com_aux_id) +#define PIOS_COM_DEBUG (PIOS_COM_AUX +#endif + +#define PIOS_GCSRCVR_TIMEOUT_MS 200 +/** + * glue macros for file IO + * STM32 uses DOSFS for file IO + */ +#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL + +#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL + +#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length + +#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file) + + + +#define PIOS_FCLOSE(file) fclose(file) + +#define PIOS_FUNLINK(file) unlink((char*)filename) + +#endif /* PIOS_BOARD_H */ diff --git a/flight/targets/Revolution/System/inc/pios_config.h b/flight/targets/Revolution/System/inc/pios_config.h index 575017d73..c148d9142 100644 --- a/flight/targets/Revolution/System/inc/pios_config.h +++ b/flight/targets/Revolution/System/inc/pios_config.h @@ -1,175 +1,175 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013. - * @brief PiOS configuration header, the compile time config file for the PIOS. - * Defines which PiOS libraries and features are included in the firmware. - * @see The GNU Public License (GPL) Version 3 - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* - * Below is a complete list of PIOS configurable options. - * Please do not remove or rearrange them. Only comment out - * unused options in the list. See main pios.h header for more - * details. - */ - -/* #define PIOS_INCLUDE_DEBUG_CONSOLE */ -/* #define DEBUG_LEVEL 0 */ - -/* PIOS FreeRTOS support */ -#define PIOS_INCLUDE_FREERTOS - -/* PIOS bootloader helper */ -#define PIOS_INCLUDE_BL_HELPER -/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */ - -/* PIOS system functions */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_INITCALL -#define PIOS_INCLUDE_SYS - -/* PIOS hardware peripherals */ -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_RTC -#define PIOS_INCLUDE_TIM -#define PIOS_INCLUDE_USART -#define PIOS_INCLUDE_ADC -#define PIOS_INCLUDE_I2C -#define PIOS_INCLUDE_SPI -/* #define PIOS_INCLUDE_GPIO */ -#define PIOS_INCLUDE_EXTI -#define PIOS_INCLUDE_WDG - -/* PIOS USB functions */ -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -/* #define PIOS_INCLUDE_USB_CDC */ -/* #define PIOS_INCLUDE_USB_RCTX */ - -/* PIOS sensor interfaces */ -/* #define PIOS_INCLUDE_ADXL345 */ -#define PIOS_INCLUDE_BMA180 -#define PIOS_INCLUDE_L3GD20 -#define PIOS_INCLUDE_MPU6000 -#define PIOS_MPU6000_ACCEL -/* #define PIOS_INCLUDE_HMC5843 */ -#define PIOS_INCLUDE_HMC5883 -#define PIOS_HMC5883_HAS_GPIOS -/* #define PIOS_INCLUDE_BMP085 */ -#define PIOS_INCLUDE_MS5611 -#define PIOS_INCLUDE_MPXV -#define PIOS_INCLUDE_ETASV3 -/* #define PIOS_INCLUDE_HCSR04 */ - -/* PIOS receiver drivers */ -#define PIOS_INCLUDE_PWM -#define PIOS_INCLUDE_PPM -/* #define PIOS_INCLUDE_PPM_FLEXI */ -#define PIOS_INCLUDE_DSM -#define PIOS_INCLUDE_SBUS -#define PIOS_INCLUDE_GCSRCVR - -/* PIOS abstract receiver interface */ -#define PIOS_INCLUDE_RCVR - -/* PIOS common peripherals */ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_SERVO -/* #define PIOS_INCLUDE_I2C_ESC */ -#define PIOS_INCLUDE_OVERO -#define PIOS_OVERO_SPI -/* #define PIOS_INCLUDE_SDCARD */ -/* #define LOG_FILENAME "startup.log" */ -#define PIOS_INCLUDE_FLASH -#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS -#define FLASH_FREERTOS -/* #define PIOS_INCLUDE_FLASH_EEPROM */ - -/* PIOS radio modules */ -/* #define PIOS_INCLUDE_RFM22B */ -/* #define PIOS_INCLUDE_RFM22B_COM */ -/* #define PIOS_INCLUDE_RFM22B_RCVR */ -/* #define PIOS_INCLUDE_PPM_OUT */ -/* #define PIOS_RFM22B_DEBUG_ON_TELEM */ - -/* PIOS misc peripherals */ -/* #define PIOS_INCLUDE_VIDEO */ -/* #define PIOS_INCLUDE_WAVE */ -/* #define PIOS_INCLUDE_UDP */ - -/* PIOS abstract comms interface with options */ -#define PIOS_INCLUDE_COM -/* #define PIOS_INCLUDE_COM_MSG */ -/* #define PIOS_INCLUDE_TELEMETRY_RF */ -#define PIOS_INCLUDE_COM_TELEM -#define PIOS_INCLUDE_COM_FLEXI -#define PIOS_INCLUDE_COM_AUX -#define PIOS_TELEM_PRIORITY_QUEUE -#define PIOS_INCLUDE_GPS -/* #define PIOS_GPS_MINIMAL */ -#define PIOS_INCLUDE_GPS_NMEA_PARSER -#define PIOS_INCLUDE_GPS_UBX_PARSER -#define PIOS_GPS_SETS_HOMELOCATION - -/* Stabilization options */ -/* #define PIOS_QUATERNION_STABILIZATION */ - -/* Performance counters */ -#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 8379692 - -/* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 1000 -#define HEAP_LIMIT_CRITICAL 500 -#define IRQSTACK_LIMIT_WARNING 150 -#define IRQSTACK_LIMIT_CRITICAL 80 -#define CPULOAD_LIMIT_WARNING 80 -#define CPULOAD_LIMIT_CRITICAL 95 - -/* Task stack sizes */ -/* #define PIOS_ACTUATOR_STACK_SIZE 1020 */ -/* #define PIOS_MANUAL_STACK_SIZE 800 */ -/* #define PIOS_SYSTEM_STACK_SIZE 660 */ -/* #define PIOS_STABILIZATION_STACK_SIZE 524 */ -/* #define PIOS_TELEM_STACK_SIZE 500 */ -/* #define PIOS_EVENTDISPATCHER_STACK_SIZE 130 */ - -/* This can't be too high to stop eventdispatcher thread overflowing */ -#define PIOS_EVENTDISAPTCHER_QUEUE 10 - -/* Revolution series */ -#define REVOLUTION - -/* OBSOLETE */ -#define PIOS_INCLUDE_COM_AUXSBUS -#define PIOS_FLASH_ON_ACCEL /* true for second revo */ - -#endif /* PIOS_CONFIG_H */ - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013. + * @brief PiOS configuration header, the compile time config file for the PIOS. + * Defines which PiOS libraries and features are included in the firmware. + * @see The GNU Public License (GPL) Version 3 + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* + * Below is a complete list of PIOS configurable options. + * Please do not remove or rearrange them. Only comment out + * unused options in the list. See main pios.h header for more + * details. + */ + +/* #define PIOS_INCLUDE_DEBUG_CONSOLE */ +/* #define DEBUG_LEVEL 0 */ + +/* PIOS FreeRTOS support */ +#define PIOS_INCLUDE_FREERTOS + +/* PIOS bootloader helper */ +#define PIOS_INCLUDE_BL_HELPER +/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */ + +/* PIOS system functions */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_INITCALL +#define PIOS_INCLUDE_SYS + +/* PIOS hardware peripherals */ +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_RTC +#define PIOS_INCLUDE_TIM +#define PIOS_INCLUDE_USART +#define PIOS_INCLUDE_ADC +#define PIOS_INCLUDE_I2C +#define PIOS_INCLUDE_SPI +/* #define PIOS_INCLUDE_GPIO */ +#define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_WDG + +/* PIOS USB functions */ +#define PIOS_INCLUDE_USB +#define PIOS_INCLUDE_USB_HID +/* #define PIOS_INCLUDE_USB_CDC */ +/* #define PIOS_INCLUDE_USB_RCTX */ + +/* PIOS sensor interfaces */ +/* #define PIOS_INCLUDE_ADXL345 */ +#define PIOS_INCLUDE_BMA180 +#define PIOS_INCLUDE_L3GD20 +#define PIOS_INCLUDE_MPU6000 +#define PIOS_MPU6000_ACCEL +/* #define PIOS_INCLUDE_HMC5843 */ +#define PIOS_INCLUDE_HMC5883 +#define PIOS_HMC5883_HAS_GPIOS +/* #define PIOS_INCLUDE_BMP085 */ +#define PIOS_INCLUDE_MS5611 +#define PIOS_INCLUDE_MPXV +#define PIOS_INCLUDE_ETASV3 +/* #define PIOS_INCLUDE_HCSR04 */ + +/* PIOS receiver drivers */ +#define PIOS_INCLUDE_PWM +#define PIOS_INCLUDE_PPM +/* #define PIOS_INCLUDE_PPM_FLEXI */ +#define PIOS_INCLUDE_DSM +#define PIOS_INCLUDE_SBUS +#define PIOS_INCLUDE_GCSRCVR + +/* PIOS abstract receiver interface */ +#define PIOS_INCLUDE_RCVR + +/* PIOS common peripherals */ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_SERVO +/* #define PIOS_INCLUDE_I2C_ESC */ +#define PIOS_INCLUDE_OVERO +#define PIOS_OVERO_SPI +/* #define PIOS_INCLUDE_SDCARD */ +/* #define LOG_FILENAME "startup.log" */ +#define PIOS_INCLUDE_FLASH +#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS +#define FLASH_FREERTOS +/* #define PIOS_INCLUDE_FLASH_EEPROM */ + +/* PIOS radio modules */ +/* #define PIOS_INCLUDE_RFM22B */ +/* #define PIOS_INCLUDE_RFM22B_COM */ +/* #define PIOS_INCLUDE_RFM22B_RCVR */ +/* #define PIOS_INCLUDE_PPM_OUT */ +/* #define PIOS_RFM22B_DEBUG_ON_TELEM */ + +/* PIOS misc peripherals */ +/* #define PIOS_INCLUDE_VIDEO */ +/* #define PIOS_INCLUDE_WAVE */ +/* #define PIOS_INCLUDE_UDP */ + +/* PIOS abstract comms interface with options */ +#define PIOS_INCLUDE_COM +/* #define PIOS_INCLUDE_COM_MSG */ +/* #define PIOS_INCLUDE_TELEMETRY_RF */ +#define PIOS_INCLUDE_COM_TELEM +#define PIOS_INCLUDE_COM_FLEXI +#define PIOS_INCLUDE_COM_AUX +#define PIOS_TELEM_PRIORITY_QUEUE +#define PIOS_INCLUDE_GPS +/* #define PIOS_GPS_MINIMAL */ +#define PIOS_INCLUDE_GPS_NMEA_PARSER +#define PIOS_INCLUDE_GPS_UBX_PARSER +#define PIOS_GPS_SETS_HOMELOCATION + +/* Stabilization options */ +/* #define PIOS_QUATERNION_STABILIZATION */ + +/* Performance counters */ +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 8379692 + +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 1000 +#define HEAP_LIMIT_CRITICAL 500 +#define IRQSTACK_LIMIT_WARNING 150 +#define IRQSTACK_LIMIT_CRITICAL 80 +#define CPULOAD_LIMIT_WARNING 80 +#define CPULOAD_LIMIT_CRITICAL 95 + +/* Task stack sizes */ +/* #define PIOS_ACTUATOR_STACK_SIZE 1020 */ +/* #define PIOS_MANUAL_STACK_SIZE 800 */ +/* #define PIOS_SYSTEM_STACK_SIZE 660 */ +/* #define PIOS_STABILIZATION_STACK_SIZE 524 */ +/* #define PIOS_TELEM_STACK_SIZE 500 */ +/* #define PIOS_EVENTDISPATCHER_STACK_SIZE 130 */ + +/* This can't be too high to stop eventdispatcher thread overflowing */ +#define PIOS_EVENTDISAPTCHER_QUEUE 10 + +/* Revolution series */ +#define REVOLUTION + +/* OBSOLETE */ +#define PIOS_INCLUDE_COM_AUXSBUS +#define PIOS_FLASH_ON_ACCEL /* true for second revo */ + +#endif /* PIOS_CONFIG_H */ + +/** + * @} + * @} + */ diff --git a/flight/targets/Revolution/System/inc/pios_config_sim.h b/flight/targets/Revolution/System/inc/pios_config_sim.h index 53ab13125..ab313d0a1 100644 --- a/flight/targets/Revolution/System/inc/pios_config_sim.h +++ b/flight/targets/Revolution/System/inc/pios_config_sim.h @@ -1,82 +1,82 @@ -/** - ****************************************************************************** - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * Central compile time config for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_CONFIG_POSIX_H -#define PIOS_CONFIG_POSIX_H - - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SDCARD -#define PIOS_INCLUDE_FREERTOS -#define PIOS_INCLUDE_COM -//#define PIOS_INCLUDE_GPS -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_TELEMETRY_RF -#define PIOS_INCLUDE_TCP -#define PIOS_INCLUDE_UDP -#define PIOS_INCLUDE_SERVO -#define PIOS_INCLUDE_RCVR -#define PIOS_INCLUDE_GCSRCVR -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_BL_HELPER - -#define PIOS_RCVR_MAX_CHANNELS 12 -#define PIOS_RCVR_MAX_DEVS 3 - -/* Defaults for Logging */ -#define LOG_FILENAME "PIOS.LOG" -#define STARTUP_LOG_ENABLED 1 - -/* COM Module */ -#define GPS_BAUDRATE 19200 -#define TELEM_BAUDRATE 19200 -#define AUXUART_ENABLED 0 -#define AUXUART_BAUDRATE 19200 - -#define TELEM_QUEUE_SIZE 20 -#define PIOS_TELEM_STACK_SIZE 2048 - -/* Stabilization options */ -#define PIOS_QUATERNION_STABILIZATION - -/* GPS options */ -#define PIOS_GPS_SETS_HOMELOCATION - -#define HEAP_LIMIT_WARNING 4000 -#define HEAP_LIMIT_CRITICAL 1000 -#define IRQSTACK_LIMIT_WARNING 150 -#define IRQSTACK_LIMIT_CRITICAL 80 -#define CPULOAD_LIMIT_WARNING 80 -#define CPULOAD_LIMIT_CRITICAL 95 - -#define REVOLUTION -#define SIM_OSX - -#endif /* PIOS_CONFIG_POSIX_H */ +/** + ****************************************************************************** + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * Central compile time config for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_CONFIG_POSIX_H +#define PIOS_CONFIG_POSIX_H + + +/* Enable/Disable PiOS Modules */ +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_SDCARD +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_COM +//#define PIOS_INCLUDE_GPS +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_TELEMETRY_RF +#define PIOS_INCLUDE_TCP +#define PIOS_INCLUDE_UDP +#define PIOS_INCLUDE_SERVO +#define PIOS_INCLUDE_RCVR +#define PIOS_INCLUDE_GCSRCVR +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_BL_HELPER + +#define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_RCVR_MAX_DEVS 3 + +/* Defaults for Logging */ +#define LOG_FILENAME "PIOS.LOG" +#define STARTUP_LOG_ENABLED 1 + +/* COM Module */ +#define GPS_BAUDRATE 19200 +#define TELEM_BAUDRATE 19200 +#define AUXUART_ENABLED 0 +#define AUXUART_BAUDRATE 19200 + +#define TELEM_QUEUE_SIZE 20 +#define PIOS_TELEM_STACK_SIZE 2048 + +/* Stabilization options */ +#define PIOS_QUATERNION_STABILIZATION + +/* GPS options */ +#define PIOS_GPS_SETS_HOMELOCATION + +#define HEAP_LIMIT_WARNING 4000 +#define HEAP_LIMIT_CRITICAL 1000 +#define IRQSTACK_LIMIT_WARNING 150 +#define IRQSTACK_LIMIT_CRITICAL 80 +#define CPULOAD_LIMIT_WARNING 80 +#define CPULOAD_LIMIT_CRITICAL 95 + +#define REVOLUTION +#define SIM_OSX + +#endif /* PIOS_CONFIG_POSIX_H */ diff --git a/flight/targets/Revolution/System/revolution.c b/flight/targets/Revolution/System/revolution.c index ff2814fbd..7adcbf8d6 100644 --- a/flight/targets/Revolution/System/revolution.c +++ b/flight/targets/Revolution/System/revolution.c @@ -1,142 +1,142 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @brief These files are the core system files of OpenPilot. - * They are the ground layer just above PiOS. In practice, OpenPilot actually starts - * in the main() function of openpilot.c - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @brief This is where the OP firmware starts. Those files also define the compile-time - * options of the firmware. - * @{ - * @file openpilot.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sets up and runs main OpenPilot tasks. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* OpenPilot Includes */ -#include "openpilot.h" -#include "uavobjectsinit.h" -#include "systemmod.h" - -/* Task Priorities */ -#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) - -/* Global Variables */ - -/* Local Variables */ -#define INCLUDE_TEST_TASKS 0 -#if INCLUDE_TEST_TASKS -static uint8_t sdcard_available; -#endif -char Buffer[1024]; -uint32_t Cache; - -/* Function Prototypes */ -#if INCLUDE_TEST_TASKS -static void TaskTick(void *pvParameters); -static void TaskTesting(void *pvParameters); -static void TaskHIDTest(void *pvParameters); -static void TaskServos(void *pvParameters); -static void TaskSDCard(void *pvParameters); -#endif -int32_t CONSOLE_Parse(uint8_t port, char c); -void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value); - -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void Stack_Change(void); -static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change"))); - -/* Local Variables */ -#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority -#define INIT_TASK_STACK (1024 / 4) // XXX this seems excessive -static xTaskHandle initTaskHandle; - -/* Function Prototypes */ -static void initTask(void *parameters); - -/* Prototype of generated InitModules() function */ -extern void InitModules(void); - -/** -* OpenPilot Main function: -* -* Initialize PiOS
-* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
-* Start FreeRTOS Scheduler (vTaskStartScheduler)
-* If something goes wrong, blink LED1 and LED2 every 100ms -* -*/ -int main() -{ - int result; - - /* NOTE: Do NOT modify the following start-up sequence */ - /* Any new initialization functions should be added in OpenPilotInit() */ - vPortInitialiseBlocks(); - - /* Brings up System using CMSIS functions, enables the LEDs. */ - PIOS_SYS_Init(); - - /* For Revolution we use a FreeRTOS task to bring up the system so we can */ - /* always rely on FreeRTOS primitive */ - result = xTaskCreate(initTask, (const signed char *)"init", - INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY, - &initTaskHandle); - PIOS_Assert(result == pdPASS); - - /* Start the FreeRTOS scheduler */ - vTaskStartScheduler(); - - /* If all is well we will never reach here as the scheduler will now be running. */ - /* Do some PIOS_LED_HEARTBEAT to user that something bad just happened */ - PIOS_LED_Off(PIOS_LED_HEARTBEAT); \ - for(;;) { \ - PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ - PIOS_DELAY_WaitmS(100); \ - }; - - return 0; -} -/** - * Initialisation task. - * - * Runs board and module initialisation, then terminates. - */ -void -initTask(void *parameters) -{ - /* board driver init */ - PIOS_Board_Init(); - - /* Initialize modules */ - MODULE_INITIALISE_ALL; - - /* terminate this task */ - vTaskDelete(NULL); -} - -/** - * @} - * @} - */ - +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @brief These files are the core system files of OpenPilot. + * They are the ground layer just above PiOS. In practice, OpenPilot actually starts + * in the main() function of openpilot.c + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @brief This is where the OP firmware starts. Those files also define the compile-time + * options of the firmware. + * @{ + * @file openpilot.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Sets up and runs main OpenPilot tasks. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* OpenPilot Includes */ +#include "openpilot.h" +#include "uavobjectsinit.h" +#include "systemmod.h" + +/* Task Priorities */ +#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) + +/* Global Variables */ + +/* Local Variables */ +#define INCLUDE_TEST_TASKS 0 +#if INCLUDE_TEST_TASKS +static uint8_t sdcard_available; +#endif +char Buffer[1024]; +uint32_t Cache; + +/* Function Prototypes */ +#if INCLUDE_TEST_TASKS +static void TaskTick(void *pvParameters); +static void TaskTesting(void *pvParameters); +static void TaskHIDTest(void *pvParameters); +static void TaskServos(void *pvParameters); +static void TaskSDCard(void *pvParameters); +#endif +int32_t CONSOLE_Parse(uint8_t port, char c); +void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value); + +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void Stack_Change(void); +static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change"))); + +/* Local Variables */ +#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority +#define INIT_TASK_STACK (1024 / 4) // XXX this seems excessive +static xTaskHandle initTaskHandle; + +/* Function Prototypes */ +static void initTask(void *parameters); + +/* Prototype of generated InitModules() function */ +extern void InitModules(void); + +/** +* OpenPilot Main function: +* +* Initialize PiOS
+* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
+* Start FreeRTOS Scheduler (vTaskStartScheduler)
+* If something goes wrong, blink LED1 and LED2 every 100ms +* +*/ +int main() +{ + int result; + + /* NOTE: Do NOT modify the following start-up sequence */ + /* Any new initialization functions should be added in OpenPilotInit() */ + vPortInitialiseBlocks(); + + /* Brings up System using CMSIS functions, enables the LEDs. */ + PIOS_SYS_Init(); + + /* For Revolution we use a FreeRTOS task to bring up the system so we can */ + /* always rely on FreeRTOS primitive */ + result = xTaskCreate(initTask, (const signed char *)"init", + INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY, + &initTaskHandle); + PIOS_Assert(result == pdPASS); + + /* Start the FreeRTOS scheduler */ + vTaskStartScheduler(); + + /* If all is well we will never reach here as the scheduler will now be running. */ + /* Do some PIOS_LED_HEARTBEAT to user that something bad just happened */ + PIOS_LED_Off(PIOS_LED_HEARTBEAT); \ + for(;;) { \ + PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ + PIOS_DELAY_WaitmS(100); \ + }; + + return 0; +} +/** + * Initialisation task. + * + * Runs board and module initialisation, then terminates. + */ +void +initTask(void *parameters) +{ + /* board driver init */ + PIOS_Board_Init(); + + /* Initialize modules */ + MODULE_INITIALISE_ALL; + + /* terminate this task */ + vTaskDelete(NULL); +} + +/** + * @} + * @} + */ + diff --git a/flight/targets/SimPosix/System/inc/FreeRTOSConfig.h b/flight/targets/SimPosix/System/inc/FreeRTOSConfig.h index f6602c721..c2a334f41 100644 --- a/flight/targets/SimPosix/System/inc/FreeRTOSConfig.h +++ b/flight/targets/SimPosix/System/inc/FreeRTOSConfig.h @@ -1,107 +1,107 @@ - -#ifndef FREERTOS_CONFIG_H -#define FREERTOS_CONFIG_H - -/*----------------------------------------------------------- - * Application specific definitions. - * - * These definitions should be adjusted for your particular hardware and - * application requirements. - * - * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE - * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. - * - * See http://www.freertos.org/a00110.html. - *----------------------------------------------------------*/ - -/* Notes: We use 5 task priorities */ - - -#ifdef __APPLE__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES - #define RUNNING_THREAD_MUTEX -// #define TICK_SIGNAL -// #define TICK_SIGWAIT - #define IDLE_SLEEPS - - #define configUSE_PREEMPTION 1 - #define configIDLE_SHOULD_YIELD 0 -#endif -#ifdef __CYGWIN__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES -// #define RUNNING_THREAD_MUTEX -// #define TICK_SIGNAL - #define TICK_SIGWAIT - #define IDLE_SLEEPS - - #define configUSE_PREEMPTION 0 - #define configIDLE_SHOULD_YIELD 1 -#endif -#ifdef __linux__ - #define COND_SIGNALING - #define CHECK_TASK_RESUMES - #define RUNNING_THREAD_MUTEX -// #define TICK_SIGNAL -// #define TICK_SIGWAIT - #define IDLE_SLEEPS - - #define configUSE_PREEMPTION 1 - #define configIDLE_SHOULD_YIELD 0 -#endif - - -#define configUSE_IDLE_HOOK 1 -#define configUSE_TICK_HOOK 0 -#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) -#define configTICK_RATE_HZ ( ( portTickType ) 1000 ) -#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) -#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 ) -#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 45 * 1024 ) ) -#define configMAX_TASK_NAME_LEN ( 16 ) -#define configUSE_TRACE_FACILITY 0 -#define configUSE_16_BIT_TICKS 0 -#define configUSE_MUTEXES 1 -#define configUSE_RECURSIVE_MUTEXES 1 -#define configUSE_COUNTING_SEMAPHORES 0 -#define configUSE_ALTERNATIVE_API 0 -#define configCHECK_FOR_STACK_OVERFLOW 2 -#define configQUEUE_REGISTRY_SIZE 10 - - -/* Co-routine definitions. */ -#define configUSE_CO_ROUTINES 0 -#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) - -/* Set the following definitions to 1 to include the API function, or zero -to exclude the API function. */ - -#define INCLUDE_vTaskPrioritySet 1 -#define INCLUDE_uxTaskPriorityGet 1 -#define INCLUDE_vTaskDelete 1 -#define INCLUDE_vTaskCleanUpResources 0 -#define INCLUDE_vTaskSuspend 1 -#define INCLUDE_vTaskDelayUntil 1 -#define INCLUDE_vTaskDelay 1 -#define INCLUDE_xTaskGetSchedulerState 1 -#define INCLUDE_xTaskGetCurrentTaskHandle 1 -#define INCLUDE_uxTaskGetStackHighWaterMark 0 - - - - -/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 -(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ -#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ -#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ - - -/* This is the value being used as per the ST library which permits 16 -priority values, 0 to 15. This must correspond to the -configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest -NVIC value of 255. */ -#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 - -#endif /* FREERTOS_CONFIG_H */ - + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html. + *----------------------------------------------------------*/ + +/* Notes: We use 5 task priorities */ + + +#ifdef __APPLE__ + #define COND_SIGNALING + #define CHECK_TASK_RESUMES + #define RUNNING_THREAD_MUTEX +// #define TICK_SIGNAL +// #define TICK_SIGWAIT + #define IDLE_SLEEPS + + #define configUSE_PREEMPTION 1 + #define configIDLE_SHOULD_YIELD 0 +#endif +#ifdef __CYGWIN__ + #define COND_SIGNALING + #define CHECK_TASK_RESUMES +// #define RUNNING_THREAD_MUTEX +// #define TICK_SIGNAL + #define TICK_SIGWAIT + #define IDLE_SLEEPS + + #define configUSE_PREEMPTION 0 + #define configIDLE_SHOULD_YIELD 1 +#endif +#ifdef __linux__ + #define COND_SIGNALING + #define CHECK_TASK_RESUMES + #define RUNNING_THREAD_MUTEX +// #define TICK_SIGNAL +// #define TICK_SIGWAIT + #define IDLE_SLEEPS + + #define configUSE_PREEMPTION 1 + #define configIDLE_SHOULD_YIELD 0 +#endif + + +#define configUSE_IDLE_HOOK 1 +#define configUSE_TICK_HOOK 0 +#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) +#define configTICK_RATE_HZ ( ( portTickType ) 1000 ) +#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) +#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 ) +#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 45 * 1024 ) ) +#define configMAX_TASK_NAME_LEN ( 16 ) +#define configUSE_TRACE_FACILITY 0 +#define configUSE_16_BIT_TICKS 0 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 0 +#define configUSE_ALTERNATIVE_API 0 +#define configCHECK_FOR_STACK_OVERFLOW 2 +#define configQUEUE_REGISTRY_SIZE 10 + + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ + +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 0 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 1 +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 0 + + + + +/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 +(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ +#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ + + +/* This is the value being used as per the ST library which permits 16 +priority values, 0 to 15. This must correspond to the +configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest +NVIC value of 255. */ +#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 + +#endif /* FREERTOS_CONFIG_H */ + diff --git a/flight/targets/SimPosix/System/inc/openpilot.h b/flight/targets/SimPosix/System/inc/openpilot.h index 5cad3ec7a..eb3cadcc7 100644 --- a/flight/targets/SimPosix/System/inc/openpilot.h +++ b/flight/targets/SimPosix/System/inc/openpilot.h @@ -1,52 +1,52 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @{ - * @file openpilot.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main OpenPilot header. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef OPENPILOT_H -#define OPENPILOT_H - - -/* PIOS Includes */ -#include - -/* OpenPilot Libraries */ -#include "utlist.h" -#include "uavobjectmanager.h" -#include "eventdispatcher.h" -#include "alarms.h" -#include "taskmonitor.h" -#include "uavtalk.h" - -/* Global Functions */ -void OpenPilotInit(void); - -#endif /* OPENPILOT_H */ -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @{ + * @file openpilot.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main OpenPilot header. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef OPENPILOT_H +#define OPENPILOT_H + + +/* PIOS Includes */ +#include + +/* OpenPilot Libraries */ +#include "utlist.h" +#include "uavobjectmanager.h" +#include "eventdispatcher.h" +#include "alarms.h" +#include "taskmonitor.h" +#include "uavtalk.h" + +/* Global Functions */ +void OpenPilotInit(void); + +#endif /* OPENPILOT_H */ +/** + * @} + * @} + */ diff --git a/flight/targets/UAVObjects/inc/eventdispatcher.h b/flight/targets/UAVObjects/inc/eventdispatcher.h index 5c2f7e148..258312624 100644 --- a/flight/targets/UAVObjects/inc/eventdispatcher.h +++ b/flight/targets/UAVObjects/inc/eventdispatcher.h @@ -1,48 +1,48 @@ -/** - ****************************************************************************** - * - * @file eventdispatcher.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include files of the uavobjectlist library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef EVENTDISPATCHER_H -#define EVENTDISPATCHER_H - -// Public types -/** - * Event dispatcher statistics - */ -typedef struct { - uint32_t lastErrorID; - uint32_t eventErrors; -} EventStats; - -// Public functions -int32_t EventDispatcherInitialize(); -void EventGetStats(EventStats* statsOut); -void EventClearStats(); -int32_t EventCallbackDispatch(UAVObjEvent* ev, UAVObjEventCallback cb); -int32_t EventPeriodicCallbackCreate(UAVObjEvent* ev, UAVObjEventCallback cb, uint16_t periodMs); -int32_t EventPeriodicCallbackUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, uint16_t periodMs); -int32_t EventPeriodicQueueCreate(UAVObjEvent* ev, xQueueHandle queue, uint16_t periodMs); -int32_t EventPeriodicQueueUpdate(UAVObjEvent* ev, xQueueHandle queue, uint16_t periodMs); - -#endif // EVENTDISPATCHER_H +/** + ****************************************************************************** + * + * @file eventdispatcher.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include files of the uavobjectlist library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef EVENTDISPATCHER_H +#define EVENTDISPATCHER_H + +// Public types +/** + * Event dispatcher statistics + */ +typedef struct { + uint32_t lastErrorID; + uint32_t eventErrors; +} EventStats; + +// Public functions +int32_t EventDispatcherInitialize(); +void EventGetStats(EventStats* statsOut); +void EventClearStats(); +int32_t EventCallbackDispatch(UAVObjEvent* ev, UAVObjEventCallback cb); +int32_t EventPeriodicCallbackCreate(UAVObjEvent* ev, UAVObjEventCallback cb, uint16_t periodMs); +int32_t EventPeriodicCallbackUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, uint16_t periodMs); +int32_t EventPeriodicQueueCreate(UAVObjEvent* ev, xQueueHandle queue, uint16_t periodMs); +int32_t EventPeriodicQueueUpdate(UAVObjEvent* ev, xQueueHandle queue, uint16_t periodMs); + +#endif // EVENTDISPATCHER_H diff --git a/flight/targets/UAVObjects/inc/uavobjectmanager.h b/flight/targets/UAVObjects/inc/uavobjectmanager.h index 7d774d5ae..9383e2e84 100644 --- a/flight/targets/UAVObjects/inc/uavobjectmanager.h +++ b/flight/targets/UAVObjects/inc/uavobjectmanager.h @@ -1,209 +1,209 @@ -/** - ****************************************************************************** - * @addtogroup UAVObjects OpenPilot UAVObjects - * @{ - * @addtogroup UAV Object Manager - * @brief The core UAV Objects functions, most of which are wrappered by - * autogenerated defines - * @{ - * - * @file uavobjectmanager.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include files of the uavobjectlist library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef UAVOBJECTMANAGER_H -#define UAVOBJECTMANAGER_H - -#define UAVOBJ_ALL_INSTANCES 0xFFFF -#define UAVOBJ_MAX_INSTANCES 1000 - -/* - * Shifts and masks used to read/write metadata flags. - */ -#define UAVOBJ_ACCESS_SHIFT 0 -#define UAVOBJ_GCS_ACCESS_SHIFT 1 -#define UAVOBJ_TELEMETRY_ACKED_SHIFT 2 -#define UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT 3 -#define UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT 4 -#define UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT 6 -#define UAVOBJ_UPDATE_MODE_MASK 0x3 - -typedef void* UAVObjHandle; - -/** - * Object update mode, used by multiple modules (e.g. telemetry and logger) - */ -typedef enum { - UPDATEMODE_MANUAL = 0, /** Manually update object, by calling the updated() function */ - UPDATEMODE_PERIODIC = 1, /** Automatically update object at periodic intervals */ - UPDATEMODE_ONCHANGE = 2, /** Only update object when its data changes */ - UPDATEMODE_THROTTLED = 3 /** Object is updated on change, but not more often than the interval time */ -} UAVObjUpdateMode; - -/** - * Object metadata, each object has a meta object that holds its metadata. The metadata define - * properties for each object and can be used by multiple modules (e.g. telemetry and logger) - * - * The object metadata flags are packed into a single 16 bit integer. - * The bits in the flag field are defined as: - * - * Bit(s) Name Meaning - * ------ ---- ------- - * 0 access Defines the access level for the local transactions (readonly=1 and readwrite=0) - * 1 gcsAccess Defines the access level for the local GCS transactions (readonly=1 and readwrite=0), not used in the flight s/w - * 2 telemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) - * 3 gcsTelemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) - * 4-5 telemetryUpdateMode Update mode used by the telemetry module (UAVObjUpdateMode) - * 6-7 gcsTelemetryUpdateMode Update mode used by the GCS (UAVObjUpdateMode) - */ -typedef struct { - uint8_t flags; /** Defines flags for update and logging modes and whether an update should be ACK'd (bits defined above) */ - uint16_t telemetryUpdatePeriod; /** Update period used by the telemetry module (only if telemetry mode is PERIODIC) */ - uint16_t gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ - uint16_t loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ -} __attribute__((packed)) UAVObjMetadata; - -/** - * Event types generated by the objects. - */ -typedef enum { - EV_NONE = 0x00, /** No event */ - EV_UNPACKED = 0x01, /** Object data updated by unpacking */ - EV_UPDATED = 0x02, /** Object data updated by changing the data structure */ - EV_UPDATED_MANUAL = 0x04, /** Object update event manually generated */ - EV_UPDATED_PERIODIC = 0x08, /** Object update from periodic event */ - EV_UPDATE_REQ = 0x10 /** Request to update object data */ -} UAVObjEventType; - -/** - * Helper macros for event masks - */ -#define EV_MASK_ALL 0 -#define EV_MASK_ALL_UPDATES (EV_UNPACKED | EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATED_PERIODIC) - -/** - * Access types - */ -typedef enum { - ACCESS_READWRITE = 0, - ACCESS_READONLY = 1 -} UAVObjAccessType; - -/** - * Event message, this structure is sent in the event queue each time an event is generated - */ -typedef struct { - UAVObjHandle obj; - uint16_t instId; - UAVObjEventType event; -} UAVObjEvent; - -/** - * Event callback, this function is called when an event is invoked. The function - * will be executed in the event task. The ev parameter should be copied if needed - * after the function returns. - */ -typedef void (*UAVObjEventCallback)(UAVObjEvent* ev); - -/** - * Callback used to initialize the object fields to their default values. - */ -typedef void (*UAVObjInitializeCallback)(UAVObjHandle obj_handle, uint16_t instId); - -/** - * Event manager statistics - */ -typedef struct { - uint32_t eventQueueErrors; - uint32_t eventCallbackErrors; - uint32_t lastCallbackErrorID; - uint32_t lastQueueErrorID; -} UAVObjStats; - -int32_t UAVObjInitialize(); -void UAVObjGetStats(UAVObjStats* statsOut); -void UAVObjClearStats(); -UAVObjHandle UAVObjRegister(uint32_t id, - int32_t isSingleInstance, int32_t isSettings, uint32_t numBytes, UAVObjInitializeCallback initCb); -UAVObjHandle UAVObjGetByID(uint32_t id); -uint32_t UAVObjGetID(UAVObjHandle obj); -uint32_t UAVObjGetNumBytes(UAVObjHandle obj); -uint16_t UAVObjGetNumInstances(UAVObjHandle obj); -UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj); -uint16_t UAVObjCreateInstance(UAVObjHandle obj_handle, UAVObjInitializeCallback initCb); -bool UAVObjIsSingleInstance(UAVObjHandle obj); -bool UAVObjIsMetaobject(UAVObjHandle obj); -bool UAVObjIsSettings(UAVObjHandle obj); -int32_t UAVObjUnpack(UAVObjHandle obj_handle, uint16_t instId, const uint8_t* dataIn); -int32_t UAVObjPack(UAVObjHandle obj_handle, uint16_t instId, uint8_t* dataOut); -int32_t UAVObjSave(UAVObjHandle obj_handle, uint16_t instId); -int32_t UAVObjLoad(UAVObjHandle obj_handle, uint16_t instId); -int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId); -#if defined(PIOS_INCLUDE_SDCARD) -int32_t UAVObjSaveToFile(UAVObjHandle obj_handle, uint16_t instId, FILEINFO* file); -UAVObjHandle UAVObjLoadFromFile(FILEINFO* file); -#endif -int32_t UAVObjSaveSettings(); -int32_t UAVObjLoadSettings(); -int32_t UAVObjDeleteSettings(); -int32_t UAVObjSaveMetaobjects(); -int32_t UAVObjLoadMetaobjects(); -int32_t UAVObjDeleteMetaobjects(); -int32_t UAVObjSetData(UAVObjHandle obj_handle, const void* dataIn); -int32_t UAVObjSetDataField(UAVObjHandle obj_handle, const void* dataIn, uint32_t offset, uint32_t size); -int32_t UAVObjGetData(UAVObjHandle obj_handle, void* dataOut); -int32_t UAVObjGetDataField(UAVObjHandle obj_handle, void* dataOut, uint32_t offset, uint32_t size); -int32_t UAVObjSetInstanceData(UAVObjHandle obj_handle, uint16_t instId, const void* dataIn); -int32_t UAVObjSetInstanceDataField(UAVObjHandle obj_handle, uint16_t instId, const void* dataIn, uint32_t offset, uint32_t size); -int32_t UAVObjGetInstanceData(UAVObjHandle obj_handle, uint16_t instId, void* dataOut); -int32_t UAVObjGetInstanceDataField(UAVObjHandle obj_handle, uint16_t instId, void* dataOut, uint32_t offset, uint32_t size); -int32_t UAVObjSetMetadata(UAVObjHandle obj_handle, const UAVObjMetadata* dataIn); -int32_t UAVObjGetMetadata(UAVObjHandle obj_handle, UAVObjMetadata* dataOut); -uint8_t UAVObjGetMetadataAccess(const UAVObjMetadata* dataOut); -UAVObjAccessType UAVObjGetAccess(const UAVObjMetadata* dataOut); -void UAVObjSetAccess(UAVObjMetadata* dataOut, UAVObjAccessType mode); -UAVObjAccessType UAVObjGetGcsAccess(const UAVObjMetadata* dataOut); -void UAVObjSetGcsAccess(UAVObjMetadata* dataOut, UAVObjAccessType mode); -uint8_t UAVObjGetTelemetryAcked(const UAVObjMetadata* dataOut); -void UAVObjSetTelemetryAcked( UAVObjMetadata* dataOut, uint8_t val); -uint8_t UAVObjGetGcsTelemetryAcked(const UAVObjMetadata* dataOut); -void UAVObjSetGcsTelemetryAcked(UAVObjMetadata* dataOut, uint8_t val); -UAVObjUpdateMode UAVObjGetTelemetryUpdateMode(const UAVObjMetadata* dataOut); -void UAVObjSetTelemetryUpdateMode(UAVObjMetadata* dataOut, UAVObjUpdateMode val); -UAVObjUpdateMode UAVObjGetGcsTelemetryUpdateMode(const UAVObjMetadata* dataOut); -void UAVObjSetTelemetryGcsUpdateMode(UAVObjMetadata* dataOut, UAVObjUpdateMode val); -int8_t UAVObjReadOnly(UAVObjHandle obj); -int32_t UAVObjConnectQueue(UAVObjHandle obj_handle, xQueueHandle queue, uint8_t eventMask); -int32_t UAVObjDisconnectQueue(UAVObjHandle obj_handle, xQueueHandle queue); -int32_t UAVObjConnectCallback(UAVObjHandle obj_handle, UAVObjEventCallback cb, uint8_t eventMask); -int32_t UAVObjDisconnectCallback(UAVObjHandle obj_handle, UAVObjEventCallback cb); -void UAVObjRequestUpdate(UAVObjHandle obj); -void UAVObjRequestInstanceUpdate(UAVObjHandle obj_handle, uint16_t instId); -void UAVObjUpdated(UAVObjHandle obj); -void UAVObjInstanceUpdated(UAVObjHandle obj_handle, uint16_t instId); -void UAVObjIterate(void (*iterator)(UAVObjHandle obj)); - -#endif // UAVOBJECTMANAGER_H - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup UAVObjects OpenPilot UAVObjects + * @{ + * @addtogroup UAV Object Manager + * @brief The core UAV Objects functions, most of which are wrappered by + * autogenerated defines + * @{ + * + * @file uavobjectmanager.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Include files of the uavobjectlist library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef UAVOBJECTMANAGER_H +#define UAVOBJECTMANAGER_H + +#define UAVOBJ_ALL_INSTANCES 0xFFFF +#define UAVOBJ_MAX_INSTANCES 1000 + +/* + * Shifts and masks used to read/write metadata flags. + */ +#define UAVOBJ_ACCESS_SHIFT 0 +#define UAVOBJ_GCS_ACCESS_SHIFT 1 +#define UAVOBJ_TELEMETRY_ACKED_SHIFT 2 +#define UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT 3 +#define UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT 4 +#define UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT 6 +#define UAVOBJ_UPDATE_MODE_MASK 0x3 + +typedef void* UAVObjHandle; + +/** + * Object update mode, used by multiple modules (e.g. telemetry and logger) + */ +typedef enum { + UPDATEMODE_MANUAL = 0, /** Manually update object, by calling the updated() function */ + UPDATEMODE_PERIODIC = 1, /** Automatically update object at periodic intervals */ + UPDATEMODE_ONCHANGE = 2, /** Only update object when its data changes */ + UPDATEMODE_THROTTLED = 3 /** Object is updated on change, but not more often than the interval time */ +} UAVObjUpdateMode; + +/** + * Object metadata, each object has a meta object that holds its metadata. The metadata define + * properties for each object and can be used by multiple modules (e.g. telemetry and logger) + * + * The object metadata flags are packed into a single 16 bit integer. + * The bits in the flag field are defined as: + * + * Bit(s) Name Meaning + * ------ ---- ------- + * 0 access Defines the access level for the local transactions (readonly=1 and readwrite=0) + * 1 gcsAccess Defines the access level for the local GCS transactions (readonly=1 and readwrite=0), not used in the flight s/w + * 2 telemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 3 gcsTelemetryAcked Defines if an ack is required for the transactions of this object (1:acked, 0:not acked) + * 4-5 telemetryUpdateMode Update mode used by the telemetry module (UAVObjUpdateMode) + * 6-7 gcsTelemetryUpdateMode Update mode used by the GCS (UAVObjUpdateMode) + */ +typedef struct { + uint8_t flags; /** Defines flags for update and logging modes and whether an update should be ACK'd (bits defined above) */ + uint16_t telemetryUpdatePeriod; /** Update period used by the telemetry module (only if telemetry mode is PERIODIC) */ + uint16_t gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ + uint16_t loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ +} __attribute__((packed)) UAVObjMetadata; + +/** + * Event types generated by the objects. + */ +typedef enum { + EV_NONE = 0x00, /** No event */ + EV_UNPACKED = 0x01, /** Object data updated by unpacking */ + EV_UPDATED = 0x02, /** Object data updated by changing the data structure */ + EV_UPDATED_MANUAL = 0x04, /** Object update event manually generated */ + EV_UPDATED_PERIODIC = 0x08, /** Object update from periodic event */ + EV_UPDATE_REQ = 0x10 /** Request to update object data */ +} UAVObjEventType; + +/** + * Helper macros for event masks + */ +#define EV_MASK_ALL 0 +#define EV_MASK_ALL_UPDATES (EV_UNPACKED | EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATED_PERIODIC) + +/** + * Access types + */ +typedef enum { + ACCESS_READWRITE = 0, + ACCESS_READONLY = 1 +} UAVObjAccessType; + +/** + * Event message, this structure is sent in the event queue each time an event is generated + */ +typedef struct { + UAVObjHandle obj; + uint16_t instId; + UAVObjEventType event; +} UAVObjEvent; + +/** + * Event callback, this function is called when an event is invoked. The function + * will be executed in the event task. The ev parameter should be copied if needed + * after the function returns. + */ +typedef void (*UAVObjEventCallback)(UAVObjEvent* ev); + +/** + * Callback used to initialize the object fields to their default values. + */ +typedef void (*UAVObjInitializeCallback)(UAVObjHandle obj_handle, uint16_t instId); + +/** + * Event manager statistics + */ +typedef struct { + uint32_t eventQueueErrors; + uint32_t eventCallbackErrors; + uint32_t lastCallbackErrorID; + uint32_t lastQueueErrorID; +} UAVObjStats; + +int32_t UAVObjInitialize(); +void UAVObjGetStats(UAVObjStats* statsOut); +void UAVObjClearStats(); +UAVObjHandle UAVObjRegister(uint32_t id, + int32_t isSingleInstance, int32_t isSettings, uint32_t numBytes, UAVObjInitializeCallback initCb); +UAVObjHandle UAVObjGetByID(uint32_t id); +uint32_t UAVObjGetID(UAVObjHandle obj); +uint32_t UAVObjGetNumBytes(UAVObjHandle obj); +uint16_t UAVObjGetNumInstances(UAVObjHandle obj); +UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj); +uint16_t UAVObjCreateInstance(UAVObjHandle obj_handle, UAVObjInitializeCallback initCb); +bool UAVObjIsSingleInstance(UAVObjHandle obj); +bool UAVObjIsMetaobject(UAVObjHandle obj); +bool UAVObjIsSettings(UAVObjHandle obj); +int32_t UAVObjUnpack(UAVObjHandle obj_handle, uint16_t instId, const uint8_t* dataIn); +int32_t UAVObjPack(UAVObjHandle obj_handle, uint16_t instId, uint8_t* dataOut); +int32_t UAVObjSave(UAVObjHandle obj_handle, uint16_t instId); +int32_t UAVObjLoad(UAVObjHandle obj_handle, uint16_t instId); +int32_t UAVObjDelete(UAVObjHandle obj_handle, uint16_t instId); +#if defined(PIOS_INCLUDE_SDCARD) +int32_t UAVObjSaveToFile(UAVObjHandle obj_handle, uint16_t instId, FILEINFO* file); +UAVObjHandle UAVObjLoadFromFile(FILEINFO* file); +#endif +int32_t UAVObjSaveSettings(); +int32_t UAVObjLoadSettings(); +int32_t UAVObjDeleteSettings(); +int32_t UAVObjSaveMetaobjects(); +int32_t UAVObjLoadMetaobjects(); +int32_t UAVObjDeleteMetaobjects(); +int32_t UAVObjSetData(UAVObjHandle obj_handle, const void* dataIn); +int32_t UAVObjSetDataField(UAVObjHandle obj_handle, const void* dataIn, uint32_t offset, uint32_t size); +int32_t UAVObjGetData(UAVObjHandle obj_handle, void* dataOut); +int32_t UAVObjGetDataField(UAVObjHandle obj_handle, void* dataOut, uint32_t offset, uint32_t size); +int32_t UAVObjSetInstanceData(UAVObjHandle obj_handle, uint16_t instId, const void* dataIn); +int32_t UAVObjSetInstanceDataField(UAVObjHandle obj_handle, uint16_t instId, const void* dataIn, uint32_t offset, uint32_t size); +int32_t UAVObjGetInstanceData(UAVObjHandle obj_handle, uint16_t instId, void* dataOut); +int32_t UAVObjGetInstanceDataField(UAVObjHandle obj_handle, uint16_t instId, void* dataOut, uint32_t offset, uint32_t size); +int32_t UAVObjSetMetadata(UAVObjHandle obj_handle, const UAVObjMetadata* dataIn); +int32_t UAVObjGetMetadata(UAVObjHandle obj_handle, UAVObjMetadata* dataOut); +uint8_t UAVObjGetMetadataAccess(const UAVObjMetadata* dataOut); +UAVObjAccessType UAVObjGetAccess(const UAVObjMetadata* dataOut); +void UAVObjSetAccess(UAVObjMetadata* dataOut, UAVObjAccessType mode); +UAVObjAccessType UAVObjGetGcsAccess(const UAVObjMetadata* dataOut); +void UAVObjSetGcsAccess(UAVObjMetadata* dataOut, UAVObjAccessType mode); +uint8_t UAVObjGetTelemetryAcked(const UAVObjMetadata* dataOut); +void UAVObjSetTelemetryAcked( UAVObjMetadata* dataOut, uint8_t val); +uint8_t UAVObjGetGcsTelemetryAcked(const UAVObjMetadata* dataOut); +void UAVObjSetGcsTelemetryAcked(UAVObjMetadata* dataOut, uint8_t val); +UAVObjUpdateMode UAVObjGetTelemetryUpdateMode(const UAVObjMetadata* dataOut); +void UAVObjSetTelemetryUpdateMode(UAVObjMetadata* dataOut, UAVObjUpdateMode val); +UAVObjUpdateMode UAVObjGetGcsTelemetryUpdateMode(const UAVObjMetadata* dataOut); +void UAVObjSetTelemetryGcsUpdateMode(UAVObjMetadata* dataOut, UAVObjUpdateMode val); +int8_t UAVObjReadOnly(UAVObjHandle obj); +int32_t UAVObjConnectQueue(UAVObjHandle obj_handle, xQueueHandle queue, uint8_t eventMask); +int32_t UAVObjDisconnectQueue(UAVObjHandle obj_handle, xQueueHandle queue); +int32_t UAVObjConnectCallback(UAVObjHandle obj_handle, UAVObjEventCallback cb, uint8_t eventMask); +int32_t UAVObjDisconnectCallback(UAVObjHandle obj_handle, UAVObjEventCallback cb); +void UAVObjRequestUpdate(UAVObjHandle obj); +void UAVObjRequestInstanceUpdate(UAVObjHandle obj_handle, uint16_t instId); +void UAVObjUpdated(UAVObjHandle obj); +void UAVObjInstanceUpdated(UAVObjHandle obj_handle, uint16_t instId); +void UAVObjIterate(void (*iterator)(UAVObjHandle obj)); + +#endif // UAVOBJECTMANAGER_H + +/** + * @} + * @} + */ diff --git a/flight/targets/UAVObjects/inc/uavobjectsinittemplate.h b/flight/targets/UAVObjects/inc/uavobjectsinittemplate.h index ec11c47ad..29264f5fe 100644 --- a/flight/targets/UAVObjects/inc/uavobjectsinittemplate.h +++ b/flight/targets/UAVObjects/inc/uavobjectsinittemplate.h @@ -1,34 +1,34 @@ -/** - ****************************************************************************** - * - * @file uavobjectsinit.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Initialize all objects. - * This file is automatically updated by the parser. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef UAVOBJECTSINIT_H -#define UAVOBJECTSINIT_H - -void UAVObjectsInitializeAll(); - -#define UAVOBJECTS_LARGEST $(SIZECALCULATION) - -#endif // UAVOBJECTSINIT_H +/** + ****************************************************************************** + * + * @file uavobjectsinit.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Initialize all objects. + * This file is automatically updated by the parser. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef UAVOBJECTSINIT_H +#define UAVOBJECTSINIT_H + +void UAVObjectsInitializeAll(); + +#define UAVOBJECTS_LARGEST $(SIZECALCULATION) + +#endif // UAVOBJECTSINIT_H diff --git a/flight/targets/UAVObjects/inc/uavobjecttemplate.h b/flight/targets/UAVObjects/inc/uavobjecttemplate.h index 8bbbda12a..8aee9ded0 100644 --- a/flight/targets/UAVObjects/inc/uavobjecttemplate.h +++ b/flight/targets/UAVObjects/inc/uavobjecttemplate.h @@ -1,104 +1,104 @@ -/** - ****************************************************************************** - * @addtogroup UAVObjects OpenPilot UAVObjects - * @{ - * @addtogroup $(NAME) $(NAME) - * @brief $(DESCRIPTION) - * - * Autogenerated files and functions for $(NAME) Object - - * @{ - * - * @file $(NAMELC).h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Implementation of the $(NAME) object. This file has been - * automatically generated by the UAVObjectGenerator. - * - * @note Object definition file: $(XMLFILE). - * This is an automatically generated file. - * DO NOT modify manually. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef $(NAMEUC)_H -#define $(NAMEUC)_H - -// Object constants -#define $(NAMEUC)_OBJID $(OBJIDHEX) -#define $(NAMEUC)_ISSINGLEINST $(ISSINGLEINST) -#define $(NAMEUC)_ISSETTINGS $(ISSETTINGS) -#define $(NAMEUC)_NUMBYTES sizeof($(NAME)Data) - -// Generic interface functions -int32_t $(NAME)Initialize(); -UAVObjHandle $(NAME)Handle(); -void $(NAME)SetDefaults(UAVObjHandle obj, uint16_t instId); - -// Object data -typedef struct { -$(DATAFIELDS) -} __attribute__((packed)) $(NAME)Data; - -// Typesafe Object access functions -/** - * @function $(NAME)Get(dataOut) - * @brief Populate a $(NAME)Data object - * @param[out] dataOut - */ -static inline int32_t $(NAME)Get($(NAME)Data *dataOut) { return UAVObjGetData($(NAME)Handle(), dataOut); } - -static inline int32_t $(NAME)Set(const $(NAME)Data *dataIn) { return UAVObjSetData($(NAME)Handle(), dataIn); } - -static inline int32_t $(NAME)InstGet(uint16_t instId, $(NAME)Data *dataOut) { return UAVObjGetInstanceData($(NAME)Handle(), instId, dataOut); } - -static inline int32_t $(NAME)InstSet(uint16_t instId, const $(NAME)Data *dataIn) { return UAVObjSetInstanceData($(NAME)Handle(), instId, dataIn); } - -static inline int32_t $(NAME)ConnectQueue(xQueueHandle queue) { return UAVObjConnectQueue($(NAME)Handle(), queue, EV_MASK_ALL_UPDATES); } - -static inline int32_t $(NAME)ConnectCallback(UAVObjEventCallback cb) { return UAVObjConnectCallback($(NAME)Handle(), cb, EV_MASK_ALL_UPDATES); } - -static inline uint16_t $(NAME)CreateInstance() { return UAVObjCreateInstance($(NAME)Handle(), &$(NAME)SetDefaults); } - -static inline void $(NAME)RequestUpdate() { UAVObjRequestUpdate($(NAME)Handle()); } - -static inline void $(NAME)RequestInstUpdate(uint16_t instId) { UAVObjRequestInstanceUpdate($(NAME)Handle(), instId); } - -static inline void $(NAME)Updated() { UAVObjUpdated($(NAME)Handle()); } - -static inline void $(NAME)InstUpdated(uint16_t instId) { UAVObjInstanceUpdated($(NAME)Handle(), instId); } - -static inline int32_t $(NAME)GetMetadata(UAVObjMetadata *dataOut) { return UAVObjGetMetadata($(NAME)Handle(), dataOut); } - -static inline int32_t $(NAME)SetMetadata(const UAVObjMetadata *dataIn) { return UAVObjSetMetadata($(NAME)Handle(), dataIn); } - -static inline int8_t $(NAME)ReadOnly() { return UAVObjReadOnly($(NAME)Handle()); } - -// Field information -$(DATAFIELDINFO) - -// set/Get functions -$(SETGETFIELDSEXTERN) - -#endif // $(NAMEUC)_H - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * @addtogroup UAVObjects OpenPilot UAVObjects + * @{ + * @addtogroup $(NAME) $(NAME) + * @brief $(DESCRIPTION) + * + * Autogenerated files and functions for $(NAME) Object + + * @{ + * + * @file $(NAMELC).h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Implementation of the $(NAME) object. This file has been + * automatically generated by the UAVObjectGenerator. + * + * @note Object definition file: $(XMLFILE). + * This is an automatically generated file. + * DO NOT modify manually. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef $(NAMEUC)_H +#define $(NAMEUC)_H + +// Object constants +#define $(NAMEUC)_OBJID $(OBJIDHEX) +#define $(NAMEUC)_ISSINGLEINST $(ISSINGLEINST) +#define $(NAMEUC)_ISSETTINGS $(ISSETTINGS) +#define $(NAMEUC)_NUMBYTES sizeof($(NAME)Data) + +// Generic interface functions +int32_t $(NAME)Initialize(); +UAVObjHandle $(NAME)Handle(); +void $(NAME)SetDefaults(UAVObjHandle obj, uint16_t instId); + +// Object data +typedef struct { +$(DATAFIELDS) +} __attribute__((packed)) $(NAME)Data; + +// Typesafe Object access functions +/** + * @function $(NAME)Get(dataOut) + * @brief Populate a $(NAME)Data object + * @param[out] dataOut + */ +static inline int32_t $(NAME)Get($(NAME)Data *dataOut) { return UAVObjGetData($(NAME)Handle(), dataOut); } + +static inline int32_t $(NAME)Set(const $(NAME)Data *dataIn) { return UAVObjSetData($(NAME)Handle(), dataIn); } + +static inline int32_t $(NAME)InstGet(uint16_t instId, $(NAME)Data *dataOut) { return UAVObjGetInstanceData($(NAME)Handle(), instId, dataOut); } + +static inline int32_t $(NAME)InstSet(uint16_t instId, const $(NAME)Data *dataIn) { return UAVObjSetInstanceData($(NAME)Handle(), instId, dataIn); } + +static inline int32_t $(NAME)ConnectQueue(xQueueHandle queue) { return UAVObjConnectQueue($(NAME)Handle(), queue, EV_MASK_ALL_UPDATES); } + +static inline int32_t $(NAME)ConnectCallback(UAVObjEventCallback cb) { return UAVObjConnectCallback($(NAME)Handle(), cb, EV_MASK_ALL_UPDATES); } + +static inline uint16_t $(NAME)CreateInstance() { return UAVObjCreateInstance($(NAME)Handle(), &$(NAME)SetDefaults); } + +static inline void $(NAME)RequestUpdate() { UAVObjRequestUpdate($(NAME)Handle()); } + +static inline void $(NAME)RequestInstUpdate(uint16_t instId) { UAVObjRequestInstanceUpdate($(NAME)Handle(), instId); } + +static inline void $(NAME)Updated() { UAVObjUpdated($(NAME)Handle()); } + +static inline void $(NAME)InstUpdated(uint16_t instId) { UAVObjInstanceUpdated($(NAME)Handle(), instId); } + +static inline int32_t $(NAME)GetMetadata(UAVObjMetadata *dataOut) { return UAVObjGetMetadata($(NAME)Handle(), dataOut); } + +static inline int32_t $(NAME)SetMetadata(const UAVObjMetadata *dataIn) { return UAVObjSetMetadata($(NAME)Handle(), dataIn); } + +static inline int8_t $(NAME)ReadOnly() { return UAVObjReadOnly($(NAME)Handle()); } + +// Field information +$(DATAFIELDINFO) + +// set/Get functions +$(SETGETFIELDSEXTERN) + +#endif // $(NAMEUC)_H + +/** + * @} + * @} + */ diff --git a/flight/targets/UAVObjects/uavobjectsinittemplate.c b/flight/targets/UAVObjects/uavobjectsinittemplate.c index 75a104d18..724156047 100644 --- a/flight/targets/UAVObjects/uavobjectsinittemplate.c +++ b/flight/targets/UAVObjects/uavobjectsinittemplate.c @@ -1,40 +1,40 @@ -/** - ****************************************************************************** - * - * @file uavobjectsinit.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Initialize all objects. - * Automatically generated by the UAVObjectGenerator. - * - * @note This is an automatically generated file. - * DO NOT modify manually. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -$(OBJINC) - -/** - * Function used to initialize the first instance of each object. - * This file is automatically updated by the UAVObjectGenerator. - */ -void UAVObjectsInitializeAll() -{ -$(OBJINIT) -} +/** + ****************************************************************************** + * + * @file uavobjectsinit.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Initialize all objects. + * Automatically generated by the UAVObjectGenerator. + * + * @note This is an automatically generated file. + * DO NOT modify manually. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +$(OBJINC) + +/** + * Function used to initialize the first instance of each object. + * This file is automatically updated by the UAVObjectGenerator. + */ +void UAVObjectsInitializeAll() +{ +$(OBJINIT) +} diff --git a/flight/targets/UAVObjects/uavobjecttemplate.c b/flight/targets/UAVObjects/uavobjecttemplate.c index f8db8a024..69b0c94d1 100644 --- a/flight/targets/UAVObjects/uavobjecttemplate.c +++ b/flight/targets/UAVObjects/uavobjecttemplate.c @@ -1,117 +1,117 @@ -/** - ****************************************************************************** - * @addtogroup UAVObjects OpenPilot UAVObjects - * @{ - * @addtogroup $(NAME) $(NAME) - * @brief $(DESCRIPTION) - * - * Autogenerated files and functions for $(NAME) Object - * @{ - * - * @file $(NAMELC).c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Implementation of the $(NAME) object. This file has been - * automatically generated by the UAVObjectGenerator. - * - * @note Object definition file: $(XMLFILE). - * This is an automatically generated file. - * DO NOT modify manually. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "$(NAMELC).h" - -// Private variables -static UAVObjHandle handle = NULL; - -/** - * Initialize object. - * \return 0 Success - * \return -1 Failure to initialize or -2 for already initialized - */ -int32_t $(NAME)Initialize(void) -{ - // Don't set the handle to null if already registered - if(UAVObjGetByID($(NAMEUC)_OBJID) != NULL) - return -2; - - // Register object with the object manager - handle = UAVObjRegister($(NAMEUC)_OBJID, - $(NAMEUC)_ISSINGLEINST, $(NAMEUC)_ISSETTINGS, $(NAMEUC)_NUMBYTES, &$(NAME)SetDefaults); - - // Done - if (handle != 0) - { - return 0; - } - else - { - return -1; - } -} - -/** - * Initialize object fields and metadata with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ -void $(NAME)SetDefaults(UAVObjHandle obj, uint16_t instId) -{ - $(NAME)Data data; - UAVObjMetadata metadata; - - // Initialize object fields to their default values - UAVObjGetInstanceData(obj, instId, &data); - memset(&data, 0, sizeof($(NAME)Data)); -$(INITFIELDS) - UAVObjSetInstanceData(obj, instId, &data); - - // Initialize object metadata to their default values - metadata.flags = - $(FLIGHTACCESS) << UAVOBJ_ACCESS_SHIFT | - $(GCSACCESS) << UAVOBJ_GCS_ACCESS_SHIFT | - $(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT | - $(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - $(FLIGHTTELEM_UPDATEMODE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - $(GCSTELEM_UPDATEMODE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.telemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); - UAVObjSetMetadata(obj, &metadata); -} - -/** - * Get object handle - */ -UAVObjHandle $(NAME)Handle() -{ - return handle; -} - -/** - * Get/Set object Functions - */ -$(SETGETFIELDS) - -/** - * @} - */ - +/** + ****************************************************************************** + * @addtogroup UAVObjects OpenPilot UAVObjects + * @{ + * @addtogroup $(NAME) $(NAME) + * @brief $(DESCRIPTION) + * + * Autogenerated files and functions for $(NAME) Object + * @{ + * + * @file $(NAMELC).c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Implementation of the $(NAME) object. This file has been + * automatically generated by the UAVObjectGenerator. + * + * @note Object definition file: $(XMLFILE). + * This is an automatically generated file. + * DO NOT modify manually. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "$(NAMELC).h" + +// Private variables +static UAVObjHandle handle = NULL; + +/** + * Initialize object. + * \return 0 Success + * \return -1 Failure to initialize or -2 for already initialized + */ +int32_t $(NAME)Initialize(void) +{ + // Don't set the handle to null if already registered + if(UAVObjGetByID($(NAMEUC)_OBJID) != NULL) + return -2; + + // Register object with the object manager + handle = UAVObjRegister($(NAMEUC)_OBJID, + $(NAMEUC)_ISSINGLEINST, $(NAMEUC)_ISSETTINGS, $(NAMEUC)_NUMBYTES, &$(NAME)SetDefaults); + + // Done + if (handle != 0) + { + return 0; + } + else + { + return -1; + } +} + +/** + * Initialize object fields and metadata with the default values. + * If a default value is not specified the object fields + * will be initialized to zero. + */ +void $(NAME)SetDefaults(UAVObjHandle obj, uint16_t instId) +{ + $(NAME)Data data; + UAVObjMetadata metadata; + + // Initialize object fields to their default values + UAVObjGetInstanceData(obj, instId, &data); + memset(&data, 0, sizeof($(NAME)Data)); +$(INITFIELDS) + UAVObjSetInstanceData(obj, instId, &data); + + // Initialize object metadata to their default values + metadata.flags = + $(FLIGHTACCESS) << UAVOBJ_ACCESS_SHIFT | + $(GCSACCESS) << UAVOBJ_GCS_ACCESS_SHIFT | + $(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT | + $(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + $(FLIGHTTELEM_UPDATEMODE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + $(GCSTELEM_UPDATEMODE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.telemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); + metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); + metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + UAVObjSetMetadata(obj, &metadata); +} + +/** + * Get object handle + */ +UAVObjHandle $(NAME)Handle() +{ + return handle; +} + +/** + * Get/Set object Functions + */ +$(SETGETFIELDS) + +/** + * @} + */ + diff --git a/ground/.gitattributes b/ground/.gitattributes new file mode 100644 index 000000000..a9834a726 --- /dev/null +++ b/ground/.gitattributes @@ -0,0 +1,17 @@ +# +# Ground source code files should always have CRLF line endings by agreement +# http://wiki.openpilot.org/display/Doc/Coding+Style +# + +*.c text eol=crlf +*.cpp text eol=crlf +*.h text eol=crlf +*.hpp text eol=crlf + +*.ui text eol=crlf +*.qrc text eol=crlf +*.qml text eol=crlf +*.pluginspec text eol=crlf + +*.pri text eol=crlf +*.pro text eol=crlf diff --git a/ground/ground.pro b/ground/ground.pro index 3d7aeef0f..e443006ec 100644 --- a/ground/ground.pro +++ b/ground/ground.pro @@ -1,48 +1,51 @@ # -# Top level Qt-Creator project file +# Top level Qt-Creator project file for OpenPilot GCS +# Copyright (c) 2009-2013, The OpenPilot Team, http://www.openpilot.org # - # This meta-project allows qt-creator users to open and configure a -# single project and to build all required software to produce a GCS. -# This includes regenerating all uavobject output. +# single project and build all required software to produce the GCS. +# This includes regenerating all uavobject-synthetic files. # -# NOTE: to use this meta-project, you MUST perform these steps once +# NOTE: to use this meta-project you MUST perform these steps once # for each source tree checkout: # - Open /ground/ground.pro in qt-creator # - Select the "Projects" tab -# - Under Build Settings/General heading, click "Show Details" -# - Activate "Shadow Build" -# - Set your Build Directory to /build/ground -# -# = the full path to the base of your git source tree which +# - Under Build Settings/General heading activate "Shadow build" +# - Set "Build directory" below to /build +# Here = the full path to the base of your git source tree which # should contain "flight", "ground", etc. - -# There is a small problem with dependencies. qmake needs synthetic +# +# NOTE: only debug qt-creator builds are supported on Windows. +# Release builds may fail because it seems that qt-creator does not +# define QTMINGW variable used to copy MinGW DLLs in release builds. +# +# There is a minor problem with dependencies. qmake needs synthetic # files when it generates GCS Makefiles. But we do not have -# uavobjgenerator at that time (on the 1st build). So we use the -# following trick: at make stage in uavobjects we rerun qmake for -# openpilotgcs.pro and regenerate GCS Makefiles using just built -# synthetic files. It takes some extra time but solves the -# dependency problem. +# uavobjgenerator built yet. So we use the following trick: at make +# stage in uavobject-synthetics we rerun qmake for openpilotgcs.pro +# and regenerate GCS Makefiles using just built synthetic files. +# It takes some extra time but solves the dependency problem. +# +# Please note that this meta-project is only intended to be used by +# qt-creator users. Top level Makefile handles all dependencies itself +# and does not use ground.pro. -# Please note that this meta-project intended only for qt-creator -# users. Top level Makefile handles all dependencies itself and -# doesn't use ground.pro. +message("Make sure you have shadow build path set as noted in ground.pro. Build will fail otherwise") TEMPLATE = subdirs SUBDIRS = \ sub_openpilotgcs \ - sub_uavobjects \ + sub_uavobject-synthetics \ sub_uavobjgenerator # uavobjgenerator sub_uavobjgenerator.subdir = uavobjgenerator -# uavobjects -sub_uavobjects.subdir = uavobjects -sub_uavobjects.depends = sub_uavobjgenerator +# uavobject-synthetics +sub_uavobject-synthetics.subdir = uavobject-synthetics +sub_uavobject-synthetics.depends = sub_uavobjgenerator # openpilotgcs sub_openpilotgcs.subdir = openpilotgcs -sub_openpilotgcs.depends = sub_uavobjects +sub_openpilotgcs.depends = sub_uavobject-synthetics diff --git a/ground/openpilotgcs/bin/bin.pro b/ground/openpilotgcs/bin/bin.pro index 3988a81e3..c8df2097d 100644 --- a/ground/openpilotgcs/bin/bin.pro +++ b/ground/openpilotgcs/bin/bin.pro @@ -1,14 +1,14 @@ -include(../openpilotgcs.pri) - -TEMPLATE = app -TARGET = $$GCS_APP_WRAPPER -OBJECTS_DIR = - -PRE_TARGETDEPS = $$PWD/openpilotgcs - -QMAKE_LINK = cp $$PWD/openpilotgcs $@ && : IGNORE REST - -QMAKE_CLEAN = $$GCS_APP_WRAPPER - -target.path = /bin -INSTALLS += target +include(../openpilotgcs.pri) + +TEMPLATE = app +TARGET = $$GCS_APP_WRAPPER +OBJECTS_DIR = + +PRE_TARGETDEPS = $$PWD/openpilotgcs + +QMAKE_LINK = cp $$PWD/openpilotgcs $@ && : IGNORE REST + +QMAKE_CLEAN = $$GCS_APP_WRAPPER + +target.path = /bin +INSTALLS += target diff --git a/ground/openpilotgcs/copydata.pro b/ground/openpilotgcs/copydata.pro index 23a3d5ba6..4c3289264 100644 --- a/ground/openpilotgcs/copydata.pro +++ b/ground/openpilotgcs/copydata.pro @@ -1,83 +1,83 @@ -include(openpilotgcs.pri) - -TEMPLATE = subdirs - -# Copy Qt runtime libraries into the build directory (to run or package) -equals(copydata, 1) { - - # Windows release only, no debug target DLLs ending with 'd' - # It is assumed that SDL.dll can be found in the same directory as mingw32-make.exe - win32:CONFIG(release, debug|release) { - - # copy Qt DLLs and phonon4 - QT_DLLS = phonon4.dll \ - QtCore4.dll \ - QtGui4.dll \ - QtNetwork4.dll \ - QtOpenGL4.dll \ - QtSql4.dll \ - QtSvg4.dll \ - QtTest4.dll \ - QtXml4.dll \ - QtDeclarative4.dll \ - QtXmlPatterns4.dll \ - QtScript4.dll - for(dll, QT_DLLS) { - data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() - } - - # copy MinGW DLLs - MINGW_DLLS = libgcc_s_dw2-1.dll \ - mingwm10.dll - for(dll, MINGW_DLLS) { - data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(QTMINGW)/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() - } - - # copy iconengines - QT_ICONENGINE_DLLS = qsvgicon4.dll - data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/iconengines\") $$addNewline() - for(dll, QT_ICONENGINE_DLLS) { - data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_PLUGINS]/iconengines/$$dll\") $$targetPath(\"$$GCS_APP_PATH/iconengines/$$dll\") $$addNewline() - } - - # copy imageformats - QT_IMAGEFORMAT_DLLS = qgif4.dll qico4.dll qjpeg4.dll qmng4.dll qsvg4.dll qtiff4.dll - data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/imageformats\") $$addNewline() - for(dll, QT_IMAGEFORMAT_DLLS) { - data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_PLUGINS]/imageformats/$$dll\") $$targetPath(\"$$GCS_APP_PATH/imageformats/$$dll\") $$addNewline() - } - - # copy phonon_backend - QT_PHONON_BACKEND_DLLS = phonon_ds94.dll - data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/phonon_backend\") $$addNewline() - for(dll, QT_PHONON_BACKEND_DLLS) { - data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_PLUGINS]/phonon_backend/$$dll\") $$targetPath(\"$$GCS_APP_PATH/phonon_backend/$$dll\") $$addNewline() - } - - # copy sqldrivers - QT_SQLDRIVERS_DLLS = qsqlite4.dll - data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/sqldrivers\") $$addNewline() - for(dll, QT_SQLDRIVERS_DLLS) { - data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_PLUGINS]/sqldrivers/$$dll\") $$targetPath(\"$$GCS_APP_PATH/sqldrivers/$$dll\") $$addNewline() - } - - # copy SDL - Simple DirectMedia Layer (www.libsdl.org) - # Check the wiki for SDL installation, it should be copied first - # (make sure that the Qt installation path below is correct) - # - # - For qt-sdk-win-opensource-2010.05.exe: - # xcopy /s /e \bin\SDL.dll C:\Qt\2010.05\mingw\bin\SDL.dll - # xcopy /s /e \include\SDL\* C:\Qt\2010.05\mingw\include\SDL - # xcopy /s /e \lib\* C:\Qt\2010.05\mingw\lib - # - # - For Qt_SDK_Win_offline_v1_1_1_en.exe: - # xcopy /s /e \bin\SDL.dll C:\QtSDK\Desktop\Qt\4.7.3\mingw\bin\SDL.dll - # xcopy /s /e \include\SDL\* C:\QtSDK\Desktop\Qt\4.7.3\mingw\include\SDL - # xcopy /s /e \lib\* C:\QtSDK\Desktop\Qt\4.7.3\mingw\lib - SDL_DLL = SDL.dll - data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(QTMINGW)/$$SDL_DLL\") $$targetPath(\"$$GCS_APP_PATH/$$SDL_DLL\") $$addNewline() - - data_copy.target = FORCE - QMAKE_EXTRA_TARGETS += data_copy - } -} +include(openpilotgcs.pri) + +TEMPLATE = subdirs + +# Copy Qt runtime libraries into the build directory (to run or package) +equals(copydata, 1) { + + # Windows release only, no debug target DLLs ending with 'd' + # It is assumed that SDL.dll can be found in the same directory as mingw32-make.exe + win32:CONFIG(release, debug|release) { + + # copy Qt DLLs and phonon4 + QT_DLLS = phonon4.dll \ + QtCore4.dll \ + QtGui4.dll \ + QtNetwork4.dll \ + QtOpenGL4.dll \ + QtSql4.dll \ + QtSvg4.dll \ + QtTest4.dll \ + QtXml4.dll \ + QtDeclarative4.dll \ + QtXmlPatterns4.dll \ + QtScript4.dll + for(dll, QT_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() + } + + # copy MinGW DLLs + MINGW_DLLS = libgcc_s_dw2-1.dll \ + mingwm10.dll + for(dll, MINGW_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(QTMINGW)/$$dll\") $$targetPath(\"$$GCS_APP_PATH/$$dll\") $$addNewline() + } + + # copy iconengines + QT_ICONENGINE_DLLS = qsvgicon4.dll + data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/iconengines\") $$addNewline() + for(dll, QT_ICONENGINE_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_PLUGINS]/iconengines/$$dll\") $$targetPath(\"$$GCS_APP_PATH/iconengines/$$dll\") $$addNewline() + } + + # copy imageformats + QT_IMAGEFORMAT_DLLS = qgif4.dll qico4.dll qjpeg4.dll qmng4.dll qsvg4.dll qtiff4.dll + data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/imageformats\") $$addNewline() + for(dll, QT_IMAGEFORMAT_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_PLUGINS]/imageformats/$$dll\") $$targetPath(\"$$GCS_APP_PATH/imageformats/$$dll\") $$addNewline() + } + + # copy phonon_backend + QT_PHONON_BACKEND_DLLS = phonon_ds94.dll + data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/phonon_backend\") $$addNewline() + for(dll, QT_PHONON_BACKEND_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_PLUGINS]/phonon_backend/$$dll\") $$targetPath(\"$$GCS_APP_PATH/phonon_backend/$$dll\") $$addNewline() + } + + # copy sqldrivers + QT_SQLDRIVERS_DLLS = qsqlite4.dll + data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_APP_PATH/sqldrivers\") $$addNewline() + for(dll, QT_SQLDRIVERS_DLLS) { + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_PLUGINS]/sqldrivers/$$dll\") $$targetPath(\"$$GCS_APP_PATH/sqldrivers/$$dll\") $$addNewline() + } + + # copy SDL - Simple DirectMedia Layer (www.libsdl.org) + # Check the wiki for SDL installation, it should be copied first + # (make sure that the Qt installation path below is correct) + # + # - For qt-sdk-win-opensource-2010.05.exe: + # xcopy /s /e \bin\SDL.dll C:\Qt\2010.05\mingw\bin\SDL.dll + # xcopy /s /e \include\SDL\* C:\Qt\2010.05\mingw\include\SDL + # xcopy /s /e \lib\* C:\Qt\2010.05\mingw\lib + # + # - For Qt_SDK_Win_offline_v1_1_1_en.exe: + # xcopy /s /e \bin\SDL.dll C:\QtSDK\Desktop\Qt\4.7.3\mingw\bin\SDL.dll + # xcopy /s /e \include\SDL\* C:\QtSDK\Desktop\Qt\4.7.3\mingw\include\SDL + # xcopy /s /e \lib\* C:\QtSDK\Desktop\Qt\4.7.3\mingw\lib + SDL_DLL = SDL.dll + data_copy.commands += $(COPY_FILE) $$targetPath(\"$$(QTMINGW)/$$SDL_DLL\") $$targetPath(\"$$GCS_APP_PATH/$$SDL_DLL\") $$addNewline() + + data_copy.target = FORCE + QMAKE_EXTRA_TARGETS += data_copy + } +} diff --git a/ground/openpilotgcs/openpilotgcs.pri b/ground/openpilotgcs/openpilotgcs.pri index b9da7f671..b333b5571 100644 --- a/ground/openpilotgcs/openpilotgcs.pri +++ b/ground/openpilotgcs/openpilotgcs.pri @@ -1,135 +1,135 @@ -defineReplace(cleanPath) { - win32:1 ~= s|\\\\|/|g - contains(1, ^/.*):pfx = / - else:pfx = - segs = $$split(1, /) - out = - for(seg, segs) { - equals(seg, ..):out = $$member(out, 0, -2) - else:!equals(seg, .):out += $$seg - } - return($$join(out, /, $$pfx)) -} - -defineReplace(targetPath) { - return($$replace(1, /, $$QMAKE_DIR_SEP)) -} - -defineReplace(addNewline) { - return($$escape_expand(\\n\\t)) -} - -defineReplace(qtLibraryName) { - unset(LIBRARY_NAME) - LIBRARY_NAME = $$1 - CONFIG(debug, debug|release) { - !debug_and_release|build_pass { - mac:RET = $$member(LIBRARY_NAME, 0)_debug - else:win32:RET = $$member(LIBRARY_NAME, 0)d - } - } - isEmpty(RET):RET = $$LIBRARY_NAME - return($$RET) -} - -# For use in custom compilers which just copy files -win32:i_flag = i -defineReplace(stripSrcDir) { - win32 { - !contains(1, ^.:.*):1 = $$OUT_PWD/$$1 - } else { - !contains(1, ^/.*):1 = $$OUT_PWD/$$1 - } - out = $$cleanPath($$1) - out ~= s|^$$re_escape($$PWD/)||$$i_flag - return($$out) -} - -isEmpty(TEST):CONFIG(debug, debug|release) { - !debug_and_release|build_pass { - TEST = 1 - } -} - -isEmpty(GCS_LIBRARY_BASENAME) { - GCS_LIBRARY_BASENAME = lib -} - -DEFINES += GCS_LIBRARY_BASENAME=\\\"$$GCS_LIBRARY_BASENAME\\\" - -equals(TEST, 1) { - QT +=testlib - DEFINES += WITH_TESTS -} - -#ideally, we would want a qmake.conf patch, but this does the trick... -win32:!isEmpty(QMAKE_SH):QMAKE_COPY_DIR = cp -r -f - -GCS_SOURCE_TREE = $$PWD -isEmpty(GCS_BUILD_TREE) { - sub_dir = $$_PRO_FILE_PWD_ - sub_dir ~= s,^$$re_escape($$PWD),, - GCS_BUILD_TREE = $$cleanPath($$OUT_PWD) - GCS_BUILD_TREE ~= s,$$re_escape($$sub_dir)$,, -} -GCS_APP_PATH = $$GCS_BUILD_TREE/bin -macx { - GCS_APP_TARGET = "OpenPilot GCS" - GCS_LIBRARY_PATH = $$GCS_APP_PATH/$${GCS_APP_TARGET}.app/Contents/Plugins - GCS_PLUGIN_PATH = $$GCS_LIBRARY_PATH - GCS_LIBEXEC_PATH = $$GCS_APP_PATH/$${GCS_APP_TARGET}.app/Contents/Resources - GCS_DATA_PATH = $$GCS_APP_PATH/$${GCS_APP_TARGET}.app/Contents/Resources - GCS_DATA_BASENAME = Resources - GCS_DOC_PATH = $$GCS_DATA_PATH/doc - copydata = 1 -} else { - win32 { - contains(TEMPLATE, vc.*)|contains(TEMPLATE_PREFIX, vc):vcproj = 1 - GCS_APP_TARGET = openpilotgcs - } else { - GCS_APP_WRAPPER = openpilotgcs - GCS_APP_TARGET = openpilotgcs.bin - } - GCS_LIBRARY_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/openpilotgcs - GCS_PLUGIN_PATH = $$GCS_LIBRARY_PATH/plugins - GCS_LIBEXEC_PATH = $$GCS_APP_PATH # FIXME - GCS_DATA_PATH = $$GCS_BUILD_TREE/share/openpilotgcs - GCS_DATA_BASENAME = share/openpilotgcs - GCS_DOC_PATH = $$GCS_BUILD_TREE/share/doc - !isEqual(GCS_SOURCE_TREE, $$GCS_BUILD_TREE):copydata = 1 -} - - -DEFINES += GCS_DATA_BASENAME=\\\"$$GCS_DATA_BASENAME\\\" - - -INCLUDEPATH += \ - $$GCS_SOURCE_TREE/src/libs - -DEPENDPATH += \ - $$GCS_SOURCE_TREE/src/libs - -LIBS += -L$$GCS_LIBRARY_PATH - -# DEFINES += QT_NO_CAST_FROM_ASCII -DEFINES += QT_NO_CAST_TO_ASCII -#DEFINES += QT_USE_FAST_OPERATOR_PLUS -#DEFINES += QT_USE_FAST_CONCATENATION - -unix { - CONFIG(debug, debug|release):OBJECTS_DIR = $${OUT_PWD}/.obj/debug-shared - CONFIG(release, debug|release):OBJECTS_DIR = $${OUT_PWD}/.obj/release-shared - - CONFIG(debug, debug|release):MOC_DIR = $${OUT_PWD}/.moc/debug-shared - CONFIG(release, debug|release):MOC_DIR = $${OUT_PWD}/.moc/release-shared - - RCC_DIR = $${OUT_PWD}/.rcc - UI_DIR = $${OUT_PWD}/.uic -} - -linux-g++-* { - # Bail out on non-selfcontained libraries. Just a security measure - # to prevent checking in code that does not compile on other platforms. - QMAKE_LFLAGS += -Wl,--allow-shlib-undefined -Wl,--no-undefined -} - +defineReplace(cleanPath) { + win32:1 ~= s|\\\\|/|g + contains(1, ^/.*):pfx = / + else:pfx = + segs = $$split(1, /) + out = + for(seg, segs) { + equals(seg, ..):out = $$member(out, 0, -2) + else:!equals(seg, .):out += $$seg + } + return($$join(out, /, $$pfx)) +} + +defineReplace(targetPath) { + return($$replace(1, /, $$QMAKE_DIR_SEP)) +} + +defineReplace(addNewline) { + return($$escape_expand(\\n\\t)) +} + +defineReplace(qtLibraryName) { + unset(LIBRARY_NAME) + LIBRARY_NAME = $$1 + CONFIG(debug, debug|release) { + !debug_and_release|build_pass { + mac:RET = $$member(LIBRARY_NAME, 0)_debug + else:win32:RET = $$member(LIBRARY_NAME, 0)d + } + } + isEmpty(RET):RET = $$LIBRARY_NAME + return($$RET) +} + +# For use in custom compilers which just copy files +win32:i_flag = i +defineReplace(stripSrcDir) { + win32 { + !contains(1, ^.:.*):1 = $$OUT_PWD/$$1 + } else { + !contains(1, ^/.*):1 = $$OUT_PWD/$$1 + } + out = $$cleanPath($$1) + out ~= s|^$$re_escape($$PWD/)||$$i_flag + return($$out) +} + +isEmpty(TEST):CONFIG(debug, debug|release) { + !debug_and_release|build_pass { + TEST = 1 + } +} + +isEmpty(GCS_LIBRARY_BASENAME) { + GCS_LIBRARY_BASENAME = lib +} + +DEFINES += GCS_LIBRARY_BASENAME=\\\"$$GCS_LIBRARY_BASENAME\\\" + +equals(TEST, 1) { + QT +=testlib + DEFINES += WITH_TESTS +} + +#ideally, we would want a qmake.conf patch, but this does the trick... +win32:!isEmpty(QMAKE_SH):QMAKE_COPY_DIR = cp -r -f + +GCS_SOURCE_TREE = $$PWD +isEmpty(GCS_BUILD_TREE) { + sub_dir = $$_PRO_FILE_PWD_ + sub_dir ~= s,^$$re_escape($$PWD),, + GCS_BUILD_TREE = $$cleanPath($$OUT_PWD) + GCS_BUILD_TREE ~= s,$$re_escape($$sub_dir)$,, +} +GCS_APP_PATH = $$GCS_BUILD_TREE/bin +macx { + GCS_APP_TARGET = "OpenPilot GCS" + GCS_LIBRARY_PATH = $$GCS_APP_PATH/$${GCS_APP_TARGET}.app/Contents/Plugins + GCS_PLUGIN_PATH = $$GCS_LIBRARY_PATH + GCS_LIBEXEC_PATH = $$GCS_APP_PATH/$${GCS_APP_TARGET}.app/Contents/Resources + GCS_DATA_PATH = $$GCS_APP_PATH/$${GCS_APP_TARGET}.app/Contents/Resources + GCS_DATA_BASENAME = Resources + GCS_DOC_PATH = $$GCS_DATA_PATH/doc + copydata = 1 +} else { + win32 { + contains(TEMPLATE, vc.*)|contains(TEMPLATE_PREFIX, vc):vcproj = 1 + GCS_APP_TARGET = openpilotgcs + } else { + GCS_APP_WRAPPER = openpilotgcs + GCS_APP_TARGET = openpilotgcs.bin + } + GCS_LIBRARY_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/openpilotgcs + GCS_PLUGIN_PATH = $$GCS_LIBRARY_PATH/plugins + GCS_LIBEXEC_PATH = $$GCS_APP_PATH # FIXME + GCS_DATA_PATH = $$GCS_BUILD_TREE/share/openpilotgcs + GCS_DATA_BASENAME = share/openpilotgcs + GCS_DOC_PATH = $$GCS_BUILD_TREE/share/doc + !isEqual(GCS_SOURCE_TREE, $$GCS_BUILD_TREE):copydata = 1 +} + + +DEFINES += GCS_DATA_BASENAME=\\\"$$GCS_DATA_BASENAME\\\" + + +INCLUDEPATH += \ + $$GCS_SOURCE_TREE/src/libs + +DEPENDPATH += \ + $$GCS_SOURCE_TREE/src/libs + +LIBS += -L$$GCS_LIBRARY_PATH + +# DEFINES += QT_NO_CAST_FROM_ASCII +DEFINES += QT_NO_CAST_TO_ASCII +#DEFINES += QT_USE_FAST_OPERATOR_PLUS +#DEFINES += QT_USE_FAST_CONCATENATION + +unix { + CONFIG(debug, debug|release):OBJECTS_DIR = $${OUT_PWD}/.obj/debug-shared + CONFIG(release, debug|release):OBJECTS_DIR = $${OUT_PWD}/.obj/release-shared + + CONFIG(debug, debug|release):MOC_DIR = $${OUT_PWD}/.moc/debug-shared + CONFIG(release, debug|release):MOC_DIR = $${OUT_PWD}/.moc/release-shared + + RCC_DIR = $${OUT_PWD}/.rcc + UI_DIR = $${OUT_PWD}/.uic +} + +linux-g++-* { + # Bail out on non-selfcontained libraries. Just a security measure + # to prevent checking in code that does not compile on other platforms. + QMAKE_LFLAGS += -Wl,--allow-shlib-undefined -Wl,--no-undefined +} + diff --git a/ground/openpilotgcs/openpilotgcs.pro b/ground/openpilotgcs/openpilotgcs.pro index df6b0cf86..57a5f1ecf 100644 --- a/ground/openpilotgcs/openpilotgcs.pro +++ b/ground/openpilotgcs/openpilotgcs.pro @@ -1,17 +1,22 @@ -#version check qt -contains(QT_VERSION, ^4\\.[0-5]\\..*) { - message("Cannot build OpenPilot GCS with Qt version $${QT_VERSION}.") - error("Cannot build OpenPilot GCS with Qt version $${QT_VERSION}. Use at least Qt 4.6!") -} - -include(openpilotgcs.pri) - -TEMPLATE = subdirs -CONFIG += ordered - -DEFINES += USE_PATHPLANNER - -SUBDIRS = src share copydata -unix:!macx:!isEmpty(copydata):SUBDIRS += bin - -copydata.file = copydata.pro +# +# Qmake project for the OpenPilot GCS. +# Copyright (c) 2009-2013, The OpenPilot Team, http://www.openpilot.org +# + +#version check qt +contains(QT_VERSION, ^4\\.[0-5]\\..*) { + message("Cannot build OpenPilot GCS with Qt version $${QT_VERSION}.") + error("Cannot build OpenPilot GCS with Qt version $${QT_VERSION}. Use at least Qt 4.6!") +} + +include(openpilotgcs.pri) + +TEMPLATE = subdirs +CONFIG += ordered + +DEFINES += USE_PATHPLANNER + +SUBDIRS = src share copydata +unix:!macx:!isEmpty(copydata):SUBDIRS += bin + +copydata.file = copydata.pro diff --git a/ground/openpilotgcs/share/openpilotgcs/translations/translations.pro b/ground/openpilotgcs/share/openpilotgcs/translations/translations.pro index 2ebd0d4a5..95443456c 100644 --- a/ground/openpilotgcs/share/openpilotgcs/translations/translations.pro +++ b/ground/openpilotgcs/share/openpilotgcs/translations/translations.pro @@ -1,89 +1,89 @@ -include(../../../openpilotgcs.pri) - +include(../../../openpilotgcs.pri) + # Commented languages with outdated translations # Allow removing the 'C' language in default config files at first start. # Need to be uncommented for update in all languages files (make ts) -LANGUAGES = fr # de es ru zh_CN - -# var, prepend, append -defineReplace(prependAll) { - for(a,$$1):result += $$2$${a}$$3 - return($$result) -} - -XMLPATTERNS = $$targetPath($$[QT_INSTALL_BINS]/xmlpatterns) -LUPDATE = $$targetPath($$[QT_INSTALL_BINS]/lupdate) -locations relative -no-ui-lines -no-sort -noobsolete -LRELEASE = $$targetPath($$[QT_INSTALL_BINS]/lrelease) - -TRANSLATIONS = $$prependAll(LANGUAGES, $$PWD/openpilotgcs_,.ts) - -MIME_TR_H = $$PWD/mime_tr.h - -contains(QT_VERSION, ^4\\.[0-5]\\..*) { - ts.commands = @echo This Qt version is too old for the ts target. Need Qt 4.6+. -} else { - for(dir, $$list($$files($$GCS_SOURCE_TREE/src/plugins/*))):MIMETYPES_FILES += $$files($$dir/*.mimetypes.xml) - MIMETYPES_FILES = \"$$join(MIMETYPES_FILES, \", \")\" - QMAKE_SUBSTITUTES += extract-mimetypes.xq.in - ts.commands += \ - $$XMLPATTERNS -output $$MIME_TR_H $$PWD/extract-mimetypes.xq && \ - (cd $$GCS_SOURCE_TREE && $$LUPDATE src $$MIME_TR_H -ts $$TRANSLATIONS) && \ - $$QMAKE_DEL_FILE $$targetPath($$MIME_TR_H) -} -QMAKE_EXTRA_TARGETS += ts - -TEMPLATE = app -TARGET = phony_target2 -CONFIG -= qt -QT = -LIBS = - -updateqm.input = TRANSLATIONS -updateqm.output = $$GCS_DATA_PATH/translations/${QMAKE_FILE_BASE}.qm -isEmpty(vcproj):updateqm.variable_out = PRE_TARGETDEPS -updateqm.commands = $$LRELEASE ${QMAKE_FILE_IN} -qm ${QMAKE_FILE_OUT} -updateqm.name = LRELEASE ${QMAKE_FILE_IN} -updateqm.CONFIG += no_link -QMAKE_EXTRA_COMPILERS += updateqm - -isEmpty(vcproj) { - QMAKE_LINK = @: IGNORE THIS LINE - OBJECTS_DIR = - win32:CONFIG -= embed_manifest_exe -} else { - CONFIG += console - PHONY_DEPS = . - phony_src.input = PHONY_DEPS - phony_src.output = phony.c - phony_src.variable_out = GENERATED_SOURCES - phony_src.commands = echo int main() { return 0; } > phony.c - phony_src.name = CREATE phony.c - phony_src.CONFIG += combine - QMAKE_EXTRA_COMPILERS += phony_src -} - -qmfiles.files = $$prependAll(LANGUAGES, $$OUT_PWD/openpilotgcs_,.qm) -qmfiles.path = /share/openpilotgcs/translations -qmfiles.CONFIG += no_check_exist -INSTALLS += qmfiles - -#========= begin block copying qt_*.qm files ========== -win32 { - defineReplace(QtQmExists) { - for(lang,$$1) { - qm_file = $$[QT_INSTALL_TRANSLATIONS]/qt_$${lang}.qm - exists($$qm_file) : result += $$qm_file - } - return($$result) - } - QT_TRANSLATIONS = $$QtQmExists(LANGUAGES) - - copyQT_QMs.input = QT_TRANSLATIONS - copyQT_QMs.output = $$GCS_DATA_PATH/translations/${QMAKE_FILE_BASE}.qm - isEmpty(vcproj):copyQT_QMs.variable_out = PRE_TARGETDEPS - copyQT_QMs.commands = $(COPY_FILE) ${QMAKE_FILE_IN} ${QMAKE_FILE_OUT} - copyQT_QMs.name = Copy ${QMAKE_FILE_IN} - copyQT_QMs.CONFIG += no_link - QMAKE_EXTRA_COMPILERS += copyQT_QMs -} -#========= end block copying qt_*.qm files ============ +LANGUAGES = fr # de es ru zh_CN + +# var, prepend, append +defineReplace(prependAll) { + for(a,$$1):result += $$2$${a}$$3 + return($$result) +} + +XMLPATTERNS = $$targetPath($$[QT_INSTALL_BINS]/xmlpatterns) +LUPDATE = $$targetPath($$[QT_INSTALL_BINS]/lupdate) -locations relative -no-ui-lines -no-sort -noobsolete +LRELEASE = $$targetPath($$[QT_INSTALL_BINS]/lrelease) + +TRANSLATIONS = $$prependAll(LANGUAGES, $$PWD/openpilotgcs_,.ts) + +MIME_TR_H = $$PWD/mime_tr.h + +contains(QT_VERSION, ^4\\.[0-5]\\..*) { + ts.commands = @echo This Qt version is too old for the ts target. Need Qt 4.6+. +} else { + for(dir, $$list($$files($$GCS_SOURCE_TREE/src/plugins/*))):MIMETYPES_FILES += $$files($$dir/*.mimetypes.xml) + MIMETYPES_FILES = \"$$join(MIMETYPES_FILES, \", \")\" + QMAKE_SUBSTITUTES += extract-mimetypes.xq.in + ts.commands += \ + $$XMLPATTERNS -output $$MIME_TR_H $$PWD/extract-mimetypes.xq && \ + (cd $$GCS_SOURCE_TREE && $$LUPDATE src $$MIME_TR_H -ts $$TRANSLATIONS) && \ + $$QMAKE_DEL_FILE $$targetPath($$MIME_TR_H) +} +QMAKE_EXTRA_TARGETS += ts + +TEMPLATE = app +TARGET = phony_target2 +CONFIG -= qt +QT = +LIBS = + +updateqm.input = TRANSLATIONS +updateqm.output = $$GCS_DATA_PATH/translations/${QMAKE_FILE_BASE}.qm +isEmpty(vcproj):updateqm.variable_out = PRE_TARGETDEPS +updateqm.commands = $$LRELEASE ${QMAKE_FILE_IN} -qm ${QMAKE_FILE_OUT} +updateqm.name = LRELEASE ${QMAKE_FILE_IN} +updateqm.CONFIG += no_link +QMAKE_EXTRA_COMPILERS += updateqm + +isEmpty(vcproj) { + QMAKE_LINK = @: IGNORE THIS LINE + OBJECTS_DIR = + win32:CONFIG -= embed_manifest_exe +} else { + CONFIG += console + PHONY_DEPS = . + phony_src.input = PHONY_DEPS + phony_src.output = phony.c + phony_src.variable_out = GENERATED_SOURCES + phony_src.commands = echo int main() { return 0; } > phony.c + phony_src.name = CREATE phony.c + phony_src.CONFIG += combine + QMAKE_EXTRA_COMPILERS += phony_src +} + +qmfiles.files = $$prependAll(LANGUAGES, $$OUT_PWD/openpilotgcs_,.qm) +qmfiles.path = /share/openpilotgcs/translations +qmfiles.CONFIG += no_check_exist +INSTALLS += qmfiles + +#========= begin block copying qt_*.qm files ========== +win32 { + defineReplace(QtQmExists) { + for(lang,$$1) { + qm_file = $$[QT_INSTALL_TRANSLATIONS]/qt_$${lang}.qm + exists($$qm_file) : result += $$qm_file + } + return($$result) + } + QT_TRANSLATIONS = $$QtQmExists(LANGUAGES) + + copyQT_QMs.input = QT_TRANSLATIONS + copyQT_QMs.output = $$GCS_DATA_PATH/translations/${QMAKE_FILE_BASE}.qm + isEmpty(vcproj):copyQT_QMs.variable_out = PRE_TARGETDEPS + copyQT_QMs.commands = $(COPY_FILE) ${QMAKE_FILE_IN} ${QMAKE_FILE_OUT} + copyQT_QMs.name = Copy ${QMAKE_FILE_IN} + copyQT_QMs.CONFIG += no_link + QMAKE_EXTRA_COMPILERS += copyQT_QMs +} +#========= end block copying qt_*.qm files ============ diff --git a/ground/openpilotgcs/share/share.pro b/ground/openpilotgcs/share/share.pro index c53b22640..61e3d398d 100644 --- a/ground/openpilotgcs/share/share.pro +++ b/ground/openpilotgcs/share/share.pro @@ -1,20 +1,26 @@ -include(../openpilotgcs.pri) - -TEMPLATE = subdirs -SUBDIRS = openpilotgcs/translations - -DATACOLLECTIONS = dials models pfd sounds diagrams mapicons stylesheets default_configurations - -equals(copydata, 1) { - for(dir, DATACOLLECTIONS) { - exists($$GCS_SOURCE_TREE/share/openpilotgcs/$$dir) { - macx:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline() - win32:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline() - unix:data_copy.commands += $(MKDIR) $$targetPath(\"$$GCS_DATA_PATH/$$dir\") $$addNewline() - unix:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline() - } - } - - data_copy.target = FORCE - QMAKE_EXTRA_TARGETS += data_copy -} +include(../openpilotgcs.pri) + +TEMPLATE = subdirs +SUBDIRS = openpilotgcs/translations + +DATACOLLECTIONS = dials models pfd sounds diagrams mapicons stylesheets default_configurations + +equals(copydata, 1) { + for(dir, DATACOLLECTIONS) { + exists($$GCS_SOURCE_TREE/share/openpilotgcs/$$dir) { + # Qt make macros (CHK_DIR_EXISTS, COPY_DIR, etc) have different syntax. They cannot be used + # reliably to copy subdirectories in two different Windows environments (bash and cmd/QtCreator). + # So undocumented QMAKE_SH variable is used to find out the real environment. + !isEmpty(QMAKE_SH) { + # sh environment (including Windows bash) + data_copy.commands += $(MKDIR) $$targetPath(\"$$GCS_DATA_PATH/$$dir\") $$addNewline() + data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline() + } else { + # native Windows cmd environment + data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/$$dir\") $$addNewline() + } + } + } + data_copy.target = FORCE + QMAKE_EXTRA_TARGETS += data_copy +} diff --git a/ground/openpilotgcs/src/app/app.pro b/ground/openpilotgcs/src/app/app.pro index 16d52e292..9d5c1446b 100644 --- a/ground/openpilotgcs/src/app/app.pro +++ b/ground/openpilotgcs/src/app/app.pro @@ -1,38 +1,38 @@ -include(../../openpilotgcs.pri) -include(../shared/qtsingleapplication/qtsingleapplication.pri) -include(gcsversioninfo.pri) - -TEMPLATE = app -TARGET = $$GCS_APP_TARGET -DESTDIR = $$GCS_APP_PATH -QT += xml -SOURCES += main.cpp \ - gcssplashscreen.cpp -include(../rpath.pri) -include(../libs/utils/utils.pri) - -LIBS *= -l$$qtLibraryName(ExtensionSystem) -l$$qtLibraryName(Aggregation) - -win32 { - RC_FILE = openpilotgcs.rc - target.path = /bin - INSTALLS += target -} else:macx { - LIBS += -framework CoreFoundation - ICON = openpilotgcs.icns - QMAKE_INFO_PLIST = Info.plist - FILETYPES.files = profile.icns prifile.icns - FILETYPES.path = Contents/Resources - QMAKE_BUNDLE_DATA += FILETYPES -} else { - target.path = /bin - INSTALLS += target -} - -OTHER_FILES += openpilotgcs.rc - -RESOURCES += \ - appresources.qrc - -HEADERS += \ - gcssplashscreen.h +include(../../openpilotgcs.pri) +include(../shared/qtsingleapplication/qtsingleapplication.pri) +include(gcsversioninfo.pri) + +TEMPLATE = app +TARGET = $$GCS_APP_TARGET +DESTDIR = $$GCS_APP_PATH +QT += xml +SOURCES += main.cpp \ + gcssplashscreen.cpp +include(../rpath.pri) +include(../libs/utils/utils.pri) + +LIBS *= -l$$qtLibraryName(ExtensionSystem) -l$$qtLibraryName(Aggregation) + +win32 { + RC_FILE = openpilotgcs.rc + target.path = /bin + INSTALLS += target +} else:macx { + LIBS += -framework CoreFoundation + ICON = openpilotgcs.icns + QMAKE_INFO_PLIST = Info.plist + FILETYPES.files = profile.icns prifile.icns + FILETYPES.path = Contents/Resources + QMAKE_BUNDLE_DATA += FILETYPES +} else { + target.path = /bin + INSTALLS += target +} + +OTHER_FILES += openpilotgcs.rc + +RESOURCES += \ + appresources.qrc + +HEADERS += \ + gcssplashscreen.h diff --git a/ground/openpilotgcs/src/app/gcssplashscreen.h b/ground/openpilotgcs/src/app/gcssplashscreen.h index a7e4c35d5..6c04e2367 100644 --- a/ground/openpilotgcs/src/app/gcssplashscreen.h +++ b/ground/openpilotgcs/src/app/gcssplashscreen.h @@ -33,7 +33,7 @@ #include #include -#include "../../../../build/ground/openpilotgcs/gcsversioninfo.h" +#include "../gcs_version_info.h" class GCSSplashScreen : public QSplashScreen { diff --git a/ground/openpilotgcs/src/app/gcsversioninfo.pri b/ground/openpilotgcs/src/app/gcsversioninfo.pri index c052a0d31..0dbf3e19e 100644 --- a/ground/openpilotgcs/src/app/gcsversioninfo.pri +++ b/ground/openpilotgcs/src/app/gcsversioninfo.pri @@ -1,37 +1,39 @@ -# -# This qmake file generates a header with the GCS version info string. -# -# This is a bit tricky since the script should be run always and before -# the other dependencies evaluation. -# - -# Since debug_and_release option is set, we need this -!debug_and_release|build_pass { - ROOT_DIR = $$GCS_SOURCE_TREE/../.. - VERSION_INFO_HEADER = $$GCS_BUILD_TREE/../gcsversioninfo.h - VERSION_INFO_SCRIPT = $$ROOT_DIR/make/scripts/version-info.py - VERSION_INFO_TEMPLATE = $$ROOT_DIR/make/templates/gcsversioninfotemplate.h - VERSION_INFO_COMMAND = python \"$$VERSION_INFO_SCRIPT\" - UAVO_DEF_PATH = $$ROOT_DIR/shared/uavobjectdefinition - - # Create custom version_info target which generates a header - version_info.target = $$VERSION_INFO_HEADER - version_info.commands = $$VERSION_INFO_COMMAND \ - --path=\"$$GCS_SOURCE_TREE\" \ - --template=\"$$VERSION_INFO_TEMPLATE\" \ - --uavodir=\"$$UAVO_DEF_PATH\" \ - --outfile=\"$$VERSION_INFO_HEADER\" - version_info.depends = FORCE - QMAKE_EXTRA_TARGETS += version_info - - # Hook version_info target in between qmake's Makefile update and - # the actual project target - version_info_hook.depends = version_info - debug_and_release { - CONFIG(debug,debug|release):version_info_hook.target = Makefile.Debug - CONFIG(release,debug|release):version_info_hook.target = Makefile.Release - } else { - version_info_hook.target = Makefile - } - QMAKE_EXTRA_TARGETS += version_info_hook -} +# +# This qmake file generates a header with the GCS version info string. +# +# This is a bit tricky since the script should be run always and before +# the other dependencies evaluation. +# + +# Since debug_and_release option is set, we need this +!debug_and_release|build_pass { + ROOT_DIR = $$GCS_SOURCE_TREE/../.. + VERSION_INFO_DIR = $$GCS_BUILD_TREE/../openpilotgcs-synthetics + VERSION_INFO_HEADER = $$VERSION_INFO_DIR/gcs_version_info.h + VERSION_INFO_SCRIPT = $$ROOT_DIR/make/scripts/version-info.py + VERSION_INFO_TEMPLATE = $$ROOT_DIR/make/templates/gcs_version_info_template.h + VERSION_INFO_COMMAND = python \"$$VERSION_INFO_SCRIPT\" + UAVO_DEF_PATH = $$ROOT_DIR/shared/uavobjectdefinition + + # Create custom version_info target which generates a header + version_info.target = $$VERSION_INFO_HEADER + version_info.commands = -$(MKDIR) $$targetPath($$VERSION_INFO_DIR) $$addNewline() + version_info.commands += $$VERSION_INFO_COMMAND \ + --path=\"$$GCS_SOURCE_TREE\" \ + --template=\"$$VERSION_INFO_TEMPLATE\" \ + --uavodir=\"$$UAVO_DEF_PATH\" \ + --outfile=\"$$VERSION_INFO_HEADER\" + version_info.depends = FORCE + QMAKE_EXTRA_TARGETS += version_info + + # Hook version_info target in between qmake's Makefile update and + # the actual project target + version_info_hook.depends = version_info + debug_and_release { + CONFIG(debug,debug|release):version_info_hook.target = Makefile.Debug + CONFIG(release,debug|release):version_info_hook.target = Makefile.Release + } else { + version_info_hook.target = Makefile + } + QMAKE_EXTRA_TARGETS += version_info_hook +} diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/common.h b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/common.h index 64f6a41e3..97e39a7c1 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/common.h +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/common.h @@ -1,18 +1,18 @@ -#ifndef COMMON_H -#define COMMON_H - -enum decodeState_ { - decode_len1_e = 0, - decode_seqNo_e, - decode_data_e, - decode_crc1_e, - decode_crc2_e, - decode_idle_e -}; -enum ReceiveState { - state_escaped_e = 0, - state_unescaped_e -}; - - -#endif // COMMON_H +#ifndef COMMON_H +#define COMMON_H + +enum decodeState_ { + decode_len1_e = 0, + decode_seqNo_e, + decode_data_e, + decode_crc1_e, + decode_crc2_e, + decode_idle_e +}; +enum ReceiveState { + state_escaped_e = 0, + state_unescaped_e +}; + + +#endif // COMMON_H diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/main.cpp b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/main.cpp index a3b1c624f..61ca74b04 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/main.cpp +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/main.cpp @@ -1,75 +1,75 @@ -#include -#include "../../../libs/qextserialport/src/qextserialport.h" -#include -#include -#include "qssp.h" -#include "port.h" -#include "qsspt.h" -int main(int argc, char *argv[]) -{ -#define MAX_PACKET_DATA_LEN 255 -#define MAX_PACKET_BUF_SIZE (1+1+255+2) - - uint8_t sspTxBuf[MAX_PACKET_BUF_SIZE]; - uint8_t sspRxBuf[MAX_PACKET_BUF_SIZE]; - - port * info; - PortSettings settings; - settings.BaudRate=BAUD57600; - settings.DataBits=DATA_8; - settings.FlowControl=FLOW_OFF; - settings.Parity=PAR_NONE; - settings.StopBits=STOP_1; - settings.Timeout_Millisec=5000; - - info=new port(settings,"COM3"); - info->rxBuf = sspRxBuf; - info->rxBufSize = MAX_PACKET_DATA_LEN; - info->txBuf = sspTxBuf; - info->txBufSize = 255; - info->max_retry = 3; - info->timeoutLen = 5000; - //qssp b(info); - qsspt bb(info); - uint8_t buf[1000]; - QCoreApplication a(argc, argv); - while(!bb.ssp_Synchronise()) - { - qDebug()<<"trying sync"; - } - bb.start(); - qDebug()<<"sync complete"; - buf[0]=0; - buf[1]=1; - buf[2]=2; - while(true) - { - if(bb.sendData(buf,63)) - qDebug()<<"send OK"; -// else -// qDebug()<<"send NOK"; -// //bb.ssp_SendData(buf,63); - } - while(true) - { - - - - if(bb.packets_Available()>0) - { - - bb.read_Packet(buf); - qDebug()<<"receive="<<(int)buf[0]<<(int)buf[1]<<(int)buf[2]; - ++buf[0]; - ++buf[1]; - ++buf[2]; - //bb.ssp_SendData(buf,63); - bb.sendData(buf,63); - } - //bb.ssp_ReceiveProcess(); - //bb.ssp_SendProcess(); - - - } - return a.exec(); -} +#include +#include "../../../libs/qextserialport/src/qextserialport.h" +#include +#include +#include "qssp.h" +#include "port.h" +#include "qsspt.h" +int main(int argc, char *argv[]) +{ +#define MAX_PACKET_DATA_LEN 255 +#define MAX_PACKET_BUF_SIZE (1+1+255+2) + + uint8_t sspTxBuf[MAX_PACKET_BUF_SIZE]; + uint8_t sspRxBuf[MAX_PACKET_BUF_SIZE]; + + port * info; + PortSettings settings; + settings.BaudRate=BAUD57600; + settings.DataBits=DATA_8; + settings.FlowControl=FLOW_OFF; + settings.Parity=PAR_NONE; + settings.StopBits=STOP_1; + settings.Timeout_Millisec=5000; + + info=new port(settings,"COM3"); + info->rxBuf = sspRxBuf; + info->rxBufSize = MAX_PACKET_DATA_LEN; + info->txBuf = sspTxBuf; + info->txBufSize = 255; + info->max_retry = 3; + info->timeoutLen = 5000; + //qssp b(info); + qsspt bb(info); + uint8_t buf[1000]; + QCoreApplication a(argc, argv); + while(!bb.ssp_Synchronise()) + { + qDebug()<<"trying sync"; + } + bb.start(); + qDebug()<<"sync complete"; + buf[0]=0; + buf[1]=1; + buf[2]=2; + while(true) + { + if(bb.sendData(buf,63)) + qDebug()<<"send OK"; +// else +// qDebug()<<"send NOK"; +// //bb.ssp_SendData(buf,63); + } + while(true) + { + + + + if(bb.packets_Available()>0) + { + + bb.read_Packet(buf); + qDebug()<<"receive="<<(int)buf[0]<<(int)buf[1]<<(int)buf[2]; + ++buf[0]; + ++buf[1]; + ++buf[2]; + //bb.ssp_SendData(buf,63); + bb.sendData(buf,63); + } + //bb.ssp_ReceiveProcess(); + //bb.ssp_SendProcess(); + + + } + return a.exec(); +} diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/port.cpp b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/port.cpp index 2bb529c96..b247a642c 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/port.cpp +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/port.cpp @@ -1,41 +1,41 @@ -#include "port.h" -#include "delay.h" -port::port(PortSettings settings,QString name):mstatus(port::closed) -{ - timer.start(); - sport = new QextSerialPort(name,settings, QextSerialPort::Polling); - if(sport->open(QIODevice::ReadWrite|QIODevice::Unbuffered)) - { - mstatus=port::open; - // sport->setDtr(); - } - else - mstatus=port::error; -} -port::portstatus port::status() -{ - return mstatus; -} -int16_t port::pfSerialRead(void) -{ - - char c[1]; - if(sport->bytesAvailable()) - { - sport->read(c,1); - } - else return -1; - return (uint8_t)c[0]; -} - -void port::pfSerialWrite(uint8_t c) -{ - char cc[1]; - cc[0]=c; - sport->write(cc,1); -} - -uint32_t port::pfGetTime(void) -{ - return timer.elapsed(); -} +#include "port.h" +#include "delay.h" +port::port(PortSettings settings,QString name):mstatus(port::closed) +{ + timer.start(); + sport = new QextSerialPort(name,settings, QextSerialPort::Polling); + if(sport->open(QIODevice::ReadWrite|QIODevice::Unbuffered)) + { + mstatus=port::open; + // sport->setDtr(); + } + else + mstatus=port::error; +} +port::portstatus port::status() +{ + return mstatus; +} +int16_t port::pfSerialRead(void) +{ + + char c[1]; + if(sport->bytesAvailable()) + { + sport->read(c,1); + } + else return -1; + return (uint8_t)c[0]; +} + +void port::pfSerialWrite(uint8_t c) +{ + char cc[1]; + cc[0]=c; + sport->write(cc,1); +} + +uint32_t port::pfGetTime(void) +{ + return timer.elapsed(); +} diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/port.h b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/port.h index afa4fc734..6ffea1c11 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/port.h +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/port.h @@ -1,48 +1,48 @@ -#ifndef PORT_H -#define PORT_H -#include -#include "../../../libs/qextserialport/src/qextserialport.h" -#include -#include -#include "common.h" - -class port -{ -public: - enum portstatus{open,closed,error}; - virtual int16_t pfSerialRead(void); // function to read a character from the serial input stream - virtual void pfSerialWrite( uint8_t ); // function to write a byte to be sent out the serial port - virtual uint32_t pfGetTime(void); - uint8_t retryCount; // how many times have we tried to transmit the 'send' packet - uint8_t maxRetryCount; // max. times to try to transmit the 'send' packet - uint16_t max_retry; // Maximum number of retrys for a single transmit. - int32_t timeoutLen; // how long to wait for each retry to succeed - int32_t timeout; // current timeout. when 'time' reaches this point we have timed out - uint8_t txSeqNo; // current 'send' packet sequence number - uint16_t rxBufPos; // current buffer position in the receive packet - uint16_t rxBufLen; // number of 'data' bytes in the buffer - uint8_t rxSeqNo; // current 'receive' packet number - uint16_t rxBufSize; // size of the receive buffer. - uint16_t txBufSize; // size of the transmit buffer. - uint8_t *txBuf; // transmit buffer. REquired to store a copy of packet data in case a retry is needed. - uint8_t *rxBuf; // receive buffer. Used to store data as a packet is received. - uint16_t sendSynch; // flag to indicate that we should send a synchronize packet to the host - // this is required when switching from the application to the bootloader - // and vice-versa. This fixes the firwmare download timeout. - // when this flag is set to true, the next time we send a packet we will first // send a synchronize packet. - ReceiveState InputState; - decodeState_ DecodeState; - uint16_t SendState; - uint16_t crc; - uint32_t RxError; - uint32_t TxError; - uint16_t flags; - port(PortSettings settings,QString name); - portstatus status(); -private: - portstatus mstatus; - QTime timer; - QextSerialPort *sport; -}; - -#endif // PORT_H +#ifndef PORT_H +#define PORT_H +#include +#include "../../../libs/qextserialport/src/qextserialport.h" +#include +#include +#include "common.h" + +class port +{ +public: + enum portstatus{open,closed,error}; + virtual int16_t pfSerialRead(void); // function to read a character from the serial input stream + virtual void pfSerialWrite( uint8_t ); // function to write a byte to be sent out the serial port + virtual uint32_t pfGetTime(void); + uint8_t retryCount; // how many times have we tried to transmit the 'send' packet + uint8_t maxRetryCount; // max. times to try to transmit the 'send' packet + uint16_t max_retry; // Maximum number of retrys for a single transmit. + int32_t timeoutLen; // how long to wait for each retry to succeed + int32_t timeout; // current timeout. when 'time' reaches this point we have timed out + uint8_t txSeqNo; // current 'send' packet sequence number + uint16_t rxBufPos; // current buffer position in the receive packet + uint16_t rxBufLen; // number of 'data' bytes in the buffer + uint8_t rxSeqNo; // current 'receive' packet number + uint16_t rxBufSize; // size of the receive buffer. + uint16_t txBufSize; // size of the transmit buffer. + uint8_t *txBuf; // transmit buffer. REquired to store a copy of packet data in case a retry is needed. + uint8_t *rxBuf; // receive buffer. Used to store data as a packet is received. + uint16_t sendSynch; // flag to indicate that we should send a synchronize packet to the host + // this is required when switching from the application to the bootloader + // and vice-versa. This fixes the firwmare download timeout. + // when this flag is set to true, the next time we send a packet we will first // send a synchronize packet. + ReceiveState InputState; + decodeState_ DecodeState; + uint16_t SendState; + uint16_t crc; + uint32_t RxError; + uint32_t TxError; + uint16_t flags; + port(PortSettings settings,QString name); + portstatus status(); +private: + portstatus mstatus; + QTime timer; + QextSerialPort *sport; +}; + +#endif // PORT_H diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/qssp.cpp b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/qssp.cpp index 58ac7d17e..fdb371e35 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/qssp.cpp +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/qssp.cpp @@ -1,781 +1,781 @@ -#include "qssp.h" - - -#include -#include -#include - - -/** PRIVATE DEFINITIONS **/ -#define SYNC 225 // Sync character used in Serial Protocol -#define ESC 224 // ESC character used in Serial Protocol -#define ESC_SYNC 1 // ESC_SYNC character used in Serial Protocol -#define ACK_BIT 0x80 // Ack bit, bit 7 of sequence number, 1 = Acknowledge, 0 = -// new packet -// packet location definitions. -#define LENGTH 0 -#define SEQNUM 1 -#define DATA 2 - - -// Make larger sized integers from smaller sized integers -#define MAKEWORD16( ub, lb ) ((uint16_t)0x0000 | ((uint16_t)(ub) << 8) | (uint16_t)(lb) ) -#define MAKEWORD32( uw, lw ) ((uint32_t)(0x0UL | ((uint32_t)(uw) << 16) | (uint32_t)(lw)) ) -#define MAKEWORD32B( b3, b2, b1, b0 ) ((uint32_t)((uint32_t)(b3)<< 24) | ((uint32_t)(b2)<<16) | ((uint32_t)(b1)<<8) | ((uint32_t)(b0) ) - - -// Used to extract smaller integers from larger sized intergers -#define LOWERBYTE( w ) (uint8_t)((w) & 0x00ff ) -#define UPPERBYTE( w ) (uint8_t)(((w) & 0xff00) >> 8 ) -#define UPPERWORD(lw) (uint16_t)(((lw) & 0xffff0000) >> 16 ) -#define LOWERWORD(lw) (uint16_t)((lw) & 0x0000ffff) - -// Macros to operate on a target and bitmask. -#define CLEARBIT( a, b ) ((a) = (a) & ~(b)) -#define SETBIT( a, b ) ((a) = (a) | (b) ) -#define TOGGLEBIT(a,b) ((a) = (a) ^ (b) ) - -// test bit macros operate using a bit mask. -#define ISBITSET( a, b ) ( ((a) & (b)) == (b) ? TRUE : FALSE ) -#define ISBITCLEAR( a, b) ( (~(a) & (b)) == (b) ? TRUE : FALSE ) - - - -/* Flag bit masks...*/ -#define SENT_SYNCH (0x01) -#define ACK_RECEIVED (0x02) -#define ACK_EXPECTED (0x04) - -#define SSP_AWAITING_ACK 0 -#define SSP_ACKED 1 -#define SSP_IDLE 2 - -/** PRIVATE DATA **/ -static const uint16_t CRC_TABLE[] = { - 0x0000, 0xC0C1, 0xC181, 0x0140, 0xC301, 0x03C0, 0x0280, 0xC241, - 0xC601, 0x06C0, 0x0780, 0xC741, 0x0500, 0xC5C1, 0xC481, 0x0440, - 0xCC01, 0x0CC0, 0x0D80, 0xCD41, 0x0F00, 0xCFC1, 0xCE81, 0x0E40, - 0x0A00, 0xCAC1, 0xCB81, 0x0B40, 0xC901, 0x09C0, 0x0880, 0xC841, - 0xD801, 0x18C0, 0x1980, 0xD941, 0x1B00, 0xDBC1, 0xDA81, 0x1A40, - 0x1E00, 0xDEC1, 0xDF81, 0x1F40, 0xDD01, 0x1DC0, 0x1C80, 0xDC41, - 0x1400, 0xD4C1, 0xD581, 0x1540, 0xD701, 0x17C0, 0x1680, 0xD641, - 0xD201, 0x12C0, 0x1380, 0xD341, 0x1100, 0xD1C1, 0xD081, 0x1040, - 0xF001, 0x30C0, 0x3180, 0xF141, 0x3300, 0xF3C1, 0xF281, 0x3240, - 0x3600, 0xF6C1, 0xF781, 0x3740, 0xF501, 0x35C0, 0x3480, 0xF441, - 0x3C00, 0xFCC1, 0xFD81, 0x3D40, 0xFF01, 0x3FC0, 0x3E80, 0xFE41, - 0xFA01, 0x3AC0, 0x3B80, 0xFB41, 0x3900, 0xF9C1, 0xF881, 0x3840, - 0x2800, 0xE8C1, 0xE981, 0x2940, 0xEB01, 0x2BC0, 0x2A80, 0xEA41, - 0xEE01, 0x2EC0, 0x2F80, 0xEF41, 0x2D00, 0xEDC1, 0xEC81, 0x2C40, - 0xE401, 0x24C0, 0x2580, 0xE541, 0x2700, 0xE7C1, 0xE681, 0x2640, - 0x2200, 0xE2C1, 0xE381, 0x2340, 0xE101, 0x21C0, 0x2080, 0xE041, - 0xA001, 0x60C0, 0x6180, 0xA141, 0x6300, 0xA3C1, 0xA281, 0x6240, - 0x6600, 0xA6C1, 0xA781, 0x6740, 0xA501, 0x65C0, 0x6480, 0xA441, - 0x6C00, 0xACC1, 0xAD81, 0x6D40, 0xAF01, 0x6FC0, 0x6E80, 0xAE41, - 0xAA01, 0x6AC0, 0x6B80, 0xAB41, 0x6900, 0xA9C1, 0xA881, 0x6840, - 0x7800, 0xB8C1, 0xB981, 0x7940, 0xBB01, 0x7BC0, 0x7A80, 0xBA41, - 0xBE01, 0x7EC0, 0x7F80, 0xBF41, 0x7D00, 0xBDC1, 0xBC81, 0x7C40, - 0xB401, 0x74C0, 0x7580, 0xB541, 0x7700, 0xB7C1, 0xB681, 0x7640, - 0x7200, 0xB2C1, 0xB381, 0x7340, 0xB101, 0x71C0, 0x7080, 0xB041, - 0x5000, 0x90C1, 0x9181, 0x5140, 0x9301, 0x53C0, 0x5280, 0x9241, - 0x9601, 0x56C0, 0x5780, 0x9741, 0x5500, 0x95C1, 0x9481, 0x5440, - 0x9C01, 0x5CC0, 0x5D80, 0x9D41, 0x5F00, 0x9FC1, 0x9E81, 0x5E40, - 0x5A00, 0x9AC1, 0x9B81, 0x5B40, 0x9901, 0x59C0, 0x5880, 0x9841, - 0x8801, 0x48C0, 0x4980, 0x8941, 0x4B00, 0x8BC1, 0x8A81, 0x4A40, - 0x4E00, 0x8EC1, 0x8F81, 0x4F40, 0x8D01, 0x4DC0, 0x4C80, 0x8C41, - 0x4400, 0x84C1, 0x8581, 0x4540, 0x8701, 0x47C0, 0x4680, 0x8641, - 0x8201, 0x42C0, 0x4380, 0x8341, 0x4100, 0x81C1, 0x8081, 0x4040 -}; - -/** EXTERNAL DATA **/ - -/** EXTERNAL FUNCTIONS **/ - -/** VERIFICATION FUNCTIONS **/ - - -/***********************************************************************************************************/ - -/*! - * \brief Initializes the communication port for use - * \param thisport = pointer to port structure to initialize - * \param info = config struct with default values. - * \return None. - * - * \note - * Must be called before calling the Send or REceive process functions. - */ - -void qssp::ssp_Init(const PortConfig_t* const info) -{ - - - thisport->maxRetryCount = info->max_retry; - thisport->timeoutLen = info->timeoutLen; - thisport->txBufSize = info->txBufSize; - thisport->rxBufSize = info->rxBufSize; - thisport->txBuf = info->txBuf; - thisport->rxBuf = info->rxBuf; - thisport->retryCount = 0; - thisport->sendSynch = FALSE; //TRUE; - thisport->rxSeqNo = 255; - thisport->txSeqNo = 255; - thisport->SendState = SSP_IDLE; - thisport->InputState =(ReceiveState)0; - thisport->DecodeState =(decodeState_)0; - thisport->TxError =0; - thisport->RxError =0; - thisport->txSeqNo =0; - thisport->rxSeqNo =0; -} - -/*! - * \brief Runs the send process, checks for receipt of ack, timeouts and resends if needed. - * \param thisport = which port to use - * \return SSP_TX_WAITING - waiting for a valid ACK to arrive - * \return SSP_TX_TIMEOUT - failed to receive a valid ACK in the timeout period, after retrying. - * \return SSP_TX_IDLE - not expecting a ACK packet (no current transmissions in progress) - * \return SSP_TX_ACKED - valid ACK received before timeout period. - * - * \note - * - */ -int16_t qssp::ssp_SendProcess( ) -{ - int16_t value = SSP_TX_WAITING; - - if (thisport->SendState == SSP_AWAITING_ACK ) { - if (sf_CheckTimeout() == TRUE) { - if (thisport->retryCount < thisport->maxRetryCount) { - // Try again - sf_SendPacket(); - sf_SetSendTimeout(); - value = SSP_TX_WAITING; - } else { - // Give up, # of trys has exceded the limit - value = SSP_TX_TIMEOUT; - CLEARBIT( thisport->flags, ACK_RECEIVED); - thisport->SendState = SSP_IDLE; - if (debug) - qDebug()<<"Send TimeOut!"; - } - } else { - value = SSP_TX_WAITING; - } - } else if( thisport->SendState == SSP_ACKED ) { - SETBIT( thisport->flags, ACK_RECEIVED); - value = SSP_TX_ACKED; - thisport->SendState = SSP_IDLE; - } else { - thisport->SendState = SSP_IDLE; - value = SSP_TX_IDLE; - } - return value; -} - -/*! - * \brief Runs the receive process. fetches a byte at a time and runs the byte through the protocol receive state machine. - * \param thisport - which port to use. - * \return receive status. - * - * \note - * - */ -int16_t qssp::ssp_ReceiveProcess() -{ - int16_t b; - int16_t packet_status = SSP_RX_IDLE; - - do { - b = thisport->pfSerialRead(); // attempt to read a char from the serial buffer - if (b != -1) { - packet_status = sf_ReceiveState(b); // process the newly received byte in the receive state machine - } - // keep going until either we received a full packet or there are no more bytes to process - } while (packet_status != SSP_RX_COMPLETE && b != -1); - - return packet_status; -} - -/*! - * \brief processes a single byte through the receive state machine. - * \param thisport = which port to use - * \return current receive status - * - * \note - * - */ - -int16_t qssp::ssp_ReceiveByte() -{ - int16_t b; - int16_t packet_status = SSP_RX_IDLE; - - b = thisport->pfSerialRead(); - if( b != -1 ) { - packet_status = sf_ReceiveState(b); - } - return packet_status; -} - -/*! - * \brief Sends a data packet and blocks until timeout or ack is received. - * \param thisport = which port to use - * \param data = pointer to data to send - * \param length = number of data bytes to send. Must be less than 254 - * \return true = ack was received within number of retries - * \return false = ack was not received. - * - * \note - * - */ -uint16_t qssp::ssp_SendDataBlock(uint8_t *data, uint16_t length ) -{ - int16_t packet_status = SSP_TX_WAITING; - uint16_t retval = FALSE; - - packet_status = ssp_SendData(data, length ); // send the data - while( packet_status == SSP_TX_WAITING ) { // check the status - (void)ssp_ReceiveProcess(); // process any bytes received. - packet_status = ssp_SendProcess(); // check the send status - } - if( packet_status == SSP_TX_ACKED ) { // figure out what happened to the packet - retval = TRUE; - } else { - retval = FALSE; - } - return retval; -} - -/*! - * \brief sends a chunk of data and does not block - * \param thisport = which port to use - * \param data = pointer to data to send - * \param length = number of bytes to send - * \return SSP_TX_BUFOVERRUN = tried to send too much data - * \return SSP_TX_WAITING = data sent and waiting for an ack to arrive - * \return SSP_TX_BUSY = a packet has already been sent, but not yet acked - * - * \note - * - */ -int16_t qssp::ssp_SendData(const uint8_t *data, const uint16_t length ) -{ - - int16_t value = SSP_TX_WAITING; - - if( (length + 2) > thisport->txBufSize ) { - // TRYING to send too much data. - value = SSP_TX_BUFOVERRUN; - } else if( thisport->SendState == SSP_IDLE ) { -#ifdef ACTIVE_SYNCH - if( thisport->sendSynch == TRUE ) { - sf_SendSynchPacket(); - } -#endif - -#ifdef SYNCH_SEND - if( length == 0 ) { - // TODO this method could allow a task/user to start a synchronisation step if a zero is mistakenly passed to this function. - // could add a check for a NULL data pointer, or use some sort of static flag that can only be accessed by a static function - // that must be called before calling this function. - // we are attempting to send a synch packet - thisport->txSeqNo = 0; // make this zero to cause the other end to re-synch with us - SETBIT(thisport->flags, SENT_SYNCH); - } else { - // we are sending a data packet - CLEARBIT( thisport->txSeqNo, ACK_BIT ); // make sure we are not sending a ACK packet - thisport->txSeqNo++; // update the sequence number. - if( thisport->txSeqNo > 0x7F) { // check for sequence number rollover - thisport->txSeqNo = 1; // if we do have rollover then reset to 1 not zero, - // zero is reserviced for synchronization requests - } - } - -#else - CLEARBIT( thisport->txSeqNo, ACK_BIT ); // make sure we are not sending a ACK packet - thisport->txSeqNo++; // update the sequence number. - if( thisport->txSeqNo > 0x7F) { // check for sequence number rollover - thisport->txSeqNo = 1; // if we do have rollover then reset to 1 not zero, - // zero is reserved for synchronization requests - } -#endif - CLEARBIT( thisport->flags, ACK_RECEIVED); - thisport->SendState = SSP_AWAITING_ACK; - value = SSP_TX_WAITING; - thisport->retryCount = 0; // zero out the retry counter for this transmission - sf_MakePacket( thisport->txBuf, data, length, thisport->txSeqNo ); - sf_SendPacket( ); // punch out the packet to the serial port - sf_SetSendTimeout( ); // do the timeout values - if (debug) - qDebug()<<"Sent DATA PACKET:"<txSeqNo; - } else { - // error we are already sending a packet. Need to wait for the current packet to be acked or timeout. - value = SSP_TX_BUSY; - if (debug) - qDebug()<<"Error sending TX was busy"; - } - return value; -} - -/*! - * \brief Attempts to synchronize the sequence numbers with the other end of the connectin. - * \param thisport = which port to use - * \return true = success - * \return false = failed to receive an ACK to our synch request - * - * \note - * A. send a packet with a sequence number equal to zero - * B. if timed out then: - * send synch packet again - * increment try counter - * if number of tries exceed maximum try limit then exit - * C. goto A - */ -uint16_t qssp::ssp_Synchronise( ) -{ - int16_t packet_status; - uint16_t retval = FALSE; - -#ifndef USE_SENDPACKET_DATA - thisport->txSeqNo = 0; // make this zero to cause the other end to re-synch with us - SETBIT(thisport->flags, SENT_SYNCH); - // TODO - should this be using ssp_SendPacketData()?? - sf_MakePacket( thisport->txBuf, NULL, 0, thisport->txSeqNo ); // construct the packet - sf_SendPacket( ); - sf_SetSendTimeout( ); - thisport->SendState = SSP_AWAITING_ACK; - packet_status = SSP_TX_WAITING; -#else - packet_status = ssp_SendData( NULL, 0 ); -#endif - while( packet_status == SSP_TX_WAITING ) { // we loop until we time out. - (void)ssp_ReceiveProcess( ); // do the receive process - packet_status = ssp_SendProcess( ); // do the send process - } - thisport->sendSynch = FALSE; - switch( packet_status ) { - case SSP_TX_ACKED: - retval = TRUE; - break; - case SSP_TX_BUSY: // intentional fall through. - case SSP_TX_TIMEOUT: // intentional fall through. - case SSP_TX_BUFOVERRUN: - retval = FALSE; - break; - default: - retval = FALSE; - break; - }; - return retval; -} - - -/*! - * \brief sends out a preformatted packet for a give port - * \param thisport = which port to use. - * \return none. - * - * \note - * Packet should be formed through the use of sf_MakePacket before calling this function. - */ -void qssp::sf_SendPacket() -{ - // add 3 to packet data length for: 1 length + 2 CRC (packet overhead) - uint8_t packetLen = thisport->txBuf[LENGTH] + 3; - - // use the raw serial write function so the SYNC byte does not get 'escaped' - thisport->pfSerialWrite(SYNC); - for( uint8_t x = 0; x < packetLen; x++ ) { - sf_write_byte(thisport->txBuf[x] ); - } - thisport->retryCount++; -} - - -/*! - * \brief converts data to transport layer protocol packet format. - * \param txbuf = buffer to use when forming the packet - * \param pdata = pointer to data to use - * \param length = number of bytes to use - * \param seqNo = sequence number of this packet - * \return none. - * - * \note - * 1. This function does not try to interpret ACK or SYNCH packets. This should - * be done by the caller of this function. - * 2. This function will attempt to format all data upto the size of the tx buffer. - * Any extra data beyond that will be ignored. - * 3. TODO: Should this function return an error if data length to be sent is greater th tx buffer size? - * - */ -void qssp::sf_MakePacket( uint8_t *txBuf, const uint8_t * pdata, uint16_t length, uint8_t seqNo ) -{ - uint16_t crc = 0xffff; - uint16_t bufPos = 0; - uint8_t b; - - // add 1 for the seq. number - txBuf[LENGTH] = length + 1; - txBuf[SEQNUM] = seqNo; - crc = sf_crc16( crc, seqNo ); - - length = length + 2; // add two for the length and seqno bytes which are added before the loop. - for( bufPos = 2; bufPos < length; bufPos++ ) { - b = *pdata++; - txBuf[bufPos] = b; - crc = sf_crc16( crc, b ); // update CRC value - } - txBuf[bufPos++] = LOWERBYTE(crc); - txBuf[bufPos] = UPPERBYTE(crc); - -} - -/*! - * \brief sends out an ack packet to given sequence number - * \param thisport = which port to use - * \param seqNumber = sequence number of the packet we would like to ack - * \return none. - * - * \note - * - */ - -void qssp::sf_SendAckPacket(uint8_t seqNumber) -{ - uint8_t AckSeqNumber = SETBIT( seqNumber, ACK_BIT ); - - // create the packet, note we pass AckSequenceNumber directly - sf_MakePacket( thisport->txBuf, NULL, 0, AckSeqNumber ); - sf_SendPacket( ); - if (debug) - qDebug()<<"Sent ACK PACKET:"<pfSerialWrite( ESC ); // since we are not starting a packet we must ESCAPE the SYNCH byte - thisport->pfSerialWrite( ESC_SYNC ); // now send the escaped synch char - } else if( c == ESC ) { // Check for ESC character - thisport->pfSerialWrite( ESC ); // if it is, we need to send it twice - thisport->pfSerialWrite( ESC ); - } else { - thisport->pfSerialWrite( c ); // otherwise write the byte to serial port - } -} - -/************************************************************************************************************ -* -* NAME: uint16_t ssp_crc16( uint16_t crc, uint16_t data ) -* DESCRIPTION: Uses crc_table to calculate new crc -* ARGUMENTS: -* arg1: crc -* arg2: data - byte to calculate into CRC -* RETURN: New crc -* CREATED: 5/8/02 -* -*************************************************************************************************************/ -/*! - * \brief calculates the new CRC value for 'data' - * \param crc = current CRC value - * \param data = new byte - * \return updated CRC value - * - * \note - * - */ - -uint16_t qssp::sf_crc16( uint16_t crc, uint8_t data ) -{ - return (crc >> 8) ^ CRC_TABLE[( crc ^ data ) & 0x00FF ]; -} - - -/*! - * \brief sets the timeout for the given packet - * \param thisport = which port to use - * \return none. - * - * \note - * - */ - -void qssp::sf_SetSendTimeout() -{ - uint32_t timeout; - timeout = thisport->pfGetTime() + thisport->timeoutLen; - thisport->timeout = timeout; -} - -/*! - * \brief checks to see if a timeout occured - * \param thisport = which port to use - * \return true = a timeout has occurred - * \return false = has not timed out - * - * \note - * - */ -uint16_t qssp::sf_CheckTimeout() -{ - uint16_t retval = FALSE; - uint32_t current_time; - - current_time = thisport->pfGetTime(); - if( current_time > thisport->timeout ) { - retval = TRUE; - } - if(retval) - if (debug) - qDebug()<<"timeout"<timeout; - return retval; -} - - -/**************************************************************************** - * NAME: sf_ReceiveState - * DESC: Implements the receive state handling code for escaped and unescaped data - * ARGS: thisport - which port to operate on - * c - incoming byte - * RETURN: - * CREATED: - * NOTES: - * 1. change from using pointer to functions. - ****************************************************************************/ -/*! - * \brief implements the receive state handling code for escaped and unescaped data - * \param thisport = which port to use - * \param c = byte to process through the receive state machine - * \return receive status - * - * \note - * - */ -int16_t qssp::sf_ReceiveState(uint8_t c ) -{ - int16_t retval = SSP_RX_RECEIVING; - - switch( thisport->InputState ) { - case state_unescaped_e: - if( c == SYNC ) { - thisport->DecodeState = decode_len1_e; - } else if ( c == ESC ) { - thisport->InputState = state_escaped_e; - } else { - retval = sf_DecodeState(c); - } - break; // end of unescaped state. - case state_escaped_e: - thisport->InputState = state_unescaped_e; - if( c == SYNC ) { - thisport->DecodeState = decode_len1_e; - } else if (c == ESC_SYNC ) { - retval = sf_DecodeState(SYNC); - } else { - retval = sf_DecodeState(c); - } - break; // end of the escaped state. - default: - break; - } - return retval; -} - -/**************************************************************************** - * NAME: sf_DecodeState - * DESC: Implements the receive state finite state machine - * ARGS: thisport - which port to operate on - * c - incoming byte - * RETURN: - * CREATED: - * NOTES: - * 1. change from using pointer to functions. - ****************************************************************************/ - -/*! - * \brief implements the receiving decoding state machine - * \param thisport = which port to use - * \param c = byte to process - * \return receive status - * - * \note - * - */ -int16_t qssp::sf_DecodeState( uint8_t c ) -{ - int16_t retval; - switch( thisport->DecodeState ) { - case decode_idle_e: - // 'c' is ignored in this state as the only way to leave the idle state is - // recognition of the SYNC byte in the sf_ReceiveState function. - retval = SSP_RX_IDLE; - break; - case decode_len1_e: - thisport->rxBuf[LENGTH]= c; - thisport->rxBufLen = c; - if( thisport->rxBufLen <= thisport->rxBufSize ) { - thisport->DecodeState = decode_seqNo_e; - retval = SSP_RX_RECEIVING; - } else { - thisport->DecodeState = decode_idle_e; - retval = SSP_RX_IDLE; - } - break; - case decode_seqNo_e: - thisport->rxBuf[SEQNUM] = c; - thisport->crc = 0xffff; - thisport->rxBufLen--; // subtract 1 for the seq. no. - thisport->rxBufPos = 2; - - thisport->crc = sf_crc16( thisport->crc, c ); - if( thisport->rxBufLen > 0 ) { - thisport->DecodeState = decode_data_e; - } else { - thisport->DecodeState = decode_crc1_e; - } - retval = SSP_RX_RECEIVING; - break; - case decode_data_e: - thisport->rxBuf[ (thisport->rxBufPos)++] = c; - thisport->crc = sf_crc16( thisport->crc, c ); - if( thisport->rxBufPos == (thisport->rxBufLen+2) ) { - thisport->DecodeState = decode_crc1_e; - } - retval = SSP_RX_RECEIVING; - break; - case decode_crc1_e: - thisport->crc = sf_crc16( thisport->crc, c ); - thisport->DecodeState = decode_crc2_e; - retval = SSP_RX_RECEIVING; - break; - case decode_crc2_e: - thisport->DecodeState = decode_idle_e; - // verify the CRC value for the packet - if( sf_crc16( thisport->crc, c) == 0) { - // TODO shouldn't the return value of sf_ReceivePacket() be checked? - sf_ReceivePacket(); - retval = SSP_RX_COMPLETE; - } else { - thisport->RxError++; - retval = SSP_RX_IDLE; - } - break; - default: - thisport->DecodeState = decode_idle_e; // unknown state so reset to idle state and wait for the next start of a packet. - retval = SSP_RX_IDLE; - break; - } - return retval; -} - -/************************************************************************************************************ -* -* NAME: int16_t sf_ReceivePacket( ) -* DESCRIPTION: Receive one packet, assumed that data is in rec.buff[] -* ARGUMENTS: -* RETURN: 0 . no new packet was received, could be ack or same packet -* 1 . new packet received -* SSP_PACKET_? -* SSP_PACKET_COMPLETE -* SSP_PACKET_ACK -* CREATED: 5/8/02 -* -*************************************************************************************************************/ -/*! - * \brief receive one packet. calls the callback function if needed. - * \param thisport = which port to use - * \return true = valid data packet received. - * \return false = otherwise - * - * \note - * - * Created: Oct 7, 2010 12:07:22 AM by joe - */ - -int16_t qssp::sf_ReceivePacket() -{ - int16_t value = FALSE; - - if( ISBITSET(thisport->rxBuf[SEQNUM], ACK_BIT ) ) { - // Received an ACK packet, need to check if it matches the previous sent packet - if( ( thisport->rxBuf[SEQNUM] & 0x7F) == (thisport->txSeqNo & 0x7f)) { - // It matches the last packet sent by us - SETBIT( thisport->txSeqNo, ACK_BIT ); - thisport->SendState = SSP_ACKED; - value = FALSE; - if (debug) - qDebug()<<"Received ACK:"<<(thisport->txSeqNo & 0x7F); - } - // else ignore the ACK packet - } else { - // Received a 'data' packet, figure out what type of packet we received... - if( thisport->rxBuf[SEQNUM] == 0 ) { - if (debug) - qDebug()<<"Received SYNC Request"; - // Synchronize sequence number with host -#ifdef ACTIVE_SYNCH - thisport->sendSynch = TRUE; -#endif - sf_SendAckPacket(thisport->rxBuf[SEQNUM] ); - thisport->rxSeqNo = 0; - value = FALSE; - } else if( thisport->rxBuf[SEQNUM] == thisport->rxSeqNo ) { - // Already seen this packet, just ack it, don't act on the packet. - sf_SendAckPacket(thisport->rxBuf[SEQNUM] ); - value = FALSE; - } else { - //New Packet - thisport->rxSeqNo = thisport->rxBuf[SEQNUM]; - // Let the application do something with the data/packet. - - // skip the first two bytes (length and seq. no.) in the buffer. - if (debug) - qDebug()<<"Received DATA PACKET seq="<rxSeqNo<<"Data="<<(uint8_t)thisport->rxBuf[2]<<(uint8_t)thisport->rxBuf[3]<<(uint8_t)thisport->rxBuf[4]; - pfCallBack( &(thisport->rxBuf[2]), thisport->rxBufLen); - - // after we send the ACK, it is possible for the host to send a new packet. - // Thus the application needs to copy the data and reset the receive buffer - // inside of thisport->pfCallBack() - sf_SendAckPacket(thisport->rxBuf[SEQNUM] ); - value = TRUE; - } - } - return value; -} -qssp::qssp(port * info,bool debug):debug(debug) -{ - - thisport=info; - thisport->maxRetryCount = info->max_retry; - thisport->timeoutLen = info->timeoutLen; - thisport->txBufSize = info->txBufSize; - thisport->rxBufSize = info->rxBufSize; - thisport->txBuf = info->txBuf; - thisport->rxBuf = info->rxBuf; - thisport->retryCount = 0; - thisport->sendSynch = FALSE; //TRUE; - thisport->rxSeqNo = 255; - thisport->txSeqNo = 255; - thisport->SendState = SSP_IDLE; - thisport->InputState =(ReceiveState)0; - thisport->DecodeState =(decodeState_)0; - thisport->TxError =0; - thisport->RxError =0; - thisport->txSeqNo =0; - thisport->rxSeqNo =0; -} -void qssp::pfCallBack( uint8_t * buf, uint16_t size) -{ - if (debug) - qDebug()<<"receive callback"< +#include +#include + + +/** PRIVATE DEFINITIONS **/ +#define SYNC 225 // Sync character used in Serial Protocol +#define ESC 224 // ESC character used in Serial Protocol +#define ESC_SYNC 1 // ESC_SYNC character used in Serial Protocol +#define ACK_BIT 0x80 // Ack bit, bit 7 of sequence number, 1 = Acknowledge, 0 = +// new packet +// packet location definitions. +#define LENGTH 0 +#define SEQNUM 1 +#define DATA 2 + + +// Make larger sized integers from smaller sized integers +#define MAKEWORD16( ub, lb ) ((uint16_t)0x0000 | ((uint16_t)(ub) << 8) | (uint16_t)(lb) ) +#define MAKEWORD32( uw, lw ) ((uint32_t)(0x0UL | ((uint32_t)(uw) << 16) | (uint32_t)(lw)) ) +#define MAKEWORD32B( b3, b2, b1, b0 ) ((uint32_t)((uint32_t)(b3)<< 24) | ((uint32_t)(b2)<<16) | ((uint32_t)(b1)<<8) | ((uint32_t)(b0) ) + + +// Used to extract smaller integers from larger sized intergers +#define LOWERBYTE( w ) (uint8_t)((w) & 0x00ff ) +#define UPPERBYTE( w ) (uint8_t)(((w) & 0xff00) >> 8 ) +#define UPPERWORD(lw) (uint16_t)(((lw) & 0xffff0000) >> 16 ) +#define LOWERWORD(lw) (uint16_t)((lw) & 0x0000ffff) + +// Macros to operate on a target and bitmask. +#define CLEARBIT( a, b ) ((a) = (a) & ~(b)) +#define SETBIT( a, b ) ((a) = (a) | (b) ) +#define TOGGLEBIT(a,b) ((a) = (a) ^ (b) ) + +// test bit macros operate using a bit mask. +#define ISBITSET( a, b ) ( ((a) & (b)) == (b) ? TRUE : FALSE ) +#define ISBITCLEAR( a, b) ( (~(a) & (b)) == (b) ? TRUE : FALSE ) + + + +/* Flag bit masks...*/ +#define SENT_SYNCH (0x01) +#define ACK_RECEIVED (0x02) +#define ACK_EXPECTED (0x04) + +#define SSP_AWAITING_ACK 0 +#define SSP_ACKED 1 +#define SSP_IDLE 2 + +/** PRIVATE DATA **/ +static const uint16_t CRC_TABLE[] = { + 0x0000, 0xC0C1, 0xC181, 0x0140, 0xC301, 0x03C0, 0x0280, 0xC241, + 0xC601, 0x06C0, 0x0780, 0xC741, 0x0500, 0xC5C1, 0xC481, 0x0440, + 0xCC01, 0x0CC0, 0x0D80, 0xCD41, 0x0F00, 0xCFC1, 0xCE81, 0x0E40, + 0x0A00, 0xCAC1, 0xCB81, 0x0B40, 0xC901, 0x09C0, 0x0880, 0xC841, + 0xD801, 0x18C0, 0x1980, 0xD941, 0x1B00, 0xDBC1, 0xDA81, 0x1A40, + 0x1E00, 0xDEC1, 0xDF81, 0x1F40, 0xDD01, 0x1DC0, 0x1C80, 0xDC41, + 0x1400, 0xD4C1, 0xD581, 0x1540, 0xD701, 0x17C0, 0x1680, 0xD641, + 0xD201, 0x12C0, 0x1380, 0xD341, 0x1100, 0xD1C1, 0xD081, 0x1040, + 0xF001, 0x30C0, 0x3180, 0xF141, 0x3300, 0xF3C1, 0xF281, 0x3240, + 0x3600, 0xF6C1, 0xF781, 0x3740, 0xF501, 0x35C0, 0x3480, 0xF441, + 0x3C00, 0xFCC1, 0xFD81, 0x3D40, 0xFF01, 0x3FC0, 0x3E80, 0xFE41, + 0xFA01, 0x3AC0, 0x3B80, 0xFB41, 0x3900, 0xF9C1, 0xF881, 0x3840, + 0x2800, 0xE8C1, 0xE981, 0x2940, 0xEB01, 0x2BC0, 0x2A80, 0xEA41, + 0xEE01, 0x2EC0, 0x2F80, 0xEF41, 0x2D00, 0xEDC1, 0xEC81, 0x2C40, + 0xE401, 0x24C0, 0x2580, 0xE541, 0x2700, 0xE7C1, 0xE681, 0x2640, + 0x2200, 0xE2C1, 0xE381, 0x2340, 0xE101, 0x21C0, 0x2080, 0xE041, + 0xA001, 0x60C0, 0x6180, 0xA141, 0x6300, 0xA3C1, 0xA281, 0x6240, + 0x6600, 0xA6C1, 0xA781, 0x6740, 0xA501, 0x65C0, 0x6480, 0xA441, + 0x6C00, 0xACC1, 0xAD81, 0x6D40, 0xAF01, 0x6FC0, 0x6E80, 0xAE41, + 0xAA01, 0x6AC0, 0x6B80, 0xAB41, 0x6900, 0xA9C1, 0xA881, 0x6840, + 0x7800, 0xB8C1, 0xB981, 0x7940, 0xBB01, 0x7BC0, 0x7A80, 0xBA41, + 0xBE01, 0x7EC0, 0x7F80, 0xBF41, 0x7D00, 0xBDC1, 0xBC81, 0x7C40, + 0xB401, 0x74C0, 0x7580, 0xB541, 0x7700, 0xB7C1, 0xB681, 0x7640, + 0x7200, 0xB2C1, 0xB381, 0x7340, 0xB101, 0x71C0, 0x7080, 0xB041, + 0x5000, 0x90C1, 0x9181, 0x5140, 0x9301, 0x53C0, 0x5280, 0x9241, + 0x9601, 0x56C0, 0x5780, 0x9741, 0x5500, 0x95C1, 0x9481, 0x5440, + 0x9C01, 0x5CC0, 0x5D80, 0x9D41, 0x5F00, 0x9FC1, 0x9E81, 0x5E40, + 0x5A00, 0x9AC1, 0x9B81, 0x5B40, 0x9901, 0x59C0, 0x5880, 0x9841, + 0x8801, 0x48C0, 0x4980, 0x8941, 0x4B00, 0x8BC1, 0x8A81, 0x4A40, + 0x4E00, 0x8EC1, 0x8F81, 0x4F40, 0x8D01, 0x4DC0, 0x4C80, 0x8C41, + 0x4400, 0x84C1, 0x8581, 0x4540, 0x8701, 0x47C0, 0x4680, 0x8641, + 0x8201, 0x42C0, 0x4380, 0x8341, 0x4100, 0x81C1, 0x8081, 0x4040 +}; + +/** EXTERNAL DATA **/ + +/** EXTERNAL FUNCTIONS **/ + +/** VERIFICATION FUNCTIONS **/ + + +/***********************************************************************************************************/ + +/*! + * \brief Initializes the communication port for use + * \param thisport = pointer to port structure to initialize + * \param info = config struct with default values. + * \return None. + * + * \note + * Must be called before calling the Send or REceive process functions. + */ + +void qssp::ssp_Init(const PortConfig_t* const info) +{ + + + thisport->maxRetryCount = info->max_retry; + thisport->timeoutLen = info->timeoutLen; + thisport->txBufSize = info->txBufSize; + thisport->rxBufSize = info->rxBufSize; + thisport->txBuf = info->txBuf; + thisport->rxBuf = info->rxBuf; + thisport->retryCount = 0; + thisport->sendSynch = FALSE; //TRUE; + thisport->rxSeqNo = 255; + thisport->txSeqNo = 255; + thisport->SendState = SSP_IDLE; + thisport->InputState =(ReceiveState)0; + thisport->DecodeState =(decodeState_)0; + thisport->TxError =0; + thisport->RxError =0; + thisport->txSeqNo =0; + thisport->rxSeqNo =0; +} + +/*! + * \brief Runs the send process, checks for receipt of ack, timeouts and resends if needed. + * \param thisport = which port to use + * \return SSP_TX_WAITING - waiting for a valid ACK to arrive + * \return SSP_TX_TIMEOUT - failed to receive a valid ACK in the timeout period, after retrying. + * \return SSP_TX_IDLE - not expecting a ACK packet (no current transmissions in progress) + * \return SSP_TX_ACKED - valid ACK received before timeout period. + * + * \note + * + */ +int16_t qssp::ssp_SendProcess( ) +{ + int16_t value = SSP_TX_WAITING; + + if (thisport->SendState == SSP_AWAITING_ACK ) { + if (sf_CheckTimeout() == TRUE) { + if (thisport->retryCount < thisport->maxRetryCount) { + // Try again + sf_SendPacket(); + sf_SetSendTimeout(); + value = SSP_TX_WAITING; + } else { + // Give up, # of trys has exceded the limit + value = SSP_TX_TIMEOUT; + CLEARBIT( thisport->flags, ACK_RECEIVED); + thisport->SendState = SSP_IDLE; + if (debug) + qDebug()<<"Send TimeOut!"; + } + } else { + value = SSP_TX_WAITING; + } + } else if( thisport->SendState == SSP_ACKED ) { + SETBIT( thisport->flags, ACK_RECEIVED); + value = SSP_TX_ACKED; + thisport->SendState = SSP_IDLE; + } else { + thisport->SendState = SSP_IDLE; + value = SSP_TX_IDLE; + } + return value; +} + +/*! + * \brief Runs the receive process. fetches a byte at a time and runs the byte through the protocol receive state machine. + * \param thisport - which port to use. + * \return receive status. + * + * \note + * + */ +int16_t qssp::ssp_ReceiveProcess() +{ + int16_t b; + int16_t packet_status = SSP_RX_IDLE; + + do { + b = thisport->pfSerialRead(); // attempt to read a char from the serial buffer + if (b != -1) { + packet_status = sf_ReceiveState(b); // process the newly received byte in the receive state machine + } + // keep going until either we received a full packet or there are no more bytes to process + } while (packet_status != SSP_RX_COMPLETE && b != -1); + + return packet_status; +} + +/*! + * \brief processes a single byte through the receive state machine. + * \param thisport = which port to use + * \return current receive status + * + * \note + * + */ + +int16_t qssp::ssp_ReceiveByte() +{ + int16_t b; + int16_t packet_status = SSP_RX_IDLE; + + b = thisport->pfSerialRead(); + if( b != -1 ) { + packet_status = sf_ReceiveState(b); + } + return packet_status; +} + +/*! + * \brief Sends a data packet and blocks until timeout or ack is received. + * \param thisport = which port to use + * \param data = pointer to data to send + * \param length = number of data bytes to send. Must be less than 254 + * \return true = ack was received within number of retries + * \return false = ack was not received. + * + * \note + * + */ +uint16_t qssp::ssp_SendDataBlock(uint8_t *data, uint16_t length ) +{ + int16_t packet_status = SSP_TX_WAITING; + uint16_t retval = FALSE; + + packet_status = ssp_SendData(data, length ); // send the data + while( packet_status == SSP_TX_WAITING ) { // check the status + (void)ssp_ReceiveProcess(); // process any bytes received. + packet_status = ssp_SendProcess(); // check the send status + } + if( packet_status == SSP_TX_ACKED ) { // figure out what happened to the packet + retval = TRUE; + } else { + retval = FALSE; + } + return retval; +} + +/*! + * \brief sends a chunk of data and does not block + * \param thisport = which port to use + * \param data = pointer to data to send + * \param length = number of bytes to send + * \return SSP_TX_BUFOVERRUN = tried to send too much data + * \return SSP_TX_WAITING = data sent and waiting for an ack to arrive + * \return SSP_TX_BUSY = a packet has already been sent, but not yet acked + * + * \note + * + */ +int16_t qssp::ssp_SendData(const uint8_t *data, const uint16_t length ) +{ + + int16_t value = SSP_TX_WAITING; + + if( (length + 2) > thisport->txBufSize ) { + // TRYING to send too much data. + value = SSP_TX_BUFOVERRUN; + } else if( thisport->SendState == SSP_IDLE ) { +#ifdef ACTIVE_SYNCH + if( thisport->sendSynch == TRUE ) { + sf_SendSynchPacket(); + } +#endif + +#ifdef SYNCH_SEND + if( length == 0 ) { + // TODO this method could allow a task/user to start a synchronisation step if a zero is mistakenly passed to this function. + // could add a check for a NULL data pointer, or use some sort of static flag that can only be accessed by a static function + // that must be called before calling this function. + // we are attempting to send a synch packet + thisport->txSeqNo = 0; // make this zero to cause the other end to re-synch with us + SETBIT(thisport->flags, SENT_SYNCH); + } else { + // we are sending a data packet + CLEARBIT( thisport->txSeqNo, ACK_BIT ); // make sure we are not sending a ACK packet + thisport->txSeqNo++; // update the sequence number. + if( thisport->txSeqNo > 0x7F) { // check for sequence number rollover + thisport->txSeqNo = 1; // if we do have rollover then reset to 1 not zero, + // zero is reserviced for synchronization requests + } + } + +#else + CLEARBIT( thisport->txSeqNo, ACK_BIT ); // make sure we are not sending a ACK packet + thisport->txSeqNo++; // update the sequence number. + if( thisport->txSeqNo > 0x7F) { // check for sequence number rollover + thisport->txSeqNo = 1; // if we do have rollover then reset to 1 not zero, + // zero is reserved for synchronization requests + } +#endif + CLEARBIT( thisport->flags, ACK_RECEIVED); + thisport->SendState = SSP_AWAITING_ACK; + value = SSP_TX_WAITING; + thisport->retryCount = 0; // zero out the retry counter for this transmission + sf_MakePacket( thisport->txBuf, data, length, thisport->txSeqNo ); + sf_SendPacket( ); // punch out the packet to the serial port + sf_SetSendTimeout( ); // do the timeout values + if (debug) + qDebug()<<"Sent DATA PACKET:"<txSeqNo; + } else { + // error we are already sending a packet. Need to wait for the current packet to be acked or timeout. + value = SSP_TX_BUSY; + if (debug) + qDebug()<<"Error sending TX was busy"; + } + return value; +} + +/*! + * \brief Attempts to synchronize the sequence numbers with the other end of the connectin. + * \param thisport = which port to use + * \return true = success + * \return false = failed to receive an ACK to our synch request + * + * \note + * A. send a packet with a sequence number equal to zero + * B. if timed out then: + * send synch packet again + * increment try counter + * if number of tries exceed maximum try limit then exit + * C. goto A + */ +uint16_t qssp::ssp_Synchronise( ) +{ + int16_t packet_status; + uint16_t retval = FALSE; + +#ifndef USE_SENDPACKET_DATA + thisport->txSeqNo = 0; // make this zero to cause the other end to re-synch with us + SETBIT(thisport->flags, SENT_SYNCH); + // TODO - should this be using ssp_SendPacketData()?? + sf_MakePacket( thisport->txBuf, NULL, 0, thisport->txSeqNo ); // construct the packet + sf_SendPacket( ); + sf_SetSendTimeout( ); + thisport->SendState = SSP_AWAITING_ACK; + packet_status = SSP_TX_WAITING; +#else + packet_status = ssp_SendData( NULL, 0 ); +#endif + while( packet_status == SSP_TX_WAITING ) { // we loop until we time out. + (void)ssp_ReceiveProcess( ); // do the receive process + packet_status = ssp_SendProcess( ); // do the send process + } + thisport->sendSynch = FALSE; + switch( packet_status ) { + case SSP_TX_ACKED: + retval = TRUE; + break; + case SSP_TX_BUSY: // intentional fall through. + case SSP_TX_TIMEOUT: // intentional fall through. + case SSP_TX_BUFOVERRUN: + retval = FALSE; + break; + default: + retval = FALSE; + break; + }; + return retval; +} + + +/*! + * \brief sends out a preformatted packet for a give port + * \param thisport = which port to use. + * \return none. + * + * \note + * Packet should be formed through the use of sf_MakePacket before calling this function. + */ +void qssp::sf_SendPacket() +{ + // add 3 to packet data length for: 1 length + 2 CRC (packet overhead) + uint8_t packetLen = thisport->txBuf[LENGTH] + 3; + + // use the raw serial write function so the SYNC byte does not get 'escaped' + thisport->pfSerialWrite(SYNC); + for( uint8_t x = 0; x < packetLen; x++ ) { + sf_write_byte(thisport->txBuf[x] ); + } + thisport->retryCount++; +} + + +/*! + * \brief converts data to transport layer protocol packet format. + * \param txbuf = buffer to use when forming the packet + * \param pdata = pointer to data to use + * \param length = number of bytes to use + * \param seqNo = sequence number of this packet + * \return none. + * + * \note + * 1. This function does not try to interpret ACK or SYNCH packets. This should + * be done by the caller of this function. + * 2. This function will attempt to format all data upto the size of the tx buffer. + * Any extra data beyond that will be ignored. + * 3. TODO: Should this function return an error if data length to be sent is greater th tx buffer size? + * + */ +void qssp::sf_MakePacket( uint8_t *txBuf, const uint8_t * pdata, uint16_t length, uint8_t seqNo ) +{ + uint16_t crc = 0xffff; + uint16_t bufPos = 0; + uint8_t b; + + // add 1 for the seq. number + txBuf[LENGTH] = length + 1; + txBuf[SEQNUM] = seqNo; + crc = sf_crc16( crc, seqNo ); + + length = length + 2; // add two for the length and seqno bytes which are added before the loop. + for( bufPos = 2; bufPos < length; bufPos++ ) { + b = *pdata++; + txBuf[bufPos] = b; + crc = sf_crc16( crc, b ); // update CRC value + } + txBuf[bufPos++] = LOWERBYTE(crc); + txBuf[bufPos] = UPPERBYTE(crc); + +} + +/*! + * \brief sends out an ack packet to given sequence number + * \param thisport = which port to use + * \param seqNumber = sequence number of the packet we would like to ack + * \return none. + * + * \note + * + */ + +void qssp::sf_SendAckPacket(uint8_t seqNumber) +{ + uint8_t AckSeqNumber = SETBIT( seqNumber, ACK_BIT ); + + // create the packet, note we pass AckSequenceNumber directly + sf_MakePacket( thisport->txBuf, NULL, 0, AckSeqNumber ); + sf_SendPacket( ); + if (debug) + qDebug()<<"Sent ACK PACKET:"<pfSerialWrite( ESC ); // since we are not starting a packet we must ESCAPE the SYNCH byte + thisport->pfSerialWrite( ESC_SYNC ); // now send the escaped synch char + } else if( c == ESC ) { // Check for ESC character + thisport->pfSerialWrite( ESC ); // if it is, we need to send it twice + thisport->pfSerialWrite( ESC ); + } else { + thisport->pfSerialWrite( c ); // otherwise write the byte to serial port + } +} + +/************************************************************************************************************ +* +* NAME: uint16_t ssp_crc16( uint16_t crc, uint16_t data ) +* DESCRIPTION: Uses crc_table to calculate new crc +* ARGUMENTS: +* arg1: crc +* arg2: data - byte to calculate into CRC +* RETURN: New crc +* CREATED: 5/8/02 +* +*************************************************************************************************************/ +/*! + * \brief calculates the new CRC value for 'data' + * \param crc = current CRC value + * \param data = new byte + * \return updated CRC value + * + * \note + * + */ + +uint16_t qssp::sf_crc16( uint16_t crc, uint8_t data ) +{ + return (crc >> 8) ^ CRC_TABLE[( crc ^ data ) & 0x00FF ]; +} + + +/*! + * \brief sets the timeout for the given packet + * \param thisport = which port to use + * \return none. + * + * \note + * + */ + +void qssp::sf_SetSendTimeout() +{ + uint32_t timeout; + timeout = thisport->pfGetTime() + thisport->timeoutLen; + thisport->timeout = timeout; +} + +/*! + * \brief checks to see if a timeout occured + * \param thisport = which port to use + * \return true = a timeout has occurred + * \return false = has not timed out + * + * \note + * + */ +uint16_t qssp::sf_CheckTimeout() +{ + uint16_t retval = FALSE; + uint32_t current_time; + + current_time = thisport->pfGetTime(); + if( current_time > thisport->timeout ) { + retval = TRUE; + } + if(retval) + if (debug) + qDebug()<<"timeout"<timeout; + return retval; +} + + +/**************************************************************************** + * NAME: sf_ReceiveState + * DESC: Implements the receive state handling code for escaped and unescaped data + * ARGS: thisport - which port to operate on + * c - incoming byte + * RETURN: + * CREATED: + * NOTES: + * 1. change from using pointer to functions. + ****************************************************************************/ +/*! + * \brief implements the receive state handling code for escaped and unescaped data + * \param thisport = which port to use + * \param c = byte to process through the receive state machine + * \return receive status + * + * \note + * + */ +int16_t qssp::sf_ReceiveState(uint8_t c ) +{ + int16_t retval = SSP_RX_RECEIVING; + + switch( thisport->InputState ) { + case state_unescaped_e: + if( c == SYNC ) { + thisport->DecodeState = decode_len1_e; + } else if ( c == ESC ) { + thisport->InputState = state_escaped_e; + } else { + retval = sf_DecodeState(c); + } + break; // end of unescaped state. + case state_escaped_e: + thisport->InputState = state_unescaped_e; + if( c == SYNC ) { + thisport->DecodeState = decode_len1_e; + } else if (c == ESC_SYNC ) { + retval = sf_DecodeState(SYNC); + } else { + retval = sf_DecodeState(c); + } + break; // end of the escaped state. + default: + break; + } + return retval; +} + +/**************************************************************************** + * NAME: sf_DecodeState + * DESC: Implements the receive state finite state machine + * ARGS: thisport - which port to operate on + * c - incoming byte + * RETURN: + * CREATED: + * NOTES: + * 1. change from using pointer to functions. + ****************************************************************************/ + +/*! + * \brief implements the receiving decoding state machine + * \param thisport = which port to use + * \param c = byte to process + * \return receive status + * + * \note + * + */ +int16_t qssp::sf_DecodeState( uint8_t c ) +{ + int16_t retval; + switch( thisport->DecodeState ) { + case decode_idle_e: + // 'c' is ignored in this state as the only way to leave the idle state is + // recognition of the SYNC byte in the sf_ReceiveState function. + retval = SSP_RX_IDLE; + break; + case decode_len1_e: + thisport->rxBuf[LENGTH]= c; + thisport->rxBufLen = c; + if( thisport->rxBufLen <= thisport->rxBufSize ) { + thisport->DecodeState = decode_seqNo_e; + retval = SSP_RX_RECEIVING; + } else { + thisport->DecodeState = decode_idle_e; + retval = SSP_RX_IDLE; + } + break; + case decode_seqNo_e: + thisport->rxBuf[SEQNUM] = c; + thisport->crc = 0xffff; + thisport->rxBufLen--; // subtract 1 for the seq. no. + thisport->rxBufPos = 2; + + thisport->crc = sf_crc16( thisport->crc, c ); + if( thisport->rxBufLen > 0 ) { + thisport->DecodeState = decode_data_e; + } else { + thisport->DecodeState = decode_crc1_e; + } + retval = SSP_RX_RECEIVING; + break; + case decode_data_e: + thisport->rxBuf[ (thisport->rxBufPos)++] = c; + thisport->crc = sf_crc16( thisport->crc, c ); + if( thisport->rxBufPos == (thisport->rxBufLen+2) ) { + thisport->DecodeState = decode_crc1_e; + } + retval = SSP_RX_RECEIVING; + break; + case decode_crc1_e: + thisport->crc = sf_crc16( thisport->crc, c ); + thisport->DecodeState = decode_crc2_e; + retval = SSP_RX_RECEIVING; + break; + case decode_crc2_e: + thisport->DecodeState = decode_idle_e; + // verify the CRC value for the packet + if( sf_crc16( thisport->crc, c) == 0) { + // TODO shouldn't the return value of sf_ReceivePacket() be checked? + sf_ReceivePacket(); + retval = SSP_RX_COMPLETE; + } else { + thisport->RxError++; + retval = SSP_RX_IDLE; + } + break; + default: + thisport->DecodeState = decode_idle_e; // unknown state so reset to idle state and wait for the next start of a packet. + retval = SSP_RX_IDLE; + break; + } + return retval; +} + +/************************************************************************************************************ +* +* NAME: int16_t sf_ReceivePacket( ) +* DESCRIPTION: Receive one packet, assumed that data is in rec.buff[] +* ARGUMENTS: +* RETURN: 0 . no new packet was received, could be ack or same packet +* 1 . new packet received +* SSP_PACKET_? +* SSP_PACKET_COMPLETE +* SSP_PACKET_ACK +* CREATED: 5/8/02 +* +*************************************************************************************************************/ +/*! + * \brief receive one packet. calls the callback function if needed. + * \param thisport = which port to use + * \return true = valid data packet received. + * \return false = otherwise + * + * \note + * + * Created: Oct 7, 2010 12:07:22 AM by joe + */ + +int16_t qssp::sf_ReceivePacket() +{ + int16_t value = FALSE; + + if( ISBITSET(thisport->rxBuf[SEQNUM], ACK_BIT ) ) { + // Received an ACK packet, need to check if it matches the previous sent packet + if( ( thisport->rxBuf[SEQNUM] & 0x7F) == (thisport->txSeqNo & 0x7f)) { + // It matches the last packet sent by us + SETBIT( thisport->txSeqNo, ACK_BIT ); + thisport->SendState = SSP_ACKED; + value = FALSE; + if (debug) + qDebug()<<"Received ACK:"<<(thisport->txSeqNo & 0x7F); + } + // else ignore the ACK packet + } else { + // Received a 'data' packet, figure out what type of packet we received... + if( thisport->rxBuf[SEQNUM] == 0 ) { + if (debug) + qDebug()<<"Received SYNC Request"; + // Synchronize sequence number with host +#ifdef ACTIVE_SYNCH + thisport->sendSynch = TRUE; +#endif + sf_SendAckPacket(thisport->rxBuf[SEQNUM] ); + thisport->rxSeqNo = 0; + value = FALSE; + } else if( thisport->rxBuf[SEQNUM] == thisport->rxSeqNo ) { + // Already seen this packet, just ack it, don't act on the packet. + sf_SendAckPacket(thisport->rxBuf[SEQNUM] ); + value = FALSE; + } else { + //New Packet + thisport->rxSeqNo = thisport->rxBuf[SEQNUM]; + // Let the application do something with the data/packet. + + // skip the first two bytes (length and seq. no.) in the buffer. + if (debug) + qDebug()<<"Received DATA PACKET seq="<rxSeqNo<<"Data="<<(uint8_t)thisport->rxBuf[2]<<(uint8_t)thisport->rxBuf[3]<<(uint8_t)thisport->rxBuf[4]; + pfCallBack( &(thisport->rxBuf[2]), thisport->rxBufLen); + + // after we send the ACK, it is possible for the host to send a new packet. + // Thus the application needs to copy the data and reset the receive buffer + // inside of thisport->pfCallBack() + sf_SendAckPacket(thisport->rxBuf[SEQNUM] ); + value = TRUE; + } + } + return value; +} +qssp::qssp(port * info,bool debug):debug(debug) +{ + + thisport=info; + thisport->maxRetryCount = info->max_retry; + thisport->timeoutLen = info->timeoutLen; + thisport->txBufSize = info->txBufSize; + thisport->rxBufSize = info->rxBufSize; + thisport->txBuf = info->txBuf; + thisport->rxBuf = info->rxBuf; + thisport->retryCount = 0; + thisport->sendSynch = FALSE; //TRUE; + thisport->rxSeqNo = 255; + thisport->txSeqNo = 255; + thisport->SendState = SSP_IDLE; + thisport->InputState =(ReceiveState)0; + thisport->DecodeState =(decodeState_)0; + thisport->TxError =0; + thisport->RxError =0; + thisport->txSeqNo =0; + thisport->rxSeqNo =0; +} +void qssp::pfCallBack( uint8_t * buf, uint16_t size) +{ + if (debug) + qDebug()<<"receive callback"< -#include "port.h" -#include "common.h" -/** LOCAL DEFINITIONS **/ -#ifndef TRUE -#define TRUE 1 -#endif - -#ifndef FALSE -#define FALSE 0 -#endif - -#define SSP_TX_IDLE 0 // not expecting a ACK packet (no current transmissions in progress) -#define SSP_TX_WAITING 1 // waiting for a valid ACK to arrive -#define SSP_TX_TIMEOUT 2 // failed to receive a valid ACK in the timeout period, after retrying. -#define SSP_TX_ACKED 3 // valid ACK received before timeout period. -#define SSP_TX_BUFOVERRUN 4 // amount of data to send execeds the transmission buffer sizeof -#define SSP_TX_BUSY 5 // Attempted to start a transmission while a transmission was already in progress. -//#define SSP_TX_FAIL - failure... - -#define SSP_RX_IDLE 0 -#define SSP_RX_RECEIVING 1 -#define SSP_RX_COMPLETE 2 - -// types of packet that can be received -#define SSP_RX_DATA 5 -#define SSP_RX_ACK 6 -#define SSP_RX_SYNCH 7 - - -typedef struct -{ - uint8_t *pbuff; - uint16_t length; - uint16_t crc; - uint8_t seqNo; -} Packet_t; - -typedef struct { - - uint8_t *rxBuf; // Buffer used to store rcv data - uint16_t rxBufSize; // rcv buffer size. - uint8_t *txBuf; // Length of data in buffer - uint16_t txBufSize; // CRC for data in Packet buff - uint16_t max_retry; // Maximum number of retrys for a single transmit. - int32_t timeoutLen; // how long to wait for each retry to succeed - // function returns time in number of seconds that has elapsed from a given reference point -} PortConfig_t; - - - - - -/** Public Data **/ - - - - -/** EXTERNAL FUNCTIONS **/ - -class qssp -{ -private: - port * thisport; - decodeState_ DecodeState_t; - /** PRIVATE FUNCTIONS **/ - //static void sf_SendSynchPacket( Port_t *thisport ); - uint16_t sf_crc16( uint16_t crc, uint8_t data ); - void sf_write_byte(uint8_t c ); - void sf_SetSendTimeout(); - uint16_t sf_CheckTimeout(); - int16_t sf_DecodeState(uint8_t c ); - int16_t sf_ReceiveState(uint8_t c ); - - void sf_SendPacket(); - void sf_SendAckPacket(uint8_t seqNumber); - void sf_MakePacket( uint8_t *buf, const uint8_t * pdata, uint16_t length, uint8_t seqNo ); - int16_t sf_ReceivePacket(); - uint16_t ssp_SendDataBlock(uint8_t *data, uint16_t length ); - bool debug; -public: - /** PUBLIC FUNCTIONS **/ - virtual void pfCallBack( uint8_t *, uint16_t); // call back function that is called when a full packet has been received - int16_t ssp_ReceiveProcess(); - int16_t ssp_SendProcess(); - uint16_t ssp_SendString(char *str ); - int16_t ssp_SendData( const uint8_t * data,const uint16_t length ); - void ssp_Init( const PortConfig_t* const info); - int16_t ssp_ReceiveByte( ); - uint16_t ssp_Synchronise( ); - qssp(port * info,bool debug); -}; - -#endif // QSSP_H +#ifndef QSSP_H +#define QSSP_H +#include +#include "port.h" +#include "common.h" +/** LOCAL DEFINITIONS **/ +#ifndef TRUE +#define TRUE 1 +#endif + +#ifndef FALSE +#define FALSE 0 +#endif + +#define SSP_TX_IDLE 0 // not expecting a ACK packet (no current transmissions in progress) +#define SSP_TX_WAITING 1 // waiting for a valid ACK to arrive +#define SSP_TX_TIMEOUT 2 // failed to receive a valid ACK in the timeout period, after retrying. +#define SSP_TX_ACKED 3 // valid ACK received before timeout period. +#define SSP_TX_BUFOVERRUN 4 // amount of data to send execeds the transmission buffer sizeof +#define SSP_TX_BUSY 5 // Attempted to start a transmission while a transmission was already in progress. +//#define SSP_TX_FAIL - failure... + +#define SSP_RX_IDLE 0 +#define SSP_RX_RECEIVING 1 +#define SSP_RX_COMPLETE 2 + +// types of packet that can be received +#define SSP_RX_DATA 5 +#define SSP_RX_ACK 6 +#define SSP_RX_SYNCH 7 + + +typedef struct +{ + uint8_t *pbuff; + uint16_t length; + uint16_t crc; + uint8_t seqNo; +} Packet_t; + +typedef struct { + + uint8_t *rxBuf; // Buffer used to store rcv data + uint16_t rxBufSize; // rcv buffer size. + uint8_t *txBuf; // Length of data in buffer + uint16_t txBufSize; // CRC for data in Packet buff + uint16_t max_retry; // Maximum number of retrys for a single transmit. + int32_t timeoutLen; // how long to wait for each retry to succeed + // function returns time in number of seconds that has elapsed from a given reference point +} PortConfig_t; + + + + + +/** Public Data **/ + + + + +/** EXTERNAL FUNCTIONS **/ + +class qssp +{ +private: + port * thisport; + decodeState_ DecodeState_t; + /** PRIVATE FUNCTIONS **/ + //static void sf_SendSynchPacket( Port_t *thisport ); + uint16_t sf_crc16( uint16_t crc, uint8_t data ); + void sf_write_byte(uint8_t c ); + void sf_SetSendTimeout(); + uint16_t sf_CheckTimeout(); + int16_t sf_DecodeState(uint8_t c ); + int16_t sf_ReceiveState(uint8_t c ); + + void sf_SendPacket(); + void sf_SendAckPacket(uint8_t seqNumber); + void sf_MakePacket( uint8_t *buf, const uint8_t * pdata, uint16_t length, uint8_t seqNo ); + int16_t sf_ReceivePacket(); + uint16_t ssp_SendDataBlock(uint8_t *data, uint16_t length ); + bool debug; +public: + /** PUBLIC FUNCTIONS **/ + virtual void pfCallBack( uint8_t *, uint16_t); // call back function that is called when a full packet has been received + int16_t ssp_ReceiveProcess(); + int16_t ssp_SendProcess(); + uint16_t ssp_SendString(char *str ); + int16_t ssp_SendData( const uint8_t * data,const uint16_t length ); + void ssp_Init( const PortConfig_t* const info); + int16_t ssp_ReceiveByte( ); + uint16_t ssp_Synchronise( ); + qssp(port * info,bool debug); +}; + +#endif // QSSP_H diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/qsspt.cpp b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/qsspt.cpp index 0d1df867d..7087c2d44 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/qsspt.cpp +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/qsspt.cpp @@ -1,75 +1,75 @@ -#include "qsspt.h" - -qsspt::qsspt(port * info,bool debug):qssp(info,debug),endthread(false),datapending(false),debug(debug) -{ -} - -void qsspt::run() -{ - while(!endthread) - { - receivestatus=this->ssp_ReceiveProcess(); - sendstatus=this->ssp_SendProcess(); - sendbufmutex.lock(); - if(datapending && receivestatus==SSP_TX_IDLE) - { - this->ssp_SendData(mbuf,msize); - datapending=false; - } - sendbufmutex.unlock(); - if(sendstatus==SSP_TX_ACKED) - sendwait.wakeAll(); - } - -} -bool qsspt::sendData(uint8_t * buf,uint16_t size) -{ - if(datapending) - return false; - sendbufmutex.lock(); - datapending=true; - mbuf=buf; - msize=size; - sendbufmutex.unlock(); - msendwait.lock(); - sendwait.wait(&msendwait,100000); - msendwait.unlock(); - return true; -} - -void qsspt::pfCallBack( uint8_t * buf, uint16_t size) -{ - if (debug) - qDebug()<<"receive callback"<ssp_ReceiveProcess(); + sendstatus=this->ssp_SendProcess(); + sendbufmutex.lock(); + if(datapending && receivestatus==SSP_TX_IDLE) + { + this->ssp_SendData(mbuf,msize); + datapending=false; + } + sendbufmutex.unlock(); + if(sendstatus==SSP_TX_ACKED) + sendwait.wakeAll(); + } + +} +bool qsspt::sendData(uint8_t * buf,uint16_t size) +{ + if(datapending) + return false; + sendbufmutex.lock(); + datapending=true; + mbuf=buf; + msize=size; + sendbufmutex.unlock(); + msendwait.lock(); + sendwait.wait(&msendwait,100000); + msendwait.unlock(); + return true; +} + +void qsspt::pfCallBack( uint8_t * buf, uint16_t size) +{ + if (debug) + qDebug()<<"receive callback"< -#include -#include -class qsspt:public qssp, public QThread -{ -public: - qsspt(port * info,bool debug); - void run(); - int packets_Available(); - int read_Packet(void *); - ~qsspt(); - bool sendData(uint8_t * buf,uint16_t size); -private: - virtual void pfCallBack( uint8_t *, uint16_t); - uint8_t * mbuf; - uint16_t msize; - QQueue queue; - QMutex mutex; - QMutex sendbufmutex; - bool datapending; - bool endthread; - uint16_t sendstatus; - uint16_t receivestatus; - QWaitCondition sendwait; - QMutex msendwait; - bool debug; -}; - -#endif // QSSPT_H +#ifndef QSSPT_H +#define QSSPT_H + +#include "qssp.h" +#include +#include +#include +class qsspt:public qssp, public QThread +{ +public: + qsspt(port * info,bool debug); + void run(); + int packets_Available(); + int read_Packet(void *); + ~qsspt(); + bool sendData(uint8_t * buf,uint16_t size); +private: + virtual void pfCallBack( uint8_t *, uint16_t); + uint8_t * mbuf; + uint16_t msize; + QQueue queue; + QMutex mutex; + QMutex sendbufmutex; + bool datapending; + bool endthread; + uint16_t sendstatus; + uint16_t receivestatus; + QWaitCondition sendwait; + QMutex msendwait; + bool debug; +}; + +#endif // QSSPT_H diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp.cpp b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp.cpp index 316558fb0..e8ac6706b 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp.cpp +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp.cpp @@ -1,817 +1,817 @@ -/*********************************************************************************************************** -* -* NAME: ssp.c -* DESCRIPTION: simple serial protocol - packet based serial transport layer. -* AUTHOR: Joe Hlebasko -* HISTORY: Created 1/1/2010 -* -* Packet Formats -* Format: -* +------+----+------+---------------------------+--------+ -* | 225 | L1 | S# | App Data (0-254 bytes) | CRC 16 | -* +------+----+------+---------------------------+--------+ -* -* 225 = sync byte, indicates start of a packet -* L1 = 1 byte for size of data payload. (sequence number is part of data payload.) -* S# = 1 byte for sequence number. -* Seq of 0 = seq # synchronise request, forces other end to reset receive sequence number to 1. -* sender of synchronise request will reset the tx seq number to 1 -* Seq # of 1..127 = normal data packets. Sequence number is incremented by for each transmitted -* packet. Rolls over from 127 to 1. -* if most sig. bit is set then the packet is an ACK packet of data packet sequence number of the -* lower 7 bits (1..127) -* App Data may contain 0..254 bytes. The sequence number is consider part of the payload. -* CRC 16 - 16 bits of CRC values of Sequence # and data bytes. -* -* Protocol has two types of packets: data and ack packets. ACK packets have the most sig. bit set in the -* sequence number, this implies that valid sequence numbers are 1..127 -* -* This protocol uses the concept of sequences numbers to determine if a given packet has been received. This -* requires both devices to be able to synchronize sequence numbers. This is accomplished by sending a packet -* length 1 and sequence number = 0. The receive then resets it's transmit sequence number to 1. -* -* ACTIVE_SYNCH is a version that will automatically send a synch request if it receives a synch packet. Only -* one device in the communication should do otherwise you end up with an endless loops of synchronization. -* Right now each side needs to manually issues a synch request. -* -* This protocol is best used in cases where one device is the master and the other is the slave, or a don't -* speak unless spoken to type of approach. -* -* The following are items are required to initialize a port for communications: -* 1. The number attempts for each packet -* 2. time to wait for an ack. -* 3. pointer to buffer to be used for receiving. -* 4. pointer to a buffer to be used for transmission -* 5. length of each buffer (rx and tx) -* 6. Four functions: -* 1. write byte = writes a byte out the serial port (or other comm device) -* 2. read byte = retrieves a byte from the serial port. Returns -1 if a byte is not available -* 3. callback = function to call when a valid data packet has been received. This function is responsible -* to do what needs to be done with the data when it is received. The primary mission of this function -* should be to copy the data to a private buffer out of the working receive buffer to prevent overrun. -* processing should be kept to a minimum. -* 4. get time = function should return the current time. Note that time units are not specified it just -* needs to be some measure of time that increments as time passes by. The timeout values for a given -* port should the units used/returned by the get time function. -* -* All of the state information of a communication port is contained in a Port_t structure. This allows this -* module to operature on multiple communication ports with a single code base. -* -* The ssp_ReceiveProcess and ssp_SendProcess functions need to be called to process data through the -* respective state machines. Typical implementation would have a serial ISR to pull bytes out of the UART -* and place into a circular buffer. The serial read function would then pull bytes out this buffer -* processing. The TX side has the write function placing bytes into a circular buffer with the TX ISR -* pulling bytes out of the buffer and putting into the UART. It is possible to run the receive process from -* the receive ISR but care must be taken on processing data when it is received to avoid holding up the ISR -* and sending ACK packets from the receive ISR. -* -***********************************************************************************************************/ - -/** INCLUDE FILES **/ - - - -#include -#include -#include - -#include "ssp.h" - -/** PRIVATE DEFINITIONS **/ -#define SYNC 225 // Sync character used in Serial Protocol -#define ESC 224 // ESC character used in Serial Protocol -#define ESC_SYNC 1 // ESC_SYNC character used in Serial Protocol -#define ACK_BIT 0x80 // Ack bit, bit 7 of sequence number, 1 = Acknowledge, 0 = - // new packet -// packet location definitions. -#define LENGTH 0 -#define SEQNUM 1 -#define DATA 2 - - -// Make larger sized integers from smaller sized integers -#define MAKEWORD16( ub, lb ) ((uint16_t)0x0000 | ((uint16_t)(ub) << 8) | (uint16_t)(lb) ) -#define MAKEWORD32( uw, lw ) ((uint32_t)(0x0UL | ((uint32_t)(uw) << 16) | (uint32_t)(lw)) ) -#define MAKEWORD32B( b3, b2, b1, b0 ) ((uint32_t)((uint32_t)(b3)<< 24) | ((uint32_t)(b2)<<16) | ((uint32_t)(b1)<<8) | ((uint32_t)(b0) ) - - -// Used to extract smaller integers from larger sized intergers -#define LOWERBYTE( w ) (uint8_t)((w) & 0x00ff ) -#define UPPERBYTE( w ) (uint8_t)(((w) & 0xff00) >> 8 ) -#define UPPERWORD(lw) (uint16_t)(((lw) & 0xffff0000) >> 16 ) -#define LOWERWORD(lw) (uint16_t)((lw) & 0x0000ffff) - -// Macros to operate on a target and bitmask. -#define CLEARBIT( a, b ) ((a) = (a) & ~(b)) -#define SETBIT( a, b ) ((a) = (a) | (b) ) -#define TOGGLEBIT(a,b) ((a) = (a) ^ (b) ) - -// test bit macros operate using a bit mask. -#define ISBITSET( a, b ) ( ((a) & (b)) == (b) ? TRUE : FALSE ) -#define ISBITCLEAR( a, b) ( (~(a) & (b)) == (b) ? TRUE : FALSE ) - -/** PRIVATE FUNCTIONS **/ -//static void sf_SendSynchPacket( Port_t *thisport ); -static uint16_t sf_crc16( uint16_t crc, uint8_t data ); -static void sf_write_byte( Port_t *thisport, uint8_t c ); -static void sf_SetSendTimeout( Port_t *thisport ); -static uint16_t sf_CheckTimeout( Port_t *thisport ); -static int16_t sf_DecodeState( Port_t *thisport, uint8_t c ); -static int16_t sf_ReceiveState( Port_t *thisport, uint8_t c ); - -static void sf_SendPacket( Port_t *thisport ); -static void sf_SendAckPacket( Port_t *thisport, uint8_t seqNumber); -static void sf_MakePacket( uint8_t *buf, const uint8_t * pdata, uint16_t length, uint8_t seqNo ); -static int16_t sf_ReceivePacket(Port_t *thisport); - -/* Flag bit masks...*/ -#define SENT_SYNCH (0x01) -#define ACK_RECEIVED (0x02) -#define ACK_EXPECTED (0x04) - -#define SSP_AWAITING_ACK 0 -#define SSP_ACKED 1 -#define SSP_IDLE 2 - -/** PRIVATE DATA **/ -static const uint16_t CRC_TABLE[] = { - 0x0000, 0xC0C1, 0xC181, 0x0140, 0xC301, 0x03C0, 0x0280, 0xC241, - 0xC601, 0x06C0, 0x0780, 0xC741, 0x0500, 0xC5C1, 0xC481, 0x0440, - 0xCC01, 0x0CC0, 0x0D80, 0xCD41, 0x0F00, 0xCFC1, 0xCE81, 0x0E40, - 0x0A00, 0xCAC1, 0xCB81, 0x0B40, 0xC901, 0x09C0, 0x0880, 0xC841, - 0xD801, 0x18C0, 0x1980, 0xD941, 0x1B00, 0xDBC1, 0xDA81, 0x1A40, - 0x1E00, 0xDEC1, 0xDF81, 0x1F40, 0xDD01, 0x1DC0, 0x1C80, 0xDC41, - 0x1400, 0xD4C1, 0xD581, 0x1540, 0xD701, 0x17C0, 0x1680, 0xD641, - 0xD201, 0x12C0, 0x1380, 0xD341, 0x1100, 0xD1C1, 0xD081, 0x1040, - 0xF001, 0x30C0, 0x3180, 0xF141, 0x3300, 0xF3C1, 0xF281, 0x3240, - 0x3600, 0xF6C1, 0xF781, 0x3740, 0xF501, 0x35C0, 0x3480, 0xF441, - 0x3C00, 0xFCC1, 0xFD81, 0x3D40, 0xFF01, 0x3FC0, 0x3E80, 0xFE41, - 0xFA01, 0x3AC0, 0x3B80, 0xFB41, 0x3900, 0xF9C1, 0xF881, 0x3840, - 0x2800, 0xE8C1, 0xE981, 0x2940, 0xEB01, 0x2BC0, 0x2A80, 0xEA41, - 0xEE01, 0x2EC0, 0x2F80, 0xEF41, 0x2D00, 0xEDC1, 0xEC81, 0x2C40, - 0xE401, 0x24C0, 0x2580, 0xE541, 0x2700, 0xE7C1, 0xE681, 0x2640, - 0x2200, 0xE2C1, 0xE381, 0x2340, 0xE101, 0x21C0, 0x2080, 0xE041, - 0xA001, 0x60C0, 0x6180, 0xA141, 0x6300, 0xA3C1, 0xA281, 0x6240, - 0x6600, 0xA6C1, 0xA781, 0x6740, 0xA501, 0x65C0, 0x6480, 0xA441, - 0x6C00, 0xACC1, 0xAD81, 0x6D40, 0xAF01, 0x6FC0, 0x6E80, 0xAE41, - 0xAA01, 0x6AC0, 0x6B80, 0xAB41, 0x6900, 0xA9C1, 0xA881, 0x6840, - 0x7800, 0xB8C1, 0xB981, 0x7940, 0xBB01, 0x7BC0, 0x7A80, 0xBA41, - 0xBE01, 0x7EC0, 0x7F80, 0xBF41, 0x7D00, 0xBDC1, 0xBC81, 0x7C40, - 0xB401, 0x74C0, 0x7580, 0xB541, 0x7700, 0xB7C1, 0xB681, 0x7640, - 0x7200, 0xB2C1, 0xB381, 0x7340, 0xB101, 0x71C0, 0x7080, 0xB041, - 0x5000, 0x90C1, 0x9181, 0x5140, 0x9301, 0x53C0, 0x5280, 0x9241, - 0x9601, 0x56C0, 0x5780, 0x9741, 0x5500, 0x95C1, 0x9481, 0x5440, - 0x9C01, 0x5CC0, 0x5D80, 0x9D41, 0x5F00, 0x9FC1, 0x9E81, 0x5E40, - 0x5A00, 0x9AC1, 0x9B81, 0x5B40, 0x9901, 0x59C0, 0x5880, 0x9841, - 0x8801, 0x48C0, 0x4980, 0x8941, 0x4B00, 0x8BC1, 0x8A81, 0x4A40, - 0x4E00, 0x8EC1, 0x8F81, 0x4F40, 0x8D01, 0x4DC0, 0x4C80, 0x8C41, - 0x4400, 0x84C1, 0x8581, 0x4540, 0x8701, 0x47C0, 0x4680, 0x8641, - 0x8201, 0x42C0, 0x4380, 0x8341, 0x4100, 0x81C1, 0x8081, 0x4040 - }; - -/** EXTERNAL DATA **/ - -/** EXTERNAL FUNCTIONS **/ - -/** VERIFICATION FUNCTIONS **/ - - -/***********************************************************************************************************/ - -/*! - * \brief Initializes the communication port for use - * \param thisport = pointer to port structure to initialize - * \param info = config struct with default values. - * \return None. - * - * \note - * Must be called before calling the Send or REceive process functions. - */ - -void ssp_Init( Port_t *thisport, const PortConfig_t* const info) -{ - thisport->pfCallBack = info->pfCallBack; - thisport->pfSerialRead = info->pfSerialRead; - thisport->pfSerialWrite = info->pfSerialWrite; - thisport->pfGetTime = info->pfGetTime; - - thisport->maxRetryCount = info->max_retry; - thisport->timeoutLen = info->timeoutLen; - thisport->txBufSize = info->txBufSize; - thisport->rxBufSize = info->rxBufSize; - thisport->txBuf = info->txBuf; - thisport->rxBuf = info->rxBuf; - thisport->retryCount = 0; - thisport->sendSynch = FALSE; //TRUE; - thisport->rxSeqNo = 255; - thisport->txSeqNo = 255; - thisport->SendState = SSP_IDLE; -} - -/*! - * \brief Runs the send process, checks for receipt of ack, timeouts and resends if needed. - * \param thisport = which port to use - * \return SSP_TX_WAITING - waiting for a valid ACK to arrive - * \return SSP_TX_TIMEOUT - failed to receive a valid ACK in the timeout period, after retrying. - * \return SSP_TX_IDLE - not expecting a ACK packet (no current transmissions in progress) - * \return SSP_TX_ACKED - valid ACK received before timeout period. - * - * \note - * - */ -int16_t ssp_SendProcess( Port_t *thisport ) -{ - int16_t value = SSP_TX_WAITING; - - if (thisport->SendState == SSP_AWAITING_ACK ) { - if (sf_CheckTimeout(thisport) == TRUE) { - if (thisport->retryCount < thisport->maxRetryCount) { - // Try again - sf_SendPacket(thisport); - sf_SetSendTimeout(thisport); - value = SSP_TX_WAITING; - } else { - // Give up, # of trys has exceded the limit - value = SSP_TX_TIMEOUT; - CLEARBIT( thisport->flags, ACK_RECEIVED); - thisport->SendState = SSP_IDLE; - } - } else { - value = SSP_TX_WAITING; - } - } else if( thisport->SendState == SSP_ACKED ) { - SETBIT( thisport->flags, ACK_RECEIVED); - value = SSP_TX_ACKED; - thisport->SendState = SSP_IDLE; - } else { - thisport->SendState = SSP_IDLE; - value = SSP_TX_IDLE; - } - return value; -} - -/*! - * \brief Runs the receive process. fetches a byte at a time and runs the byte through the protocol receive state machine. - * \param thisport - which port to use. - * \return receive status. - * - * \note - * - */ -int16_t ssp_ReceiveProcess(Port_t *thisport) -{ - int16_t b; - int16_t packet_status = SSP_RX_IDLE; - - do { - b = thisport->pfSerialRead(); // attempt to read a char from the serial buffer - if (b != -1) { - packet_status = sf_ReceiveState(thisport, b); // process the newly received byte in the receive state machine - } - // keep going until either we received a full packet or there are no more bytes to process - } while (packet_status != SSP_RX_COMPLETE && b != -1); - return packet_status; -} - -/*! - * \brief processes a single byte through the receive state machine. - * \param thisport = which port to use - * \return current receive status - * - * \note - * - */ - -int16_t ssp_ReceiveByte(Port_t *thisport ) -{ - int16_t b; - int16_t packet_status = SSP_RX_IDLE; - - b = thisport->pfSerialRead(); - if( b != -1 ) { - packet_status = sf_ReceiveState(thisport, b); - } - return packet_status; -} - -/*! - * \brief Sends a data packet and blocks until timeout or ack is received. - * \param thisport = which port to use - * \param data = pointer to data to send - * \param length = number of data bytes to send. Must be less than 254 - * \return true = ack was received within number of retries - * \return false = ack was not received. - * - * \note - * - */ -uint16_t ssp_SendDataBlock( Port_t *thisport, uint8_t *data, uint16_t length ) -{ - int16_t packet_status = SSP_TX_WAITING; - uint16_t retval = FALSE; - - packet_status = ssp_SendData( thisport, data, length ); // send the data - while( packet_status == SSP_TX_WAITING ) { // check the status - (void)ssp_ReceiveProcess( thisport ); // process any bytes received. - packet_status = ssp_SendProcess( thisport ); // check the send status - } - if( packet_status == SSP_TX_ACKED ) { // figure out what happened to the packet - retval = TRUE; - } else { - retval = FALSE; - } - return retval; -} - -/*! - * \brief sends a chunk of data and does not block - * \param thisport = which port to use - * \param data = pointer to data to send - * \param length = number of bytes to send - * \return SSP_TX_BUFOVERRUN = tried to send too much data - * \return SSP_TX_WAITING = data sent and waiting for an ack to arrive - * \return SSP_TX_BUSY = a packet has already been sent, but not yet acked - * - * \note - * - */ -int16_t ssp_SendData( Port_t *thisport, const uint8_t *data, const uint16_t length ) -{ - - int16_t value = SSP_TX_WAITING; - - if( (length + 2) > thisport->txBufSize ) { - // TRYING to send too much data. - value = SSP_TX_BUFOVERRUN; - } else if( thisport->SendState == SSP_IDLE ) { -#ifdef ACTIVE_SYNCH - if( thisport->sendSynch == TRUE ) { - sf_SendSynchPacket(thisport); - } -#endif - -#ifdef SYNCH_SEND - if( length == 0 ) { - // TODO this method could allow a task/user to start a synchronisation step if a zero is mistakenly passed to this function. - // could add a check for a NULL data pointer, or use some sort of static flag that can only be accessed by a static function - // that must be called before calling this function. - // we are attempting to send a synch packet - thisport->txSeqNo = 0; // make this zero to cause the other end to re-synch with us - SETBIT(thisport->flags, SENT_SYNCH); - } else { - // we are sending a data packet - CLEARBIT( thisport->txSeqNo, ACK_BIT ); // make sure we are not sending a ACK packet - thisport->txSeqNo++; // update the sequence number. - if( thisport->txSeqNo > 0x7F) { // check for sequence number rollover - thisport->txSeqNo = 1; // if we do have rollover then reset to 1 not zero, - // zero is reserviced for synchronization requests - } - } - -#else - CLEARBIT( thisport->txSeqNo, ACK_BIT ); // make sure we are not sending a ACK packet - thisport->txSeqNo++; // update the sequence number. - if( thisport->txSeqNo > 0x7F) { // check for sequence number rollover - thisport->txSeqNo = 1; // if we do have rollover then reset to 1 not zero, - // zero is reserved for synchronization requests - } -#endif - CLEARBIT( thisport->flags, ACK_RECEIVED); - thisport->SendState = SSP_AWAITING_ACK; - value = SSP_TX_WAITING; - thisport->retryCount = 0; // zero out the retry counter for this transmission - sf_MakePacket( thisport->txBuf, data, length, thisport->txSeqNo ); - sf_SendPacket( thisport ); // punch out the packet to the serial port - sf_SetSendTimeout( thisport ); // do the timeout values - } else { - // error we are already sending a packet. Need to wait for the current packet to be acked or timeout. - value = SSP_TX_BUSY; - } - return value; -} - -/*! - * \brief Attempts to synchronize the sequence numbers with the other end of the connectin. - * \param thisport = which port to use - * \return true = success - * \return false = failed to receive an ACK to our synch request - * - * \note - * A. send a packet with a sequence number equal to zero - * B. if timed out then: - * send synch packet again - * increment try counter - * if number of tries exceed maximum try limit then exit - * C. goto A - */ -uint16_t ssp_Synchronise( Port_t *thisport ) -{ - int16_t packet_status; - uint16_t retval = FALSE; - -#ifndef USE_SENDPACKET_DATA - thisport->txSeqNo = 0; // make this zero to cause the other end to re-synch with us - SETBIT(thisport->flags, SENT_SYNCH); - // TODO - should this be using ssp_SendPacketData()?? - sf_MakePacket( thisport->txBuf, NULL, 0, thisport->txSeqNo ); // construct the packet - sf_SendPacket( thisport ); - sf_SetSendTimeout( thisport ); - thisport->SendState = SSP_AWAITING_ACK; - packet_status = SSP_TX_WAITING; -#else - packet_status = ssp_SendData( thisport, NULL, 0 ); -#endif - while( packet_status == SSP_TX_WAITING ) { // we loop until we time out. - (void)ssp_ReceiveProcess( thisport ); // do the receive process - packet_status = ssp_SendProcess( thisport ); // do the send process - } - thisport->sendSynch = FALSE; - switch( packet_status ) { - case SSP_TX_ACKED: - retval = TRUE; - break; - case SSP_TX_BUSY: // intentional fall through. - case SSP_TX_TIMEOUT: // intentional fall through. - case SSP_TX_BUFOVERRUN: - retval = FALSE; - break; - default: - retval = FALSE; - break; - }; - return retval; -} - - -/*! - * \brief sends out a preformatted packet for a give port - * \param thisport = which port to use. - * \return none. - * - * \note - * Packet should be formed through the use of sf_MakePacket before calling this function. - */ -static void sf_SendPacket(Port_t *thisport) - { - // add 3 to packet data length for: 1 length + 2 CRC (packet overhead) - uint8_t packetLen = thisport->txBuf[LENGTH] + 3; - - // use the raw serial write function so the SYNC byte does not get 'escaped' - thisport->pfSerialWrite(SYNC); - for( uint8_t x = 0; x < packetLen; x++ ) { - sf_write_byte(thisport, thisport->txBuf[x] ); - } - thisport->retryCount++; -} - - -/*! - * \brief converts data to transport layer protocol packet format. - * \param txbuf = buffer to use when forming the packet - * \param pdata = pointer to data to use - * \param length = number of bytes to use - * \param seqNo = sequence number of this packet - * \return none. - * - * \note - * 1. This function does not try to interpret ACK or SYNCH packets. This should - * be done by the caller of this function. - * 2. This function will attempt to format all data upto the size of the tx buffer. - * Any extra data beyond that will be ignored. - * 3. TODO: Should this function return an error if data length to be sent is greater th tx buffer size? - * - */ -void sf_MakePacket( uint8_t *txBuf, const uint8_t * pdata, uint16_t length, uint8_t seqNo ) -{ - uint16_t crc = 0xffff; - uint16_t bufPos = 0; - uint8_t b; - - // add 1 for the seq. number - txBuf[LENGTH] = length + 1; - txBuf[SEQNUM] = seqNo; - crc = sf_crc16( crc, seqNo ); - - length = length + 2; // add two for the length and seqno bytes which are added before the loop. - for( bufPos = 2; bufPos < length; bufPos++ ) { - b = *pdata++; - txBuf[bufPos] = b; - crc = sf_crc16( crc, b ); // update CRC value - } - txBuf[bufPos++] = LOWERBYTE(crc); - txBuf[bufPos] = UPPERBYTE(crc); - -} - -/*! - * \brief sends out an ack packet to given sequence number - * \param thisport = which port to use - * \param seqNumber = sequence number of the packet we would like to ack - * \return none. - * - * \note - * - */ - -static void sf_SendAckPacket( Port_t *thisport, uint8_t seqNumber) -{ - uint8_t AckSeqNumber = SETBIT( seqNumber, ACK_BIT ); - - // create the packet, note we pass AckSequenceNumber directly - sf_MakePacket( thisport->txBuf, NULL, 0, AckSeqNumber ); - sf_SendPacket( thisport ); - // we don't set the timeout for an ACK because we don't ACK our ACKs in this protocol -} - -/*! - * \brief writes a byte out the output channel. Adds escape byte where needed - * \param thisport = which port to use - * \param c = byte to send - * \return none. - * - * \note - * - */ -static void sf_write_byte( Port_t *thisport, uint8_t c ) -{ - if( c == SYNC ) { // check for SYNC byte - thisport->pfSerialWrite( ESC ); // since we are not starting a packet we must ESCAPE the SYNCH byte - thisport->pfSerialWrite( ESC_SYNC ); // now send the escaped synch char - } else if( c == ESC ) { // Check for ESC character - thisport->pfSerialWrite( ESC ); // if it is, we need to send it twice - thisport->pfSerialWrite( ESC ); - } else { - thisport->pfSerialWrite( c ); // otherwise write the byte to serial port - } -} - -/************************************************************************************************************ -* -* NAME: uint16_t ssp_crc16( uint16_t crc, uint16_t data ) -* DESCRIPTION: Uses crc_table to calculate new crc -* ARGUMENTS: -* arg1: crc -* arg2: data - byte to calculate into CRC -* RETURN: New crc -* CREATED: 5/8/02 -* -*************************************************************************************************************/ -/*! - * \brief calculates the new CRC value for 'data' - * \param crc = current CRC value - * \param data = new byte - * \return updated CRC value - * - * \note - * - */ - -static uint16_t sf_crc16( uint16_t crc, uint8_t data ) -{ - return (crc >> 8) ^ CRC_TABLE[( crc ^ data ) & 0x00FF ]; -} - - -/*! - * \brief sets the timeout for the given packet - * \param thisport = which port to use - * \return none. - * - * \note - * - */ - -static void sf_SetSendTimeout( Port_t *thisport ) -{ - uint32_t timeout; - timeout = thisport->pfGetTime() + thisport->timeoutLen; - thisport->timeout = timeout; -} - -/*! - * \brief checks to see if a timeout occured - * \param thisport = which port to use - * \return true = a timeout has occurred - * \return false = has not timed out - * - * \note - * - */ -static uint16_t sf_CheckTimeout( Port_t *thisport ) -{ - uint16_t retval = FALSE; - uint32_t current_time; - - current_time = thisport->pfGetTime(); - if( current_time > thisport->timeout ) { - retval = TRUE; - } - return retval; -} - - -/**************************************************************************** - * NAME: sf_ReceiveState - * DESC: Implements the receive state handling code for escaped and unescaped data - * ARGS: thisport - which port to operate on - * c - incoming byte - * RETURN: - * CREATED: - * NOTES: - * 1. change from using pointer to functions. - ****************************************************************************/ -/*! - * \brief implements the receive state handling code for escaped and unescaped data - * \param thisport = which port to use - * \param c = byte to process through the receive state machine - * \return receive status - * - * \note - * - */ -static int16_t sf_ReceiveState( Port_t *thisport, uint8_t c ) -{ - int16_t retval = SSP_RX_RECEIVING; - - switch( thisport->InputState ) { - case state_unescaped_e: - if( c == SYNC ) { - thisport->DecodeState = decode_len1_e; - } else if ( c == ESC ) { - thisport->InputState = state_escaped_e; - } else { - retval = sf_DecodeState( thisport, c); - } - break; // end of unescaped state. - case state_escaped_e: - thisport->InputState = state_unescaped_e; - if( c == SYNC ) { - thisport->DecodeState = decode_len1_e; - } else if (c == ESC_SYNC ) { - retval = sf_DecodeState( thisport, SYNC); - } else { - retval = sf_DecodeState( thisport, c); - } - break; // end of the escaped state. - default: - break; - } - return retval; -} - -/**************************************************************************** - * NAME: sf_DecodeState - * DESC: Implements the receive state finite state machine - * ARGS: thisport - which port to operate on - * c - incoming byte - * RETURN: - * CREATED: - * NOTES: - * 1. change from using pointer to functions. - ****************************************************************************/ - -/*! - * \brief implements the receiving decoding state machine - * \param thisport = which port to use - * \param c = byte to process - * \return receive status - * - * \note - * - */ -static int16_t sf_DecodeState( Port_t *thisport, uint8_t c ) -{ - int16_t retval; - switch( thisport->DecodeState ) { - case decode_idle_e: - // 'c' is ignored in this state as the only way to leave the idle state is - // recognition of the SYNC byte in the sf_ReceiveState function. - retval = SSP_RX_IDLE; - break; - case decode_len1_e: - thisport->rxBuf[LENGTH]= c; - thisport->rxBufLen = c; - if( thisport->rxBufLen <= thisport->rxBufSize ) { - thisport->DecodeState = decode_seqNo_e; - retval = SSP_RX_RECEIVING; - } else { - thisport->DecodeState = decode_idle_e; - retval = SSP_RX_IDLE; - } - break; - case decode_seqNo_e: - thisport->rxBuf[SEQNUM] = c; - thisport->crc = 0xffff; - thisport->rxBufLen--; // subtract 1 for the seq. no. - thisport->rxBufPos = 2; - - thisport->crc = sf_crc16( thisport->crc, c ); - if( thisport->rxBufLen > 0 ) { - thisport->DecodeState = decode_data_e; - } else { - thisport->DecodeState = decode_crc1_e; - } - retval = SSP_RX_RECEIVING; - break; - case decode_data_e: - thisport->rxBuf[ (thisport->rxBufPos)++] = c; - thisport->crc = sf_crc16( thisport->crc, c ); - if( thisport->rxBufPos == (thisport->rxBufLen+2) ) { - thisport->DecodeState = decode_crc1_e; - } - retval = SSP_RX_RECEIVING; - break; - case decode_crc1_e: - thisport->crc = sf_crc16( thisport->crc, c ); - thisport->DecodeState = decode_crc2_e; - retval = SSP_RX_RECEIVING; - break; - case decode_crc2_e: - thisport->DecodeState = decode_idle_e; - // verify the CRC value for the packet - if( sf_crc16( thisport->crc, c) == 0) { - // TODO shouldn't the return value of sf_ReceivePacket() be checked? - sf_ReceivePacket( thisport ); - retval = SSP_RX_COMPLETE; - } else { - thisport->RxError++; - retval = SSP_RX_IDLE; - } - break; - default: - thisport->DecodeState = decode_idle_e; // unknown state so reset to idle state and wait for the next start of a packet. - retval = SSP_RX_IDLE; - break; - } - return retval; -} - -/************************************************************************************************************ -* -* NAME: int16_t sf_ReceivePacket( ) -* DESCRIPTION: Receive one packet, assumed that data is in rec.buff[] -* ARGUMENTS: -* RETURN: 0 . no new packet was received, could be ack or same packet -* 1 . new packet received -* SSP_PACKET_? -* SSP_PACKET_COMPLETE -* SSP_PACKET_ACK -* CREATED: 5/8/02 -* -*************************************************************************************************************/ -/*! - * \brief receive one packet. calls the callback function if needed. - * \param thisport = which port to use - * \return true = valid data packet received. - * \return false = otherwise - * - * \note - * - * Created: Oct 7, 2010 12:07:22 AM by joe - */ - -static int16_t sf_ReceivePacket(Port_t *thisport) -{ - int16_t value = FALSE; - - if( ISBITSET(thisport->rxBuf[SEQNUM], ACK_BIT ) ) { - // Received an ACK packet, need to check if it matches the previous sent packet - if( ( thisport->rxBuf[SEQNUM] & 0x7F) == (thisport->txSeqNo & 0x7f)) { - // It matches the last packet sent by us - SETBIT( thisport->txSeqNo, ACK_BIT ); - thisport->SendState = SSP_ACKED; - value = FALSE; - } - // else ignore the ACK packet - } else { - // Received a 'data' packet, figure out what type of packet we received... - if( thisport->rxBuf[SEQNUM] == 0 ) { - // Synchronize sequence number with host -#ifdef ACTIVE_SYNCH - thisport->sendSynch = TRUE; -#endif - sf_SendAckPacket( thisport, thisport->rxBuf[SEQNUM] ); - thisport->rxSeqNo = 0; - value = FALSE; - } else if( thisport->rxBuf[SEQNUM] == thisport->rxSeqNo ) { - // Already seen this packet, just ack it, don't act on the packet. - sf_SendAckPacket( thisport, thisport->rxBuf[SEQNUM] ); - value = FALSE; - } else { - //New Packet - thisport->rxSeqNo = thisport->rxBuf[SEQNUM]; - // Let the application do something with the data/packet. - if( thisport->pfCallBack != NULL ) { - // skip the first two bytes (length and seq. no.) in the buffer. - thisport->pfCallBack( &(thisport->rxBuf[2]), thisport->rxBufLen); - } - // after we send the ACK, it is possible for the host to send a new packet. - // Thus the application needs to copy the data and reset the receive buffer - // inside of thisport->pfCallBack() - sf_SendAckPacket( thisport, thisport->rxBuf[SEQNUM] ); - value = TRUE; - } - } - return value; -} - +/*********************************************************************************************************** +* +* NAME: ssp.c +* DESCRIPTION: simple serial protocol - packet based serial transport layer. +* AUTHOR: Joe Hlebasko +* HISTORY: Created 1/1/2010 +* +* Packet Formats +* Format: +* +------+----+------+---------------------------+--------+ +* | 225 | L1 | S# | App Data (0-254 bytes) | CRC 16 | +* +------+----+------+---------------------------+--------+ +* +* 225 = sync byte, indicates start of a packet +* L1 = 1 byte for size of data payload. (sequence number is part of data payload.) +* S# = 1 byte for sequence number. +* Seq of 0 = seq # synchronise request, forces other end to reset receive sequence number to 1. +* sender of synchronise request will reset the tx seq number to 1 +* Seq # of 1..127 = normal data packets. Sequence number is incremented by for each transmitted +* packet. Rolls over from 127 to 1. +* if most sig. bit is set then the packet is an ACK packet of data packet sequence number of the +* lower 7 bits (1..127) +* App Data may contain 0..254 bytes. The sequence number is consider part of the payload. +* CRC 16 - 16 bits of CRC values of Sequence # and data bytes. +* +* Protocol has two types of packets: data and ack packets. ACK packets have the most sig. bit set in the +* sequence number, this implies that valid sequence numbers are 1..127 +* +* This protocol uses the concept of sequences numbers to determine if a given packet has been received. This +* requires both devices to be able to synchronize sequence numbers. This is accomplished by sending a packet +* length 1 and sequence number = 0. The receive then resets it's transmit sequence number to 1. +* +* ACTIVE_SYNCH is a version that will automatically send a synch request if it receives a synch packet. Only +* one device in the communication should do otherwise you end up with an endless loops of synchronization. +* Right now each side needs to manually issues a synch request. +* +* This protocol is best used in cases where one device is the master and the other is the slave, or a don't +* speak unless spoken to type of approach. +* +* The following are items are required to initialize a port for communications: +* 1. The number attempts for each packet +* 2. time to wait for an ack. +* 3. pointer to buffer to be used for receiving. +* 4. pointer to a buffer to be used for transmission +* 5. length of each buffer (rx and tx) +* 6. Four functions: +* 1. write byte = writes a byte out the serial port (or other comm device) +* 2. read byte = retrieves a byte from the serial port. Returns -1 if a byte is not available +* 3. callback = function to call when a valid data packet has been received. This function is responsible +* to do what needs to be done with the data when it is received. The primary mission of this function +* should be to copy the data to a private buffer out of the working receive buffer to prevent overrun. +* processing should be kept to a minimum. +* 4. get time = function should return the current time. Note that time units are not specified it just +* needs to be some measure of time that increments as time passes by. The timeout values for a given +* port should the units used/returned by the get time function. +* +* All of the state information of a communication port is contained in a Port_t structure. This allows this +* module to operature on multiple communication ports with a single code base. +* +* The ssp_ReceiveProcess and ssp_SendProcess functions need to be called to process data through the +* respective state machines. Typical implementation would have a serial ISR to pull bytes out of the UART +* and place into a circular buffer. The serial read function would then pull bytes out this buffer +* processing. The TX side has the write function placing bytes into a circular buffer with the TX ISR +* pulling bytes out of the buffer and putting into the UART. It is possible to run the receive process from +* the receive ISR but care must be taken on processing data when it is received to avoid holding up the ISR +* and sending ACK packets from the receive ISR. +* +***********************************************************************************************************/ + +/** INCLUDE FILES **/ + + + +#include +#include +#include + +#include "ssp.h" + +/** PRIVATE DEFINITIONS **/ +#define SYNC 225 // Sync character used in Serial Protocol +#define ESC 224 // ESC character used in Serial Protocol +#define ESC_SYNC 1 // ESC_SYNC character used in Serial Protocol +#define ACK_BIT 0x80 // Ack bit, bit 7 of sequence number, 1 = Acknowledge, 0 = + // new packet +// packet location definitions. +#define LENGTH 0 +#define SEQNUM 1 +#define DATA 2 + + +// Make larger sized integers from smaller sized integers +#define MAKEWORD16( ub, lb ) ((uint16_t)0x0000 | ((uint16_t)(ub) << 8) | (uint16_t)(lb) ) +#define MAKEWORD32( uw, lw ) ((uint32_t)(0x0UL | ((uint32_t)(uw) << 16) | (uint32_t)(lw)) ) +#define MAKEWORD32B( b3, b2, b1, b0 ) ((uint32_t)((uint32_t)(b3)<< 24) | ((uint32_t)(b2)<<16) | ((uint32_t)(b1)<<8) | ((uint32_t)(b0) ) + + +// Used to extract smaller integers from larger sized intergers +#define LOWERBYTE( w ) (uint8_t)((w) & 0x00ff ) +#define UPPERBYTE( w ) (uint8_t)(((w) & 0xff00) >> 8 ) +#define UPPERWORD(lw) (uint16_t)(((lw) & 0xffff0000) >> 16 ) +#define LOWERWORD(lw) (uint16_t)((lw) & 0x0000ffff) + +// Macros to operate on a target and bitmask. +#define CLEARBIT( a, b ) ((a) = (a) & ~(b)) +#define SETBIT( a, b ) ((a) = (a) | (b) ) +#define TOGGLEBIT(a,b) ((a) = (a) ^ (b) ) + +// test bit macros operate using a bit mask. +#define ISBITSET( a, b ) ( ((a) & (b)) == (b) ? TRUE : FALSE ) +#define ISBITCLEAR( a, b) ( (~(a) & (b)) == (b) ? TRUE : FALSE ) + +/** PRIVATE FUNCTIONS **/ +//static void sf_SendSynchPacket( Port_t *thisport ); +static uint16_t sf_crc16( uint16_t crc, uint8_t data ); +static void sf_write_byte( Port_t *thisport, uint8_t c ); +static void sf_SetSendTimeout( Port_t *thisport ); +static uint16_t sf_CheckTimeout( Port_t *thisport ); +static int16_t sf_DecodeState( Port_t *thisport, uint8_t c ); +static int16_t sf_ReceiveState( Port_t *thisport, uint8_t c ); + +static void sf_SendPacket( Port_t *thisport ); +static void sf_SendAckPacket( Port_t *thisport, uint8_t seqNumber); +static void sf_MakePacket( uint8_t *buf, const uint8_t * pdata, uint16_t length, uint8_t seqNo ); +static int16_t sf_ReceivePacket(Port_t *thisport); + +/* Flag bit masks...*/ +#define SENT_SYNCH (0x01) +#define ACK_RECEIVED (0x02) +#define ACK_EXPECTED (0x04) + +#define SSP_AWAITING_ACK 0 +#define SSP_ACKED 1 +#define SSP_IDLE 2 + +/** PRIVATE DATA **/ +static const uint16_t CRC_TABLE[] = { + 0x0000, 0xC0C1, 0xC181, 0x0140, 0xC301, 0x03C0, 0x0280, 0xC241, + 0xC601, 0x06C0, 0x0780, 0xC741, 0x0500, 0xC5C1, 0xC481, 0x0440, + 0xCC01, 0x0CC0, 0x0D80, 0xCD41, 0x0F00, 0xCFC1, 0xCE81, 0x0E40, + 0x0A00, 0xCAC1, 0xCB81, 0x0B40, 0xC901, 0x09C0, 0x0880, 0xC841, + 0xD801, 0x18C0, 0x1980, 0xD941, 0x1B00, 0xDBC1, 0xDA81, 0x1A40, + 0x1E00, 0xDEC1, 0xDF81, 0x1F40, 0xDD01, 0x1DC0, 0x1C80, 0xDC41, + 0x1400, 0xD4C1, 0xD581, 0x1540, 0xD701, 0x17C0, 0x1680, 0xD641, + 0xD201, 0x12C0, 0x1380, 0xD341, 0x1100, 0xD1C1, 0xD081, 0x1040, + 0xF001, 0x30C0, 0x3180, 0xF141, 0x3300, 0xF3C1, 0xF281, 0x3240, + 0x3600, 0xF6C1, 0xF781, 0x3740, 0xF501, 0x35C0, 0x3480, 0xF441, + 0x3C00, 0xFCC1, 0xFD81, 0x3D40, 0xFF01, 0x3FC0, 0x3E80, 0xFE41, + 0xFA01, 0x3AC0, 0x3B80, 0xFB41, 0x3900, 0xF9C1, 0xF881, 0x3840, + 0x2800, 0xE8C1, 0xE981, 0x2940, 0xEB01, 0x2BC0, 0x2A80, 0xEA41, + 0xEE01, 0x2EC0, 0x2F80, 0xEF41, 0x2D00, 0xEDC1, 0xEC81, 0x2C40, + 0xE401, 0x24C0, 0x2580, 0xE541, 0x2700, 0xE7C1, 0xE681, 0x2640, + 0x2200, 0xE2C1, 0xE381, 0x2340, 0xE101, 0x21C0, 0x2080, 0xE041, + 0xA001, 0x60C0, 0x6180, 0xA141, 0x6300, 0xA3C1, 0xA281, 0x6240, + 0x6600, 0xA6C1, 0xA781, 0x6740, 0xA501, 0x65C0, 0x6480, 0xA441, + 0x6C00, 0xACC1, 0xAD81, 0x6D40, 0xAF01, 0x6FC0, 0x6E80, 0xAE41, + 0xAA01, 0x6AC0, 0x6B80, 0xAB41, 0x6900, 0xA9C1, 0xA881, 0x6840, + 0x7800, 0xB8C1, 0xB981, 0x7940, 0xBB01, 0x7BC0, 0x7A80, 0xBA41, + 0xBE01, 0x7EC0, 0x7F80, 0xBF41, 0x7D00, 0xBDC1, 0xBC81, 0x7C40, + 0xB401, 0x74C0, 0x7580, 0xB541, 0x7700, 0xB7C1, 0xB681, 0x7640, + 0x7200, 0xB2C1, 0xB381, 0x7340, 0xB101, 0x71C0, 0x7080, 0xB041, + 0x5000, 0x90C1, 0x9181, 0x5140, 0x9301, 0x53C0, 0x5280, 0x9241, + 0x9601, 0x56C0, 0x5780, 0x9741, 0x5500, 0x95C1, 0x9481, 0x5440, + 0x9C01, 0x5CC0, 0x5D80, 0x9D41, 0x5F00, 0x9FC1, 0x9E81, 0x5E40, + 0x5A00, 0x9AC1, 0x9B81, 0x5B40, 0x9901, 0x59C0, 0x5880, 0x9841, + 0x8801, 0x48C0, 0x4980, 0x8941, 0x4B00, 0x8BC1, 0x8A81, 0x4A40, + 0x4E00, 0x8EC1, 0x8F81, 0x4F40, 0x8D01, 0x4DC0, 0x4C80, 0x8C41, + 0x4400, 0x84C1, 0x8581, 0x4540, 0x8701, 0x47C0, 0x4680, 0x8641, + 0x8201, 0x42C0, 0x4380, 0x8341, 0x4100, 0x81C1, 0x8081, 0x4040 + }; + +/** EXTERNAL DATA **/ + +/** EXTERNAL FUNCTIONS **/ + +/** VERIFICATION FUNCTIONS **/ + + +/***********************************************************************************************************/ + +/*! + * \brief Initializes the communication port for use + * \param thisport = pointer to port structure to initialize + * \param info = config struct with default values. + * \return None. + * + * \note + * Must be called before calling the Send or REceive process functions. + */ + +void ssp_Init( Port_t *thisport, const PortConfig_t* const info) +{ + thisport->pfCallBack = info->pfCallBack; + thisport->pfSerialRead = info->pfSerialRead; + thisport->pfSerialWrite = info->pfSerialWrite; + thisport->pfGetTime = info->pfGetTime; + + thisport->maxRetryCount = info->max_retry; + thisport->timeoutLen = info->timeoutLen; + thisport->txBufSize = info->txBufSize; + thisport->rxBufSize = info->rxBufSize; + thisport->txBuf = info->txBuf; + thisport->rxBuf = info->rxBuf; + thisport->retryCount = 0; + thisport->sendSynch = FALSE; //TRUE; + thisport->rxSeqNo = 255; + thisport->txSeqNo = 255; + thisport->SendState = SSP_IDLE; +} + +/*! + * \brief Runs the send process, checks for receipt of ack, timeouts and resends if needed. + * \param thisport = which port to use + * \return SSP_TX_WAITING - waiting for a valid ACK to arrive + * \return SSP_TX_TIMEOUT - failed to receive a valid ACK in the timeout period, after retrying. + * \return SSP_TX_IDLE - not expecting a ACK packet (no current transmissions in progress) + * \return SSP_TX_ACKED - valid ACK received before timeout period. + * + * \note + * + */ +int16_t ssp_SendProcess( Port_t *thisport ) +{ + int16_t value = SSP_TX_WAITING; + + if (thisport->SendState == SSP_AWAITING_ACK ) { + if (sf_CheckTimeout(thisport) == TRUE) { + if (thisport->retryCount < thisport->maxRetryCount) { + // Try again + sf_SendPacket(thisport); + sf_SetSendTimeout(thisport); + value = SSP_TX_WAITING; + } else { + // Give up, # of trys has exceded the limit + value = SSP_TX_TIMEOUT; + CLEARBIT( thisport->flags, ACK_RECEIVED); + thisport->SendState = SSP_IDLE; + } + } else { + value = SSP_TX_WAITING; + } + } else if( thisport->SendState == SSP_ACKED ) { + SETBIT( thisport->flags, ACK_RECEIVED); + value = SSP_TX_ACKED; + thisport->SendState = SSP_IDLE; + } else { + thisport->SendState = SSP_IDLE; + value = SSP_TX_IDLE; + } + return value; +} + +/*! + * \brief Runs the receive process. fetches a byte at a time and runs the byte through the protocol receive state machine. + * \param thisport - which port to use. + * \return receive status. + * + * \note + * + */ +int16_t ssp_ReceiveProcess(Port_t *thisport) +{ + int16_t b; + int16_t packet_status = SSP_RX_IDLE; + + do { + b = thisport->pfSerialRead(); // attempt to read a char from the serial buffer + if (b != -1) { + packet_status = sf_ReceiveState(thisport, b); // process the newly received byte in the receive state machine + } + // keep going until either we received a full packet or there are no more bytes to process + } while (packet_status != SSP_RX_COMPLETE && b != -1); + return packet_status; +} + +/*! + * \brief processes a single byte through the receive state machine. + * \param thisport = which port to use + * \return current receive status + * + * \note + * + */ + +int16_t ssp_ReceiveByte(Port_t *thisport ) +{ + int16_t b; + int16_t packet_status = SSP_RX_IDLE; + + b = thisport->pfSerialRead(); + if( b != -1 ) { + packet_status = sf_ReceiveState(thisport, b); + } + return packet_status; +} + +/*! + * \brief Sends a data packet and blocks until timeout or ack is received. + * \param thisport = which port to use + * \param data = pointer to data to send + * \param length = number of data bytes to send. Must be less than 254 + * \return true = ack was received within number of retries + * \return false = ack was not received. + * + * \note + * + */ +uint16_t ssp_SendDataBlock( Port_t *thisport, uint8_t *data, uint16_t length ) +{ + int16_t packet_status = SSP_TX_WAITING; + uint16_t retval = FALSE; + + packet_status = ssp_SendData( thisport, data, length ); // send the data + while( packet_status == SSP_TX_WAITING ) { // check the status + (void)ssp_ReceiveProcess( thisport ); // process any bytes received. + packet_status = ssp_SendProcess( thisport ); // check the send status + } + if( packet_status == SSP_TX_ACKED ) { // figure out what happened to the packet + retval = TRUE; + } else { + retval = FALSE; + } + return retval; +} + +/*! + * \brief sends a chunk of data and does not block + * \param thisport = which port to use + * \param data = pointer to data to send + * \param length = number of bytes to send + * \return SSP_TX_BUFOVERRUN = tried to send too much data + * \return SSP_TX_WAITING = data sent and waiting for an ack to arrive + * \return SSP_TX_BUSY = a packet has already been sent, but not yet acked + * + * \note + * + */ +int16_t ssp_SendData( Port_t *thisport, const uint8_t *data, const uint16_t length ) +{ + + int16_t value = SSP_TX_WAITING; + + if( (length + 2) > thisport->txBufSize ) { + // TRYING to send too much data. + value = SSP_TX_BUFOVERRUN; + } else if( thisport->SendState == SSP_IDLE ) { +#ifdef ACTIVE_SYNCH + if( thisport->sendSynch == TRUE ) { + sf_SendSynchPacket(thisport); + } +#endif + +#ifdef SYNCH_SEND + if( length == 0 ) { + // TODO this method could allow a task/user to start a synchronisation step if a zero is mistakenly passed to this function. + // could add a check for a NULL data pointer, or use some sort of static flag that can only be accessed by a static function + // that must be called before calling this function. + // we are attempting to send a synch packet + thisport->txSeqNo = 0; // make this zero to cause the other end to re-synch with us + SETBIT(thisport->flags, SENT_SYNCH); + } else { + // we are sending a data packet + CLEARBIT( thisport->txSeqNo, ACK_BIT ); // make sure we are not sending a ACK packet + thisport->txSeqNo++; // update the sequence number. + if( thisport->txSeqNo > 0x7F) { // check for sequence number rollover + thisport->txSeqNo = 1; // if we do have rollover then reset to 1 not zero, + // zero is reserviced for synchronization requests + } + } + +#else + CLEARBIT( thisport->txSeqNo, ACK_BIT ); // make sure we are not sending a ACK packet + thisport->txSeqNo++; // update the sequence number. + if( thisport->txSeqNo > 0x7F) { // check for sequence number rollover + thisport->txSeqNo = 1; // if we do have rollover then reset to 1 not zero, + // zero is reserved for synchronization requests + } +#endif + CLEARBIT( thisport->flags, ACK_RECEIVED); + thisport->SendState = SSP_AWAITING_ACK; + value = SSP_TX_WAITING; + thisport->retryCount = 0; // zero out the retry counter for this transmission + sf_MakePacket( thisport->txBuf, data, length, thisport->txSeqNo ); + sf_SendPacket( thisport ); // punch out the packet to the serial port + sf_SetSendTimeout( thisport ); // do the timeout values + } else { + // error we are already sending a packet. Need to wait for the current packet to be acked or timeout. + value = SSP_TX_BUSY; + } + return value; +} + +/*! + * \brief Attempts to synchronize the sequence numbers with the other end of the connectin. + * \param thisport = which port to use + * \return true = success + * \return false = failed to receive an ACK to our synch request + * + * \note + * A. send a packet with a sequence number equal to zero + * B. if timed out then: + * send synch packet again + * increment try counter + * if number of tries exceed maximum try limit then exit + * C. goto A + */ +uint16_t ssp_Synchronise( Port_t *thisport ) +{ + int16_t packet_status; + uint16_t retval = FALSE; + +#ifndef USE_SENDPACKET_DATA + thisport->txSeqNo = 0; // make this zero to cause the other end to re-synch with us + SETBIT(thisport->flags, SENT_SYNCH); + // TODO - should this be using ssp_SendPacketData()?? + sf_MakePacket( thisport->txBuf, NULL, 0, thisport->txSeqNo ); // construct the packet + sf_SendPacket( thisport ); + sf_SetSendTimeout( thisport ); + thisport->SendState = SSP_AWAITING_ACK; + packet_status = SSP_TX_WAITING; +#else + packet_status = ssp_SendData( thisport, NULL, 0 ); +#endif + while( packet_status == SSP_TX_WAITING ) { // we loop until we time out. + (void)ssp_ReceiveProcess( thisport ); // do the receive process + packet_status = ssp_SendProcess( thisport ); // do the send process + } + thisport->sendSynch = FALSE; + switch( packet_status ) { + case SSP_TX_ACKED: + retval = TRUE; + break; + case SSP_TX_BUSY: // intentional fall through. + case SSP_TX_TIMEOUT: // intentional fall through. + case SSP_TX_BUFOVERRUN: + retval = FALSE; + break; + default: + retval = FALSE; + break; + }; + return retval; +} + + +/*! + * \brief sends out a preformatted packet for a give port + * \param thisport = which port to use. + * \return none. + * + * \note + * Packet should be formed through the use of sf_MakePacket before calling this function. + */ +static void sf_SendPacket(Port_t *thisport) + { + // add 3 to packet data length for: 1 length + 2 CRC (packet overhead) + uint8_t packetLen = thisport->txBuf[LENGTH] + 3; + + // use the raw serial write function so the SYNC byte does not get 'escaped' + thisport->pfSerialWrite(SYNC); + for( uint8_t x = 0; x < packetLen; x++ ) { + sf_write_byte(thisport, thisport->txBuf[x] ); + } + thisport->retryCount++; +} + + +/*! + * \brief converts data to transport layer protocol packet format. + * \param txbuf = buffer to use when forming the packet + * \param pdata = pointer to data to use + * \param length = number of bytes to use + * \param seqNo = sequence number of this packet + * \return none. + * + * \note + * 1. This function does not try to interpret ACK or SYNCH packets. This should + * be done by the caller of this function. + * 2. This function will attempt to format all data upto the size of the tx buffer. + * Any extra data beyond that will be ignored. + * 3. TODO: Should this function return an error if data length to be sent is greater th tx buffer size? + * + */ +void sf_MakePacket( uint8_t *txBuf, const uint8_t * pdata, uint16_t length, uint8_t seqNo ) +{ + uint16_t crc = 0xffff; + uint16_t bufPos = 0; + uint8_t b; + + // add 1 for the seq. number + txBuf[LENGTH] = length + 1; + txBuf[SEQNUM] = seqNo; + crc = sf_crc16( crc, seqNo ); + + length = length + 2; // add two for the length and seqno bytes which are added before the loop. + for( bufPos = 2; bufPos < length; bufPos++ ) { + b = *pdata++; + txBuf[bufPos] = b; + crc = sf_crc16( crc, b ); // update CRC value + } + txBuf[bufPos++] = LOWERBYTE(crc); + txBuf[bufPos] = UPPERBYTE(crc); + +} + +/*! + * \brief sends out an ack packet to given sequence number + * \param thisport = which port to use + * \param seqNumber = sequence number of the packet we would like to ack + * \return none. + * + * \note + * + */ + +static void sf_SendAckPacket( Port_t *thisport, uint8_t seqNumber) +{ + uint8_t AckSeqNumber = SETBIT( seqNumber, ACK_BIT ); + + // create the packet, note we pass AckSequenceNumber directly + sf_MakePacket( thisport->txBuf, NULL, 0, AckSeqNumber ); + sf_SendPacket( thisport ); + // we don't set the timeout for an ACK because we don't ACK our ACKs in this protocol +} + +/*! + * \brief writes a byte out the output channel. Adds escape byte where needed + * \param thisport = which port to use + * \param c = byte to send + * \return none. + * + * \note + * + */ +static void sf_write_byte( Port_t *thisport, uint8_t c ) +{ + if( c == SYNC ) { // check for SYNC byte + thisport->pfSerialWrite( ESC ); // since we are not starting a packet we must ESCAPE the SYNCH byte + thisport->pfSerialWrite( ESC_SYNC ); // now send the escaped synch char + } else if( c == ESC ) { // Check for ESC character + thisport->pfSerialWrite( ESC ); // if it is, we need to send it twice + thisport->pfSerialWrite( ESC ); + } else { + thisport->pfSerialWrite( c ); // otherwise write the byte to serial port + } +} + +/************************************************************************************************************ +* +* NAME: uint16_t ssp_crc16( uint16_t crc, uint16_t data ) +* DESCRIPTION: Uses crc_table to calculate new crc +* ARGUMENTS: +* arg1: crc +* arg2: data - byte to calculate into CRC +* RETURN: New crc +* CREATED: 5/8/02 +* +*************************************************************************************************************/ +/*! + * \brief calculates the new CRC value for 'data' + * \param crc = current CRC value + * \param data = new byte + * \return updated CRC value + * + * \note + * + */ + +static uint16_t sf_crc16( uint16_t crc, uint8_t data ) +{ + return (crc >> 8) ^ CRC_TABLE[( crc ^ data ) & 0x00FF ]; +} + + +/*! + * \brief sets the timeout for the given packet + * \param thisport = which port to use + * \return none. + * + * \note + * + */ + +static void sf_SetSendTimeout( Port_t *thisport ) +{ + uint32_t timeout; + timeout = thisport->pfGetTime() + thisport->timeoutLen; + thisport->timeout = timeout; +} + +/*! + * \brief checks to see if a timeout occured + * \param thisport = which port to use + * \return true = a timeout has occurred + * \return false = has not timed out + * + * \note + * + */ +static uint16_t sf_CheckTimeout( Port_t *thisport ) +{ + uint16_t retval = FALSE; + uint32_t current_time; + + current_time = thisport->pfGetTime(); + if( current_time > thisport->timeout ) { + retval = TRUE; + } + return retval; +} + + +/**************************************************************************** + * NAME: sf_ReceiveState + * DESC: Implements the receive state handling code for escaped and unescaped data + * ARGS: thisport - which port to operate on + * c - incoming byte + * RETURN: + * CREATED: + * NOTES: + * 1. change from using pointer to functions. + ****************************************************************************/ +/*! + * \brief implements the receive state handling code for escaped and unescaped data + * \param thisport = which port to use + * \param c = byte to process through the receive state machine + * \return receive status + * + * \note + * + */ +static int16_t sf_ReceiveState( Port_t *thisport, uint8_t c ) +{ + int16_t retval = SSP_RX_RECEIVING; + + switch( thisport->InputState ) { + case state_unescaped_e: + if( c == SYNC ) { + thisport->DecodeState = decode_len1_e; + } else if ( c == ESC ) { + thisport->InputState = state_escaped_e; + } else { + retval = sf_DecodeState( thisport, c); + } + break; // end of unescaped state. + case state_escaped_e: + thisport->InputState = state_unescaped_e; + if( c == SYNC ) { + thisport->DecodeState = decode_len1_e; + } else if (c == ESC_SYNC ) { + retval = sf_DecodeState( thisport, SYNC); + } else { + retval = sf_DecodeState( thisport, c); + } + break; // end of the escaped state. + default: + break; + } + return retval; +} + +/**************************************************************************** + * NAME: sf_DecodeState + * DESC: Implements the receive state finite state machine + * ARGS: thisport - which port to operate on + * c - incoming byte + * RETURN: + * CREATED: + * NOTES: + * 1. change from using pointer to functions. + ****************************************************************************/ + +/*! + * \brief implements the receiving decoding state machine + * \param thisport = which port to use + * \param c = byte to process + * \return receive status + * + * \note + * + */ +static int16_t sf_DecodeState( Port_t *thisport, uint8_t c ) +{ + int16_t retval; + switch( thisport->DecodeState ) { + case decode_idle_e: + // 'c' is ignored in this state as the only way to leave the idle state is + // recognition of the SYNC byte in the sf_ReceiveState function. + retval = SSP_RX_IDLE; + break; + case decode_len1_e: + thisport->rxBuf[LENGTH]= c; + thisport->rxBufLen = c; + if( thisport->rxBufLen <= thisport->rxBufSize ) { + thisport->DecodeState = decode_seqNo_e; + retval = SSP_RX_RECEIVING; + } else { + thisport->DecodeState = decode_idle_e; + retval = SSP_RX_IDLE; + } + break; + case decode_seqNo_e: + thisport->rxBuf[SEQNUM] = c; + thisport->crc = 0xffff; + thisport->rxBufLen--; // subtract 1 for the seq. no. + thisport->rxBufPos = 2; + + thisport->crc = sf_crc16( thisport->crc, c ); + if( thisport->rxBufLen > 0 ) { + thisport->DecodeState = decode_data_e; + } else { + thisport->DecodeState = decode_crc1_e; + } + retval = SSP_RX_RECEIVING; + break; + case decode_data_e: + thisport->rxBuf[ (thisport->rxBufPos)++] = c; + thisport->crc = sf_crc16( thisport->crc, c ); + if( thisport->rxBufPos == (thisport->rxBufLen+2) ) { + thisport->DecodeState = decode_crc1_e; + } + retval = SSP_RX_RECEIVING; + break; + case decode_crc1_e: + thisport->crc = sf_crc16( thisport->crc, c ); + thisport->DecodeState = decode_crc2_e; + retval = SSP_RX_RECEIVING; + break; + case decode_crc2_e: + thisport->DecodeState = decode_idle_e; + // verify the CRC value for the packet + if( sf_crc16( thisport->crc, c) == 0) { + // TODO shouldn't the return value of sf_ReceivePacket() be checked? + sf_ReceivePacket( thisport ); + retval = SSP_RX_COMPLETE; + } else { + thisport->RxError++; + retval = SSP_RX_IDLE; + } + break; + default: + thisport->DecodeState = decode_idle_e; // unknown state so reset to idle state and wait for the next start of a packet. + retval = SSP_RX_IDLE; + break; + } + return retval; +} + +/************************************************************************************************************ +* +* NAME: int16_t sf_ReceivePacket( ) +* DESCRIPTION: Receive one packet, assumed that data is in rec.buff[] +* ARGUMENTS: +* RETURN: 0 . no new packet was received, could be ack or same packet +* 1 . new packet received +* SSP_PACKET_? +* SSP_PACKET_COMPLETE +* SSP_PACKET_ACK +* CREATED: 5/8/02 +* +*************************************************************************************************************/ +/*! + * \brief receive one packet. calls the callback function if needed. + * \param thisport = which port to use + * \return true = valid data packet received. + * \return false = otherwise + * + * \note + * + * Created: Oct 7, 2010 12:07:22 AM by joe + */ + +static int16_t sf_ReceivePacket(Port_t *thisport) +{ + int16_t value = FALSE; + + if( ISBITSET(thisport->rxBuf[SEQNUM], ACK_BIT ) ) { + // Received an ACK packet, need to check if it matches the previous sent packet + if( ( thisport->rxBuf[SEQNUM] & 0x7F) == (thisport->txSeqNo & 0x7f)) { + // It matches the last packet sent by us + SETBIT( thisport->txSeqNo, ACK_BIT ); + thisport->SendState = SSP_ACKED; + value = FALSE; + } + // else ignore the ACK packet + } else { + // Received a 'data' packet, figure out what type of packet we received... + if( thisport->rxBuf[SEQNUM] == 0 ) { + // Synchronize sequence number with host +#ifdef ACTIVE_SYNCH + thisport->sendSynch = TRUE; +#endif + sf_SendAckPacket( thisport, thisport->rxBuf[SEQNUM] ); + thisport->rxSeqNo = 0; + value = FALSE; + } else if( thisport->rxBuf[SEQNUM] == thisport->rxSeqNo ) { + // Already seen this packet, just ack it, don't act on the packet. + sf_SendAckPacket( thisport, thisport->rxBuf[SEQNUM] ); + value = FALSE; + } else { + //New Packet + thisport->rxSeqNo = thisport->rxBuf[SEQNUM]; + // Let the application do something with the data/packet. + if( thisport->pfCallBack != NULL ) { + // skip the first two bytes (length and seq. no.) in the buffer. + thisport->pfCallBack( &(thisport->rxBuf[2]), thisport->rxBufLen); + } + // after we send the ACK, it is possible for the host to send a new packet. + // Thus the application needs to copy the data and reset the receive buffer + // inside of thisport->pfCallBack() + sf_SendAckPacket( thisport, thisport->rxBuf[SEQNUM] ); + value = TRUE; + } + } + return value; +} + diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp.h b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp.h index 59ef87e0e..e269043ea 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp.h +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp.h @@ -1,121 +1,121 @@ -/******************************************************************* - * - * NAME: ssp.h - * - * - *******************************************************************/ -#ifndef SSP_H -#define SSP_H -/** INCLUDE FILES **/ -#include - -/** LOCAL DEFINITIONS **/ -#ifndef TRUE -#define TRUE 1 -#endif - -#ifndef FALSE -#define FALSE 0 -#endif - -#define SSP_TX_IDLE 0 // not expecting a ACK packet (no current transmissions in progress) -#define SSP_TX_WAITING 1 // waiting for a valid ACK to arrive -#define SSP_TX_TIMEOUT 2 // failed to receive a valid ACK in the timeout period, after retrying. -#define SSP_TX_ACKED 3 // valid ACK received before timeout period. -#define SSP_TX_BUFOVERRUN 4 // amount of data to send execeds the transmission buffer sizeof -#define SSP_TX_BUSY 5 // Attempted to start a transmission while a transmission was already in progress. -//#define SSP_TX_FAIL - failure... - -#define SSP_RX_IDLE 0 -#define SSP_RX_RECEIVING 1 -#define SSP_RX_COMPLETE 2 - -// types of packet that can be received -#define SSP_RX_DATA 5 -#define SSP_RX_ACK 6 -#define SSP_RX_SYNCH 7 - -typedef enum decodeState_ { - decode_len1_e = 0, - decode_seqNo_e, - decode_data_e, - decode_crc1_e, - decode_crc2_e, - decode_idle_e -} DecodeState_t; - -typedef enum ReceiveState { - state_escaped_e = 0, - state_unescaped_e -} ReceiveState_t; - -typedef struct -{ - uint8_t *pbuff; - uint16_t length; - uint16_t crc; - uint8_t seqNo; -} Packet_t; - -typedef struct { - - uint8_t *rxBuf; // Buffer used to store rcv data - uint16_t rxBufSize; // rcv buffer size. - uint8_t *txBuf; // Length of data in buffer - uint16_t txBufSize; // CRC for data in Packet buff - uint16_t max_retry; // Maximum number of retrys for a single transmit. - int32_t timeoutLen; // how long to wait for each retry to succeed - void (*pfCallBack)( uint8_t *, uint16_t); // call back function that is called when a full packet has been received - int16_t (*pfSerialRead)(void); // function to call to read a byte from serial hardware - void (*pfSerialWrite)( uint8_t ); // function used to write a byte to serial hardware for transmission - uint32_t (*pfGetTime)(void); // function returns time in number of seconds that has elapsed from a given reference point -} PortConfig_t; - -typedef struct Port_tag { - void (*pfCallBack)( uint8_t *, uint16_t); // call back function that is called when a full packet has been received - int16_t (*pfSerialRead)(void); // function to read a character from the serial input stream - void (*pfSerialWrite)( uint8_t ); // function to write a byte to be sent out the serial port - uint32_t (*pfGetTime)(void); // function returns time in number of seconds that has elapsed from a given reference point - uint8_t retryCount; // how many times have we tried to transmit the 'send' packet - uint8_t maxRetryCount; // max. times to try to transmit the 'send' packet - int32_t timeoutLen; // how long to wait for each retry to succeed - int32_t timeout; // current timeout. when 'time' reaches this point we have timed out - uint8_t txSeqNo; // current 'send' packet sequence number - uint16_t rxBufPos; // current buffer position in the receive packet - uint16_t rxBufLen; // number of 'data' bytes in the buffer - uint8_t rxSeqNo; // current 'receive' packet number - uint16_t rxBufSize; // size of the receive buffer. - uint16_t txBufSize; // size of the transmit buffer. - uint8_t *txBuf; // transmit buffer. REquired to store a copy of packet data in case a retry is needed. - uint8_t *rxBuf; // receive buffer. Used to store data as a packet is received. - uint16_t sendSynch; // flag to indicate that we should send a synchronize packet to the host - // this is required when switching from the application to the bootloader - // and vice-versa. This fixes the firwmare download timeout. - // when this flag is set to true, the next time we send a packet we will first - // send a synchronize packet. - ReceiveState_t InputState; - DecodeState_t DecodeState; - uint16_t SendState; - uint16_t crc; - uint32_t RxError; - uint32_t TxError; - uint16_t flags; -} Port_t; - - - -/** Public Data **/ - -/** PUBLIC FUNCTIONS **/ -int16_t ssp_ReceiveProcess( Port_t *thisport ); -int16_t ssp_SendProcess( Port_t *thisport ); -uint16_t ssp_SendString( Port_t *thisport, char *str ); -int16_t ssp_SendData(Port_t *thisport, const uint8_t * data,const uint16_t length ); -void ssp_Init( Port_t *thisport, const PortConfig_t* const info); -int16_t ssp_ReceiveByte(Port_t *thisport ); -uint16_t ssp_Synchronise( Port_t *thisport ); - - -/** EXTERNAL FUNCTIONS **/ - -#endif +/******************************************************************* + * + * NAME: ssp.h + * + * + *******************************************************************/ +#ifndef SSP_H +#define SSP_H +/** INCLUDE FILES **/ +#include + +/** LOCAL DEFINITIONS **/ +#ifndef TRUE +#define TRUE 1 +#endif + +#ifndef FALSE +#define FALSE 0 +#endif + +#define SSP_TX_IDLE 0 // not expecting a ACK packet (no current transmissions in progress) +#define SSP_TX_WAITING 1 // waiting for a valid ACK to arrive +#define SSP_TX_TIMEOUT 2 // failed to receive a valid ACK in the timeout period, after retrying. +#define SSP_TX_ACKED 3 // valid ACK received before timeout period. +#define SSP_TX_BUFOVERRUN 4 // amount of data to send execeds the transmission buffer sizeof +#define SSP_TX_BUSY 5 // Attempted to start a transmission while a transmission was already in progress. +//#define SSP_TX_FAIL - failure... + +#define SSP_RX_IDLE 0 +#define SSP_RX_RECEIVING 1 +#define SSP_RX_COMPLETE 2 + +// types of packet that can be received +#define SSP_RX_DATA 5 +#define SSP_RX_ACK 6 +#define SSP_RX_SYNCH 7 + +typedef enum decodeState_ { + decode_len1_e = 0, + decode_seqNo_e, + decode_data_e, + decode_crc1_e, + decode_crc2_e, + decode_idle_e +} DecodeState_t; + +typedef enum ReceiveState { + state_escaped_e = 0, + state_unescaped_e +} ReceiveState_t; + +typedef struct +{ + uint8_t *pbuff; + uint16_t length; + uint16_t crc; + uint8_t seqNo; +} Packet_t; + +typedef struct { + + uint8_t *rxBuf; // Buffer used to store rcv data + uint16_t rxBufSize; // rcv buffer size. + uint8_t *txBuf; // Length of data in buffer + uint16_t txBufSize; // CRC for data in Packet buff + uint16_t max_retry; // Maximum number of retrys for a single transmit. + int32_t timeoutLen; // how long to wait for each retry to succeed + void (*pfCallBack)( uint8_t *, uint16_t); // call back function that is called when a full packet has been received + int16_t (*pfSerialRead)(void); // function to call to read a byte from serial hardware + void (*pfSerialWrite)( uint8_t ); // function used to write a byte to serial hardware for transmission + uint32_t (*pfGetTime)(void); // function returns time in number of seconds that has elapsed from a given reference point +} PortConfig_t; + +typedef struct Port_tag { + void (*pfCallBack)( uint8_t *, uint16_t); // call back function that is called when a full packet has been received + int16_t (*pfSerialRead)(void); // function to read a character from the serial input stream + void (*pfSerialWrite)( uint8_t ); // function to write a byte to be sent out the serial port + uint32_t (*pfGetTime)(void); // function returns time in number of seconds that has elapsed from a given reference point + uint8_t retryCount; // how many times have we tried to transmit the 'send' packet + uint8_t maxRetryCount; // max. times to try to transmit the 'send' packet + int32_t timeoutLen; // how long to wait for each retry to succeed + int32_t timeout; // current timeout. when 'time' reaches this point we have timed out + uint8_t txSeqNo; // current 'send' packet sequence number + uint16_t rxBufPos; // current buffer position in the receive packet + uint16_t rxBufLen; // number of 'data' bytes in the buffer + uint8_t rxSeqNo; // current 'receive' packet number + uint16_t rxBufSize; // size of the receive buffer. + uint16_t txBufSize; // size of the transmit buffer. + uint8_t *txBuf; // transmit buffer. REquired to store a copy of packet data in case a retry is needed. + uint8_t *rxBuf; // receive buffer. Used to store data as a packet is received. + uint16_t sendSynch; // flag to indicate that we should send a synchronize packet to the host + // this is required when switching from the application to the bootloader + // and vice-versa. This fixes the firwmare download timeout. + // when this flag is set to true, the next time we send a packet we will first + // send a synchronize packet. + ReceiveState_t InputState; + DecodeState_t DecodeState; + uint16_t SendState; + uint16_t crc; + uint32_t RxError; + uint32_t TxError; + uint16_t flags; +} Port_t; + + + +/** Public Data **/ + +/** PUBLIC FUNCTIONS **/ +int16_t ssp_ReceiveProcess( Port_t *thisport ); +int16_t ssp_SendProcess( Port_t *thisport ); +uint16_t ssp_SendString( Port_t *thisport, char *str ); +int16_t ssp_SendData(Port_t *thisport, const uint8_t * data,const uint16_t length ); +void ssp_Init( Port_t *thisport, const PortConfig_t* const info); +int16_t ssp_ReceiveByte(Port_t *thisport ); +uint16_t ssp_Synchronise( Port_t *thisport ); + + +/** EXTERNAL FUNCTIONS **/ + +#endif diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp_test.pro b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp_test.pro index 2ed07b42f..e0fdc09e0 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp_test.pro +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/SSP/ssp_test.pro @@ -1,42 +1,42 @@ -#------------------------------------------------- -# -# Project created by QtCreator 2010-07-24T11:26:38 -# -#------------------------------------------------- - -QT += core - -QT -= gui -DEFINES += QEXTSERIALPORT_LIBRARY -TARGET = ssp_test -CONFIG += console -CONFIG -= app_bundle - -TEMPLATE = app - -SOURCES += main.cpp \ - qssp.cpp \ - port.cpp \ - qsspt.cpp -HEADERS += ../../../libs/qextserialport/src/qextserialport.h \ - ../../../libs/qextserialport/src/qextserialenumerator.h \ - ../../../libs/qextserialport/src/qextserialport_global.h \ - qssp.h \ - port.h \ - common.h \ - qsspt.h -SOURCES += ../../../libs/qextserialport/src/qextserialport.cpp - -unix:SOURCES += ../../../libs/qextserialport/src/posix_qextserialport.cpp -unix:!macx:SOURCES += ../../../libs/qextserialport/src/qextserialenumerator_unix.cpp -macx { - SOURCES += ../../../libs/qextserialport/src/qextserialenumerator_osx.cpp - LIBS += -framework IOKit -framework CoreFoundation -} - -win32 { - SOURCES += ../../../libs/qextserialport/src/win_qextserialport.cpp \ -../../../libs/qextserialport/src/qextserialenumerator_win.cpp - DEFINES += WINVER=0x0501 # needed for mingw to pull in appropriate dbt business...probably a better way to do this - LIBS += -lsetupapi -} +#------------------------------------------------- +# +# Project created by QtCreator 2010-07-24T11:26:38 +# +#------------------------------------------------- + +QT += core + +QT -= gui +DEFINES += QEXTSERIALPORT_LIBRARY +TARGET = ssp_test +CONFIG += console +CONFIG -= app_bundle + +TEMPLATE = app + +SOURCES += main.cpp \ + qssp.cpp \ + port.cpp \ + qsspt.cpp +HEADERS += ../../../libs/qextserialport/src/qextserialport.h \ + ../../../libs/qextserialport/src/qextserialenumerator.h \ + ../../../libs/qextserialport/src/qextserialport_global.h \ + qssp.h \ + port.h \ + common.h \ + qsspt.h +SOURCES += ../../../libs/qextserialport/src/qextserialport.cpp + +unix:SOURCES += ../../../libs/qextserialport/src/posix_qextserialport.cpp +unix:!macx:SOURCES += ../../../libs/qextserialport/src/qextserialenumerator_unix.cpp +macx { + SOURCES += ../../../libs/qextserialport/src/qextserialenumerator_osx.cpp + LIBS += -framework IOKit -framework CoreFoundation +} + +win32 { + SOURCES += ../../../libs/qextserialport/src/win_qextserialport.cpp \ +../../../libs/qextserialport/src/qextserialenumerator_win.cpp + DEFINES += WINVER=0x0501 # needed for mingw to pull in appropriate dbt business...probably a better way to do this + LIBS += -lsetupapi +} diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/delay.cpp b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/delay.cpp index d681db85f..3ef75e8ee 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/delay.cpp +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/delay.cpp @@ -1,3 +1,3 @@ - -#include "delay.h" - + +#include "delay.h" + diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/delay.h b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/delay.h index ccf14ee5b..7119a770d 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/delay.h +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/delay.h @@ -1,13 +1,13 @@ -#ifndef DELAY_H -#define DELAY_H -#include - -class delay : public QThread -{ -public: - static void msleep(unsigned long msecs) - { - QThread::msleep(msecs); - } -}; -#endif // DELAY_H +#ifndef DELAY_H +#define DELAY_H +#include + +class delay : public QThread +{ +public: + static void msleep(unsigned long msecs) + { + QThread::msleep(msecs); + } +}; +#endif // DELAY_H diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/op_dfu.cpp b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/op_dfu.cpp index 363cb17b4..d89f0916f 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/op_dfu.cpp +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/op_dfu.cpp @@ -1,868 +1,868 @@ -#include "op_dfu.h" -#include -#include -#include - -OP_DFU::OP_DFU(bool _debug,bool _use_serial,QString portname,bool umodereset): debug(_debug),use_serial(_use_serial),mready(true) -{ - if(use_serial) - { - cout<<"Connect hw now and press any key"; - // getch(); - // delay::msleep(2000); - PortSettings settings; - settings.BaudRate=BAUD57600; - settings.DataBits=DATA_8; - settings.FlowControl=FLOW_OFF; - settings.Parity=PAR_NONE; - settings.StopBits=STOP_1; - settings.Timeout_Millisec=1000; - info=new port(settings,portname); - info->rxBuf = sspRxBuf; - info->rxBufSize = MAX_PACKET_DATA_LEN; - info->txBuf = sspTxBuf; - info->txBufSize = MAX_PACKET_DATA_LEN; - info->max_retry = 10; - info->timeoutLen = 1000; - if(info->status()!=port::open) - { - cout<<"Could not open serial port\n"; - mready=false; - return; - } - if(umodereset) - sendReset(); - delay::msleep(5000); - serialhandle=new qsspt(info,debug); - - while(serialhandle->ssp_Synchronise()==false) - { - if (debug) - qDebug()<<"SYNC failed, resending"; - } - qDebug()<<"SYNC Succeded"; - serialhandle->start(); - // serialhandle->start(); - } - else - { - - send_delay=10; - use_delay=true; - int numDevices=0; - cout<<"Please connect device now\n"; - int count=0; - while(numDevices==0) - { - cout<<"."; - delay::msleep(500); - numDevices = hidHandle.open(1,0x20a0,0x415A,0,0); //0xff9c,0x0001); - if(numDevices==0) - numDevices = hidHandle.open(1,0x20a0,0x415B,0,0); //0xff9c,0x0001); - if(++count==10) - { - cout<<"\r"; - cout<<" "; - cout<<"\r"; - count=0; - } - } - if(debug) - qDebug() << numDevices << " device(s) opened"; - if(umodereset) - { - sendReset(); - - qDebug()<<"before delay"; - delay::msleep(5000); - qDebug()<<"after delay"; - if(hidHandle.open(1,0x20a0,0x4117,0,0)==0) - mready=false; - } - } -} -void OP_DFU::sendReset(void) -{ - qDebug()<<"Requesting user mode reset"; - char aa[255]= {0x02,0x3E,0x3C,0x20,0x75,0x00,0x20,0x4F,0x67,0x34,0x62,0x04,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00};//63 - char ba[255]= {0x02,0x3E,0x3C,0x20,0x75,0x00,0x20,0x4F,0x67,0x34,0xB9,0x08,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}; - char ca[255]= {0x02,0x3E,0x3C,0x20,0x75,0x00,0x20,0x4F,0x67,0x34,0x10,0x0D,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}; - char bb[255]={0x02,0x3D,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x28,0x8D,0x19,0x00,0x00,0x13}; - char ab[255]={0x02,0x3D,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x47,0x1B,0x19,0x00,0x00,0x76}; - char cb[255]={0x02,0x3D,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x66,0x78,0x1C,0x00,0x00,0x25}; - //125 - if(!use_serial) - { - hidHandle.send(0,aa, 64, 5000); - hidHandle.send(0,ab, 64, 5000); - delay::msleep(600); - hidHandle.send(0,ba, 64, 5000); - hidHandle.send(0,bb, 64, 5000); - delay::msleep(600); - hidHandle.send(0,ca, 64, 5000); - hidHandle.send(0,cb, 64, 5000); - delay::msleep(100); - hidHandle.close(1); -} - else - { - char a[255]; - char b[255]; - char c[255]; - memcpy (a,aa+2,62); - memcpy (a+62,ab+2,60); - memcpy (b,ba+2,62); - memcpy (b+62,bb+2,60); - memcpy (c,ca+2,62); - memcpy (c+62,cb+2,60); - for(int x=0;x<123;++x) - info->pfSerialWrite(a[x]); - delay::msleep(600); - for(int x=0;x<123;++x) - info->pfSerialWrite(b[x]); - delay::msleep(600); - for(int x=0;x<123;++x) - info->pfSerialWrite(c[x]); - } -} - -bool OP_DFU::SaveByteArrayToFile(QString const & sfile, const QByteArray &array) -{ - QFile file(sfile); - //QFile file("in.txt"); - if (!file.open(QIODevice::WriteOnly)) - { - if(debug) - qDebug()<<"Cant open file"; - return false; - } - file.write(array); - file.close(); - return true; -} - -bool OP_DFU::enterDFU(int const &devNumber) -{ - char buf[BUF_LEN]; - buf[0] =0x02;//reportID - buf[1] = OP_DFU::EnterDFU;//DFU Command - buf[2] = 0;//DFU Count - buf[3] = 0;//DFU Count - buf[4] = 0;//DFU Count - buf[5] = 0;//DFU Count - buf[6] = devNumber;//DFU Data0 - buf[7] = 1;//DFU Data1 - buf[8] = 1;//DFU Data2 - buf[9] = 1;//DFU Data3 - - int result = sendData(buf, BUF_LEN); - if(result<1) - return false; - if(debug) - qDebug() << result << " bytes sent"; - return true; -} -bool OP_DFU::StartUpload(qint32 const & numberOfBytes, TransferTypes const & type,quint32 crc) -{ - int lastPacketCount; - qint32 numberOfPackets=numberOfBytes/4/14; - int pad=(numberOfBytes-numberOfPackets*4*14)/4; - if(pad==0) - { - lastPacketCount=14; - } - else - { - ++numberOfPackets; - lastPacketCount=pad; - } - char buf[BUF_LEN]; - buf[0] =0x02;//reportID - buf[1] = setStartBit(OP_DFU::Upload);//DFU Command - buf[2] = numberOfPackets>>24;//DFU Count - buf[3] = numberOfPackets>>16;//DFU Count - buf[4] = numberOfPackets>>8;//DFU Count - buf[5] = numberOfPackets;//DFU Count - buf[6] = (int)type;//DFU Data0 - buf[7] = lastPacketCount;//DFU Data1 - buf[8] = crc>>24; - buf[9] = crc>>16; - buf[10] = crc>>8; - buf[11] = crc; - if(debug) - qDebug()<<"Number of packets:"<0) - { - return true; - } - return false; -} -bool OP_DFU::UploadData(qint32 const & numberOfBytes, QByteArray & data) -{ - int lastPacketCount; - qint32 numberOfPackets=numberOfBytes/4/14; - int pad=(numberOfBytes-numberOfPackets*4*14)/4; - if(pad==0) - { - lastPacketCount=14; - } - else - { - ++numberOfPackets; - lastPacketCount=pad; - } - if(debug) - qDebug()<<"Start Uploading:"<>24;//DFU Count - buf[3] = packetcount>>16;//DFU Count - buf[4] = packetcount>>8;//DFU Count - buf[5] = packetcount;//DFU Count - char *pointer=data.data(); - pointer=pointer+4*14*packetcount; - // qDebug()<<"Packet Number="<>24;//DFU Count - buf[3] = numberOfPackets>>16;//DFU Count - buf[4] = numberOfPackets>>8;//DFU Count - buf[5] = numberOfPackets;//DFU Count - buf[6] = (int)type;//DFU Data0 - buf[7] = lastPacketCount;//DFU Data1 - buf[8] = 1;//DFU Data2 - buf[9] = 1;//DFU Data3 - - int result = sendData(buf, BUF_LEN); - if(debug) - qDebug() << "StartDownload:"<>(x*2) & 1); - dev.Writable=(bool)(RWFlags>>(x*2+1) & 1); - devices.append(dev); - buf[0] =0x02;//reportID - buf[1] = OP_DFU::Req_Capabilities;//DFU Command - buf[2] = 0; - buf[3] = 0; - buf[4] = 0; - buf[5] = 0; - buf[6] = x+1; - buf[7] = 0; - buf[8] = 0; - buf[9] = 0; - int result = sendData(buf, BUF_LEN); - result = receiveData(buf,BUF_LEN); - // devices[x].ID=buf[9]; - devices[x].ID=buf[14]; - devices[x].ID=devices[x].ID<<8 | (quint8)buf[15]; - devices[x].BL_Version=buf[7]; - devices[x].SizeOfDesc=buf[8]; - - quint32 aux; - aux=(quint8)buf[10]; - aux=aux<<8 |(quint8)buf[11]; - aux=aux<<8 |(quint8)buf[12]; - aux=aux<<8 |(quint8)buf[13]; - - devices[x].FW_CRC=aux; - - - aux=(quint8)buf[2]; - aux=aux<<8 |(quint8)buf[3]; - aux=aux<<8 |(quint8)buf[4]; - aux=aux<<8 |(quint8)buf[5]; - devices[x].SizeOfCode=aux; - } - if(debug) - { - qDebug()<<"Found "<0) - return true; - return false; -} -OP_DFU::Status OP_DFU::UploadFirmware(const QString &sfile, const bool &verify,int device) -{ - OP_DFU::Status ret; - cout<<"Starting Firmware Uploading...\n"; - QFile file(sfile); - //QFile file("in.txt"); - if (!file.open(QIODevice::ReadOnly)) - { - if(debug) - qDebug()<<"Cant open file"; - return OP_DFU::abort; - } - QByteArray arr=file.readAll(); - - if(debug) - qDebug()<<"Bytes Loaded="<"); - }else{ - bar.replace(i,1," "); - } - } - - std::cout<< "\r"<> 2; // /4 Size passed in as a byte count, assumed to be a multiple of 4 - - while(Size--) - { - static const quint32 CrcTable[16] = { // Nibble lookup table for 0x04C11DB7 polynomial - 0x00000000,0x04C11DB7,0x09823B6E,0x0D4326D9,0x130476DC,0x17C56B6B,0x1A864DB2,0x1E475005, - 0x2608EDB8,0x22C9F00F,0x2F8AD6D6,0x2B4BCB61,0x350C9B64,0x31CD86D3,0x3C8EA00A,0x384FBDBD }; - - Crc = Crc ^ *((quint32 *)Buffer); // Apply all 32-bits - - Buffer += 1; - - // Process 32-bits, 4 at a time, or 8 rounds - - Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; // Assumes 32-bit reg, masking index to 4-bits - Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; // 0x04C11DB7 Polynomial used in STM32 - Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; - Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; - Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; - Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; - Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; - Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; - } - - return(Crc); -} -quint32 OP_DFU::CRCFromQBArray(QByteArray array, quint32 Size) -{ - int pad=Size-array.length(); - array.append(QByteArray(pad,255)); - quint32 t[Size/4]; - for(int x=0;xsendData((uint8_t*)data+1,size-1)) - { - if (debug) - qDebug()<<"packet sent"<<"data0"<<((uint8_t*)data+1)[0]; - return size; - } - if(debug) - qDebug()<<"Serial send OVERRUN"; - } -} -int OP_DFU::receiveData(void * data,int size) -{ - if(!use_serial) - { - return hidHandle.receive(0,data, size, 10000); - } - else - { - int x; - QTime time; - time.start(); - while(true) - { - if(x=serialhandle->read_Packet(((char *) data)+1)!=-1||time.elapsed()>10000) - { - if(time.elapsed()>10000) - qDebug()<<"____timeout"; - return x; - } - } - } -} +#include "op_dfu.h" +#include +#include +#include + +OP_DFU::OP_DFU(bool _debug,bool _use_serial,QString portname,bool umodereset): debug(_debug),use_serial(_use_serial),mready(true) +{ + if(use_serial) + { + cout<<"Connect hw now and press any key"; + // getch(); + // delay::msleep(2000); + PortSettings settings; + settings.BaudRate=BAUD57600; + settings.DataBits=DATA_8; + settings.FlowControl=FLOW_OFF; + settings.Parity=PAR_NONE; + settings.StopBits=STOP_1; + settings.Timeout_Millisec=1000; + info=new port(settings,portname); + info->rxBuf = sspRxBuf; + info->rxBufSize = MAX_PACKET_DATA_LEN; + info->txBuf = sspTxBuf; + info->txBufSize = MAX_PACKET_DATA_LEN; + info->max_retry = 10; + info->timeoutLen = 1000; + if(info->status()!=port::open) + { + cout<<"Could not open serial port\n"; + mready=false; + return; + } + if(umodereset) + sendReset(); + delay::msleep(5000); + serialhandle=new qsspt(info,debug); + + while(serialhandle->ssp_Synchronise()==false) + { + if (debug) + qDebug()<<"SYNC failed, resending"; + } + qDebug()<<"SYNC Succeded"; + serialhandle->start(); + // serialhandle->start(); + } + else + { + + send_delay=10; + use_delay=true; + int numDevices=0; + cout<<"Please connect device now\n"; + int count=0; + while(numDevices==0) + { + cout<<"."; + delay::msleep(500); + numDevices = hidHandle.open(1,0x20a0,0x415A,0,0); //0xff9c,0x0001); + if(numDevices==0) + numDevices = hidHandle.open(1,0x20a0,0x415B,0,0); //0xff9c,0x0001); + if(++count==10) + { + cout<<"\r"; + cout<<" "; + cout<<"\r"; + count=0; + } + } + if(debug) + qDebug() << numDevices << " device(s) opened"; + if(umodereset) + { + sendReset(); + + qDebug()<<"before delay"; + delay::msleep(5000); + qDebug()<<"after delay"; + if(hidHandle.open(1,0x20a0,0x4117,0,0)==0) + mready=false; + } + } +} +void OP_DFU::sendReset(void) +{ + qDebug()<<"Requesting user mode reset"; + char aa[255]= {0x02,0x3E,0x3C,0x20,0x75,0x00,0x20,0x4F,0x67,0x34,0x62,0x04,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00};//63 + char ba[255]= {0x02,0x3E,0x3C,0x20,0x75,0x00,0x20,0x4F,0x67,0x34,0xB9,0x08,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}; + char ca[255]= {0x02,0x3E,0x3C,0x20,0x75,0x00,0x20,0x4F,0x67,0x34,0x10,0x0D,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}; + char bb[255]={0x02,0x3D,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x28,0x8D,0x19,0x00,0x00,0x13}; + char ab[255]={0x02,0x3D,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x47,0x1B,0x19,0x00,0x00,0x76}; + char cb[255]={0x02,0x3D,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x66,0x78,0x1C,0x00,0x00,0x25}; + //125 + if(!use_serial) + { + hidHandle.send(0,aa, 64, 5000); + hidHandle.send(0,ab, 64, 5000); + delay::msleep(600); + hidHandle.send(0,ba, 64, 5000); + hidHandle.send(0,bb, 64, 5000); + delay::msleep(600); + hidHandle.send(0,ca, 64, 5000); + hidHandle.send(0,cb, 64, 5000); + delay::msleep(100); + hidHandle.close(1); +} + else + { + char a[255]; + char b[255]; + char c[255]; + memcpy (a,aa+2,62); + memcpy (a+62,ab+2,60); + memcpy (b,ba+2,62); + memcpy (b+62,bb+2,60); + memcpy (c,ca+2,62); + memcpy (c+62,cb+2,60); + for(int x=0;x<123;++x) + info->pfSerialWrite(a[x]); + delay::msleep(600); + for(int x=0;x<123;++x) + info->pfSerialWrite(b[x]); + delay::msleep(600); + for(int x=0;x<123;++x) + info->pfSerialWrite(c[x]); + } +} + +bool OP_DFU::SaveByteArrayToFile(QString const & sfile, const QByteArray &array) +{ + QFile file(sfile); + //QFile file("in.txt"); + if (!file.open(QIODevice::WriteOnly)) + { + if(debug) + qDebug()<<"Cant open file"; + return false; + } + file.write(array); + file.close(); + return true; +} + +bool OP_DFU::enterDFU(int const &devNumber) +{ + char buf[BUF_LEN]; + buf[0] =0x02;//reportID + buf[1] = OP_DFU::EnterDFU;//DFU Command + buf[2] = 0;//DFU Count + buf[3] = 0;//DFU Count + buf[4] = 0;//DFU Count + buf[5] = 0;//DFU Count + buf[6] = devNumber;//DFU Data0 + buf[7] = 1;//DFU Data1 + buf[8] = 1;//DFU Data2 + buf[9] = 1;//DFU Data3 + + int result = sendData(buf, BUF_LEN); + if(result<1) + return false; + if(debug) + qDebug() << result << " bytes sent"; + return true; +} +bool OP_DFU::StartUpload(qint32 const & numberOfBytes, TransferTypes const & type,quint32 crc) +{ + int lastPacketCount; + qint32 numberOfPackets=numberOfBytes/4/14; + int pad=(numberOfBytes-numberOfPackets*4*14)/4; + if(pad==0) + { + lastPacketCount=14; + } + else + { + ++numberOfPackets; + lastPacketCount=pad; + } + char buf[BUF_LEN]; + buf[0] =0x02;//reportID + buf[1] = setStartBit(OP_DFU::Upload);//DFU Command + buf[2] = numberOfPackets>>24;//DFU Count + buf[3] = numberOfPackets>>16;//DFU Count + buf[4] = numberOfPackets>>8;//DFU Count + buf[5] = numberOfPackets;//DFU Count + buf[6] = (int)type;//DFU Data0 + buf[7] = lastPacketCount;//DFU Data1 + buf[8] = crc>>24; + buf[9] = crc>>16; + buf[10] = crc>>8; + buf[11] = crc; + if(debug) + qDebug()<<"Number of packets:"<0) + { + return true; + } + return false; +} +bool OP_DFU::UploadData(qint32 const & numberOfBytes, QByteArray & data) +{ + int lastPacketCount; + qint32 numberOfPackets=numberOfBytes/4/14; + int pad=(numberOfBytes-numberOfPackets*4*14)/4; + if(pad==0) + { + lastPacketCount=14; + } + else + { + ++numberOfPackets; + lastPacketCount=pad; + } + if(debug) + qDebug()<<"Start Uploading:"<>24;//DFU Count + buf[3] = packetcount>>16;//DFU Count + buf[4] = packetcount>>8;//DFU Count + buf[5] = packetcount;//DFU Count + char *pointer=data.data(); + pointer=pointer+4*14*packetcount; + // qDebug()<<"Packet Number="<>24;//DFU Count + buf[3] = numberOfPackets>>16;//DFU Count + buf[4] = numberOfPackets>>8;//DFU Count + buf[5] = numberOfPackets;//DFU Count + buf[6] = (int)type;//DFU Data0 + buf[7] = lastPacketCount;//DFU Data1 + buf[8] = 1;//DFU Data2 + buf[9] = 1;//DFU Data3 + + int result = sendData(buf, BUF_LEN); + if(debug) + qDebug() << "StartDownload:"<>(x*2) & 1); + dev.Writable=(bool)(RWFlags>>(x*2+1) & 1); + devices.append(dev); + buf[0] =0x02;//reportID + buf[1] = OP_DFU::Req_Capabilities;//DFU Command + buf[2] = 0; + buf[3] = 0; + buf[4] = 0; + buf[5] = 0; + buf[6] = x+1; + buf[7] = 0; + buf[8] = 0; + buf[9] = 0; + int result = sendData(buf, BUF_LEN); + result = receiveData(buf,BUF_LEN); + // devices[x].ID=buf[9]; + devices[x].ID=buf[14]; + devices[x].ID=devices[x].ID<<8 | (quint8)buf[15]; + devices[x].BL_Version=buf[7]; + devices[x].SizeOfDesc=buf[8]; + + quint32 aux; + aux=(quint8)buf[10]; + aux=aux<<8 |(quint8)buf[11]; + aux=aux<<8 |(quint8)buf[12]; + aux=aux<<8 |(quint8)buf[13]; + + devices[x].FW_CRC=aux; + + + aux=(quint8)buf[2]; + aux=aux<<8 |(quint8)buf[3]; + aux=aux<<8 |(quint8)buf[4]; + aux=aux<<8 |(quint8)buf[5]; + devices[x].SizeOfCode=aux; + } + if(debug) + { + qDebug()<<"Found "<0) + return true; + return false; +} +OP_DFU::Status OP_DFU::UploadFirmware(const QString &sfile, const bool &verify,int device) +{ + OP_DFU::Status ret; + cout<<"Starting Firmware Uploading...\n"; + QFile file(sfile); + //QFile file("in.txt"); + if (!file.open(QIODevice::ReadOnly)) + { + if(debug) + qDebug()<<"Cant open file"; + return OP_DFU::abort; + } + QByteArray arr=file.readAll(); + + if(debug) + qDebug()<<"Bytes Loaded="<"); + }else{ + bar.replace(i,1," "); + } + } + + std::cout<< "\r"<> 2; // /4 Size passed in as a byte count, assumed to be a multiple of 4 + + while(Size--) + { + static const quint32 CrcTable[16] = { // Nibble lookup table for 0x04C11DB7 polynomial + 0x00000000,0x04C11DB7,0x09823B6E,0x0D4326D9,0x130476DC,0x17C56B6B,0x1A864DB2,0x1E475005, + 0x2608EDB8,0x22C9F00F,0x2F8AD6D6,0x2B4BCB61,0x350C9B64,0x31CD86D3,0x3C8EA00A,0x384FBDBD }; + + Crc = Crc ^ *((quint32 *)Buffer); // Apply all 32-bits + + Buffer += 1; + + // Process 32-bits, 4 at a time, or 8 rounds + + Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; // Assumes 32-bit reg, masking index to 4-bits + Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; // 0x04C11DB7 Polynomial used in STM32 + Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; + Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; + Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; + Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; + Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; + Crc = (Crc << 4) ^ CrcTable[Crc >> 28]; + } + + return(Crc); +} +quint32 OP_DFU::CRCFromQBArray(QByteArray array, quint32 Size) +{ + int pad=Size-array.length(); + array.append(QByteArray(pad,255)); + quint32 t[Size/4]; + for(int x=0;xsendData((uint8_t*)data+1,size-1)) + { + if (debug) + qDebug()<<"packet sent"<<"data0"<<((uint8_t*)data+1)[0]; + return size; + } + if(debug) + qDebug()<<"Serial send OVERRUN"; + } +} +int OP_DFU::receiveData(void * data,int size) +{ + if(!use_serial) + { + return hidHandle.receive(0,data, size, 10000); + } + else + { + int x; + QTime time; + time.start(); + while(true) + { + if(x=serialhandle->read_Packet(((char *) data)+1)!=-1||time.elapsed()>10000) + { + if(time.elapsed()>10000) + qDebug()<<"____timeout"; + return x; + } + } + } +} diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/op_dfu.h b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/op_dfu.h index 5700edbbd..f5b82f7e7 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/op_dfu.h +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/op_dfu.h @@ -1,158 +1,158 @@ -#ifndef OP_DFU_H -#define OP_DFU_H - -#include -#include <../../plugins/rawhid/pjrc_rawhid.h> -#include -#include -#include -#include -#include -#include "delay.h" -#include "../../libs/qextserialport/src/qextserialport.h" -#include -#include "SSP/qssp.h" -#include "SSP/port.h" -#include "SSP/qsspt.h" -using namespace std; -#define BUF_LEN 64 - -//Command Line Options -#define DOWNLOAD "-dn" //done -#define DEVICE "-d" //done -//#define DOWNDESCRIPTION "-dd" //done -#define PROGRAMFW "-p" //done -#define PROGRAMDESC "-w" //done -#define VERIFY "-v" //done -#define COMPARECRC "-cc" -#define COMPAREALL "-ca" -#define STATUSREQUEST "-s" //done -#define LISTDEVICES "-ls" //done -#define RESET "-r" -#define JUMP "-j" -#define USE_SERIAL "-t" - -#define MAX_PACKET_DATA_LEN 255 -#define MAX_PACKET_BUF_SIZE (1+1+MAX_PACKET_DATA_LEN+2) - - -class OP_DFU -{ -public: - enum TransferTypes - { - FW, - Descript - }; - enum CompareType - { - crccompare, - bytetobytecompare - }; - - enum Status - { - DFUidle,//0 - uploading,//1 - wrong_packet_received,//2 - too_many_packets,//3 - too_few_packets,//4 - Last_operation_Success,//5 - downloading,//6 - idle,//7 - Last_operation_failed,//8 - uploadingStarting,//9 - outsideDevCapabilities,//10 - CRC_Fail,//11 - failed_jump,//12 - abort//13 - - }; - enum Actions - { - actionProgram, - actionProgramAndVerify, - actionDownload, - actionCompareAll, - actionCompareCrc, - actionListDevs, - actionStatusReq, - actionReset, - actionJump - }; - - enum Commands - { - Reserved,//0 - Req_Capabilities,//1 - Rep_Capabilities,//2 - EnterDFU,//3 - JumpFW,//4 - Reset,//5 - Abort_Operation,//6 - Upload,//7 - Op_END,//8 - Download_Req,//9 - Download,//10 - Status_Request,//11 - Status_Rep,//12 - - }; - struct device - { - int ID; - quint32 FW_CRC; - int BL_Version; - int SizeOfDesc; - quint32 SizeOfCode; - bool Readable; - bool Writable; - }; - void JumpToApp(); - void ResetDevice(void); - bool enterDFU(int const &devNumber); - bool StartUpload(qint32 const &numberOfBytes, TransferTypes const & type,quint32 crc); - bool UploadData(qint32 const & numberOfPackets,QByteArray & data); - Status UploadDescription(QString & description); - Status UploadFirmware(const QString &sfile, const bool &verify,int device); - Status StatusRequest(); - bool EndOperation(); - void printProgBar( int const & percent,QString const& label); - QString DownloadDescription(int const & numberOfChars); - QByteArray StartDownload(qint32 const & numberOfBytes, TransferTypes const & type); - bool SaveByteArrayToFile(QString const & file,QByteArray const &array); - void CopyWords(char * source, char* destination, int count); - // QByteArray DownloadData(int devNumber,int numberOfPackets); - OP_DFU(bool debug,bool use_serial,QString port,bool umodereset); - void sendReset(void); - bool findDevices(); - QList devices; - int numberOfDevices; - QString StatusToString(OP_DFU::Status const & status); - OP_DFU::Status CompareFirmware(const QString &sfile, const CompareType &type,int device); - quint32 CRC32WideFast(quint32 Crc, quint32 Size, quint32 *Buffer); - quint32 CRCFromQBArray(QByteArray array, quint32 Size); - void test(); - int send_delay; - bool use_delay; - bool ready(){return mready;} - void AbortOperation(void); -private: - bool mready; - bool debug; - int RWFlags; - bool use_serial; - qsspt * serialhandle; - int sendData(void*,int); - int receiveData(void * data,int size); - pjrc_rawhid hidHandle; - int setStartBit(int command){return command|0x20;} - uint8_t sspTxBuf[MAX_PACKET_BUF_SIZE]; - uint8_t sspRxBuf[MAX_PACKET_BUF_SIZE]; - - port * info; -}; - - - -#endif // OP_DFU_H +#ifndef OP_DFU_H +#define OP_DFU_H + +#include +#include <../../plugins/rawhid/pjrc_rawhid.h> +#include +#include +#include +#include +#include +#include "delay.h" +#include "../../libs/qextserialport/src/qextserialport.h" +#include +#include "SSP/qssp.h" +#include "SSP/port.h" +#include "SSP/qsspt.h" +using namespace std; +#define BUF_LEN 64 + +//Command Line Options +#define DOWNLOAD "-dn" //done +#define DEVICE "-d" //done +//#define DOWNDESCRIPTION "-dd" //done +#define PROGRAMFW "-p" //done +#define PROGRAMDESC "-w" //done +#define VERIFY "-v" //done +#define COMPARECRC "-cc" +#define COMPAREALL "-ca" +#define STATUSREQUEST "-s" //done +#define LISTDEVICES "-ls" //done +#define RESET "-r" +#define JUMP "-j" +#define USE_SERIAL "-t" + +#define MAX_PACKET_DATA_LEN 255 +#define MAX_PACKET_BUF_SIZE (1+1+MAX_PACKET_DATA_LEN+2) + + +class OP_DFU +{ +public: + enum TransferTypes + { + FW, + Descript + }; + enum CompareType + { + crccompare, + bytetobytecompare + }; + + enum Status + { + DFUidle,//0 + uploading,//1 + wrong_packet_received,//2 + too_many_packets,//3 + too_few_packets,//4 + Last_operation_Success,//5 + downloading,//6 + idle,//7 + Last_operation_failed,//8 + uploadingStarting,//9 + outsideDevCapabilities,//10 + CRC_Fail,//11 + failed_jump,//12 + abort//13 + + }; + enum Actions + { + actionProgram, + actionProgramAndVerify, + actionDownload, + actionCompareAll, + actionCompareCrc, + actionListDevs, + actionStatusReq, + actionReset, + actionJump + }; + + enum Commands + { + Reserved,//0 + Req_Capabilities,//1 + Rep_Capabilities,//2 + EnterDFU,//3 + JumpFW,//4 + Reset,//5 + Abort_Operation,//6 + Upload,//7 + Op_END,//8 + Download_Req,//9 + Download,//10 + Status_Request,//11 + Status_Rep,//12 + + }; + struct device + { + int ID; + quint32 FW_CRC; + int BL_Version; + int SizeOfDesc; + quint32 SizeOfCode; + bool Readable; + bool Writable; + }; + void JumpToApp(); + void ResetDevice(void); + bool enterDFU(int const &devNumber); + bool StartUpload(qint32 const &numberOfBytes, TransferTypes const & type,quint32 crc); + bool UploadData(qint32 const & numberOfPackets,QByteArray & data); + Status UploadDescription(QString & description); + Status UploadFirmware(const QString &sfile, const bool &verify,int device); + Status StatusRequest(); + bool EndOperation(); + void printProgBar( int const & percent,QString const& label); + QString DownloadDescription(int const & numberOfChars); + QByteArray StartDownload(qint32 const & numberOfBytes, TransferTypes const & type); + bool SaveByteArrayToFile(QString const & file,QByteArray const &array); + void CopyWords(char * source, char* destination, int count); + // QByteArray DownloadData(int devNumber,int numberOfPackets); + OP_DFU(bool debug,bool use_serial,QString port,bool umodereset); + void sendReset(void); + bool findDevices(); + QList devices; + int numberOfDevices; + QString StatusToString(OP_DFU::Status const & status); + OP_DFU::Status CompareFirmware(const QString &sfile, const CompareType &type,int device); + quint32 CRC32WideFast(quint32 Crc, quint32 Size, quint32 *Buffer); + quint32 CRCFromQBArray(QByteArray array, quint32 Size); + void test(); + int send_delay; + bool use_delay; + bool ready(){return mready;} + void AbortOperation(void); +private: + bool mready; + bool debug; + int RWFlags; + bool use_serial; + qsspt * serialhandle; + int sendData(void*,int); + int receiveData(void * data,int size); + pjrc_rawhid hidHandle; + int setStartBit(int command){return command|0x20;} + uint8_t sspTxBuf[MAX_PACKET_BUF_SIZE]; + uint8_t sspRxBuf[MAX_PACKET_BUF_SIZE]; + + port * info; +}; + + + +#endif // OP_DFU_H diff --git a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/upload.pro b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/upload.pro index 05c08b685..50aae95c8 100644 --- a/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/upload.pro +++ b/ground/openpilotgcs/src/experimental/USB_UPLOAD_TOOL/upload.pro @@ -1,78 +1,78 @@ -#------------------------------------------------- -# -# Project created by QtCreator 2010-07-24T11:26:38 -# -#------------------------------------------------- - -QT += core - -QT -= gui -DEFINES += QEXTSERIALPORT_LIBRARY -TARGET = OPUploadTool -CONFIG += console -CONFIG -= app_bundle - -TEMPLATE = app -DEFINES += RAWHID_LIBRARY -SOURCES += main.cpp \ - op_dfu.cpp \ - delay.cpp \ - ./SSP/qssp.cpp \ - ./SSP/port.cpp \ - ./SSP/qsspt.cpp \ -../../libs/qextserialport/src/qextserialport.cpp -HEADERS += ../../plugins/rawhid/pjrc_rawhid.h \ - ../../plugins/rawhid/rawhid_global.h \ - op_dfu.h \ - delay.h \ - ../../libs/qextserialport/src/qextserialport.h \ - ../../libs/qextserialport/src/qextserialenumerator.h \ - ../../libs/qextserialport/src/qextserialport_global.h \ - ./SSP/qssp.h \ - ./SSP/port.h \ - ./SSP/common.h \ - ./SSP/qsspt.h - -win32 { - SOURCES += ../../plugins/rawhid/pjrc_rawhid_win.cpp - - LIBS += -lhid \ - -lsetupapi -} - -macx { - SOURCES += ../../plugins/rawhid/pjrc_rawhid_mac.cpp - SDK = /Developer/SDKs/MacOSX10.5.sdk - ARCH = -mmacosx-version-min=10.5 \ - -arch \ - ppc \ - -arch \ - i386 - LIBS += $(ARCH) \ - -Wl,-syslibroot,$(SDK) \ - -framework \ - IOKit \ - -framework \ - CoreFoundation -} -linux-g++ { - SOURCES += ../../plugins/rawhid/pjrc_rawhid_unix.cpp - LIBS += -lusb -} -linux-g++-64 { - SOURCES += ../../plugins/rawhid/pjrc_rawhid_unix.cpp - LIBS += -lusb -} -unix:SOURCES += ../../libs/qextserialport/src/posix_qextserialport.cpp -unix:!macx:SOURCES += ../../libs/qextserialport/src/qextserialenumerator_unix.cpp -macx { - SOURCES += ../../libs/qextserialport/src/qextserialenumerator_osx.cpp - LIBS += -framework IOKit -framework CoreFoundation -} - -win32 { - SOURCES += ../../libs/qextserialport/src/win_qextserialport.cpp \ -../../libs/qextserialport/src/qextserialenumerator_win.cpp - DEFINES += WINVER=0x0501 # needed for mingw to pull in appropriate dbt business...probably a better way to do this - LIBS += -lsetupapi -} +#------------------------------------------------- +# +# Project created by QtCreator 2010-07-24T11:26:38 +# +#------------------------------------------------- + +QT += core + +QT -= gui +DEFINES += QEXTSERIALPORT_LIBRARY +TARGET = OPUploadTool +CONFIG += console +CONFIG -= app_bundle + +TEMPLATE = app +DEFINES += RAWHID_LIBRARY +SOURCES += main.cpp \ + op_dfu.cpp \ + delay.cpp \ + ./SSP/qssp.cpp \ + ./SSP/port.cpp \ + ./SSP/qsspt.cpp \ +../../libs/qextserialport/src/qextserialport.cpp +HEADERS += ../../plugins/rawhid/pjrc_rawhid.h \ + ../../plugins/rawhid/rawhid_global.h \ + op_dfu.h \ + delay.h \ + ../../libs/qextserialport/src/qextserialport.h \ + ../../libs/qextserialport/src/qextserialenumerator.h \ + ../../libs/qextserialport/src/qextserialport_global.h \ + ./SSP/qssp.h \ + ./SSP/port.h \ + ./SSP/common.h \ + ./SSP/qsspt.h + +win32 { + SOURCES += ../../plugins/rawhid/pjrc_rawhid_win.cpp + + LIBS += -lhid \ + -lsetupapi +} + +macx { + SOURCES += ../../plugins/rawhid/pjrc_rawhid_mac.cpp + SDK = /Developer/SDKs/MacOSX10.5.sdk + ARCH = -mmacosx-version-min=10.5 \ + -arch \ + ppc \ + -arch \ + i386 + LIBS += $(ARCH) \ + -Wl,-syslibroot,$(SDK) \ + -framework \ + IOKit \ + -framework \ + CoreFoundation +} +linux-g++ { + SOURCES += ../../plugins/rawhid/pjrc_rawhid_unix.cpp + LIBS += -lusb +} +linux-g++-64 { + SOURCES += ../../plugins/rawhid/pjrc_rawhid_unix.cpp + LIBS += -lusb +} +unix:SOURCES += ../../libs/qextserialport/src/posix_qextserialport.cpp +unix:!macx:SOURCES += ../../libs/qextserialport/src/qextserialenumerator_unix.cpp +macx { + SOURCES += ../../libs/qextserialport/src/qextserialenumerator_osx.cpp + LIBS += -framework IOKit -framework CoreFoundation +} + +win32 { + SOURCES += ../../libs/qextserialport/src/win_qextserialport.cpp \ +../../libs/qextserialport/src/qextserialenumerator_win.cpp + DEFINES += WINVER=0x0501 # needed for mingw to pull in appropriate dbt business...probably a better way to do this + LIBS += -lsetupapi +} diff --git a/ground/openpilotgcs/src/experimental/finaltest/finaltest.pro b/ground/openpilotgcs/src/experimental/finaltest/finaltest.pro index 803f4a919..62097fc45 100644 --- a/ground/openpilotgcs/src/experimental/finaltest/finaltest.pro +++ b/ground/openpilotgcs/src/experimental/finaltest/finaltest.pro @@ -1,20 +1,20 @@ -#------------------------------------------------- -# -# Project created by QtCreator 2010-06-11T10:37:33 -# -#------------------------------------------------- - -TARGET = finaltest -TEMPLATE = app -DESTDIR = ../build -QT += network -QT += sql -QT += opengl -LIBS += -L../build \ - -lopmapwidgetd -SOURCES += main.cpp\ - mainwindow.cpp - -HEADERS += mainwindow.h - -FORMS += mainwindow.ui +#------------------------------------------------- +# +# Project created by QtCreator 2010-06-11T10:37:33 +# +#------------------------------------------------- + +TARGET = finaltest +TEMPLATE = app +DESTDIR = ../build +QT += network +QT += sql +QT += opengl +LIBS += -L../build \ + -lopmapwidgetd +SOURCES += main.cpp\ + mainwindow.cpp + +HEADERS += mainwindow.h + +FORMS += mainwindow.ui diff --git a/ground/openpilotgcs/src/experimental/finaltest/main.cpp b/ground/openpilotgcs/src/experimental/finaltest/main.cpp index 49a2cb9b8..6e7efd975 100644 --- a/ground/openpilotgcs/src/experimental/finaltest/main.cpp +++ b/ground/openpilotgcs/src/experimental/finaltest/main.cpp @@ -1,10 +1,10 @@ -#include -#include "mainwindow.h" - -int main(int argc, char *argv[]) -{ - QApplication a(argc, argv); - MainWindow w; - w.show(); - return a.exec(); -} +#include +#include "mainwindow.h" + +int main(int argc, char *argv[]) +{ + QApplication a(argc, argv); + MainWindow w; + w.show(); + return a.exec(); +} diff --git a/ground/openpilotgcs/src/experimental/finaltest/mainwindow.cpp b/ground/openpilotgcs/src/experimental/finaltest/mainwindow.cpp index d6e4e3c8a..6cd849d10 100644 --- a/ground/openpilotgcs/src/experimental/finaltest/mainwindow.cpp +++ b/ground/openpilotgcs/src/experimental/finaltest/mainwindow.cpp @@ -1,148 +1,148 @@ -#include "mainwindow.h" -#include "ui_mainwindow.h" -//#include "../mapwidget/mapgraphicitem.h" - -MainWindow::MainWindow(QWidget *parent) : - QMainWindow(parent), - ui(new Ui::MainWindow) -{ - map=new mapcontrol::OPMapWidget(); - map->SetShowUAV(true); - map->SetShowHome(true); - ui->setupUi(this); - ui->comboBox->addItems(mapcontrol::Helper::MapTypes()); - ui->comboBox->setCurrentIndex(mapcontrol::Helper::MapTypes().indexOf("GoogleHybrid")); - QHBoxLayout *layout=new QHBoxLayout(parent); - layout->addWidget(map); - layout->addWidget(ui->widget); - ui->centralWidget->setLayout(layout); - QTimer * timer=new QTimer; - timer->setInterval(500); - timer->start(); - connect(map,SIGNAL(zoomChanged(double,double,double)),this,SLOT(zoomChanged(double,double,double))); - connect(map,SIGNAL(OnTilesStillToLoad(int)),this,SLOT(ttl(int))); - connect(timer,SIGNAL(timeout()),this,SLOT(time())); - map->WPCreate(internals::PointLatLng(38.42,-9.5),0,"lisbon"); - map->SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionAndCenter); -} - -MainWindow::~MainWindow() -{ - delete ui; - delete map; -} - -void MainWindow::ttl(int value) -{ - ui->label_2->setText(QString::number(value)); -} - -void MainWindow::time() -{ - internals::PointLatLng ll; - ll.SetLat(map->currentMousePosition().Lat()); - ll.SetLng(map->currentMousePosition().Lng()); - // map->UAV->SetUAVPos(ll,10); - ui->label_2->setText(map->currentMousePosition().ToString()); - QGraphicsItem* itemm=map->itemAt(map->mapFromGlobal(QCursor::pos())); - mapcontrol::WayPointItem* w=qgraphicsitem_cast(itemm); - //if(w) - // qDebug()<Type; - if (itemm->Type==mapcontrol::WayPointItem::Type) - { - int x=itemm->Type; - int xx= x; - QLabel* l=new QLabel(this); - l->show(); - } -} - -void MainWindow::changeEvent(QEvent *e) -{ - QMainWindow::changeEvent(e); - switch (e->type()) { - case QEvent::LanguageChange: - ui->retranslateUi(this); - break; - default: - break; - } -} - -void MainWindow::on_pushButtonZoomP_clicked() -{ - double x=map->ZoomTotal(); - double y=ui->doubleSpinBox->value(); - double z=x+y; - map->SetZoom(map->ZoomTotal()+ui->doubleSpinBox->value()); -} - -void MainWindow::on_pushButtonZoomM_clicked() -{ - map->SetZoom(map->ZoomTotal()-ui->doubleSpinBox->value()); -} - -void MainWindow::on_checkBox_clicked(bool checked) -{ - map->SetShowTileGridLines(checked); -} -void MainWindow::zoomChanged(double zoomt,double zoom,double zoomdigi) -{ - ui->label_5->setText("CurrentZoom="+QString::number(zoomt)+QString::number(zoom)+QString::number(zoomdigi)); -} - -void MainWindow::on_pushButtonRL_clicked() -{ - map->UAV->DeleteTrail(); - // map->UAV->SetUAVHeading(10); - //map->SetRotate(map->Rotate()-1); - //map->WPCreate(); - // map->WPCreate(internals::PointLatLng(20,20),100); -} - -void MainWindow::on_pushButtonRC_clicked() -{ - map->SetRotate(0); -// wp=map->WPInsert(1); -} - -void MainWindow::on_pushButtonRR_clicked() -{ - map->SetRotate(map->Rotate()+1); - // map->WPDeleteAll(); - // map->WPDelete(wp); -// QList list= map->WPSelected(); -// int x=list.at(0)->Number(); -} - -void MainWindow::on_pushButton_clicked() -{ - map->ReloadMap(); -} - -void MainWindow::on_pushButtonGO_clicked() -{ - core::GeoCoderStatusCode::Types x=map->SetCurrentPositionByKeywords(ui->lineEdit->text()); - ui->label->setText( mapcontrol::Helper::StrFromGeoCoderStatusCode(x)); - -} - -void MainWindow::on_checkBox_2_clicked(bool checked) -{ - map->SetUseOpenGL(checked); -} - -void MainWindow::on_comboBox_currentIndexChanged(QString value) -{ - if (map->isStarted()) - map->SetMapType(mapcontrol::Helper::MapTypeFromString(value)); -} - -void MainWindow::on_pushButton_2_clicked() -{ - map->RipMap(); -// QLabel *x=new QLabel(); -// ima=map->X(); -// x->setPixmap(QPixmap::fromImage(ima)); -// x->show(); -} +#include "mainwindow.h" +#include "ui_mainwindow.h" +//#include "../mapwidget/mapgraphicitem.h" + +MainWindow::MainWindow(QWidget *parent) : + QMainWindow(parent), + ui(new Ui::MainWindow) +{ + map=new mapcontrol::OPMapWidget(); + map->SetShowUAV(true); + map->SetShowHome(true); + ui->setupUi(this); + ui->comboBox->addItems(mapcontrol::Helper::MapTypes()); + ui->comboBox->setCurrentIndex(mapcontrol::Helper::MapTypes().indexOf("GoogleHybrid")); + QHBoxLayout *layout=new QHBoxLayout(parent); + layout->addWidget(map); + layout->addWidget(ui->widget); + ui->centralWidget->setLayout(layout); + QTimer * timer=new QTimer; + timer->setInterval(500); + timer->start(); + connect(map,SIGNAL(zoomChanged(double,double,double)),this,SLOT(zoomChanged(double,double,double))); + connect(map,SIGNAL(OnTilesStillToLoad(int)),this,SLOT(ttl(int))); + connect(timer,SIGNAL(timeout()),this,SLOT(time())); + map->WPCreate(internals::PointLatLng(38.42,-9.5),0,"lisbon"); + map->SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionAndCenter); +} + +MainWindow::~MainWindow() +{ + delete ui; + delete map; +} + +void MainWindow::ttl(int value) +{ + ui->label_2->setText(QString::number(value)); +} + +void MainWindow::time() +{ + internals::PointLatLng ll; + ll.SetLat(map->currentMousePosition().Lat()); + ll.SetLng(map->currentMousePosition().Lng()); + // map->UAV->SetUAVPos(ll,10); + ui->label_2->setText(map->currentMousePosition().ToString()); + QGraphicsItem* itemm=map->itemAt(map->mapFromGlobal(QCursor::pos())); + mapcontrol::WayPointItem* w=qgraphicsitem_cast(itemm); + //if(w) + // qDebug()<Type; + if (itemm->Type==mapcontrol::WayPointItem::Type) + { + int x=itemm->Type; + int xx= x; + QLabel* l=new QLabel(this); + l->show(); + } +} + +void MainWindow::changeEvent(QEvent *e) +{ + QMainWindow::changeEvent(e); + switch (e->type()) { + case QEvent::LanguageChange: + ui->retranslateUi(this); + break; + default: + break; + } +} + +void MainWindow::on_pushButtonZoomP_clicked() +{ + double x=map->ZoomTotal(); + double y=ui->doubleSpinBox->value(); + double z=x+y; + map->SetZoom(map->ZoomTotal()+ui->doubleSpinBox->value()); +} + +void MainWindow::on_pushButtonZoomM_clicked() +{ + map->SetZoom(map->ZoomTotal()-ui->doubleSpinBox->value()); +} + +void MainWindow::on_checkBox_clicked(bool checked) +{ + map->SetShowTileGridLines(checked); +} +void MainWindow::zoomChanged(double zoomt,double zoom,double zoomdigi) +{ + ui->label_5->setText("CurrentZoom="+QString::number(zoomt)+QString::number(zoom)+QString::number(zoomdigi)); +} + +void MainWindow::on_pushButtonRL_clicked() +{ + map->UAV->DeleteTrail(); + // map->UAV->SetUAVHeading(10); + //map->SetRotate(map->Rotate()-1); + //map->WPCreate(); + // map->WPCreate(internals::PointLatLng(20,20),100); +} + +void MainWindow::on_pushButtonRC_clicked() +{ + map->SetRotate(0); +// wp=map->WPInsert(1); +} + +void MainWindow::on_pushButtonRR_clicked() +{ + map->SetRotate(map->Rotate()+1); + // map->WPDeleteAll(); + // map->WPDelete(wp); +// QList list= map->WPSelected(); +// int x=list.at(0)->Number(); +} + +void MainWindow::on_pushButton_clicked() +{ + map->ReloadMap(); +} + +void MainWindow::on_pushButtonGO_clicked() +{ + core::GeoCoderStatusCode::Types x=map->SetCurrentPositionByKeywords(ui->lineEdit->text()); + ui->label->setText( mapcontrol::Helper::StrFromGeoCoderStatusCode(x)); + +} + +void MainWindow::on_checkBox_2_clicked(bool checked) +{ + map->SetUseOpenGL(checked); +} + +void MainWindow::on_comboBox_currentIndexChanged(QString value) +{ + if (map->isStarted()) + map->SetMapType(mapcontrol::Helper::MapTypeFromString(value)); +} + +void MainWindow::on_pushButton_2_clicked() +{ + map->RipMap(); +// QLabel *x=new QLabel(); +// ima=map->X(); +// x->setPixmap(QPixmap::fromImage(ima)); +// x->show(); +} diff --git a/ground/openpilotgcs/src/experimental/finaltest/mainwindow.h b/ground/openpilotgcs/src/experimental/finaltest/mainwindow.h index 4935b1cae..9dd7e509a 100644 --- a/ground/openpilotgcs/src/experimental/finaltest/mainwindow.h +++ b/ground/openpilotgcs/src/experimental/finaltest/mainwindow.h @@ -1,44 +1,44 @@ -#ifndef MAINWINDOW_H -#define MAINWINDOW_H -#include "../mapwidget/opmapwidget.h" -#include "../mapwidget/waypointitem.h" -#include - -namespace Ui { - class MainWindow; -} - -class MainWindow : public QMainWindow { - Q_OBJECT -public: - MainWindow(QWidget *parent = 0); - ~MainWindow(); - -protected: - void changeEvent(QEvent *e); - -private: - Ui::MainWindow *ui; - mapcontrol::OPMapWidget *map; - mapcontrol::WayPointItem* wp; - QImage ima; - QLabel l; - -private slots: - void on_pushButton_2_clicked(); - void on_comboBox_currentIndexChanged(QString ); - void on_checkBox_2_clicked(bool checked); - void on_pushButtonGO_clicked(); - void on_pushButton_clicked(); - void on_pushButtonRR_clicked(); - void on_pushButtonRC_clicked(); - void on_pushButtonRL_clicked(); - void on_checkBox_clicked(bool checked); - void on_pushButtonZoomM_clicked(); - void on_pushButtonZoomP_clicked(); - void zoomChanged(double zoomt,double zoom,double zoomdigi); - void ttl(int value); - void time(); -}; - -#endif // MAINWINDOW_H +#ifndef MAINWINDOW_H +#define MAINWINDOW_H +#include "../mapwidget/opmapwidget.h" +#include "../mapwidget/waypointitem.h" +#include + +namespace Ui { + class MainWindow; +} + +class MainWindow : public QMainWindow { + Q_OBJECT +public: + MainWindow(QWidget *parent = 0); + ~MainWindow(); + +protected: + void changeEvent(QEvent *e); + +private: + Ui::MainWindow *ui; + mapcontrol::OPMapWidget *map; + mapcontrol::WayPointItem* wp; + QImage ima; + QLabel l; + +private slots: + void on_pushButton_2_clicked(); + void on_comboBox_currentIndexChanged(QString ); + void on_checkBox_2_clicked(bool checked); + void on_pushButtonGO_clicked(); + void on_pushButton_clicked(); + void on_pushButtonRR_clicked(); + void on_pushButtonRC_clicked(); + void on_pushButtonRL_clicked(); + void on_checkBox_clicked(bool checked); + void on_pushButtonZoomM_clicked(); + void on_pushButtonZoomP_clicked(); + void zoomChanged(double zoomt,double zoom,double zoomdigi); + void ttl(int value); + void time(); +}; + +#endif // MAINWINDOW_H diff --git a/ground/openpilotgcs/src/experimental/finaltest/mainwindow.ui b/ground/openpilotgcs/src/experimental/finaltest/mainwindow.ui index 4372dc480..c30c15971 100644 --- a/ground/openpilotgcs/src/experimental/finaltest/mainwindow.ui +++ b/ground/openpilotgcs/src/experimental/finaltest/mainwindow.ui @@ -1,255 +1,255 @@ - - - MainWindow - - - - 0 - 0 - 524 - 551 - - - - MainWindow - - - - - - 110 - 15 - 181 - 421 - - - - - 10 - 0 - - - - - 181 - 16777215 - - - - - 0 - - - 0 - - - - - - - MapType - - - - - - TextLabel - - - - - - - - - - PushButton - - - - - - - - - - Goto Place - - - - - - - - - - - GO - - - - - - - - - GeoCoderStatusCode - - - - - - - - - - Rotate - - - - - - Left - - - - - - - Center - - - - - - - Right - - - - - - - - - - Zoom - - - - - - - - + - - - - - - - - - - - - - - - - - - - ZoomIncrement - - - Qt::AlignCenter - - - - - - - - - 0.100000000000000 - - - 1.000000000000000 - - - - - - - CurrentZoom= - - - Qt::AlignCenter - - - - - - - Misc - - - - - - ShowGridLines - - - true - - - - - - - UseOpenGL - - - - - - - ReloadMap - - - - - - - - - - - - - - - - - - 0 - 0 - 524 - 21 - - - - - - TopToolBarArea - - - false - - - - - - - - + + + MainWindow + + + + 0 + 0 + 524 + 551 + + + + MainWindow + + + + + + 110 + 15 + 181 + 421 + + + + + 10 + 0 + + + + + 181 + 16777215 + + + + + 0 + + + 0 + + + + + + + MapType + + + + + + TextLabel + + + + + + + + + + PushButton + + + + + + + + + + Goto Place + + + + + + + + + + + GO + + + + + + + + + GeoCoderStatusCode + + + + + + + + + + Rotate + + + + + + Left + + + + + + + Center + + + + + + + Right + + + + + + + + + + Zoom + + + + + + + + + + + + + + + + - + + + + + + + + + + + ZoomIncrement + + + Qt::AlignCenter + + + + + + + + + 0.100000000000000 + + + 1.000000000000000 + + + + + + + CurrentZoom= + + + Qt::AlignCenter + + + + + + + Misc + + + + + + ShowGridLines + + + true + + + + + + + UseOpenGL + + + + + + + ReloadMap + + + + + + + + + + + + + + + + + + 0 + 0 + 524 + 21 + + + + + + TopToolBarArea + + + false + + + + + + + + diff --git a/ground/openpilotgcs/src/experimental/finaltest/ui_mainwindow.h b/ground/openpilotgcs/src/experimental/finaltest/ui_mainwindow.h index 4ec26b473..4a65bd5c0 100644 --- a/ground/openpilotgcs/src/experimental/finaltest/ui_mainwindow.h +++ b/ground/openpilotgcs/src/experimental/finaltest/ui_mainwindow.h @@ -1,304 +1,304 @@ -/******************************************************************************** -** Form generated from reading UI file 'mainwindow.ui' -** -** Created: Sat 16. Oct 22:04:12 2010 -** by: Qt User Interface Compiler version 4.6.3 -** -** WARNING! All changes made in this file will be lost when recompiling UI file! -********************************************************************************/ - -#ifndef UI_MAINWINDOW_H -#define UI_MAINWINDOW_H - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -QT_BEGIN_NAMESPACE - -class Ui_MainWindow -{ -public: - QWidget *centralWidget; - QWidget *widget; - QVBoxLayout *verticalLayout_4; - QVBoxLayout *verticalLayout_3; - QGroupBox *groupBox_5; - QVBoxLayout *verticalLayout_8; - QLabel *label_2; - QComboBox *comboBox; - QPushButton *pushButton_2; - QGroupBox *groupBox; - QVBoxLayout *verticalLayout_6; - QVBoxLayout *verticalLayout_5; - QLineEdit *lineEdit; - QPushButton *pushButtonGO; - QLabel *label; - QGroupBox *groupBox_2; - QHBoxLayout *horizontalLayout; - QPushButton *pushButtonRL; - QPushButton *pushButtonRC; - QPushButton *pushButtonRR; - QGroupBox *groupBox_3; - QVBoxLayout *verticalLayout; - QHBoxLayout *horizontalLayout_3; - QPushButton *pushButtonZoomP; - QPushButton *pushButtonZoomM; - QVBoxLayout *verticalLayout_2; - QLabel *label_4; - QDoubleSpinBox *doubleSpinBox; - QLabel *label_5; - QGroupBox *groupBox_4; - QVBoxLayout *verticalLayout_7; - QCheckBox *checkBox; - QCheckBox *checkBox_2; - QPushButton *pushButton; - QMenuBar *menuBar; - QToolBar *mainToolBar; - QStatusBar *statusBar; - - void setupUi(QMainWindow *MainWindow) - { - if (MainWindow->objectName().isEmpty()) - MainWindow->setObjectName(QString::fromUtf8("MainWindow")); - MainWindow->resize(524, 551); - centralWidget = new QWidget(MainWindow); - centralWidget->setObjectName(QString::fromUtf8("centralWidget")); - widget = new QWidget(centralWidget); - widget->setObjectName(QString::fromUtf8("widget")); - widget->setGeometry(QRect(110, 15, 181, 421)); - QSizePolicy sizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); - sizePolicy.setHorizontalStretch(10); - sizePolicy.setVerticalStretch(0); - sizePolicy.setHeightForWidth(widget->sizePolicy().hasHeightForWidth()); - widget->setSizePolicy(sizePolicy); - widget->setMaximumSize(QSize(181, 16777215)); - verticalLayout_4 = new QVBoxLayout(widget); - verticalLayout_4->setSpacing(0); - verticalLayout_4->setContentsMargins(0, 0, 0, 0); - verticalLayout_4->setObjectName(QString::fromUtf8("verticalLayout_4")); - verticalLayout_3 = new QVBoxLayout(); - verticalLayout_3->setSpacing(6); - verticalLayout_3->setObjectName(QString::fromUtf8("verticalLayout_3")); - groupBox_5 = new QGroupBox(widget); - groupBox_5->setObjectName(QString::fromUtf8("groupBox_5")); - verticalLayout_8 = new QVBoxLayout(groupBox_5); - verticalLayout_8->setSpacing(6); - verticalLayout_8->setContentsMargins(11, 11, 11, 11); - verticalLayout_8->setObjectName(QString::fromUtf8("verticalLayout_8")); - label_2 = new QLabel(groupBox_5); - label_2->setObjectName(QString::fromUtf8("label_2")); - - verticalLayout_8->addWidget(label_2); - - comboBox = new QComboBox(groupBox_5); - comboBox->setObjectName(QString::fromUtf8("comboBox")); - - verticalLayout_8->addWidget(comboBox); - - pushButton_2 = new QPushButton(groupBox_5); - pushButton_2->setObjectName(QString::fromUtf8("pushButton_2")); - - verticalLayout_8->addWidget(pushButton_2); - - - verticalLayout_3->addWidget(groupBox_5); - - groupBox = new QGroupBox(widget); - groupBox->setObjectName(QString::fromUtf8("groupBox")); - verticalLayout_6 = new QVBoxLayout(groupBox); - verticalLayout_6->setSpacing(6); - verticalLayout_6->setContentsMargins(11, 11, 11, 11); - verticalLayout_6->setObjectName(QString::fromUtf8("verticalLayout_6")); - verticalLayout_5 = new QVBoxLayout(); - verticalLayout_5->setSpacing(6); - verticalLayout_5->setObjectName(QString::fromUtf8("verticalLayout_5")); - lineEdit = new QLineEdit(groupBox); - lineEdit->setObjectName(QString::fromUtf8("lineEdit")); - - verticalLayout_5->addWidget(lineEdit); - - pushButtonGO = new QPushButton(groupBox); - pushButtonGO->setObjectName(QString::fromUtf8("pushButtonGO")); - - verticalLayout_5->addWidget(pushButtonGO); - - - verticalLayout_6->addLayout(verticalLayout_5); - - label = new QLabel(groupBox); - label->setObjectName(QString::fromUtf8("label")); - - verticalLayout_6->addWidget(label); - - - verticalLayout_3->addWidget(groupBox); - - groupBox_2 = new QGroupBox(widget); - groupBox_2->setObjectName(QString::fromUtf8("groupBox_2")); - horizontalLayout = new QHBoxLayout(groupBox_2); - horizontalLayout->setSpacing(6); - horizontalLayout->setContentsMargins(11, 11, 11, 11); - horizontalLayout->setObjectName(QString::fromUtf8("horizontalLayout")); - pushButtonRL = new QPushButton(groupBox_2); - pushButtonRL->setObjectName(QString::fromUtf8("pushButtonRL")); - - horizontalLayout->addWidget(pushButtonRL); - - pushButtonRC = new QPushButton(groupBox_2); - pushButtonRC->setObjectName(QString::fromUtf8("pushButtonRC")); - - horizontalLayout->addWidget(pushButtonRC); - - pushButtonRR = new QPushButton(groupBox_2); - pushButtonRR->setObjectName(QString::fromUtf8("pushButtonRR")); - - horizontalLayout->addWidget(pushButtonRR); - - - verticalLayout_3->addWidget(groupBox_2); - - groupBox_3 = new QGroupBox(widget); - groupBox_3->setObjectName(QString::fromUtf8("groupBox_3")); - verticalLayout = new QVBoxLayout(groupBox_3); - verticalLayout->setSpacing(6); - verticalLayout->setContentsMargins(11, 11, 11, 11); - verticalLayout->setObjectName(QString::fromUtf8("verticalLayout")); - horizontalLayout_3 = new QHBoxLayout(); - horizontalLayout_3->setSpacing(6); - horizontalLayout_3->setObjectName(QString::fromUtf8("horizontalLayout_3")); - pushButtonZoomP = new QPushButton(groupBox_3); - pushButtonZoomP->setObjectName(QString::fromUtf8("pushButtonZoomP")); - - horizontalLayout_3->addWidget(pushButtonZoomP); - - pushButtonZoomM = new QPushButton(groupBox_3); - pushButtonZoomM->setObjectName(QString::fromUtf8("pushButtonZoomM")); - - horizontalLayout_3->addWidget(pushButtonZoomM); - - - verticalLayout->addLayout(horizontalLayout_3); - - verticalLayout_2 = new QVBoxLayout(); - verticalLayout_2->setSpacing(6); - verticalLayout_2->setObjectName(QString::fromUtf8("verticalLayout_2")); - label_4 = new QLabel(groupBox_3); - label_4->setObjectName(QString::fromUtf8("label_4")); - label_4->setAlignment(Qt::AlignCenter); - - verticalLayout_2->addWidget(label_4); - - - verticalLayout->addLayout(verticalLayout_2); - - doubleSpinBox = new QDoubleSpinBox(groupBox_3); - doubleSpinBox->setObjectName(QString::fromUtf8("doubleSpinBox")); - doubleSpinBox->setSingleStep(0.1); - doubleSpinBox->setValue(1); - - verticalLayout->addWidget(doubleSpinBox); - - label_5 = new QLabel(groupBox_3); - label_5->setObjectName(QString::fromUtf8("label_5")); - label_5->setAlignment(Qt::AlignCenter); - - verticalLayout->addWidget(label_5); - - groupBox_4 = new QGroupBox(groupBox_3); - groupBox_4->setObjectName(QString::fromUtf8("groupBox_4")); - verticalLayout_7 = new QVBoxLayout(groupBox_4); - verticalLayout_7->setSpacing(6); - verticalLayout_7->setContentsMargins(11, 11, 11, 11); - verticalLayout_7->setObjectName(QString::fromUtf8("verticalLayout_7")); - checkBox = new QCheckBox(groupBox_4); - checkBox->setObjectName(QString::fromUtf8("checkBox")); - checkBox->setChecked(true); - - verticalLayout_7->addWidget(checkBox); - - checkBox_2 = new QCheckBox(groupBox_4); - checkBox_2->setObjectName(QString::fromUtf8("checkBox_2")); - - verticalLayout_7->addWidget(checkBox_2); - - pushButton = new QPushButton(groupBox_4); - pushButton->setObjectName(QString::fromUtf8("pushButton")); - - verticalLayout_7->addWidget(pushButton); - - - verticalLayout->addWidget(groupBox_4); - - - verticalLayout_3->addWidget(groupBox_3); - - - verticalLayout_4->addLayout(verticalLayout_3); - - MainWindow->setCentralWidget(centralWidget); - menuBar = new QMenuBar(MainWindow); - menuBar->setObjectName(QString::fromUtf8("menuBar")); - menuBar->setGeometry(QRect(0, 0, 524, 21)); - MainWindow->setMenuBar(menuBar); - mainToolBar = new QToolBar(MainWindow); - mainToolBar->setObjectName(QString::fromUtf8("mainToolBar")); - MainWindow->addToolBar(Qt::TopToolBarArea, mainToolBar); - statusBar = new QStatusBar(MainWindow); - statusBar->setObjectName(QString::fromUtf8("statusBar")); - MainWindow->setStatusBar(statusBar); - - retranslateUi(MainWindow); - - QMetaObject::connectSlotsByName(MainWindow); - } // setupUi - - void retranslateUi(QMainWindow *MainWindow) - { - MainWindow->setWindowTitle(QApplication::translate("MainWindow", "MainWindow", 0, QApplication::UnicodeUTF8)); - groupBox_5->setTitle(QApplication::translate("MainWindow", "MapType", 0, QApplication::UnicodeUTF8)); - label_2->setText(QApplication::translate("MainWindow", "TextLabel", 0, QApplication::UnicodeUTF8)); - pushButton_2->setText(QApplication::translate("MainWindow", "PushButton", 0, QApplication::UnicodeUTF8)); - groupBox->setTitle(QApplication::translate("MainWindow", "Goto Place", 0, QApplication::UnicodeUTF8)); - pushButtonGO->setText(QApplication::translate("MainWindow", "GO", 0, QApplication::UnicodeUTF8)); - label->setText(QApplication::translate("MainWindow", "GeoCoderStatusCode", 0, QApplication::UnicodeUTF8)); - groupBox_2->setTitle(QApplication::translate("MainWindow", "Rotate", 0, QApplication::UnicodeUTF8)); - pushButtonRL->setText(QApplication::translate("MainWindow", "Left", 0, QApplication::UnicodeUTF8)); - pushButtonRC->setText(QApplication::translate("MainWindow", "Center", 0, QApplication::UnicodeUTF8)); - pushButtonRR->setText(QApplication::translate("MainWindow", "Right", 0, QApplication::UnicodeUTF8)); - groupBox_3->setTitle(QApplication::translate("MainWindow", "Zoom", 0, QApplication::UnicodeUTF8)); - pushButtonZoomP->setText(QApplication::translate("MainWindow", "+", 0, QApplication::UnicodeUTF8)); - pushButtonZoomM->setText(QApplication::translate("MainWindow", "-", 0, QApplication::UnicodeUTF8)); - label_4->setText(QApplication::translate("MainWindow", "ZoomIncrement", 0, QApplication::UnicodeUTF8)); - label_5->setText(QApplication::translate("MainWindow", "CurrentZoom=", 0, QApplication::UnicodeUTF8)); - groupBox_4->setTitle(QApplication::translate("MainWindow", "Misc", 0, QApplication::UnicodeUTF8)); - checkBox->setText(QApplication::translate("MainWindow", "ShowGridLines", 0, QApplication::UnicodeUTF8)); - checkBox_2->setText(QApplication::translate("MainWindow", "UseOpenGL", 0, QApplication::UnicodeUTF8)); - pushButton->setText(QApplication::translate("MainWindow", "ReloadMap", 0, QApplication::UnicodeUTF8)); - } // retranslateUi - -}; - -namespace Ui { - class MainWindow: public Ui_MainWindow {}; -} // namespace Ui - -QT_END_NAMESPACE - -#endif // UI_MAINWINDOW_H +/******************************************************************************** +** Form generated from reading UI file 'mainwindow.ui' +** +** Created: Sat 16. Oct 22:04:12 2010 +** by: Qt User Interface Compiler version 4.6.3 +** +** WARNING! All changes made in this file will be lost when recompiling UI file! +********************************************************************************/ + +#ifndef UI_MAINWINDOW_H +#define UI_MAINWINDOW_H + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +QT_BEGIN_NAMESPACE + +class Ui_MainWindow +{ +public: + QWidget *centralWidget; + QWidget *widget; + QVBoxLayout *verticalLayout_4; + QVBoxLayout *verticalLayout_3; + QGroupBox *groupBox_5; + QVBoxLayout *verticalLayout_8; + QLabel *label_2; + QComboBox *comboBox; + QPushButton *pushButton_2; + QGroupBox *groupBox; + QVBoxLayout *verticalLayout_6; + QVBoxLayout *verticalLayout_5; + QLineEdit *lineEdit; + QPushButton *pushButtonGO; + QLabel *label; + QGroupBox *groupBox_2; + QHBoxLayout *horizontalLayout; + QPushButton *pushButtonRL; + QPushButton *pushButtonRC; + QPushButton *pushButtonRR; + QGroupBox *groupBox_3; + QVBoxLayout *verticalLayout; + QHBoxLayout *horizontalLayout_3; + QPushButton *pushButtonZoomP; + QPushButton *pushButtonZoomM; + QVBoxLayout *verticalLayout_2; + QLabel *label_4; + QDoubleSpinBox *doubleSpinBox; + QLabel *label_5; + QGroupBox *groupBox_4; + QVBoxLayout *verticalLayout_7; + QCheckBox *checkBox; + QCheckBox *checkBox_2; + QPushButton *pushButton; + QMenuBar *menuBar; + QToolBar *mainToolBar; + QStatusBar *statusBar; + + void setupUi(QMainWindow *MainWindow) + { + if (MainWindow->objectName().isEmpty()) + MainWindow->setObjectName(QString::fromUtf8("MainWindow")); + MainWindow->resize(524, 551); + centralWidget = new QWidget(MainWindow); + centralWidget->setObjectName(QString::fromUtf8("centralWidget")); + widget = new QWidget(centralWidget); + widget->setObjectName(QString::fromUtf8("widget")); + widget->setGeometry(QRect(110, 15, 181, 421)); + QSizePolicy sizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); + sizePolicy.setHorizontalStretch(10); + sizePolicy.setVerticalStretch(0); + sizePolicy.setHeightForWidth(widget->sizePolicy().hasHeightForWidth()); + widget->setSizePolicy(sizePolicy); + widget->setMaximumSize(QSize(181, 16777215)); + verticalLayout_4 = new QVBoxLayout(widget); + verticalLayout_4->setSpacing(0); + verticalLayout_4->setContentsMargins(0, 0, 0, 0); + verticalLayout_4->setObjectName(QString::fromUtf8("verticalLayout_4")); + verticalLayout_3 = new QVBoxLayout(); + verticalLayout_3->setSpacing(6); + verticalLayout_3->setObjectName(QString::fromUtf8("verticalLayout_3")); + groupBox_5 = new QGroupBox(widget); + groupBox_5->setObjectName(QString::fromUtf8("groupBox_5")); + verticalLayout_8 = new QVBoxLayout(groupBox_5); + verticalLayout_8->setSpacing(6); + verticalLayout_8->setContentsMargins(11, 11, 11, 11); + verticalLayout_8->setObjectName(QString::fromUtf8("verticalLayout_8")); + label_2 = new QLabel(groupBox_5); + label_2->setObjectName(QString::fromUtf8("label_2")); + + verticalLayout_8->addWidget(label_2); + + comboBox = new QComboBox(groupBox_5); + comboBox->setObjectName(QString::fromUtf8("comboBox")); + + verticalLayout_8->addWidget(comboBox); + + pushButton_2 = new QPushButton(groupBox_5); + pushButton_2->setObjectName(QString::fromUtf8("pushButton_2")); + + verticalLayout_8->addWidget(pushButton_2); + + + verticalLayout_3->addWidget(groupBox_5); + + groupBox = new QGroupBox(widget); + groupBox->setObjectName(QString::fromUtf8("groupBox")); + verticalLayout_6 = new QVBoxLayout(groupBox); + verticalLayout_6->setSpacing(6); + verticalLayout_6->setContentsMargins(11, 11, 11, 11); + verticalLayout_6->setObjectName(QString::fromUtf8("verticalLayout_6")); + verticalLayout_5 = new QVBoxLayout(); + verticalLayout_5->setSpacing(6); + verticalLayout_5->setObjectName(QString::fromUtf8("verticalLayout_5")); + lineEdit = new QLineEdit(groupBox); + lineEdit->setObjectName(QString::fromUtf8("lineEdit")); + + verticalLayout_5->addWidget(lineEdit); + + pushButtonGO = new QPushButton(groupBox); + pushButtonGO->setObjectName(QString::fromUtf8("pushButtonGO")); + + verticalLayout_5->addWidget(pushButtonGO); + + + verticalLayout_6->addLayout(verticalLayout_5); + + label = new QLabel(groupBox); + label->setObjectName(QString::fromUtf8("label")); + + verticalLayout_6->addWidget(label); + + + verticalLayout_3->addWidget(groupBox); + + groupBox_2 = new QGroupBox(widget); + groupBox_2->setObjectName(QString::fromUtf8("groupBox_2")); + horizontalLayout = new QHBoxLayout(groupBox_2); + horizontalLayout->setSpacing(6); + horizontalLayout->setContentsMargins(11, 11, 11, 11); + horizontalLayout->setObjectName(QString::fromUtf8("horizontalLayout")); + pushButtonRL = new QPushButton(groupBox_2); + pushButtonRL->setObjectName(QString::fromUtf8("pushButtonRL")); + + horizontalLayout->addWidget(pushButtonRL); + + pushButtonRC = new QPushButton(groupBox_2); + pushButtonRC->setObjectName(QString::fromUtf8("pushButtonRC")); + + horizontalLayout->addWidget(pushButtonRC); + + pushButtonRR = new QPushButton(groupBox_2); + pushButtonRR->setObjectName(QString::fromUtf8("pushButtonRR")); + + horizontalLayout->addWidget(pushButtonRR); + + + verticalLayout_3->addWidget(groupBox_2); + + groupBox_3 = new QGroupBox(widget); + groupBox_3->setObjectName(QString::fromUtf8("groupBox_3")); + verticalLayout = new QVBoxLayout(groupBox_3); + verticalLayout->setSpacing(6); + verticalLayout->setContentsMargins(11, 11, 11, 11); + verticalLayout->setObjectName(QString::fromUtf8("verticalLayout")); + horizontalLayout_3 = new QHBoxLayout(); + horizontalLayout_3->setSpacing(6); + horizontalLayout_3->setObjectName(QString::fromUtf8("horizontalLayout_3")); + pushButtonZoomP = new QPushButton(groupBox_3); + pushButtonZoomP->setObjectName(QString::fromUtf8("pushButtonZoomP")); + + horizontalLayout_3->addWidget(pushButtonZoomP); + + pushButtonZoomM = new QPushButton(groupBox_3); + pushButtonZoomM->setObjectName(QString::fromUtf8("pushButtonZoomM")); + + horizontalLayout_3->addWidget(pushButtonZoomM); + + + verticalLayout->addLayout(horizontalLayout_3); + + verticalLayout_2 = new QVBoxLayout(); + verticalLayout_2->setSpacing(6); + verticalLayout_2->setObjectName(QString::fromUtf8("verticalLayout_2")); + label_4 = new QLabel(groupBox_3); + label_4->setObjectName(QString::fromUtf8("label_4")); + label_4->setAlignment(Qt::AlignCenter); + + verticalLayout_2->addWidget(label_4); + + + verticalLayout->addLayout(verticalLayout_2); + + doubleSpinBox = new QDoubleSpinBox(groupBox_3); + doubleSpinBox->setObjectName(QString::fromUtf8("doubleSpinBox")); + doubleSpinBox->setSingleStep(0.1); + doubleSpinBox->setValue(1); + + verticalLayout->addWidget(doubleSpinBox); + + label_5 = new QLabel(groupBox_3); + label_5->setObjectName(QString::fromUtf8("label_5")); + label_5->setAlignment(Qt::AlignCenter); + + verticalLayout->addWidget(label_5); + + groupBox_4 = new QGroupBox(groupBox_3); + groupBox_4->setObjectName(QString::fromUtf8("groupBox_4")); + verticalLayout_7 = new QVBoxLayout(groupBox_4); + verticalLayout_7->setSpacing(6); + verticalLayout_7->setContentsMargins(11, 11, 11, 11); + verticalLayout_7->setObjectName(QString::fromUtf8("verticalLayout_7")); + checkBox = new QCheckBox(groupBox_4); + checkBox->setObjectName(QString::fromUtf8("checkBox")); + checkBox->setChecked(true); + + verticalLayout_7->addWidget(checkBox); + + checkBox_2 = new QCheckBox(groupBox_4); + checkBox_2->setObjectName(QString::fromUtf8("checkBox_2")); + + verticalLayout_7->addWidget(checkBox_2); + + pushButton = new QPushButton(groupBox_4); + pushButton->setObjectName(QString::fromUtf8("pushButton")); + + verticalLayout_7->addWidget(pushButton); + + + verticalLayout->addWidget(groupBox_4); + + + verticalLayout_3->addWidget(groupBox_3); + + + verticalLayout_4->addLayout(verticalLayout_3); + + MainWindow->setCentralWidget(centralWidget); + menuBar = new QMenuBar(MainWindow); + menuBar->setObjectName(QString::fromUtf8("menuBar")); + menuBar->setGeometry(QRect(0, 0, 524, 21)); + MainWindow->setMenuBar(menuBar); + mainToolBar = new QToolBar(MainWindow); + mainToolBar->setObjectName(QString::fromUtf8("mainToolBar")); + MainWindow->addToolBar(Qt::TopToolBarArea, mainToolBar); + statusBar = new QStatusBar(MainWindow); + statusBar->setObjectName(QString::fromUtf8("statusBar")); + MainWindow->setStatusBar(statusBar); + + retranslateUi(MainWindow); + + QMetaObject::connectSlotsByName(MainWindow); + } // setupUi + + void retranslateUi(QMainWindow *MainWindow) + { + MainWindow->setWindowTitle(QApplication::translate("MainWindow", "MainWindow", 0, QApplication::UnicodeUTF8)); + groupBox_5->setTitle(QApplication::translate("MainWindow", "MapType", 0, QApplication::UnicodeUTF8)); + label_2->setText(QApplication::translate("MainWindow", "TextLabel", 0, QApplication::UnicodeUTF8)); + pushButton_2->setText(QApplication::translate("MainWindow", "PushButton", 0, QApplication::UnicodeUTF8)); + groupBox->setTitle(QApplication::translate("MainWindow", "Goto Place", 0, QApplication::UnicodeUTF8)); + pushButtonGO->setText(QApplication::translate("MainWindow", "GO", 0, QApplication::UnicodeUTF8)); + label->setText(QApplication::translate("MainWindow", "GeoCoderStatusCode", 0, QApplication::UnicodeUTF8)); + groupBox_2->setTitle(QApplication::translate("MainWindow", "Rotate", 0, QApplication::UnicodeUTF8)); + pushButtonRL->setText(QApplication::translate("MainWindow", "Left", 0, QApplication::UnicodeUTF8)); + pushButtonRC->setText(QApplication::translate("MainWindow", "Center", 0, QApplication::UnicodeUTF8)); + pushButtonRR->setText(QApplication::translate("MainWindow", "Right", 0, QApplication::UnicodeUTF8)); + groupBox_3->setTitle(QApplication::translate("MainWindow", "Zoom", 0, QApplication::UnicodeUTF8)); + pushButtonZoomP->setText(QApplication::translate("MainWindow", "+", 0, QApplication::UnicodeUTF8)); + pushButtonZoomM->setText(QApplication::translate("MainWindow", "-", 0, QApplication::UnicodeUTF8)); + label_4->setText(QApplication::translate("MainWindow", "ZoomIncrement", 0, QApplication::UnicodeUTF8)); + label_5->setText(QApplication::translate("MainWindow", "CurrentZoom=", 0, QApplication::UnicodeUTF8)); + groupBox_4->setTitle(QApplication::translate("MainWindow", "Misc", 0, QApplication::UnicodeUTF8)); + checkBox->setText(QApplication::translate("MainWindow", "ShowGridLines", 0, QApplication::UnicodeUTF8)); + checkBox_2->setText(QApplication::translate("MainWindow", "UseOpenGL", 0, QApplication::UnicodeUTF8)); + pushButton->setText(QApplication::translate("MainWindow", "ReloadMap", 0, QApplication::UnicodeUTF8)); + } // retranslateUi + +}; + +namespace Ui { + class MainWindow: public Ui_MainWindow {}; +} // namespace Ui + +QT_END_NAMESPACE + +#endif // UI_MAINWINDOW_H diff --git a/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/DocumentationHelper.pro b/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/DocumentationHelper.pro index 3e0c1207f..0b98445aa 100644 --- a/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/DocumentationHelper.pro +++ b/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/DocumentationHelper.pro @@ -1,16 +1,16 @@ -#------------------------------------------------- -# -# Project created by QtCreator 2010-05-30T17:21:05 -# -#------------------------------------------------- - -TARGET = DocumentationHelper -TEMPLATE = app - - -SOURCES += main.cpp\ - mainwindow.cpp - -HEADERS += mainwindow.h - -FORMS += mainwindow.ui +#------------------------------------------------- +# +# Project created by QtCreator 2010-05-30T17:21:05 +# +#------------------------------------------------- + +TARGET = DocumentationHelper +TEMPLATE = app + + +SOURCES += main.cpp\ + mainwindow.cpp + +HEADERS += mainwindow.h + +FORMS += mainwindow.ui diff --git a/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/main.cpp b/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/main.cpp index d5d5775ab..256051ba7 100644 --- a/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/main.cpp +++ b/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/main.cpp @@ -1,38 +1,38 @@ -/** -****************************************************************************** -* -* @file main.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup DocumentationHelper -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include -#include "mainwindow.h" - - -int main(int argc, char *argv[]) -{ - QApplication a(argc, argv); - MainWindow w; - w.show(); - return a.exec(); -} - +/** +****************************************************************************** +* +* @file main.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup DocumentationHelper +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include +#include "mainwindow.h" + + +int main(int argc, char *argv[]) +{ + QApplication a(argc, argv); + MainWindow w; + w.show(); + return a.exec(); +} + diff --git a/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/mainwindow.cpp b/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/mainwindow.cpp index 524c67103..1c0b61203 100644 --- a/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/mainwindow.cpp +++ b/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/mainwindow.cpp @@ -1,244 +1,244 @@ -/** -****************************************************************************** -* -* @file mainwindow.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup DocumentationHelper -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - - -#include "mainwindow.h" -#include "ui_mainwindow.h" -#include "QFileDialog" -MainWindow::MainWindow(QWidget *parent) : - QMainWindow(parent), - ui(new Ui::MainWindow) -{ - ui->setupUi(this); - license<<"/**"; - license<<"******************************************************************************"; - license<<"*"; - license<<"* @file %file"; - license<<"* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010."; - license<<"* @brief "; - license<<"* @see The GNU Public License (GPL) Version 3"; - license<<"* @defgroup %defgroup"; - license<<"* @{"; - license<<"* "; - license<<"*****************************************************************************/"; - license<<"/* "; - license<<"* This program is free software; you can redistribute it and/or modify "; - license<<"* it under the terms of the GNU General Public License as published by "; - license<<"* the Free Software Foundation; either version 3 of the License, or "; - license<<"* (at your option) any later version."; - license<<"* "; - license<<"* This program is distributed in the hope that it will be useful, but "; - license<<"* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY "; - license<<"* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License "; - license<<"* for more details."; - license<<"* "; - license<<"* You should have received a copy of the GNU General Public License along "; - license<<"* with this program; if not, write to the Free Software Foundation, Inc., "; - license<<"* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA"; - license<<"*/"; - -} - -MainWindow::~MainWindow() -{ - delete ui; -} - -void MainWindow::changeEvent(QEvent *e) -{ - QMainWindow::changeEvent(e); - switch (e->type()) { - case QEvent::LanguageChange: - ui->retranslateUi(this); - break; - default: - break; - } -} - -void MainWindow::on_cpathBT_clicked() -{ - wpath=QFileDialog::getExistingDirectory(this,"Choose Work Path"); - ui->cpathL->setText("Current Path:"+wpath); -} - -void MainWindow::on_goBT_clicked() -{ - QDir myDir(wpath); - QStringList filter; - filter<<"*.cpp"<<"*.h"; - QStringList list = myDir.entryList (filter); - - foreach(QString str,list) - { - bool go=true; - if(ui->confirmCB->isChecked()) - if(QMessageBox::question(this,"Process File?:",str,QMessageBox::Yes,QMessageBox::No)==QMessageBox::No)go=false; - if(go){ - ui->cfileL->setText("Current File:"+str); - QFile file(wpath+QDir::separator()+str); - if (!file.open(QIODevice::ReadWrite)) { - ui->output->append("Cannot open file "+str+" for writing"); - } - else - { - ui->output->append("Processing file "+str); - QTextStream out(&file); - QStringList filestr; - out.seek(0); - while(!out.atEnd()) filestr<licenseCB->isChecked()) - { - - bool haslicense=false; - foreach(QString str,filestr) - { - if(str.contains("The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010")) - { - haslicense=true; - ui->output->append("File Already has License Info"); - } - } - - if(!haslicense) - { - bool process=true; - if(ui->confirmCB->isChecked()) - if(QMessageBox::question(this,"Add license Info?:",str,QMessageBox::Yes,QMessageBox::No)==QMessageBox::No) process=false; - if(process) - { - ui->output->append("Added License info to file"); - out.seek(0); - foreach(QString line,license) - { - line.replace("%file",str); - line.replace("%defgroup",ui->defgroup->text()); - out<nameCB->isChecked()) - { - filestr.clear(); - out.seek(0); - while(!out.atEnd()) filestr<output->append("File Already has Namespace"); - } - } - - if(ui->confirmCB->isChecked() && process) - if(QMessageBox::question(this,"Create Namespace?:",str,QMessageBox::Yes,QMessageBox::No)==QMessageBox::No) process=false; - if(process) - { - ui->output->append("Added NameSpace to file"); - out.seek(0); - bool initdone=false; - for(int x=0;xnamespa->text()+" {"); - filestr.insert(x," "); - initdone=true; - } - } - else - { - if((QString)str.split(".").at(1)=="cpp") - { - filestr.append("}"); - break; - } - else - { - for(int y=filestr.count()-1;y>1;--y) - { - QString s=filestr.at(y); - if(s.contains("#endif")) - { - filestr.insert(y,"}"); - break; - } - } - break; - } - } - } - foreach(QString str,filestr) out<bockifCB->isChecked()) - { - QString genif; - ui->output->append("Creating block ifs"); - filestr.clear(); - out.seek(0); - while(!out.atEnd()) filestr<textEdit->append(genif); - foreach(QString str,filestr) out<setupUi(this); + license<<"/**"; + license<<"******************************************************************************"; + license<<"*"; + license<<"* @file %file"; + license<<"* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010."; + license<<"* @brief "; + license<<"* @see The GNU Public License (GPL) Version 3"; + license<<"* @defgroup %defgroup"; + license<<"* @{"; + license<<"* "; + license<<"*****************************************************************************/"; + license<<"/* "; + license<<"* This program is free software; you can redistribute it and/or modify "; + license<<"* it under the terms of the GNU General Public License as published by "; + license<<"* the Free Software Foundation; either version 3 of the License, or "; + license<<"* (at your option) any later version."; + license<<"* "; + license<<"* This program is distributed in the hope that it will be useful, but "; + license<<"* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY "; + license<<"* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License "; + license<<"* for more details."; + license<<"* "; + license<<"* You should have received a copy of the GNU General Public License along "; + license<<"* with this program; if not, write to the Free Software Foundation, Inc., "; + license<<"* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA"; + license<<"*/"; + +} + +MainWindow::~MainWindow() +{ + delete ui; +} + +void MainWindow::changeEvent(QEvent *e) +{ + QMainWindow::changeEvent(e); + switch (e->type()) { + case QEvent::LanguageChange: + ui->retranslateUi(this); + break; + default: + break; + } +} + +void MainWindow::on_cpathBT_clicked() +{ + wpath=QFileDialog::getExistingDirectory(this,"Choose Work Path"); + ui->cpathL->setText("Current Path:"+wpath); +} + +void MainWindow::on_goBT_clicked() +{ + QDir myDir(wpath); + QStringList filter; + filter<<"*.cpp"<<"*.h"; + QStringList list = myDir.entryList (filter); + + foreach(QString str,list) + { + bool go=true; + if(ui->confirmCB->isChecked()) + if(QMessageBox::question(this,"Process File?:",str,QMessageBox::Yes,QMessageBox::No)==QMessageBox::No)go=false; + if(go){ + ui->cfileL->setText("Current File:"+str); + QFile file(wpath+QDir::separator()+str); + if (!file.open(QIODevice::ReadWrite)) { + ui->output->append("Cannot open file "+str+" for writing"); + } + else + { + ui->output->append("Processing file "+str); + QTextStream out(&file); + QStringList filestr; + out.seek(0); + while(!out.atEnd()) filestr<licenseCB->isChecked()) + { + + bool haslicense=false; + foreach(QString str,filestr) + { + if(str.contains("The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010")) + { + haslicense=true; + ui->output->append("File Already has License Info"); + } + } + + if(!haslicense) + { + bool process=true; + if(ui->confirmCB->isChecked()) + if(QMessageBox::question(this,"Add license Info?:",str,QMessageBox::Yes,QMessageBox::No)==QMessageBox::No) process=false; + if(process) + { + ui->output->append("Added License info to file"); + out.seek(0); + foreach(QString line,license) + { + line.replace("%file",str); + line.replace("%defgroup",ui->defgroup->text()); + out<nameCB->isChecked()) + { + filestr.clear(); + out.seek(0); + while(!out.atEnd()) filestr<output->append("File Already has Namespace"); + } + } + + if(ui->confirmCB->isChecked() && process) + if(QMessageBox::question(this,"Create Namespace?:",str,QMessageBox::Yes,QMessageBox::No)==QMessageBox::No) process=false; + if(process) + { + ui->output->append("Added NameSpace to file"); + out.seek(0); + bool initdone=false; + for(int x=0;xnamespa->text()+" {"); + filestr.insert(x," "); + initdone=true; + } + } + else + { + if((QString)str.split(".").at(1)=="cpp") + { + filestr.append("}"); + break; + } + else + { + for(int y=filestr.count()-1;y>1;--y) + { + QString s=filestr.at(y); + if(s.contains("#endif")) + { + filestr.insert(y,"}"); + break; + } + } + break; + } + } + } + foreach(QString str,filestr) out<bockifCB->isChecked()) + { + QString genif; + ui->output->append("Creating block ifs"); + filestr.clear(); + out.seek(0); + while(!out.atEnd()) filestr<textEdit->append(genif); + foreach(QString str,filestr) out< -#include -#include -#include -#include - -namespace Ui { - class MainWindow; -} - -class MainWindow : public QMainWindow { - Q_OBJECT -public: - MainWindow(QWidget *parent = 0); - ~MainWindow(); - -protected: - void changeEvent(QEvent *e); - -private: - Ui::MainWindow *ui; - QString wpath; - QStringList license; - -private slots: - void on_goBT_clicked(); - void on_cpathBT_clicked(); -}; - -#endif // MAINWINDOW_H +/** +****************************************************************************** +* +* @file mainwindow.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup DocumentationHelper +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef MAINWINDOW_H +#define MAINWINDOW_H + +#include +#include +#include +#include +#include + +namespace Ui { + class MainWindow; +} + +class MainWindow : public QMainWindow { + Q_OBJECT +public: + MainWindow(QWidget *parent = 0); + ~MainWindow(); + +protected: + void changeEvent(QEvent *e); + +private: + Ui::MainWindow *ui; + QString wpath; + QStringList license; + +private slots: + void on_goBT_clicked(); + void on_cpathBT_clicked(); +}; + +#endif // MAINWINDOW_H diff --git a/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/mainwindow.ui b/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/mainwindow.ui index 6a18399fa..44bbbfb61 100644 --- a/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/mainwindow.ui +++ b/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/mainwindow.ui @@ -1,266 +1,266 @@ - - - MainWindow - - - - 0 - 0 - 600 - 455 - - - - MainWindow - - - - - - 110 - 10 - 75 - 23 - - - - Go - - - - - - 20 - 380 - 561 - 16 - - - - - 10 - - - - Current File: - - - - - - 20 - 360 - 561 - 16 - - - - - 10 - - - - Current Path: - - - - - - 20 - 10 - 75 - 23 - - - - Choose Path - - - - - - 25 - 177 - 131 - 16 - - - - Created #IF statements - - - - - - 20 - 80 - 111 - 17 - - - - Create NameSpace - - - - - - 20 - 140 - 211 - 17 - - - - Create Block #if in qDebug Statements - - - - - - 20 - 190 - 201 - 161 - - - - - - - 20 - 40 - 111 - 17 - - - - Write License Info - - - - - - 20 - 120 - 141 - 17 - - - - Confirm Before Change - - - - - - 245 - 30 - 341 - 321 - - - - - - - 250 - 10 - 46 - 13 - - - - Output - - - - - false - - - - 20 - 57 - 113 - 20 - - - - DefGroup - - - - - false - - - - 20 - 97 - 113 - 20 - - - - namespace - - - - - - - 0 - 0 - 600 - 21 - - - - - - TopToolBarArea - - - false - - - - - - - - - licenseCB - toggled(bool) - defgroup - setEnabled(bool) - - - 43 - 80 - - - 54 - 100 - - - - - nameCB - toggled(bool) - namespa - setEnabled(bool) - - - 95 - 124 - - - 100 - 144 - - - - - + + + MainWindow + + + + 0 + 0 + 600 + 455 + + + + MainWindow + + + + + + 110 + 10 + 75 + 23 + + + + Go + + + + + + 20 + 380 + 561 + 16 + + + + + 10 + + + + Current File: + + + + + + 20 + 360 + 561 + 16 + + + + + 10 + + + + Current Path: + + + + + + 20 + 10 + 75 + 23 + + + + Choose Path + + + + + + 25 + 177 + 131 + 16 + + + + Created #IF statements + + + + + + 20 + 80 + 111 + 17 + + + + Create NameSpace + + + + + + 20 + 140 + 211 + 17 + + + + Create Block #if in qDebug Statements + + + + + + 20 + 190 + 201 + 161 + + + + + + + 20 + 40 + 111 + 17 + + + + Write License Info + + + + + + 20 + 120 + 141 + 17 + + + + Confirm Before Change + + + + + + 245 + 30 + 341 + 321 + + + + + + + 250 + 10 + 46 + 13 + + + + Output + + + + + false + + + + 20 + 57 + 113 + 20 + + + + DefGroup + + + + + false + + + + 20 + 97 + 113 + 20 + + + + namespace + + + + + + + 0 + 0 + 600 + 21 + + + + + + TopToolBarArea + + + false + + + + + + + + + licenseCB + toggled(bool) + defgroup + setEnabled(bool) + + + 43 + 80 + + + 54 + 100 + + + + + nameCB + toggled(bool) + namespa + setEnabled(bool) + + + 95 + 124 + + + 100 + 144 + + + + + diff --git a/ground/openpilotgcs/src/gcs_version_info.h b/ground/openpilotgcs/src/gcs_version_info.h new file mode 100644 index 000000000..4f4bc2261 --- /dev/null +++ b/ground/openpilotgcs/src/gcs_version_info.h @@ -0,0 +1,6 @@ +// +// This file includes autogenerated version info header used by other plugins. +// The autogenerated file is build by app/gcsversioninfo.pri. +// + +#include "../../../build/openpilotgcs-synthetics/gcs_version_info.h" diff --git a/ground/openpilotgcs/src/libs/aggregation/aggregation.pro b/ground/openpilotgcs/src/libs/aggregation/aggregation.pro index 19c3be888..a542b181b 100644 --- a/ground/openpilotgcs/src/libs/aggregation/aggregation.pro +++ b/ground/openpilotgcs/src/libs/aggregation/aggregation.pro @@ -1,12 +1,12 @@ -TEMPLATE = lib -TARGET = Aggregation - -include(../../openpilotgcslibrary.pri) - -DEFINES += AGGREGATION_LIBRARY - -HEADERS = aggregate.h \ - aggregation_global.h - -SOURCES = aggregate.cpp - +TEMPLATE = lib +TARGET = Aggregation + +include(../../openpilotgcslibrary.pri) + +DEFINES += AGGREGATION_LIBRARY + +HEADERS = aggregate.h \ + aggregation_global.h + +SOURCES = aggregate.cpp + diff --git a/ground/openpilotgcs/src/libs/extensionsystem/extensionsystem.pro b/ground/openpilotgcs/src/libs/extensionsystem/extensionsystem.pro index 30b21dec3..b27eb6272 100644 --- a/ground/openpilotgcs/src/libs/extensionsystem/extensionsystem.pro +++ b/ground/openpilotgcs/src/libs/extensionsystem/extensionsystem.pro @@ -1,33 +1,33 @@ -TEMPLATE = lib -TARGET = ExtensionSystem -DEFINES += EXTENSIONSYSTEM_LIBRARY -include(../../openpilotgcslibrary.pri) -include(extensionsystem_dependencies.pri) - -unix:!macx:!freebsd*:LIBS += -ldl - -DEFINES += GCS_TEST_DIR=\\\"$$GCS_SOURCE_TREE\\\" - -HEADERS += pluginerrorview.h \ - plugindetailsview.h \ - iplugin.h \ - iplugin_p.h \ - extensionsystem_global.h \ - pluginmanager.h \ - pluginmanager_p.h \ - pluginspec.h \ - pluginspec_p.h \ - pluginview.h \ - pluginview_p.h \ - optionsparser.h -SOURCES += pluginerrorview.cpp \ - plugindetailsview.cpp \ - iplugin.cpp \ - pluginmanager.cpp \ - pluginspec.cpp \ - pluginview.cpp \ - optionsparser.cpp -FORMS += pluginview.ui \ - pluginerrorview.ui \ - plugindetailsview.ui -RESOURCES += pluginview.qrc +TEMPLATE = lib +TARGET = ExtensionSystem +DEFINES += EXTENSIONSYSTEM_LIBRARY +include(../../openpilotgcslibrary.pri) +include(extensionsystem_dependencies.pri) + +unix:!macx:!freebsd*:LIBS += -ldl + +DEFINES += GCS_TEST_DIR=\\\"$$GCS_SOURCE_TREE\\\" + +HEADERS += pluginerrorview.h \ + plugindetailsview.h \ + iplugin.h \ + iplugin_p.h \ + extensionsystem_global.h \ + pluginmanager.h \ + pluginmanager_p.h \ + pluginspec.h \ + pluginspec_p.h \ + pluginview.h \ + pluginview_p.h \ + optionsparser.h +SOURCES += pluginerrorview.cpp \ + plugindetailsview.cpp \ + iplugin.cpp \ + pluginmanager.cpp \ + pluginspec.cpp \ + pluginview.cpp \ + optionsparser.cpp +FORMS += pluginview.ui \ + pluginerrorview.ui \ + plugindetailsview.ui +RESOURCES += pluginview.qrc diff --git a/ground/openpilotgcs/src/libs/extensionsystem/plugindetailsview.ui b/ground/openpilotgcs/src/libs/extensionsystem/plugindetailsview.ui index 0e7a02d1e..47e936a16 100644 --- a/ground/openpilotgcs/src/libs/extensionsystem/plugindetailsview.ui +++ b/ground/openpilotgcs/src/libs/extensionsystem/plugindetailsview.ui @@ -1,224 +1,224 @@ - - - ExtensionSystem::Internal::PluginDetailsView - - - - 0 - 0 - 674 - 505 - - - - - 2 - - - - - Name: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - Version: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - Compatibility Version: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - Developer: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - Url: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - true - - - - - - - Location: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - false - - - - - - - - - Description: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - true - - - true - - - - - - - Copyright: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - - - License: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Vertical - - - - 17 - 13 - - - - - - - - - - true - - - true - - - - - - - - - Dependencies: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - - + + + ExtensionSystem::Internal::PluginDetailsView + + + + 0 + 0 + 674 + 505 + + + + + 2 + + + + + Name: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + Version: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + Compatibility Version: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + Developer: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + Url: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + true + + + + + + + Location: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + false + + + + + + + + + Description: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + true + + + true + + + + + + + Copyright: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + + License: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Vertical + + + + 17 + 13 + + + + + + + + + + true + + + true + + + + + + + + + Dependencies: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/libs/extensionsystem/pluginmanager.cpp b/ground/openpilotgcs/src/libs/extensionsystem/pluginmanager.cpp index e29c1644e..09730f2d5 100644 --- a/ground/openpilotgcs/src/libs/extensionsystem/pluginmanager.cpp +++ b/ground/openpilotgcs/src/libs/extensionsystem/pluginmanager.cpp @@ -1,764 +1,764 @@ -/** - ****************************************************************************** - * - * @file pluginmanager.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009. - * @brief - * @see The GNU Public License (GPL) Version 3 - * @defgroup - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pluginmanager.h" -#include "pluginmanager_p.h" -#include "pluginspec.h" -#include "pluginspec_p.h" -#include "optionsparser.h" -#include "iplugin.h" - -#include -#include -#include -#include -#include -#ifdef WITH_TESTS -#include -#endif - -typedef QList PluginSpecSet; - -enum { debugLeaks = 0 }; - -/*! - \namespace ExtensionSystem - \brief The ExtensionSystem namespace provides classes that belong to the core plugin system. - - The basic extension system contains of the plugin manager and its supporting classes, - and the IPlugin interface that must be implemented by plugin providers. -*/ - -/*! - \namespace ExtensionSystem::Internal - \internal -*/ - -/*! - \class ExtensionSystem::PluginManager - \mainclass - - \brief Core plugin system that manages the plugins, their life cycle and their registered objects. - - The plugin manager is used for the following tasks: - \list - \o Manage plugins and their state - \o Manipulate a 'common object pool' - \endlist - - \section1 Plugins - Plugins consist of an xml descriptor file, and of a library that contains a Qt plugin - (declared via Q_EXPORT_PLUGIN) that must derive from the IPlugin class. - The plugin manager is used to set a list of file system directories to search for - plugins, retrieve information about the state of these plugins, and to load them. - - Usually the application creates a PluginManager instance and initiates the loading. - \code - ExtensionSystem::PluginManager *manager = new ExtensionSystem::PluginManager(); - manager->setPluginPaths(QStringList() << "plugins"); // 'plugins' and subdirs will be searched for plugins - manager->loadPlugins(); // try to load all the plugins - \endcode - Additionally it is possible to directly access to the plugin specifications - (the information in the descriptor file), and the plugin instances (via PluginSpec), - and their state. - - \section1 Object Pool - Plugins (and everybody else) can add objects to a common 'pool' that is located in - the plugin manager. Objects in the pool must derive from QObject, there are no other - prerequisites. All objects of a specified type can be retrieved from the object pool - via the getObjects() and getObject() methods. They are aware of Aggregation::Aggregate, i.e. - these methods use the Aggregation::query methods instead of a qobject_cast to determine - the matching objects. - - Whenever the state of the object pool changes a corresponding signal is emitted by the plugin manager. - - A common usecase for the object pool is that a plugin (or the application) provides - an "extension point" for other plugins, which is a class / interface that can - be implemented and added to the object pool. The plugin that provides the - extension point looks for implementations of the class / interface in the object pool. - \code - // plugin A provides a "MimeTypeHandler" extension point - // in plugin B: - MyMimeTypeHandler *handler = new MyMimeTypeHandler(); - ExtensionSystem::PluginManager::instance()->addObject(handler); - // in plugin A: - QList mimeHandlers = - ExtensionSystem::PluginManager::instance()->getObjects(); - \endcode - - \bold Note: The object pool manipulating functions are thread-safe. -*/ - -/*! - \fn void PluginManager::objectAdded(QObject *obj) - Signal that \a obj has been added to the object pool. -*/ - -/*! - \fn void PluginManager::aboutToRemoveObject(QObject *obj) - Signal that \a obj will be removed from the object pool. -*/ - -/*! - \fn void PluginManager::pluginsChanged() - Signal that the list of available plugins has changed. - - \sa plugins() -*/ - -/*! - \fn T *PluginManager::getObject() const - Retrieve the object of a given type from the object pool. - This method is aware of Aggregation::Aggregate, i.e. it uses - the Aggregation::query methods instead of qobject_cast to - determine the type of an object. - If there are more than one object of the given type in - the object pool, this method will choose an arbitrary one of them. - - \sa addObject() -*/ - -/*! - \fn QList PluginManager::getObjects() const - Retrieve all objects of a given type from the object pool. - This method is aware of Aggregation::Aggregate, i.e. it uses - the Aggregation::query methods instead of qobject_cast to - determine the type of an object. - - \sa addObject() -*/ - -using namespace ExtensionSystem; -using namespace ExtensionSystem::Internal; - -static bool lessThanByPluginName(const PluginSpec *one, const PluginSpec *two) -{ - return one->name() < two->name(); -} - -PluginManager *PluginManager::m_instance = 0; - -/*! - \fn PluginManager *PluginManager::instance() - Get the unique plugin manager instance. -*/ -PluginManager *PluginManager::instance() -{ - return m_instance; -} - -/*! - \fn PluginManager::PluginManager() - Create a plugin manager. Should be done only once per application. -*/ -PluginManager::PluginManager() - : d(new PluginManagerPrivate(this)),m_allPluginsLoaded(false) -{ - m_instance = this; -} - -/*! - \fn PluginManager::~PluginManager() - \internal -*/ -PluginManager::~PluginManager() -{ - delete d; - d = 0; -} - -/*! - \fn void PluginManager::addObject(QObject *obj) - Add the given object \a obj to the object pool, so it can be retrieved again from the pool by type. - The plugin manager does not do any memory management - added objects - must be removed from the pool and deleted manually by whoever is responsible for the object. - - Emits the objectAdded() signal. - - \sa PluginManager::removeObject() - \sa PluginManager::getObject() - \sa PluginManager::getObjects() -*/ -void PluginManager::addObject(QObject *obj) -{ - d->addObject(obj); -} - -/*! - \fn void PluginManager::removeObject(QObject *obj) - Emits aboutToRemoveObject() and removes the object \a obj from the object pool. - \sa PluginManager::addObject() -*/ -void PluginManager::removeObject(QObject *obj) -{ - d->removeObject(obj); -} - -/*! - \fn QList PluginManager::allObjects() const - Retrieve the list of all objects in the pool, unfiltered. - Usually clients do not need to call this. - \sa PluginManager::getObject() - \sa PluginManager::getObjects() -*/ -QList PluginManager::allObjects() const -{ - return d->allObjects; -} - -/*! - \fn void PluginManager::loadPlugins() - Tries to load all the plugins that were previously found when - setting the plugin search paths. The plugin specs of the plugins - can be used to retrieve error and state information about individual plugins. - - \sa setPluginPaths() - \sa plugins() -*/ -void PluginManager::loadPlugins() -{ - return d->loadPlugins(); -} - -/*! - \fn QStringList PluginManager::pluginPaths() const - The list of paths were the plugin manager searches for plugins. - - \sa setPluginPaths() -*/ -QStringList PluginManager::pluginPaths() const -{ - return d->pluginPaths; -} - -/*! - \fn void PluginManager::setPluginPaths(const QStringList &paths) - Sets the plugin search paths, i.e. the file system paths where the plugin manager - looks for plugin descriptions. All given \a paths and their sub directory trees - are searched for plugin xml description files. - - \sa pluginPaths() - \sa loadPlugins() -*/ -void PluginManager::setPluginPaths(const QStringList &paths) -{ - d->setPluginPaths(paths); -} - -/*! - \fn QString PluginManager::fileExtension() const - The file extension of plugin description files. - The default is "xml". - - \sa setFileExtension() -*/ -QString PluginManager::fileExtension() const -{ - return d->extension; -} - -/*! - \fn void PluginManager::setFileExtension(const QString &extension) - Sets the file extension of plugin description files. - The default is "xml". - At the moment this must be called before setPluginPaths() is called. - // ### TODO let this + setPluginPaths read the plugin specs lazyly whenever loadPlugins() or plugins() is called. -*/ -void PluginManager::setFileExtension(const QString &extension) -{ - d->extension = extension; -} - -/*! - \fn QStringList PluginManager::arguments() const - The arguments left over after parsing (Neither startup nor plugin - arguments). Typically, this will be the list of files to open. -*/ -QStringList PluginManager::arguments() const -{ - return d->arguments; -} - -/*! - \fn QList PluginManager::plugins() const - List of all plugin specifications that have been found in the plugin search paths. - This list is valid directly after the setPluginPaths() call. - The plugin specifications contain the information from the plugins' xml description files - and the current state of the plugins. If a plugin's library has been already successfully loaded, - the plugin specification has a reference to the created plugin instance as well. - - \sa setPluginPaths() -*/ -QList PluginManager::plugins() const -{ - return d->pluginSpecs; -} - -/*! - \fn bool PluginManager::parseOptions(const QStringList &args, const QMap &appOptions, QMap *foundAppOptions, QString *errorString) - Takes the list of command line options in \a args and parses them. - The plugin manager itself might process some options itself directly (-noload ), and - adds options that are registered by plugins to their plugin specs. - The caller (the application) may register itself for options via the \a appOptions list, containing pairs - of "option string" and a bool that indicates if the option requires an argument. - Application options always override any plugin's options. - - \a foundAppOptions is set to pairs of ("option string", "argument") for any application options that were found. - The command line options that were not processed can be retrieved via the arguments() method. - If an error occurred (like missing argument for an option that requires one), \a errorString contains - a descriptive message of the error. - - Returns if there was an error. - */ -bool PluginManager::parseOptions(const QStringList &args, - const QMap &appOptions, - QMap *foundAppOptions, - QString *errorString) -{ - OptionsParser options(args, appOptions, foundAppOptions, errorString, d); - return options.parse(); -} - - - -static inline void indent(QTextStream &str, int indent) -{ - const QChar blank = QLatin1Char(' '); - for (int i = 0 ; i < indent; i++) - str << blank; -} - -static inline void formatOption(QTextStream &str, - const QString &opt, const QString &parm, const QString &description, - int optionIndentation, int descriptionIndentation) -{ - int remainingIndent = descriptionIndentation - optionIndentation - opt.size(); - indent(str, optionIndentation); - str << opt; - if (!parm.isEmpty()) { - str << " <" << parm << '>'; - remainingIndent -= 3 + parm.size(); - } - indent(str, qMax(0, remainingIndent)); - str << description << '\n'; -} - -/*! - \fn static PluginManager::formatOptions(QTextStream &str, int optionIndentation, int descriptionIndentation) - - Format the startup options of the plugin manager for command line help. -*/ - -void PluginManager::formatOptions(QTextStream &str, int optionIndentation, int descriptionIndentation) -{ - formatOption(str, QLatin1String(OptionsParser::NO_LOAD_OPTION), - QLatin1String("plugin"), QLatin1String("Do not load "), - optionIndentation, descriptionIndentation); -} - -/*! - \fn PluginManager::formatPluginOptions(QTextStream &str, int optionIndentation, int descriptionIndentation) const - - Format the plugin options of the plugin specs for command line help. -*/ - -void PluginManager::formatPluginOptions(QTextStream &str, int optionIndentation, int descriptionIndentation) const -{ - typedef PluginSpec::PluginArgumentDescriptions PluginArgumentDescriptions; - // Check plugins for options - const PluginSpecSet::const_iterator pcend = d->pluginSpecs.constEnd(); - for (PluginSpecSet::const_iterator pit = d->pluginSpecs.constBegin(); pit != pcend; ++pit) { - const PluginArgumentDescriptions pargs = (*pit)->argumentDescriptions(); - if (!pargs.empty()) { - str << "\nPlugin: " << (*pit)->name() << '\n'; - const PluginArgumentDescriptions::const_iterator acend = pargs.constEnd(); - for (PluginArgumentDescriptions::const_iterator ait =pargs.constBegin(); ait != acend; ++ait) - formatOption(str, ait->name, ait->parameter, ait->description, optionIndentation, descriptionIndentation); - } - } -} - -/*! - \fn PluginManager::formatPluginVersions(QTextStream &str) const - - Format the version of the plugin specs for command line help. -*/ - -void PluginManager::formatPluginVersions(QTextStream &str) const -{ - const PluginSpecSet::const_iterator cend = d->pluginSpecs.constEnd(); - for (PluginSpecSet::const_iterator it = d->pluginSpecs.constBegin(); it != cend; ++it) { - const PluginSpec *ps = *it; - str << " " << ps->name() << ' ' << ps->version() << ' ' << ps->description() << '\n'; - } -} - -void PluginManager::startTests() -{ -#ifdef WITH_TESTS - foreach (PluginSpec *pluginSpec, d->testSpecs) { - const QMetaObject *mo = pluginSpec->plugin()->metaObject(); - QStringList methods; - methods.append("arg0"); - // We only want slots starting with "test" - for (int i = mo->methodOffset(); i < mo->methodCount(); ++i) { - if (QByteArray(mo->method(i).signature()).startsWith("test")) { - QString method = QString::fromLatin1(mo->method(i).signature()); - methods.append(method.left(method.size()-2)); - } - } - QTest::qExec(pluginSpec->plugin(), methods); - - } -#endif -} - -/*! - * \fn bool PluginManager::runningTests() const - * \internal - */ -bool PluginManager::runningTests() const -{ - return !d->testSpecs.isEmpty(); -} - -/*! - * \fn QString PluginManager::testDataDirectory() const - * \internal - */ -QString PluginManager::testDataDirectory() const -{ - QByteArray ba = qgetenv("QTCREATOR_TEST_DIR"); - QString s = QString::fromLocal8Bit(ba.constData(), ba.size()); - if (s.isEmpty()) { - s = GCS_TEST_DIR; - s.append("/tests"); - } - s = QDir::cleanPath(s); - return s; -} - -//============PluginManagerPrivate=========== - -/*! - \fn PluginSpec *PluginManagerPrivate::createSpec() - \internal -*/ -PluginSpec *PluginManagerPrivate::createSpec() -{ - return new PluginSpec(); -} - -/*! - \fn PluginSpecPrivate *PluginManagerPrivate::privateSpec(PluginSpec *spec) - \internal -*/ -PluginSpecPrivate *PluginManagerPrivate::privateSpec(PluginSpec *spec) -{ - return spec->d; -} - -/*! - \fn PluginManagerPrivate::PluginManagerPrivate(PluginManager *pluginManager) - \internal -*/ -PluginManagerPrivate::PluginManagerPrivate(PluginManager *pluginManager) - : extension("xml"), q(pluginManager) -{ -} - -/*! - \fn PluginManagerPrivate::~PluginManagerPrivate() - \internal -*/ -PluginManagerPrivate::~PluginManagerPrivate() -{ - stopAll(); - qDeleteAll(pluginSpecs); - if (!allObjects.isEmpty()) { - qDebug() << "There are" << allObjects.size() << "objects left in the plugin manager pool: " << allObjects; - } -} - -void PluginManagerPrivate::stopAll() -{ - QList queue = loadQueue(); - foreach (PluginSpec *spec, queue) { - loadPlugin(spec, PluginSpec::Stopped); - } - QListIterator it(queue); - it.toBack(); - while (it.hasPrevious()) { - loadPlugin(it.previous(), PluginSpec::Deleted); - } -} - -/*! - \fn void PluginManagerPrivate::addObject(QObject *obj) - \internal -*/ -void PluginManagerPrivate::addObject(QObject *obj) -{ - { - QWriteLocker lock(&(q->m_lock)); - if (obj == 0) { - qWarning() << "PluginManagerPrivate::addObject(): trying to add null object"; - return; - } - if (allObjects.contains(obj)) { - qWarning() << "PluginManagerPrivate::addObject(): trying to add duplicate object"; - return; - } - - if (debugLeaks) - qDebug() << "PluginManagerPrivate::addObject" << obj << obj->objectName(); - - allObjects.append(obj); - } - emit q->objectAdded(obj); -} - -/*! - \fn void PluginManagerPrivate::removeObject(QObject *obj) - \internal -*/ -void PluginManagerPrivate::removeObject(QObject *obj) -{ - if (obj == 0) { - qWarning() << "PluginManagerPrivate::removeObject(): trying to remove null object"; - return; - } - - if (!allObjects.contains(obj)) { - qWarning() << "PluginManagerPrivate::removeObject(): object not in list:" - << obj << obj->objectName(); - return; - } - if (debugLeaks) - qDebug() << "PluginManagerPrivate::removeObject" << obj << obj->objectName(); - - emit q->aboutToRemoveObject(obj); - QWriteLocker lock(&(q->m_lock)); - allObjects.removeAll(obj); -} - -/*! - \fn void PluginManagerPrivate::loadPlugins() - \internal -*/ -void PluginManagerPrivate::loadPlugins() -{ - QList queue = loadQueue(); - foreach (PluginSpec *spec, queue) { - loadPlugin(spec, PluginSpec::Loaded); - } - foreach (PluginSpec *spec, queue) { - loadPlugin(spec, PluginSpec::Initialized); - } - QListIterator it(queue); - it.toBack(); - while (it.hasPrevious()) { - PluginSpec* plugin = it.previous(); - emit q->pluginAboutToBeLoaded(plugin); - loadPlugin(plugin, PluginSpec::Running); - } - emit q->pluginsChanged(); - q->m_allPluginsLoaded=true; - emit q->pluginsLoadEnded(); -} - -/*! - \fn void PluginManagerPrivate::loadQueue() - \internal -*/ -QList PluginManagerPrivate::loadQueue() -{ - QList queue; - foreach (PluginSpec *spec, pluginSpecs) { - QList circularityCheckQueue; - loadQueue(spec, queue, circularityCheckQueue); - } - return queue; -} - -/*! - \fn bool PluginManagerPrivate::loadQueue(PluginSpec *spec, QList &queue, QList &circularityCheckQueue) - \internal -*/ -bool PluginManagerPrivate::loadQueue(PluginSpec *spec, QList &queue, - QList &circularityCheckQueue) -{ - if (queue.contains(spec)) - return true; - // check for circular dependencies - if (circularityCheckQueue.contains(spec)) { - spec->d->hasError = true; - spec->d->errorString = PluginManager::tr("Circular dependency detected:\n"); - int index = circularityCheckQueue.indexOf(spec); - for (int i = index; i < circularityCheckQueue.size(); ++i) { - spec->d->errorString.append(PluginManager::tr("%1(%2) depends on\n") - .arg(circularityCheckQueue.at(i)->name()).arg(circularityCheckQueue.at(i)->version())); - } - spec->d->errorString.append(PluginManager::tr("%1(%2)").arg(spec->name()).arg(spec->version())); - return false; - } - circularityCheckQueue.append(spec); - // check if we have the dependencies - if (spec->state() == PluginSpec::Invalid || spec->state() == PluginSpec::Read) { - spec->d->hasError = true; - spec->d->errorString += "\n"; - spec->d->errorString += PluginManager::tr("Cannot load plugin because dependencies are not resolved"); - return false; - } - // add dependencies - foreach (PluginSpec *depSpec, spec->dependencySpecs()) { - if (!loadQueue(depSpec, queue, circularityCheckQueue)) { - spec->d->hasError = true; - spec->d->errorString = - PluginManager::tr("Cannot load plugin because dependency failed to load: %1(%2)\nReason: %3") - .arg(depSpec->name()).arg(depSpec->version()).arg(depSpec->errorString()); - return false; - } - } - // add self - queue.append(spec); - return true; -} - -/*! - \fn void PluginManagerPrivate::loadPlugin(PluginSpec *spec, PluginSpec::State destState) - \internal -*/ -void PluginManagerPrivate::loadPlugin(PluginSpec *spec, PluginSpec::State destState) -{ - if (spec->hasError()) - return; - if (destState == PluginSpec::Running) { - spec->d->initializeExtensions(); - return; - } else if (destState == PluginSpec::Deleted) { - spec->d->kill(); - return; - } - foreach (PluginSpec *depSpec, spec->dependencySpecs()) { - if (depSpec->state() != destState) { - spec->d->hasError = true; - spec->d->errorString = - PluginManager::tr("Cannot load plugin because dependency failed to load: %1(%2)\nReason: %3") - .arg(depSpec->name()).arg(depSpec->version()).arg(depSpec->errorString()); - return; - } - } - if (destState == PluginSpec::Loaded) - spec->d->loadLibrary(); - else if (destState == PluginSpec::Initialized) - spec->d->initializePlugin(); - else if (destState == PluginSpec::Stopped) - spec->d->stop(); -} - -/*! - \fn void PluginManagerPrivate::setPluginPaths(const QStringList &paths) - \internal -*/ -void PluginManagerPrivate::setPluginPaths(const QStringList &paths) -{ - pluginPaths = paths; - readPluginPaths(); -} - -/*! - \fn void PluginManagerPrivate::readPluginPaths() - \internal -*/ -void PluginManagerPrivate::readPluginPaths() -{ - qDeleteAll(pluginSpecs); - pluginSpecs.clear(); - - QStringList specFiles; - QStringList searchPaths = pluginPaths; - while (!searchPaths.isEmpty()) { - const QDir dir(searchPaths.takeFirst()); - const QFileInfoList files = dir.entryInfoList(QStringList() << QString("*.%1").arg(extension), QDir::Files); - foreach (const QFileInfo &file, files) - specFiles << file.absoluteFilePath(); - const QFileInfoList dirs = dir.entryInfoList(QDir::Dirs|QDir::NoDotAndDotDot); - foreach (const QFileInfo &subdir, dirs) - searchPaths << subdir.absoluteFilePath(); - } - foreach (const QString &specFile, specFiles) { - PluginSpec *spec = new PluginSpec; - spec->d->read(specFile); - pluginSpecs.append(spec); - } - resolveDependencies(); - // ensure deterministic plugin load order by sorting - qSort(pluginSpecs.begin(), pluginSpecs.end(), lessThanByPluginName); - emit q->pluginsChanged(); -} - -void PluginManagerPrivate::resolveDependencies() -{ - foreach (PluginSpec *spec, pluginSpecs) { - spec->d->resolveDependencies(pluginSpecs); - } -} - - // Look in argument descriptions of the specs for the option. -PluginSpec *PluginManagerPrivate::pluginForOption(const QString &option, bool *requiresArgument) const -{ - // Look in the plugins for an option - typedef PluginSpec::PluginArgumentDescriptions PluginArgumentDescriptions; - - *requiresArgument = false; - const PluginSpecSet::const_iterator pcend = pluginSpecs.constEnd(); - for (PluginSpecSet::const_iterator pit = pluginSpecs.constBegin(); pit != pcend; ++pit) { - PluginSpec *ps = *pit; - const PluginArgumentDescriptions pargs = ps->argumentDescriptions(); - if (!pargs.empty()) { - const PluginArgumentDescriptions::const_iterator acend = pargs.constEnd(); - for (PluginArgumentDescriptions::const_iterator ait = pargs.constBegin(); ait != acend; ++ait) { - if (ait->name == option) { - *requiresArgument = !ait->parameter.isEmpty(); - return ps; - } - } - } - } - return 0; -} - -PluginSpec *PluginManagerPrivate::pluginByName(const QString &name) const -{ - foreach (PluginSpec *spec, pluginSpecs) - if (spec->name() == name) - return spec; - return 0; -} - +/** + ****************************************************************************** + * + * @file pluginmanager.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009. + * @brief + * @see The GNU Public License (GPL) Version 3 + * @defgroup + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pluginmanager.h" +#include "pluginmanager_p.h" +#include "pluginspec.h" +#include "pluginspec_p.h" +#include "optionsparser.h" +#include "iplugin.h" + +#include +#include +#include +#include +#include +#ifdef WITH_TESTS +#include +#endif + +typedef QList PluginSpecSet; + +enum { debugLeaks = 0 }; + +/*! + \namespace ExtensionSystem + \brief The ExtensionSystem namespace provides classes that belong to the core plugin system. + + The basic extension system contains of the plugin manager and its supporting classes, + and the IPlugin interface that must be implemented by plugin providers. +*/ + +/*! + \namespace ExtensionSystem::Internal + \internal +*/ + +/*! + \class ExtensionSystem::PluginManager + \mainclass + + \brief Core plugin system that manages the plugins, their life cycle and their registered objects. + + The plugin manager is used for the following tasks: + \list + \o Manage plugins and their state + \o Manipulate a 'common object pool' + \endlist + + \section1 Plugins + Plugins consist of an xml descriptor file, and of a library that contains a Qt plugin + (declared via Q_EXPORT_PLUGIN) that must derive from the IPlugin class. + The plugin manager is used to set a list of file system directories to search for + plugins, retrieve information about the state of these plugins, and to load them. + + Usually the application creates a PluginManager instance and initiates the loading. + \code + ExtensionSystem::PluginManager *manager = new ExtensionSystem::PluginManager(); + manager->setPluginPaths(QStringList() << "plugins"); // 'plugins' and subdirs will be searched for plugins + manager->loadPlugins(); // try to load all the plugins + \endcode + Additionally it is possible to directly access to the plugin specifications + (the information in the descriptor file), and the plugin instances (via PluginSpec), + and their state. + + \section1 Object Pool + Plugins (and everybody else) can add objects to a common 'pool' that is located in + the plugin manager. Objects in the pool must derive from QObject, there are no other + prerequisites. All objects of a specified type can be retrieved from the object pool + via the getObjects() and getObject() methods. They are aware of Aggregation::Aggregate, i.e. + these methods use the Aggregation::query methods instead of a qobject_cast to determine + the matching objects. + + Whenever the state of the object pool changes a corresponding signal is emitted by the plugin manager. + + A common usecase for the object pool is that a plugin (or the application) provides + an "extension point" for other plugins, which is a class / interface that can + be implemented and added to the object pool. The plugin that provides the + extension point looks for implementations of the class / interface in the object pool. + \code + // plugin A provides a "MimeTypeHandler" extension point + // in plugin B: + MyMimeTypeHandler *handler = new MyMimeTypeHandler(); + ExtensionSystem::PluginManager::instance()->addObject(handler); + // in plugin A: + QList mimeHandlers = + ExtensionSystem::PluginManager::instance()->getObjects(); + \endcode + + \bold Note: The object pool manipulating functions are thread-safe. +*/ + +/*! + \fn void PluginManager::objectAdded(QObject *obj) + Signal that \a obj has been added to the object pool. +*/ + +/*! + \fn void PluginManager::aboutToRemoveObject(QObject *obj) + Signal that \a obj will be removed from the object pool. +*/ + +/*! + \fn void PluginManager::pluginsChanged() + Signal that the list of available plugins has changed. + + \sa plugins() +*/ + +/*! + \fn T *PluginManager::getObject() const + Retrieve the object of a given type from the object pool. + This method is aware of Aggregation::Aggregate, i.e. it uses + the Aggregation::query methods instead of qobject_cast to + determine the type of an object. + If there are more than one object of the given type in + the object pool, this method will choose an arbitrary one of them. + + \sa addObject() +*/ + +/*! + \fn QList PluginManager::getObjects() const + Retrieve all objects of a given type from the object pool. + This method is aware of Aggregation::Aggregate, i.e. it uses + the Aggregation::query methods instead of qobject_cast to + determine the type of an object. + + \sa addObject() +*/ + +using namespace ExtensionSystem; +using namespace ExtensionSystem::Internal; + +static bool lessThanByPluginName(const PluginSpec *one, const PluginSpec *two) +{ + return one->name() < two->name(); +} + +PluginManager *PluginManager::m_instance = 0; + +/*! + \fn PluginManager *PluginManager::instance() + Get the unique plugin manager instance. +*/ +PluginManager *PluginManager::instance() +{ + return m_instance; +} + +/*! + \fn PluginManager::PluginManager() + Create a plugin manager. Should be done only once per application. +*/ +PluginManager::PluginManager() + : d(new PluginManagerPrivate(this)),m_allPluginsLoaded(false) +{ + m_instance = this; +} + +/*! + \fn PluginManager::~PluginManager() + \internal +*/ +PluginManager::~PluginManager() +{ + delete d; + d = 0; +} + +/*! + \fn void PluginManager::addObject(QObject *obj) + Add the given object \a obj to the object pool, so it can be retrieved again from the pool by type. + The plugin manager does not do any memory management - added objects + must be removed from the pool and deleted manually by whoever is responsible for the object. + + Emits the objectAdded() signal. + + \sa PluginManager::removeObject() + \sa PluginManager::getObject() + \sa PluginManager::getObjects() +*/ +void PluginManager::addObject(QObject *obj) +{ + d->addObject(obj); +} + +/*! + \fn void PluginManager::removeObject(QObject *obj) + Emits aboutToRemoveObject() and removes the object \a obj from the object pool. + \sa PluginManager::addObject() +*/ +void PluginManager::removeObject(QObject *obj) +{ + d->removeObject(obj); +} + +/*! + \fn QList PluginManager::allObjects() const + Retrieve the list of all objects in the pool, unfiltered. + Usually clients do not need to call this. + \sa PluginManager::getObject() + \sa PluginManager::getObjects() +*/ +QList PluginManager::allObjects() const +{ + return d->allObjects; +} + +/*! + \fn void PluginManager::loadPlugins() + Tries to load all the plugins that were previously found when + setting the plugin search paths. The plugin specs of the plugins + can be used to retrieve error and state information about individual plugins. + + \sa setPluginPaths() + \sa plugins() +*/ +void PluginManager::loadPlugins() +{ + return d->loadPlugins(); +} + +/*! + \fn QStringList PluginManager::pluginPaths() const + The list of paths were the plugin manager searches for plugins. + + \sa setPluginPaths() +*/ +QStringList PluginManager::pluginPaths() const +{ + return d->pluginPaths; +} + +/*! + \fn void PluginManager::setPluginPaths(const QStringList &paths) + Sets the plugin search paths, i.e. the file system paths where the plugin manager + looks for plugin descriptions. All given \a paths and their sub directory trees + are searched for plugin xml description files. + + \sa pluginPaths() + \sa loadPlugins() +*/ +void PluginManager::setPluginPaths(const QStringList &paths) +{ + d->setPluginPaths(paths); +} + +/*! + \fn QString PluginManager::fileExtension() const + The file extension of plugin description files. + The default is "xml". + + \sa setFileExtension() +*/ +QString PluginManager::fileExtension() const +{ + return d->extension; +} + +/*! + \fn void PluginManager::setFileExtension(const QString &extension) + Sets the file extension of plugin description files. + The default is "xml". + At the moment this must be called before setPluginPaths() is called. + // ### TODO let this + setPluginPaths read the plugin specs lazyly whenever loadPlugins() or plugins() is called. +*/ +void PluginManager::setFileExtension(const QString &extension) +{ + d->extension = extension; +} + +/*! + \fn QStringList PluginManager::arguments() const + The arguments left over after parsing (Neither startup nor plugin + arguments). Typically, this will be the list of files to open. +*/ +QStringList PluginManager::arguments() const +{ + return d->arguments; +} + +/*! + \fn QList PluginManager::plugins() const + List of all plugin specifications that have been found in the plugin search paths. + This list is valid directly after the setPluginPaths() call. + The plugin specifications contain the information from the plugins' xml description files + and the current state of the plugins. If a plugin's library has been already successfully loaded, + the plugin specification has a reference to the created plugin instance as well. + + \sa setPluginPaths() +*/ +QList PluginManager::plugins() const +{ + return d->pluginSpecs; +} + +/*! + \fn bool PluginManager::parseOptions(const QStringList &args, const QMap &appOptions, QMap *foundAppOptions, QString *errorString) + Takes the list of command line options in \a args and parses them. + The plugin manager itself might process some options itself directly (-noload ), and + adds options that are registered by plugins to their plugin specs. + The caller (the application) may register itself for options via the \a appOptions list, containing pairs + of "option string" and a bool that indicates if the option requires an argument. + Application options always override any plugin's options. + + \a foundAppOptions is set to pairs of ("option string", "argument") for any application options that were found. + The command line options that were not processed can be retrieved via the arguments() method. + If an error occurred (like missing argument for an option that requires one), \a errorString contains + a descriptive message of the error. + + Returns if there was an error. + */ +bool PluginManager::parseOptions(const QStringList &args, + const QMap &appOptions, + QMap *foundAppOptions, + QString *errorString) +{ + OptionsParser options(args, appOptions, foundAppOptions, errorString, d); + return options.parse(); +} + + + +static inline void indent(QTextStream &str, int indent) +{ + const QChar blank = QLatin1Char(' '); + for (int i = 0 ; i < indent; i++) + str << blank; +} + +static inline void formatOption(QTextStream &str, + const QString &opt, const QString &parm, const QString &description, + int optionIndentation, int descriptionIndentation) +{ + int remainingIndent = descriptionIndentation - optionIndentation - opt.size(); + indent(str, optionIndentation); + str << opt; + if (!parm.isEmpty()) { + str << " <" << parm << '>'; + remainingIndent -= 3 + parm.size(); + } + indent(str, qMax(0, remainingIndent)); + str << description << '\n'; +} + +/*! + \fn static PluginManager::formatOptions(QTextStream &str, int optionIndentation, int descriptionIndentation) + + Format the startup options of the plugin manager for command line help. +*/ + +void PluginManager::formatOptions(QTextStream &str, int optionIndentation, int descriptionIndentation) +{ + formatOption(str, QLatin1String(OptionsParser::NO_LOAD_OPTION), + QLatin1String("plugin"), QLatin1String("Do not load "), + optionIndentation, descriptionIndentation); +} + +/*! + \fn PluginManager::formatPluginOptions(QTextStream &str, int optionIndentation, int descriptionIndentation) const + + Format the plugin options of the plugin specs for command line help. +*/ + +void PluginManager::formatPluginOptions(QTextStream &str, int optionIndentation, int descriptionIndentation) const +{ + typedef PluginSpec::PluginArgumentDescriptions PluginArgumentDescriptions; + // Check plugins for options + const PluginSpecSet::const_iterator pcend = d->pluginSpecs.constEnd(); + for (PluginSpecSet::const_iterator pit = d->pluginSpecs.constBegin(); pit != pcend; ++pit) { + const PluginArgumentDescriptions pargs = (*pit)->argumentDescriptions(); + if (!pargs.empty()) { + str << "\nPlugin: " << (*pit)->name() << '\n'; + const PluginArgumentDescriptions::const_iterator acend = pargs.constEnd(); + for (PluginArgumentDescriptions::const_iterator ait =pargs.constBegin(); ait != acend; ++ait) + formatOption(str, ait->name, ait->parameter, ait->description, optionIndentation, descriptionIndentation); + } + } +} + +/*! + \fn PluginManager::formatPluginVersions(QTextStream &str) const + + Format the version of the plugin specs for command line help. +*/ + +void PluginManager::formatPluginVersions(QTextStream &str) const +{ + const PluginSpecSet::const_iterator cend = d->pluginSpecs.constEnd(); + for (PluginSpecSet::const_iterator it = d->pluginSpecs.constBegin(); it != cend; ++it) { + const PluginSpec *ps = *it; + str << " " << ps->name() << ' ' << ps->version() << ' ' << ps->description() << '\n'; + } +} + +void PluginManager::startTests() +{ +#ifdef WITH_TESTS + foreach (PluginSpec *pluginSpec, d->testSpecs) { + const QMetaObject *mo = pluginSpec->plugin()->metaObject(); + QStringList methods; + methods.append("arg0"); + // We only want slots starting with "test" + for (int i = mo->methodOffset(); i < mo->methodCount(); ++i) { + if (QByteArray(mo->method(i).signature()).startsWith("test")) { + QString method = QString::fromLatin1(mo->method(i).signature()); + methods.append(method.left(method.size()-2)); + } + } + QTest::qExec(pluginSpec->plugin(), methods); + + } +#endif +} + +/*! + * \fn bool PluginManager::runningTests() const + * \internal + */ +bool PluginManager::runningTests() const +{ + return !d->testSpecs.isEmpty(); +} + +/*! + * \fn QString PluginManager::testDataDirectory() const + * \internal + */ +QString PluginManager::testDataDirectory() const +{ + QByteArray ba = qgetenv("QTCREATOR_TEST_DIR"); + QString s = QString::fromLocal8Bit(ba.constData(), ba.size()); + if (s.isEmpty()) { + s = GCS_TEST_DIR; + s.append("/tests"); + } + s = QDir::cleanPath(s); + return s; +} + +//============PluginManagerPrivate=========== + +/*! + \fn PluginSpec *PluginManagerPrivate::createSpec() + \internal +*/ +PluginSpec *PluginManagerPrivate::createSpec() +{ + return new PluginSpec(); +} + +/*! + \fn PluginSpecPrivate *PluginManagerPrivate::privateSpec(PluginSpec *spec) + \internal +*/ +PluginSpecPrivate *PluginManagerPrivate::privateSpec(PluginSpec *spec) +{ + return spec->d; +} + +/*! + \fn PluginManagerPrivate::PluginManagerPrivate(PluginManager *pluginManager) + \internal +*/ +PluginManagerPrivate::PluginManagerPrivate(PluginManager *pluginManager) + : extension("xml"), q(pluginManager) +{ +} + +/*! + \fn PluginManagerPrivate::~PluginManagerPrivate() + \internal +*/ +PluginManagerPrivate::~PluginManagerPrivate() +{ + stopAll(); + qDeleteAll(pluginSpecs); + if (!allObjects.isEmpty()) { + qDebug() << "There are" << allObjects.size() << "objects left in the plugin manager pool: " << allObjects; + } +} + +void PluginManagerPrivate::stopAll() +{ + QList queue = loadQueue(); + foreach (PluginSpec *spec, queue) { + loadPlugin(spec, PluginSpec::Stopped); + } + QListIterator it(queue); + it.toBack(); + while (it.hasPrevious()) { + loadPlugin(it.previous(), PluginSpec::Deleted); + } +} + +/*! + \fn void PluginManagerPrivate::addObject(QObject *obj) + \internal +*/ +void PluginManagerPrivate::addObject(QObject *obj) +{ + { + QWriteLocker lock(&(q->m_lock)); + if (obj == 0) { + qWarning() << "PluginManagerPrivate::addObject(): trying to add null object"; + return; + } + if (allObjects.contains(obj)) { + qWarning() << "PluginManagerPrivate::addObject(): trying to add duplicate object"; + return; + } + + if (debugLeaks) + qDebug() << "PluginManagerPrivate::addObject" << obj << obj->objectName(); + + allObjects.append(obj); + } + emit q->objectAdded(obj); +} + +/*! + \fn void PluginManagerPrivate::removeObject(QObject *obj) + \internal +*/ +void PluginManagerPrivate::removeObject(QObject *obj) +{ + if (obj == 0) { + qWarning() << "PluginManagerPrivate::removeObject(): trying to remove null object"; + return; + } + + if (!allObjects.contains(obj)) { + qWarning() << "PluginManagerPrivate::removeObject(): object not in list:" + << obj << obj->objectName(); + return; + } + if (debugLeaks) + qDebug() << "PluginManagerPrivate::removeObject" << obj << obj->objectName(); + + emit q->aboutToRemoveObject(obj); + QWriteLocker lock(&(q->m_lock)); + allObjects.removeAll(obj); +} + +/*! + \fn void PluginManagerPrivate::loadPlugins() + \internal +*/ +void PluginManagerPrivate::loadPlugins() +{ + QList queue = loadQueue(); + foreach (PluginSpec *spec, queue) { + loadPlugin(spec, PluginSpec::Loaded); + } + foreach (PluginSpec *spec, queue) { + loadPlugin(spec, PluginSpec::Initialized); + } + QListIterator it(queue); + it.toBack(); + while (it.hasPrevious()) { + PluginSpec* plugin = it.previous(); + emit q->pluginAboutToBeLoaded(plugin); + loadPlugin(plugin, PluginSpec::Running); + } + emit q->pluginsChanged(); + q->m_allPluginsLoaded=true; + emit q->pluginsLoadEnded(); +} + +/*! + \fn void PluginManagerPrivate::loadQueue() + \internal +*/ +QList PluginManagerPrivate::loadQueue() +{ + QList queue; + foreach (PluginSpec *spec, pluginSpecs) { + QList circularityCheckQueue; + loadQueue(spec, queue, circularityCheckQueue); + } + return queue; +} + +/*! + \fn bool PluginManagerPrivate::loadQueue(PluginSpec *spec, QList &queue, QList &circularityCheckQueue) + \internal +*/ +bool PluginManagerPrivate::loadQueue(PluginSpec *spec, QList &queue, + QList &circularityCheckQueue) +{ + if (queue.contains(spec)) + return true; + // check for circular dependencies + if (circularityCheckQueue.contains(spec)) { + spec->d->hasError = true; + spec->d->errorString = PluginManager::tr("Circular dependency detected:\n"); + int index = circularityCheckQueue.indexOf(spec); + for (int i = index; i < circularityCheckQueue.size(); ++i) { + spec->d->errorString.append(PluginManager::tr("%1(%2) depends on\n") + .arg(circularityCheckQueue.at(i)->name()).arg(circularityCheckQueue.at(i)->version())); + } + spec->d->errorString.append(PluginManager::tr("%1(%2)").arg(spec->name()).arg(spec->version())); + return false; + } + circularityCheckQueue.append(spec); + // check if we have the dependencies + if (spec->state() == PluginSpec::Invalid || spec->state() == PluginSpec::Read) { + spec->d->hasError = true; + spec->d->errorString += "\n"; + spec->d->errorString += PluginManager::tr("Cannot load plugin because dependencies are not resolved"); + return false; + } + // add dependencies + foreach (PluginSpec *depSpec, spec->dependencySpecs()) { + if (!loadQueue(depSpec, queue, circularityCheckQueue)) { + spec->d->hasError = true; + spec->d->errorString = + PluginManager::tr("Cannot load plugin because dependency failed to load: %1(%2)\nReason: %3") + .arg(depSpec->name()).arg(depSpec->version()).arg(depSpec->errorString()); + return false; + } + } + // add self + queue.append(spec); + return true; +} + +/*! + \fn void PluginManagerPrivate::loadPlugin(PluginSpec *spec, PluginSpec::State destState) + \internal +*/ +void PluginManagerPrivate::loadPlugin(PluginSpec *spec, PluginSpec::State destState) +{ + if (spec->hasError()) + return; + if (destState == PluginSpec::Running) { + spec->d->initializeExtensions(); + return; + } else if (destState == PluginSpec::Deleted) { + spec->d->kill(); + return; + } + foreach (PluginSpec *depSpec, spec->dependencySpecs()) { + if (depSpec->state() != destState) { + spec->d->hasError = true; + spec->d->errorString = + PluginManager::tr("Cannot load plugin because dependency failed to load: %1(%2)\nReason: %3") + .arg(depSpec->name()).arg(depSpec->version()).arg(depSpec->errorString()); + return; + } + } + if (destState == PluginSpec::Loaded) + spec->d->loadLibrary(); + else if (destState == PluginSpec::Initialized) + spec->d->initializePlugin(); + else if (destState == PluginSpec::Stopped) + spec->d->stop(); +} + +/*! + \fn void PluginManagerPrivate::setPluginPaths(const QStringList &paths) + \internal +*/ +void PluginManagerPrivate::setPluginPaths(const QStringList &paths) +{ + pluginPaths = paths; + readPluginPaths(); +} + +/*! + \fn void PluginManagerPrivate::readPluginPaths() + \internal +*/ +void PluginManagerPrivate::readPluginPaths() +{ + qDeleteAll(pluginSpecs); + pluginSpecs.clear(); + + QStringList specFiles; + QStringList searchPaths = pluginPaths; + while (!searchPaths.isEmpty()) { + const QDir dir(searchPaths.takeFirst()); + const QFileInfoList files = dir.entryInfoList(QStringList() << QString("*.%1").arg(extension), QDir::Files); + foreach (const QFileInfo &file, files) + specFiles << file.absoluteFilePath(); + const QFileInfoList dirs = dir.entryInfoList(QDir::Dirs|QDir::NoDotAndDotDot); + foreach (const QFileInfo &subdir, dirs) + searchPaths << subdir.absoluteFilePath(); + } + foreach (const QString &specFile, specFiles) { + PluginSpec *spec = new PluginSpec; + spec->d->read(specFile); + pluginSpecs.append(spec); + } + resolveDependencies(); + // ensure deterministic plugin load order by sorting + qSort(pluginSpecs.begin(), pluginSpecs.end(), lessThanByPluginName); + emit q->pluginsChanged(); +} + +void PluginManagerPrivate::resolveDependencies() +{ + foreach (PluginSpec *spec, pluginSpecs) { + spec->d->resolveDependencies(pluginSpecs); + } +} + + // Look in argument descriptions of the specs for the option. +PluginSpec *PluginManagerPrivate::pluginForOption(const QString &option, bool *requiresArgument) const +{ + // Look in the plugins for an option + typedef PluginSpec::PluginArgumentDescriptions PluginArgumentDescriptions; + + *requiresArgument = false; + const PluginSpecSet::const_iterator pcend = pluginSpecs.constEnd(); + for (PluginSpecSet::const_iterator pit = pluginSpecs.constBegin(); pit != pcend; ++pit) { + PluginSpec *ps = *pit; + const PluginArgumentDescriptions pargs = ps->argumentDescriptions(); + if (!pargs.empty()) { + const PluginArgumentDescriptions::const_iterator acend = pargs.constEnd(); + for (PluginArgumentDescriptions::const_iterator ait = pargs.constBegin(); ait != acend; ++ait) { + if (ait->name == option) { + *requiresArgument = !ait->parameter.isEmpty(); + return ps; + } + } + } + } + return 0; +} + +PluginSpec *PluginManagerPrivate::pluginByName(const QString &name) const +{ + foreach (PluginSpec *spec, pluginSpecs) + if (spec->name() == name) + return spec; + return 0; +} + diff --git a/ground/openpilotgcs/src/libs/extensionsystem/pluginview.ui b/ground/openpilotgcs/src/libs/extensionsystem/pluginview.ui index 1ba739541..e48785255 100644 --- a/ground/openpilotgcs/src/libs/extensionsystem/pluginview.ui +++ b/ground/openpilotgcs/src/libs/extensionsystem/pluginview.ui @@ -1,71 +1,71 @@ - - - ExtensionSystem::Internal::PluginView - - - - 0 - 0 - 773 - 304 - - - - - 2 - - - - - true - - - 0 - - - false - - - true - - - false - - - true - - - 5 - - - - State - - - - - Name - - - - - Version - - - - - Developer - - - - - Location - - - - - - - - - + + + ExtensionSystem::Internal::PluginView + + + + 0 + 0 + 773 + 304 + + + + + 2 + + + + + true + + + 0 + + + false + + + true + + + false + + + true + + + 5 + + + + State + + + + + Name + + + + + Version + + + + + Developer + + + + + Location + + + + + + + + + diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/adler32.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/adler32.c index f201d6701..007ba2627 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/adler32.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/adler32.c @@ -1,149 +1,149 @@ -/* adler32.c -- compute the Adler-32 checksum of a data stream - * Copyright (C) 1995-2004 Mark Adler - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* @(#) $Id$ */ - -#define ZLIB_INTERNAL -#include "zlib.h" - -#define BASE 65521UL /* largest prime smaller than 65536 */ -#define NMAX 5552 -/* NMAX is the largest n such that 255n(n+1)/2 + (n+1)(BASE-1) <= 2^32-1 */ - -#define DO1(buf,i) {adler += (buf)[i]; sum2 += adler;} -#define DO2(buf,i) DO1(buf,i); DO1(buf,i+1); -#define DO4(buf,i) DO2(buf,i); DO2(buf,i+2); -#define DO8(buf,i) DO4(buf,i); DO4(buf,i+4); -#define DO16(buf) DO8(buf,0); DO8(buf,8); - -/* use NO_DIVIDE if your processor does not do division in hardware */ -#ifdef NO_DIVIDE -# define MOD(a) \ - do { \ - if (a >= (BASE << 16)) a -= (BASE << 16); \ - if (a >= (BASE << 15)) a -= (BASE << 15); \ - if (a >= (BASE << 14)) a -= (BASE << 14); \ - if (a >= (BASE << 13)) a -= (BASE << 13); \ - if (a >= (BASE << 12)) a -= (BASE << 12); \ - if (a >= (BASE << 11)) a -= (BASE << 11); \ - if (a >= (BASE << 10)) a -= (BASE << 10); \ - if (a >= (BASE << 9)) a -= (BASE << 9); \ - if (a >= (BASE << 8)) a -= (BASE << 8); \ - if (a >= (BASE << 7)) a -= (BASE << 7); \ - if (a >= (BASE << 6)) a -= (BASE << 6); \ - if (a >= (BASE << 5)) a -= (BASE << 5); \ - if (a >= (BASE << 4)) a -= (BASE << 4); \ - if (a >= (BASE << 3)) a -= (BASE << 3); \ - if (a >= (BASE << 2)) a -= (BASE << 2); \ - if (a >= (BASE << 1)) a -= (BASE << 1); \ - if (a >= BASE) a -= BASE; \ - } while (0) -# define MOD4(a) \ - do { \ - if (a >= (BASE << 4)) a -= (BASE << 4); \ - if (a >= (BASE << 3)) a -= (BASE << 3); \ - if (a >= (BASE << 2)) a -= (BASE << 2); \ - if (a >= (BASE << 1)) a -= (BASE << 1); \ - if (a >= BASE) a -= BASE; \ - } while (0) -#else -# define MOD(a) a %= BASE -# define MOD4(a) a %= BASE -#endif - -/* ========================================================================= */ -uLong ZEXPORT adler32(adler, buf, len) - uLong adler; - const Bytef *buf; - uInt len; -{ - unsigned long sum2; - unsigned n; - - /* split Adler-32 into component sums */ - sum2 = (adler >> 16) & 0xffff; - adler &= 0xffff; - - /* in case user likes doing a byte at a time, keep it fast */ - if (len == 1) { - adler += buf[0]; - if (adler >= BASE) - adler -= BASE; - sum2 += adler; - if (sum2 >= BASE) - sum2 -= BASE; - return adler | (sum2 << 16); - } - - /* initial Adler-32 value (deferred check for len == 1 speed) */ - if (buf == Z_NULL) - return 1L; - - /* in case short lengths are provided, keep it somewhat fast */ - if (len < 16) { - while (len--) { - adler += *buf++; - sum2 += adler; - } - if (adler >= BASE) - adler -= BASE; - MOD4(sum2); /* only added so many BASE's */ - return adler | (sum2 << 16); - } - - /* do length NMAX blocks -- requires just one modulo operation */ - while (len >= NMAX) { - len -= NMAX; - n = NMAX / 16; /* NMAX is divisible by 16 */ - do { - DO16(buf); /* 16 sums unrolled */ - buf += 16; - } while (--n); - MOD(adler); - MOD(sum2); - } - - /* do remaining bytes (less than NMAX, still just one modulo) */ - if (len) { /* avoid modulos if none remaining */ - while (len >= 16) { - len -= 16; - DO16(buf); - buf += 16; - } - while (len--) { - adler += *buf++; - sum2 += adler; - } - MOD(adler); - MOD(sum2); - } - - /* return recombined sums */ - return adler | (sum2 << 16); -} - -/* ========================================================================= */ -uLong ZEXPORT adler32_combine(adler1, adler2, len2) - uLong adler1; - uLong adler2; - z_off_t len2; -{ - unsigned long sum1; - unsigned long sum2; - unsigned rem; - - /* the derivation of this formula is left as an exercise for the reader */ - rem = (unsigned)(len2 % BASE); - sum1 = adler1 & 0xffff; - sum2 = rem * sum1; - MOD(sum2); - sum1 += (adler2 & 0xffff) + BASE - 1; - sum2 += ((adler1 >> 16) & 0xffff) + ((adler2 >> 16) & 0xffff) + BASE - rem; - if (sum1 > BASE) sum1 -= BASE; - if (sum1 > BASE) sum1 -= BASE; - if (sum2 > (BASE << 1)) sum2 -= (BASE << 1); - if (sum2 > BASE) sum2 -= BASE; - return sum1 | (sum2 << 16); -} +/* adler32.c -- compute the Adler-32 checksum of a data stream + * Copyright (C) 1995-2004 Mark Adler + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* @(#) $Id$ */ + +#define ZLIB_INTERNAL +#include "zlib.h" + +#define BASE 65521UL /* largest prime smaller than 65536 */ +#define NMAX 5552 +/* NMAX is the largest n such that 255n(n+1)/2 + (n+1)(BASE-1) <= 2^32-1 */ + +#define DO1(buf,i) {adler += (buf)[i]; sum2 += adler;} +#define DO2(buf,i) DO1(buf,i); DO1(buf,i+1); +#define DO4(buf,i) DO2(buf,i); DO2(buf,i+2); +#define DO8(buf,i) DO4(buf,i); DO4(buf,i+4); +#define DO16(buf) DO8(buf,0); DO8(buf,8); + +/* use NO_DIVIDE if your processor does not do division in hardware */ +#ifdef NO_DIVIDE +# define MOD(a) \ + do { \ + if (a >= (BASE << 16)) a -= (BASE << 16); \ + if (a >= (BASE << 15)) a -= (BASE << 15); \ + if (a >= (BASE << 14)) a -= (BASE << 14); \ + if (a >= (BASE << 13)) a -= (BASE << 13); \ + if (a >= (BASE << 12)) a -= (BASE << 12); \ + if (a >= (BASE << 11)) a -= (BASE << 11); \ + if (a >= (BASE << 10)) a -= (BASE << 10); \ + if (a >= (BASE << 9)) a -= (BASE << 9); \ + if (a >= (BASE << 8)) a -= (BASE << 8); \ + if (a >= (BASE << 7)) a -= (BASE << 7); \ + if (a >= (BASE << 6)) a -= (BASE << 6); \ + if (a >= (BASE << 5)) a -= (BASE << 5); \ + if (a >= (BASE << 4)) a -= (BASE << 4); \ + if (a >= (BASE << 3)) a -= (BASE << 3); \ + if (a >= (BASE << 2)) a -= (BASE << 2); \ + if (a >= (BASE << 1)) a -= (BASE << 1); \ + if (a >= BASE) a -= BASE; \ + } while (0) +# define MOD4(a) \ + do { \ + if (a >= (BASE << 4)) a -= (BASE << 4); \ + if (a >= (BASE << 3)) a -= (BASE << 3); \ + if (a >= (BASE << 2)) a -= (BASE << 2); \ + if (a >= (BASE << 1)) a -= (BASE << 1); \ + if (a >= BASE) a -= BASE; \ + } while (0) +#else +# define MOD(a) a %= BASE +# define MOD4(a) a %= BASE +#endif + +/* ========================================================================= */ +uLong ZEXPORT adler32(adler, buf, len) + uLong adler; + const Bytef *buf; + uInt len; +{ + unsigned long sum2; + unsigned n; + + /* split Adler-32 into component sums */ + sum2 = (adler >> 16) & 0xffff; + adler &= 0xffff; + + /* in case user likes doing a byte at a time, keep it fast */ + if (len == 1) { + adler += buf[0]; + if (adler >= BASE) + adler -= BASE; + sum2 += adler; + if (sum2 >= BASE) + sum2 -= BASE; + return adler | (sum2 << 16); + } + + /* initial Adler-32 value (deferred check for len == 1 speed) */ + if (buf == Z_NULL) + return 1L; + + /* in case short lengths are provided, keep it somewhat fast */ + if (len < 16) { + while (len--) { + adler += *buf++; + sum2 += adler; + } + if (adler >= BASE) + adler -= BASE; + MOD4(sum2); /* only added so many BASE's */ + return adler | (sum2 << 16); + } + + /* do length NMAX blocks -- requires just one modulo operation */ + while (len >= NMAX) { + len -= NMAX; + n = NMAX / 16; /* NMAX is divisible by 16 */ + do { + DO16(buf); /* 16 sums unrolled */ + buf += 16; + } while (--n); + MOD(adler); + MOD(sum2); + } + + /* do remaining bytes (less than NMAX, still just one modulo) */ + if (len) { /* avoid modulos if none remaining */ + while (len >= 16) { + len -= 16; + DO16(buf); + buf += 16; + } + while (len--) { + adler += *buf++; + sum2 += adler; + } + MOD(adler); + MOD(sum2); + } + + /* return recombined sums */ + return adler | (sum2 << 16); +} + +/* ========================================================================= */ +uLong ZEXPORT adler32_combine(adler1, adler2, len2) + uLong adler1; + uLong adler2; + z_off_t len2; +{ + unsigned long sum1; + unsigned long sum2; + unsigned rem; + + /* the derivation of this formula is left as an exercise for the reader */ + rem = (unsigned)(len2 % BASE); + sum1 = adler1 & 0xffff; + sum2 = rem * sum1; + MOD(sum2); + sum1 += (adler2 & 0xffff) + BASE - 1; + sum2 += ((adler1 >> 16) & 0xffff) + ((adler2 >> 16) & 0xffff) + BASE - rem; + if (sum1 > BASE) sum1 -= BASE; + if (sum1 > BASE) sum1 -= BASE; + if (sum2 > (BASE << 1)) sum2 -= (BASE << 1); + if (sum2 > BASE) sum2 -= BASE; + return sum1 | (sum2 << 16); +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/compress.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/compress.c index a2e865479..df8013419 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/compress.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/compress.c @@ -1,79 +1,79 @@ -/* compress.c -- compress a memory buffer - * Copyright (C) 1995-2003 Jean-loup Gailly. - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* @(#) $Id$ */ - -#define ZLIB_INTERNAL -#include "zlib.h" - -/* =========================================================================== - Compresses the source buffer into the destination buffer. The level - parameter has the same meaning as in deflateInit. sourceLen is the byte - length of the source buffer. Upon entry, destLen is the total size of the - destination buffer, which must be at least 0.1% larger than sourceLen plus - 12 bytes. Upon exit, destLen is the actual size of the compressed buffer. - - compress2 returns Z_OK if success, Z_MEM_ERROR if there was not enough - memory, Z_BUF_ERROR if there was not enough room in the output buffer, - Z_STREAM_ERROR if the level parameter is invalid. -*/ -int ZEXPORT compress2 (dest, destLen, source, sourceLen, level) - Bytef *dest; - uLongf *destLen; - const Bytef *source; - uLong sourceLen; - int level; -{ - z_stream stream; - int err; - - stream.next_in = (Bytef*)source; - stream.avail_in = (uInt)sourceLen; -#ifdef MAXSEG_64K - /* Check for source > 64K on 16-bit machine: */ - if ((uLong)stream.avail_in != sourceLen) return Z_BUF_ERROR; -#endif - stream.next_out = dest; - stream.avail_out = (uInt)*destLen; - if ((uLong)stream.avail_out != *destLen) return Z_BUF_ERROR; - - stream.zalloc = (alloc_func)0; - stream.zfree = (free_func)0; - stream.opaque = (voidpf)0; - - err = deflateInit(&stream, level); - if (err != Z_OK) return err; - - err = deflate(&stream, Z_FINISH); - if (err != Z_STREAM_END) { - deflateEnd(&stream); - return err == Z_OK ? Z_BUF_ERROR : err; - } - *destLen = stream.total_out; - - err = deflateEnd(&stream); - return err; -} - -/* =========================================================================== - */ -int Q_ZEXPORT compress (dest, destLen, source, sourceLen) - Bytef *dest; - uLongf *destLen; - const Bytef *source; - uLong sourceLen; -{ - return compress2(dest, destLen, source, sourceLen, Z_DEFAULT_COMPRESSION); -} - -/* =========================================================================== - If the default memLevel or windowBits for deflateInit() is changed, then - this function needs to be updated. - */ -uLong ZEXPORT compressBound (sourceLen) - uLong sourceLen; -{ - return sourceLen + (sourceLen >> 12) + (sourceLen >> 14) + 11; -} +/* compress.c -- compress a memory buffer + * Copyright (C) 1995-2003 Jean-loup Gailly. + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* @(#) $Id$ */ + +#define ZLIB_INTERNAL +#include "zlib.h" + +/* =========================================================================== + Compresses the source buffer into the destination buffer. The level + parameter has the same meaning as in deflateInit. sourceLen is the byte + length of the source buffer. Upon entry, destLen is the total size of the + destination buffer, which must be at least 0.1% larger than sourceLen plus + 12 bytes. Upon exit, destLen is the actual size of the compressed buffer. + + compress2 returns Z_OK if success, Z_MEM_ERROR if there was not enough + memory, Z_BUF_ERROR if there was not enough room in the output buffer, + Z_STREAM_ERROR if the level parameter is invalid. +*/ +int ZEXPORT compress2 (dest, destLen, source, sourceLen, level) + Bytef *dest; + uLongf *destLen; + const Bytef *source; + uLong sourceLen; + int level; +{ + z_stream stream; + int err; + + stream.next_in = (Bytef*)source; + stream.avail_in = (uInt)sourceLen; +#ifdef MAXSEG_64K + /* Check for source > 64K on 16-bit machine: */ + if ((uLong)stream.avail_in != sourceLen) return Z_BUF_ERROR; +#endif + stream.next_out = dest; + stream.avail_out = (uInt)*destLen; + if ((uLong)stream.avail_out != *destLen) return Z_BUF_ERROR; + + stream.zalloc = (alloc_func)0; + stream.zfree = (free_func)0; + stream.opaque = (voidpf)0; + + err = deflateInit(&stream, level); + if (err != Z_OK) return err; + + err = deflate(&stream, Z_FINISH); + if (err != Z_STREAM_END) { + deflateEnd(&stream); + return err == Z_OK ? Z_BUF_ERROR : err; + } + *destLen = stream.total_out; + + err = deflateEnd(&stream); + return err; +} + +/* =========================================================================== + */ +int Q_ZEXPORT compress (dest, destLen, source, sourceLen) + Bytef *dest; + uLongf *destLen; + const Bytef *source; + uLong sourceLen; +{ + return compress2(dest, destLen, source, sourceLen, Z_DEFAULT_COMPRESSION); +} + +/* =========================================================================== + If the default memLevel or windowBits for deflateInit() is changed, then + this function needs to be updated. + */ +uLong ZEXPORT compressBound (sourceLen) + uLong sourceLen; +{ + return sourceLen + (sourceLen >> 12) + (sourceLen >> 14) + 11; +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/crc32.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/crc32.c index 32814c20c..f658a9ef5 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/crc32.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/crc32.c @@ -1,423 +1,423 @@ -/* crc32.c -- compute the CRC-32 of a data stream - * Copyright (C) 1995-2005 Mark Adler - * For conditions of distribution and use, see copyright notice in zlib.h - * - * Thanks to Rodney Brown for his contribution of faster - * CRC methods: exclusive-oring 32 bits of data at a time, and pre-computing - * tables for updating the shift register in one step with three exclusive-ors - * instead of four steps with four exclusive-ors. This results in about a - * factor of two increase in speed on a Power PC G4 (PPC7455) using gcc -O3. - */ - -/* @(#) $Id$ */ - -/* - Note on the use of DYNAMIC_CRC_TABLE: there is no mutex or semaphore - protection on the static variables used to control the first-use generation - of the crc tables. Therefore, if you #define DYNAMIC_CRC_TABLE, you should - first call get_crc_table() to initialize the tables before allowing more than - one thread to use crc32(). - */ - -#ifdef MAKECRCH -# include -# ifndef DYNAMIC_CRC_TABLE -# define DYNAMIC_CRC_TABLE -# endif /* !DYNAMIC_CRC_TABLE */ -#endif /* MAKECRCH */ - -#include "zutil.h" /* for STDC and FAR definitions */ - -#define local static - -/* Find a four-byte integer type for crc32_little() and crc32_big(). */ -#ifndef NOBYFOUR -# ifdef STDC /* need ANSI C limits.h to determine sizes */ -# include -# define BYFOUR -# if (UINT_MAX == 0xffffffffUL) - typedef unsigned int u4; -# else -# if (ULONG_MAX == 0xffffffffUL) - typedef unsigned long u4; -# else -# if (USHRT_MAX == 0xffffffffUL) - typedef unsigned short u4; -# else -# undef BYFOUR /* can't find a four-byte integer type! */ -# endif -# endif -# endif -# endif /* STDC */ -#endif /* !NOBYFOUR */ - -/* Definitions for doing the crc four data bytes at a time. */ -#ifdef BYFOUR -# define REV(w) (((w)>>24)+(((w)>>8)&0xff00)+ \ - (((w)&0xff00)<<8)+(((w)&0xff)<<24)) - local unsigned long crc32_little OF((unsigned long, - const unsigned char FAR *, unsigned)); - local unsigned long crc32_big OF((unsigned long, - const unsigned char FAR *, unsigned)); -# define TBLS 8 -#else -# define TBLS 1 -#endif /* BYFOUR */ - -/* Local functions for crc concatenation */ -local unsigned long gf2_matrix_times OF((unsigned long *mat, - unsigned long vec)); -local void gf2_matrix_square OF((unsigned long *square, unsigned long *mat)); - -#ifdef DYNAMIC_CRC_TABLE - -local volatile int crc_table_empty = 1; -local unsigned long FAR crc_table[TBLS][256]; -local void make_crc_table OF((void)); -#ifdef MAKECRCH - local void write_table OF((FILE *, const unsigned long FAR *)); -#endif /* MAKECRCH */ -/* - Generate tables for a byte-wise 32-bit CRC calculation on the polynomial: - x^32+x^26+x^23+x^22+x^16+x^12+x^11+x^10+x^8+x^7+x^5+x^4+x^2+x+1. - - Polynomials over GF(2) are represented in binary, one bit per coefficient, - with the lowest powers in the most significant bit. Then adding polynomials - is just exclusive-or, and multiplying a polynomial by x is a right shift by - one. If we call the above polynomial p, and represent a byte as the - polynomial q, also with the lowest power in the most significant bit (so the - byte 0xb1 is the polynomial x^7+x^3+x+1), then the CRC is (q*x^32) mod p, - where a mod b means the remainder after dividing a by b. - - This calculation is done using the shift-register method of multiplying and - taking the remainder. The register is initialized to zero, and for each - incoming bit, x^32 is added mod p to the register if the bit is a one (where - x^32 mod p is p+x^32 = x^26+...+1), and the register is multiplied mod p by - x (which is shifting right by one and adding x^32 mod p if the bit shifted - out is a one). We start with the highest power (least significant bit) of - q and repeat for all eight bits of q. - - The first table is simply the CRC of all possible eight bit values. This is - all the information needed to generate CRCs on data a byte at a time for all - combinations of CRC register values and incoming bytes. The remaining tables - allow for word-at-a-time CRC calculation for both big-endian and little- - endian machines, where a word is four bytes. -*/ -local void make_crc_table() -{ - unsigned long c; - int n, k; - unsigned long poly; /* polynomial exclusive-or pattern */ - /* terms of polynomial defining this crc (except x^32): */ - static volatile int first = 1; /* flag to limit concurrent making */ - static const unsigned char p[] = {0,1,2,4,5,7,8,10,11,12,16,22,23,26}; - - /* See if another task is already doing this (not thread-safe, but better - than nothing -- significantly reduces duration of vulnerability in - case the advice about DYNAMIC_CRC_TABLE is ignored) */ - if (first) { - first = 0; - - /* make exclusive-or pattern from polynomial (0xedb88320UL) */ - poly = 0UL; - for (n = 0; n < sizeof(p)/sizeof(unsigned char); n++) - poly |= 1UL << (31 - p[n]); - - /* generate a crc for every 8-bit value */ - for (n = 0; n < 256; n++) { - c = (unsigned long)n; - for (k = 0; k < 8; k++) - c = c & 1 ? poly ^ (c >> 1) : c >> 1; - crc_table[0][n] = c; - } - -#ifdef BYFOUR - /* generate crc for each value followed by one, two, and three zeros, - and then the byte reversal of those as well as the first table */ - for (n = 0; n < 256; n++) { - c = crc_table[0][n]; - crc_table[4][n] = REV(c); - for (k = 1; k < 4; k++) { - c = crc_table[0][c & 0xff] ^ (c >> 8); - crc_table[k][n] = c; - crc_table[k + 4][n] = REV(c); - } - } -#endif /* BYFOUR */ - - crc_table_empty = 0; - } - else { /* not first */ - /* wait for the other guy to finish (not efficient, but rare) */ - while (crc_table_empty) - ; - } - -#ifdef MAKECRCH - /* write out CRC tables to crc32.h */ - { - FILE *out; - - out = fopen("crc32.h", "w"); - if (out == NULL) return; - fprintf(out, "/* crc32.h -- tables for rapid CRC calculation\n"); - fprintf(out, " * Generated automatically by crc32.c\n */\n\n"); - fprintf(out, "local const unsigned long FAR "); - fprintf(out, "crc_table[TBLS][256] =\n{\n {\n"); - write_table(out, crc_table[0]); -# ifdef BYFOUR - fprintf(out, "#ifdef BYFOUR\n"); - for (k = 1; k < 8; k++) { - fprintf(out, " },\n {\n"); - write_table(out, crc_table[k]); - } - fprintf(out, "#endif\n"); -# endif /* BYFOUR */ - fprintf(out, " }\n};\n"); - fclose(out); - } -#endif /* MAKECRCH */ -} - -#ifdef MAKECRCH -local void write_table(out, table) - FILE *out; - const unsigned long FAR *table; -{ - int n; - - for (n = 0; n < 256; n++) - fprintf(out, "%s0x%08lxUL%s", n % 5 ? "" : " ", table[n], - n == 255 ? "\n" : (n % 5 == 4 ? ",\n" : ", ")); -} -#endif /* MAKECRCH */ - -#else /* !DYNAMIC_CRC_TABLE */ -/* ======================================================================== - * Tables of CRC-32s of all single-byte values, made by make_crc_table(). - */ -#include "crc32.h" -#endif /* DYNAMIC_CRC_TABLE */ - -/* ========================================================================= - * This function can be used by asm versions of crc32() - */ -const unsigned long FAR * ZEXPORT get_crc_table() -{ -#ifdef DYNAMIC_CRC_TABLE - if (crc_table_empty) - make_crc_table(); -#endif /* DYNAMIC_CRC_TABLE */ - return (const unsigned long FAR *)crc_table; -} - -/* ========================================================================= */ -#define DO1 crc = crc_table[0][((int)crc ^ (*buf++)) & 0xff] ^ (crc >> 8) -#define DO8 DO1; DO1; DO1; DO1; DO1; DO1; DO1; DO1 - -/* ========================================================================= */ -unsigned long ZEXPORT crc32(crc, buf, len) - unsigned long crc; - const unsigned char FAR *buf; - unsigned len; -{ - if (buf == Z_NULL) return 0UL; - -#ifdef DYNAMIC_CRC_TABLE - if (crc_table_empty) - make_crc_table(); -#endif /* DYNAMIC_CRC_TABLE */ - -#ifdef BYFOUR - if (sizeof(void *) == sizeof(ptrdiff_t)) { - u4 endian; - - endian = 1; - if (*((unsigned char *)(&endian))) - return crc32_little(crc, buf, len); - else - return crc32_big(crc, buf, len); - } -#endif /* BYFOUR */ - crc = crc ^ 0xffffffffUL; - while (len >= 8) { - DO8; - len -= 8; - } - if (len) do { - DO1; - } while (--len); - return crc ^ 0xffffffffUL; -} - -#ifdef BYFOUR - -/* ========================================================================= */ -#define DOLIT4 c ^= *buf4++; \ - c = crc_table[3][c & 0xff] ^ crc_table[2][(c >> 8) & 0xff] ^ \ - crc_table[1][(c >> 16) & 0xff] ^ crc_table[0][c >> 24] -#define DOLIT32 DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4 - -/* ========================================================================= */ -local unsigned long crc32_little(crc, buf, len) - unsigned long crc; - const unsigned char FAR *buf; - unsigned len; -{ - register u4 c; - register const u4 FAR *buf4; - - c = (u4)crc; - c = ~c; - while (len && ((ptrdiff_t)buf & 3)) { - c = crc_table[0][(c ^ *buf++) & 0xff] ^ (c >> 8); - len--; - } - - buf4 = (const u4 FAR *)(const void FAR *)buf; - while (len >= 32) { - DOLIT32; - len -= 32; - } - while (len >= 4) { - DOLIT4; - len -= 4; - } - buf = (const unsigned char FAR *)buf4; - - if (len) do { - c = crc_table[0][(c ^ *buf++) & 0xff] ^ (c >> 8); - } while (--len); - c = ~c; - return (unsigned long)c; -} - -/* ========================================================================= */ -#define DOBIG4 c ^= *++buf4; \ - c = crc_table[4][c & 0xff] ^ crc_table[5][(c >> 8) & 0xff] ^ \ - crc_table[6][(c >> 16) & 0xff] ^ crc_table[7][c >> 24] -#define DOBIG32 DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4 - -/* ========================================================================= */ -local unsigned long crc32_big(crc, buf, len) - unsigned long crc; - const unsigned char FAR *buf; - unsigned len; -{ - register u4 c; - register const u4 FAR *buf4; - - c = REV((u4)crc); - c = ~c; - while (len && ((ptrdiff_t)buf & 3)) { - c = crc_table[4][(c >> 24) ^ *buf++] ^ (c << 8); - len--; - } - - buf4 = (const u4 FAR *)(const void FAR *)buf; - buf4--; - while (len >= 32) { - DOBIG32; - len -= 32; - } - while (len >= 4) { - DOBIG4; - len -= 4; - } - buf4++; - buf = (const unsigned char FAR *)buf4; - - if (len) do { - c = crc_table[4][(c >> 24) ^ *buf++] ^ (c << 8); - } while (--len); - c = ~c; - return (unsigned long)(REV(c)); -} - -#endif /* BYFOUR */ - -#define GF2_DIM 32 /* dimension of GF(2) vectors (length of CRC) */ - -/* ========================================================================= */ -local unsigned long gf2_matrix_times(mat, vec) - unsigned long *mat; - unsigned long vec; -{ - unsigned long sum; - - sum = 0; - while (vec) { - if (vec & 1) - sum ^= *mat; - vec >>= 1; - mat++; - } - return sum; -} - -/* ========================================================================= */ -local void gf2_matrix_square(square, mat) - unsigned long *square; - unsigned long *mat; -{ - int n; - - for (n = 0; n < GF2_DIM; n++) - square[n] = gf2_matrix_times(mat, mat[n]); -} - -/* ========================================================================= */ -uLong ZEXPORT crc32_combine(crc1, crc2, len2) - uLong crc1; - uLong crc2; - z_off_t len2; -{ - int n; - unsigned long row; - unsigned long even[GF2_DIM]; /* even-power-of-two zeros operator */ - unsigned long odd[GF2_DIM]; /* odd-power-of-two zeros operator */ - - /* degenerate case */ - if (len2 == 0) - return crc1; - - /* put operator for one zero bit in odd */ - odd[0] = 0xedb88320L; /* CRC-32 polynomial */ - row = 1; - for (n = 1; n < GF2_DIM; n++) { - odd[n] = row; - row <<= 1; - } - - /* put operator for two zero bits in even */ - gf2_matrix_square(even, odd); - - /* put operator for four zero bits in odd */ - gf2_matrix_square(odd, even); - - /* apply len2 zeros to crc1 (first square will put the operator for one - zero byte, eight zero bits, in even) */ - do { - /* apply zeros operator for this bit of len2 */ - gf2_matrix_square(even, odd); - if (len2 & 1) - crc1 = gf2_matrix_times(even, crc1); - len2 >>= 1; - - /* if no more bits set, then done */ - if (len2 == 0) - break; - - /* another iteration of the loop with odd and even swapped */ - gf2_matrix_square(odd, even); - if (len2 & 1) - crc1 = gf2_matrix_times(odd, crc1); - len2 >>= 1; - - /* if no more bits set, then done */ - } while (len2 != 0); - - /* return combined crc */ - crc1 ^= crc2; - return crc1; -} +/* crc32.c -- compute the CRC-32 of a data stream + * Copyright (C) 1995-2005 Mark Adler + * For conditions of distribution and use, see copyright notice in zlib.h + * + * Thanks to Rodney Brown for his contribution of faster + * CRC methods: exclusive-oring 32 bits of data at a time, and pre-computing + * tables for updating the shift register in one step with three exclusive-ors + * instead of four steps with four exclusive-ors. This results in about a + * factor of two increase in speed on a Power PC G4 (PPC7455) using gcc -O3. + */ + +/* @(#) $Id$ */ + +/* + Note on the use of DYNAMIC_CRC_TABLE: there is no mutex or semaphore + protection on the static variables used to control the first-use generation + of the crc tables. Therefore, if you #define DYNAMIC_CRC_TABLE, you should + first call get_crc_table() to initialize the tables before allowing more than + one thread to use crc32(). + */ + +#ifdef MAKECRCH +# include +# ifndef DYNAMIC_CRC_TABLE +# define DYNAMIC_CRC_TABLE +# endif /* !DYNAMIC_CRC_TABLE */ +#endif /* MAKECRCH */ + +#include "zutil.h" /* for STDC and FAR definitions */ + +#define local static + +/* Find a four-byte integer type for crc32_little() and crc32_big(). */ +#ifndef NOBYFOUR +# ifdef STDC /* need ANSI C limits.h to determine sizes */ +# include +# define BYFOUR +# if (UINT_MAX == 0xffffffffUL) + typedef unsigned int u4; +# else +# if (ULONG_MAX == 0xffffffffUL) + typedef unsigned long u4; +# else +# if (USHRT_MAX == 0xffffffffUL) + typedef unsigned short u4; +# else +# undef BYFOUR /* can't find a four-byte integer type! */ +# endif +# endif +# endif +# endif /* STDC */ +#endif /* !NOBYFOUR */ + +/* Definitions for doing the crc four data bytes at a time. */ +#ifdef BYFOUR +# define REV(w) (((w)>>24)+(((w)>>8)&0xff00)+ \ + (((w)&0xff00)<<8)+(((w)&0xff)<<24)) + local unsigned long crc32_little OF((unsigned long, + const unsigned char FAR *, unsigned)); + local unsigned long crc32_big OF((unsigned long, + const unsigned char FAR *, unsigned)); +# define TBLS 8 +#else +# define TBLS 1 +#endif /* BYFOUR */ + +/* Local functions for crc concatenation */ +local unsigned long gf2_matrix_times OF((unsigned long *mat, + unsigned long vec)); +local void gf2_matrix_square OF((unsigned long *square, unsigned long *mat)); + +#ifdef DYNAMIC_CRC_TABLE + +local volatile int crc_table_empty = 1; +local unsigned long FAR crc_table[TBLS][256]; +local void make_crc_table OF((void)); +#ifdef MAKECRCH + local void write_table OF((FILE *, const unsigned long FAR *)); +#endif /* MAKECRCH */ +/* + Generate tables for a byte-wise 32-bit CRC calculation on the polynomial: + x^32+x^26+x^23+x^22+x^16+x^12+x^11+x^10+x^8+x^7+x^5+x^4+x^2+x+1. + + Polynomials over GF(2) are represented in binary, one bit per coefficient, + with the lowest powers in the most significant bit. Then adding polynomials + is just exclusive-or, and multiplying a polynomial by x is a right shift by + one. If we call the above polynomial p, and represent a byte as the + polynomial q, also with the lowest power in the most significant bit (so the + byte 0xb1 is the polynomial x^7+x^3+x+1), then the CRC is (q*x^32) mod p, + where a mod b means the remainder after dividing a by b. + + This calculation is done using the shift-register method of multiplying and + taking the remainder. The register is initialized to zero, and for each + incoming bit, x^32 is added mod p to the register if the bit is a one (where + x^32 mod p is p+x^32 = x^26+...+1), and the register is multiplied mod p by + x (which is shifting right by one and adding x^32 mod p if the bit shifted + out is a one). We start with the highest power (least significant bit) of + q and repeat for all eight bits of q. + + The first table is simply the CRC of all possible eight bit values. This is + all the information needed to generate CRCs on data a byte at a time for all + combinations of CRC register values and incoming bytes. The remaining tables + allow for word-at-a-time CRC calculation for both big-endian and little- + endian machines, where a word is four bytes. +*/ +local void make_crc_table() +{ + unsigned long c; + int n, k; + unsigned long poly; /* polynomial exclusive-or pattern */ + /* terms of polynomial defining this crc (except x^32): */ + static volatile int first = 1; /* flag to limit concurrent making */ + static const unsigned char p[] = {0,1,2,4,5,7,8,10,11,12,16,22,23,26}; + + /* See if another task is already doing this (not thread-safe, but better + than nothing -- significantly reduces duration of vulnerability in + case the advice about DYNAMIC_CRC_TABLE is ignored) */ + if (first) { + first = 0; + + /* make exclusive-or pattern from polynomial (0xedb88320UL) */ + poly = 0UL; + for (n = 0; n < sizeof(p)/sizeof(unsigned char); n++) + poly |= 1UL << (31 - p[n]); + + /* generate a crc for every 8-bit value */ + for (n = 0; n < 256; n++) { + c = (unsigned long)n; + for (k = 0; k < 8; k++) + c = c & 1 ? poly ^ (c >> 1) : c >> 1; + crc_table[0][n] = c; + } + +#ifdef BYFOUR + /* generate crc for each value followed by one, two, and three zeros, + and then the byte reversal of those as well as the first table */ + for (n = 0; n < 256; n++) { + c = crc_table[0][n]; + crc_table[4][n] = REV(c); + for (k = 1; k < 4; k++) { + c = crc_table[0][c & 0xff] ^ (c >> 8); + crc_table[k][n] = c; + crc_table[k + 4][n] = REV(c); + } + } +#endif /* BYFOUR */ + + crc_table_empty = 0; + } + else { /* not first */ + /* wait for the other guy to finish (not efficient, but rare) */ + while (crc_table_empty) + ; + } + +#ifdef MAKECRCH + /* write out CRC tables to crc32.h */ + { + FILE *out; + + out = fopen("crc32.h", "w"); + if (out == NULL) return; + fprintf(out, "/* crc32.h -- tables for rapid CRC calculation\n"); + fprintf(out, " * Generated automatically by crc32.c\n */\n\n"); + fprintf(out, "local const unsigned long FAR "); + fprintf(out, "crc_table[TBLS][256] =\n{\n {\n"); + write_table(out, crc_table[0]); +# ifdef BYFOUR + fprintf(out, "#ifdef BYFOUR\n"); + for (k = 1; k < 8; k++) { + fprintf(out, " },\n {\n"); + write_table(out, crc_table[k]); + } + fprintf(out, "#endif\n"); +# endif /* BYFOUR */ + fprintf(out, " }\n};\n"); + fclose(out); + } +#endif /* MAKECRCH */ +} + +#ifdef MAKECRCH +local void write_table(out, table) + FILE *out; + const unsigned long FAR *table; +{ + int n; + + for (n = 0; n < 256; n++) + fprintf(out, "%s0x%08lxUL%s", n % 5 ? "" : " ", table[n], + n == 255 ? "\n" : (n % 5 == 4 ? ",\n" : ", ")); +} +#endif /* MAKECRCH */ + +#else /* !DYNAMIC_CRC_TABLE */ +/* ======================================================================== + * Tables of CRC-32s of all single-byte values, made by make_crc_table(). + */ +#include "crc32.h" +#endif /* DYNAMIC_CRC_TABLE */ + +/* ========================================================================= + * This function can be used by asm versions of crc32() + */ +const unsigned long FAR * ZEXPORT get_crc_table() +{ +#ifdef DYNAMIC_CRC_TABLE + if (crc_table_empty) + make_crc_table(); +#endif /* DYNAMIC_CRC_TABLE */ + return (const unsigned long FAR *)crc_table; +} + +/* ========================================================================= */ +#define DO1 crc = crc_table[0][((int)crc ^ (*buf++)) & 0xff] ^ (crc >> 8) +#define DO8 DO1; DO1; DO1; DO1; DO1; DO1; DO1; DO1 + +/* ========================================================================= */ +unsigned long ZEXPORT crc32(crc, buf, len) + unsigned long crc; + const unsigned char FAR *buf; + unsigned len; +{ + if (buf == Z_NULL) return 0UL; + +#ifdef DYNAMIC_CRC_TABLE + if (crc_table_empty) + make_crc_table(); +#endif /* DYNAMIC_CRC_TABLE */ + +#ifdef BYFOUR + if (sizeof(void *) == sizeof(ptrdiff_t)) { + u4 endian; + + endian = 1; + if (*((unsigned char *)(&endian))) + return crc32_little(crc, buf, len); + else + return crc32_big(crc, buf, len); + } +#endif /* BYFOUR */ + crc = crc ^ 0xffffffffUL; + while (len >= 8) { + DO8; + len -= 8; + } + if (len) do { + DO1; + } while (--len); + return crc ^ 0xffffffffUL; +} + +#ifdef BYFOUR + +/* ========================================================================= */ +#define DOLIT4 c ^= *buf4++; \ + c = crc_table[3][c & 0xff] ^ crc_table[2][(c >> 8) & 0xff] ^ \ + crc_table[1][(c >> 16) & 0xff] ^ crc_table[0][c >> 24] +#define DOLIT32 DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4; DOLIT4 + +/* ========================================================================= */ +local unsigned long crc32_little(crc, buf, len) + unsigned long crc; + const unsigned char FAR *buf; + unsigned len; +{ + register u4 c; + register const u4 FAR *buf4; + + c = (u4)crc; + c = ~c; + while (len && ((ptrdiff_t)buf & 3)) { + c = crc_table[0][(c ^ *buf++) & 0xff] ^ (c >> 8); + len--; + } + + buf4 = (const u4 FAR *)(const void FAR *)buf; + while (len >= 32) { + DOLIT32; + len -= 32; + } + while (len >= 4) { + DOLIT4; + len -= 4; + } + buf = (const unsigned char FAR *)buf4; + + if (len) do { + c = crc_table[0][(c ^ *buf++) & 0xff] ^ (c >> 8); + } while (--len); + c = ~c; + return (unsigned long)c; +} + +/* ========================================================================= */ +#define DOBIG4 c ^= *++buf4; \ + c = crc_table[4][c & 0xff] ^ crc_table[5][(c >> 8) & 0xff] ^ \ + crc_table[6][(c >> 16) & 0xff] ^ crc_table[7][c >> 24] +#define DOBIG32 DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4; DOBIG4 + +/* ========================================================================= */ +local unsigned long crc32_big(crc, buf, len) + unsigned long crc; + const unsigned char FAR *buf; + unsigned len; +{ + register u4 c; + register const u4 FAR *buf4; + + c = REV((u4)crc); + c = ~c; + while (len && ((ptrdiff_t)buf & 3)) { + c = crc_table[4][(c >> 24) ^ *buf++] ^ (c << 8); + len--; + } + + buf4 = (const u4 FAR *)(const void FAR *)buf; + buf4--; + while (len >= 32) { + DOBIG32; + len -= 32; + } + while (len >= 4) { + DOBIG4; + len -= 4; + } + buf4++; + buf = (const unsigned char FAR *)buf4; + + if (len) do { + c = crc_table[4][(c >> 24) ^ *buf++] ^ (c << 8); + } while (--len); + c = ~c; + return (unsigned long)(REV(c)); +} + +#endif /* BYFOUR */ + +#define GF2_DIM 32 /* dimension of GF(2) vectors (length of CRC) */ + +/* ========================================================================= */ +local unsigned long gf2_matrix_times(mat, vec) + unsigned long *mat; + unsigned long vec; +{ + unsigned long sum; + + sum = 0; + while (vec) { + if (vec & 1) + sum ^= *mat; + vec >>= 1; + mat++; + } + return sum; +} + +/* ========================================================================= */ +local void gf2_matrix_square(square, mat) + unsigned long *square; + unsigned long *mat; +{ + int n; + + for (n = 0; n < GF2_DIM; n++) + square[n] = gf2_matrix_times(mat, mat[n]); +} + +/* ========================================================================= */ +uLong ZEXPORT crc32_combine(crc1, crc2, len2) + uLong crc1; + uLong crc2; + z_off_t len2; +{ + int n; + unsigned long row; + unsigned long even[GF2_DIM]; /* even-power-of-two zeros operator */ + unsigned long odd[GF2_DIM]; /* odd-power-of-two zeros operator */ + + /* degenerate case */ + if (len2 == 0) + return crc1; + + /* put operator for one zero bit in odd */ + odd[0] = 0xedb88320L; /* CRC-32 polynomial */ + row = 1; + for (n = 1; n < GF2_DIM; n++) { + odd[n] = row; + row <<= 1; + } + + /* put operator for two zero bits in even */ + gf2_matrix_square(even, odd); + + /* put operator for four zero bits in odd */ + gf2_matrix_square(odd, even); + + /* apply len2 zeros to crc1 (first square will put the operator for one + zero byte, eight zero bits, in even) */ + do { + /* apply zeros operator for this bit of len2 */ + gf2_matrix_square(even, odd); + if (len2 & 1) + crc1 = gf2_matrix_times(even, crc1); + len2 >>= 1; + + /* if no more bits set, then done */ + if (len2 == 0) + break; + + /* another iteration of the loop with odd and even swapped */ + gf2_matrix_square(odd, even); + if (len2 & 1) + crc1 = gf2_matrix_times(odd, crc1); + len2 >>= 1; + + /* if no more bits set, then done */ + } while (len2 != 0); + + /* return combined crc */ + crc1 ^= crc2; + return crc1; +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/crc32.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/crc32.h index 5de49bc97..8053b6117 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/crc32.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/crc32.h @@ -1,441 +1,441 @@ -/* crc32.h -- tables for rapid CRC calculation - * Generated automatically by crc32.c - */ - -local const unsigned long FAR crc_table[TBLS][256] = -{ - { - 0x00000000UL, 0x77073096UL, 0xee0e612cUL, 0x990951baUL, 0x076dc419UL, - 0x706af48fUL, 0xe963a535UL, 0x9e6495a3UL, 0x0edb8832UL, 0x79dcb8a4UL, - 0xe0d5e91eUL, 0x97d2d988UL, 0x09b64c2bUL, 0x7eb17cbdUL, 0xe7b82d07UL, - 0x90bf1d91UL, 0x1db71064UL, 0x6ab020f2UL, 0xf3b97148UL, 0x84be41deUL, - 0x1adad47dUL, 0x6ddde4ebUL, 0xf4d4b551UL, 0x83d385c7UL, 0x136c9856UL, - 0x646ba8c0UL, 0xfd62f97aUL, 0x8a65c9ecUL, 0x14015c4fUL, 0x63066cd9UL, - 0xfa0f3d63UL, 0x8d080df5UL, 0x3b6e20c8UL, 0x4c69105eUL, 0xd56041e4UL, - 0xa2677172UL, 0x3c03e4d1UL, 0x4b04d447UL, 0xd20d85fdUL, 0xa50ab56bUL, - 0x35b5a8faUL, 0x42b2986cUL, 0xdbbbc9d6UL, 0xacbcf940UL, 0x32d86ce3UL, - 0x45df5c75UL, 0xdcd60dcfUL, 0xabd13d59UL, 0x26d930acUL, 0x51de003aUL, - 0xc8d75180UL, 0xbfd06116UL, 0x21b4f4b5UL, 0x56b3c423UL, 0xcfba9599UL, - 0xb8bda50fUL, 0x2802b89eUL, 0x5f058808UL, 0xc60cd9b2UL, 0xb10be924UL, - 0x2f6f7c87UL, 0x58684c11UL, 0xc1611dabUL, 0xb6662d3dUL, 0x76dc4190UL, - 0x01db7106UL, 0x98d220bcUL, 0xefd5102aUL, 0x71b18589UL, 0x06b6b51fUL, - 0x9fbfe4a5UL, 0xe8b8d433UL, 0x7807c9a2UL, 0x0f00f934UL, 0x9609a88eUL, - 0xe10e9818UL, 0x7f6a0dbbUL, 0x086d3d2dUL, 0x91646c97UL, 0xe6635c01UL, - 0x6b6b51f4UL, 0x1c6c6162UL, 0x856530d8UL, 0xf262004eUL, 0x6c0695edUL, - 0x1b01a57bUL, 0x8208f4c1UL, 0xf50fc457UL, 0x65b0d9c6UL, 0x12b7e950UL, - 0x8bbeb8eaUL, 0xfcb9887cUL, 0x62dd1ddfUL, 0x15da2d49UL, 0x8cd37cf3UL, - 0xfbd44c65UL, 0x4db26158UL, 0x3ab551ceUL, 0xa3bc0074UL, 0xd4bb30e2UL, - 0x4adfa541UL, 0x3dd895d7UL, 0xa4d1c46dUL, 0xd3d6f4fbUL, 0x4369e96aUL, - 0x346ed9fcUL, 0xad678846UL, 0xda60b8d0UL, 0x44042d73UL, 0x33031de5UL, - 0xaa0a4c5fUL, 0xdd0d7cc9UL, 0x5005713cUL, 0x270241aaUL, 0xbe0b1010UL, - 0xc90c2086UL, 0x5768b525UL, 0x206f85b3UL, 0xb966d409UL, 0xce61e49fUL, - 0x5edef90eUL, 0x29d9c998UL, 0xb0d09822UL, 0xc7d7a8b4UL, 0x59b33d17UL, - 0x2eb40d81UL, 0xb7bd5c3bUL, 0xc0ba6cadUL, 0xedb88320UL, 0x9abfb3b6UL, - 0x03b6e20cUL, 0x74b1d29aUL, 0xead54739UL, 0x9dd277afUL, 0x04db2615UL, - 0x73dc1683UL, 0xe3630b12UL, 0x94643b84UL, 0x0d6d6a3eUL, 0x7a6a5aa8UL, - 0xe40ecf0bUL, 0x9309ff9dUL, 0x0a00ae27UL, 0x7d079eb1UL, 0xf00f9344UL, - 0x8708a3d2UL, 0x1e01f268UL, 0x6906c2feUL, 0xf762575dUL, 0x806567cbUL, - 0x196c3671UL, 0x6e6b06e7UL, 0xfed41b76UL, 0x89d32be0UL, 0x10da7a5aUL, - 0x67dd4accUL, 0xf9b9df6fUL, 0x8ebeeff9UL, 0x17b7be43UL, 0x60b08ed5UL, - 0xd6d6a3e8UL, 0xa1d1937eUL, 0x38d8c2c4UL, 0x4fdff252UL, 0xd1bb67f1UL, - 0xa6bc5767UL, 0x3fb506ddUL, 0x48b2364bUL, 0xd80d2bdaUL, 0xaf0a1b4cUL, - 0x36034af6UL, 0x41047a60UL, 0xdf60efc3UL, 0xa867df55UL, 0x316e8eefUL, - 0x4669be79UL, 0xcb61b38cUL, 0xbc66831aUL, 0x256fd2a0UL, 0x5268e236UL, - 0xcc0c7795UL, 0xbb0b4703UL, 0x220216b9UL, 0x5505262fUL, 0xc5ba3bbeUL, - 0xb2bd0b28UL, 0x2bb45a92UL, 0x5cb36a04UL, 0xc2d7ffa7UL, 0xb5d0cf31UL, - 0x2cd99e8bUL, 0x5bdeae1dUL, 0x9b64c2b0UL, 0xec63f226UL, 0x756aa39cUL, - 0x026d930aUL, 0x9c0906a9UL, 0xeb0e363fUL, 0x72076785UL, 0x05005713UL, - 0x95bf4a82UL, 0xe2b87a14UL, 0x7bb12baeUL, 0x0cb61b38UL, 0x92d28e9bUL, - 0xe5d5be0dUL, 0x7cdcefb7UL, 0x0bdbdf21UL, 0x86d3d2d4UL, 0xf1d4e242UL, - 0x68ddb3f8UL, 0x1fda836eUL, 0x81be16cdUL, 0xf6b9265bUL, 0x6fb077e1UL, - 0x18b74777UL, 0x88085ae6UL, 0xff0f6a70UL, 0x66063bcaUL, 0x11010b5cUL, - 0x8f659effUL, 0xf862ae69UL, 0x616bffd3UL, 0x166ccf45UL, 0xa00ae278UL, - 0xd70dd2eeUL, 0x4e048354UL, 0x3903b3c2UL, 0xa7672661UL, 0xd06016f7UL, - 0x4969474dUL, 0x3e6e77dbUL, 0xaed16a4aUL, 0xd9d65adcUL, 0x40df0b66UL, - 0x37d83bf0UL, 0xa9bcae53UL, 0xdebb9ec5UL, 0x47b2cf7fUL, 0x30b5ffe9UL, - 0xbdbdf21cUL, 0xcabac28aUL, 0x53b39330UL, 0x24b4a3a6UL, 0xbad03605UL, - 0xcdd70693UL, 0x54de5729UL, 0x23d967bfUL, 0xb3667a2eUL, 0xc4614ab8UL, - 0x5d681b02UL, 0x2a6f2b94UL, 0xb40bbe37UL, 0xc30c8ea1UL, 0x5a05df1bUL, - 0x2d02ef8dUL -#ifdef BYFOUR - }, - { - 0x00000000UL, 0x191b3141UL, 0x32366282UL, 0x2b2d53c3UL, 0x646cc504UL, - 0x7d77f445UL, 0x565aa786UL, 0x4f4196c7UL, 0xc8d98a08UL, 0xd1c2bb49UL, - 0xfaefe88aUL, 0xe3f4d9cbUL, 0xacb54f0cUL, 0xb5ae7e4dUL, 0x9e832d8eUL, - 0x87981ccfUL, 0x4ac21251UL, 0x53d92310UL, 0x78f470d3UL, 0x61ef4192UL, - 0x2eaed755UL, 0x37b5e614UL, 0x1c98b5d7UL, 0x05838496UL, 0x821b9859UL, - 0x9b00a918UL, 0xb02dfadbUL, 0xa936cb9aUL, 0xe6775d5dUL, 0xff6c6c1cUL, - 0xd4413fdfUL, 0xcd5a0e9eUL, 0x958424a2UL, 0x8c9f15e3UL, 0xa7b24620UL, - 0xbea97761UL, 0xf1e8e1a6UL, 0xe8f3d0e7UL, 0xc3de8324UL, 0xdac5b265UL, - 0x5d5daeaaUL, 0x44469febUL, 0x6f6bcc28UL, 0x7670fd69UL, 0x39316baeUL, - 0x202a5aefUL, 0x0b07092cUL, 0x121c386dUL, 0xdf4636f3UL, 0xc65d07b2UL, - 0xed705471UL, 0xf46b6530UL, 0xbb2af3f7UL, 0xa231c2b6UL, 0x891c9175UL, - 0x9007a034UL, 0x179fbcfbUL, 0x0e848dbaUL, 0x25a9de79UL, 0x3cb2ef38UL, - 0x73f379ffUL, 0x6ae848beUL, 0x41c51b7dUL, 0x58de2a3cUL, 0xf0794f05UL, - 0xe9627e44UL, 0xc24f2d87UL, 0xdb541cc6UL, 0x94158a01UL, 0x8d0ebb40UL, - 0xa623e883UL, 0xbf38d9c2UL, 0x38a0c50dUL, 0x21bbf44cUL, 0x0a96a78fUL, - 0x138d96ceUL, 0x5ccc0009UL, 0x45d73148UL, 0x6efa628bUL, 0x77e153caUL, - 0xbabb5d54UL, 0xa3a06c15UL, 0x888d3fd6UL, 0x91960e97UL, 0xded79850UL, - 0xc7cca911UL, 0xece1fad2UL, 0xf5facb93UL, 0x7262d75cUL, 0x6b79e61dUL, - 0x4054b5deUL, 0x594f849fUL, 0x160e1258UL, 0x0f152319UL, 0x243870daUL, - 0x3d23419bUL, 0x65fd6ba7UL, 0x7ce65ae6UL, 0x57cb0925UL, 0x4ed03864UL, - 0x0191aea3UL, 0x188a9fe2UL, 0x33a7cc21UL, 0x2abcfd60UL, 0xad24e1afUL, - 0xb43fd0eeUL, 0x9f12832dUL, 0x8609b26cUL, 0xc94824abUL, 0xd05315eaUL, - 0xfb7e4629UL, 0xe2657768UL, 0x2f3f79f6UL, 0x362448b7UL, 0x1d091b74UL, - 0x04122a35UL, 0x4b53bcf2UL, 0x52488db3UL, 0x7965de70UL, 0x607eef31UL, - 0xe7e6f3feUL, 0xfefdc2bfUL, 0xd5d0917cUL, 0xcccba03dUL, 0x838a36faUL, - 0x9a9107bbUL, 0xb1bc5478UL, 0xa8a76539UL, 0x3b83984bUL, 0x2298a90aUL, - 0x09b5fac9UL, 0x10aecb88UL, 0x5fef5d4fUL, 0x46f46c0eUL, 0x6dd93fcdUL, - 0x74c20e8cUL, 0xf35a1243UL, 0xea412302UL, 0xc16c70c1UL, 0xd8774180UL, - 0x9736d747UL, 0x8e2de606UL, 0xa500b5c5UL, 0xbc1b8484UL, 0x71418a1aUL, - 0x685abb5bUL, 0x4377e898UL, 0x5a6cd9d9UL, 0x152d4f1eUL, 0x0c367e5fUL, - 0x271b2d9cUL, 0x3e001cddUL, 0xb9980012UL, 0xa0833153UL, 0x8bae6290UL, - 0x92b553d1UL, 0xddf4c516UL, 0xc4eff457UL, 0xefc2a794UL, 0xf6d996d5UL, - 0xae07bce9UL, 0xb71c8da8UL, 0x9c31de6bUL, 0x852aef2aUL, 0xca6b79edUL, - 0xd37048acUL, 0xf85d1b6fUL, 0xe1462a2eUL, 0x66de36e1UL, 0x7fc507a0UL, - 0x54e85463UL, 0x4df36522UL, 0x02b2f3e5UL, 0x1ba9c2a4UL, 0x30849167UL, - 0x299fa026UL, 0xe4c5aeb8UL, 0xfdde9ff9UL, 0xd6f3cc3aUL, 0xcfe8fd7bUL, - 0x80a96bbcUL, 0x99b25afdUL, 0xb29f093eUL, 0xab84387fUL, 0x2c1c24b0UL, - 0x350715f1UL, 0x1e2a4632UL, 0x07317773UL, 0x4870e1b4UL, 0x516bd0f5UL, - 0x7a468336UL, 0x635db277UL, 0xcbfad74eUL, 0xd2e1e60fUL, 0xf9ccb5ccUL, - 0xe0d7848dUL, 0xaf96124aUL, 0xb68d230bUL, 0x9da070c8UL, 0x84bb4189UL, - 0x03235d46UL, 0x1a386c07UL, 0x31153fc4UL, 0x280e0e85UL, 0x674f9842UL, - 0x7e54a903UL, 0x5579fac0UL, 0x4c62cb81UL, 0x8138c51fUL, 0x9823f45eUL, - 0xb30ea79dUL, 0xaa1596dcUL, 0xe554001bUL, 0xfc4f315aUL, 0xd7626299UL, - 0xce7953d8UL, 0x49e14f17UL, 0x50fa7e56UL, 0x7bd72d95UL, 0x62cc1cd4UL, - 0x2d8d8a13UL, 0x3496bb52UL, 0x1fbbe891UL, 0x06a0d9d0UL, 0x5e7ef3ecUL, - 0x4765c2adUL, 0x6c48916eUL, 0x7553a02fUL, 0x3a1236e8UL, 0x230907a9UL, - 0x0824546aUL, 0x113f652bUL, 0x96a779e4UL, 0x8fbc48a5UL, 0xa4911b66UL, - 0xbd8a2a27UL, 0xf2cbbce0UL, 0xebd08da1UL, 0xc0fdde62UL, 0xd9e6ef23UL, - 0x14bce1bdUL, 0x0da7d0fcUL, 0x268a833fUL, 0x3f91b27eUL, 0x70d024b9UL, - 0x69cb15f8UL, 0x42e6463bUL, 0x5bfd777aUL, 0xdc656bb5UL, 0xc57e5af4UL, - 0xee530937UL, 0xf7483876UL, 0xb809aeb1UL, 0xa1129ff0UL, 0x8a3fcc33UL, - 0x9324fd72UL - }, - { - 0x00000000UL, 0x01c26a37UL, 0x0384d46eUL, 0x0246be59UL, 0x0709a8dcUL, - 0x06cbc2ebUL, 0x048d7cb2UL, 0x054f1685UL, 0x0e1351b8UL, 0x0fd13b8fUL, - 0x0d9785d6UL, 0x0c55efe1UL, 0x091af964UL, 0x08d89353UL, 0x0a9e2d0aUL, - 0x0b5c473dUL, 0x1c26a370UL, 0x1de4c947UL, 0x1fa2771eUL, 0x1e601d29UL, - 0x1b2f0bacUL, 0x1aed619bUL, 0x18abdfc2UL, 0x1969b5f5UL, 0x1235f2c8UL, - 0x13f798ffUL, 0x11b126a6UL, 0x10734c91UL, 0x153c5a14UL, 0x14fe3023UL, - 0x16b88e7aUL, 0x177ae44dUL, 0x384d46e0UL, 0x398f2cd7UL, 0x3bc9928eUL, - 0x3a0bf8b9UL, 0x3f44ee3cUL, 0x3e86840bUL, 0x3cc03a52UL, 0x3d025065UL, - 0x365e1758UL, 0x379c7d6fUL, 0x35dac336UL, 0x3418a901UL, 0x3157bf84UL, - 0x3095d5b3UL, 0x32d36beaUL, 0x331101ddUL, 0x246be590UL, 0x25a98fa7UL, - 0x27ef31feUL, 0x262d5bc9UL, 0x23624d4cUL, 0x22a0277bUL, 0x20e69922UL, - 0x2124f315UL, 0x2a78b428UL, 0x2bbade1fUL, 0x29fc6046UL, 0x283e0a71UL, - 0x2d711cf4UL, 0x2cb376c3UL, 0x2ef5c89aUL, 0x2f37a2adUL, 0x709a8dc0UL, - 0x7158e7f7UL, 0x731e59aeUL, 0x72dc3399UL, 0x7793251cUL, 0x76514f2bUL, - 0x7417f172UL, 0x75d59b45UL, 0x7e89dc78UL, 0x7f4bb64fUL, 0x7d0d0816UL, - 0x7ccf6221UL, 0x798074a4UL, 0x78421e93UL, 0x7a04a0caUL, 0x7bc6cafdUL, - 0x6cbc2eb0UL, 0x6d7e4487UL, 0x6f38fadeUL, 0x6efa90e9UL, 0x6bb5866cUL, - 0x6a77ec5bUL, 0x68315202UL, 0x69f33835UL, 0x62af7f08UL, 0x636d153fUL, - 0x612bab66UL, 0x60e9c151UL, 0x65a6d7d4UL, 0x6464bde3UL, 0x662203baUL, - 0x67e0698dUL, 0x48d7cb20UL, 0x4915a117UL, 0x4b531f4eUL, 0x4a917579UL, - 0x4fde63fcUL, 0x4e1c09cbUL, 0x4c5ab792UL, 0x4d98dda5UL, 0x46c49a98UL, - 0x4706f0afUL, 0x45404ef6UL, 0x448224c1UL, 0x41cd3244UL, 0x400f5873UL, - 0x4249e62aUL, 0x438b8c1dUL, 0x54f16850UL, 0x55330267UL, 0x5775bc3eUL, - 0x56b7d609UL, 0x53f8c08cUL, 0x523aaabbUL, 0x507c14e2UL, 0x51be7ed5UL, - 0x5ae239e8UL, 0x5b2053dfUL, 0x5966ed86UL, 0x58a487b1UL, 0x5deb9134UL, - 0x5c29fb03UL, 0x5e6f455aUL, 0x5fad2f6dUL, 0xe1351b80UL, 0xe0f771b7UL, - 0xe2b1cfeeUL, 0xe373a5d9UL, 0xe63cb35cUL, 0xe7fed96bUL, 0xe5b86732UL, - 0xe47a0d05UL, 0xef264a38UL, 0xeee4200fUL, 0xeca29e56UL, 0xed60f461UL, - 0xe82fe2e4UL, 0xe9ed88d3UL, 0xebab368aUL, 0xea695cbdUL, 0xfd13b8f0UL, - 0xfcd1d2c7UL, 0xfe976c9eUL, 0xff5506a9UL, 0xfa1a102cUL, 0xfbd87a1bUL, - 0xf99ec442UL, 0xf85cae75UL, 0xf300e948UL, 0xf2c2837fUL, 0xf0843d26UL, - 0xf1465711UL, 0xf4094194UL, 0xf5cb2ba3UL, 0xf78d95faUL, 0xf64fffcdUL, - 0xd9785d60UL, 0xd8ba3757UL, 0xdafc890eUL, 0xdb3ee339UL, 0xde71f5bcUL, - 0xdfb39f8bUL, 0xddf521d2UL, 0xdc374be5UL, 0xd76b0cd8UL, 0xd6a966efUL, - 0xd4efd8b6UL, 0xd52db281UL, 0xd062a404UL, 0xd1a0ce33UL, 0xd3e6706aUL, - 0xd2241a5dUL, 0xc55efe10UL, 0xc49c9427UL, 0xc6da2a7eUL, 0xc7184049UL, - 0xc25756ccUL, 0xc3953cfbUL, 0xc1d382a2UL, 0xc011e895UL, 0xcb4dafa8UL, - 0xca8fc59fUL, 0xc8c97bc6UL, 0xc90b11f1UL, 0xcc440774UL, 0xcd866d43UL, - 0xcfc0d31aUL, 0xce02b92dUL, 0x91af9640UL, 0x906dfc77UL, 0x922b422eUL, - 0x93e92819UL, 0x96a63e9cUL, 0x976454abUL, 0x9522eaf2UL, 0x94e080c5UL, - 0x9fbcc7f8UL, 0x9e7eadcfUL, 0x9c381396UL, 0x9dfa79a1UL, 0x98b56f24UL, - 0x99770513UL, 0x9b31bb4aUL, 0x9af3d17dUL, 0x8d893530UL, 0x8c4b5f07UL, - 0x8e0de15eUL, 0x8fcf8b69UL, 0x8a809decUL, 0x8b42f7dbUL, 0x89044982UL, - 0x88c623b5UL, 0x839a6488UL, 0x82580ebfUL, 0x801eb0e6UL, 0x81dcdad1UL, - 0x8493cc54UL, 0x8551a663UL, 0x8717183aUL, 0x86d5720dUL, 0xa9e2d0a0UL, - 0xa820ba97UL, 0xaa6604ceUL, 0xaba46ef9UL, 0xaeeb787cUL, 0xaf29124bUL, - 0xad6fac12UL, 0xacadc625UL, 0xa7f18118UL, 0xa633eb2fUL, 0xa4755576UL, - 0xa5b73f41UL, 0xa0f829c4UL, 0xa13a43f3UL, 0xa37cfdaaUL, 0xa2be979dUL, - 0xb5c473d0UL, 0xb40619e7UL, 0xb640a7beUL, 0xb782cd89UL, 0xb2cddb0cUL, - 0xb30fb13bUL, 0xb1490f62UL, 0xb08b6555UL, 0xbbd72268UL, 0xba15485fUL, - 0xb853f606UL, 0xb9919c31UL, 0xbcde8ab4UL, 0xbd1ce083UL, 0xbf5a5edaUL, - 0xbe9834edUL - }, - { - 0x00000000UL, 0xb8bc6765UL, 0xaa09c88bUL, 0x12b5afeeUL, 0x8f629757UL, - 0x37def032UL, 0x256b5fdcUL, 0x9dd738b9UL, 0xc5b428efUL, 0x7d084f8aUL, - 0x6fbde064UL, 0xd7018701UL, 0x4ad6bfb8UL, 0xf26ad8ddUL, 0xe0df7733UL, - 0x58631056UL, 0x5019579fUL, 0xe8a530faUL, 0xfa109f14UL, 0x42acf871UL, - 0xdf7bc0c8UL, 0x67c7a7adUL, 0x75720843UL, 0xcdce6f26UL, 0x95ad7f70UL, - 0x2d111815UL, 0x3fa4b7fbUL, 0x8718d09eUL, 0x1acfe827UL, 0xa2738f42UL, - 0xb0c620acUL, 0x087a47c9UL, 0xa032af3eUL, 0x188ec85bUL, 0x0a3b67b5UL, - 0xb28700d0UL, 0x2f503869UL, 0x97ec5f0cUL, 0x8559f0e2UL, 0x3de59787UL, - 0x658687d1UL, 0xdd3ae0b4UL, 0xcf8f4f5aUL, 0x7733283fUL, 0xeae41086UL, - 0x525877e3UL, 0x40edd80dUL, 0xf851bf68UL, 0xf02bf8a1UL, 0x48979fc4UL, - 0x5a22302aUL, 0xe29e574fUL, 0x7f496ff6UL, 0xc7f50893UL, 0xd540a77dUL, - 0x6dfcc018UL, 0x359fd04eUL, 0x8d23b72bUL, 0x9f9618c5UL, 0x272a7fa0UL, - 0xbafd4719UL, 0x0241207cUL, 0x10f48f92UL, 0xa848e8f7UL, 0x9b14583dUL, - 0x23a83f58UL, 0x311d90b6UL, 0x89a1f7d3UL, 0x1476cf6aUL, 0xaccaa80fUL, - 0xbe7f07e1UL, 0x06c36084UL, 0x5ea070d2UL, 0xe61c17b7UL, 0xf4a9b859UL, - 0x4c15df3cUL, 0xd1c2e785UL, 0x697e80e0UL, 0x7bcb2f0eUL, 0xc377486bUL, - 0xcb0d0fa2UL, 0x73b168c7UL, 0x6104c729UL, 0xd9b8a04cUL, 0x446f98f5UL, - 0xfcd3ff90UL, 0xee66507eUL, 0x56da371bUL, 0x0eb9274dUL, 0xb6054028UL, - 0xa4b0efc6UL, 0x1c0c88a3UL, 0x81dbb01aUL, 0x3967d77fUL, 0x2bd27891UL, - 0x936e1ff4UL, 0x3b26f703UL, 0x839a9066UL, 0x912f3f88UL, 0x299358edUL, - 0xb4446054UL, 0x0cf80731UL, 0x1e4da8dfUL, 0xa6f1cfbaUL, 0xfe92dfecUL, - 0x462eb889UL, 0x549b1767UL, 0xec277002UL, 0x71f048bbUL, 0xc94c2fdeUL, - 0xdbf98030UL, 0x6345e755UL, 0x6b3fa09cUL, 0xd383c7f9UL, 0xc1366817UL, - 0x798a0f72UL, 0xe45d37cbUL, 0x5ce150aeUL, 0x4e54ff40UL, 0xf6e89825UL, - 0xae8b8873UL, 0x1637ef16UL, 0x048240f8UL, 0xbc3e279dUL, 0x21e91f24UL, - 0x99557841UL, 0x8be0d7afUL, 0x335cb0caUL, 0xed59b63bUL, 0x55e5d15eUL, - 0x47507eb0UL, 0xffec19d5UL, 0x623b216cUL, 0xda874609UL, 0xc832e9e7UL, - 0x708e8e82UL, 0x28ed9ed4UL, 0x9051f9b1UL, 0x82e4565fUL, 0x3a58313aUL, - 0xa78f0983UL, 0x1f336ee6UL, 0x0d86c108UL, 0xb53aa66dUL, 0xbd40e1a4UL, - 0x05fc86c1UL, 0x1749292fUL, 0xaff54e4aUL, 0x322276f3UL, 0x8a9e1196UL, - 0x982bbe78UL, 0x2097d91dUL, 0x78f4c94bUL, 0xc048ae2eUL, 0xd2fd01c0UL, - 0x6a4166a5UL, 0xf7965e1cUL, 0x4f2a3979UL, 0x5d9f9697UL, 0xe523f1f2UL, - 0x4d6b1905UL, 0xf5d77e60UL, 0xe762d18eUL, 0x5fdeb6ebUL, 0xc2098e52UL, - 0x7ab5e937UL, 0x680046d9UL, 0xd0bc21bcUL, 0x88df31eaUL, 0x3063568fUL, - 0x22d6f961UL, 0x9a6a9e04UL, 0x07bda6bdUL, 0xbf01c1d8UL, 0xadb46e36UL, - 0x15080953UL, 0x1d724e9aUL, 0xa5ce29ffUL, 0xb77b8611UL, 0x0fc7e174UL, - 0x9210d9cdUL, 0x2aacbea8UL, 0x38191146UL, 0x80a57623UL, 0xd8c66675UL, - 0x607a0110UL, 0x72cfaefeUL, 0xca73c99bUL, 0x57a4f122UL, 0xef189647UL, - 0xfdad39a9UL, 0x45115eccUL, 0x764dee06UL, 0xcef18963UL, 0xdc44268dUL, - 0x64f841e8UL, 0xf92f7951UL, 0x41931e34UL, 0x5326b1daUL, 0xeb9ad6bfUL, - 0xb3f9c6e9UL, 0x0b45a18cUL, 0x19f00e62UL, 0xa14c6907UL, 0x3c9b51beUL, - 0x842736dbUL, 0x96929935UL, 0x2e2efe50UL, 0x2654b999UL, 0x9ee8defcUL, - 0x8c5d7112UL, 0x34e11677UL, 0xa9362eceUL, 0x118a49abUL, 0x033fe645UL, - 0xbb838120UL, 0xe3e09176UL, 0x5b5cf613UL, 0x49e959fdUL, 0xf1553e98UL, - 0x6c820621UL, 0xd43e6144UL, 0xc68bceaaUL, 0x7e37a9cfUL, 0xd67f4138UL, - 0x6ec3265dUL, 0x7c7689b3UL, 0xc4caeed6UL, 0x591dd66fUL, 0xe1a1b10aUL, - 0xf3141ee4UL, 0x4ba87981UL, 0x13cb69d7UL, 0xab770eb2UL, 0xb9c2a15cUL, - 0x017ec639UL, 0x9ca9fe80UL, 0x241599e5UL, 0x36a0360bUL, 0x8e1c516eUL, - 0x866616a7UL, 0x3eda71c2UL, 0x2c6fde2cUL, 0x94d3b949UL, 0x090481f0UL, - 0xb1b8e695UL, 0xa30d497bUL, 0x1bb12e1eUL, 0x43d23e48UL, 0xfb6e592dUL, - 0xe9dbf6c3UL, 0x516791a6UL, 0xccb0a91fUL, 0x740cce7aUL, 0x66b96194UL, - 0xde0506f1UL - }, - { - 0x00000000UL, 0x96300777UL, 0x2c610eeeUL, 0xba510999UL, 0x19c46d07UL, - 0x8ff46a70UL, 0x35a563e9UL, 0xa395649eUL, 0x3288db0eUL, 0xa4b8dc79UL, - 0x1ee9d5e0UL, 0x88d9d297UL, 0x2b4cb609UL, 0xbd7cb17eUL, 0x072db8e7UL, - 0x911dbf90UL, 0x6410b71dUL, 0xf220b06aUL, 0x4871b9f3UL, 0xde41be84UL, - 0x7dd4da1aUL, 0xebe4dd6dUL, 0x51b5d4f4UL, 0xc785d383UL, 0x56986c13UL, - 0xc0a86b64UL, 0x7af962fdUL, 0xecc9658aUL, 0x4f5c0114UL, 0xd96c0663UL, - 0x633d0ffaUL, 0xf50d088dUL, 0xc8206e3bUL, 0x5e10694cUL, 0xe44160d5UL, - 0x727167a2UL, 0xd1e4033cUL, 0x47d4044bUL, 0xfd850dd2UL, 0x6bb50aa5UL, - 0xfaa8b535UL, 0x6c98b242UL, 0xd6c9bbdbUL, 0x40f9bcacUL, 0xe36cd832UL, - 0x755cdf45UL, 0xcf0dd6dcUL, 0x593dd1abUL, 0xac30d926UL, 0x3a00de51UL, - 0x8051d7c8UL, 0x1661d0bfUL, 0xb5f4b421UL, 0x23c4b356UL, 0x9995bacfUL, - 0x0fa5bdb8UL, 0x9eb80228UL, 0x0888055fUL, 0xb2d90cc6UL, 0x24e90bb1UL, - 0x877c6f2fUL, 0x114c6858UL, 0xab1d61c1UL, 0x3d2d66b6UL, 0x9041dc76UL, - 0x0671db01UL, 0xbc20d298UL, 0x2a10d5efUL, 0x8985b171UL, 0x1fb5b606UL, - 0xa5e4bf9fUL, 0x33d4b8e8UL, 0xa2c90778UL, 0x34f9000fUL, 0x8ea80996UL, - 0x18980ee1UL, 0xbb0d6a7fUL, 0x2d3d6d08UL, 0x976c6491UL, 0x015c63e6UL, - 0xf4516b6bUL, 0x62616c1cUL, 0xd8306585UL, 0x4e0062f2UL, 0xed95066cUL, - 0x7ba5011bUL, 0xc1f40882UL, 0x57c40ff5UL, 0xc6d9b065UL, 0x50e9b712UL, - 0xeab8be8bUL, 0x7c88b9fcUL, 0xdf1ddd62UL, 0x492dda15UL, 0xf37cd38cUL, - 0x654cd4fbUL, 0x5861b24dUL, 0xce51b53aUL, 0x7400bca3UL, 0xe230bbd4UL, - 0x41a5df4aUL, 0xd795d83dUL, 0x6dc4d1a4UL, 0xfbf4d6d3UL, 0x6ae96943UL, - 0xfcd96e34UL, 0x468867adUL, 0xd0b860daUL, 0x732d0444UL, 0xe51d0333UL, - 0x5f4c0aaaUL, 0xc97c0dddUL, 0x3c710550UL, 0xaa410227UL, 0x10100bbeUL, - 0x86200cc9UL, 0x25b56857UL, 0xb3856f20UL, 0x09d466b9UL, 0x9fe461ceUL, - 0x0ef9de5eUL, 0x98c9d929UL, 0x2298d0b0UL, 0xb4a8d7c7UL, 0x173db359UL, - 0x810db42eUL, 0x3b5cbdb7UL, 0xad6cbac0UL, 0x2083b8edUL, 0xb6b3bf9aUL, - 0x0ce2b603UL, 0x9ad2b174UL, 0x3947d5eaUL, 0xaf77d29dUL, 0x1526db04UL, - 0x8316dc73UL, 0x120b63e3UL, 0x843b6494UL, 0x3e6a6d0dUL, 0xa85a6a7aUL, - 0x0bcf0ee4UL, 0x9dff0993UL, 0x27ae000aUL, 0xb19e077dUL, 0x44930ff0UL, - 0xd2a30887UL, 0x68f2011eUL, 0xfec20669UL, 0x5d5762f7UL, 0xcb676580UL, - 0x71366c19UL, 0xe7066b6eUL, 0x761bd4feUL, 0xe02bd389UL, 0x5a7ada10UL, - 0xcc4add67UL, 0x6fdfb9f9UL, 0xf9efbe8eUL, 0x43beb717UL, 0xd58eb060UL, - 0xe8a3d6d6UL, 0x7e93d1a1UL, 0xc4c2d838UL, 0x52f2df4fUL, 0xf167bbd1UL, - 0x6757bca6UL, 0xdd06b53fUL, 0x4b36b248UL, 0xda2b0dd8UL, 0x4c1b0aafUL, - 0xf64a0336UL, 0x607a0441UL, 0xc3ef60dfUL, 0x55df67a8UL, 0xef8e6e31UL, - 0x79be6946UL, 0x8cb361cbUL, 0x1a8366bcUL, 0xa0d26f25UL, 0x36e26852UL, - 0x95770cccUL, 0x03470bbbUL, 0xb9160222UL, 0x2f260555UL, 0xbe3bbac5UL, - 0x280bbdb2UL, 0x925ab42bUL, 0x046ab35cUL, 0xa7ffd7c2UL, 0x31cfd0b5UL, - 0x8b9ed92cUL, 0x1daede5bUL, 0xb0c2649bUL, 0x26f263ecUL, 0x9ca36a75UL, - 0x0a936d02UL, 0xa906099cUL, 0x3f360eebUL, 0x85670772UL, 0x13570005UL, - 0x824abf95UL, 0x147ab8e2UL, 0xae2bb17bUL, 0x381bb60cUL, 0x9b8ed292UL, - 0x0dbed5e5UL, 0xb7efdc7cUL, 0x21dfdb0bUL, 0xd4d2d386UL, 0x42e2d4f1UL, - 0xf8b3dd68UL, 0x6e83da1fUL, 0xcd16be81UL, 0x5b26b9f6UL, 0xe177b06fUL, - 0x7747b718UL, 0xe65a0888UL, 0x706a0fffUL, 0xca3b0666UL, 0x5c0b0111UL, - 0xff9e658fUL, 0x69ae62f8UL, 0xd3ff6b61UL, 0x45cf6c16UL, 0x78e20aa0UL, - 0xeed20dd7UL, 0x5483044eUL, 0xc2b30339UL, 0x612667a7UL, 0xf71660d0UL, - 0x4d476949UL, 0xdb776e3eUL, 0x4a6ad1aeUL, 0xdc5ad6d9UL, 0x660bdf40UL, - 0xf03bd837UL, 0x53aebca9UL, 0xc59ebbdeUL, 0x7fcfb247UL, 0xe9ffb530UL, - 0x1cf2bdbdUL, 0x8ac2bacaUL, 0x3093b353UL, 0xa6a3b424UL, 0x0536d0baUL, - 0x9306d7cdUL, 0x2957de54UL, 0xbf67d923UL, 0x2e7a66b3UL, 0xb84a61c4UL, - 0x021b685dUL, 0x942b6f2aUL, 0x37be0bb4UL, 0xa18e0cc3UL, 0x1bdf055aUL, - 0x8def022dUL - }, - { - 0x00000000UL, 0x41311b19UL, 0x82623632UL, 0xc3532d2bUL, 0x04c56c64UL, - 0x45f4777dUL, 0x86a75a56UL, 0xc796414fUL, 0x088ad9c8UL, 0x49bbc2d1UL, - 0x8ae8effaUL, 0xcbd9f4e3UL, 0x0c4fb5acUL, 0x4d7eaeb5UL, 0x8e2d839eUL, - 0xcf1c9887UL, 0x5112c24aUL, 0x1023d953UL, 0xd370f478UL, 0x9241ef61UL, - 0x55d7ae2eUL, 0x14e6b537UL, 0xd7b5981cUL, 0x96848305UL, 0x59981b82UL, - 0x18a9009bUL, 0xdbfa2db0UL, 0x9acb36a9UL, 0x5d5d77e6UL, 0x1c6c6cffUL, - 0xdf3f41d4UL, 0x9e0e5acdUL, 0xa2248495UL, 0xe3159f8cUL, 0x2046b2a7UL, - 0x6177a9beUL, 0xa6e1e8f1UL, 0xe7d0f3e8UL, 0x2483dec3UL, 0x65b2c5daUL, - 0xaaae5d5dUL, 0xeb9f4644UL, 0x28cc6b6fUL, 0x69fd7076UL, 0xae6b3139UL, - 0xef5a2a20UL, 0x2c09070bUL, 0x6d381c12UL, 0xf33646dfUL, 0xb2075dc6UL, - 0x715470edUL, 0x30656bf4UL, 0xf7f32abbUL, 0xb6c231a2UL, 0x75911c89UL, - 0x34a00790UL, 0xfbbc9f17UL, 0xba8d840eUL, 0x79dea925UL, 0x38efb23cUL, - 0xff79f373UL, 0xbe48e86aUL, 0x7d1bc541UL, 0x3c2ade58UL, 0x054f79f0UL, - 0x447e62e9UL, 0x872d4fc2UL, 0xc61c54dbUL, 0x018a1594UL, 0x40bb0e8dUL, - 0x83e823a6UL, 0xc2d938bfUL, 0x0dc5a038UL, 0x4cf4bb21UL, 0x8fa7960aUL, - 0xce968d13UL, 0x0900cc5cUL, 0x4831d745UL, 0x8b62fa6eUL, 0xca53e177UL, - 0x545dbbbaUL, 0x156ca0a3UL, 0xd63f8d88UL, 0x970e9691UL, 0x5098d7deUL, - 0x11a9ccc7UL, 0xd2fae1ecUL, 0x93cbfaf5UL, 0x5cd76272UL, 0x1de6796bUL, - 0xdeb55440UL, 0x9f844f59UL, 0x58120e16UL, 0x1923150fUL, 0xda703824UL, - 0x9b41233dUL, 0xa76bfd65UL, 0xe65ae67cUL, 0x2509cb57UL, 0x6438d04eUL, - 0xa3ae9101UL, 0xe29f8a18UL, 0x21cca733UL, 0x60fdbc2aUL, 0xafe124adUL, - 0xeed03fb4UL, 0x2d83129fUL, 0x6cb20986UL, 0xab2448c9UL, 0xea1553d0UL, - 0x29467efbUL, 0x687765e2UL, 0xf6793f2fUL, 0xb7482436UL, 0x741b091dUL, - 0x352a1204UL, 0xf2bc534bUL, 0xb38d4852UL, 0x70de6579UL, 0x31ef7e60UL, - 0xfef3e6e7UL, 0xbfc2fdfeUL, 0x7c91d0d5UL, 0x3da0cbccUL, 0xfa368a83UL, - 0xbb07919aUL, 0x7854bcb1UL, 0x3965a7a8UL, 0x4b98833bUL, 0x0aa99822UL, - 0xc9fab509UL, 0x88cbae10UL, 0x4f5def5fUL, 0x0e6cf446UL, 0xcd3fd96dUL, - 0x8c0ec274UL, 0x43125af3UL, 0x022341eaUL, 0xc1706cc1UL, 0x804177d8UL, - 0x47d73697UL, 0x06e62d8eUL, 0xc5b500a5UL, 0x84841bbcUL, 0x1a8a4171UL, - 0x5bbb5a68UL, 0x98e87743UL, 0xd9d96c5aUL, 0x1e4f2d15UL, 0x5f7e360cUL, - 0x9c2d1b27UL, 0xdd1c003eUL, 0x120098b9UL, 0x533183a0UL, 0x9062ae8bUL, - 0xd153b592UL, 0x16c5f4ddUL, 0x57f4efc4UL, 0x94a7c2efUL, 0xd596d9f6UL, - 0xe9bc07aeUL, 0xa88d1cb7UL, 0x6bde319cUL, 0x2aef2a85UL, 0xed796bcaUL, - 0xac4870d3UL, 0x6f1b5df8UL, 0x2e2a46e1UL, 0xe136de66UL, 0xa007c57fUL, - 0x6354e854UL, 0x2265f34dUL, 0xe5f3b202UL, 0xa4c2a91bUL, 0x67918430UL, - 0x26a09f29UL, 0xb8aec5e4UL, 0xf99fdefdUL, 0x3accf3d6UL, 0x7bfde8cfUL, - 0xbc6ba980UL, 0xfd5ab299UL, 0x3e099fb2UL, 0x7f3884abUL, 0xb0241c2cUL, - 0xf1150735UL, 0x32462a1eUL, 0x73773107UL, 0xb4e17048UL, 0xf5d06b51UL, - 0x3683467aUL, 0x77b25d63UL, 0x4ed7facbUL, 0x0fe6e1d2UL, 0xccb5ccf9UL, - 0x8d84d7e0UL, 0x4a1296afUL, 0x0b238db6UL, 0xc870a09dUL, 0x8941bb84UL, - 0x465d2303UL, 0x076c381aUL, 0xc43f1531UL, 0x850e0e28UL, 0x42984f67UL, - 0x03a9547eUL, 0xc0fa7955UL, 0x81cb624cUL, 0x1fc53881UL, 0x5ef42398UL, - 0x9da70eb3UL, 0xdc9615aaUL, 0x1b0054e5UL, 0x5a314ffcUL, 0x996262d7UL, - 0xd85379ceUL, 0x174fe149UL, 0x567efa50UL, 0x952dd77bUL, 0xd41ccc62UL, - 0x138a8d2dUL, 0x52bb9634UL, 0x91e8bb1fUL, 0xd0d9a006UL, 0xecf37e5eUL, - 0xadc26547UL, 0x6e91486cUL, 0x2fa05375UL, 0xe836123aUL, 0xa9070923UL, - 0x6a542408UL, 0x2b653f11UL, 0xe479a796UL, 0xa548bc8fUL, 0x661b91a4UL, - 0x272a8abdUL, 0xe0bccbf2UL, 0xa18dd0ebUL, 0x62defdc0UL, 0x23efe6d9UL, - 0xbde1bc14UL, 0xfcd0a70dUL, 0x3f838a26UL, 0x7eb2913fUL, 0xb924d070UL, - 0xf815cb69UL, 0x3b46e642UL, 0x7a77fd5bUL, 0xb56b65dcUL, 0xf45a7ec5UL, - 0x370953eeUL, 0x763848f7UL, 0xb1ae09b8UL, 0xf09f12a1UL, 0x33cc3f8aUL, - 0x72fd2493UL - }, - { - 0x00000000UL, 0x376ac201UL, 0x6ed48403UL, 0x59be4602UL, 0xdca80907UL, - 0xebc2cb06UL, 0xb27c8d04UL, 0x85164f05UL, 0xb851130eUL, 0x8f3bd10fUL, - 0xd685970dUL, 0xe1ef550cUL, 0x64f91a09UL, 0x5393d808UL, 0x0a2d9e0aUL, - 0x3d475c0bUL, 0x70a3261cUL, 0x47c9e41dUL, 0x1e77a21fUL, 0x291d601eUL, - 0xac0b2f1bUL, 0x9b61ed1aUL, 0xc2dfab18UL, 0xf5b56919UL, 0xc8f23512UL, - 0xff98f713UL, 0xa626b111UL, 0x914c7310UL, 0x145a3c15UL, 0x2330fe14UL, - 0x7a8eb816UL, 0x4de47a17UL, 0xe0464d38UL, 0xd72c8f39UL, 0x8e92c93bUL, - 0xb9f80b3aUL, 0x3cee443fUL, 0x0b84863eUL, 0x523ac03cUL, 0x6550023dUL, - 0x58175e36UL, 0x6f7d9c37UL, 0x36c3da35UL, 0x01a91834UL, 0x84bf5731UL, - 0xb3d59530UL, 0xea6bd332UL, 0xdd011133UL, 0x90e56b24UL, 0xa78fa925UL, - 0xfe31ef27UL, 0xc95b2d26UL, 0x4c4d6223UL, 0x7b27a022UL, 0x2299e620UL, - 0x15f32421UL, 0x28b4782aUL, 0x1fdeba2bUL, 0x4660fc29UL, 0x710a3e28UL, - 0xf41c712dUL, 0xc376b32cUL, 0x9ac8f52eUL, 0xada2372fUL, 0xc08d9a70UL, - 0xf7e75871UL, 0xae591e73UL, 0x9933dc72UL, 0x1c259377UL, 0x2b4f5176UL, - 0x72f11774UL, 0x459bd575UL, 0x78dc897eUL, 0x4fb64b7fUL, 0x16080d7dUL, - 0x2162cf7cUL, 0xa4748079UL, 0x931e4278UL, 0xcaa0047aUL, 0xfdcac67bUL, - 0xb02ebc6cUL, 0x87447e6dUL, 0xdefa386fUL, 0xe990fa6eUL, 0x6c86b56bUL, - 0x5bec776aUL, 0x02523168UL, 0x3538f369UL, 0x087faf62UL, 0x3f156d63UL, - 0x66ab2b61UL, 0x51c1e960UL, 0xd4d7a665UL, 0xe3bd6464UL, 0xba032266UL, - 0x8d69e067UL, 0x20cbd748UL, 0x17a11549UL, 0x4e1f534bUL, 0x7975914aUL, - 0xfc63de4fUL, 0xcb091c4eUL, 0x92b75a4cUL, 0xa5dd984dUL, 0x989ac446UL, - 0xaff00647UL, 0xf64e4045UL, 0xc1248244UL, 0x4432cd41UL, 0x73580f40UL, - 0x2ae64942UL, 0x1d8c8b43UL, 0x5068f154UL, 0x67023355UL, 0x3ebc7557UL, - 0x09d6b756UL, 0x8cc0f853UL, 0xbbaa3a52UL, 0xe2147c50UL, 0xd57ebe51UL, - 0xe839e25aUL, 0xdf53205bUL, 0x86ed6659UL, 0xb187a458UL, 0x3491eb5dUL, - 0x03fb295cUL, 0x5a456f5eUL, 0x6d2fad5fUL, 0x801b35e1UL, 0xb771f7e0UL, - 0xeecfb1e2UL, 0xd9a573e3UL, 0x5cb33ce6UL, 0x6bd9fee7UL, 0x3267b8e5UL, - 0x050d7ae4UL, 0x384a26efUL, 0x0f20e4eeUL, 0x569ea2ecUL, 0x61f460edUL, - 0xe4e22fe8UL, 0xd388ede9UL, 0x8a36abebUL, 0xbd5c69eaUL, 0xf0b813fdUL, - 0xc7d2d1fcUL, 0x9e6c97feUL, 0xa90655ffUL, 0x2c101afaUL, 0x1b7ad8fbUL, - 0x42c49ef9UL, 0x75ae5cf8UL, 0x48e900f3UL, 0x7f83c2f2UL, 0x263d84f0UL, - 0x115746f1UL, 0x944109f4UL, 0xa32bcbf5UL, 0xfa958df7UL, 0xcdff4ff6UL, - 0x605d78d9UL, 0x5737bad8UL, 0x0e89fcdaUL, 0x39e33edbUL, 0xbcf571deUL, - 0x8b9fb3dfUL, 0xd221f5ddUL, 0xe54b37dcUL, 0xd80c6bd7UL, 0xef66a9d6UL, - 0xb6d8efd4UL, 0x81b22dd5UL, 0x04a462d0UL, 0x33cea0d1UL, 0x6a70e6d3UL, - 0x5d1a24d2UL, 0x10fe5ec5UL, 0x27949cc4UL, 0x7e2adac6UL, 0x494018c7UL, - 0xcc5657c2UL, 0xfb3c95c3UL, 0xa282d3c1UL, 0x95e811c0UL, 0xa8af4dcbUL, - 0x9fc58fcaUL, 0xc67bc9c8UL, 0xf1110bc9UL, 0x740744ccUL, 0x436d86cdUL, - 0x1ad3c0cfUL, 0x2db902ceUL, 0x4096af91UL, 0x77fc6d90UL, 0x2e422b92UL, - 0x1928e993UL, 0x9c3ea696UL, 0xab546497UL, 0xf2ea2295UL, 0xc580e094UL, - 0xf8c7bc9fUL, 0xcfad7e9eUL, 0x9613389cUL, 0xa179fa9dUL, 0x246fb598UL, - 0x13057799UL, 0x4abb319bUL, 0x7dd1f39aUL, 0x3035898dUL, 0x075f4b8cUL, - 0x5ee10d8eUL, 0x698bcf8fUL, 0xec9d808aUL, 0xdbf7428bUL, 0x82490489UL, - 0xb523c688UL, 0x88649a83UL, 0xbf0e5882UL, 0xe6b01e80UL, 0xd1dadc81UL, - 0x54cc9384UL, 0x63a65185UL, 0x3a181787UL, 0x0d72d586UL, 0xa0d0e2a9UL, - 0x97ba20a8UL, 0xce0466aaUL, 0xf96ea4abUL, 0x7c78ebaeUL, 0x4b1229afUL, - 0x12ac6fadUL, 0x25c6adacUL, 0x1881f1a7UL, 0x2feb33a6UL, 0x765575a4UL, - 0x413fb7a5UL, 0xc429f8a0UL, 0xf3433aa1UL, 0xaafd7ca3UL, 0x9d97bea2UL, - 0xd073c4b5UL, 0xe71906b4UL, 0xbea740b6UL, 0x89cd82b7UL, 0x0cdbcdb2UL, - 0x3bb10fb3UL, 0x620f49b1UL, 0x55658bb0UL, 0x6822d7bbUL, 0x5f4815baUL, - 0x06f653b8UL, 0x319c91b9UL, 0xb48adebcUL, 0x83e01cbdUL, 0xda5e5abfUL, - 0xed3498beUL - }, - { - 0x00000000UL, 0x6567bcb8UL, 0x8bc809aaUL, 0xeeafb512UL, 0x5797628fUL, - 0x32f0de37UL, 0xdc5f6b25UL, 0xb938d79dUL, 0xef28b4c5UL, 0x8a4f087dUL, - 0x64e0bd6fUL, 0x018701d7UL, 0xb8bfd64aUL, 0xddd86af2UL, 0x3377dfe0UL, - 0x56106358UL, 0x9f571950UL, 0xfa30a5e8UL, 0x149f10faUL, 0x71f8ac42UL, - 0xc8c07bdfUL, 0xada7c767UL, 0x43087275UL, 0x266fcecdUL, 0x707fad95UL, - 0x1518112dUL, 0xfbb7a43fUL, 0x9ed01887UL, 0x27e8cf1aUL, 0x428f73a2UL, - 0xac20c6b0UL, 0xc9477a08UL, 0x3eaf32a0UL, 0x5bc88e18UL, 0xb5673b0aUL, - 0xd00087b2UL, 0x6938502fUL, 0x0c5fec97UL, 0xe2f05985UL, 0x8797e53dUL, - 0xd1878665UL, 0xb4e03addUL, 0x5a4f8fcfUL, 0x3f283377UL, 0x8610e4eaUL, - 0xe3775852UL, 0x0dd8ed40UL, 0x68bf51f8UL, 0xa1f82bf0UL, 0xc49f9748UL, - 0x2a30225aUL, 0x4f579ee2UL, 0xf66f497fUL, 0x9308f5c7UL, 0x7da740d5UL, - 0x18c0fc6dUL, 0x4ed09f35UL, 0x2bb7238dUL, 0xc518969fUL, 0xa07f2a27UL, - 0x1947fdbaUL, 0x7c204102UL, 0x928ff410UL, 0xf7e848a8UL, 0x3d58149bUL, - 0x583fa823UL, 0xb6901d31UL, 0xd3f7a189UL, 0x6acf7614UL, 0x0fa8caacUL, - 0xe1077fbeUL, 0x8460c306UL, 0xd270a05eUL, 0xb7171ce6UL, 0x59b8a9f4UL, - 0x3cdf154cUL, 0x85e7c2d1UL, 0xe0807e69UL, 0x0e2fcb7bUL, 0x6b4877c3UL, - 0xa20f0dcbUL, 0xc768b173UL, 0x29c70461UL, 0x4ca0b8d9UL, 0xf5986f44UL, - 0x90ffd3fcUL, 0x7e5066eeUL, 0x1b37da56UL, 0x4d27b90eUL, 0x284005b6UL, - 0xc6efb0a4UL, 0xa3880c1cUL, 0x1ab0db81UL, 0x7fd76739UL, 0x9178d22bUL, - 0xf41f6e93UL, 0x03f7263bUL, 0x66909a83UL, 0x883f2f91UL, 0xed589329UL, - 0x546044b4UL, 0x3107f80cUL, 0xdfa84d1eUL, 0xbacff1a6UL, 0xecdf92feUL, - 0x89b82e46UL, 0x67179b54UL, 0x027027ecUL, 0xbb48f071UL, 0xde2f4cc9UL, - 0x3080f9dbUL, 0x55e74563UL, 0x9ca03f6bUL, 0xf9c783d3UL, 0x176836c1UL, - 0x720f8a79UL, 0xcb375de4UL, 0xae50e15cUL, 0x40ff544eUL, 0x2598e8f6UL, - 0x73888baeUL, 0x16ef3716UL, 0xf8408204UL, 0x9d273ebcUL, 0x241fe921UL, - 0x41785599UL, 0xafd7e08bUL, 0xcab05c33UL, 0x3bb659edUL, 0x5ed1e555UL, - 0xb07e5047UL, 0xd519ecffUL, 0x6c213b62UL, 0x094687daUL, 0xe7e932c8UL, - 0x828e8e70UL, 0xd49eed28UL, 0xb1f95190UL, 0x5f56e482UL, 0x3a31583aUL, - 0x83098fa7UL, 0xe66e331fUL, 0x08c1860dUL, 0x6da63ab5UL, 0xa4e140bdUL, - 0xc186fc05UL, 0x2f294917UL, 0x4a4ef5afUL, 0xf3762232UL, 0x96119e8aUL, - 0x78be2b98UL, 0x1dd99720UL, 0x4bc9f478UL, 0x2eae48c0UL, 0xc001fdd2UL, - 0xa566416aUL, 0x1c5e96f7UL, 0x79392a4fUL, 0x97969f5dUL, 0xf2f123e5UL, - 0x05196b4dUL, 0x607ed7f5UL, 0x8ed162e7UL, 0xebb6de5fUL, 0x528e09c2UL, - 0x37e9b57aUL, 0xd9460068UL, 0xbc21bcd0UL, 0xea31df88UL, 0x8f566330UL, - 0x61f9d622UL, 0x049e6a9aUL, 0xbda6bd07UL, 0xd8c101bfUL, 0x366eb4adUL, - 0x53090815UL, 0x9a4e721dUL, 0xff29cea5UL, 0x11867bb7UL, 0x74e1c70fUL, - 0xcdd91092UL, 0xa8beac2aUL, 0x46111938UL, 0x2376a580UL, 0x7566c6d8UL, - 0x10017a60UL, 0xfeaecf72UL, 0x9bc973caUL, 0x22f1a457UL, 0x479618efUL, - 0xa939adfdUL, 0xcc5e1145UL, 0x06ee4d76UL, 0x6389f1ceUL, 0x8d2644dcUL, - 0xe841f864UL, 0x51792ff9UL, 0x341e9341UL, 0xdab12653UL, 0xbfd69aebUL, - 0xe9c6f9b3UL, 0x8ca1450bUL, 0x620ef019UL, 0x07694ca1UL, 0xbe519b3cUL, - 0xdb362784UL, 0x35999296UL, 0x50fe2e2eUL, 0x99b95426UL, 0xfcdee89eUL, - 0x12715d8cUL, 0x7716e134UL, 0xce2e36a9UL, 0xab498a11UL, 0x45e63f03UL, - 0x208183bbUL, 0x7691e0e3UL, 0x13f65c5bUL, 0xfd59e949UL, 0x983e55f1UL, - 0x2106826cUL, 0x44613ed4UL, 0xaace8bc6UL, 0xcfa9377eUL, 0x38417fd6UL, - 0x5d26c36eUL, 0xb389767cUL, 0xd6eecac4UL, 0x6fd61d59UL, 0x0ab1a1e1UL, - 0xe41e14f3UL, 0x8179a84bUL, 0xd769cb13UL, 0xb20e77abUL, 0x5ca1c2b9UL, - 0x39c67e01UL, 0x80fea99cUL, 0xe5991524UL, 0x0b36a036UL, 0x6e511c8eUL, - 0xa7166686UL, 0xc271da3eUL, 0x2cde6f2cUL, 0x49b9d394UL, 0xf0810409UL, - 0x95e6b8b1UL, 0x7b490da3UL, 0x1e2eb11bUL, 0x483ed243UL, 0x2d596efbUL, - 0xc3f6dbe9UL, 0xa6916751UL, 0x1fa9b0ccUL, 0x7ace0c74UL, 0x9461b966UL, - 0xf10605deUL -#endif - } -}; +/* crc32.h -- tables for rapid CRC calculation + * Generated automatically by crc32.c + */ + +local const unsigned long FAR crc_table[TBLS][256] = +{ + { + 0x00000000UL, 0x77073096UL, 0xee0e612cUL, 0x990951baUL, 0x076dc419UL, + 0x706af48fUL, 0xe963a535UL, 0x9e6495a3UL, 0x0edb8832UL, 0x79dcb8a4UL, + 0xe0d5e91eUL, 0x97d2d988UL, 0x09b64c2bUL, 0x7eb17cbdUL, 0xe7b82d07UL, + 0x90bf1d91UL, 0x1db71064UL, 0x6ab020f2UL, 0xf3b97148UL, 0x84be41deUL, + 0x1adad47dUL, 0x6ddde4ebUL, 0xf4d4b551UL, 0x83d385c7UL, 0x136c9856UL, + 0x646ba8c0UL, 0xfd62f97aUL, 0x8a65c9ecUL, 0x14015c4fUL, 0x63066cd9UL, + 0xfa0f3d63UL, 0x8d080df5UL, 0x3b6e20c8UL, 0x4c69105eUL, 0xd56041e4UL, + 0xa2677172UL, 0x3c03e4d1UL, 0x4b04d447UL, 0xd20d85fdUL, 0xa50ab56bUL, + 0x35b5a8faUL, 0x42b2986cUL, 0xdbbbc9d6UL, 0xacbcf940UL, 0x32d86ce3UL, + 0x45df5c75UL, 0xdcd60dcfUL, 0xabd13d59UL, 0x26d930acUL, 0x51de003aUL, + 0xc8d75180UL, 0xbfd06116UL, 0x21b4f4b5UL, 0x56b3c423UL, 0xcfba9599UL, + 0xb8bda50fUL, 0x2802b89eUL, 0x5f058808UL, 0xc60cd9b2UL, 0xb10be924UL, + 0x2f6f7c87UL, 0x58684c11UL, 0xc1611dabUL, 0xb6662d3dUL, 0x76dc4190UL, + 0x01db7106UL, 0x98d220bcUL, 0xefd5102aUL, 0x71b18589UL, 0x06b6b51fUL, + 0x9fbfe4a5UL, 0xe8b8d433UL, 0x7807c9a2UL, 0x0f00f934UL, 0x9609a88eUL, + 0xe10e9818UL, 0x7f6a0dbbUL, 0x086d3d2dUL, 0x91646c97UL, 0xe6635c01UL, + 0x6b6b51f4UL, 0x1c6c6162UL, 0x856530d8UL, 0xf262004eUL, 0x6c0695edUL, + 0x1b01a57bUL, 0x8208f4c1UL, 0xf50fc457UL, 0x65b0d9c6UL, 0x12b7e950UL, + 0x8bbeb8eaUL, 0xfcb9887cUL, 0x62dd1ddfUL, 0x15da2d49UL, 0x8cd37cf3UL, + 0xfbd44c65UL, 0x4db26158UL, 0x3ab551ceUL, 0xa3bc0074UL, 0xd4bb30e2UL, + 0x4adfa541UL, 0x3dd895d7UL, 0xa4d1c46dUL, 0xd3d6f4fbUL, 0x4369e96aUL, + 0x346ed9fcUL, 0xad678846UL, 0xda60b8d0UL, 0x44042d73UL, 0x33031de5UL, + 0xaa0a4c5fUL, 0xdd0d7cc9UL, 0x5005713cUL, 0x270241aaUL, 0xbe0b1010UL, + 0xc90c2086UL, 0x5768b525UL, 0x206f85b3UL, 0xb966d409UL, 0xce61e49fUL, + 0x5edef90eUL, 0x29d9c998UL, 0xb0d09822UL, 0xc7d7a8b4UL, 0x59b33d17UL, + 0x2eb40d81UL, 0xb7bd5c3bUL, 0xc0ba6cadUL, 0xedb88320UL, 0x9abfb3b6UL, + 0x03b6e20cUL, 0x74b1d29aUL, 0xead54739UL, 0x9dd277afUL, 0x04db2615UL, + 0x73dc1683UL, 0xe3630b12UL, 0x94643b84UL, 0x0d6d6a3eUL, 0x7a6a5aa8UL, + 0xe40ecf0bUL, 0x9309ff9dUL, 0x0a00ae27UL, 0x7d079eb1UL, 0xf00f9344UL, + 0x8708a3d2UL, 0x1e01f268UL, 0x6906c2feUL, 0xf762575dUL, 0x806567cbUL, + 0x196c3671UL, 0x6e6b06e7UL, 0xfed41b76UL, 0x89d32be0UL, 0x10da7a5aUL, + 0x67dd4accUL, 0xf9b9df6fUL, 0x8ebeeff9UL, 0x17b7be43UL, 0x60b08ed5UL, + 0xd6d6a3e8UL, 0xa1d1937eUL, 0x38d8c2c4UL, 0x4fdff252UL, 0xd1bb67f1UL, + 0xa6bc5767UL, 0x3fb506ddUL, 0x48b2364bUL, 0xd80d2bdaUL, 0xaf0a1b4cUL, + 0x36034af6UL, 0x41047a60UL, 0xdf60efc3UL, 0xa867df55UL, 0x316e8eefUL, + 0x4669be79UL, 0xcb61b38cUL, 0xbc66831aUL, 0x256fd2a0UL, 0x5268e236UL, + 0xcc0c7795UL, 0xbb0b4703UL, 0x220216b9UL, 0x5505262fUL, 0xc5ba3bbeUL, + 0xb2bd0b28UL, 0x2bb45a92UL, 0x5cb36a04UL, 0xc2d7ffa7UL, 0xb5d0cf31UL, + 0x2cd99e8bUL, 0x5bdeae1dUL, 0x9b64c2b0UL, 0xec63f226UL, 0x756aa39cUL, + 0x026d930aUL, 0x9c0906a9UL, 0xeb0e363fUL, 0x72076785UL, 0x05005713UL, + 0x95bf4a82UL, 0xe2b87a14UL, 0x7bb12baeUL, 0x0cb61b38UL, 0x92d28e9bUL, + 0xe5d5be0dUL, 0x7cdcefb7UL, 0x0bdbdf21UL, 0x86d3d2d4UL, 0xf1d4e242UL, + 0x68ddb3f8UL, 0x1fda836eUL, 0x81be16cdUL, 0xf6b9265bUL, 0x6fb077e1UL, + 0x18b74777UL, 0x88085ae6UL, 0xff0f6a70UL, 0x66063bcaUL, 0x11010b5cUL, + 0x8f659effUL, 0xf862ae69UL, 0x616bffd3UL, 0x166ccf45UL, 0xa00ae278UL, + 0xd70dd2eeUL, 0x4e048354UL, 0x3903b3c2UL, 0xa7672661UL, 0xd06016f7UL, + 0x4969474dUL, 0x3e6e77dbUL, 0xaed16a4aUL, 0xd9d65adcUL, 0x40df0b66UL, + 0x37d83bf0UL, 0xa9bcae53UL, 0xdebb9ec5UL, 0x47b2cf7fUL, 0x30b5ffe9UL, + 0xbdbdf21cUL, 0xcabac28aUL, 0x53b39330UL, 0x24b4a3a6UL, 0xbad03605UL, + 0xcdd70693UL, 0x54de5729UL, 0x23d967bfUL, 0xb3667a2eUL, 0xc4614ab8UL, + 0x5d681b02UL, 0x2a6f2b94UL, 0xb40bbe37UL, 0xc30c8ea1UL, 0x5a05df1bUL, + 0x2d02ef8dUL +#ifdef BYFOUR + }, + { + 0x00000000UL, 0x191b3141UL, 0x32366282UL, 0x2b2d53c3UL, 0x646cc504UL, + 0x7d77f445UL, 0x565aa786UL, 0x4f4196c7UL, 0xc8d98a08UL, 0xd1c2bb49UL, + 0xfaefe88aUL, 0xe3f4d9cbUL, 0xacb54f0cUL, 0xb5ae7e4dUL, 0x9e832d8eUL, + 0x87981ccfUL, 0x4ac21251UL, 0x53d92310UL, 0x78f470d3UL, 0x61ef4192UL, + 0x2eaed755UL, 0x37b5e614UL, 0x1c98b5d7UL, 0x05838496UL, 0x821b9859UL, + 0x9b00a918UL, 0xb02dfadbUL, 0xa936cb9aUL, 0xe6775d5dUL, 0xff6c6c1cUL, + 0xd4413fdfUL, 0xcd5a0e9eUL, 0x958424a2UL, 0x8c9f15e3UL, 0xa7b24620UL, + 0xbea97761UL, 0xf1e8e1a6UL, 0xe8f3d0e7UL, 0xc3de8324UL, 0xdac5b265UL, + 0x5d5daeaaUL, 0x44469febUL, 0x6f6bcc28UL, 0x7670fd69UL, 0x39316baeUL, + 0x202a5aefUL, 0x0b07092cUL, 0x121c386dUL, 0xdf4636f3UL, 0xc65d07b2UL, + 0xed705471UL, 0xf46b6530UL, 0xbb2af3f7UL, 0xa231c2b6UL, 0x891c9175UL, + 0x9007a034UL, 0x179fbcfbUL, 0x0e848dbaUL, 0x25a9de79UL, 0x3cb2ef38UL, + 0x73f379ffUL, 0x6ae848beUL, 0x41c51b7dUL, 0x58de2a3cUL, 0xf0794f05UL, + 0xe9627e44UL, 0xc24f2d87UL, 0xdb541cc6UL, 0x94158a01UL, 0x8d0ebb40UL, + 0xa623e883UL, 0xbf38d9c2UL, 0x38a0c50dUL, 0x21bbf44cUL, 0x0a96a78fUL, + 0x138d96ceUL, 0x5ccc0009UL, 0x45d73148UL, 0x6efa628bUL, 0x77e153caUL, + 0xbabb5d54UL, 0xa3a06c15UL, 0x888d3fd6UL, 0x91960e97UL, 0xded79850UL, + 0xc7cca911UL, 0xece1fad2UL, 0xf5facb93UL, 0x7262d75cUL, 0x6b79e61dUL, + 0x4054b5deUL, 0x594f849fUL, 0x160e1258UL, 0x0f152319UL, 0x243870daUL, + 0x3d23419bUL, 0x65fd6ba7UL, 0x7ce65ae6UL, 0x57cb0925UL, 0x4ed03864UL, + 0x0191aea3UL, 0x188a9fe2UL, 0x33a7cc21UL, 0x2abcfd60UL, 0xad24e1afUL, + 0xb43fd0eeUL, 0x9f12832dUL, 0x8609b26cUL, 0xc94824abUL, 0xd05315eaUL, + 0xfb7e4629UL, 0xe2657768UL, 0x2f3f79f6UL, 0x362448b7UL, 0x1d091b74UL, + 0x04122a35UL, 0x4b53bcf2UL, 0x52488db3UL, 0x7965de70UL, 0x607eef31UL, + 0xe7e6f3feUL, 0xfefdc2bfUL, 0xd5d0917cUL, 0xcccba03dUL, 0x838a36faUL, + 0x9a9107bbUL, 0xb1bc5478UL, 0xa8a76539UL, 0x3b83984bUL, 0x2298a90aUL, + 0x09b5fac9UL, 0x10aecb88UL, 0x5fef5d4fUL, 0x46f46c0eUL, 0x6dd93fcdUL, + 0x74c20e8cUL, 0xf35a1243UL, 0xea412302UL, 0xc16c70c1UL, 0xd8774180UL, + 0x9736d747UL, 0x8e2de606UL, 0xa500b5c5UL, 0xbc1b8484UL, 0x71418a1aUL, + 0x685abb5bUL, 0x4377e898UL, 0x5a6cd9d9UL, 0x152d4f1eUL, 0x0c367e5fUL, + 0x271b2d9cUL, 0x3e001cddUL, 0xb9980012UL, 0xa0833153UL, 0x8bae6290UL, + 0x92b553d1UL, 0xddf4c516UL, 0xc4eff457UL, 0xefc2a794UL, 0xf6d996d5UL, + 0xae07bce9UL, 0xb71c8da8UL, 0x9c31de6bUL, 0x852aef2aUL, 0xca6b79edUL, + 0xd37048acUL, 0xf85d1b6fUL, 0xe1462a2eUL, 0x66de36e1UL, 0x7fc507a0UL, + 0x54e85463UL, 0x4df36522UL, 0x02b2f3e5UL, 0x1ba9c2a4UL, 0x30849167UL, + 0x299fa026UL, 0xe4c5aeb8UL, 0xfdde9ff9UL, 0xd6f3cc3aUL, 0xcfe8fd7bUL, + 0x80a96bbcUL, 0x99b25afdUL, 0xb29f093eUL, 0xab84387fUL, 0x2c1c24b0UL, + 0x350715f1UL, 0x1e2a4632UL, 0x07317773UL, 0x4870e1b4UL, 0x516bd0f5UL, + 0x7a468336UL, 0x635db277UL, 0xcbfad74eUL, 0xd2e1e60fUL, 0xf9ccb5ccUL, + 0xe0d7848dUL, 0xaf96124aUL, 0xb68d230bUL, 0x9da070c8UL, 0x84bb4189UL, + 0x03235d46UL, 0x1a386c07UL, 0x31153fc4UL, 0x280e0e85UL, 0x674f9842UL, + 0x7e54a903UL, 0x5579fac0UL, 0x4c62cb81UL, 0x8138c51fUL, 0x9823f45eUL, + 0xb30ea79dUL, 0xaa1596dcUL, 0xe554001bUL, 0xfc4f315aUL, 0xd7626299UL, + 0xce7953d8UL, 0x49e14f17UL, 0x50fa7e56UL, 0x7bd72d95UL, 0x62cc1cd4UL, + 0x2d8d8a13UL, 0x3496bb52UL, 0x1fbbe891UL, 0x06a0d9d0UL, 0x5e7ef3ecUL, + 0x4765c2adUL, 0x6c48916eUL, 0x7553a02fUL, 0x3a1236e8UL, 0x230907a9UL, + 0x0824546aUL, 0x113f652bUL, 0x96a779e4UL, 0x8fbc48a5UL, 0xa4911b66UL, + 0xbd8a2a27UL, 0xf2cbbce0UL, 0xebd08da1UL, 0xc0fdde62UL, 0xd9e6ef23UL, + 0x14bce1bdUL, 0x0da7d0fcUL, 0x268a833fUL, 0x3f91b27eUL, 0x70d024b9UL, + 0x69cb15f8UL, 0x42e6463bUL, 0x5bfd777aUL, 0xdc656bb5UL, 0xc57e5af4UL, + 0xee530937UL, 0xf7483876UL, 0xb809aeb1UL, 0xa1129ff0UL, 0x8a3fcc33UL, + 0x9324fd72UL + }, + { + 0x00000000UL, 0x01c26a37UL, 0x0384d46eUL, 0x0246be59UL, 0x0709a8dcUL, + 0x06cbc2ebUL, 0x048d7cb2UL, 0x054f1685UL, 0x0e1351b8UL, 0x0fd13b8fUL, + 0x0d9785d6UL, 0x0c55efe1UL, 0x091af964UL, 0x08d89353UL, 0x0a9e2d0aUL, + 0x0b5c473dUL, 0x1c26a370UL, 0x1de4c947UL, 0x1fa2771eUL, 0x1e601d29UL, + 0x1b2f0bacUL, 0x1aed619bUL, 0x18abdfc2UL, 0x1969b5f5UL, 0x1235f2c8UL, + 0x13f798ffUL, 0x11b126a6UL, 0x10734c91UL, 0x153c5a14UL, 0x14fe3023UL, + 0x16b88e7aUL, 0x177ae44dUL, 0x384d46e0UL, 0x398f2cd7UL, 0x3bc9928eUL, + 0x3a0bf8b9UL, 0x3f44ee3cUL, 0x3e86840bUL, 0x3cc03a52UL, 0x3d025065UL, + 0x365e1758UL, 0x379c7d6fUL, 0x35dac336UL, 0x3418a901UL, 0x3157bf84UL, + 0x3095d5b3UL, 0x32d36beaUL, 0x331101ddUL, 0x246be590UL, 0x25a98fa7UL, + 0x27ef31feUL, 0x262d5bc9UL, 0x23624d4cUL, 0x22a0277bUL, 0x20e69922UL, + 0x2124f315UL, 0x2a78b428UL, 0x2bbade1fUL, 0x29fc6046UL, 0x283e0a71UL, + 0x2d711cf4UL, 0x2cb376c3UL, 0x2ef5c89aUL, 0x2f37a2adUL, 0x709a8dc0UL, + 0x7158e7f7UL, 0x731e59aeUL, 0x72dc3399UL, 0x7793251cUL, 0x76514f2bUL, + 0x7417f172UL, 0x75d59b45UL, 0x7e89dc78UL, 0x7f4bb64fUL, 0x7d0d0816UL, + 0x7ccf6221UL, 0x798074a4UL, 0x78421e93UL, 0x7a04a0caUL, 0x7bc6cafdUL, + 0x6cbc2eb0UL, 0x6d7e4487UL, 0x6f38fadeUL, 0x6efa90e9UL, 0x6bb5866cUL, + 0x6a77ec5bUL, 0x68315202UL, 0x69f33835UL, 0x62af7f08UL, 0x636d153fUL, + 0x612bab66UL, 0x60e9c151UL, 0x65a6d7d4UL, 0x6464bde3UL, 0x662203baUL, + 0x67e0698dUL, 0x48d7cb20UL, 0x4915a117UL, 0x4b531f4eUL, 0x4a917579UL, + 0x4fde63fcUL, 0x4e1c09cbUL, 0x4c5ab792UL, 0x4d98dda5UL, 0x46c49a98UL, + 0x4706f0afUL, 0x45404ef6UL, 0x448224c1UL, 0x41cd3244UL, 0x400f5873UL, + 0x4249e62aUL, 0x438b8c1dUL, 0x54f16850UL, 0x55330267UL, 0x5775bc3eUL, + 0x56b7d609UL, 0x53f8c08cUL, 0x523aaabbUL, 0x507c14e2UL, 0x51be7ed5UL, + 0x5ae239e8UL, 0x5b2053dfUL, 0x5966ed86UL, 0x58a487b1UL, 0x5deb9134UL, + 0x5c29fb03UL, 0x5e6f455aUL, 0x5fad2f6dUL, 0xe1351b80UL, 0xe0f771b7UL, + 0xe2b1cfeeUL, 0xe373a5d9UL, 0xe63cb35cUL, 0xe7fed96bUL, 0xe5b86732UL, + 0xe47a0d05UL, 0xef264a38UL, 0xeee4200fUL, 0xeca29e56UL, 0xed60f461UL, + 0xe82fe2e4UL, 0xe9ed88d3UL, 0xebab368aUL, 0xea695cbdUL, 0xfd13b8f0UL, + 0xfcd1d2c7UL, 0xfe976c9eUL, 0xff5506a9UL, 0xfa1a102cUL, 0xfbd87a1bUL, + 0xf99ec442UL, 0xf85cae75UL, 0xf300e948UL, 0xf2c2837fUL, 0xf0843d26UL, + 0xf1465711UL, 0xf4094194UL, 0xf5cb2ba3UL, 0xf78d95faUL, 0xf64fffcdUL, + 0xd9785d60UL, 0xd8ba3757UL, 0xdafc890eUL, 0xdb3ee339UL, 0xde71f5bcUL, + 0xdfb39f8bUL, 0xddf521d2UL, 0xdc374be5UL, 0xd76b0cd8UL, 0xd6a966efUL, + 0xd4efd8b6UL, 0xd52db281UL, 0xd062a404UL, 0xd1a0ce33UL, 0xd3e6706aUL, + 0xd2241a5dUL, 0xc55efe10UL, 0xc49c9427UL, 0xc6da2a7eUL, 0xc7184049UL, + 0xc25756ccUL, 0xc3953cfbUL, 0xc1d382a2UL, 0xc011e895UL, 0xcb4dafa8UL, + 0xca8fc59fUL, 0xc8c97bc6UL, 0xc90b11f1UL, 0xcc440774UL, 0xcd866d43UL, + 0xcfc0d31aUL, 0xce02b92dUL, 0x91af9640UL, 0x906dfc77UL, 0x922b422eUL, + 0x93e92819UL, 0x96a63e9cUL, 0x976454abUL, 0x9522eaf2UL, 0x94e080c5UL, + 0x9fbcc7f8UL, 0x9e7eadcfUL, 0x9c381396UL, 0x9dfa79a1UL, 0x98b56f24UL, + 0x99770513UL, 0x9b31bb4aUL, 0x9af3d17dUL, 0x8d893530UL, 0x8c4b5f07UL, + 0x8e0de15eUL, 0x8fcf8b69UL, 0x8a809decUL, 0x8b42f7dbUL, 0x89044982UL, + 0x88c623b5UL, 0x839a6488UL, 0x82580ebfUL, 0x801eb0e6UL, 0x81dcdad1UL, + 0x8493cc54UL, 0x8551a663UL, 0x8717183aUL, 0x86d5720dUL, 0xa9e2d0a0UL, + 0xa820ba97UL, 0xaa6604ceUL, 0xaba46ef9UL, 0xaeeb787cUL, 0xaf29124bUL, + 0xad6fac12UL, 0xacadc625UL, 0xa7f18118UL, 0xa633eb2fUL, 0xa4755576UL, + 0xa5b73f41UL, 0xa0f829c4UL, 0xa13a43f3UL, 0xa37cfdaaUL, 0xa2be979dUL, + 0xb5c473d0UL, 0xb40619e7UL, 0xb640a7beUL, 0xb782cd89UL, 0xb2cddb0cUL, + 0xb30fb13bUL, 0xb1490f62UL, 0xb08b6555UL, 0xbbd72268UL, 0xba15485fUL, + 0xb853f606UL, 0xb9919c31UL, 0xbcde8ab4UL, 0xbd1ce083UL, 0xbf5a5edaUL, + 0xbe9834edUL + }, + { + 0x00000000UL, 0xb8bc6765UL, 0xaa09c88bUL, 0x12b5afeeUL, 0x8f629757UL, + 0x37def032UL, 0x256b5fdcUL, 0x9dd738b9UL, 0xc5b428efUL, 0x7d084f8aUL, + 0x6fbde064UL, 0xd7018701UL, 0x4ad6bfb8UL, 0xf26ad8ddUL, 0xe0df7733UL, + 0x58631056UL, 0x5019579fUL, 0xe8a530faUL, 0xfa109f14UL, 0x42acf871UL, + 0xdf7bc0c8UL, 0x67c7a7adUL, 0x75720843UL, 0xcdce6f26UL, 0x95ad7f70UL, + 0x2d111815UL, 0x3fa4b7fbUL, 0x8718d09eUL, 0x1acfe827UL, 0xa2738f42UL, + 0xb0c620acUL, 0x087a47c9UL, 0xa032af3eUL, 0x188ec85bUL, 0x0a3b67b5UL, + 0xb28700d0UL, 0x2f503869UL, 0x97ec5f0cUL, 0x8559f0e2UL, 0x3de59787UL, + 0x658687d1UL, 0xdd3ae0b4UL, 0xcf8f4f5aUL, 0x7733283fUL, 0xeae41086UL, + 0x525877e3UL, 0x40edd80dUL, 0xf851bf68UL, 0xf02bf8a1UL, 0x48979fc4UL, + 0x5a22302aUL, 0xe29e574fUL, 0x7f496ff6UL, 0xc7f50893UL, 0xd540a77dUL, + 0x6dfcc018UL, 0x359fd04eUL, 0x8d23b72bUL, 0x9f9618c5UL, 0x272a7fa0UL, + 0xbafd4719UL, 0x0241207cUL, 0x10f48f92UL, 0xa848e8f7UL, 0x9b14583dUL, + 0x23a83f58UL, 0x311d90b6UL, 0x89a1f7d3UL, 0x1476cf6aUL, 0xaccaa80fUL, + 0xbe7f07e1UL, 0x06c36084UL, 0x5ea070d2UL, 0xe61c17b7UL, 0xf4a9b859UL, + 0x4c15df3cUL, 0xd1c2e785UL, 0x697e80e0UL, 0x7bcb2f0eUL, 0xc377486bUL, + 0xcb0d0fa2UL, 0x73b168c7UL, 0x6104c729UL, 0xd9b8a04cUL, 0x446f98f5UL, + 0xfcd3ff90UL, 0xee66507eUL, 0x56da371bUL, 0x0eb9274dUL, 0xb6054028UL, + 0xa4b0efc6UL, 0x1c0c88a3UL, 0x81dbb01aUL, 0x3967d77fUL, 0x2bd27891UL, + 0x936e1ff4UL, 0x3b26f703UL, 0x839a9066UL, 0x912f3f88UL, 0x299358edUL, + 0xb4446054UL, 0x0cf80731UL, 0x1e4da8dfUL, 0xa6f1cfbaUL, 0xfe92dfecUL, + 0x462eb889UL, 0x549b1767UL, 0xec277002UL, 0x71f048bbUL, 0xc94c2fdeUL, + 0xdbf98030UL, 0x6345e755UL, 0x6b3fa09cUL, 0xd383c7f9UL, 0xc1366817UL, + 0x798a0f72UL, 0xe45d37cbUL, 0x5ce150aeUL, 0x4e54ff40UL, 0xf6e89825UL, + 0xae8b8873UL, 0x1637ef16UL, 0x048240f8UL, 0xbc3e279dUL, 0x21e91f24UL, + 0x99557841UL, 0x8be0d7afUL, 0x335cb0caUL, 0xed59b63bUL, 0x55e5d15eUL, + 0x47507eb0UL, 0xffec19d5UL, 0x623b216cUL, 0xda874609UL, 0xc832e9e7UL, + 0x708e8e82UL, 0x28ed9ed4UL, 0x9051f9b1UL, 0x82e4565fUL, 0x3a58313aUL, + 0xa78f0983UL, 0x1f336ee6UL, 0x0d86c108UL, 0xb53aa66dUL, 0xbd40e1a4UL, + 0x05fc86c1UL, 0x1749292fUL, 0xaff54e4aUL, 0x322276f3UL, 0x8a9e1196UL, + 0x982bbe78UL, 0x2097d91dUL, 0x78f4c94bUL, 0xc048ae2eUL, 0xd2fd01c0UL, + 0x6a4166a5UL, 0xf7965e1cUL, 0x4f2a3979UL, 0x5d9f9697UL, 0xe523f1f2UL, + 0x4d6b1905UL, 0xf5d77e60UL, 0xe762d18eUL, 0x5fdeb6ebUL, 0xc2098e52UL, + 0x7ab5e937UL, 0x680046d9UL, 0xd0bc21bcUL, 0x88df31eaUL, 0x3063568fUL, + 0x22d6f961UL, 0x9a6a9e04UL, 0x07bda6bdUL, 0xbf01c1d8UL, 0xadb46e36UL, + 0x15080953UL, 0x1d724e9aUL, 0xa5ce29ffUL, 0xb77b8611UL, 0x0fc7e174UL, + 0x9210d9cdUL, 0x2aacbea8UL, 0x38191146UL, 0x80a57623UL, 0xd8c66675UL, + 0x607a0110UL, 0x72cfaefeUL, 0xca73c99bUL, 0x57a4f122UL, 0xef189647UL, + 0xfdad39a9UL, 0x45115eccUL, 0x764dee06UL, 0xcef18963UL, 0xdc44268dUL, + 0x64f841e8UL, 0xf92f7951UL, 0x41931e34UL, 0x5326b1daUL, 0xeb9ad6bfUL, + 0xb3f9c6e9UL, 0x0b45a18cUL, 0x19f00e62UL, 0xa14c6907UL, 0x3c9b51beUL, + 0x842736dbUL, 0x96929935UL, 0x2e2efe50UL, 0x2654b999UL, 0x9ee8defcUL, + 0x8c5d7112UL, 0x34e11677UL, 0xa9362eceUL, 0x118a49abUL, 0x033fe645UL, + 0xbb838120UL, 0xe3e09176UL, 0x5b5cf613UL, 0x49e959fdUL, 0xf1553e98UL, + 0x6c820621UL, 0xd43e6144UL, 0xc68bceaaUL, 0x7e37a9cfUL, 0xd67f4138UL, + 0x6ec3265dUL, 0x7c7689b3UL, 0xc4caeed6UL, 0x591dd66fUL, 0xe1a1b10aUL, + 0xf3141ee4UL, 0x4ba87981UL, 0x13cb69d7UL, 0xab770eb2UL, 0xb9c2a15cUL, + 0x017ec639UL, 0x9ca9fe80UL, 0x241599e5UL, 0x36a0360bUL, 0x8e1c516eUL, + 0x866616a7UL, 0x3eda71c2UL, 0x2c6fde2cUL, 0x94d3b949UL, 0x090481f0UL, + 0xb1b8e695UL, 0xa30d497bUL, 0x1bb12e1eUL, 0x43d23e48UL, 0xfb6e592dUL, + 0xe9dbf6c3UL, 0x516791a6UL, 0xccb0a91fUL, 0x740cce7aUL, 0x66b96194UL, + 0xde0506f1UL + }, + { + 0x00000000UL, 0x96300777UL, 0x2c610eeeUL, 0xba510999UL, 0x19c46d07UL, + 0x8ff46a70UL, 0x35a563e9UL, 0xa395649eUL, 0x3288db0eUL, 0xa4b8dc79UL, + 0x1ee9d5e0UL, 0x88d9d297UL, 0x2b4cb609UL, 0xbd7cb17eUL, 0x072db8e7UL, + 0x911dbf90UL, 0x6410b71dUL, 0xf220b06aUL, 0x4871b9f3UL, 0xde41be84UL, + 0x7dd4da1aUL, 0xebe4dd6dUL, 0x51b5d4f4UL, 0xc785d383UL, 0x56986c13UL, + 0xc0a86b64UL, 0x7af962fdUL, 0xecc9658aUL, 0x4f5c0114UL, 0xd96c0663UL, + 0x633d0ffaUL, 0xf50d088dUL, 0xc8206e3bUL, 0x5e10694cUL, 0xe44160d5UL, + 0x727167a2UL, 0xd1e4033cUL, 0x47d4044bUL, 0xfd850dd2UL, 0x6bb50aa5UL, + 0xfaa8b535UL, 0x6c98b242UL, 0xd6c9bbdbUL, 0x40f9bcacUL, 0xe36cd832UL, + 0x755cdf45UL, 0xcf0dd6dcUL, 0x593dd1abUL, 0xac30d926UL, 0x3a00de51UL, + 0x8051d7c8UL, 0x1661d0bfUL, 0xb5f4b421UL, 0x23c4b356UL, 0x9995bacfUL, + 0x0fa5bdb8UL, 0x9eb80228UL, 0x0888055fUL, 0xb2d90cc6UL, 0x24e90bb1UL, + 0x877c6f2fUL, 0x114c6858UL, 0xab1d61c1UL, 0x3d2d66b6UL, 0x9041dc76UL, + 0x0671db01UL, 0xbc20d298UL, 0x2a10d5efUL, 0x8985b171UL, 0x1fb5b606UL, + 0xa5e4bf9fUL, 0x33d4b8e8UL, 0xa2c90778UL, 0x34f9000fUL, 0x8ea80996UL, + 0x18980ee1UL, 0xbb0d6a7fUL, 0x2d3d6d08UL, 0x976c6491UL, 0x015c63e6UL, + 0xf4516b6bUL, 0x62616c1cUL, 0xd8306585UL, 0x4e0062f2UL, 0xed95066cUL, + 0x7ba5011bUL, 0xc1f40882UL, 0x57c40ff5UL, 0xc6d9b065UL, 0x50e9b712UL, + 0xeab8be8bUL, 0x7c88b9fcUL, 0xdf1ddd62UL, 0x492dda15UL, 0xf37cd38cUL, + 0x654cd4fbUL, 0x5861b24dUL, 0xce51b53aUL, 0x7400bca3UL, 0xe230bbd4UL, + 0x41a5df4aUL, 0xd795d83dUL, 0x6dc4d1a4UL, 0xfbf4d6d3UL, 0x6ae96943UL, + 0xfcd96e34UL, 0x468867adUL, 0xd0b860daUL, 0x732d0444UL, 0xe51d0333UL, + 0x5f4c0aaaUL, 0xc97c0dddUL, 0x3c710550UL, 0xaa410227UL, 0x10100bbeUL, + 0x86200cc9UL, 0x25b56857UL, 0xb3856f20UL, 0x09d466b9UL, 0x9fe461ceUL, + 0x0ef9de5eUL, 0x98c9d929UL, 0x2298d0b0UL, 0xb4a8d7c7UL, 0x173db359UL, + 0x810db42eUL, 0x3b5cbdb7UL, 0xad6cbac0UL, 0x2083b8edUL, 0xb6b3bf9aUL, + 0x0ce2b603UL, 0x9ad2b174UL, 0x3947d5eaUL, 0xaf77d29dUL, 0x1526db04UL, + 0x8316dc73UL, 0x120b63e3UL, 0x843b6494UL, 0x3e6a6d0dUL, 0xa85a6a7aUL, + 0x0bcf0ee4UL, 0x9dff0993UL, 0x27ae000aUL, 0xb19e077dUL, 0x44930ff0UL, + 0xd2a30887UL, 0x68f2011eUL, 0xfec20669UL, 0x5d5762f7UL, 0xcb676580UL, + 0x71366c19UL, 0xe7066b6eUL, 0x761bd4feUL, 0xe02bd389UL, 0x5a7ada10UL, + 0xcc4add67UL, 0x6fdfb9f9UL, 0xf9efbe8eUL, 0x43beb717UL, 0xd58eb060UL, + 0xe8a3d6d6UL, 0x7e93d1a1UL, 0xc4c2d838UL, 0x52f2df4fUL, 0xf167bbd1UL, + 0x6757bca6UL, 0xdd06b53fUL, 0x4b36b248UL, 0xda2b0dd8UL, 0x4c1b0aafUL, + 0xf64a0336UL, 0x607a0441UL, 0xc3ef60dfUL, 0x55df67a8UL, 0xef8e6e31UL, + 0x79be6946UL, 0x8cb361cbUL, 0x1a8366bcUL, 0xa0d26f25UL, 0x36e26852UL, + 0x95770cccUL, 0x03470bbbUL, 0xb9160222UL, 0x2f260555UL, 0xbe3bbac5UL, + 0x280bbdb2UL, 0x925ab42bUL, 0x046ab35cUL, 0xa7ffd7c2UL, 0x31cfd0b5UL, + 0x8b9ed92cUL, 0x1daede5bUL, 0xb0c2649bUL, 0x26f263ecUL, 0x9ca36a75UL, + 0x0a936d02UL, 0xa906099cUL, 0x3f360eebUL, 0x85670772UL, 0x13570005UL, + 0x824abf95UL, 0x147ab8e2UL, 0xae2bb17bUL, 0x381bb60cUL, 0x9b8ed292UL, + 0x0dbed5e5UL, 0xb7efdc7cUL, 0x21dfdb0bUL, 0xd4d2d386UL, 0x42e2d4f1UL, + 0xf8b3dd68UL, 0x6e83da1fUL, 0xcd16be81UL, 0x5b26b9f6UL, 0xe177b06fUL, + 0x7747b718UL, 0xe65a0888UL, 0x706a0fffUL, 0xca3b0666UL, 0x5c0b0111UL, + 0xff9e658fUL, 0x69ae62f8UL, 0xd3ff6b61UL, 0x45cf6c16UL, 0x78e20aa0UL, + 0xeed20dd7UL, 0x5483044eUL, 0xc2b30339UL, 0x612667a7UL, 0xf71660d0UL, + 0x4d476949UL, 0xdb776e3eUL, 0x4a6ad1aeUL, 0xdc5ad6d9UL, 0x660bdf40UL, + 0xf03bd837UL, 0x53aebca9UL, 0xc59ebbdeUL, 0x7fcfb247UL, 0xe9ffb530UL, + 0x1cf2bdbdUL, 0x8ac2bacaUL, 0x3093b353UL, 0xa6a3b424UL, 0x0536d0baUL, + 0x9306d7cdUL, 0x2957de54UL, 0xbf67d923UL, 0x2e7a66b3UL, 0xb84a61c4UL, + 0x021b685dUL, 0x942b6f2aUL, 0x37be0bb4UL, 0xa18e0cc3UL, 0x1bdf055aUL, + 0x8def022dUL + }, + { + 0x00000000UL, 0x41311b19UL, 0x82623632UL, 0xc3532d2bUL, 0x04c56c64UL, + 0x45f4777dUL, 0x86a75a56UL, 0xc796414fUL, 0x088ad9c8UL, 0x49bbc2d1UL, + 0x8ae8effaUL, 0xcbd9f4e3UL, 0x0c4fb5acUL, 0x4d7eaeb5UL, 0x8e2d839eUL, + 0xcf1c9887UL, 0x5112c24aUL, 0x1023d953UL, 0xd370f478UL, 0x9241ef61UL, + 0x55d7ae2eUL, 0x14e6b537UL, 0xd7b5981cUL, 0x96848305UL, 0x59981b82UL, + 0x18a9009bUL, 0xdbfa2db0UL, 0x9acb36a9UL, 0x5d5d77e6UL, 0x1c6c6cffUL, + 0xdf3f41d4UL, 0x9e0e5acdUL, 0xa2248495UL, 0xe3159f8cUL, 0x2046b2a7UL, + 0x6177a9beUL, 0xa6e1e8f1UL, 0xe7d0f3e8UL, 0x2483dec3UL, 0x65b2c5daUL, + 0xaaae5d5dUL, 0xeb9f4644UL, 0x28cc6b6fUL, 0x69fd7076UL, 0xae6b3139UL, + 0xef5a2a20UL, 0x2c09070bUL, 0x6d381c12UL, 0xf33646dfUL, 0xb2075dc6UL, + 0x715470edUL, 0x30656bf4UL, 0xf7f32abbUL, 0xb6c231a2UL, 0x75911c89UL, + 0x34a00790UL, 0xfbbc9f17UL, 0xba8d840eUL, 0x79dea925UL, 0x38efb23cUL, + 0xff79f373UL, 0xbe48e86aUL, 0x7d1bc541UL, 0x3c2ade58UL, 0x054f79f0UL, + 0x447e62e9UL, 0x872d4fc2UL, 0xc61c54dbUL, 0x018a1594UL, 0x40bb0e8dUL, + 0x83e823a6UL, 0xc2d938bfUL, 0x0dc5a038UL, 0x4cf4bb21UL, 0x8fa7960aUL, + 0xce968d13UL, 0x0900cc5cUL, 0x4831d745UL, 0x8b62fa6eUL, 0xca53e177UL, + 0x545dbbbaUL, 0x156ca0a3UL, 0xd63f8d88UL, 0x970e9691UL, 0x5098d7deUL, + 0x11a9ccc7UL, 0xd2fae1ecUL, 0x93cbfaf5UL, 0x5cd76272UL, 0x1de6796bUL, + 0xdeb55440UL, 0x9f844f59UL, 0x58120e16UL, 0x1923150fUL, 0xda703824UL, + 0x9b41233dUL, 0xa76bfd65UL, 0xe65ae67cUL, 0x2509cb57UL, 0x6438d04eUL, + 0xa3ae9101UL, 0xe29f8a18UL, 0x21cca733UL, 0x60fdbc2aUL, 0xafe124adUL, + 0xeed03fb4UL, 0x2d83129fUL, 0x6cb20986UL, 0xab2448c9UL, 0xea1553d0UL, + 0x29467efbUL, 0x687765e2UL, 0xf6793f2fUL, 0xb7482436UL, 0x741b091dUL, + 0x352a1204UL, 0xf2bc534bUL, 0xb38d4852UL, 0x70de6579UL, 0x31ef7e60UL, + 0xfef3e6e7UL, 0xbfc2fdfeUL, 0x7c91d0d5UL, 0x3da0cbccUL, 0xfa368a83UL, + 0xbb07919aUL, 0x7854bcb1UL, 0x3965a7a8UL, 0x4b98833bUL, 0x0aa99822UL, + 0xc9fab509UL, 0x88cbae10UL, 0x4f5def5fUL, 0x0e6cf446UL, 0xcd3fd96dUL, + 0x8c0ec274UL, 0x43125af3UL, 0x022341eaUL, 0xc1706cc1UL, 0x804177d8UL, + 0x47d73697UL, 0x06e62d8eUL, 0xc5b500a5UL, 0x84841bbcUL, 0x1a8a4171UL, + 0x5bbb5a68UL, 0x98e87743UL, 0xd9d96c5aUL, 0x1e4f2d15UL, 0x5f7e360cUL, + 0x9c2d1b27UL, 0xdd1c003eUL, 0x120098b9UL, 0x533183a0UL, 0x9062ae8bUL, + 0xd153b592UL, 0x16c5f4ddUL, 0x57f4efc4UL, 0x94a7c2efUL, 0xd596d9f6UL, + 0xe9bc07aeUL, 0xa88d1cb7UL, 0x6bde319cUL, 0x2aef2a85UL, 0xed796bcaUL, + 0xac4870d3UL, 0x6f1b5df8UL, 0x2e2a46e1UL, 0xe136de66UL, 0xa007c57fUL, + 0x6354e854UL, 0x2265f34dUL, 0xe5f3b202UL, 0xa4c2a91bUL, 0x67918430UL, + 0x26a09f29UL, 0xb8aec5e4UL, 0xf99fdefdUL, 0x3accf3d6UL, 0x7bfde8cfUL, + 0xbc6ba980UL, 0xfd5ab299UL, 0x3e099fb2UL, 0x7f3884abUL, 0xb0241c2cUL, + 0xf1150735UL, 0x32462a1eUL, 0x73773107UL, 0xb4e17048UL, 0xf5d06b51UL, + 0x3683467aUL, 0x77b25d63UL, 0x4ed7facbUL, 0x0fe6e1d2UL, 0xccb5ccf9UL, + 0x8d84d7e0UL, 0x4a1296afUL, 0x0b238db6UL, 0xc870a09dUL, 0x8941bb84UL, + 0x465d2303UL, 0x076c381aUL, 0xc43f1531UL, 0x850e0e28UL, 0x42984f67UL, + 0x03a9547eUL, 0xc0fa7955UL, 0x81cb624cUL, 0x1fc53881UL, 0x5ef42398UL, + 0x9da70eb3UL, 0xdc9615aaUL, 0x1b0054e5UL, 0x5a314ffcUL, 0x996262d7UL, + 0xd85379ceUL, 0x174fe149UL, 0x567efa50UL, 0x952dd77bUL, 0xd41ccc62UL, + 0x138a8d2dUL, 0x52bb9634UL, 0x91e8bb1fUL, 0xd0d9a006UL, 0xecf37e5eUL, + 0xadc26547UL, 0x6e91486cUL, 0x2fa05375UL, 0xe836123aUL, 0xa9070923UL, + 0x6a542408UL, 0x2b653f11UL, 0xe479a796UL, 0xa548bc8fUL, 0x661b91a4UL, + 0x272a8abdUL, 0xe0bccbf2UL, 0xa18dd0ebUL, 0x62defdc0UL, 0x23efe6d9UL, + 0xbde1bc14UL, 0xfcd0a70dUL, 0x3f838a26UL, 0x7eb2913fUL, 0xb924d070UL, + 0xf815cb69UL, 0x3b46e642UL, 0x7a77fd5bUL, 0xb56b65dcUL, 0xf45a7ec5UL, + 0x370953eeUL, 0x763848f7UL, 0xb1ae09b8UL, 0xf09f12a1UL, 0x33cc3f8aUL, + 0x72fd2493UL + }, + { + 0x00000000UL, 0x376ac201UL, 0x6ed48403UL, 0x59be4602UL, 0xdca80907UL, + 0xebc2cb06UL, 0xb27c8d04UL, 0x85164f05UL, 0xb851130eUL, 0x8f3bd10fUL, + 0xd685970dUL, 0xe1ef550cUL, 0x64f91a09UL, 0x5393d808UL, 0x0a2d9e0aUL, + 0x3d475c0bUL, 0x70a3261cUL, 0x47c9e41dUL, 0x1e77a21fUL, 0x291d601eUL, + 0xac0b2f1bUL, 0x9b61ed1aUL, 0xc2dfab18UL, 0xf5b56919UL, 0xc8f23512UL, + 0xff98f713UL, 0xa626b111UL, 0x914c7310UL, 0x145a3c15UL, 0x2330fe14UL, + 0x7a8eb816UL, 0x4de47a17UL, 0xe0464d38UL, 0xd72c8f39UL, 0x8e92c93bUL, + 0xb9f80b3aUL, 0x3cee443fUL, 0x0b84863eUL, 0x523ac03cUL, 0x6550023dUL, + 0x58175e36UL, 0x6f7d9c37UL, 0x36c3da35UL, 0x01a91834UL, 0x84bf5731UL, + 0xb3d59530UL, 0xea6bd332UL, 0xdd011133UL, 0x90e56b24UL, 0xa78fa925UL, + 0xfe31ef27UL, 0xc95b2d26UL, 0x4c4d6223UL, 0x7b27a022UL, 0x2299e620UL, + 0x15f32421UL, 0x28b4782aUL, 0x1fdeba2bUL, 0x4660fc29UL, 0x710a3e28UL, + 0xf41c712dUL, 0xc376b32cUL, 0x9ac8f52eUL, 0xada2372fUL, 0xc08d9a70UL, + 0xf7e75871UL, 0xae591e73UL, 0x9933dc72UL, 0x1c259377UL, 0x2b4f5176UL, + 0x72f11774UL, 0x459bd575UL, 0x78dc897eUL, 0x4fb64b7fUL, 0x16080d7dUL, + 0x2162cf7cUL, 0xa4748079UL, 0x931e4278UL, 0xcaa0047aUL, 0xfdcac67bUL, + 0xb02ebc6cUL, 0x87447e6dUL, 0xdefa386fUL, 0xe990fa6eUL, 0x6c86b56bUL, + 0x5bec776aUL, 0x02523168UL, 0x3538f369UL, 0x087faf62UL, 0x3f156d63UL, + 0x66ab2b61UL, 0x51c1e960UL, 0xd4d7a665UL, 0xe3bd6464UL, 0xba032266UL, + 0x8d69e067UL, 0x20cbd748UL, 0x17a11549UL, 0x4e1f534bUL, 0x7975914aUL, + 0xfc63de4fUL, 0xcb091c4eUL, 0x92b75a4cUL, 0xa5dd984dUL, 0x989ac446UL, + 0xaff00647UL, 0xf64e4045UL, 0xc1248244UL, 0x4432cd41UL, 0x73580f40UL, + 0x2ae64942UL, 0x1d8c8b43UL, 0x5068f154UL, 0x67023355UL, 0x3ebc7557UL, + 0x09d6b756UL, 0x8cc0f853UL, 0xbbaa3a52UL, 0xe2147c50UL, 0xd57ebe51UL, + 0xe839e25aUL, 0xdf53205bUL, 0x86ed6659UL, 0xb187a458UL, 0x3491eb5dUL, + 0x03fb295cUL, 0x5a456f5eUL, 0x6d2fad5fUL, 0x801b35e1UL, 0xb771f7e0UL, + 0xeecfb1e2UL, 0xd9a573e3UL, 0x5cb33ce6UL, 0x6bd9fee7UL, 0x3267b8e5UL, + 0x050d7ae4UL, 0x384a26efUL, 0x0f20e4eeUL, 0x569ea2ecUL, 0x61f460edUL, + 0xe4e22fe8UL, 0xd388ede9UL, 0x8a36abebUL, 0xbd5c69eaUL, 0xf0b813fdUL, + 0xc7d2d1fcUL, 0x9e6c97feUL, 0xa90655ffUL, 0x2c101afaUL, 0x1b7ad8fbUL, + 0x42c49ef9UL, 0x75ae5cf8UL, 0x48e900f3UL, 0x7f83c2f2UL, 0x263d84f0UL, + 0x115746f1UL, 0x944109f4UL, 0xa32bcbf5UL, 0xfa958df7UL, 0xcdff4ff6UL, + 0x605d78d9UL, 0x5737bad8UL, 0x0e89fcdaUL, 0x39e33edbUL, 0xbcf571deUL, + 0x8b9fb3dfUL, 0xd221f5ddUL, 0xe54b37dcUL, 0xd80c6bd7UL, 0xef66a9d6UL, + 0xb6d8efd4UL, 0x81b22dd5UL, 0x04a462d0UL, 0x33cea0d1UL, 0x6a70e6d3UL, + 0x5d1a24d2UL, 0x10fe5ec5UL, 0x27949cc4UL, 0x7e2adac6UL, 0x494018c7UL, + 0xcc5657c2UL, 0xfb3c95c3UL, 0xa282d3c1UL, 0x95e811c0UL, 0xa8af4dcbUL, + 0x9fc58fcaUL, 0xc67bc9c8UL, 0xf1110bc9UL, 0x740744ccUL, 0x436d86cdUL, + 0x1ad3c0cfUL, 0x2db902ceUL, 0x4096af91UL, 0x77fc6d90UL, 0x2e422b92UL, + 0x1928e993UL, 0x9c3ea696UL, 0xab546497UL, 0xf2ea2295UL, 0xc580e094UL, + 0xf8c7bc9fUL, 0xcfad7e9eUL, 0x9613389cUL, 0xa179fa9dUL, 0x246fb598UL, + 0x13057799UL, 0x4abb319bUL, 0x7dd1f39aUL, 0x3035898dUL, 0x075f4b8cUL, + 0x5ee10d8eUL, 0x698bcf8fUL, 0xec9d808aUL, 0xdbf7428bUL, 0x82490489UL, + 0xb523c688UL, 0x88649a83UL, 0xbf0e5882UL, 0xe6b01e80UL, 0xd1dadc81UL, + 0x54cc9384UL, 0x63a65185UL, 0x3a181787UL, 0x0d72d586UL, 0xa0d0e2a9UL, + 0x97ba20a8UL, 0xce0466aaUL, 0xf96ea4abUL, 0x7c78ebaeUL, 0x4b1229afUL, + 0x12ac6fadUL, 0x25c6adacUL, 0x1881f1a7UL, 0x2feb33a6UL, 0x765575a4UL, + 0x413fb7a5UL, 0xc429f8a0UL, 0xf3433aa1UL, 0xaafd7ca3UL, 0x9d97bea2UL, + 0xd073c4b5UL, 0xe71906b4UL, 0xbea740b6UL, 0x89cd82b7UL, 0x0cdbcdb2UL, + 0x3bb10fb3UL, 0x620f49b1UL, 0x55658bb0UL, 0x6822d7bbUL, 0x5f4815baUL, + 0x06f653b8UL, 0x319c91b9UL, 0xb48adebcUL, 0x83e01cbdUL, 0xda5e5abfUL, + 0xed3498beUL + }, + { + 0x00000000UL, 0x6567bcb8UL, 0x8bc809aaUL, 0xeeafb512UL, 0x5797628fUL, + 0x32f0de37UL, 0xdc5f6b25UL, 0xb938d79dUL, 0xef28b4c5UL, 0x8a4f087dUL, + 0x64e0bd6fUL, 0x018701d7UL, 0xb8bfd64aUL, 0xddd86af2UL, 0x3377dfe0UL, + 0x56106358UL, 0x9f571950UL, 0xfa30a5e8UL, 0x149f10faUL, 0x71f8ac42UL, + 0xc8c07bdfUL, 0xada7c767UL, 0x43087275UL, 0x266fcecdUL, 0x707fad95UL, + 0x1518112dUL, 0xfbb7a43fUL, 0x9ed01887UL, 0x27e8cf1aUL, 0x428f73a2UL, + 0xac20c6b0UL, 0xc9477a08UL, 0x3eaf32a0UL, 0x5bc88e18UL, 0xb5673b0aUL, + 0xd00087b2UL, 0x6938502fUL, 0x0c5fec97UL, 0xe2f05985UL, 0x8797e53dUL, + 0xd1878665UL, 0xb4e03addUL, 0x5a4f8fcfUL, 0x3f283377UL, 0x8610e4eaUL, + 0xe3775852UL, 0x0dd8ed40UL, 0x68bf51f8UL, 0xa1f82bf0UL, 0xc49f9748UL, + 0x2a30225aUL, 0x4f579ee2UL, 0xf66f497fUL, 0x9308f5c7UL, 0x7da740d5UL, + 0x18c0fc6dUL, 0x4ed09f35UL, 0x2bb7238dUL, 0xc518969fUL, 0xa07f2a27UL, + 0x1947fdbaUL, 0x7c204102UL, 0x928ff410UL, 0xf7e848a8UL, 0x3d58149bUL, + 0x583fa823UL, 0xb6901d31UL, 0xd3f7a189UL, 0x6acf7614UL, 0x0fa8caacUL, + 0xe1077fbeUL, 0x8460c306UL, 0xd270a05eUL, 0xb7171ce6UL, 0x59b8a9f4UL, + 0x3cdf154cUL, 0x85e7c2d1UL, 0xe0807e69UL, 0x0e2fcb7bUL, 0x6b4877c3UL, + 0xa20f0dcbUL, 0xc768b173UL, 0x29c70461UL, 0x4ca0b8d9UL, 0xf5986f44UL, + 0x90ffd3fcUL, 0x7e5066eeUL, 0x1b37da56UL, 0x4d27b90eUL, 0x284005b6UL, + 0xc6efb0a4UL, 0xa3880c1cUL, 0x1ab0db81UL, 0x7fd76739UL, 0x9178d22bUL, + 0xf41f6e93UL, 0x03f7263bUL, 0x66909a83UL, 0x883f2f91UL, 0xed589329UL, + 0x546044b4UL, 0x3107f80cUL, 0xdfa84d1eUL, 0xbacff1a6UL, 0xecdf92feUL, + 0x89b82e46UL, 0x67179b54UL, 0x027027ecUL, 0xbb48f071UL, 0xde2f4cc9UL, + 0x3080f9dbUL, 0x55e74563UL, 0x9ca03f6bUL, 0xf9c783d3UL, 0x176836c1UL, + 0x720f8a79UL, 0xcb375de4UL, 0xae50e15cUL, 0x40ff544eUL, 0x2598e8f6UL, + 0x73888baeUL, 0x16ef3716UL, 0xf8408204UL, 0x9d273ebcUL, 0x241fe921UL, + 0x41785599UL, 0xafd7e08bUL, 0xcab05c33UL, 0x3bb659edUL, 0x5ed1e555UL, + 0xb07e5047UL, 0xd519ecffUL, 0x6c213b62UL, 0x094687daUL, 0xe7e932c8UL, + 0x828e8e70UL, 0xd49eed28UL, 0xb1f95190UL, 0x5f56e482UL, 0x3a31583aUL, + 0x83098fa7UL, 0xe66e331fUL, 0x08c1860dUL, 0x6da63ab5UL, 0xa4e140bdUL, + 0xc186fc05UL, 0x2f294917UL, 0x4a4ef5afUL, 0xf3762232UL, 0x96119e8aUL, + 0x78be2b98UL, 0x1dd99720UL, 0x4bc9f478UL, 0x2eae48c0UL, 0xc001fdd2UL, + 0xa566416aUL, 0x1c5e96f7UL, 0x79392a4fUL, 0x97969f5dUL, 0xf2f123e5UL, + 0x05196b4dUL, 0x607ed7f5UL, 0x8ed162e7UL, 0xebb6de5fUL, 0x528e09c2UL, + 0x37e9b57aUL, 0xd9460068UL, 0xbc21bcd0UL, 0xea31df88UL, 0x8f566330UL, + 0x61f9d622UL, 0x049e6a9aUL, 0xbda6bd07UL, 0xd8c101bfUL, 0x366eb4adUL, + 0x53090815UL, 0x9a4e721dUL, 0xff29cea5UL, 0x11867bb7UL, 0x74e1c70fUL, + 0xcdd91092UL, 0xa8beac2aUL, 0x46111938UL, 0x2376a580UL, 0x7566c6d8UL, + 0x10017a60UL, 0xfeaecf72UL, 0x9bc973caUL, 0x22f1a457UL, 0x479618efUL, + 0xa939adfdUL, 0xcc5e1145UL, 0x06ee4d76UL, 0x6389f1ceUL, 0x8d2644dcUL, + 0xe841f864UL, 0x51792ff9UL, 0x341e9341UL, 0xdab12653UL, 0xbfd69aebUL, + 0xe9c6f9b3UL, 0x8ca1450bUL, 0x620ef019UL, 0x07694ca1UL, 0xbe519b3cUL, + 0xdb362784UL, 0x35999296UL, 0x50fe2e2eUL, 0x99b95426UL, 0xfcdee89eUL, + 0x12715d8cUL, 0x7716e134UL, 0xce2e36a9UL, 0xab498a11UL, 0x45e63f03UL, + 0x208183bbUL, 0x7691e0e3UL, 0x13f65c5bUL, 0xfd59e949UL, 0x983e55f1UL, + 0x2106826cUL, 0x44613ed4UL, 0xaace8bc6UL, 0xcfa9377eUL, 0x38417fd6UL, + 0x5d26c36eUL, 0xb389767cUL, 0xd6eecac4UL, 0x6fd61d59UL, 0x0ab1a1e1UL, + 0xe41e14f3UL, 0x8179a84bUL, 0xd769cb13UL, 0xb20e77abUL, 0x5ca1c2b9UL, + 0x39c67e01UL, 0x80fea99cUL, 0xe5991524UL, 0x0b36a036UL, 0x6e511c8eUL, + 0xa7166686UL, 0xc271da3eUL, 0x2cde6f2cUL, 0x49b9d394UL, 0xf0810409UL, + 0x95e6b8b1UL, 0x7b490da3UL, 0x1e2eb11bUL, 0x483ed243UL, 0x2d596efbUL, + 0xc3f6dbe9UL, 0xa6916751UL, 0x1fa9b0ccUL, 0x7ace0c74UL, 0x9461b966UL, + 0xf10605deUL +#endif + } +}; diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/deflate.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/deflate.c index 529f716b7..29ce1f64a 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/deflate.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/deflate.c @@ -1,1736 +1,1736 @@ -/* deflate.c -- compress data using the deflation algorithm - * Copyright (C) 1995-2005 Jean-loup Gailly. - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* - * ALGORITHM - * - * The "deflation" process depends on being able to identify portions - * of the input text which are identical to earlier input (within a - * sliding window trailing behind the input currently being processed). - * - * The most straightforward technique turns out to be the fastest for - * most input files: try all possible matches and select the longest. - * The key feature of this algorithm is that insertions into the string - * dictionary are very simple and thus fast, and deletions are avoided - * completely. Insertions are performed at each input character, whereas - * string matches are performed only when the previous match ends. So it - * is preferable to spend more time in matches to allow very fast string - * insertions and avoid deletions. The matching algorithm for small - * strings is inspired from that of Rabin & Karp. A brute force approach - * is used to find longer strings when a small match has been found. - * A similar algorithm is used in comic (by Jan-Mark Wams) and freeze - * (by Leonid Broukhis). - * A previous version of this file used a more sophisticated algorithm - * (by Fiala and Greene) which is guaranteed to run in linear amortized - * time, but has a larger average cost, uses more memory and is patented. - * However the F&G algorithm may be faster for some highly redundant - * files if the parameter max_chain_length (described below) is too large. - * - * ACKNOWLEDGEMENTS - * - * The idea of lazy evaluation of matches is due to Jan-Mark Wams, and - * I found it in 'freeze' written by Leonid Broukhis. - * Thanks to many people for bug reports and testing. - * - * REFERENCES - * - * Deutsch, L.P.,"DEFLATE Compressed Data Format Specification". - * Available in http://www.ietf.org/rfc/rfc1951.txt - * - * A description of the Rabin and Karp algorithm is given in the book - * "Algorithms" by R. Sedgewick, Addison-Wesley, p252. - * - * Fiala,E.R., and Greene,D.H. - * Data Compression with Finite Windows, Comm.ACM, 32,4 (1989) 490-595 - * - */ - -/* @(#) $Id$ */ - -#include "deflate.h" - -const char deflate_copyright[] = - " deflate 1.2.3 Copyright 1995-2005 Jean-loup Gailly "; -/* - If you use the zlib library in a product, an acknowledgment is welcome - in the documentation of your product. If for some reason you cannot - include such an acknowledgment, I would appreciate that you keep this - copyright string in the executable of your product. - */ - -/* =========================================================================== - * Function prototypes. - */ -typedef enum { - need_more, /* block not completed, need more input or more output */ - block_done, /* block flush performed */ - finish_started, /* finish started, need only more output at next deflate */ - finish_done /* finish done, accept no more input or output */ -} block_state; - -typedef block_state (*compress_func) OF((deflate_state *s, int flush)); -/* Compression function. Returns the block state after the call. */ - -local void fill_window OF((deflate_state *s)); -local block_state deflate_stored OF((deflate_state *s, int flush)); -local block_state deflate_fast OF((deflate_state *s, int flush)); -#ifndef FASTEST -local block_state deflate_slow OF((deflate_state *s, int flush)); -#endif -local void lm_init OF((deflate_state *s)); -local void putShortMSB OF((deflate_state *s, uInt b)); -local void flush_pending OF((z_streamp strm)); -local int read_buf OF((z_streamp strm, Bytef *buf, unsigned size)); -#ifndef FASTEST -#ifdef ASMV - void match_init OF((void)); /* asm code initialization */ - uInt longest_match OF((deflate_state *s, IPos cur_match)); -#else -local uInt longest_match OF((deflate_state *s, IPos cur_match)); -#endif -#endif -local uInt longest_match_fast OF((deflate_state *s, IPos cur_match)); - -#ifdef DEBUG -local void check_match OF((deflate_state *s, IPos start, IPos match, - int length)); -#endif - -/* =========================================================================== - * Local data - */ - -#define NIL 0 -/* Tail of hash chains */ - -#ifndef TOO_FAR -# define TOO_FAR 4096 -#endif -/* Matches of length 3 are discarded if their distance exceeds TOO_FAR */ - -#define MIN_LOOKAHEAD (MAX_MATCH+MIN_MATCH+1) -/* Minimum amount of lookahead, except at the end of the input file. - * See deflate.c for comments about the MIN_MATCH+1. - */ - -/* Values for max_lazy_match, good_match and max_chain_length, depending on - * the desired pack level (0..9). The values given below have been tuned to - * exclude worst case performance for pathological files. Better values may be - * found for specific files. - */ -typedef struct config_s { - ush good_length; /* reduce lazy search above this match length */ - ush max_lazy; /* do not perform lazy search above this match length */ - ush nice_length; /* quit search above this match length */ - ush max_chain; - compress_func func; -} config; - -#ifdef FASTEST -local const config configuration_table[2] = { -/* good lazy nice chain */ -/* 0 */ {0, 0, 0, 0, deflate_stored}, /* store only */ -/* 1 */ {4, 4, 8, 4, deflate_fast}}; /* max speed, no lazy matches */ -#else -local const config configuration_table[10] = { -/* good lazy nice chain */ -/* 0 */ {0, 0, 0, 0, deflate_stored}, /* store only */ -/* 1 */ {4, 4, 8, 4, deflate_fast}, /* max speed, no lazy matches */ -/* 2 */ {4, 5, 16, 8, deflate_fast}, -/* 3 */ {4, 6, 32, 32, deflate_fast}, - -/* 4 */ {4, 4, 16, 16, deflate_slow}, /* lazy matches */ -/* 5 */ {8, 16, 32, 32, deflate_slow}, -/* 6 */ {8, 16, 128, 128, deflate_slow}, -/* 7 */ {8, 32, 128, 256, deflate_slow}, -/* 8 */ {32, 128, 258, 1024, deflate_slow}, -/* 9 */ {32, 258, 258, 4096, deflate_slow}}; /* max compression */ -#endif - -/* Note: the deflate() code requires max_lazy >= MIN_MATCH and max_chain >= 4 - * For deflate_fast() (levels <= 3) good is ignored and lazy has a different - * meaning. - */ - -#define EQUAL 0 -/* result of memcmp for equal strings */ - -#ifndef NO_DUMMY_DECL -struct static_tree_desc_s {int dummy;}; /* for buggy compilers */ -#endif - -/* =========================================================================== - * Update a hash value with the given input byte - * IN assertion: all calls to to UPDATE_HASH are made with consecutive - * input characters, so that a running hash key can be computed from the - * previous key instead of complete recalculation each time. - */ -#define UPDATE_HASH(s,h,c) (h = (((h)<hash_shift) ^ (c)) & s->hash_mask) - - -/* =========================================================================== - * Insert string str in the dictionary and set match_head to the previous head - * of the hash chain (the most recent string with same hash key). Return - * the previous length of the hash chain. - * If this file is compiled with -DFASTEST, the compression level is forced - * to 1, and no hash chains are maintained. - * IN assertion: all calls to to INSERT_STRING are made with consecutive - * input characters and the first MIN_MATCH bytes of str are valid - * (except for the last MIN_MATCH-1 bytes of the input file). - */ -#ifdef FASTEST -#define INSERT_STRING(s, str, match_head) \ - (UPDATE_HASH(s, s->ins_h, s->window[(str) + (MIN_MATCH-1)]), \ - match_head = s->head[s->ins_h], \ - s->head[s->ins_h] = (Pos)(str)) -#else -#define INSERT_STRING(s, str, match_head) \ - (UPDATE_HASH(s, s->ins_h, s->window[(str) + (MIN_MATCH-1)]), \ - match_head = s->prev[(str) & s->w_mask] = s->head[s->ins_h], \ - s->head[s->ins_h] = (Pos)(str)) -#endif - -/* =========================================================================== - * Initialize the hash table (avoiding 64K overflow for 16 bit systems). - * prev[] will be initialized on the fly. - */ -#define CLEAR_HASH(s) \ - s->head[s->hash_size-1] = NIL; \ - zmemzero((Bytef *)s->head, (unsigned)(s->hash_size-1)*sizeof(*s->head)); - -/* ========================================================================= */ -int ZEXPORT deflateInit_(strm, level, version, stream_size) - z_streamp strm; - int level; - const char *version; - int stream_size; -{ - return deflateInit2_(strm, level, Z_DEFLATED, MAX_WBITS, DEF_MEM_LEVEL, - Z_DEFAULT_STRATEGY, version, stream_size); - /* To do: ignore strm->next_in if we use it as window */ -} - -/* ========================================================================= */ -int ZEXPORT deflateInit2_(strm, level, method, windowBits, memLevel, strategy, - version, stream_size) - z_streamp strm; - int level; - int method; - int windowBits; - int memLevel; - int strategy; - const char *version; - int stream_size; -{ - deflate_state *s; - int wrap = 1; - static const char my_version[] = ZLIB_VERSION; - - ushf *overlay; - /* We overlay pending_buf and d_buf+l_buf. This works since the average - * output size for (length,distance) codes is <= 24 bits. - */ - - if (version == Z_NULL || version[0] != my_version[0] || - stream_size != sizeof(z_stream)) { - return Z_VERSION_ERROR; - } - if (strm == Z_NULL) return Z_STREAM_ERROR; - - strm->msg = Z_NULL; - if (strm->zalloc == (alloc_func)0) { - strm->zalloc = zcalloc; - strm->opaque = (voidpf)0; - } - if (strm->zfree == (free_func)0) strm->zfree = zcfree; - -#ifdef FASTEST - if (level != 0) level = 1; -#else - if (level == Z_DEFAULT_COMPRESSION) level = 6; -#endif - - if (windowBits < 0) { /* suppress zlib wrapper */ - wrap = 0; - windowBits = -windowBits; - } -#ifdef GZIP - else if (windowBits > 15) { - wrap = 2; /* write gzip wrapper instead */ - windowBits -= 16; - } -#endif - if (memLevel < 1 || memLevel > MAX_MEM_LEVEL || method != Z_DEFLATED || - windowBits < 8 || windowBits > 15 || level < 0 || level > 9 || - strategy < 0 || strategy > Z_FIXED) { - return Z_STREAM_ERROR; - } - if (windowBits == 8) windowBits = 9; /* until 256-byte window bug fixed */ - s = (deflate_state *) ZALLOC(strm, 1, sizeof(deflate_state)); - if (s == Z_NULL) return Z_MEM_ERROR; - strm->state = (struct internal_state FAR *)s; - s->strm = strm; - - s->wrap = wrap; - s->gzhead = Z_NULL; - s->w_bits = windowBits; - s->w_size = 1 << s->w_bits; - s->w_mask = s->w_size - 1; - - s->hash_bits = memLevel + 7; - s->hash_size = 1 << s->hash_bits; - s->hash_mask = s->hash_size - 1; - s->hash_shift = ((s->hash_bits+MIN_MATCH-1)/MIN_MATCH); - - s->window = (Bytef *) ZALLOC(strm, s->w_size, 2*sizeof(Byte)); - s->prev = (Posf *) ZALLOC(strm, s->w_size, sizeof(Pos)); - s->head = (Posf *) ZALLOC(strm, s->hash_size, sizeof(Pos)); - - s->lit_bufsize = 1 << (memLevel + 6); /* 16K elements by default */ - - overlay = (ushf *) ZALLOC(strm, s->lit_bufsize, sizeof(ush)+2); - s->pending_buf = (uchf *) overlay; - s->pending_buf_size = (ulg)s->lit_bufsize * (sizeof(ush)+2L); - - if (s->window == Z_NULL || s->prev == Z_NULL || s->head == Z_NULL || - s->pending_buf == Z_NULL) { - s->status = FINISH_STATE; - strm->msg = (char*)ERR_MSG(Z_MEM_ERROR); - deflateEnd (strm); - return Z_MEM_ERROR; - } - s->d_buf = overlay + s->lit_bufsize/sizeof(ush); - s->l_buf = s->pending_buf + (1+sizeof(ush))*s->lit_bufsize; - - s->level = level; - s->strategy = strategy; - s->method = (Byte)method; - - return deflateReset(strm); -} - -/* ========================================================================= */ -int ZEXPORT deflateSetDictionary (strm, dictionary, dictLength) - z_streamp strm; - const Bytef *dictionary; - uInt dictLength; -{ - deflate_state *s; - uInt length = dictLength; - uInt n; - IPos hash_head = 0; - - if (strm == Z_NULL || strm->state == Z_NULL || dictionary == Z_NULL || - strm->state->wrap == 2 || - (strm->state->wrap == 1 && strm->state->status != INIT_STATE)) - return Z_STREAM_ERROR; - - s = strm->state; - if (s->wrap) - strm->adler = adler32(strm->adler, dictionary, dictLength); - - if (length < MIN_MATCH) return Z_OK; - if (length > MAX_DIST(s)) { - length = MAX_DIST(s); - dictionary += dictLength - length; /* use the tail of the dictionary */ - } - zmemcpy(s->window, dictionary, length); - s->strstart = length; - s->block_start = (long)length; - - /* Insert all strings in the hash table (except for the last two bytes). - * s->lookahead stays null, so s->ins_h will be recomputed at the next - * call of fill_window. - */ - s->ins_h = s->window[0]; - UPDATE_HASH(s, s->ins_h, s->window[1]); - for (n = 0; n <= length - MIN_MATCH; n++) { - INSERT_STRING(s, n, hash_head); - } - if (hash_head) hash_head = 0; /* to make compiler happy */ - return Z_OK; -} - -/* ========================================================================= */ -int ZEXPORT deflateReset (strm) - z_streamp strm; -{ - deflate_state *s; - - if (strm == Z_NULL || strm->state == Z_NULL || - strm->zalloc == (alloc_func)0 || strm->zfree == (free_func)0) { - return Z_STREAM_ERROR; - } - - strm->total_in = strm->total_out = 0; - strm->msg = Z_NULL; /* use zfree if we ever allocate msg dynamically */ - strm->data_type = Z_UNKNOWN; - - s = (deflate_state *)strm->state; - s->pending = 0; - s->pending_out = s->pending_buf; - - if (s->wrap < 0) { - s->wrap = -s->wrap; /* was made negative by deflate(..., Z_FINISH); */ - } - s->status = s->wrap ? INIT_STATE : BUSY_STATE; - strm->adler = -#ifdef GZIP - s->wrap == 2 ? crc32(0L, Z_NULL, 0) : -#endif - adler32(0L, Z_NULL, 0); - s->last_flush = Z_NO_FLUSH; - - _tr_init(s); - lm_init(s); - - return Z_OK; -} - -/* ========================================================================= */ -int ZEXPORT deflateSetHeader (strm, head) - z_streamp strm; - gz_headerp head; -{ - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - if (strm->state->wrap != 2) return Z_STREAM_ERROR; - strm->state->gzhead = head; - return Z_OK; -} - -/* ========================================================================= */ -int ZEXPORT deflatePrime (strm, bits, value) - z_streamp strm; - int bits; - int value; -{ - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - strm->state->bi_valid = bits; - strm->state->bi_buf = (ush)(value & ((1 << bits) - 1)); - return Z_OK; -} - -/* ========================================================================= */ -int ZEXPORT deflateParams(strm, level, strategy) - z_streamp strm; - int level; - int strategy; -{ - deflate_state *s; - compress_func func; - int err = Z_OK; - - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - s = strm->state; - -#ifdef FASTEST - if (level != 0) level = 1; -#else - if (level == Z_DEFAULT_COMPRESSION) level = 6; -#endif - if (level < 0 || level > 9 || strategy < 0 || strategy > Z_FIXED) { - return Z_STREAM_ERROR; - } - func = configuration_table[s->level].func; - - if (func != configuration_table[level].func && strm->total_in != 0) { - /* Flush the last buffer: */ - err = deflate(strm, Z_PARTIAL_FLUSH); - } - if (s->level != level) { - s->level = level; - s->max_lazy_match = configuration_table[level].max_lazy; - s->good_match = configuration_table[level].good_length; - s->nice_match = configuration_table[level].nice_length; - s->max_chain_length = configuration_table[level].max_chain; - } - s->strategy = strategy; - return err; -} - -/* ========================================================================= */ -int ZEXPORT deflateTune(strm, good_length, max_lazy, nice_length, max_chain) - z_streamp strm; - int good_length; - int max_lazy; - int nice_length; - int max_chain; -{ - deflate_state *s; - - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - s = strm->state; - s->good_match = good_length; - s->max_lazy_match = max_lazy; - s->nice_match = nice_length; - s->max_chain_length = max_chain; - return Z_OK; -} - -/* ========================================================================= - * For the default windowBits of 15 and memLevel of 8, this function returns - * a close to exact, as well as small, upper bound on the compressed size. - * They are coded as constants here for a reason--if the #define's are - * changed, then this function needs to be changed as well. The return - * value for 15 and 8 only works for those exact settings. - * - * For any setting other than those defaults for windowBits and memLevel, - * the value returned is a conservative worst case for the maximum expansion - * resulting from using fixed blocks instead of stored blocks, which deflate - * can emit on compressed data for some combinations of the parameters. - * - * This function could be more sophisticated to provide closer upper bounds - * for every combination of windowBits and memLevel, as well as wrap. - * But even the conservative upper bound of about 14% expansion does not - * seem onerous for output buffer allocation. - */ -uLong ZEXPORT deflateBound(strm, sourceLen) - z_streamp strm; - uLong sourceLen; -{ - deflate_state *s; - uLong destLen; - - /* conservative upper bound */ - destLen = sourceLen + - ((sourceLen + 7) >> 3) + ((sourceLen + 63) >> 6) + 11; - - /* if can't get parameters, return conservative bound */ - if (strm == Z_NULL || strm->state == Z_NULL) - return destLen; - - /* if not default parameters, return conservative bound */ - s = strm->state; - if (s->w_bits != 15 || s->hash_bits != 8 + 7) - return destLen; - - /* default settings: return tight bound for that case */ - return compressBound(sourceLen); -} - -/* ========================================================================= - * Put a short in the pending buffer. The 16-bit value is put in MSB order. - * IN assertion: the stream state is correct and there is enough room in - * pending_buf. - */ -local void putShortMSB (s, b) - deflate_state *s; - uInt b; -{ - put_byte(s, (Byte)(b >> 8)); - put_byte(s, (Byte)(b & 0xff)); -} - -/* ========================================================================= - * Flush as much pending output as possible. All deflate() output goes - * through this function so some applications may wish to modify it - * to avoid allocating a large strm->next_out buffer and copying into it. - * (See also read_buf()). - */ -local void flush_pending(strm) - z_streamp strm; -{ - unsigned len = strm->state->pending; - - if (len > strm->avail_out) len = strm->avail_out; - if (len == 0) return; - - zmemcpy(strm->next_out, strm->state->pending_out, len); - strm->next_out += len; - strm->state->pending_out += len; - strm->total_out += len; - strm->avail_out -= len; - strm->state->pending -= len; - if (strm->state->pending == 0) { - strm->state->pending_out = strm->state->pending_buf; - } -} - -/* ========================================================================= */ -int ZEXPORT deflate (strm, flush) - z_streamp strm; - int flush; -{ - int old_flush; /* value of flush param for previous deflate call */ - deflate_state *s; - - if (strm == Z_NULL || strm->state == Z_NULL || - flush > Z_FINISH || flush < 0) { - return Z_STREAM_ERROR; - } - s = strm->state; - - if (strm->next_out == Z_NULL || - (strm->next_in == Z_NULL && strm->avail_in != 0) || - (s->status == FINISH_STATE && flush != Z_FINISH)) { - ERR_RETURN(strm, Z_STREAM_ERROR); - } - if (strm->avail_out == 0) ERR_RETURN(strm, Z_BUF_ERROR); - - s->strm = strm; /* just in case */ - old_flush = s->last_flush; - s->last_flush = flush; - - /* Write the header */ - if (s->status == INIT_STATE) { -#ifdef GZIP - if (s->wrap == 2) { - strm->adler = crc32(0L, Z_NULL, 0); - put_byte(s, 31); - put_byte(s, 139); - put_byte(s, 8); - if (s->gzhead == NULL) { - put_byte(s, 0); - put_byte(s, 0); - put_byte(s, 0); - put_byte(s, 0); - put_byte(s, 0); - put_byte(s, s->level == 9 ? 2 : - (s->strategy >= Z_HUFFMAN_ONLY || s->level < 2 ? - 4 : 0)); - put_byte(s, OS_CODE); - s->status = BUSY_STATE; - } - else { - put_byte(s, (s->gzhead->text ? 1 : 0) + - (s->gzhead->hcrc ? 2 : 0) + - (s->gzhead->extra == Z_NULL ? 0 : 4) + - (s->gzhead->name == Z_NULL ? 0 : 8) + - (s->gzhead->comment == Z_NULL ? 0 : 16) - ); - put_byte(s, (Byte)(s->gzhead->time & 0xff)); - put_byte(s, (Byte)((s->gzhead->time >> 8) & 0xff)); - put_byte(s, (Byte)((s->gzhead->time >> 16) & 0xff)); - put_byte(s, (Byte)((s->gzhead->time >> 24) & 0xff)); - put_byte(s, s->level == 9 ? 2 : - (s->strategy >= Z_HUFFMAN_ONLY || s->level < 2 ? - 4 : 0)); - put_byte(s, s->gzhead->os & 0xff); - if (s->gzhead->extra != NULL) { - put_byte(s, s->gzhead->extra_len & 0xff); - put_byte(s, (s->gzhead->extra_len >> 8) & 0xff); - } - if (s->gzhead->hcrc) - strm->adler = crc32(strm->adler, s->pending_buf, - s->pending); - s->gzindex = 0; - s->status = EXTRA_STATE; - } - } - else -#endif - { - uInt header = (Z_DEFLATED + ((s->w_bits-8)<<4)) << 8; - uInt level_flags; - - if (s->strategy >= Z_HUFFMAN_ONLY || s->level < 2) - level_flags = 0; - else if (s->level < 6) - level_flags = 1; - else if (s->level == 6) - level_flags = 2; - else - level_flags = 3; - header |= (level_flags << 6); - if (s->strstart != 0) header |= PRESET_DICT; - header += 31 - (header % 31); - - s->status = BUSY_STATE; - putShortMSB(s, header); - - /* Save the adler32 of the preset dictionary: */ - if (s->strstart != 0) { - putShortMSB(s, (uInt)(strm->adler >> 16)); - putShortMSB(s, (uInt)(strm->adler & 0xffff)); - } - strm->adler = adler32(0L, Z_NULL, 0); - } - } -#ifdef GZIP - if (s->status == EXTRA_STATE) { - if (s->gzhead->extra != NULL) { - uInt beg = s->pending; /* start of bytes to update crc */ - - while (s->gzindex < (s->gzhead->extra_len & 0xffff)) { - if (s->pending == s->pending_buf_size) { - if (s->gzhead->hcrc && s->pending > beg) - strm->adler = crc32(strm->adler, s->pending_buf + beg, - s->pending - beg); - flush_pending(strm); - beg = s->pending; - if (s->pending == s->pending_buf_size) - break; - } - put_byte(s, s->gzhead->extra[s->gzindex]); - s->gzindex++; - } - if (s->gzhead->hcrc && s->pending > beg) - strm->adler = crc32(strm->adler, s->pending_buf + beg, - s->pending - beg); - if (s->gzindex == s->gzhead->extra_len) { - s->gzindex = 0; - s->status = NAME_STATE; - } - } - else - s->status = NAME_STATE; - } - if (s->status == NAME_STATE) { - if (s->gzhead->name != NULL) { - uInt beg = s->pending; /* start of bytes to update crc */ - int val; - - do { - if (s->pending == s->pending_buf_size) { - if (s->gzhead->hcrc && s->pending > beg) - strm->adler = crc32(strm->adler, s->pending_buf + beg, - s->pending - beg); - flush_pending(strm); - beg = s->pending; - if (s->pending == s->pending_buf_size) { - val = 1; - break; - } - } - val = s->gzhead->name[s->gzindex++]; - put_byte(s, val); - } while (val != 0); - if (s->gzhead->hcrc && s->pending > beg) - strm->adler = crc32(strm->adler, s->pending_buf + beg, - s->pending - beg); - if (val == 0) { - s->gzindex = 0; - s->status = COMMENT_STATE; - } - } - else - s->status = COMMENT_STATE; - } - if (s->status == COMMENT_STATE) { - if (s->gzhead->comment != NULL) { - uInt beg = s->pending; /* start of bytes to update crc */ - int val; - - do { - if (s->pending == s->pending_buf_size) { - if (s->gzhead->hcrc && s->pending > beg) - strm->adler = crc32(strm->adler, s->pending_buf + beg, - s->pending - beg); - flush_pending(strm); - beg = s->pending; - if (s->pending == s->pending_buf_size) { - val = 1; - break; - } - } - val = s->gzhead->comment[s->gzindex++]; - put_byte(s, val); - } while (val != 0); - if (s->gzhead->hcrc && s->pending > beg) - strm->adler = crc32(strm->adler, s->pending_buf + beg, - s->pending - beg); - if (val == 0) - s->status = HCRC_STATE; - } - else - s->status = HCRC_STATE; - } - if (s->status == HCRC_STATE) { - if (s->gzhead->hcrc) { - if (s->pending + 2 > s->pending_buf_size) - flush_pending(strm); - if (s->pending + 2 <= s->pending_buf_size) { - put_byte(s, (Byte)(strm->adler & 0xff)); - put_byte(s, (Byte)((strm->adler >> 8) & 0xff)); - strm->adler = crc32(0L, Z_NULL, 0); - s->status = BUSY_STATE; - } - } - else - s->status = BUSY_STATE; - } -#endif - - /* Flush as much pending output as possible */ - if (s->pending != 0) { - flush_pending(strm); - if (strm->avail_out == 0) { - /* Since avail_out is 0, deflate will be called again with - * more output space, but possibly with both pending and - * avail_in equal to zero. There won't be anything to do, - * but this is not an error situation so make sure we - * return OK instead of BUF_ERROR at next call of deflate: - */ - s->last_flush = -1; - return Z_OK; - } - - /* Make sure there is something to do and avoid duplicate consecutive - * flushes. For repeated and useless calls with Z_FINISH, we keep - * returning Z_STREAM_END instead of Z_BUF_ERROR. - */ - } else if (strm->avail_in == 0 && flush <= old_flush && - flush != Z_FINISH) { - ERR_RETURN(strm, Z_BUF_ERROR); - } - - /* User must not provide more input after the first FINISH: */ - if (s->status == FINISH_STATE && strm->avail_in != 0) { - ERR_RETURN(strm, Z_BUF_ERROR); - } - - /* Start a new block or continue the current one. - */ - if (strm->avail_in != 0 || s->lookahead != 0 || - (flush != Z_NO_FLUSH && s->status != FINISH_STATE)) { - block_state bstate; - - bstate = (*(configuration_table[s->level].func))(s, flush); - - if (bstate == finish_started || bstate == finish_done) { - s->status = FINISH_STATE; - } - if (bstate == need_more || bstate == finish_started) { - if (strm->avail_out == 0) { - s->last_flush = -1; /* avoid BUF_ERROR next call, see above */ - } - return Z_OK; - /* If flush != Z_NO_FLUSH && avail_out == 0, the next call - * of deflate should use the same flush parameter to make sure - * that the flush is complete. So we don't have to output an - * empty block here, this will be done at next call. This also - * ensures that for a very small output buffer, we emit at most - * one empty block. - */ - } - if (bstate == block_done) { - if (flush == Z_PARTIAL_FLUSH) { - _tr_align(s); - } else { /* FULL_FLUSH or SYNC_FLUSH */ - _tr_stored_block(s, (char*)0, 0L, 0); - /* For a full flush, this empty block will be recognized - * as a special marker by inflate_sync(). - */ - if (flush == Z_FULL_FLUSH) { - CLEAR_HASH(s); /* forget history */ - } - } - flush_pending(strm); - if (strm->avail_out == 0) { - s->last_flush = -1; /* avoid BUF_ERROR at next call, see above */ - return Z_OK; - } - } - } - Assert(strm->avail_out > 0, "bug2"); - - if (flush != Z_FINISH) return Z_OK; - if (s->wrap <= 0) return Z_STREAM_END; - - /* Write the trailer */ -#ifdef GZIP - if (s->wrap == 2) { - put_byte(s, (Byte)(strm->adler & 0xff)); - put_byte(s, (Byte)((strm->adler >> 8) & 0xff)); - put_byte(s, (Byte)((strm->adler >> 16) & 0xff)); - put_byte(s, (Byte)((strm->adler >> 24) & 0xff)); - put_byte(s, (Byte)(strm->total_in & 0xff)); - put_byte(s, (Byte)((strm->total_in >> 8) & 0xff)); - put_byte(s, (Byte)((strm->total_in >> 16) & 0xff)); - put_byte(s, (Byte)((strm->total_in >> 24) & 0xff)); - } - else -#endif - { - putShortMSB(s, (uInt)(strm->adler >> 16)); - putShortMSB(s, (uInt)(strm->adler & 0xffff)); - } - flush_pending(strm); - /* If avail_out is zero, the application will call deflate again - * to flush the rest. - */ - if (s->wrap > 0) s->wrap = -s->wrap; /* write the trailer only once! */ - return s->pending != 0 ? Z_OK : Z_STREAM_END; -} - -/* ========================================================================= */ -int ZEXPORT deflateEnd (strm) - z_streamp strm; -{ - int status; - - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - - status = strm->state->status; - if (status != INIT_STATE && - status != EXTRA_STATE && - status != NAME_STATE && - status != COMMENT_STATE && - status != HCRC_STATE && - status != BUSY_STATE && - status != FINISH_STATE) { - return Z_STREAM_ERROR; - } - - /* Deallocate in reverse order of allocations: */ - TRY_FREE(strm, strm->state->pending_buf); - TRY_FREE(strm, strm->state->head); - TRY_FREE(strm, strm->state->prev); - TRY_FREE(strm, strm->state->window); - - ZFREE(strm, strm->state); - strm->state = Z_NULL; - - return status == BUSY_STATE ? Z_DATA_ERROR : Z_OK; -} - -/* ========================================================================= - * Copy the source state to the destination state. - * To simplify the source, this is not supported for 16-bit MSDOS (which - * doesn't have enough memory anyway to duplicate compression states). - */ -int ZEXPORT deflateCopy (dest, source) - z_streamp dest; - z_streamp source; -{ -#ifdef MAXSEG_64K - return Z_STREAM_ERROR; -#else - deflate_state *ds; - deflate_state *ss; - ushf *overlay; - - - if (source == Z_NULL || dest == Z_NULL || source->state == Z_NULL) { - return Z_STREAM_ERROR; - } - - ss = source->state; - - zmemcpy(dest, source, sizeof(z_stream)); - - ds = (deflate_state *) ZALLOC(dest, 1, sizeof(deflate_state)); - if (ds == Z_NULL) return Z_MEM_ERROR; - dest->state = (struct internal_state FAR *) ds; - zmemcpy(ds, ss, sizeof(deflate_state)); - ds->strm = dest; - - ds->window = (Bytef *) ZALLOC(dest, ds->w_size, 2*sizeof(Byte)); - ds->prev = (Posf *) ZALLOC(dest, ds->w_size, sizeof(Pos)); - ds->head = (Posf *) ZALLOC(dest, ds->hash_size, sizeof(Pos)); - overlay = (ushf *) ZALLOC(dest, ds->lit_bufsize, sizeof(ush)+2); - ds->pending_buf = (uchf *) overlay; - - if (ds->window == Z_NULL || ds->prev == Z_NULL || ds->head == Z_NULL || - ds->pending_buf == Z_NULL) { - deflateEnd (dest); - return Z_MEM_ERROR; - } - /* following zmemcpy do not work for 16-bit MSDOS */ - zmemcpy(ds->window, ss->window, ds->w_size * 2 * sizeof(Byte)); - zmemcpy(ds->prev, ss->prev, ds->w_size * sizeof(Pos)); - zmemcpy(ds->head, ss->head, ds->hash_size * sizeof(Pos)); - zmemcpy(ds->pending_buf, ss->pending_buf, (uInt)ds->pending_buf_size); - - ds->pending_out = ds->pending_buf + (ss->pending_out - ss->pending_buf); - ds->d_buf = overlay + ds->lit_bufsize/sizeof(ush); - ds->l_buf = ds->pending_buf + (1+sizeof(ush))*ds->lit_bufsize; - - ds->l_desc.dyn_tree = ds->dyn_ltree; - ds->d_desc.dyn_tree = ds->dyn_dtree; - ds->bl_desc.dyn_tree = ds->bl_tree; - - return Z_OK; -#endif /* MAXSEG_64K */ -} - -/* =========================================================================== - * Read a new buffer from the current input stream, update the adler32 - * and total number of bytes read. All deflate() input goes through - * this function so some applications may wish to modify it to avoid - * allocating a large strm->next_in buffer and copying from it. - * (See also flush_pending()). - */ -local int read_buf(strm, buf, size) - z_streamp strm; - Bytef *buf; - unsigned size; -{ - unsigned len = strm->avail_in; - - if (len > size) len = size; - if (len == 0) return 0; - - strm->avail_in -= len; - - if (strm->state->wrap == 1) { - strm->adler = adler32(strm->adler, strm->next_in, len); - } -#ifdef GZIP - else if (strm->state->wrap == 2) { - strm->adler = crc32(strm->adler, strm->next_in, len); - } -#endif - zmemcpy(buf, strm->next_in, len); - strm->next_in += len; - strm->total_in += len; - - return (int)len; -} - -/* =========================================================================== - * Initialize the "longest match" routines for a new zlib stream - */ -local void lm_init (s) - deflate_state *s; -{ - s->window_size = (ulg)2L*s->w_size; - - CLEAR_HASH(s); - - /* Set the default configuration parameters: - */ - s->max_lazy_match = configuration_table[s->level].max_lazy; - s->good_match = configuration_table[s->level].good_length; - s->nice_match = configuration_table[s->level].nice_length; - s->max_chain_length = configuration_table[s->level].max_chain; - - s->strstart = 0; - s->block_start = 0L; - s->lookahead = 0; - s->match_length = s->prev_length = MIN_MATCH-1; - s->match_available = 0; - s->ins_h = 0; -#ifndef FASTEST -#ifdef ASMV - match_init(); /* initialize the asm code */ -#endif -#endif -} - -#ifndef FASTEST -/* =========================================================================== - * Set match_start to the longest match starting at the given string and - * return its length. Matches shorter or equal to prev_length are discarded, - * in which case the result is equal to prev_length and match_start is - * garbage. - * IN assertions: cur_match is the head of the hash chain for the current - * string (strstart) and its distance is <= MAX_DIST, and prev_length >= 1 - * OUT assertion: the match length is not greater than s->lookahead. - */ -#ifndef ASMV -/* For 80x86 and 680x0, an optimized version will be provided in match.asm or - * match.S. The code will be functionally equivalent. - */ -local uInt longest_match(s, cur_match) - deflate_state *s; - IPos cur_match; /* current match */ -{ - unsigned chain_length = s->max_chain_length;/* max hash chain length */ - register Bytef *scan = s->window + s->strstart; /* current string */ - register Bytef *match; /* matched string */ - register int len; /* length of current match */ - int best_len = s->prev_length; /* best match length so far */ - int nice_match = s->nice_match; /* stop if match long enough */ - IPos limit = s->strstart > (IPos)MAX_DIST(s) ? - s->strstart - (IPos)MAX_DIST(s) : NIL; - /* Stop when cur_match becomes <= limit. To simplify the code, - * we prevent matches with the string of window index 0. - */ - Posf *prev = s->prev; - uInt wmask = s->w_mask; - -#ifdef UNALIGNED_OK - /* Compare two bytes at a time. Note: this is not always beneficial. - * Try with and without -DUNALIGNED_OK to check. - */ - register Bytef *strend = s->window + s->strstart + MAX_MATCH - 1; - register ush scan_start = *(ushf*)scan; - register ush scan_end = *(ushf*)(scan+best_len-1); -#else - register Bytef *strend = s->window + s->strstart + MAX_MATCH; - register Byte scan_end1 = scan[best_len-1]; - register Byte scan_end = scan[best_len]; -#endif - - /* The code is optimized for HASH_BITS >= 8 and MAX_MATCH-2 multiple of 16. - * It is easy to get rid of this optimization if necessary. - */ - Assert(s->hash_bits >= 8 && MAX_MATCH == 258, "Code too clever"); - - /* Do not waste too much time if we already have a good match: */ - if (s->prev_length >= s->good_match) { - chain_length >>= 2; - } - /* Do not look for matches beyond the end of the input. This is necessary - * to make deflate deterministic. - */ - if ((uInt)nice_match > s->lookahead) nice_match = s->lookahead; - - Assert((ulg)s->strstart <= s->window_size-MIN_LOOKAHEAD, "need lookahead"); - - do { - Assert(cur_match < s->strstart, "no future"); - match = s->window + cur_match; - - /* Skip to next match if the match length cannot increase - * or if the match length is less than 2. Note that the checks below - * for insufficient lookahead only occur occasionally for performance - * reasons. Therefore uninitialized memory will be accessed, and - * conditional jumps will be made that depend on those values. - * However the length of the match is limited to the lookahead, so - * the output of deflate is not affected by the uninitialized values. - */ -#if (defined(UNALIGNED_OK) && MAX_MATCH == 258) - /* This code assumes sizeof(unsigned short) == 2. Do not use - * UNALIGNED_OK if your compiler uses a different size. - */ - if (*(ushf*)(match+best_len-1) != scan_end || - *(ushf*)match != scan_start) continue; - - /* It is not necessary to compare scan[2] and match[2] since they are - * always equal when the other bytes match, given that the hash keys - * are equal and that HASH_BITS >= 8. Compare 2 bytes at a time at - * strstart+3, +5, ... up to strstart+257. We check for insufficient - * lookahead only every 4th comparison; the 128th check will be made - * at strstart+257. If MAX_MATCH-2 is not a multiple of 8, it is - * necessary to put more guard bytes at the end of the window, or - * to check more often for insufficient lookahead. - */ - Assert(scan[2] == match[2], "scan[2]?"); - scan++, match++; - do { - } while (*(ushf*)(scan+=2) == *(ushf*)(match+=2) && - *(ushf*)(scan+=2) == *(ushf*)(match+=2) && - *(ushf*)(scan+=2) == *(ushf*)(match+=2) && - *(ushf*)(scan+=2) == *(ushf*)(match+=2) && - scan < strend); - /* The funny "do {}" generates better code on most compilers */ - - /* Here, scan <= window+strstart+257 */ - Assert(scan <= s->window+(unsigned)(s->window_size-1), "wild scan"); - if (*scan == *match) scan++; - - len = (MAX_MATCH - 1) - (int)(strend-scan); - scan = strend - (MAX_MATCH-1); - -#else /* UNALIGNED_OK */ - - if (match[best_len] != scan_end || - match[best_len-1] != scan_end1 || - *match != *scan || - *++match != scan[1]) continue; - - /* The check at best_len-1 can be removed because it will be made - * again later. (This heuristic is not always a win.) - * It is not necessary to compare scan[2] and match[2] since they - * are always equal when the other bytes match, given that - * the hash keys are equal and that HASH_BITS >= 8. - */ - scan += 2, match++; - Assert(*scan == *match, "match[2]?"); - - /* We check for insufficient lookahead only every 8th comparison; - * the 256th check will be made at strstart+258. - */ - do { - } while (*++scan == *++match && *++scan == *++match && - *++scan == *++match && *++scan == *++match && - *++scan == *++match && *++scan == *++match && - *++scan == *++match && *++scan == *++match && - scan < strend); - - Assert(scan <= s->window+(unsigned)(s->window_size-1), "wild scan"); - - len = MAX_MATCH - (int)(strend - scan); - scan = strend - MAX_MATCH; - -#endif /* UNALIGNED_OK */ - - if (len > best_len) { - s->match_start = cur_match; - best_len = len; - if (len >= nice_match) break; -#ifdef UNALIGNED_OK - scan_end = *(ushf*)(scan+best_len-1); -#else - scan_end1 = scan[best_len-1]; - scan_end = scan[best_len]; -#endif - } - } while ((cur_match = prev[cur_match & wmask]) > limit - && --chain_length != 0); - - if ((uInt)best_len <= s->lookahead) return (uInt)best_len; - return s->lookahead; -} -#endif /* ASMV */ -#endif /* FASTEST */ - -/* --------------------------------------------------------------------------- - * Optimized version for level == 1 or strategy == Z_RLE only - */ -local uInt longest_match_fast(s, cur_match) - deflate_state *s; - IPos cur_match; /* current match */ -{ - register Bytef *scan = s->window + s->strstart; /* current string */ - register Bytef *match; /* matched string */ - register int len; /* length of current match */ - register Bytef *strend = s->window + s->strstart + MAX_MATCH; - - /* The code is optimized for HASH_BITS >= 8 and MAX_MATCH-2 multiple of 16. - * It is easy to get rid of this optimization if necessary. - */ - Assert(s->hash_bits >= 8 && MAX_MATCH == 258, "Code too clever"); - - Assert((ulg)s->strstart <= s->window_size-MIN_LOOKAHEAD, "need lookahead"); - - Assert(cur_match < s->strstart, "no future"); - - match = s->window + cur_match; - - /* Return failure if the match length is less than 2: - */ - if (match[0] != scan[0] || match[1] != scan[1]) return MIN_MATCH-1; - - /* The check at best_len-1 can be removed because it will be made - * again later. (This heuristic is not always a win.) - * It is not necessary to compare scan[2] and match[2] since they - * are always equal when the other bytes match, given that - * the hash keys are equal and that HASH_BITS >= 8. - */ - scan += 2, match += 2; - Assert(*scan == *match, "match[2]?"); - - /* We check for insufficient lookahead only every 8th comparison; - * the 256th check will be made at strstart+258. - */ - do { - } while (*++scan == *++match && *++scan == *++match && - *++scan == *++match && *++scan == *++match && - *++scan == *++match && *++scan == *++match && - *++scan == *++match && *++scan == *++match && - scan < strend); - - Assert(scan <= s->window+(unsigned)(s->window_size-1), "wild scan"); - - len = MAX_MATCH - (int)(strend - scan); - - if (len < MIN_MATCH) return MIN_MATCH - 1; - - s->match_start = cur_match; - return (uInt)len <= s->lookahead ? (uInt)len : s->lookahead; -} - -#ifdef DEBUG -/* =========================================================================== - * Check that the match at match_start is indeed a match. - */ -local void check_match(s, start, match, length) - deflate_state *s; - IPos start, match; - int length; -{ - /* check that the match is indeed a match */ - if (zmemcmp(s->window + match, - s->window + start, length) != EQUAL) { - fprintf(stderr, " start %u, match %u, length %d\n", - start, match, length); - do { - fprintf(stderr, "%c%c", s->window[match++], s->window[start++]); - } while (--length != 0); - z_error("invalid match"); - } - if (z_verbose > 1) { - fprintf(stderr,"\\[%d,%d]", start-match, length); - do { putc(s->window[start++], stderr); } while (--length != 0); - } -} -#else -# define check_match(s, start, match, length) -#endif /* DEBUG */ - -/* =========================================================================== - * Fill the window when the lookahead becomes insufficient. - * Updates strstart and lookahead. - * - * IN assertion: lookahead < MIN_LOOKAHEAD - * OUT assertions: strstart <= window_size-MIN_LOOKAHEAD - * At least one byte has been read, or avail_in == 0; reads are - * performed for at least two bytes (required for the zip translate_eol - * option -- not supported here). - */ -local void fill_window(s) - deflate_state *s; -{ - register unsigned n, m; - register Posf *p; - unsigned more; /* Amount of free space at the end of the window. */ - uInt wsize = s->w_size; - - do { - more = (unsigned)(s->window_size -(ulg)s->lookahead -(ulg)s->strstart); - - /* Deal with !@#$% 64K limit: */ - if (sizeof(int) <= 2) { - if (more == 0 && s->strstart == 0 && s->lookahead == 0) { - more = wsize; - - } else if (more == (unsigned)(-1)) { - /* Very unlikely, but possible on 16 bit machine if - * strstart == 0 && lookahead == 1 (input done a byte at time) - */ - more--; - } - } - - /* If the window is almost full and there is insufficient lookahead, - * move the upper half to the lower one to make room in the upper half. - */ - if (s->strstart >= wsize+MAX_DIST(s)) { - - zmemcpy(s->window, s->window+wsize, (unsigned)wsize); - s->match_start -= wsize; - s->strstart -= wsize; /* we now have strstart >= MAX_DIST */ - s->block_start -= (long) wsize; - - /* Slide the hash table (could be avoided with 32 bit values - at the expense of memory usage). We slide even when level == 0 - to keep the hash table consistent if we switch back to level > 0 - later. (Using level 0 permanently is not an optimal usage of - zlib, so we don't care about this pathological case.) - */ - /* %%% avoid this when Z_RLE */ - n = s->hash_size; - p = &s->head[n]; - do { - m = *--p; - *p = (Pos)(m >= wsize ? m-wsize : NIL); - } while (--n); - - n = wsize; -#ifndef FASTEST - p = &s->prev[n]; - do { - m = *--p; - *p = (Pos)(m >= wsize ? m-wsize : NIL); - /* If n is not on any hash chain, prev[n] is garbage but - * its value will never be used. - */ - } while (--n); -#endif - more += wsize; - } - if (s->strm->avail_in == 0) return; - - /* If there was no sliding: - * strstart <= WSIZE+MAX_DIST-1 && lookahead <= MIN_LOOKAHEAD - 1 && - * more == window_size - lookahead - strstart - * => more >= window_size - (MIN_LOOKAHEAD-1 + WSIZE + MAX_DIST-1) - * => more >= window_size - 2*WSIZE + 2 - * In the BIG_MEM or MMAP case (not yet supported), - * window_size == input_size + MIN_LOOKAHEAD && - * strstart + s->lookahead <= input_size => more >= MIN_LOOKAHEAD. - * Otherwise, window_size == 2*WSIZE so more >= 2. - * If there was sliding, more >= WSIZE. So in all cases, more >= 2. - */ - Assert(more >= 2, "more < 2"); - - n = read_buf(s->strm, s->window + s->strstart + s->lookahead, more); - s->lookahead += n; - - /* Initialize the hash value now that we have some input: */ - if (s->lookahead >= MIN_MATCH) { - s->ins_h = s->window[s->strstart]; - UPDATE_HASH(s, s->ins_h, s->window[s->strstart+1]); -#if MIN_MATCH != 3 - Call UPDATE_HASH() MIN_MATCH-3 more times -#endif - } - /* If the whole input has less than MIN_MATCH bytes, ins_h is garbage, - * but this is not important since only literal bytes will be emitted. - */ - - } while (s->lookahead < MIN_LOOKAHEAD && s->strm->avail_in != 0); -} - -/* =========================================================================== - * Flush the current block, with given end-of-file flag. - * IN assertion: strstart is set to the end of the current match. - */ -#define FLUSH_BLOCK_ONLY(s, eof) { \ - _tr_flush_block(s, (s->block_start >= 0L ? \ - (charf *)&s->window[(unsigned)s->block_start] : \ - (charf *)Z_NULL), \ - (ulg)((long)s->strstart - s->block_start), \ - (eof)); \ - s->block_start = s->strstart; \ - flush_pending(s->strm); \ - Tracev((stderr,"[FLUSH]")); \ -} - -/* Same but force premature exit if necessary. */ -#define FLUSH_BLOCK(s, eof) { \ - FLUSH_BLOCK_ONLY(s, eof); \ - if (s->strm->avail_out == 0) return (eof) ? finish_started : need_more; \ -} - -/* =========================================================================== - * Copy without compression as much as possible from the input stream, return - * the current block state. - * This function does not insert new strings in the dictionary since - * uncompressible data is probably not useful. This function is used - * only for the level=0 compression option. - * NOTE: this function should be optimized to avoid extra copying from - * window to pending_buf. - */ -local block_state deflate_stored(s, flush) - deflate_state *s; - int flush; -{ - /* Stored blocks are limited to 0xffff bytes, pending_buf is limited - * to pending_buf_size, and each stored block has a 5 byte header: - */ - ulg max_block_size = 0xffff; - ulg max_start; - - if (max_block_size > s->pending_buf_size - 5) { - max_block_size = s->pending_buf_size - 5; - } - - /* Copy as much as possible from input to output: */ - for (;;) { - /* Fill the window as much as possible: */ - if (s->lookahead <= 1) { - - Assert(s->strstart < s->w_size+MAX_DIST(s) || - s->block_start >= (long)s->w_size, "slide too late"); - - fill_window(s); - if (s->lookahead == 0 && flush == Z_NO_FLUSH) return need_more; - - if (s->lookahead == 0) break; /* flush the current block */ - } - Assert(s->block_start >= 0L, "block gone"); - - s->strstart += s->lookahead; - s->lookahead = 0; - - /* Emit a stored block if pending_buf will be full: */ - max_start = s->block_start + max_block_size; - if (s->strstart == 0 || (ulg)s->strstart >= max_start) { - /* strstart == 0 is possible when wraparound on 16-bit machine */ - s->lookahead = (uInt)(s->strstart - max_start); - s->strstart = (uInt)max_start; - FLUSH_BLOCK(s, 0); - } - /* Flush if we may have to slide, otherwise block_start may become - * negative and the data will be gone: - */ - if (s->strstart - (uInt)s->block_start >= MAX_DIST(s)) { - FLUSH_BLOCK(s, 0); - } - } - FLUSH_BLOCK(s, flush == Z_FINISH); - return flush == Z_FINISH ? finish_done : block_done; -} - -/* =========================================================================== - * Compress as much as possible from the input stream, return the current - * block state. - * This function does not perform lazy evaluation of matches and inserts - * new strings in the dictionary only for unmatched strings or for short - * matches. It is used only for the fast compression options. - */ -local block_state deflate_fast(s, flush) - deflate_state *s; - int flush; -{ - IPos hash_head = NIL; /* head of the hash chain */ - int bflush; /* set if current block must be flushed */ - - for (;;) { - /* Make sure that we always have enough lookahead, except - * at the end of the input file. We need MAX_MATCH bytes - * for the next match, plus MIN_MATCH bytes to insert the - * string following the next match. - */ - if (s->lookahead < MIN_LOOKAHEAD) { - fill_window(s); - if (s->lookahead < MIN_LOOKAHEAD && flush == Z_NO_FLUSH) { - return need_more; - } - if (s->lookahead == 0) break; /* flush the current block */ - } - - /* Insert the string window[strstart .. strstart+2] in the - * dictionary, and set hash_head to the head of the hash chain: - */ - if (s->lookahead >= MIN_MATCH) { - INSERT_STRING(s, s->strstart, hash_head); - } - - /* Find the longest match, discarding those <= prev_length. - * At this point we have always match_length < MIN_MATCH - */ - if (hash_head != NIL && s->strstart - hash_head <= MAX_DIST(s)) { - /* To simplify the code, we prevent matches with the string - * of window index 0 (in particular we have to avoid a match - * of the string with itself at the start of the input file). - */ -#ifdef FASTEST - if ((s->strategy != Z_HUFFMAN_ONLY && s->strategy != Z_RLE) || - (s->strategy == Z_RLE && s->strstart - hash_head == 1)) { - s->match_length = longest_match_fast (s, hash_head); - } -#else - if (s->strategy != Z_HUFFMAN_ONLY && s->strategy != Z_RLE) { - s->match_length = longest_match (s, hash_head); - } else if (s->strategy == Z_RLE && s->strstart - hash_head == 1) { - s->match_length = longest_match_fast (s, hash_head); - } -#endif - /* longest_match() or longest_match_fast() sets match_start */ - } - if (s->match_length >= MIN_MATCH) { - check_match(s, s->strstart, s->match_start, s->match_length); - - _tr_tally_dist(s, s->strstart - s->match_start, - s->match_length - MIN_MATCH, bflush); - - s->lookahead -= s->match_length; - - /* Insert new strings in the hash table only if the match length - * is not too large. This saves time but degrades compression. - */ -#ifndef FASTEST - if (s->match_length <= s->max_insert_length && - s->lookahead >= MIN_MATCH) { - s->match_length--; /* string at strstart already in table */ - do { - s->strstart++; - INSERT_STRING(s, s->strstart, hash_head); - /* strstart never exceeds WSIZE-MAX_MATCH, so there are - * always MIN_MATCH bytes ahead. - */ - } while (--s->match_length != 0); - s->strstart++; - } else -#endif - { - s->strstart += s->match_length; - s->match_length = 0; - s->ins_h = s->window[s->strstart]; - UPDATE_HASH(s, s->ins_h, s->window[s->strstart+1]); -#if MIN_MATCH != 3 - Call UPDATE_HASH() MIN_MATCH-3 more times -#endif - /* If lookahead < MIN_MATCH, ins_h is garbage, but it does not - * matter since it will be recomputed at next deflate call. - */ - } - } else { - /* No match, output a literal byte */ - Tracevv((stderr,"%c", s->window[s->strstart])); - _tr_tally_lit (s, s->window[s->strstart], bflush); - s->lookahead--; - s->strstart++; - } - if (bflush) FLUSH_BLOCK(s, 0); - } - FLUSH_BLOCK(s, flush == Z_FINISH); - return flush == Z_FINISH ? finish_done : block_done; -} - -#ifndef FASTEST -/* =========================================================================== - * Same as above, but achieves better compression. We use a lazy - * evaluation for matches: a match is finally adopted only if there is - * no better match at the next window position. - */ -local block_state deflate_slow(s, flush) - deflate_state *s; - int flush; -{ - IPos hash_head = NIL; /* head of hash chain */ - int bflush; /* set if current block must be flushed */ - - /* Process the input block. */ - for (;;) { - /* Make sure that we always have enough lookahead, except - * at the end of the input file. We need MAX_MATCH bytes - * for the next match, plus MIN_MATCH bytes to insert the - * string following the next match. - */ - if (s->lookahead < MIN_LOOKAHEAD) { - fill_window(s); - if (s->lookahead < MIN_LOOKAHEAD && flush == Z_NO_FLUSH) { - return need_more; - } - if (s->lookahead == 0) break; /* flush the current block */ - } - - /* Insert the string window[strstart .. strstart+2] in the - * dictionary, and set hash_head to the head of the hash chain: - */ - if (s->lookahead >= MIN_MATCH) { - INSERT_STRING(s, s->strstart, hash_head); - } - - /* Find the longest match, discarding those <= prev_length. - */ - s->prev_length = s->match_length, s->prev_match = s->match_start; - s->match_length = MIN_MATCH-1; - - if (hash_head != NIL && s->prev_length < s->max_lazy_match && - s->strstart - hash_head <= MAX_DIST(s)) { - /* To simplify the code, we prevent matches with the string - * of window index 0 (in particular we have to avoid a match - * of the string with itself at the start of the input file). - */ - if (s->strategy != Z_HUFFMAN_ONLY && s->strategy != Z_RLE) { - s->match_length = longest_match (s, hash_head); - } else if (s->strategy == Z_RLE && s->strstart - hash_head == 1) { - s->match_length = longest_match_fast (s, hash_head); - } - /* longest_match() or longest_match_fast() sets match_start */ - - if (s->match_length <= 5 && (s->strategy == Z_FILTERED -#if TOO_FAR <= 32767 - || (s->match_length == MIN_MATCH && - s->strstart - s->match_start > TOO_FAR) -#endif - )) { - - /* If prev_match is also MIN_MATCH, match_start is garbage - * but we will ignore the current match anyway. - */ - s->match_length = MIN_MATCH-1; - } - } - /* If there was a match at the previous step and the current - * match is not better, output the previous match: - */ - if (s->prev_length >= MIN_MATCH && s->match_length <= s->prev_length) { - uInt max_insert = s->strstart + s->lookahead - MIN_MATCH; - /* Do not insert strings in hash table beyond this. */ - - check_match(s, s->strstart-1, s->prev_match, s->prev_length); - - _tr_tally_dist(s, s->strstart -1 - s->prev_match, - s->prev_length - MIN_MATCH, bflush); - - /* Insert in hash table all strings up to the end of the match. - * strstart-1 and strstart are already inserted. If there is not - * enough lookahead, the last two strings are not inserted in - * the hash table. - */ - s->lookahead -= s->prev_length-1; - s->prev_length -= 2; - do { - if (++s->strstart <= max_insert) { - INSERT_STRING(s, s->strstart, hash_head); - } - } while (--s->prev_length != 0); - s->match_available = 0; - s->match_length = MIN_MATCH-1; - s->strstart++; - - if (bflush) FLUSH_BLOCK(s, 0); - - } else if (s->match_available) { - /* If there was no match at the previous position, output a - * single literal. If there was a match but the current match - * is longer, truncate the previous match to a single literal. - */ - Tracevv((stderr,"%c", s->window[s->strstart-1])); - _tr_tally_lit(s, s->window[s->strstart-1], bflush); - if (bflush) { - FLUSH_BLOCK_ONLY(s, 0); - } - s->strstart++; - s->lookahead--; - if (s->strm->avail_out == 0) return need_more; - } else { - /* There is no previous match to compare with, wait for - * the next step to decide. - */ - s->match_available = 1; - s->strstart++; - s->lookahead--; - } - } - Assert (flush != Z_NO_FLUSH, "no flush?"); - if (s->match_available) { - Tracevv((stderr,"%c", s->window[s->strstart-1])); - _tr_tally_lit(s, s->window[s->strstart-1], bflush); - s->match_available = 0; - } - FLUSH_BLOCK(s, flush == Z_FINISH); - return flush == Z_FINISH ? finish_done : block_done; -} -#endif /* FASTEST */ - -#if 0 -/* =========================================================================== - * For Z_RLE, simply look for runs of bytes, generate matches only of distance - * one. Do not maintain a hash table. (It will be regenerated if this run of - * deflate switches away from Z_RLE.) - */ -local block_state deflate_rle(s, flush) - deflate_state *s; - int flush; -{ - int bflush; /* set if current block must be flushed */ - uInt run; /* length of run */ - uInt max; /* maximum length of run */ - uInt prev; /* byte at distance one to match */ - Bytef *scan; /* scan for end of run */ - - for (;;) { - /* Make sure that we always have enough lookahead, except - * at the end of the input file. We need MAX_MATCH bytes - * for the longest encodable run. - */ - if (s->lookahead < MAX_MATCH) { - fill_window(s); - if (s->lookahead < MAX_MATCH && flush == Z_NO_FLUSH) { - return need_more; - } - if (s->lookahead == 0) break; /* flush the current block */ - } - - /* See how many times the previous byte repeats */ - run = 0; - if (s->strstart > 0) { /* if there is a previous byte, that is */ - max = s->lookahead < MAX_MATCH ? s->lookahead : MAX_MATCH; - scan = s->window + s->strstart - 1; - prev = *scan++; - do { - if (*scan++ != prev) - break; - } while (++run < max); - } - - /* Emit match if have run of MIN_MATCH or longer, else emit literal */ - if (run >= MIN_MATCH) { - check_match(s, s->strstart, s->strstart - 1, run); - _tr_tally_dist(s, 1, run - MIN_MATCH, bflush); - s->lookahead -= run; - s->strstart += run; - } else { - /* No match, output a literal byte */ - Tracevv((stderr,"%c", s->window[s->strstart])); - _tr_tally_lit (s, s->window[s->strstart], bflush); - s->lookahead--; - s->strstart++; - } - if (bflush) FLUSH_BLOCK(s, 0); - } - FLUSH_BLOCK(s, flush == Z_FINISH); - return flush == Z_FINISH ? finish_done : block_done; -} -#endif +/* deflate.c -- compress data using the deflation algorithm + * Copyright (C) 1995-2005 Jean-loup Gailly. + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* + * ALGORITHM + * + * The "deflation" process depends on being able to identify portions + * of the input text which are identical to earlier input (within a + * sliding window trailing behind the input currently being processed). + * + * The most straightforward technique turns out to be the fastest for + * most input files: try all possible matches and select the longest. + * The key feature of this algorithm is that insertions into the string + * dictionary are very simple and thus fast, and deletions are avoided + * completely. Insertions are performed at each input character, whereas + * string matches are performed only when the previous match ends. So it + * is preferable to spend more time in matches to allow very fast string + * insertions and avoid deletions. The matching algorithm for small + * strings is inspired from that of Rabin & Karp. A brute force approach + * is used to find longer strings when a small match has been found. + * A similar algorithm is used in comic (by Jan-Mark Wams) and freeze + * (by Leonid Broukhis). + * A previous version of this file used a more sophisticated algorithm + * (by Fiala and Greene) which is guaranteed to run in linear amortized + * time, but has a larger average cost, uses more memory and is patented. + * However the F&G algorithm may be faster for some highly redundant + * files if the parameter max_chain_length (described below) is too large. + * + * ACKNOWLEDGEMENTS + * + * The idea of lazy evaluation of matches is due to Jan-Mark Wams, and + * I found it in 'freeze' written by Leonid Broukhis. + * Thanks to many people for bug reports and testing. + * + * REFERENCES + * + * Deutsch, L.P.,"DEFLATE Compressed Data Format Specification". + * Available in http://www.ietf.org/rfc/rfc1951.txt + * + * A description of the Rabin and Karp algorithm is given in the book + * "Algorithms" by R. Sedgewick, Addison-Wesley, p252. + * + * Fiala,E.R., and Greene,D.H. + * Data Compression with Finite Windows, Comm.ACM, 32,4 (1989) 490-595 + * + */ + +/* @(#) $Id$ */ + +#include "deflate.h" + +const char deflate_copyright[] = + " deflate 1.2.3 Copyright 1995-2005 Jean-loup Gailly "; +/* + If you use the zlib library in a product, an acknowledgment is welcome + in the documentation of your product. If for some reason you cannot + include such an acknowledgment, I would appreciate that you keep this + copyright string in the executable of your product. + */ + +/* =========================================================================== + * Function prototypes. + */ +typedef enum { + need_more, /* block not completed, need more input or more output */ + block_done, /* block flush performed */ + finish_started, /* finish started, need only more output at next deflate */ + finish_done /* finish done, accept no more input or output */ +} block_state; + +typedef block_state (*compress_func) OF((deflate_state *s, int flush)); +/* Compression function. Returns the block state after the call. */ + +local void fill_window OF((deflate_state *s)); +local block_state deflate_stored OF((deflate_state *s, int flush)); +local block_state deflate_fast OF((deflate_state *s, int flush)); +#ifndef FASTEST +local block_state deflate_slow OF((deflate_state *s, int flush)); +#endif +local void lm_init OF((deflate_state *s)); +local void putShortMSB OF((deflate_state *s, uInt b)); +local void flush_pending OF((z_streamp strm)); +local int read_buf OF((z_streamp strm, Bytef *buf, unsigned size)); +#ifndef FASTEST +#ifdef ASMV + void match_init OF((void)); /* asm code initialization */ + uInt longest_match OF((deflate_state *s, IPos cur_match)); +#else +local uInt longest_match OF((deflate_state *s, IPos cur_match)); +#endif +#endif +local uInt longest_match_fast OF((deflate_state *s, IPos cur_match)); + +#ifdef DEBUG +local void check_match OF((deflate_state *s, IPos start, IPos match, + int length)); +#endif + +/* =========================================================================== + * Local data + */ + +#define NIL 0 +/* Tail of hash chains */ + +#ifndef TOO_FAR +# define TOO_FAR 4096 +#endif +/* Matches of length 3 are discarded if their distance exceeds TOO_FAR */ + +#define MIN_LOOKAHEAD (MAX_MATCH+MIN_MATCH+1) +/* Minimum amount of lookahead, except at the end of the input file. + * See deflate.c for comments about the MIN_MATCH+1. + */ + +/* Values for max_lazy_match, good_match and max_chain_length, depending on + * the desired pack level (0..9). The values given below have been tuned to + * exclude worst case performance for pathological files. Better values may be + * found for specific files. + */ +typedef struct config_s { + ush good_length; /* reduce lazy search above this match length */ + ush max_lazy; /* do not perform lazy search above this match length */ + ush nice_length; /* quit search above this match length */ + ush max_chain; + compress_func func; +} config; + +#ifdef FASTEST +local const config configuration_table[2] = { +/* good lazy nice chain */ +/* 0 */ {0, 0, 0, 0, deflate_stored}, /* store only */ +/* 1 */ {4, 4, 8, 4, deflate_fast}}; /* max speed, no lazy matches */ +#else +local const config configuration_table[10] = { +/* good lazy nice chain */ +/* 0 */ {0, 0, 0, 0, deflate_stored}, /* store only */ +/* 1 */ {4, 4, 8, 4, deflate_fast}, /* max speed, no lazy matches */ +/* 2 */ {4, 5, 16, 8, deflate_fast}, +/* 3 */ {4, 6, 32, 32, deflate_fast}, + +/* 4 */ {4, 4, 16, 16, deflate_slow}, /* lazy matches */ +/* 5 */ {8, 16, 32, 32, deflate_slow}, +/* 6 */ {8, 16, 128, 128, deflate_slow}, +/* 7 */ {8, 32, 128, 256, deflate_slow}, +/* 8 */ {32, 128, 258, 1024, deflate_slow}, +/* 9 */ {32, 258, 258, 4096, deflate_slow}}; /* max compression */ +#endif + +/* Note: the deflate() code requires max_lazy >= MIN_MATCH and max_chain >= 4 + * For deflate_fast() (levels <= 3) good is ignored and lazy has a different + * meaning. + */ + +#define EQUAL 0 +/* result of memcmp for equal strings */ + +#ifndef NO_DUMMY_DECL +struct static_tree_desc_s {int dummy;}; /* for buggy compilers */ +#endif + +/* =========================================================================== + * Update a hash value with the given input byte + * IN assertion: all calls to to UPDATE_HASH are made with consecutive + * input characters, so that a running hash key can be computed from the + * previous key instead of complete recalculation each time. + */ +#define UPDATE_HASH(s,h,c) (h = (((h)<hash_shift) ^ (c)) & s->hash_mask) + + +/* =========================================================================== + * Insert string str in the dictionary and set match_head to the previous head + * of the hash chain (the most recent string with same hash key). Return + * the previous length of the hash chain. + * If this file is compiled with -DFASTEST, the compression level is forced + * to 1, and no hash chains are maintained. + * IN assertion: all calls to to INSERT_STRING are made with consecutive + * input characters and the first MIN_MATCH bytes of str are valid + * (except for the last MIN_MATCH-1 bytes of the input file). + */ +#ifdef FASTEST +#define INSERT_STRING(s, str, match_head) \ + (UPDATE_HASH(s, s->ins_h, s->window[(str) + (MIN_MATCH-1)]), \ + match_head = s->head[s->ins_h], \ + s->head[s->ins_h] = (Pos)(str)) +#else +#define INSERT_STRING(s, str, match_head) \ + (UPDATE_HASH(s, s->ins_h, s->window[(str) + (MIN_MATCH-1)]), \ + match_head = s->prev[(str) & s->w_mask] = s->head[s->ins_h], \ + s->head[s->ins_h] = (Pos)(str)) +#endif + +/* =========================================================================== + * Initialize the hash table (avoiding 64K overflow for 16 bit systems). + * prev[] will be initialized on the fly. + */ +#define CLEAR_HASH(s) \ + s->head[s->hash_size-1] = NIL; \ + zmemzero((Bytef *)s->head, (unsigned)(s->hash_size-1)*sizeof(*s->head)); + +/* ========================================================================= */ +int ZEXPORT deflateInit_(strm, level, version, stream_size) + z_streamp strm; + int level; + const char *version; + int stream_size; +{ + return deflateInit2_(strm, level, Z_DEFLATED, MAX_WBITS, DEF_MEM_LEVEL, + Z_DEFAULT_STRATEGY, version, stream_size); + /* To do: ignore strm->next_in if we use it as window */ +} + +/* ========================================================================= */ +int ZEXPORT deflateInit2_(strm, level, method, windowBits, memLevel, strategy, + version, stream_size) + z_streamp strm; + int level; + int method; + int windowBits; + int memLevel; + int strategy; + const char *version; + int stream_size; +{ + deflate_state *s; + int wrap = 1; + static const char my_version[] = ZLIB_VERSION; + + ushf *overlay; + /* We overlay pending_buf and d_buf+l_buf. This works since the average + * output size for (length,distance) codes is <= 24 bits. + */ + + if (version == Z_NULL || version[0] != my_version[0] || + stream_size != sizeof(z_stream)) { + return Z_VERSION_ERROR; + } + if (strm == Z_NULL) return Z_STREAM_ERROR; + + strm->msg = Z_NULL; + if (strm->zalloc == (alloc_func)0) { + strm->zalloc = zcalloc; + strm->opaque = (voidpf)0; + } + if (strm->zfree == (free_func)0) strm->zfree = zcfree; + +#ifdef FASTEST + if (level != 0) level = 1; +#else + if (level == Z_DEFAULT_COMPRESSION) level = 6; +#endif + + if (windowBits < 0) { /* suppress zlib wrapper */ + wrap = 0; + windowBits = -windowBits; + } +#ifdef GZIP + else if (windowBits > 15) { + wrap = 2; /* write gzip wrapper instead */ + windowBits -= 16; + } +#endif + if (memLevel < 1 || memLevel > MAX_MEM_LEVEL || method != Z_DEFLATED || + windowBits < 8 || windowBits > 15 || level < 0 || level > 9 || + strategy < 0 || strategy > Z_FIXED) { + return Z_STREAM_ERROR; + } + if (windowBits == 8) windowBits = 9; /* until 256-byte window bug fixed */ + s = (deflate_state *) ZALLOC(strm, 1, sizeof(deflate_state)); + if (s == Z_NULL) return Z_MEM_ERROR; + strm->state = (struct internal_state FAR *)s; + s->strm = strm; + + s->wrap = wrap; + s->gzhead = Z_NULL; + s->w_bits = windowBits; + s->w_size = 1 << s->w_bits; + s->w_mask = s->w_size - 1; + + s->hash_bits = memLevel + 7; + s->hash_size = 1 << s->hash_bits; + s->hash_mask = s->hash_size - 1; + s->hash_shift = ((s->hash_bits+MIN_MATCH-1)/MIN_MATCH); + + s->window = (Bytef *) ZALLOC(strm, s->w_size, 2*sizeof(Byte)); + s->prev = (Posf *) ZALLOC(strm, s->w_size, sizeof(Pos)); + s->head = (Posf *) ZALLOC(strm, s->hash_size, sizeof(Pos)); + + s->lit_bufsize = 1 << (memLevel + 6); /* 16K elements by default */ + + overlay = (ushf *) ZALLOC(strm, s->lit_bufsize, sizeof(ush)+2); + s->pending_buf = (uchf *) overlay; + s->pending_buf_size = (ulg)s->lit_bufsize * (sizeof(ush)+2L); + + if (s->window == Z_NULL || s->prev == Z_NULL || s->head == Z_NULL || + s->pending_buf == Z_NULL) { + s->status = FINISH_STATE; + strm->msg = (char*)ERR_MSG(Z_MEM_ERROR); + deflateEnd (strm); + return Z_MEM_ERROR; + } + s->d_buf = overlay + s->lit_bufsize/sizeof(ush); + s->l_buf = s->pending_buf + (1+sizeof(ush))*s->lit_bufsize; + + s->level = level; + s->strategy = strategy; + s->method = (Byte)method; + + return deflateReset(strm); +} + +/* ========================================================================= */ +int ZEXPORT deflateSetDictionary (strm, dictionary, dictLength) + z_streamp strm; + const Bytef *dictionary; + uInt dictLength; +{ + deflate_state *s; + uInt length = dictLength; + uInt n; + IPos hash_head = 0; + + if (strm == Z_NULL || strm->state == Z_NULL || dictionary == Z_NULL || + strm->state->wrap == 2 || + (strm->state->wrap == 1 && strm->state->status != INIT_STATE)) + return Z_STREAM_ERROR; + + s = strm->state; + if (s->wrap) + strm->adler = adler32(strm->adler, dictionary, dictLength); + + if (length < MIN_MATCH) return Z_OK; + if (length > MAX_DIST(s)) { + length = MAX_DIST(s); + dictionary += dictLength - length; /* use the tail of the dictionary */ + } + zmemcpy(s->window, dictionary, length); + s->strstart = length; + s->block_start = (long)length; + + /* Insert all strings in the hash table (except for the last two bytes). + * s->lookahead stays null, so s->ins_h will be recomputed at the next + * call of fill_window. + */ + s->ins_h = s->window[0]; + UPDATE_HASH(s, s->ins_h, s->window[1]); + for (n = 0; n <= length - MIN_MATCH; n++) { + INSERT_STRING(s, n, hash_head); + } + if (hash_head) hash_head = 0; /* to make compiler happy */ + return Z_OK; +} + +/* ========================================================================= */ +int ZEXPORT deflateReset (strm) + z_streamp strm; +{ + deflate_state *s; + + if (strm == Z_NULL || strm->state == Z_NULL || + strm->zalloc == (alloc_func)0 || strm->zfree == (free_func)0) { + return Z_STREAM_ERROR; + } + + strm->total_in = strm->total_out = 0; + strm->msg = Z_NULL; /* use zfree if we ever allocate msg dynamically */ + strm->data_type = Z_UNKNOWN; + + s = (deflate_state *)strm->state; + s->pending = 0; + s->pending_out = s->pending_buf; + + if (s->wrap < 0) { + s->wrap = -s->wrap; /* was made negative by deflate(..., Z_FINISH); */ + } + s->status = s->wrap ? INIT_STATE : BUSY_STATE; + strm->adler = +#ifdef GZIP + s->wrap == 2 ? crc32(0L, Z_NULL, 0) : +#endif + adler32(0L, Z_NULL, 0); + s->last_flush = Z_NO_FLUSH; + + _tr_init(s); + lm_init(s); + + return Z_OK; +} + +/* ========================================================================= */ +int ZEXPORT deflateSetHeader (strm, head) + z_streamp strm; + gz_headerp head; +{ + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + if (strm->state->wrap != 2) return Z_STREAM_ERROR; + strm->state->gzhead = head; + return Z_OK; +} + +/* ========================================================================= */ +int ZEXPORT deflatePrime (strm, bits, value) + z_streamp strm; + int bits; + int value; +{ + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + strm->state->bi_valid = bits; + strm->state->bi_buf = (ush)(value & ((1 << bits) - 1)); + return Z_OK; +} + +/* ========================================================================= */ +int ZEXPORT deflateParams(strm, level, strategy) + z_streamp strm; + int level; + int strategy; +{ + deflate_state *s; + compress_func func; + int err = Z_OK; + + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + s = strm->state; + +#ifdef FASTEST + if (level != 0) level = 1; +#else + if (level == Z_DEFAULT_COMPRESSION) level = 6; +#endif + if (level < 0 || level > 9 || strategy < 0 || strategy > Z_FIXED) { + return Z_STREAM_ERROR; + } + func = configuration_table[s->level].func; + + if (func != configuration_table[level].func && strm->total_in != 0) { + /* Flush the last buffer: */ + err = deflate(strm, Z_PARTIAL_FLUSH); + } + if (s->level != level) { + s->level = level; + s->max_lazy_match = configuration_table[level].max_lazy; + s->good_match = configuration_table[level].good_length; + s->nice_match = configuration_table[level].nice_length; + s->max_chain_length = configuration_table[level].max_chain; + } + s->strategy = strategy; + return err; +} + +/* ========================================================================= */ +int ZEXPORT deflateTune(strm, good_length, max_lazy, nice_length, max_chain) + z_streamp strm; + int good_length; + int max_lazy; + int nice_length; + int max_chain; +{ + deflate_state *s; + + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + s = strm->state; + s->good_match = good_length; + s->max_lazy_match = max_lazy; + s->nice_match = nice_length; + s->max_chain_length = max_chain; + return Z_OK; +} + +/* ========================================================================= + * For the default windowBits of 15 and memLevel of 8, this function returns + * a close to exact, as well as small, upper bound on the compressed size. + * They are coded as constants here for a reason--if the #define's are + * changed, then this function needs to be changed as well. The return + * value for 15 and 8 only works for those exact settings. + * + * For any setting other than those defaults for windowBits and memLevel, + * the value returned is a conservative worst case for the maximum expansion + * resulting from using fixed blocks instead of stored blocks, which deflate + * can emit on compressed data for some combinations of the parameters. + * + * This function could be more sophisticated to provide closer upper bounds + * for every combination of windowBits and memLevel, as well as wrap. + * But even the conservative upper bound of about 14% expansion does not + * seem onerous for output buffer allocation. + */ +uLong ZEXPORT deflateBound(strm, sourceLen) + z_streamp strm; + uLong sourceLen; +{ + deflate_state *s; + uLong destLen; + + /* conservative upper bound */ + destLen = sourceLen + + ((sourceLen + 7) >> 3) + ((sourceLen + 63) >> 6) + 11; + + /* if can't get parameters, return conservative bound */ + if (strm == Z_NULL || strm->state == Z_NULL) + return destLen; + + /* if not default parameters, return conservative bound */ + s = strm->state; + if (s->w_bits != 15 || s->hash_bits != 8 + 7) + return destLen; + + /* default settings: return tight bound for that case */ + return compressBound(sourceLen); +} + +/* ========================================================================= + * Put a short in the pending buffer. The 16-bit value is put in MSB order. + * IN assertion: the stream state is correct and there is enough room in + * pending_buf. + */ +local void putShortMSB (s, b) + deflate_state *s; + uInt b; +{ + put_byte(s, (Byte)(b >> 8)); + put_byte(s, (Byte)(b & 0xff)); +} + +/* ========================================================================= + * Flush as much pending output as possible. All deflate() output goes + * through this function so some applications may wish to modify it + * to avoid allocating a large strm->next_out buffer and copying into it. + * (See also read_buf()). + */ +local void flush_pending(strm) + z_streamp strm; +{ + unsigned len = strm->state->pending; + + if (len > strm->avail_out) len = strm->avail_out; + if (len == 0) return; + + zmemcpy(strm->next_out, strm->state->pending_out, len); + strm->next_out += len; + strm->state->pending_out += len; + strm->total_out += len; + strm->avail_out -= len; + strm->state->pending -= len; + if (strm->state->pending == 0) { + strm->state->pending_out = strm->state->pending_buf; + } +} + +/* ========================================================================= */ +int ZEXPORT deflate (strm, flush) + z_streamp strm; + int flush; +{ + int old_flush; /* value of flush param for previous deflate call */ + deflate_state *s; + + if (strm == Z_NULL || strm->state == Z_NULL || + flush > Z_FINISH || flush < 0) { + return Z_STREAM_ERROR; + } + s = strm->state; + + if (strm->next_out == Z_NULL || + (strm->next_in == Z_NULL && strm->avail_in != 0) || + (s->status == FINISH_STATE && flush != Z_FINISH)) { + ERR_RETURN(strm, Z_STREAM_ERROR); + } + if (strm->avail_out == 0) ERR_RETURN(strm, Z_BUF_ERROR); + + s->strm = strm; /* just in case */ + old_flush = s->last_flush; + s->last_flush = flush; + + /* Write the header */ + if (s->status == INIT_STATE) { +#ifdef GZIP + if (s->wrap == 2) { + strm->adler = crc32(0L, Z_NULL, 0); + put_byte(s, 31); + put_byte(s, 139); + put_byte(s, 8); + if (s->gzhead == NULL) { + put_byte(s, 0); + put_byte(s, 0); + put_byte(s, 0); + put_byte(s, 0); + put_byte(s, 0); + put_byte(s, s->level == 9 ? 2 : + (s->strategy >= Z_HUFFMAN_ONLY || s->level < 2 ? + 4 : 0)); + put_byte(s, OS_CODE); + s->status = BUSY_STATE; + } + else { + put_byte(s, (s->gzhead->text ? 1 : 0) + + (s->gzhead->hcrc ? 2 : 0) + + (s->gzhead->extra == Z_NULL ? 0 : 4) + + (s->gzhead->name == Z_NULL ? 0 : 8) + + (s->gzhead->comment == Z_NULL ? 0 : 16) + ); + put_byte(s, (Byte)(s->gzhead->time & 0xff)); + put_byte(s, (Byte)((s->gzhead->time >> 8) & 0xff)); + put_byte(s, (Byte)((s->gzhead->time >> 16) & 0xff)); + put_byte(s, (Byte)((s->gzhead->time >> 24) & 0xff)); + put_byte(s, s->level == 9 ? 2 : + (s->strategy >= Z_HUFFMAN_ONLY || s->level < 2 ? + 4 : 0)); + put_byte(s, s->gzhead->os & 0xff); + if (s->gzhead->extra != NULL) { + put_byte(s, s->gzhead->extra_len & 0xff); + put_byte(s, (s->gzhead->extra_len >> 8) & 0xff); + } + if (s->gzhead->hcrc) + strm->adler = crc32(strm->adler, s->pending_buf, + s->pending); + s->gzindex = 0; + s->status = EXTRA_STATE; + } + } + else +#endif + { + uInt header = (Z_DEFLATED + ((s->w_bits-8)<<4)) << 8; + uInt level_flags; + + if (s->strategy >= Z_HUFFMAN_ONLY || s->level < 2) + level_flags = 0; + else if (s->level < 6) + level_flags = 1; + else if (s->level == 6) + level_flags = 2; + else + level_flags = 3; + header |= (level_flags << 6); + if (s->strstart != 0) header |= PRESET_DICT; + header += 31 - (header % 31); + + s->status = BUSY_STATE; + putShortMSB(s, header); + + /* Save the adler32 of the preset dictionary: */ + if (s->strstart != 0) { + putShortMSB(s, (uInt)(strm->adler >> 16)); + putShortMSB(s, (uInt)(strm->adler & 0xffff)); + } + strm->adler = adler32(0L, Z_NULL, 0); + } + } +#ifdef GZIP + if (s->status == EXTRA_STATE) { + if (s->gzhead->extra != NULL) { + uInt beg = s->pending; /* start of bytes to update crc */ + + while (s->gzindex < (s->gzhead->extra_len & 0xffff)) { + if (s->pending == s->pending_buf_size) { + if (s->gzhead->hcrc && s->pending > beg) + strm->adler = crc32(strm->adler, s->pending_buf + beg, + s->pending - beg); + flush_pending(strm); + beg = s->pending; + if (s->pending == s->pending_buf_size) + break; + } + put_byte(s, s->gzhead->extra[s->gzindex]); + s->gzindex++; + } + if (s->gzhead->hcrc && s->pending > beg) + strm->adler = crc32(strm->adler, s->pending_buf + beg, + s->pending - beg); + if (s->gzindex == s->gzhead->extra_len) { + s->gzindex = 0; + s->status = NAME_STATE; + } + } + else + s->status = NAME_STATE; + } + if (s->status == NAME_STATE) { + if (s->gzhead->name != NULL) { + uInt beg = s->pending; /* start of bytes to update crc */ + int val; + + do { + if (s->pending == s->pending_buf_size) { + if (s->gzhead->hcrc && s->pending > beg) + strm->adler = crc32(strm->adler, s->pending_buf + beg, + s->pending - beg); + flush_pending(strm); + beg = s->pending; + if (s->pending == s->pending_buf_size) { + val = 1; + break; + } + } + val = s->gzhead->name[s->gzindex++]; + put_byte(s, val); + } while (val != 0); + if (s->gzhead->hcrc && s->pending > beg) + strm->adler = crc32(strm->adler, s->pending_buf + beg, + s->pending - beg); + if (val == 0) { + s->gzindex = 0; + s->status = COMMENT_STATE; + } + } + else + s->status = COMMENT_STATE; + } + if (s->status == COMMENT_STATE) { + if (s->gzhead->comment != NULL) { + uInt beg = s->pending; /* start of bytes to update crc */ + int val; + + do { + if (s->pending == s->pending_buf_size) { + if (s->gzhead->hcrc && s->pending > beg) + strm->adler = crc32(strm->adler, s->pending_buf + beg, + s->pending - beg); + flush_pending(strm); + beg = s->pending; + if (s->pending == s->pending_buf_size) { + val = 1; + break; + } + } + val = s->gzhead->comment[s->gzindex++]; + put_byte(s, val); + } while (val != 0); + if (s->gzhead->hcrc && s->pending > beg) + strm->adler = crc32(strm->adler, s->pending_buf + beg, + s->pending - beg); + if (val == 0) + s->status = HCRC_STATE; + } + else + s->status = HCRC_STATE; + } + if (s->status == HCRC_STATE) { + if (s->gzhead->hcrc) { + if (s->pending + 2 > s->pending_buf_size) + flush_pending(strm); + if (s->pending + 2 <= s->pending_buf_size) { + put_byte(s, (Byte)(strm->adler & 0xff)); + put_byte(s, (Byte)((strm->adler >> 8) & 0xff)); + strm->adler = crc32(0L, Z_NULL, 0); + s->status = BUSY_STATE; + } + } + else + s->status = BUSY_STATE; + } +#endif + + /* Flush as much pending output as possible */ + if (s->pending != 0) { + flush_pending(strm); + if (strm->avail_out == 0) { + /* Since avail_out is 0, deflate will be called again with + * more output space, but possibly with both pending and + * avail_in equal to zero. There won't be anything to do, + * but this is not an error situation so make sure we + * return OK instead of BUF_ERROR at next call of deflate: + */ + s->last_flush = -1; + return Z_OK; + } + + /* Make sure there is something to do and avoid duplicate consecutive + * flushes. For repeated and useless calls with Z_FINISH, we keep + * returning Z_STREAM_END instead of Z_BUF_ERROR. + */ + } else if (strm->avail_in == 0 && flush <= old_flush && + flush != Z_FINISH) { + ERR_RETURN(strm, Z_BUF_ERROR); + } + + /* User must not provide more input after the first FINISH: */ + if (s->status == FINISH_STATE && strm->avail_in != 0) { + ERR_RETURN(strm, Z_BUF_ERROR); + } + + /* Start a new block or continue the current one. + */ + if (strm->avail_in != 0 || s->lookahead != 0 || + (flush != Z_NO_FLUSH && s->status != FINISH_STATE)) { + block_state bstate; + + bstate = (*(configuration_table[s->level].func))(s, flush); + + if (bstate == finish_started || bstate == finish_done) { + s->status = FINISH_STATE; + } + if (bstate == need_more || bstate == finish_started) { + if (strm->avail_out == 0) { + s->last_flush = -1; /* avoid BUF_ERROR next call, see above */ + } + return Z_OK; + /* If flush != Z_NO_FLUSH && avail_out == 0, the next call + * of deflate should use the same flush parameter to make sure + * that the flush is complete. So we don't have to output an + * empty block here, this will be done at next call. This also + * ensures that for a very small output buffer, we emit at most + * one empty block. + */ + } + if (bstate == block_done) { + if (flush == Z_PARTIAL_FLUSH) { + _tr_align(s); + } else { /* FULL_FLUSH or SYNC_FLUSH */ + _tr_stored_block(s, (char*)0, 0L, 0); + /* For a full flush, this empty block will be recognized + * as a special marker by inflate_sync(). + */ + if (flush == Z_FULL_FLUSH) { + CLEAR_HASH(s); /* forget history */ + } + } + flush_pending(strm); + if (strm->avail_out == 0) { + s->last_flush = -1; /* avoid BUF_ERROR at next call, see above */ + return Z_OK; + } + } + } + Assert(strm->avail_out > 0, "bug2"); + + if (flush != Z_FINISH) return Z_OK; + if (s->wrap <= 0) return Z_STREAM_END; + + /* Write the trailer */ +#ifdef GZIP + if (s->wrap == 2) { + put_byte(s, (Byte)(strm->adler & 0xff)); + put_byte(s, (Byte)((strm->adler >> 8) & 0xff)); + put_byte(s, (Byte)((strm->adler >> 16) & 0xff)); + put_byte(s, (Byte)((strm->adler >> 24) & 0xff)); + put_byte(s, (Byte)(strm->total_in & 0xff)); + put_byte(s, (Byte)((strm->total_in >> 8) & 0xff)); + put_byte(s, (Byte)((strm->total_in >> 16) & 0xff)); + put_byte(s, (Byte)((strm->total_in >> 24) & 0xff)); + } + else +#endif + { + putShortMSB(s, (uInt)(strm->adler >> 16)); + putShortMSB(s, (uInt)(strm->adler & 0xffff)); + } + flush_pending(strm); + /* If avail_out is zero, the application will call deflate again + * to flush the rest. + */ + if (s->wrap > 0) s->wrap = -s->wrap; /* write the trailer only once! */ + return s->pending != 0 ? Z_OK : Z_STREAM_END; +} + +/* ========================================================================= */ +int ZEXPORT deflateEnd (strm) + z_streamp strm; +{ + int status; + + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + + status = strm->state->status; + if (status != INIT_STATE && + status != EXTRA_STATE && + status != NAME_STATE && + status != COMMENT_STATE && + status != HCRC_STATE && + status != BUSY_STATE && + status != FINISH_STATE) { + return Z_STREAM_ERROR; + } + + /* Deallocate in reverse order of allocations: */ + TRY_FREE(strm, strm->state->pending_buf); + TRY_FREE(strm, strm->state->head); + TRY_FREE(strm, strm->state->prev); + TRY_FREE(strm, strm->state->window); + + ZFREE(strm, strm->state); + strm->state = Z_NULL; + + return status == BUSY_STATE ? Z_DATA_ERROR : Z_OK; +} + +/* ========================================================================= + * Copy the source state to the destination state. + * To simplify the source, this is not supported for 16-bit MSDOS (which + * doesn't have enough memory anyway to duplicate compression states). + */ +int ZEXPORT deflateCopy (dest, source) + z_streamp dest; + z_streamp source; +{ +#ifdef MAXSEG_64K + return Z_STREAM_ERROR; +#else + deflate_state *ds; + deflate_state *ss; + ushf *overlay; + + + if (source == Z_NULL || dest == Z_NULL || source->state == Z_NULL) { + return Z_STREAM_ERROR; + } + + ss = source->state; + + zmemcpy(dest, source, sizeof(z_stream)); + + ds = (deflate_state *) ZALLOC(dest, 1, sizeof(deflate_state)); + if (ds == Z_NULL) return Z_MEM_ERROR; + dest->state = (struct internal_state FAR *) ds; + zmemcpy(ds, ss, sizeof(deflate_state)); + ds->strm = dest; + + ds->window = (Bytef *) ZALLOC(dest, ds->w_size, 2*sizeof(Byte)); + ds->prev = (Posf *) ZALLOC(dest, ds->w_size, sizeof(Pos)); + ds->head = (Posf *) ZALLOC(dest, ds->hash_size, sizeof(Pos)); + overlay = (ushf *) ZALLOC(dest, ds->lit_bufsize, sizeof(ush)+2); + ds->pending_buf = (uchf *) overlay; + + if (ds->window == Z_NULL || ds->prev == Z_NULL || ds->head == Z_NULL || + ds->pending_buf == Z_NULL) { + deflateEnd (dest); + return Z_MEM_ERROR; + } + /* following zmemcpy do not work for 16-bit MSDOS */ + zmemcpy(ds->window, ss->window, ds->w_size * 2 * sizeof(Byte)); + zmemcpy(ds->prev, ss->prev, ds->w_size * sizeof(Pos)); + zmemcpy(ds->head, ss->head, ds->hash_size * sizeof(Pos)); + zmemcpy(ds->pending_buf, ss->pending_buf, (uInt)ds->pending_buf_size); + + ds->pending_out = ds->pending_buf + (ss->pending_out - ss->pending_buf); + ds->d_buf = overlay + ds->lit_bufsize/sizeof(ush); + ds->l_buf = ds->pending_buf + (1+sizeof(ush))*ds->lit_bufsize; + + ds->l_desc.dyn_tree = ds->dyn_ltree; + ds->d_desc.dyn_tree = ds->dyn_dtree; + ds->bl_desc.dyn_tree = ds->bl_tree; + + return Z_OK; +#endif /* MAXSEG_64K */ +} + +/* =========================================================================== + * Read a new buffer from the current input stream, update the adler32 + * and total number of bytes read. All deflate() input goes through + * this function so some applications may wish to modify it to avoid + * allocating a large strm->next_in buffer and copying from it. + * (See also flush_pending()). + */ +local int read_buf(strm, buf, size) + z_streamp strm; + Bytef *buf; + unsigned size; +{ + unsigned len = strm->avail_in; + + if (len > size) len = size; + if (len == 0) return 0; + + strm->avail_in -= len; + + if (strm->state->wrap == 1) { + strm->adler = adler32(strm->adler, strm->next_in, len); + } +#ifdef GZIP + else if (strm->state->wrap == 2) { + strm->adler = crc32(strm->adler, strm->next_in, len); + } +#endif + zmemcpy(buf, strm->next_in, len); + strm->next_in += len; + strm->total_in += len; + + return (int)len; +} + +/* =========================================================================== + * Initialize the "longest match" routines for a new zlib stream + */ +local void lm_init (s) + deflate_state *s; +{ + s->window_size = (ulg)2L*s->w_size; + + CLEAR_HASH(s); + + /* Set the default configuration parameters: + */ + s->max_lazy_match = configuration_table[s->level].max_lazy; + s->good_match = configuration_table[s->level].good_length; + s->nice_match = configuration_table[s->level].nice_length; + s->max_chain_length = configuration_table[s->level].max_chain; + + s->strstart = 0; + s->block_start = 0L; + s->lookahead = 0; + s->match_length = s->prev_length = MIN_MATCH-1; + s->match_available = 0; + s->ins_h = 0; +#ifndef FASTEST +#ifdef ASMV + match_init(); /* initialize the asm code */ +#endif +#endif +} + +#ifndef FASTEST +/* =========================================================================== + * Set match_start to the longest match starting at the given string and + * return its length. Matches shorter or equal to prev_length are discarded, + * in which case the result is equal to prev_length and match_start is + * garbage. + * IN assertions: cur_match is the head of the hash chain for the current + * string (strstart) and its distance is <= MAX_DIST, and prev_length >= 1 + * OUT assertion: the match length is not greater than s->lookahead. + */ +#ifndef ASMV +/* For 80x86 and 680x0, an optimized version will be provided in match.asm or + * match.S. The code will be functionally equivalent. + */ +local uInt longest_match(s, cur_match) + deflate_state *s; + IPos cur_match; /* current match */ +{ + unsigned chain_length = s->max_chain_length;/* max hash chain length */ + register Bytef *scan = s->window + s->strstart; /* current string */ + register Bytef *match; /* matched string */ + register int len; /* length of current match */ + int best_len = s->prev_length; /* best match length so far */ + int nice_match = s->nice_match; /* stop if match long enough */ + IPos limit = s->strstart > (IPos)MAX_DIST(s) ? + s->strstart - (IPos)MAX_DIST(s) : NIL; + /* Stop when cur_match becomes <= limit. To simplify the code, + * we prevent matches with the string of window index 0. + */ + Posf *prev = s->prev; + uInt wmask = s->w_mask; + +#ifdef UNALIGNED_OK + /* Compare two bytes at a time. Note: this is not always beneficial. + * Try with and without -DUNALIGNED_OK to check. + */ + register Bytef *strend = s->window + s->strstart + MAX_MATCH - 1; + register ush scan_start = *(ushf*)scan; + register ush scan_end = *(ushf*)(scan+best_len-1); +#else + register Bytef *strend = s->window + s->strstart + MAX_MATCH; + register Byte scan_end1 = scan[best_len-1]; + register Byte scan_end = scan[best_len]; +#endif + + /* The code is optimized for HASH_BITS >= 8 and MAX_MATCH-2 multiple of 16. + * It is easy to get rid of this optimization if necessary. + */ + Assert(s->hash_bits >= 8 && MAX_MATCH == 258, "Code too clever"); + + /* Do not waste too much time if we already have a good match: */ + if (s->prev_length >= s->good_match) { + chain_length >>= 2; + } + /* Do not look for matches beyond the end of the input. This is necessary + * to make deflate deterministic. + */ + if ((uInt)nice_match > s->lookahead) nice_match = s->lookahead; + + Assert((ulg)s->strstart <= s->window_size-MIN_LOOKAHEAD, "need lookahead"); + + do { + Assert(cur_match < s->strstart, "no future"); + match = s->window + cur_match; + + /* Skip to next match if the match length cannot increase + * or if the match length is less than 2. Note that the checks below + * for insufficient lookahead only occur occasionally for performance + * reasons. Therefore uninitialized memory will be accessed, and + * conditional jumps will be made that depend on those values. + * However the length of the match is limited to the lookahead, so + * the output of deflate is not affected by the uninitialized values. + */ +#if (defined(UNALIGNED_OK) && MAX_MATCH == 258) + /* This code assumes sizeof(unsigned short) == 2. Do not use + * UNALIGNED_OK if your compiler uses a different size. + */ + if (*(ushf*)(match+best_len-1) != scan_end || + *(ushf*)match != scan_start) continue; + + /* It is not necessary to compare scan[2] and match[2] since they are + * always equal when the other bytes match, given that the hash keys + * are equal and that HASH_BITS >= 8. Compare 2 bytes at a time at + * strstart+3, +5, ... up to strstart+257. We check for insufficient + * lookahead only every 4th comparison; the 128th check will be made + * at strstart+257. If MAX_MATCH-2 is not a multiple of 8, it is + * necessary to put more guard bytes at the end of the window, or + * to check more often for insufficient lookahead. + */ + Assert(scan[2] == match[2], "scan[2]?"); + scan++, match++; + do { + } while (*(ushf*)(scan+=2) == *(ushf*)(match+=2) && + *(ushf*)(scan+=2) == *(ushf*)(match+=2) && + *(ushf*)(scan+=2) == *(ushf*)(match+=2) && + *(ushf*)(scan+=2) == *(ushf*)(match+=2) && + scan < strend); + /* The funny "do {}" generates better code on most compilers */ + + /* Here, scan <= window+strstart+257 */ + Assert(scan <= s->window+(unsigned)(s->window_size-1), "wild scan"); + if (*scan == *match) scan++; + + len = (MAX_MATCH - 1) - (int)(strend-scan); + scan = strend - (MAX_MATCH-1); + +#else /* UNALIGNED_OK */ + + if (match[best_len] != scan_end || + match[best_len-1] != scan_end1 || + *match != *scan || + *++match != scan[1]) continue; + + /* The check at best_len-1 can be removed because it will be made + * again later. (This heuristic is not always a win.) + * It is not necessary to compare scan[2] and match[2] since they + * are always equal when the other bytes match, given that + * the hash keys are equal and that HASH_BITS >= 8. + */ + scan += 2, match++; + Assert(*scan == *match, "match[2]?"); + + /* We check for insufficient lookahead only every 8th comparison; + * the 256th check will be made at strstart+258. + */ + do { + } while (*++scan == *++match && *++scan == *++match && + *++scan == *++match && *++scan == *++match && + *++scan == *++match && *++scan == *++match && + *++scan == *++match && *++scan == *++match && + scan < strend); + + Assert(scan <= s->window+(unsigned)(s->window_size-1), "wild scan"); + + len = MAX_MATCH - (int)(strend - scan); + scan = strend - MAX_MATCH; + +#endif /* UNALIGNED_OK */ + + if (len > best_len) { + s->match_start = cur_match; + best_len = len; + if (len >= nice_match) break; +#ifdef UNALIGNED_OK + scan_end = *(ushf*)(scan+best_len-1); +#else + scan_end1 = scan[best_len-1]; + scan_end = scan[best_len]; +#endif + } + } while ((cur_match = prev[cur_match & wmask]) > limit + && --chain_length != 0); + + if ((uInt)best_len <= s->lookahead) return (uInt)best_len; + return s->lookahead; +} +#endif /* ASMV */ +#endif /* FASTEST */ + +/* --------------------------------------------------------------------------- + * Optimized version for level == 1 or strategy == Z_RLE only + */ +local uInt longest_match_fast(s, cur_match) + deflate_state *s; + IPos cur_match; /* current match */ +{ + register Bytef *scan = s->window + s->strstart; /* current string */ + register Bytef *match; /* matched string */ + register int len; /* length of current match */ + register Bytef *strend = s->window + s->strstart + MAX_MATCH; + + /* The code is optimized for HASH_BITS >= 8 and MAX_MATCH-2 multiple of 16. + * It is easy to get rid of this optimization if necessary. + */ + Assert(s->hash_bits >= 8 && MAX_MATCH == 258, "Code too clever"); + + Assert((ulg)s->strstart <= s->window_size-MIN_LOOKAHEAD, "need lookahead"); + + Assert(cur_match < s->strstart, "no future"); + + match = s->window + cur_match; + + /* Return failure if the match length is less than 2: + */ + if (match[0] != scan[0] || match[1] != scan[1]) return MIN_MATCH-1; + + /* The check at best_len-1 can be removed because it will be made + * again later. (This heuristic is not always a win.) + * It is not necessary to compare scan[2] and match[2] since they + * are always equal when the other bytes match, given that + * the hash keys are equal and that HASH_BITS >= 8. + */ + scan += 2, match += 2; + Assert(*scan == *match, "match[2]?"); + + /* We check for insufficient lookahead only every 8th comparison; + * the 256th check will be made at strstart+258. + */ + do { + } while (*++scan == *++match && *++scan == *++match && + *++scan == *++match && *++scan == *++match && + *++scan == *++match && *++scan == *++match && + *++scan == *++match && *++scan == *++match && + scan < strend); + + Assert(scan <= s->window+(unsigned)(s->window_size-1), "wild scan"); + + len = MAX_MATCH - (int)(strend - scan); + + if (len < MIN_MATCH) return MIN_MATCH - 1; + + s->match_start = cur_match; + return (uInt)len <= s->lookahead ? (uInt)len : s->lookahead; +} + +#ifdef DEBUG +/* =========================================================================== + * Check that the match at match_start is indeed a match. + */ +local void check_match(s, start, match, length) + deflate_state *s; + IPos start, match; + int length; +{ + /* check that the match is indeed a match */ + if (zmemcmp(s->window + match, + s->window + start, length) != EQUAL) { + fprintf(stderr, " start %u, match %u, length %d\n", + start, match, length); + do { + fprintf(stderr, "%c%c", s->window[match++], s->window[start++]); + } while (--length != 0); + z_error("invalid match"); + } + if (z_verbose > 1) { + fprintf(stderr,"\\[%d,%d]", start-match, length); + do { putc(s->window[start++], stderr); } while (--length != 0); + } +} +#else +# define check_match(s, start, match, length) +#endif /* DEBUG */ + +/* =========================================================================== + * Fill the window when the lookahead becomes insufficient. + * Updates strstart and lookahead. + * + * IN assertion: lookahead < MIN_LOOKAHEAD + * OUT assertions: strstart <= window_size-MIN_LOOKAHEAD + * At least one byte has been read, or avail_in == 0; reads are + * performed for at least two bytes (required for the zip translate_eol + * option -- not supported here). + */ +local void fill_window(s) + deflate_state *s; +{ + register unsigned n, m; + register Posf *p; + unsigned more; /* Amount of free space at the end of the window. */ + uInt wsize = s->w_size; + + do { + more = (unsigned)(s->window_size -(ulg)s->lookahead -(ulg)s->strstart); + + /* Deal with !@#$% 64K limit: */ + if (sizeof(int) <= 2) { + if (more == 0 && s->strstart == 0 && s->lookahead == 0) { + more = wsize; + + } else if (more == (unsigned)(-1)) { + /* Very unlikely, but possible on 16 bit machine if + * strstart == 0 && lookahead == 1 (input done a byte at time) + */ + more--; + } + } + + /* If the window is almost full and there is insufficient lookahead, + * move the upper half to the lower one to make room in the upper half. + */ + if (s->strstart >= wsize+MAX_DIST(s)) { + + zmemcpy(s->window, s->window+wsize, (unsigned)wsize); + s->match_start -= wsize; + s->strstart -= wsize; /* we now have strstart >= MAX_DIST */ + s->block_start -= (long) wsize; + + /* Slide the hash table (could be avoided with 32 bit values + at the expense of memory usage). We slide even when level == 0 + to keep the hash table consistent if we switch back to level > 0 + later. (Using level 0 permanently is not an optimal usage of + zlib, so we don't care about this pathological case.) + */ + /* %%% avoid this when Z_RLE */ + n = s->hash_size; + p = &s->head[n]; + do { + m = *--p; + *p = (Pos)(m >= wsize ? m-wsize : NIL); + } while (--n); + + n = wsize; +#ifndef FASTEST + p = &s->prev[n]; + do { + m = *--p; + *p = (Pos)(m >= wsize ? m-wsize : NIL); + /* If n is not on any hash chain, prev[n] is garbage but + * its value will never be used. + */ + } while (--n); +#endif + more += wsize; + } + if (s->strm->avail_in == 0) return; + + /* If there was no sliding: + * strstart <= WSIZE+MAX_DIST-1 && lookahead <= MIN_LOOKAHEAD - 1 && + * more == window_size - lookahead - strstart + * => more >= window_size - (MIN_LOOKAHEAD-1 + WSIZE + MAX_DIST-1) + * => more >= window_size - 2*WSIZE + 2 + * In the BIG_MEM or MMAP case (not yet supported), + * window_size == input_size + MIN_LOOKAHEAD && + * strstart + s->lookahead <= input_size => more >= MIN_LOOKAHEAD. + * Otherwise, window_size == 2*WSIZE so more >= 2. + * If there was sliding, more >= WSIZE. So in all cases, more >= 2. + */ + Assert(more >= 2, "more < 2"); + + n = read_buf(s->strm, s->window + s->strstart + s->lookahead, more); + s->lookahead += n; + + /* Initialize the hash value now that we have some input: */ + if (s->lookahead >= MIN_MATCH) { + s->ins_h = s->window[s->strstart]; + UPDATE_HASH(s, s->ins_h, s->window[s->strstart+1]); +#if MIN_MATCH != 3 + Call UPDATE_HASH() MIN_MATCH-3 more times +#endif + } + /* If the whole input has less than MIN_MATCH bytes, ins_h is garbage, + * but this is not important since only literal bytes will be emitted. + */ + + } while (s->lookahead < MIN_LOOKAHEAD && s->strm->avail_in != 0); +} + +/* =========================================================================== + * Flush the current block, with given end-of-file flag. + * IN assertion: strstart is set to the end of the current match. + */ +#define FLUSH_BLOCK_ONLY(s, eof) { \ + _tr_flush_block(s, (s->block_start >= 0L ? \ + (charf *)&s->window[(unsigned)s->block_start] : \ + (charf *)Z_NULL), \ + (ulg)((long)s->strstart - s->block_start), \ + (eof)); \ + s->block_start = s->strstart; \ + flush_pending(s->strm); \ + Tracev((stderr,"[FLUSH]")); \ +} + +/* Same but force premature exit if necessary. */ +#define FLUSH_BLOCK(s, eof) { \ + FLUSH_BLOCK_ONLY(s, eof); \ + if (s->strm->avail_out == 0) return (eof) ? finish_started : need_more; \ +} + +/* =========================================================================== + * Copy without compression as much as possible from the input stream, return + * the current block state. + * This function does not insert new strings in the dictionary since + * uncompressible data is probably not useful. This function is used + * only for the level=0 compression option. + * NOTE: this function should be optimized to avoid extra copying from + * window to pending_buf. + */ +local block_state deflate_stored(s, flush) + deflate_state *s; + int flush; +{ + /* Stored blocks are limited to 0xffff bytes, pending_buf is limited + * to pending_buf_size, and each stored block has a 5 byte header: + */ + ulg max_block_size = 0xffff; + ulg max_start; + + if (max_block_size > s->pending_buf_size - 5) { + max_block_size = s->pending_buf_size - 5; + } + + /* Copy as much as possible from input to output: */ + for (;;) { + /* Fill the window as much as possible: */ + if (s->lookahead <= 1) { + + Assert(s->strstart < s->w_size+MAX_DIST(s) || + s->block_start >= (long)s->w_size, "slide too late"); + + fill_window(s); + if (s->lookahead == 0 && flush == Z_NO_FLUSH) return need_more; + + if (s->lookahead == 0) break; /* flush the current block */ + } + Assert(s->block_start >= 0L, "block gone"); + + s->strstart += s->lookahead; + s->lookahead = 0; + + /* Emit a stored block if pending_buf will be full: */ + max_start = s->block_start + max_block_size; + if (s->strstart == 0 || (ulg)s->strstart >= max_start) { + /* strstart == 0 is possible when wraparound on 16-bit machine */ + s->lookahead = (uInt)(s->strstart - max_start); + s->strstart = (uInt)max_start; + FLUSH_BLOCK(s, 0); + } + /* Flush if we may have to slide, otherwise block_start may become + * negative and the data will be gone: + */ + if (s->strstart - (uInt)s->block_start >= MAX_DIST(s)) { + FLUSH_BLOCK(s, 0); + } + } + FLUSH_BLOCK(s, flush == Z_FINISH); + return flush == Z_FINISH ? finish_done : block_done; +} + +/* =========================================================================== + * Compress as much as possible from the input stream, return the current + * block state. + * This function does not perform lazy evaluation of matches and inserts + * new strings in the dictionary only for unmatched strings or for short + * matches. It is used only for the fast compression options. + */ +local block_state deflate_fast(s, flush) + deflate_state *s; + int flush; +{ + IPos hash_head = NIL; /* head of the hash chain */ + int bflush; /* set if current block must be flushed */ + + for (;;) { + /* Make sure that we always have enough lookahead, except + * at the end of the input file. We need MAX_MATCH bytes + * for the next match, plus MIN_MATCH bytes to insert the + * string following the next match. + */ + if (s->lookahead < MIN_LOOKAHEAD) { + fill_window(s); + if (s->lookahead < MIN_LOOKAHEAD && flush == Z_NO_FLUSH) { + return need_more; + } + if (s->lookahead == 0) break; /* flush the current block */ + } + + /* Insert the string window[strstart .. strstart+2] in the + * dictionary, and set hash_head to the head of the hash chain: + */ + if (s->lookahead >= MIN_MATCH) { + INSERT_STRING(s, s->strstart, hash_head); + } + + /* Find the longest match, discarding those <= prev_length. + * At this point we have always match_length < MIN_MATCH + */ + if (hash_head != NIL && s->strstart - hash_head <= MAX_DIST(s)) { + /* To simplify the code, we prevent matches with the string + * of window index 0 (in particular we have to avoid a match + * of the string with itself at the start of the input file). + */ +#ifdef FASTEST + if ((s->strategy != Z_HUFFMAN_ONLY && s->strategy != Z_RLE) || + (s->strategy == Z_RLE && s->strstart - hash_head == 1)) { + s->match_length = longest_match_fast (s, hash_head); + } +#else + if (s->strategy != Z_HUFFMAN_ONLY && s->strategy != Z_RLE) { + s->match_length = longest_match (s, hash_head); + } else if (s->strategy == Z_RLE && s->strstart - hash_head == 1) { + s->match_length = longest_match_fast (s, hash_head); + } +#endif + /* longest_match() or longest_match_fast() sets match_start */ + } + if (s->match_length >= MIN_MATCH) { + check_match(s, s->strstart, s->match_start, s->match_length); + + _tr_tally_dist(s, s->strstart - s->match_start, + s->match_length - MIN_MATCH, bflush); + + s->lookahead -= s->match_length; + + /* Insert new strings in the hash table only if the match length + * is not too large. This saves time but degrades compression. + */ +#ifndef FASTEST + if (s->match_length <= s->max_insert_length && + s->lookahead >= MIN_MATCH) { + s->match_length--; /* string at strstart already in table */ + do { + s->strstart++; + INSERT_STRING(s, s->strstart, hash_head); + /* strstart never exceeds WSIZE-MAX_MATCH, so there are + * always MIN_MATCH bytes ahead. + */ + } while (--s->match_length != 0); + s->strstart++; + } else +#endif + { + s->strstart += s->match_length; + s->match_length = 0; + s->ins_h = s->window[s->strstart]; + UPDATE_HASH(s, s->ins_h, s->window[s->strstart+1]); +#if MIN_MATCH != 3 + Call UPDATE_HASH() MIN_MATCH-3 more times +#endif + /* If lookahead < MIN_MATCH, ins_h is garbage, but it does not + * matter since it will be recomputed at next deflate call. + */ + } + } else { + /* No match, output a literal byte */ + Tracevv((stderr,"%c", s->window[s->strstart])); + _tr_tally_lit (s, s->window[s->strstart], bflush); + s->lookahead--; + s->strstart++; + } + if (bflush) FLUSH_BLOCK(s, 0); + } + FLUSH_BLOCK(s, flush == Z_FINISH); + return flush == Z_FINISH ? finish_done : block_done; +} + +#ifndef FASTEST +/* =========================================================================== + * Same as above, but achieves better compression. We use a lazy + * evaluation for matches: a match is finally adopted only if there is + * no better match at the next window position. + */ +local block_state deflate_slow(s, flush) + deflate_state *s; + int flush; +{ + IPos hash_head = NIL; /* head of hash chain */ + int bflush; /* set if current block must be flushed */ + + /* Process the input block. */ + for (;;) { + /* Make sure that we always have enough lookahead, except + * at the end of the input file. We need MAX_MATCH bytes + * for the next match, plus MIN_MATCH bytes to insert the + * string following the next match. + */ + if (s->lookahead < MIN_LOOKAHEAD) { + fill_window(s); + if (s->lookahead < MIN_LOOKAHEAD && flush == Z_NO_FLUSH) { + return need_more; + } + if (s->lookahead == 0) break; /* flush the current block */ + } + + /* Insert the string window[strstart .. strstart+2] in the + * dictionary, and set hash_head to the head of the hash chain: + */ + if (s->lookahead >= MIN_MATCH) { + INSERT_STRING(s, s->strstart, hash_head); + } + + /* Find the longest match, discarding those <= prev_length. + */ + s->prev_length = s->match_length, s->prev_match = s->match_start; + s->match_length = MIN_MATCH-1; + + if (hash_head != NIL && s->prev_length < s->max_lazy_match && + s->strstart - hash_head <= MAX_DIST(s)) { + /* To simplify the code, we prevent matches with the string + * of window index 0 (in particular we have to avoid a match + * of the string with itself at the start of the input file). + */ + if (s->strategy != Z_HUFFMAN_ONLY && s->strategy != Z_RLE) { + s->match_length = longest_match (s, hash_head); + } else if (s->strategy == Z_RLE && s->strstart - hash_head == 1) { + s->match_length = longest_match_fast (s, hash_head); + } + /* longest_match() or longest_match_fast() sets match_start */ + + if (s->match_length <= 5 && (s->strategy == Z_FILTERED +#if TOO_FAR <= 32767 + || (s->match_length == MIN_MATCH && + s->strstart - s->match_start > TOO_FAR) +#endif + )) { + + /* If prev_match is also MIN_MATCH, match_start is garbage + * but we will ignore the current match anyway. + */ + s->match_length = MIN_MATCH-1; + } + } + /* If there was a match at the previous step and the current + * match is not better, output the previous match: + */ + if (s->prev_length >= MIN_MATCH && s->match_length <= s->prev_length) { + uInt max_insert = s->strstart + s->lookahead - MIN_MATCH; + /* Do not insert strings in hash table beyond this. */ + + check_match(s, s->strstart-1, s->prev_match, s->prev_length); + + _tr_tally_dist(s, s->strstart -1 - s->prev_match, + s->prev_length - MIN_MATCH, bflush); + + /* Insert in hash table all strings up to the end of the match. + * strstart-1 and strstart are already inserted. If there is not + * enough lookahead, the last two strings are not inserted in + * the hash table. + */ + s->lookahead -= s->prev_length-1; + s->prev_length -= 2; + do { + if (++s->strstart <= max_insert) { + INSERT_STRING(s, s->strstart, hash_head); + } + } while (--s->prev_length != 0); + s->match_available = 0; + s->match_length = MIN_MATCH-1; + s->strstart++; + + if (bflush) FLUSH_BLOCK(s, 0); + + } else if (s->match_available) { + /* If there was no match at the previous position, output a + * single literal. If there was a match but the current match + * is longer, truncate the previous match to a single literal. + */ + Tracevv((stderr,"%c", s->window[s->strstart-1])); + _tr_tally_lit(s, s->window[s->strstart-1], bflush); + if (bflush) { + FLUSH_BLOCK_ONLY(s, 0); + } + s->strstart++; + s->lookahead--; + if (s->strm->avail_out == 0) return need_more; + } else { + /* There is no previous match to compare with, wait for + * the next step to decide. + */ + s->match_available = 1; + s->strstart++; + s->lookahead--; + } + } + Assert (flush != Z_NO_FLUSH, "no flush?"); + if (s->match_available) { + Tracevv((stderr,"%c", s->window[s->strstart-1])); + _tr_tally_lit(s, s->window[s->strstart-1], bflush); + s->match_available = 0; + } + FLUSH_BLOCK(s, flush == Z_FINISH); + return flush == Z_FINISH ? finish_done : block_done; +} +#endif /* FASTEST */ + +#if 0 +/* =========================================================================== + * For Z_RLE, simply look for runs of bytes, generate matches only of distance + * one. Do not maintain a hash table. (It will be regenerated if this run of + * deflate switches away from Z_RLE.) + */ +local block_state deflate_rle(s, flush) + deflate_state *s; + int flush; +{ + int bflush; /* set if current block must be flushed */ + uInt run; /* length of run */ + uInt max; /* maximum length of run */ + uInt prev; /* byte at distance one to match */ + Bytef *scan; /* scan for end of run */ + + for (;;) { + /* Make sure that we always have enough lookahead, except + * at the end of the input file. We need MAX_MATCH bytes + * for the longest encodable run. + */ + if (s->lookahead < MAX_MATCH) { + fill_window(s); + if (s->lookahead < MAX_MATCH && flush == Z_NO_FLUSH) { + return need_more; + } + if (s->lookahead == 0) break; /* flush the current block */ + } + + /* See how many times the previous byte repeats */ + run = 0; + if (s->strstart > 0) { /* if there is a previous byte, that is */ + max = s->lookahead < MAX_MATCH ? s->lookahead : MAX_MATCH; + scan = s->window + s->strstart - 1; + prev = *scan++; + do { + if (*scan++ != prev) + break; + } while (++run < max); + } + + /* Emit match if have run of MIN_MATCH or longer, else emit literal */ + if (run >= MIN_MATCH) { + check_match(s, s->strstart, s->strstart - 1, run); + _tr_tally_dist(s, 1, run - MIN_MATCH, bflush); + s->lookahead -= run; + s->strstart += run; + } else { + /* No match, output a literal byte */ + Tracevv((stderr,"%c", s->window[s->strstart])); + _tr_tally_lit (s, s->window[s->strstart], bflush); + s->lookahead--; + s->strstart++; + } + if (bflush) FLUSH_BLOCK(s, 0); + } + FLUSH_BLOCK(s, flush == Z_FINISH); + return flush == Z_FINISH ? finish_done : block_done; +} +#endif diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/deflate.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/deflate.h index 222c53e04..05a5ab3a2 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/deflate.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/deflate.h @@ -1,331 +1,331 @@ -/* deflate.h -- internal compression state - * Copyright (C) 1995-2004 Jean-loup Gailly - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* WARNING: this file should *not* be used by applications. It is - part of the implementation of the compression library and is - subject to change. Applications should only use zlib.h. - */ - -/* @(#) $Id$ */ - -#ifndef DEFLATE_H -#define DEFLATE_H - -#include "zutil.h" - -/* define NO_GZIP when compiling if you want to disable gzip header and - trailer creation by deflate(). NO_GZIP would be used to avoid linking in - the crc code when it is not needed. For shared libraries, gzip encoding - should be left enabled. */ -#ifndef NO_GZIP -# define GZIP -#endif - -/* =========================================================================== - * Internal compression state. - */ - -#define LENGTH_CODES 29 -/* number of length codes, not counting the special END_BLOCK code */ - -#define LITERALS 256 -/* number of literal bytes 0..255 */ - -#define L_CODES (LITERALS+1+LENGTH_CODES) -/* number of Literal or Length codes, including the END_BLOCK code */ - -#define D_CODES 30 -/* number of distance codes */ - -#define BL_CODES 19 -/* number of codes used to transfer the bit lengths */ - -#define HEAP_SIZE (2*L_CODES+1) -/* maximum heap size */ - -#define MAX_BITS 15 -/* All codes must not exceed MAX_BITS bits */ - -#define INIT_STATE 42 -#define EXTRA_STATE 69 -#define NAME_STATE 73 -#define COMMENT_STATE 91 -#define HCRC_STATE 103 -#define BUSY_STATE 113 -#define FINISH_STATE 666 -/* Stream status */ - - -/* Data structure describing a single value and its code string. */ -typedef struct ct_data_s { - union { - ush freq; /* frequency count */ - ush code; /* bit string */ - } fc; - union { - ush dad; /* father node in Huffman tree */ - ush len; /* length of bit string */ - } dl; -} FAR ct_data; - -#define Freq fc.freq -#define Code fc.code -#define Dad dl.dad -#define Len dl.len - -typedef struct static_tree_desc_s static_tree_desc; - -typedef struct tree_desc_s { - ct_data *dyn_tree; /* the dynamic tree */ - int max_code; /* largest code with non zero frequency */ - static_tree_desc *stat_desc; /* the corresponding static tree */ -} FAR tree_desc; - -typedef ush Pos; -typedef Pos FAR Posf; -typedef unsigned IPos; - -/* A Pos is an index in the character window. We use short instead of int to - * save space in the various tables. IPos is used only for parameter passing. - */ - -typedef struct internal_state { - z_streamp strm; /* pointer back to this zlib stream */ - int status; /* as the name implies */ - Bytef *pending_buf; /* output still pending */ - ulg pending_buf_size; /* size of pending_buf */ - Bytef *pending_out; /* next pending byte to output to the stream */ - uInt pending; /* nb of bytes in the pending buffer */ - int wrap; /* bit 0 true for zlib, bit 1 true for gzip */ - gz_headerp gzhead; /* gzip header information to write */ - uInt gzindex; /* where in extra, name, or comment */ - Byte method; /* STORED (for zip only) or DEFLATED */ - int last_flush; /* value of flush param for previous deflate call */ - - /* used by deflate.c: */ - - uInt w_size; /* LZ77 window size (32K by default) */ - uInt w_bits; /* log2(w_size) (8..16) */ - uInt w_mask; /* w_size - 1 */ - - Bytef *window; - /* Sliding window. Input bytes are read into the second half of the window, - * and move to the first half later to keep a dictionary of at least wSize - * bytes. With this organization, matches are limited to a distance of - * wSize-MAX_MATCH bytes, but this ensures that IO is always - * performed with a length multiple of the block size. Also, it limits - * the window size to 64K, which is quite useful on MSDOS. - * To do: use the user input buffer as sliding window. - */ - - ulg window_size; - /* Actual size of window: 2*wSize, except when the user input buffer - * is directly used as sliding window. - */ - - Posf *prev; - /* Link to older string with same hash index. To limit the size of this - * array to 64K, this link is maintained only for the last 32K strings. - * An index in this array is thus a window index modulo 32K. - */ - - Posf *head; /* Heads of the hash chains or NIL. */ - - uInt ins_h; /* hash index of string to be inserted */ - uInt hash_size; /* number of elements in hash table */ - uInt hash_bits; /* log2(hash_size) */ - uInt hash_mask; /* hash_size-1 */ - - uInt hash_shift; - /* Number of bits by which ins_h must be shifted at each input - * step. It must be such that after MIN_MATCH steps, the oldest - * byte no longer takes part in the hash key, that is: - * hash_shift * MIN_MATCH >= hash_bits - */ - - long block_start; - /* Window position at the beginning of the current output block. Gets - * negative when the window is moved backwards. - */ - - uInt match_length; /* length of best match */ - IPos prev_match; /* previous match */ - int match_available; /* set if previous match exists */ - uInt strstart; /* start of string to insert */ - uInt match_start; /* start of matching string */ - uInt lookahead; /* number of valid bytes ahead in window */ - - uInt prev_length; - /* Length of the best match at previous step. Matches not greater than this - * are discarded. This is used in the lazy match evaluation. - */ - - uInt max_chain_length; - /* To speed up deflation, hash chains are never searched beyond this - * length. A higher limit improves compression ratio but degrades the - * speed. - */ - - uInt max_lazy_match; - /* Attempt to find a better match only when the current match is strictly - * smaller than this value. This mechanism is used only for compression - * levels >= 4. - */ -# define max_insert_length max_lazy_match - /* Insert new strings in the hash table only if the match length is not - * greater than this length. This saves time but degrades compression. - * max_insert_length is used only for compression levels <= 3. - */ - - int level; /* compression level (1..9) */ - int strategy; /* favor or force Huffman coding*/ - - uInt good_match; - /* Use a faster search when the previous match is longer than this */ - - int nice_match; /* Stop searching when current match exceeds this */ - - /* used by trees.c: */ - /* Didn't use ct_data typedef below to supress compiler warning */ - struct ct_data_s dyn_ltree[HEAP_SIZE]; /* literal and length tree */ - struct ct_data_s dyn_dtree[2*D_CODES+1]; /* distance tree */ - struct ct_data_s bl_tree[2*BL_CODES+1]; /* Huffman tree for bit lengths */ - - struct tree_desc_s l_desc; /* desc. for literal tree */ - struct tree_desc_s d_desc; /* desc. for distance tree */ - struct tree_desc_s bl_desc; /* desc. for bit length tree */ - - ush bl_count[MAX_BITS+1]; - /* number of codes at each bit length for an optimal tree */ - - int heap[2*L_CODES+1]; /* heap used to build the Huffman trees */ - int heap_len; /* number of elements in the heap */ - int heap_max; /* element of largest frequency */ - /* The sons of heap[n] are heap[2*n] and heap[2*n+1]. heap[0] is not used. - * The same heap array is used to build all trees. - */ - - uch depth[2*L_CODES+1]; - /* Depth of each subtree used as tie breaker for trees of equal frequency - */ - - uchf *l_buf; /* buffer for literals or lengths */ - - uInt lit_bufsize; - /* Size of match buffer for literals/lengths. There are 4 reasons for - * limiting lit_bufsize to 64K: - * - frequencies can be kept in 16 bit counters - * - if compression is not successful for the first block, all input - * data is still in the window so we can still emit a stored block even - * when input comes from standard input. (This can also be done for - * all blocks if lit_bufsize is not greater than 32K.) - * - if compression is not successful for a file smaller than 64K, we can - * even emit a stored file instead of a stored block (saving 5 bytes). - * This is applicable only for zip (not gzip or zlib). - * - creating new Huffman trees less frequently may not provide fast - * adaptation to changes in the input data statistics. (Take for - * example a binary file with poorly compressible code followed by - * a highly compressible string table.) Smaller buffer sizes give - * fast adaptation but have of course the overhead of transmitting - * trees more frequently. - * - I can't count above 4 - */ - - uInt last_lit; /* running index in l_buf */ - - ushf *d_buf; - /* Buffer for distances. To simplify the code, d_buf and l_buf have - * the same number of elements. To use different lengths, an extra flag - * array would be necessary. - */ - - ulg opt_len; /* bit length of current block with optimal trees */ - ulg static_len; /* bit length of current block with static trees */ - uInt matches; /* number of string matches in current block */ - int last_eob_len; /* bit length of EOB code for last block */ - -#ifdef DEBUG - ulg compressed_len; /* total bit length of compressed file mod 2^32 */ - ulg bits_sent; /* bit length of compressed data sent mod 2^32 */ -#endif - - ush bi_buf; - /* Output buffer. bits are inserted starting at the bottom (least - * significant bits). - */ - int bi_valid; - /* Number of valid bits in bi_buf. All bits above the last valid bit - * are always zero. - */ - -} FAR deflate_state; - -/* Output a byte on the stream. - * IN assertion: there is enough room in pending_buf. - */ -#define put_byte(s, c) {s->pending_buf[s->pending++] = (c);} - - -#define MIN_LOOKAHEAD (MAX_MATCH+MIN_MATCH+1) -/* Minimum amount of lookahead, except at the end of the input file. - * See deflate.c for comments about the MIN_MATCH+1. - */ - -#define MAX_DIST(s) ((s)->w_size-MIN_LOOKAHEAD) -/* In order to simplify the code, particularly on 16 bit machines, match - * distances are limited to MAX_DIST instead of WSIZE. - */ - - /* in trees.c */ -void _tr_init OF((deflate_state *s)); -int _tr_tally OF((deflate_state *s, unsigned dist, unsigned lc)); -void _tr_flush_block OF((deflate_state *s, charf *buf, ulg stored_len, - int eof)); -void _tr_align OF((deflate_state *s)); -void _tr_stored_block OF((deflate_state *s, charf *buf, ulg stored_len, - int eof)); - -#define d_code(dist) \ - ((dist) < 256 ? _dist_code[dist] : _dist_code[256+((dist)>>7)]) -/* Mapping from a distance to a distance code. dist is the distance - 1 and - * must not have side effects. _dist_code[256] and _dist_code[257] are never - * used. - */ - -#ifndef DEBUG -/* Inline versions of _tr_tally for speed: */ - -#if defined(GEN_TREES_H) || !defined(STDC) - extern uch _length_code[]; - extern uch _dist_code[]; -#else - extern const uch _length_code[]; - extern const uch _dist_code[]; -#endif - -# define _tr_tally_lit(s, c, flush) \ - { uch cc = (c); \ - s->d_buf[s->last_lit] = 0; \ - s->l_buf[s->last_lit++] = cc; \ - s->dyn_ltree[cc].Freq++; \ - flush = (s->last_lit == s->lit_bufsize-1); \ - } -# define _tr_tally_dist(s, distance, length, flush) \ - { uch len = (length); \ - ush dist = (distance); \ - s->d_buf[s->last_lit] = dist; \ - s->l_buf[s->last_lit++] = len; \ - dist--; \ - s->dyn_ltree[_length_code[len]+LITERALS+1].Freq++; \ - s->dyn_dtree[d_code(dist)].Freq++; \ - flush = (s->last_lit == s->lit_bufsize-1); \ - } -#else -# define _tr_tally_lit(s, c, flush) flush = _tr_tally(s, 0, c) -# define _tr_tally_dist(s, distance, length, flush) \ - flush = _tr_tally(s, distance, length) -#endif - -#endif /* DEFLATE_H */ +/* deflate.h -- internal compression state + * Copyright (C) 1995-2004 Jean-loup Gailly + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* WARNING: this file should *not* be used by applications. It is + part of the implementation of the compression library and is + subject to change. Applications should only use zlib.h. + */ + +/* @(#) $Id$ */ + +#ifndef DEFLATE_H +#define DEFLATE_H + +#include "zutil.h" + +/* define NO_GZIP when compiling if you want to disable gzip header and + trailer creation by deflate(). NO_GZIP would be used to avoid linking in + the crc code when it is not needed. For shared libraries, gzip encoding + should be left enabled. */ +#ifndef NO_GZIP +# define GZIP +#endif + +/* =========================================================================== + * Internal compression state. + */ + +#define LENGTH_CODES 29 +/* number of length codes, not counting the special END_BLOCK code */ + +#define LITERALS 256 +/* number of literal bytes 0..255 */ + +#define L_CODES (LITERALS+1+LENGTH_CODES) +/* number of Literal or Length codes, including the END_BLOCK code */ + +#define D_CODES 30 +/* number of distance codes */ + +#define BL_CODES 19 +/* number of codes used to transfer the bit lengths */ + +#define HEAP_SIZE (2*L_CODES+1) +/* maximum heap size */ + +#define MAX_BITS 15 +/* All codes must not exceed MAX_BITS bits */ + +#define INIT_STATE 42 +#define EXTRA_STATE 69 +#define NAME_STATE 73 +#define COMMENT_STATE 91 +#define HCRC_STATE 103 +#define BUSY_STATE 113 +#define FINISH_STATE 666 +/* Stream status */ + + +/* Data structure describing a single value and its code string. */ +typedef struct ct_data_s { + union { + ush freq; /* frequency count */ + ush code; /* bit string */ + } fc; + union { + ush dad; /* father node in Huffman tree */ + ush len; /* length of bit string */ + } dl; +} FAR ct_data; + +#define Freq fc.freq +#define Code fc.code +#define Dad dl.dad +#define Len dl.len + +typedef struct static_tree_desc_s static_tree_desc; + +typedef struct tree_desc_s { + ct_data *dyn_tree; /* the dynamic tree */ + int max_code; /* largest code with non zero frequency */ + static_tree_desc *stat_desc; /* the corresponding static tree */ +} FAR tree_desc; + +typedef ush Pos; +typedef Pos FAR Posf; +typedef unsigned IPos; + +/* A Pos is an index in the character window. We use short instead of int to + * save space in the various tables. IPos is used only for parameter passing. + */ + +typedef struct internal_state { + z_streamp strm; /* pointer back to this zlib stream */ + int status; /* as the name implies */ + Bytef *pending_buf; /* output still pending */ + ulg pending_buf_size; /* size of pending_buf */ + Bytef *pending_out; /* next pending byte to output to the stream */ + uInt pending; /* nb of bytes in the pending buffer */ + int wrap; /* bit 0 true for zlib, bit 1 true for gzip */ + gz_headerp gzhead; /* gzip header information to write */ + uInt gzindex; /* where in extra, name, or comment */ + Byte method; /* STORED (for zip only) or DEFLATED */ + int last_flush; /* value of flush param for previous deflate call */ + + /* used by deflate.c: */ + + uInt w_size; /* LZ77 window size (32K by default) */ + uInt w_bits; /* log2(w_size) (8..16) */ + uInt w_mask; /* w_size - 1 */ + + Bytef *window; + /* Sliding window. Input bytes are read into the second half of the window, + * and move to the first half later to keep a dictionary of at least wSize + * bytes. With this organization, matches are limited to a distance of + * wSize-MAX_MATCH bytes, but this ensures that IO is always + * performed with a length multiple of the block size. Also, it limits + * the window size to 64K, which is quite useful on MSDOS. + * To do: use the user input buffer as sliding window. + */ + + ulg window_size; + /* Actual size of window: 2*wSize, except when the user input buffer + * is directly used as sliding window. + */ + + Posf *prev; + /* Link to older string with same hash index. To limit the size of this + * array to 64K, this link is maintained only for the last 32K strings. + * An index in this array is thus a window index modulo 32K. + */ + + Posf *head; /* Heads of the hash chains or NIL. */ + + uInt ins_h; /* hash index of string to be inserted */ + uInt hash_size; /* number of elements in hash table */ + uInt hash_bits; /* log2(hash_size) */ + uInt hash_mask; /* hash_size-1 */ + + uInt hash_shift; + /* Number of bits by which ins_h must be shifted at each input + * step. It must be such that after MIN_MATCH steps, the oldest + * byte no longer takes part in the hash key, that is: + * hash_shift * MIN_MATCH >= hash_bits + */ + + long block_start; + /* Window position at the beginning of the current output block. Gets + * negative when the window is moved backwards. + */ + + uInt match_length; /* length of best match */ + IPos prev_match; /* previous match */ + int match_available; /* set if previous match exists */ + uInt strstart; /* start of string to insert */ + uInt match_start; /* start of matching string */ + uInt lookahead; /* number of valid bytes ahead in window */ + + uInt prev_length; + /* Length of the best match at previous step. Matches not greater than this + * are discarded. This is used in the lazy match evaluation. + */ + + uInt max_chain_length; + /* To speed up deflation, hash chains are never searched beyond this + * length. A higher limit improves compression ratio but degrades the + * speed. + */ + + uInt max_lazy_match; + /* Attempt to find a better match only when the current match is strictly + * smaller than this value. This mechanism is used only for compression + * levels >= 4. + */ +# define max_insert_length max_lazy_match + /* Insert new strings in the hash table only if the match length is not + * greater than this length. This saves time but degrades compression. + * max_insert_length is used only for compression levels <= 3. + */ + + int level; /* compression level (1..9) */ + int strategy; /* favor or force Huffman coding*/ + + uInt good_match; + /* Use a faster search when the previous match is longer than this */ + + int nice_match; /* Stop searching when current match exceeds this */ + + /* used by trees.c: */ + /* Didn't use ct_data typedef below to supress compiler warning */ + struct ct_data_s dyn_ltree[HEAP_SIZE]; /* literal and length tree */ + struct ct_data_s dyn_dtree[2*D_CODES+1]; /* distance tree */ + struct ct_data_s bl_tree[2*BL_CODES+1]; /* Huffman tree for bit lengths */ + + struct tree_desc_s l_desc; /* desc. for literal tree */ + struct tree_desc_s d_desc; /* desc. for distance tree */ + struct tree_desc_s bl_desc; /* desc. for bit length tree */ + + ush bl_count[MAX_BITS+1]; + /* number of codes at each bit length for an optimal tree */ + + int heap[2*L_CODES+1]; /* heap used to build the Huffman trees */ + int heap_len; /* number of elements in the heap */ + int heap_max; /* element of largest frequency */ + /* The sons of heap[n] are heap[2*n] and heap[2*n+1]. heap[0] is not used. + * The same heap array is used to build all trees. + */ + + uch depth[2*L_CODES+1]; + /* Depth of each subtree used as tie breaker for trees of equal frequency + */ + + uchf *l_buf; /* buffer for literals or lengths */ + + uInt lit_bufsize; + /* Size of match buffer for literals/lengths. There are 4 reasons for + * limiting lit_bufsize to 64K: + * - frequencies can be kept in 16 bit counters + * - if compression is not successful for the first block, all input + * data is still in the window so we can still emit a stored block even + * when input comes from standard input. (This can also be done for + * all blocks if lit_bufsize is not greater than 32K.) + * - if compression is not successful for a file smaller than 64K, we can + * even emit a stored file instead of a stored block (saving 5 bytes). + * This is applicable only for zip (not gzip or zlib). + * - creating new Huffman trees less frequently may not provide fast + * adaptation to changes in the input data statistics. (Take for + * example a binary file with poorly compressible code followed by + * a highly compressible string table.) Smaller buffer sizes give + * fast adaptation but have of course the overhead of transmitting + * trees more frequently. + * - I can't count above 4 + */ + + uInt last_lit; /* running index in l_buf */ + + ushf *d_buf; + /* Buffer for distances. To simplify the code, d_buf and l_buf have + * the same number of elements. To use different lengths, an extra flag + * array would be necessary. + */ + + ulg opt_len; /* bit length of current block with optimal trees */ + ulg static_len; /* bit length of current block with static trees */ + uInt matches; /* number of string matches in current block */ + int last_eob_len; /* bit length of EOB code for last block */ + +#ifdef DEBUG + ulg compressed_len; /* total bit length of compressed file mod 2^32 */ + ulg bits_sent; /* bit length of compressed data sent mod 2^32 */ +#endif + + ush bi_buf; + /* Output buffer. bits are inserted starting at the bottom (least + * significant bits). + */ + int bi_valid; + /* Number of valid bits in bi_buf. All bits above the last valid bit + * are always zero. + */ + +} FAR deflate_state; + +/* Output a byte on the stream. + * IN assertion: there is enough room in pending_buf. + */ +#define put_byte(s, c) {s->pending_buf[s->pending++] = (c);} + + +#define MIN_LOOKAHEAD (MAX_MATCH+MIN_MATCH+1) +/* Minimum amount of lookahead, except at the end of the input file. + * See deflate.c for comments about the MIN_MATCH+1. + */ + +#define MAX_DIST(s) ((s)->w_size-MIN_LOOKAHEAD) +/* In order to simplify the code, particularly on 16 bit machines, match + * distances are limited to MAX_DIST instead of WSIZE. + */ + + /* in trees.c */ +void _tr_init OF((deflate_state *s)); +int _tr_tally OF((deflate_state *s, unsigned dist, unsigned lc)); +void _tr_flush_block OF((deflate_state *s, charf *buf, ulg stored_len, + int eof)); +void _tr_align OF((deflate_state *s)); +void _tr_stored_block OF((deflate_state *s, charf *buf, ulg stored_len, + int eof)); + +#define d_code(dist) \ + ((dist) < 256 ? _dist_code[dist] : _dist_code[256+((dist)>>7)]) +/* Mapping from a distance to a distance code. dist is the distance - 1 and + * must not have side effects. _dist_code[256] and _dist_code[257] are never + * used. + */ + +#ifndef DEBUG +/* Inline versions of _tr_tally for speed: */ + +#if defined(GEN_TREES_H) || !defined(STDC) + extern uch _length_code[]; + extern uch _dist_code[]; +#else + extern const uch _length_code[]; + extern const uch _dist_code[]; +#endif + +# define _tr_tally_lit(s, c, flush) \ + { uch cc = (c); \ + s->d_buf[s->last_lit] = 0; \ + s->l_buf[s->last_lit++] = cc; \ + s->dyn_ltree[cc].Freq++; \ + flush = (s->last_lit == s->lit_bufsize-1); \ + } +# define _tr_tally_dist(s, distance, length, flush) \ + { uch len = (length); \ + ush dist = (distance); \ + s->d_buf[s->last_lit] = dist; \ + s->l_buf[s->last_lit++] = len; \ + dist--; \ + s->dyn_ltree[_length_code[len]+LITERALS+1].Freq++; \ + s->dyn_dtree[d_code(dist)].Freq++; \ + flush = (s->last_lit == s->lit_bufsize-1); \ + } +#else +# define _tr_tally_lit(s, c, flush) flush = _tr_tally(s, 0, c) +# define _tr_tally_dist(s, distance, length, flush) \ + flush = _tr_tally(s, distance, length) +#endif + +#endif /* DEFLATE_H */ diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/example.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/example.c index 455a1d062..6c8a0ee76 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/example.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/example.c @@ -1,565 +1,565 @@ -/* example.c -- usage example of the zlib compression library - * Copyright (C) 1995-2004 Jean-loup Gailly. - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* @(#) $Id$ */ - -#include -#include "zlib.h" - -#ifdef STDC -# include -# include -#endif - -#if defined(VMS) || defined(RISCOS) -# define TESTFILE "foo-gz" -#else -# define TESTFILE "foo.gz" -#endif - -#define CHECK_ERR(err, msg) { \ - if (err != Z_OK) { \ - fprintf(stderr, "%s error: %d\n", msg, err); \ - exit(1); \ - } \ -} - -const char hello[] = "hello, hello!"; -/* "hello world" would be more standard, but the repeated "hello" - * stresses the compression code better, sorry... - */ - -const char dictionary[] = "hello"; -uLong dictId; /* Adler32 value of the dictionary */ - -void test_compress OF((Byte *compr, uLong comprLen, - Byte *uncompr, uLong uncomprLen)); -void test_gzio OF((const char *fname, - Byte *uncompr, uLong uncomprLen)); -void test_deflate OF((Byte *compr, uLong comprLen)); -void test_inflate OF((Byte *compr, uLong comprLen, - Byte *uncompr, uLong uncomprLen)); -void test_large_deflate OF((Byte *compr, uLong comprLen, - Byte *uncompr, uLong uncomprLen)); -void test_large_inflate OF((Byte *compr, uLong comprLen, - Byte *uncompr, uLong uncomprLen)); -void test_flush OF((Byte *compr, uLong *comprLen)); -void test_sync OF((Byte *compr, uLong comprLen, - Byte *uncompr, uLong uncomprLen)); -void test_dict_deflate OF((Byte *compr, uLong comprLen)); -void test_dict_inflate OF((Byte *compr, uLong comprLen, - Byte *uncompr, uLong uncomprLen)); -int main OF((int argc, char *argv[])); - -/* =========================================================================== - * Test compress() and uncompress() - */ -void test_compress(compr, comprLen, uncompr, uncomprLen) - Byte *compr, *uncompr; - uLong comprLen, uncomprLen; -{ - int err; - uLong len = (uLong)strlen(hello)+1; - - err = compress(compr, &comprLen, (const Bytef*)hello, len); - CHECK_ERR(err, "compress"); - - strcpy((char*)uncompr, "garbage"); - - err = uncompress(uncompr, &uncomprLen, compr, comprLen); - CHECK_ERR(err, "uncompress"); - - if (strcmp((char*)uncompr, hello)) { - fprintf(stderr, "bad uncompress\n"); - exit(1); - } else { - printf("uncompress(): %s\n", (char *)uncompr); - } -} - -/* =========================================================================== - * Test read/write of .gz files - */ -void test_gzio(fname, uncompr, uncomprLen) - const char *fname; /* compressed file name */ - Byte *uncompr; - uLong uncomprLen; -{ -#ifdef NO_GZCOMPRESS - fprintf(stderr, "NO_GZCOMPRESS -- gz* functions cannot compress\n"); -#else - int err; - int len = (int)strlen(hello)+1; - gzFile file; - z_off_t pos; - - file = gzopen(fname, "wb"); - if (file == NULL) { - fprintf(stderr, "gzopen error\n"); - exit(1); - } - gzputc(file, 'h'); - if (gzputs(file, "ello") != 4) { - fprintf(stderr, "gzputs err: %s\n", gzerror(file, &err)); - exit(1); - } - if (gzprintf(file, ", %s!", "hello") != 8) { - fprintf(stderr, "gzprintf err: %s\n", gzerror(file, &err)); - exit(1); - } - gzseek(file, 1L, SEEK_CUR); /* add one zero byte */ - gzclose(file); - - file = gzopen(fname, "rb"); - if (file == NULL) { - fprintf(stderr, "gzopen error\n"); - exit(1); - } - strcpy((char*)uncompr, "garbage"); - - if (gzread(file, uncompr, (unsigned)uncomprLen) != len) { - fprintf(stderr, "gzread err: %s\n", gzerror(file, &err)); - exit(1); - } - if (strcmp((char*)uncompr, hello)) { - fprintf(stderr, "bad gzread: %s\n", (char*)uncompr); - exit(1); - } else { - printf("gzread(): %s\n", (char*)uncompr); - } - - pos = gzseek(file, -8L, SEEK_CUR); - if (pos != 6 || gztell(file) != pos) { - fprintf(stderr, "gzseek error, pos=%ld, gztell=%ld\n", - (long)pos, (long)gztell(file)); - exit(1); - } - - if (gzgetc(file) != ' ') { - fprintf(stderr, "gzgetc error\n"); - exit(1); - } - - if (gzungetc(' ', file) != ' ') { - fprintf(stderr, "gzungetc error\n"); - exit(1); - } - - gzgets(file, (char*)uncompr, (int)uncomprLen); - if (strlen((char*)uncompr) != 7) { /* " hello!" */ - fprintf(stderr, "gzgets err after gzseek: %s\n", gzerror(file, &err)); - exit(1); - } - if (strcmp((char*)uncompr, hello + 6)) { - fprintf(stderr, "bad gzgets after gzseek\n"); - exit(1); - } else { - printf("gzgets() after gzseek: %s\n", (char*)uncompr); - } - - gzclose(file); -#endif -} - -/* =========================================================================== - * Test deflate() with small buffers - */ -void test_deflate(compr, comprLen) - Byte *compr; - uLong comprLen; -{ - z_stream c_stream; /* compression stream */ - int err; - uLong len = (uLong)strlen(hello)+1; - - c_stream.zalloc = (alloc_func)0; - c_stream.zfree = (free_func)0; - c_stream.opaque = (voidpf)0; - - err = deflateInit(&c_stream, Z_DEFAULT_COMPRESSION); - CHECK_ERR(err, "deflateInit"); - - c_stream.next_in = (Bytef*)hello; - c_stream.next_out = compr; - - while (c_stream.total_in != len && c_stream.total_out < comprLen) { - c_stream.avail_in = c_stream.avail_out = 1; /* force small buffers */ - err = deflate(&c_stream, Z_NO_FLUSH); - CHECK_ERR(err, "deflate"); - } - /* Finish the stream, still forcing small buffers: */ - for (;;) { - c_stream.avail_out = 1; - err = deflate(&c_stream, Z_FINISH); - if (err == Z_STREAM_END) break; - CHECK_ERR(err, "deflate"); - } - - err = deflateEnd(&c_stream); - CHECK_ERR(err, "deflateEnd"); -} - -/* =========================================================================== - * Test inflate() with small buffers - */ -void test_inflate(compr, comprLen, uncompr, uncomprLen) - Byte *compr, *uncompr; - uLong comprLen, uncomprLen; -{ - int err; - z_stream d_stream; /* decompression stream */ - - strcpy((char*)uncompr, "garbage"); - - d_stream.zalloc = (alloc_func)0; - d_stream.zfree = (free_func)0; - d_stream.opaque = (voidpf)0; - - d_stream.next_in = compr; - d_stream.avail_in = 0; - d_stream.next_out = uncompr; - - err = inflateInit(&d_stream); - CHECK_ERR(err, "inflateInit"); - - while (d_stream.total_out < uncomprLen && d_stream.total_in < comprLen) { - d_stream.avail_in = d_stream.avail_out = 1; /* force small buffers */ - err = inflate(&d_stream, Z_NO_FLUSH); - if (err == Z_STREAM_END) break; - CHECK_ERR(err, "inflate"); - } - - err = inflateEnd(&d_stream); - CHECK_ERR(err, "inflateEnd"); - - if (strcmp((char*)uncompr, hello)) { - fprintf(stderr, "bad inflate\n"); - exit(1); - } else { - printf("inflate(): %s\n", (char *)uncompr); - } -} - -/* =========================================================================== - * Test deflate() with large buffers and dynamic change of compression level - */ -void test_large_deflate(compr, comprLen, uncompr, uncomprLen) - Byte *compr, *uncompr; - uLong comprLen, uncomprLen; -{ - z_stream c_stream; /* compression stream */ - int err; - - c_stream.zalloc = (alloc_func)0; - c_stream.zfree = (free_func)0; - c_stream.opaque = (voidpf)0; - - err = deflateInit(&c_stream, Z_BEST_SPEED); - CHECK_ERR(err, "deflateInit"); - - c_stream.next_out = compr; - c_stream.avail_out = (uInt)comprLen; - - /* At this point, uncompr is still mostly zeroes, so it should compress - * very well: - */ - c_stream.next_in = uncompr; - c_stream.avail_in = (uInt)uncomprLen; - err = deflate(&c_stream, Z_NO_FLUSH); - CHECK_ERR(err, "deflate"); - if (c_stream.avail_in != 0) { - fprintf(stderr, "deflate not greedy\n"); - exit(1); - } - - /* Feed in already compressed data and switch to no compression: */ - deflateParams(&c_stream, Z_NO_COMPRESSION, Z_DEFAULT_STRATEGY); - c_stream.next_in = compr; - c_stream.avail_in = (uInt)comprLen/2; - err = deflate(&c_stream, Z_NO_FLUSH); - CHECK_ERR(err, "deflate"); - - /* Switch back to compressing mode: */ - deflateParams(&c_stream, Z_BEST_COMPRESSION, Z_FILTERED); - c_stream.next_in = uncompr; - c_stream.avail_in = (uInt)uncomprLen; - err = deflate(&c_stream, Z_NO_FLUSH); - CHECK_ERR(err, "deflate"); - - err = deflate(&c_stream, Z_FINISH); - if (err != Z_STREAM_END) { - fprintf(stderr, "deflate should report Z_STREAM_END\n"); - exit(1); - } - err = deflateEnd(&c_stream); - CHECK_ERR(err, "deflateEnd"); -} - -/* =========================================================================== - * Test inflate() with large buffers - */ -void test_large_inflate(compr, comprLen, uncompr, uncomprLen) - Byte *compr, *uncompr; - uLong comprLen, uncomprLen; -{ - int err; - z_stream d_stream; /* decompression stream */ - - strcpy((char*)uncompr, "garbage"); - - d_stream.zalloc = (alloc_func)0; - d_stream.zfree = (free_func)0; - d_stream.opaque = (voidpf)0; - - d_stream.next_in = compr; - d_stream.avail_in = (uInt)comprLen; - - err = inflateInit(&d_stream); - CHECK_ERR(err, "inflateInit"); - - for (;;) { - d_stream.next_out = uncompr; /* discard the output */ - d_stream.avail_out = (uInt)uncomprLen; - err = inflate(&d_stream, Z_NO_FLUSH); - if (err == Z_STREAM_END) break; - CHECK_ERR(err, "large inflate"); - } - - err = inflateEnd(&d_stream); - CHECK_ERR(err, "inflateEnd"); - - if (d_stream.total_out != 2*uncomprLen + comprLen/2) { - fprintf(stderr, "bad large inflate: %ld\n", d_stream.total_out); - exit(1); - } else { - printf("large_inflate(): OK\n"); - } -} - -/* =========================================================================== - * Test deflate() with full flush - */ -void test_flush(compr, comprLen) - Byte *compr; - uLong *comprLen; -{ - z_stream c_stream; /* compression stream */ - int err; - uInt len = (uInt)strlen(hello)+1; - - c_stream.zalloc = (alloc_func)0; - c_stream.zfree = (free_func)0; - c_stream.opaque = (voidpf)0; - - err = deflateInit(&c_stream, Z_DEFAULT_COMPRESSION); - CHECK_ERR(err, "deflateInit"); - - c_stream.next_in = (Bytef*)hello; - c_stream.next_out = compr; - c_stream.avail_in = 3; - c_stream.avail_out = (uInt)*comprLen; - err = deflate(&c_stream, Z_FULL_FLUSH); - CHECK_ERR(err, "deflate"); - - compr[3]++; /* force an error in first compressed block */ - c_stream.avail_in = len - 3; - - err = deflate(&c_stream, Z_FINISH); - if (err != Z_STREAM_END) { - CHECK_ERR(err, "deflate"); - } - err = deflateEnd(&c_stream); - CHECK_ERR(err, "deflateEnd"); - - *comprLen = c_stream.total_out; -} - -/* =========================================================================== - * Test inflateSync() - */ -void test_sync(compr, comprLen, uncompr, uncomprLen) - Byte *compr, *uncompr; - uLong comprLen, uncomprLen; -{ - int err; - z_stream d_stream; /* decompression stream */ - - strcpy((char*)uncompr, "garbage"); - - d_stream.zalloc = (alloc_func)0; - d_stream.zfree = (free_func)0; - d_stream.opaque = (voidpf)0; - - d_stream.next_in = compr; - d_stream.avail_in = 2; /* just read the zlib header */ - - err = inflateInit(&d_stream); - CHECK_ERR(err, "inflateInit"); - - d_stream.next_out = uncompr; - d_stream.avail_out = (uInt)uncomprLen; - - inflate(&d_stream, Z_NO_FLUSH); - CHECK_ERR(err, "inflate"); - - d_stream.avail_in = (uInt)comprLen-2; /* read all compressed data */ - err = inflateSync(&d_stream); /* but skip the damaged part */ - CHECK_ERR(err, "inflateSync"); - - err = inflate(&d_stream, Z_FINISH); - if (err != Z_DATA_ERROR) { - fprintf(stderr, "inflate should report DATA_ERROR\n"); - /* Because of incorrect adler32 */ - exit(1); - } - err = inflateEnd(&d_stream); - CHECK_ERR(err, "inflateEnd"); - - printf("after inflateSync(): hel%s\n", (char *)uncompr); -} - -/* =========================================================================== - * Test deflate() with preset dictionary - */ -void test_dict_deflate(compr, comprLen) - Byte *compr; - uLong comprLen; -{ - z_stream c_stream; /* compression stream */ - int err; - - c_stream.zalloc = (alloc_func)0; - c_stream.zfree = (free_func)0; - c_stream.opaque = (voidpf)0; - - err = deflateInit(&c_stream, Z_BEST_COMPRESSION); - CHECK_ERR(err, "deflateInit"); - - err = deflateSetDictionary(&c_stream, - (const Bytef*)dictionary, sizeof(dictionary)); - CHECK_ERR(err, "deflateSetDictionary"); - - dictId = c_stream.adler; - c_stream.next_out = compr; - c_stream.avail_out = (uInt)comprLen; - - c_stream.next_in = (Bytef*)hello; - c_stream.avail_in = (uInt)strlen(hello)+1; - - err = deflate(&c_stream, Z_FINISH); - if (err != Z_STREAM_END) { - fprintf(stderr, "deflate should report Z_STREAM_END\n"); - exit(1); - } - err = deflateEnd(&c_stream); - CHECK_ERR(err, "deflateEnd"); -} - -/* =========================================================================== - * Test inflate() with a preset dictionary - */ -void test_dict_inflate(compr, comprLen, uncompr, uncomprLen) - Byte *compr, *uncompr; - uLong comprLen, uncomprLen; -{ - int err; - z_stream d_stream; /* decompression stream */ - - strcpy((char*)uncompr, "garbage"); - - d_stream.zalloc = (alloc_func)0; - d_stream.zfree = (free_func)0; - d_stream.opaque = (voidpf)0; - - d_stream.next_in = compr; - d_stream.avail_in = (uInt)comprLen; - - err = inflateInit(&d_stream); - CHECK_ERR(err, "inflateInit"); - - d_stream.next_out = uncompr; - d_stream.avail_out = (uInt)uncomprLen; - - for (;;) { - err = inflate(&d_stream, Z_NO_FLUSH); - if (err == Z_STREAM_END) break; - if (err == Z_NEED_DICT) { - if (d_stream.adler != dictId) { - fprintf(stderr, "unexpected dictionary"); - exit(1); - } - err = inflateSetDictionary(&d_stream, (const Bytef*)dictionary, - sizeof(dictionary)); - } - CHECK_ERR(err, "inflate with dict"); - } - - err = inflateEnd(&d_stream); - CHECK_ERR(err, "inflateEnd"); - - if (strcmp((char*)uncompr, hello)) { - fprintf(stderr, "bad inflate with dict\n"); - exit(1); - } else { - printf("inflate with dictionary: %s\n", (char *)uncompr); - } -} - -/* =========================================================================== - * Usage: example [output.gz [input.gz]] - */ - -int main(argc, argv) - int argc; - char *argv[]; -{ - Byte *compr, *uncompr; - uLong comprLen = 10000*sizeof(int); /* don't overflow on MSDOS */ - uLong uncomprLen = comprLen; - static const char* myVersion = ZLIB_VERSION; - - if (zlibVersion()[0] != myVersion[0]) { - fprintf(stderr, "incompatible zlib version\n"); - exit(1); - - } else if (strcmp(zlibVersion(), ZLIB_VERSION) != 0) { - fprintf(stderr, "warning: different zlib version\n"); - } - - printf("zlib version %s = 0x%04x, compile flags = 0x%lx\n", - ZLIB_VERSION, ZLIB_VERNUM, zlibCompileFlags()); - - compr = (Byte*)calloc((uInt)comprLen, 1); - uncompr = (Byte*)calloc((uInt)uncomprLen, 1); - /* compr and uncompr are cleared to avoid reading uninitialized - * data and to ensure that uncompr compresses well. - */ - if (compr == Z_NULL || uncompr == Z_NULL) { - printf("out of memory\n"); - exit(1); - } - test_compress(compr, comprLen, uncompr, uncomprLen); - - test_gzio((argc > 1 ? argv[1] : TESTFILE), - uncompr, uncomprLen); - - test_deflate(compr, comprLen); - test_inflate(compr, comprLen, uncompr, uncomprLen); - - test_large_deflate(compr, comprLen, uncompr, uncomprLen); - test_large_inflate(compr, comprLen, uncompr, uncomprLen); - - test_flush(compr, &comprLen); - test_sync(compr, comprLen, uncompr, uncomprLen); - comprLen = uncomprLen; - - test_dict_deflate(compr, comprLen); - test_dict_inflate(compr, comprLen, uncompr, uncomprLen); - - free(compr); - free(uncompr); - - return 0; -} +/* example.c -- usage example of the zlib compression library + * Copyright (C) 1995-2004 Jean-loup Gailly. + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* @(#) $Id$ */ + +#include +#include "zlib.h" + +#ifdef STDC +# include +# include +#endif + +#if defined(VMS) || defined(RISCOS) +# define TESTFILE "foo-gz" +#else +# define TESTFILE "foo.gz" +#endif + +#define CHECK_ERR(err, msg) { \ + if (err != Z_OK) { \ + fprintf(stderr, "%s error: %d\n", msg, err); \ + exit(1); \ + } \ +} + +const char hello[] = "hello, hello!"; +/* "hello world" would be more standard, but the repeated "hello" + * stresses the compression code better, sorry... + */ + +const char dictionary[] = "hello"; +uLong dictId; /* Adler32 value of the dictionary */ + +void test_compress OF((Byte *compr, uLong comprLen, + Byte *uncompr, uLong uncomprLen)); +void test_gzio OF((const char *fname, + Byte *uncompr, uLong uncomprLen)); +void test_deflate OF((Byte *compr, uLong comprLen)); +void test_inflate OF((Byte *compr, uLong comprLen, + Byte *uncompr, uLong uncomprLen)); +void test_large_deflate OF((Byte *compr, uLong comprLen, + Byte *uncompr, uLong uncomprLen)); +void test_large_inflate OF((Byte *compr, uLong comprLen, + Byte *uncompr, uLong uncomprLen)); +void test_flush OF((Byte *compr, uLong *comprLen)); +void test_sync OF((Byte *compr, uLong comprLen, + Byte *uncompr, uLong uncomprLen)); +void test_dict_deflate OF((Byte *compr, uLong comprLen)); +void test_dict_inflate OF((Byte *compr, uLong comprLen, + Byte *uncompr, uLong uncomprLen)); +int main OF((int argc, char *argv[])); + +/* =========================================================================== + * Test compress() and uncompress() + */ +void test_compress(compr, comprLen, uncompr, uncomprLen) + Byte *compr, *uncompr; + uLong comprLen, uncomprLen; +{ + int err; + uLong len = (uLong)strlen(hello)+1; + + err = compress(compr, &comprLen, (const Bytef*)hello, len); + CHECK_ERR(err, "compress"); + + strcpy((char*)uncompr, "garbage"); + + err = uncompress(uncompr, &uncomprLen, compr, comprLen); + CHECK_ERR(err, "uncompress"); + + if (strcmp((char*)uncompr, hello)) { + fprintf(stderr, "bad uncompress\n"); + exit(1); + } else { + printf("uncompress(): %s\n", (char *)uncompr); + } +} + +/* =========================================================================== + * Test read/write of .gz files + */ +void test_gzio(fname, uncompr, uncomprLen) + const char *fname; /* compressed file name */ + Byte *uncompr; + uLong uncomprLen; +{ +#ifdef NO_GZCOMPRESS + fprintf(stderr, "NO_GZCOMPRESS -- gz* functions cannot compress\n"); +#else + int err; + int len = (int)strlen(hello)+1; + gzFile file; + z_off_t pos; + + file = gzopen(fname, "wb"); + if (file == NULL) { + fprintf(stderr, "gzopen error\n"); + exit(1); + } + gzputc(file, 'h'); + if (gzputs(file, "ello") != 4) { + fprintf(stderr, "gzputs err: %s\n", gzerror(file, &err)); + exit(1); + } + if (gzprintf(file, ", %s!", "hello") != 8) { + fprintf(stderr, "gzprintf err: %s\n", gzerror(file, &err)); + exit(1); + } + gzseek(file, 1L, SEEK_CUR); /* add one zero byte */ + gzclose(file); + + file = gzopen(fname, "rb"); + if (file == NULL) { + fprintf(stderr, "gzopen error\n"); + exit(1); + } + strcpy((char*)uncompr, "garbage"); + + if (gzread(file, uncompr, (unsigned)uncomprLen) != len) { + fprintf(stderr, "gzread err: %s\n", gzerror(file, &err)); + exit(1); + } + if (strcmp((char*)uncompr, hello)) { + fprintf(stderr, "bad gzread: %s\n", (char*)uncompr); + exit(1); + } else { + printf("gzread(): %s\n", (char*)uncompr); + } + + pos = gzseek(file, -8L, SEEK_CUR); + if (pos != 6 || gztell(file) != pos) { + fprintf(stderr, "gzseek error, pos=%ld, gztell=%ld\n", + (long)pos, (long)gztell(file)); + exit(1); + } + + if (gzgetc(file) != ' ') { + fprintf(stderr, "gzgetc error\n"); + exit(1); + } + + if (gzungetc(' ', file) != ' ') { + fprintf(stderr, "gzungetc error\n"); + exit(1); + } + + gzgets(file, (char*)uncompr, (int)uncomprLen); + if (strlen((char*)uncompr) != 7) { /* " hello!" */ + fprintf(stderr, "gzgets err after gzseek: %s\n", gzerror(file, &err)); + exit(1); + } + if (strcmp((char*)uncompr, hello + 6)) { + fprintf(stderr, "bad gzgets after gzseek\n"); + exit(1); + } else { + printf("gzgets() after gzseek: %s\n", (char*)uncompr); + } + + gzclose(file); +#endif +} + +/* =========================================================================== + * Test deflate() with small buffers + */ +void test_deflate(compr, comprLen) + Byte *compr; + uLong comprLen; +{ + z_stream c_stream; /* compression stream */ + int err; + uLong len = (uLong)strlen(hello)+1; + + c_stream.zalloc = (alloc_func)0; + c_stream.zfree = (free_func)0; + c_stream.opaque = (voidpf)0; + + err = deflateInit(&c_stream, Z_DEFAULT_COMPRESSION); + CHECK_ERR(err, "deflateInit"); + + c_stream.next_in = (Bytef*)hello; + c_stream.next_out = compr; + + while (c_stream.total_in != len && c_stream.total_out < comprLen) { + c_stream.avail_in = c_stream.avail_out = 1; /* force small buffers */ + err = deflate(&c_stream, Z_NO_FLUSH); + CHECK_ERR(err, "deflate"); + } + /* Finish the stream, still forcing small buffers: */ + for (;;) { + c_stream.avail_out = 1; + err = deflate(&c_stream, Z_FINISH); + if (err == Z_STREAM_END) break; + CHECK_ERR(err, "deflate"); + } + + err = deflateEnd(&c_stream); + CHECK_ERR(err, "deflateEnd"); +} + +/* =========================================================================== + * Test inflate() with small buffers + */ +void test_inflate(compr, comprLen, uncompr, uncomprLen) + Byte *compr, *uncompr; + uLong comprLen, uncomprLen; +{ + int err; + z_stream d_stream; /* decompression stream */ + + strcpy((char*)uncompr, "garbage"); + + d_stream.zalloc = (alloc_func)0; + d_stream.zfree = (free_func)0; + d_stream.opaque = (voidpf)0; + + d_stream.next_in = compr; + d_stream.avail_in = 0; + d_stream.next_out = uncompr; + + err = inflateInit(&d_stream); + CHECK_ERR(err, "inflateInit"); + + while (d_stream.total_out < uncomprLen && d_stream.total_in < comprLen) { + d_stream.avail_in = d_stream.avail_out = 1; /* force small buffers */ + err = inflate(&d_stream, Z_NO_FLUSH); + if (err == Z_STREAM_END) break; + CHECK_ERR(err, "inflate"); + } + + err = inflateEnd(&d_stream); + CHECK_ERR(err, "inflateEnd"); + + if (strcmp((char*)uncompr, hello)) { + fprintf(stderr, "bad inflate\n"); + exit(1); + } else { + printf("inflate(): %s\n", (char *)uncompr); + } +} + +/* =========================================================================== + * Test deflate() with large buffers and dynamic change of compression level + */ +void test_large_deflate(compr, comprLen, uncompr, uncomprLen) + Byte *compr, *uncompr; + uLong comprLen, uncomprLen; +{ + z_stream c_stream; /* compression stream */ + int err; + + c_stream.zalloc = (alloc_func)0; + c_stream.zfree = (free_func)0; + c_stream.opaque = (voidpf)0; + + err = deflateInit(&c_stream, Z_BEST_SPEED); + CHECK_ERR(err, "deflateInit"); + + c_stream.next_out = compr; + c_stream.avail_out = (uInt)comprLen; + + /* At this point, uncompr is still mostly zeroes, so it should compress + * very well: + */ + c_stream.next_in = uncompr; + c_stream.avail_in = (uInt)uncomprLen; + err = deflate(&c_stream, Z_NO_FLUSH); + CHECK_ERR(err, "deflate"); + if (c_stream.avail_in != 0) { + fprintf(stderr, "deflate not greedy\n"); + exit(1); + } + + /* Feed in already compressed data and switch to no compression: */ + deflateParams(&c_stream, Z_NO_COMPRESSION, Z_DEFAULT_STRATEGY); + c_stream.next_in = compr; + c_stream.avail_in = (uInt)comprLen/2; + err = deflate(&c_stream, Z_NO_FLUSH); + CHECK_ERR(err, "deflate"); + + /* Switch back to compressing mode: */ + deflateParams(&c_stream, Z_BEST_COMPRESSION, Z_FILTERED); + c_stream.next_in = uncompr; + c_stream.avail_in = (uInt)uncomprLen; + err = deflate(&c_stream, Z_NO_FLUSH); + CHECK_ERR(err, "deflate"); + + err = deflate(&c_stream, Z_FINISH); + if (err != Z_STREAM_END) { + fprintf(stderr, "deflate should report Z_STREAM_END\n"); + exit(1); + } + err = deflateEnd(&c_stream); + CHECK_ERR(err, "deflateEnd"); +} + +/* =========================================================================== + * Test inflate() with large buffers + */ +void test_large_inflate(compr, comprLen, uncompr, uncomprLen) + Byte *compr, *uncompr; + uLong comprLen, uncomprLen; +{ + int err; + z_stream d_stream; /* decompression stream */ + + strcpy((char*)uncompr, "garbage"); + + d_stream.zalloc = (alloc_func)0; + d_stream.zfree = (free_func)0; + d_stream.opaque = (voidpf)0; + + d_stream.next_in = compr; + d_stream.avail_in = (uInt)comprLen; + + err = inflateInit(&d_stream); + CHECK_ERR(err, "inflateInit"); + + for (;;) { + d_stream.next_out = uncompr; /* discard the output */ + d_stream.avail_out = (uInt)uncomprLen; + err = inflate(&d_stream, Z_NO_FLUSH); + if (err == Z_STREAM_END) break; + CHECK_ERR(err, "large inflate"); + } + + err = inflateEnd(&d_stream); + CHECK_ERR(err, "inflateEnd"); + + if (d_stream.total_out != 2*uncomprLen + comprLen/2) { + fprintf(stderr, "bad large inflate: %ld\n", d_stream.total_out); + exit(1); + } else { + printf("large_inflate(): OK\n"); + } +} + +/* =========================================================================== + * Test deflate() with full flush + */ +void test_flush(compr, comprLen) + Byte *compr; + uLong *comprLen; +{ + z_stream c_stream; /* compression stream */ + int err; + uInt len = (uInt)strlen(hello)+1; + + c_stream.zalloc = (alloc_func)0; + c_stream.zfree = (free_func)0; + c_stream.opaque = (voidpf)0; + + err = deflateInit(&c_stream, Z_DEFAULT_COMPRESSION); + CHECK_ERR(err, "deflateInit"); + + c_stream.next_in = (Bytef*)hello; + c_stream.next_out = compr; + c_stream.avail_in = 3; + c_stream.avail_out = (uInt)*comprLen; + err = deflate(&c_stream, Z_FULL_FLUSH); + CHECK_ERR(err, "deflate"); + + compr[3]++; /* force an error in first compressed block */ + c_stream.avail_in = len - 3; + + err = deflate(&c_stream, Z_FINISH); + if (err != Z_STREAM_END) { + CHECK_ERR(err, "deflate"); + } + err = deflateEnd(&c_stream); + CHECK_ERR(err, "deflateEnd"); + + *comprLen = c_stream.total_out; +} + +/* =========================================================================== + * Test inflateSync() + */ +void test_sync(compr, comprLen, uncompr, uncomprLen) + Byte *compr, *uncompr; + uLong comprLen, uncomprLen; +{ + int err; + z_stream d_stream; /* decompression stream */ + + strcpy((char*)uncompr, "garbage"); + + d_stream.zalloc = (alloc_func)0; + d_stream.zfree = (free_func)0; + d_stream.opaque = (voidpf)0; + + d_stream.next_in = compr; + d_stream.avail_in = 2; /* just read the zlib header */ + + err = inflateInit(&d_stream); + CHECK_ERR(err, "inflateInit"); + + d_stream.next_out = uncompr; + d_stream.avail_out = (uInt)uncomprLen; + + inflate(&d_stream, Z_NO_FLUSH); + CHECK_ERR(err, "inflate"); + + d_stream.avail_in = (uInt)comprLen-2; /* read all compressed data */ + err = inflateSync(&d_stream); /* but skip the damaged part */ + CHECK_ERR(err, "inflateSync"); + + err = inflate(&d_stream, Z_FINISH); + if (err != Z_DATA_ERROR) { + fprintf(stderr, "inflate should report DATA_ERROR\n"); + /* Because of incorrect adler32 */ + exit(1); + } + err = inflateEnd(&d_stream); + CHECK_ERR(err, "inflateEnd"); + + printf("after inflateSync(): hel%s\n", (char *)uncompr); +} + +/* =========================================================================== + * Test deflate() with preset dictionary + */ +void test_dict_deflate(compr, comprLen) + Byte *compr; + uLong comprLen; +{ + z_stream c_stream; /* compression stream */ + int err; + + c_stream.zalloc = (alloc_func)0; + c_stream.zfree = (free_func)0; + c_stream.opaque = (voidpf)0; + + err = deflateInit(&c_stream, Z_BEST_COMPRESSION); + CHECK_ERR(err, "deflateInit"); + + err = deflateSetDictionary(&c_stream, + (const Bytef*)dictionary, sizeof(dictionary)); + CHECK_ERR(err, "deflateSetDictionary"); + + dictId = c_stream.adler; + c_stream.next_out = compr; + c_stream.avail_out = (uInt)comprLen; + + c_stream.next_in = (Bytef*)hello; + c_stream.avail_in = (uInt)strlen(hello)+1; + + err = deflate(&c_stream, Z_FINISH); + if (err != Z_STREAM_END) { + fprintf(stderr, "deflate should report Z_STREAM_END\n"); + exit(1); + } + err = deflateEnd(&c_stream); + CHECK_ERR(err, "deflateEnd"); +} + +/* =========================================================================== + * Test inflate() with a preset dictionary + */ +void test_dict_inflate(compr, comprLen, uncompr, uncomprLen) + Byte *compr, *uncompr; + uLong comprLen, uncomprLen; +{ + int err; + z_stream d_stream; /* decompression stream */ + + strcpy((char*)uncompr, "garbage"); + + d_stream.zalloc = (alloc_func)0; + d_stream.zfree = (free_func)0; + d_stream.opaque = (voidpf)0; + + d_stream.next_in = compr; + d_stream.avail_in = (uInt)comprLen; + + err = inflateInit(&d_stream); + CHECK_ERR(err, "inflateInit"); + + d_stream.next_out = uncompr; + d_stream.avail_out = (uInt)uncomprLen; + + for (;;) { + err = inflate(&d_stream, Z_NO_FLUSH); + if (err == Z_STREAM_END) break; + if (err == Z_NEED_DICT) { + if (d_stream.adler != dictId) { + fprintf(stderr, "unexpected dictionary"); + exit(1); + } + err = inflateSetDictionary(&d_stream, (const Bytef*)dictionary, + sizeof(dictionary)); + } + CHECK_ERR(err, "inflate with dict"); + } + + err = inflateEnd(&d_stream); + CHECK_ERR(err, "inflateEnd"); + + if (strcmp((char*)uncompr, hello)) { + fprintf(stderr, "bad inflate with dict\n"); + exit(1); + } else { + printf("inflate with dictionary: %s\n", (char *)uncompr); + } +} + +/* =========================================================================== + * Usage: example [output.gz [input.gz]] + */ + +int main(argc, argv) + int argc; + char *argv[]; +{ + Byte *compr, *uncompr; + uLong comprLen = 10000*sizeof(int); /* don't overflow on MSDOS */ + uLong uncomprLen = comprLen; + static const char* myVersion = ZLIB_VERSION; + + if (zlibVersion()[0] != myVersion[0]) { + fprintf(stderr, "incompatible zlib version\n"); + exit(1); + + } else if (strcmp(zlibVersion(), ZLIB_VERSION) != 0) { + fprintf(stderr, "warning: different zlib version\n"); + } + + printf("zlib version %s = 0x%04x, compile flags = 0x%lx\n", + ZLIB_VERSION, ZLIB_VERNUM, zlibCompileFlags()); + + compr = (Byte*)calloc((uInt)comprLen, 1); + uncompr = (Byte*)calloc((uInt)uncomprLen, 1); + /* compr and uncompr are cleared to avoid reading uninitialized + * data and to ensure that uncompr compresses well. + */ + if (compr == Z_NULL || uncompr == Z_NULL) { + printf("out of memory\n"); + exit(1); + } + test_compress(compr, comprLen, uncompr, uncomprLen); + + test_gzio((argc > 1 ? argv[1] : TESTFILE), + uncompr, uncomprLen); + + test_deflate(compr, comprLen); + test_inflate(compr, comprLen, uncompr, uncomprLen); + + test_large_deflate(compr, comprLen, uncompr, uncomprLen); + test_large_inflate(compr, comprLen, uncompr, uncomprLen); + + test_flush(compr, &comprLen); + test_sync(compr, comprLen, uncompr, uncomprLen); + comprLen = uncomprLen; + + test_dict_deflate(compr, comprLen); + test_dict_inflate(compr, comprLen, uncompr, uncomprLen); + + free(compr); + free(uncompr); + + return 0; +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/gzio.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/gzio.c index d77225f94..25850ad1d 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/gzio.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/gzio.c @@ -1,1026 +1,1026 @@ -/* gzio.c -- IO on .gz files - * Copyright (C) 1995-2005 Jean-loup Gailly. - * For conditions of distribution and use, see copyright notice in zlib.h - * - * Compile this file with -DNO_GZCOMPRESS to avoid the compression code. - */ - -/* @(#) $Id$ */ - -#include - -#include "zutil.h" - -#ifdef NO_DEFLATE /* for compatibility with old definition */ -# define NO_GZCOMPRESS -#endif - -#ifndef NO_DUMMY_DECL -struct internal_state {int dummy;}; /* for buggy compilers */ -#endif - -#ifndef Z_BUFSIZE -# ifdef MAXSEG_64K -# define Z_BUFSIZE 4096 /* minimize memory usage for 16-bit DOS */ -# else -# define Z_BUFSIZE 16384 -# endif -#endif -#ifndef Z_PRINTF_BUFSIZE -# define Z_PRINTF_BUFSIZE 4096 -#endif - -#ifdef __MVS__ -# pragma map (fdopen , "\174\174FDOPEN") - FILE *fdopen(int, const char *); -#endif - -#ifndef STDC -extern voidp malloc OF((uInt size)); -extern void free OF((voidpf ptr)); -#endif - -#define ALLOC(size) malloc(size) -#define TRYFREE(p) {if (p) free(p);} - -static int const gz_magic[2] = {0x1f, 0x8b}; /* gzip magic header */ - -/* gzip flag byte */ -#define ASCII_FLAG 0x01 /* bit 0 set: file probably ascii text */ -#define HEAD_CRC 0x02 /* bit 1 set: header CRC present */ -#define EXTRA_FIELD 0x04 /* bit 2 set: extra field present */ -#define ORIG_NAME 0x08 /* bit 3 set: original file name present */ -#define COMMENT 0x10 /* bit 4 set: file comment present */ -#define RESERVED 0xE0 /* bits 5..7: reserved */ - -typedef struct gz_stream { - z_stream stream; - int z_err; /* error code for last stream operation */ - int z_eof; /* set if end of input file */ - FILE *file; /* .gz file */ - Byte *inbuf; /* input buffer */ - Byte *outbuf; /* output buffer */ - uLong crc; /* crc32 of uncompressed data */ - char *msg; /* error message */ - char *path; /* path name for debugging only */ - int transparent; /* 1 if input file is not a .gz file */ - char mode; /* 'w' or 'r' */ - z_off_t start; /* start of compressed data in file (header skipped) */ - z_off_t in; /* bytes into deflate or inflate */ - z_off_t out; /* bytes out of deflate or inflate */ - int back; /* one character push-back */ - int last; /* true if push-back is last character */ -} gz_stream; - - -local gzFile gz_open OF((const char *path, const char *mode, int fd)); -local int do_flush OF((gzFile file, int flush)); -local int get_byte OF((gz_stream *s)); -local void check_header OF((gz_stream *s)); -local int destroy OF((gz_stream *s)); -local void putLong OF((FILE *file, uLong x)); -local uLong getLong OF((gz_stream *s)); - -/* =========================================================================== - Opens a gzip (.gz) file for reading or writing. The mode parameter - is as in fopen ("rb" or "wb"). The file is given either by file descriptor - or path name (if fd == -1). - gz_open returns NULL if the file could not be opened or if there was - insufficient memory to allocate the (de)compression state; errno - can be checked to distinguish the two cases (if errno is zero, the - zlib error is Z_MEM_ERROR). -*/ -local gzFile gz_open (path, mode, fd) - const char *path; - const char *mode; - int fd; -{ - int err; - int level = Z_DEFAULT_COMPRESSION; /* compression level */ - int strategy = Z_DEFAULT_STRATEGY; /* compression strategy */ - char *p = (char*)mode; - gz_stream *s; - char fmode[80]; /* copy of mode, without the compression level */ - char *m = fmode; - - if (!path || !mode) return Z_NULL; - - s = (gz_stream *)ALLOC(sizeof(gz_stream)); - if (!s) return Z_NULL; - - s->stream.zalloc = (alloc_func)0; - s->stream.zfree = (free_func)0; - s->stream.opaque = (voidpf)0; - s->stream.next_in = s->inbuf = Z_NULL; - s->stream.next_out = s->outbuf = Z_NULL; - s->stream.avail_in = s->stream.avail_out = 0; - s->file = NULL; - s->z_err = Z_OK; - s->z_eof = 0; - s->in = 0; - s->out = 0; - s->back = EOF; - s->crc = crc32(0L, Z_NULL, 0); - s->msg = NULL; - s->transparent = 0; - - s->path = (char*)ALLOC(strlen(path)+1); - if (s->path == NULL) { - return destroy(s), (gzFile)Z_NULL; - } - strcpy(s->path, path); /* do this early for debugging */ - - s->mode = '\0'; - do { - if (*p == 'r') s->mode = 'r'; - if (*p == 'w' || *p == 'a') s->mode = 'w'; - if (*p >= '0' && *p <= '9') { - level = *p - '0'; - } else if (*p == 'f') { - strategy = Z_FILTERED; - } else if (*p == 'h') { - strategy = Z_HUFFMAN_ONLY; - } else if (*p == 'R') { - strategy = Z_RLE; - } else { - *m++ = *p; /* copy the mode */ - } - } while (*p++ && m != fmode + sizeof(fmode)); - if (s->mode == '\0') return destroy(s), (gzFile)Z_NULL; - - if (s->mode == 'w') { -#ifdef NO_GZCOMPRESS - err = Z_STREAM_ERROR; -#else - err = deflateInit2(&(s->stream), level, - Z_DEFLATED, -MAX_WBITS, DEF_MEM_LEVEL, strategy); - /* windowBits is passed < 0 to suppress zlib header */ - - s->stream.next_out = s->outbuf = (Byte*)ALLOC(Z_BUFSIZE); -#endif - if (err != Z_OK || s->outbuf == Z_NULL) { - return destroy(s), (gzFile)Z_NULL; - } - } else { - s->stream.next_in = s->inbuf = (Byte*)ALLOC(Z_BUFSIZE); - - err = inflateInit2(&(s->stream), -MAX_WBITS); - /* windowBits is passed < 0 to tell that there is no zlib header. - * Note that in this case inflate *requires* an extra "dummy" byte - * after the compressed stream in order to complete decompression and - * return Z_STREAM_END. Here the gzip CRC32 ensures that 4 bytes are - * present after the compressed stream. - */ - if (err != Z_OK || s->inbuf == Z_NULL) { - return destroy(s), (gzFile)Z_NULL; - } - } - s->stream.avail_out = Z_BUFSIZE; - - errno = 0; - s->file = fd < 0 ? F_OPEN(path, fmode) : (FILE*)fdopen(fd, fmode); - - if (s->file == NULL) { - return destroy(s), (gzFile)Z_NULL; - } - if (s->mode == 'w') { - /* Write a very simple .gz header: - */ - fprintf(s->file, "%c%c%c%c%c%c%c%c%c%c", gz_magic[0], gz_magic[1], - Z_DEFLATED, 0 /*flags*/, 0,0,0,0 /*time*/, 0 /*xflags*/, OS_CODE); - s->start = 10L; - /* We use 10L instead of ftell(s->file) to because ftell causes an - * fflush on some systems. This version of the library doesn't use - * start anyway in write mode, so this initialization is not - * necessary. - */ - } else { - check_header(s); /* skip the .gz header */ - s->start = ftell(s->file) - s->stream.avail_in; - } - - return (gzFile)s; -} - -/* =========================================================================== - Opens a gzip (.gz) file for reading or writing. -*/ -gzFile Q_ZEXPORT gzopen (path, mode) - const char *path; - const char *mode; -{ - return gz_open (path, mode, -1); -} - -/* =========================================================================== - Associate a gzFile with the file descriptor fd. fd is not dup'ed here - to mimic the behavio(u)r of fdopen. -*/ -gzFile ZEXPORT gzdopen (fd, mode) - int fd; - const char *mode; -{ - char name[46]; /* allow for up to 128-bit integers */ - - if (fd < 0) return (gzFile)Z_NULL; - sprintf(name, "", fd); /* for debugging */ - - return gz_open (name, mode, fd); -} - -/* =========================================================================== - * Update the compression level and strategy - */ -int ZEXPORT gzsetparams (file, level, strategy) - gzFile file; - int level; - int strategy; -{ - gz_stream *s = (gz_stream*)file; - - if (s == NULL || s->mode != 'w') return Z_STREAM_ERROR; - - /* Make room to allow flushing */ - if (s->stream.avail_out == 0) { - - s->stream.next_out = s->outbuf; - if (fwrite(s->outbuf, 1, Z_BUFSIZE, s->file) != Z_BUFSIZE) { - s->z_err = Z_ERRNO; - } - s->stream.avail_out = Z_BUFSIZE; - } - - return deflateParams (&(s->stream), level, strategy); -} - -/* =========================================================================== - Read a byte from a gz_stream; update next_in and avail_in. Return EOF - for end of file. - IN assertion: the stream s has been sucessfully opened for reading. -*/ -local int get_byte(s) - gz_stream *s; -{ - if (s->z_eof) return EOF; - if (s->stream.avail_in == 0) { - errno = 0; - s->stream.avail_in = (uInt)fread(s->inbuf, 1, Z_BUFSIZE, s->file); - if (s->stream.avail_in == 0) { - s->z_eof = 1; - if (ferror(s->file)) s->z_err = Z_ERRNO; - return EOF; - } - s->stream.next_in = s->inbuf; - } - s->stream.avail_in--; - return *(s->stream.next_in)++; -} - -/* =========================================================================== - Check the gzip header of a gz_stream opened for reading. Set the stream - mode to transparent if the gzip magic header is not present; set s->err - to Z_DATA_ERROR if the magic header is present but the rest of the header - is incorrect. - IN assertion: the stream s has already been created sucessfully; - s->stream.avail_in is zero for the first time, but may be non-zero - for concatenated .gz files. -*/ -local void check_header(s) - gz_stream *s; -{ - int method; /* method byte */ - int flags; /* flags byte */ - uInt len; - int c; - - /* Assure two bytes in the buffer so we can peek ahead -- handle case - where first byte of header is at the end of the buffer after the last - gzip segment */ - len = s->stream.avail_in; - if (len < 2) { - if (len) s->inbuf[0] = s->stream.next_in[0]; - errno = 0; - len = (uInt)fread(s->inbuf + len, 1, Z_BUFSIZE >> len, s->file); - if (len == 0 && ferror(s->file)) s->z_err = Z_ERRNO; - s->stream.avail_in += len; - s->stream.next_in = s->inbuf; - if (s->stream.avail_in < 2) { - s->transparent = s->stream.avail_in; - return; - } - } - - /* Peek ahead to check the gzip magic header */ - if (s->stream.next_in[0] != gz_magic[0] || - s->stream.next_in[1] != gz_magic[1]) { - s->transparent = 1; - return; - } - s->stream.avail_in -= 2; - s->stream.next_in += 2; - - /* Check the rest of the gzip header */ - method = get_byte(s); - flags = get_byte(s); - if (method != Z_DEFLATED || (flags & RESERVED) != 0) { - s->z_err = Z_DATA_ERROR; - return; - } - - /* Discard time, xflags and OS code: */ - for (len = 0; len < 6; len++) (void)get_byte(s); - - if ((flags & EXTRA_FIELD) != 0) { /* skip the extra field */ - len = (uInt)get_byte(s); - len += ((uInt)get_byte(s))<<8; - /* len is garbage if EOF but the loop below will quit anyway */ - while (len-- != 0 && get_byte(s) != EOF) ; - } - if ((flags & ORIG_NAME) != 0) { /* skip the original file name */ - while ((c = get_byte(s)) != 0 && c != EOF) ; - } - if ((flags & COMMENT) != 0) { /* skip the .gz file comment */ - while ((c = get_byte(s)) != 0 && c != EOF) ; - } - if ((flags & HEAD_CRC) != 0) { /* skip the header crc */ - for (len = 0; len < 2; len++) (void)get_byte(s); - } - s->z_err = s->z_eof ? Z_DATA_ERROR : Z_OK; -} - - /* =========================================================================== - * Cleanup then free the given gz_stream. Return a zlib error code. - Try freeing in the reverse order of allocations. - */ -local int destroy (s) - gz_stream *s; -{ - int err = Z_OK; - - if (!s) return Z_STREAM_ERROR; - - TRYFREE(s->msg); - - if (s->stream.state != NULL) { - if (s->mode == 'w') { -#ifdef NO_GZCOMPRESS - err = Z_STREAM_ERROR; -#else - err = deflateEnd(&(s->stream)); -#endif - } else if (s->mode == 'r') { - err = inflateEnd(&(s->stream)); - } - } - if (s->file != NULL && fclose(s->file)) { -#ifdef ESPIPE - if (errno != ESPIPE) /* fclose is broken for pipes in HP/UX */ -#endif - err = Z_ERRNO; - } - if (s->z_err < 0) err = s->z_err; - - TRYFREE(s->inbuf); - TRYFREE(s->outbuf); - TRYFREE(s->path); - TRYFREE(s); - return err; -} - -/* =========================================================================== - Reads the given number of uncompressed bytes from the compressed file. - gzread returns the number of bytes actually read (0 for end of file). -*/ -int Q_ZEXPORT gzread (file, buf, len) - gzFile file; - voidp buf; - unsigned len; -{ - gz_stream *s = (gz_stream*)file; - Bytef *start = (Bytef*)buf; /* starting point for crc computation */ - Byte *next_out; /* == stream.next_out but not forced far (for MSDOS) */ - - if (s == NULL || s->mode != 'r') return Z_STREAM_ERROR; - - if (s->z_err == Z_DATA_ERROR || s->z_err == Z_ERRNO) return -1; - if (s->z_err == Z_STREAM_END) return 0; /* EOF */ - - next_out = (Byte*)buf; - s->stream.next_out = (Bytef*)buf; - s->stream.avail_out = len; - - if (s->stream.avail_out && s->back != EOF) { - *next_out++ = s->back; - s->stream.next_out++; - s->stream.avail_out--; - s->back = EOF; - s->out++; - start++; - if (s->last) { - s->z_err = Z_STREAM_END; - return 1; - } - } - - while (s->stream.avail_out != 0) { - - if (s->transparent) { - /* Copy first the lookahead bytes: */ - uInt n = s->stream.avail_in; - if (n > s->stream.avail_out) n = s->stream.avail_out; - if (n > 0) { - zmemcpy(s->stream.next_out, s->stream.next_in, n); - next_out += n; - s->stream.next_out = next_out; - s->stream.next_in += n; - s->stream.avail_out -= n; - s->stream.avail_in -= n; - } - if (s->stream.avail_out > 0) { - s->stream.avail_out -= - (uInt)fread(next_out, 1, s->stream.avail_out, s->file); - } - len -= s->stream.avail_out; - s->in += len; - s->out += len; - if (len == 0) s->z_eof = 1; - return (int)len; - } - if (s->stream.avail_in == 0 && !s->z_eof) { - - errno = 0; - s->stream.avail_in = (uInt)fread(s->inbuf, 1, Z_BUFSIZE, s->file); - if (s->stream.avail_in == 0) { - s->z_eof = 1; - if (ferror(s->file)) { - s->z_err = Z_ERRNO; - break; - } - } - s->stream.next_in = s->inbuf; - } - s->in += s->stream.avail_in; - s->out += s->stream.avail_out; - s->z_err = inflate(&(s->stream), Z_NO_FLUSH); - s->in -= s->stream.avail_in; - s->out -= s->stream.avail_out; - - if (s->z_err == Z_STREAM_END) { - /* Check CRC and original size */ - s->crc = crc32(s->crc, start, (uInt)(s->stream.next_out - start)); - start = s->stream.next_out; - - if (getLong(s) != s->crc) { - s->z_err = Z_DATA_ERROR; - } else { - (void)getLong(s); - /* The uncompressed length returned by above getlong() may be - * different from s->out in case of concatenated .gz files. - * Check for such files: - */ - check_header(s); - if (s->z_err == Z_OK) { - inflateReset(&(s->stream)); - s->crc = crc32(0L, Z_NULL, 0); - } - } - } - if (s->z_err != Z_OK || s->z_eof) break; - } - s->crc = crc32(s->crc, start, (uInt)(s->stream.next_out - start)); - - if (len == s->stream.avail_out && - (s->z_err == Z_DATA_ERROR || s->z_err == Z_ERRNO)) - return -1; - return (int)(len - s->stream.avail_out); -} - - -/* =========================================================================== - Reads one byte from the compressed file. gzgetc returns this byte - or -1 in case of end of file or error. -*/ -int ZEXPORT gzgetc(file) - gzFile file; -{ - unsigned char c; - - return gzread(file, &c, 1) == 1 ? c : -1; -} - - -/* =========================================================================== - Push one byte back onto the stream. -*/ -int ZEXPORT gzungetc(c, file) - int c; - gzFile file; -{ - gz_stream *s = (gz_stream*)file; - - if (s == NULL || s->mode != 'r' || c == EOF || s->back != EOF) return EOF; - s->back = c; - s->out--; - s->last = (s->z_err == Z_STREAM_END); - if (s->last) s->z_err = Z_OK; - s->z_eof = 0; - return c; -} - - -/* =========================================================================== - Reads bytes from the compressed file until len-1 characters are - read, or a newline character is read and transferred to buf, or an - end-of-file condition is encountered. The string is then terminated - with a null character. - gzgets returns buf, or Z_NULL in case of error. - - The current implementation is not optimized at all. -*/ -char * ZEXPORT gzgets(file, buf, len) - gzFile file; - char *buf; - int len; -{ - char *b = buf; - if (buf == Z_NULL || len <= 0) return Z_NULL; - - while (--len > 0 && gzread(file, buf, 1) == 1 && *buf++ != '\n') ; - *buf = '\0'; - return b == buf && len > 0 ? Z_NULL : b; -} - - -#ifndef NO_GZCOMPRESS -/* =========================================================================== - Writes the given number of uncompressed bytes into the compressed file. - gzwrite returns the number of bytes actually written (0 in case of error). -*/ -int ZEXPORT gzwrite (file, buf, len) - gzFile file; - voidpc buf; - unsigned len; -{ - gz_stream *s = (gz_stream*)file; - - if (s == NULL || s->mode != 'w') return Z_STREAM_ERROR; - - s->stream.next_in = (Bytef*)buf; - s->stream.avail_in = len; - - while (s->stream.avail_in != 0) { - - if (s->stream.avail_out == 0) { - - s->stream.next_out = s->outbuf; - if (fwrite(s->outbuf, 1, Z_BUFSIZE, s->file) != Z_BUFSIZE) { - s->z_err = Z_ERRNO; - break; - } - s->stream.avail_out = Z_BUFSIZE; - } - s->in += s->stream.avail_in; - s->out += s->stream.avail_out; - s->z_err = deflate(&(s->stream), Z_NO_FLUSH); - s->in -= s->stream.avail_in; - s->out -= s->stream.avail_out; - if (s->z_err != Z_OK) break; - } - s->crc = crc32(s->crc, (const Bytef *)buf, len); - - return (int)(len - s->stream.avail_in); -} - - -/* =========================================================================== - Converts, formats, and writes the args to the compressed file under - control of the format string, as in fprintf. gzprintf returns the number of - uncompressed bytes actually written (0 in case of error). -*/ -#ifdef STDC -#include - -int Q_ZEXPORT gzprintf (gzFile file, const char *format, /* args */ ...) -{ - char buf[Z_PRINTF_BUFSIZE]; - va_list va; - int len; - - buf[sizeof(buf) - 1] = 0; - va_start(va, format); -#ifdef NO_vsnprintf -# ifdef HAS_vsprintf_void - (void)vsprintf(buf, format, va); - va_end(va); - for (len = 0; len < sizeof(buf); len++) - if (buf[len] == 0) break; -# else - len = vsprintf(buf, format, va); - va_end(va); -# endif -#else -# ifdef HAS_vsnprintf_void - (void)vsnprintf(buf, sizeof(buf), format, va); - va_end(va); - len = strlen(buf); -# else - len = vsnprintf(buf, sizeof(buf), format, va); - va_end(va); -# endif -#endif - if (len <= 0 || len >= (int)sizeof(buf) || buf[sizeof(buf) - 1] != 0) - return 0; - return gzwrite(file, buf, (unsigned)len); -} -#else /* not ANSI C */ - -int Q_ZEXPORT gzprintf (file, format, a1, a2, a3, a4, a5, a6, a7, a8, a9, a10, - a11, a12, a13, a14, a15, a16, a17, a18, a19, a20) - gzFile file; - const char *format; - int a1, a2, a3, a4, a5, a6, a7, a8, a9, a10, - a11, a12, a13, a14, a15, a16, a17, a18, a19, a20; -{ - char buf[Z_PRINTF_BUFSIZE]; - int len; - - buf[sizeof(buf) - 1] = 0; -#ifdef NO_snprintf -# ifdef HAS_sprintf_void - sprintf(buf, format, a1, a2, a3, a4, a5, a6, a7, a8, - a9, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a20); - for (len = 0; len < sizeof(buf); len++) - if (buf[len] == 0) break; -# else - len = sprintf(buf, format, a1, a2, a3, a4, a5, a6, a7, a8, - a9, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a20); -# endif -#else -# ifdef HAS_snprintf_void - snprintf(buf, sizeof(buf), format, a1, a2, a3, a4, a5, a6, a7, a8, - a9, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a20); - len = strlen(buf); -# else - len = snprintf(buf, sizeof(buf), format, a1, a2, a3, a4, a5, a6, a7, a8, - a9, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a20); -# endif -#endif - if (len <= 0 || len >= sizeof(buf) || buf[sizeof(buf) - 1] != 0) - return 0; - return gzwrite(file, buf, len); -} -#endif - -/* =========================================================================== - Writes c, converted to an unsigned char, into the compressed file. - gzputc returns the value that was written, or -1 in case of error. -*/ -int ZEXPORT gzputc(file, c) - gzFile file; - int c; -{ - unsigned char cc = (unsigned char) c; /* required for big endian systems */ - - return gzwrite(file, &cc, 1) == 1 ? (int)cc : -1; -} - - -/* =========================================================================== - Writes the given null-terminated string to the compressed file, excluding - the terminating null character. - gzputs returns the number of characters written, or -1 in case of error. -*/ -int ZEXPORT gzputs(file, s) - gzFile file; - const char *s; -{ - return gzwrite(file, (char*)s, (unsigned)strlen(s)); -} - - -/* =========================================================================== - Flushes all pending output into the compressed file. The parameter - flush is as in the deflate() function. -*/ -local int do_flush (file, flush) - gzFile file; - int flush; -{ - uInt len; - int done = 0; - gz_stream *s = (gz_stream*)file; - - if (s == NULL || s->mode != 'w') return Z_STREAM_ERROR; - - s->stream.avail_in = 0; /* should be zero already anyway */ - - for (;;) { - len = Z_BUFSIZE - s->stream.avail_out; - - if (len != 0) { - if ((uInt)fwrite(s->outbuf, 1, len, s->file) != len) { - s->z_err = Z_ERRNO; - return Z_ERRNO; - } - s->stream.next_out = s->outbuf; - s->stream.avail_out = Z_BUFSIZE; - } - if (done) break; - s->out += s->stream.avail_out; - s->z_err = deflate(&(s->stream), flush); - s->out -= s->stream.avail_out; - - /* Ignore the second of two consecutive flushes: */ - if (len == 0 && s->z_err == Z_BUF_ERROR) s->z_err = Z_OK; - - /* deflate has finished flushing only when it hasn't used up - * all the available space in the output buffer: - */ - done = (s->stream.avail_out != 0 || s->z_err == Z_STREAM_END); - - if (s->z_err != Z_OK && s->z_err != Z_STREAM_END) break; - } - return s->z_err == Z_STREAM_END ? Z_OK : s->z_err; -} - -int ZEXPORT gzflush (file, flush) - gzFile file; - int flush; -{ - gz_stream *s = (gz_stream*)file; - int err = do_flush (file, flush); - - if (err) return err; - fflush(s->file); - return s->z_err == Z_STREAM_END ? Z_OK : s->z_err; -} -#endif /* NO_GZCOMPRESS */ - -/* =========================================================================== - Sets the starting position for the next gzread or gzwrite on the given - compressed file. The offset represents a number of bytes in the - gzseek returns the resulting offset location as measured in bytes from - the beginning of the uncompressed stream, or -1 in case of error. - SEEK_END is not implemented, returns error. - In this version of the library, gzseek can be extremely slow. -*/ -z_off_t ZEXPORT gzseek (file, offset, whence) - gzFile file; - z_off_t offset; - int whence; -{ - gz_stream *s = (gz_stream*)file; - - if (s == NULL || whence == SEEK_END || - s->z_err == Z_ERRNO || s->z_err == Z_DATA_ERROR) { - return -1L; - } - - if (s->mode == 'w') { -#ifdef NO_GZCOMPRESS - return -1L; -#else - if (whence == SEEK_SET) { - offset -= s->in; - } - if (offset < 0) return -1L; - - /* At this point, offset is the number of zero bytes to write. */ - if (s->inbuf == Z_NULL) { - s->inbuf = (Byte*)ALLOC(Z_BUFSIZE); /* for seeking */ - if (s->inbuf == Z_NULL) return -1L; - zmemzero(s->inbuf, Z_BUFSIZE); - } - while (offset > 0) { - uInt size = Z_BUFSIZE; - if (offset < Z_BUFSIZE) size = (uInt)offset; - - size = gzwrite(file, s->inbuf, size); - if (size == 0) return -1L; - - offset -= size; - } - return s->in; -#endif - } - /* Rest of function is for reading only */ - - /* compute absolute position */ - if (whence == SEEK_CUR) { - offset += s->out; - } - if (offset < 0) return -1L; - - if (s->transparent) { - /* map to fseek */ - s->back = EOF; - s->stream.avail_in = 0; - s->stream.next_in = s->inbuf; - if (fseek(s->file, offset, SEEK_SET) < 0) return -1L; - - s->in = s->out = offset; - return offset; - } - - /* For a negative seek, rewind and use positive seek */ - if (offset >= s->out) { - offset -= s->out; - } else if (gzrewind(file) < 0) { - return -1L; - } - /* offset is now the number of bytes to skip. */ - - if (offset != 0 && s->outbuf == Z_NULL) { - s->outbuf = (Byte*)ALLOC(Z_BUFSIZE); - if (s->outbuf == Z_NULL) return -1L; - } - if (offset && s->back != EOF) { - s->back = EOF; - s->out++; - offset--; - if (s->last) s->z_err = Z_STREAM_END; - } - while (offset > 0) { - int size = Z_BUFSIZE; - if (offset < Z_BUFSIZE) size = (int)offset; - - size = gzread(file, s->outbuf, (uInt)size); - if (size <= 0) return -1L; - offset -= size; - } - return s->out; -} - -/* =========================================================================== - Rewinds input file. -*/ -int ZEXPORT gzrewind (file) - gzFile file; -{ - gz_stream *s = (gz_stream*)file; - - if (s == NULL || s->mode != 'r') return -1; - - s->z_err = Z_OK; - s->z_eof = 0; - s->back = EOF; - s->stream.avail_in = 0; - s->stream.next_in = s->inbuf; - s->crc = crc32(0L, Z_NULL, 0); - if (!s->transparent) (void)inflateReset(&s->stream); - s->in = 0; - s->out = 0; - return fseek(s->file, s->start, SEEK_SET); -} - -/* =========================================================================== - Returns the starting position for the next gzread or gzwrite on the - given compressed file. This position represents a number of bytes in the - uncompressed data stream. -*/ -z_off_t ZEXPORT gztell (file) - gzFile file; -{ - return gzseek(file, 0L, SEEK_CUR); -} - -/* =========================================================================== - Returns 1 when EOF has previously been detected reading the given - input stream, otherwise zero. -*/ -int ZEXPORT gzeof (file) - gzFile file; -{ - gz_stream *s = (gz_stream*)file; - - /* With concatenated compressed files that can have embedded - * crc trailers, z_eof is no longer the only/best indicator of EOF - * on a gz_stream. Handle end-of-stream error explicitly here. - */ - if (s == NULL || s->mode != 'r') return 0; - if (s->z_eof) return 1; - return s->z_err == Z_STREAM_END; -} - -/* =========================================================================== - Returns 1 if reading and doing so transparently, otherwise zero. -*/ -int ZEXPORT gzdirect (file) - gzFile file; -{ - gz_stream *s = (gz_stream*)file; - - if (s == NULL || s->mode != 'r') return 0; - return s->transparent; -} - -/* =========================================================================== - Outputs a long in LSB order to the given file -*/ -local void putLong (file, x) - FILE *file; - uLong x; -{ - int n; - for (n = 0; n < 4; n++) { - fputc((int)(x & 0xff), file); - x >>= 8; - } -} - -/* =========================================================================== - Reads a long in LSB order from the given gz_stream. Sets z_err in case - of error. -*/ -local uLong getLong (s) - gz_stream *s; -{ - uLong x = (uLong)get_byte(s); - int c; - - x += ((uLong)get_byte(s))<<8; - x += ((uLong)get_byte(s))<<16; - c = get_byte(s); - if (c == EOF) s->z_err = Z_DATA_ERROR; - x += ((uLong)c)<<24; - return x; -} - -/* =========================================================================== - Flushes all pending output if necessary, closes the compressed file - and deallocates all the (de)compression state. -*/ -int Q_ZEXPORT gzclose (file) - gzFile file; -{ - gz_stream *s = (gz_stream*)file; - - if (s == NULL) return Z_STREAM_ERROR; - - if (s->mode == 'w') { -#ifdef NO_GZCOMPRESS - return Z_STREAM_ERROR; -#else - if (do_flush (file, Z_FINISH) != Z_OK) - return destroy((gz_stream*)file); - - putLong (s->file, s->crc); - putLong (s->file, (uLong)(s->in & 0xffffffff)); -#endif - } - return destroy((gz_stream*)file); -} - -#if defined(STDC) && !defined(_WIN32_WCE) -# define zstrerror(errnum) strerror(errnum) -#else -# define zstrerror(errnum) "" -#endif - -/* =========================================================================== - Returns the error message for the last error which occurred on the - given compressed file. errnum is set to zlib error number. If an - error occurred in the file system and not in the compression library, - errnum is set to Z_ERRNO and the application may consult errno - to get the exact error code. -*/ -const char * ZEXPORT gzerror (file, errnum) - gzFile file; - int *errnum; -{ - char *m; - gz_stream *s = (gz_stream*)file; - - if (s == NULL) { - *errnum = Z_STREAM_ERROR; - return (const char*)ERR_MSG(Z_STREAM_ERROR); - } - *errnum = s->z_err; - if (*errnum == Z_OK) return (const char*)""; - - m = (char*)(*errnum == Z_ERRNO ? zstrerror(errno) : s->stream.msg); - - if (m == NULL || *m == '\0') m = (char*)ERR_MSG(s->z_err); - - TRYFREE(s->msg); - s->msg = (char*)ALLOC(strlen(s->path) + strlen(m) + 3); - if (s->msg == Z_NULL) return (const char*)ERR_MSG(Z_MEM_ERROR); - strcpy(s->msg, s->path); - strcat(s->msg, ": "); - strcat(s->msg, m); - return (const char*)s->msg; -} - -/* =========================================================================== - Clear the error and end-of-file flags, and do the same for the real file. -*/ -void ZEXPORT gzclearerr (file) - gzFile file; -{ - gz_stream *s = (gz_stream*)file; - - if (s == NULL) return; - if (s->z_err != Z_STREAM_END) s->z_err = Z_OK; - s->z_eof = 0; - clearerr(s->file); -} +/* gzio.c -- IO on .gz files + * Copyright (C) 1995-2005 Jean-loup Gailly. + * For conditions of distribution and use, see copyright notice in zlib.h + * + * Compile this file with -DNO_GZCOMPRESS to avoid the compression code. + */ + +/* @(#) $Id$ */ + +#include + +#include "zutil.h" + +#ifdef NO_DEFLATE /* for compatibility with old definition */ +# define NO_GZCOMPRESS +#endif + +#ifndef NO_DUMMY_DECL +struct internal_state {int dummy;}; /* for buggy compilers */ +#endif + +#ifndef Z_BUFSIZE +# ifdef MAXSEG_64K +# define Z_BUFSIZE 4096 /* minimize memory usage for 16-bit DOS */ +# else +# define Z_BUFSIZE 16384 +# endif +#endif +#ifndef Z_PRINTF_BUFSIZE +# define Z_PRINTF_BUFSIZE 4096 +#endif + +#ifdef __MVS__ +# pragma map (fdopen , "\174\174FDOPEN") + FILE *fdopen(int, const char *); +#endif + +#ifndef STDC +extern voidp malloc OF((uInt size)); +extern void free OF((voidpf ptr)); +#endif + +#define ALLOC(size) malloc(size) +#define TRYFREE(p) {if (p) free(p);} + +static int const gz_magic[2] = {0x1f, 0x8b}; /* gzip magic header */ + +/* gzip flag byte */ +#define ASCII_FLAG 0x01 /* bit 0 set: file probably ascii text */ +#define HEAD_CRC 0x02 /* bit 1 set: header CRC present */ +#define EXTRA_FIELD 0x04 /* bit 2 set: extra field present */ +#define ORIG_NAME 0x08 /* bit 3 set: original file name present */ +#define COMMENT 0x10 /* bit 4 set: file comment present */ +#define RESERVED 0xE0 /* bits 5..7: reserved */ + +typedef struct gz_stream { + z_stream stream; + int z_err; /* error code for last stream operation */ + int z_eof; /* set if end of input file */ + FILE *file; /* .gz file */ + Byte *inbuf; /* input buffer */ + Byte *outbuf; /* output buffer */ + uLong crc; /* crc32 of uncompressed data */ + char *msg; /* error message */ + char *path; /* path name for debugging only */ + int transparent; /* 1 if input file is not a .gz file */ + char mode; /* 'w' or 'r' */ + z_off_t start; /* start of compressed data in file (header skipped) */ + z_off_t in; /* bytes into deflate or inflate */ + z_off_t out; /* bytes out of deflate or inflate */ + int back; /* one character push-back */ + int last; /* true if push-back is last character */ +} gz_stream; + + +local gzFile gz_open OF((const char *path, const char *mode, int fd)); +local int do_flush OF((gzFile file, int flush)); +local int get_byte OF((gz_stream *s)); +local void check_header OF((gz_stream *s)); +local int destroy OF((gz_stream *s)); +local void putLong OF((FILE *file, uLong x)); +local uLong getLong OF((gz_stream *s)); + +/* =========================================================================== + Opens a gzip (.gz) file for reading or writing. The mode parameter + is as in fopen ("rb" or "wb"). The file is given either by file descriptor + or path name (if fd == -1). + gz_open returns NULL if the file could not be opened or if there was + insufficient memory to allocate the (de)compression state; errno + can be checked to distinguish the two cases (if errno is zero, the + zlib error is Z_MEM_ERROR). +*/ +local gzFile gz_open (path, mode, fd) + const char *path; + const char *mode; + int fd; +{ + int err; + int level = Z_DEFAULT_COMPRESSION; /* compression level */ + int strategy = Z_DEFAULT_STRATEGY; /* compression strategy */ + char *p = (char*)mode; + gz_stream *s; + char fmode[80]; /* copy of mode, without the compression level */ + char *m = fmode; + + if (!path || !mode) return Z_NULL; + + s = (gz_stream *)ALLOC(sizeof(gz_stream)); + if (!s) return Z_NULL; + + s->stream.zalloc = (alloc_func)0; + s->stream.zfree = (free_func)0; + s->stream.opaque = (voidpf)0; + s->stream.next_in = s->inbuf = Z_NULL; + s->stream.next_out = s->outbuf = Z_NULL; + s->stream.avail_in = s->stream.avail_out = 0; + s->file = NULL; + s->z_err = Z_OK; + s->z_eof = 0; + s->in = 0; + s->out = 0; + s->back = EOF; + s->crc = crc32(0L, Z_NULL, 0); + s->msg = NULL; + s->transparent = 0; + + s->path = (char*)ALLOC(strlen(path)+1); + if (s->path == NULL) { + return destroy(s), (gzFile)Z_NULL; + } + strcpy(s->path, path); /* do this early for debugging */ + + s->mode = '\0'; + do { + if (*p == 'r') s->mode = 'r'; + if (*p == 'w' || *p == 'a') s->mode = 'w'; + if (*p >= '0' && *p <= '9') { + level = *p - '0'; + } else if (*p == 'f') { + strategy = Z_FILTERED; + } else if (*p == 'h') { + strategy = Z_HUFFMAN_ONLY; + } else if (*p == 'R') { + strategy = Z_RLE; + } else { + *m++ = *p; /* copy the mode */ + } + } while (*p++ && m != fmode + sizeof(fmode)); + if (s->mode == '\0') return destroy(s), (gzFile)Z_NULL; + + if (s->mode == 'w') { +#ifdef NO_GZCOMPRESS + err = Z_STREAM_ERROR; +#else + err = deflateInit2(&(s->stream), level, + Z_DEFLATED, -MAX_WBITS, DEF_MEM_LEVEL, strategy); + /* windowBits is passed < 0 to suppress zlib header */ + + s->stream.next_out = s->outbuf = (Byte*)ALLOC(Z_BUFSIZE); +#endif + if (err != Z_OK || s->outbuf == Z_NULL) { + return destroy(s), (gzFile)Z_NULL; + } + } else { + s->stream.next_in = s->inbuf = (Byte*)ALLOC(Z_BUFSIZE); + + err = inflateInit2(&(s->stream), -MAX_WBITS); + /* windowBits is passed < 0 to tell that there is no zlib header. + * Note that in this case inflate *requires* an extra "dummy" byte + * after the compressed stream in order to complete decompression and + * return Z_STREAM_END. Here the gzip CRC32 ensures that 4 bytes are + * present after the compressed stream. + */ + if (err != Z_OK || s->inbuf == Z_NULL) { + return destroy(s), (gzFile)Z_NULL; + } + } + s->stream.avail_out = Z_BUFSIZE; + + errno = 0; + s->file = fd < 0 ? F_OPEN(path, fmode) : (FILE*)fdopen(fd, fmode); + + if (s->file == NULL) { + return destroy(s), (gzFile)Z_NULL; + } + if (s->mode == 'w') { + /* Write a very simple .gz header: + */ + fprintf(s->file, "%c%c%c%c%c%c%c%c%c%c", gz_magic[0], gz_magic[1], + Z_DEFLATED, 0 /*flags*/, 0,0,0,0 /*time*/, 0 /*xflags*/, OS_CODE); + s->start = 10L; + /* We use 10L instead of ftell(s->file) to because ftell causes an + * fflush on some systems. This version of the library doesn't use + * start anyway in write mode, so this initialization is not + * necessary. + */ + } else { + check_header(s); /* skip the .gz header */ + s->start = ftell(s->file) - s->stream.avail_in; + } + + return (gzFile)s; +} + +/* =========================================================================== + Opens a gzip (.gz) file for reading or writing. +*/ +gzFile Q_ZEXPORT gzopen (path, mode) + const char *path; + const char *mode; +{ + return gz_open (path, mode, -1); +} + +/* =========================================================================== + Associate a gzFile with the file descriptor fd. fd is not dup'ed here + to mimic the behavio(u)r of fdopen. +*/ +gzFile ZEXPORT gzdopen (fd, mode) + int fd; + const char *mode; +{ + char name[46]; /* allow for up to 128-bit integers */ + + if (fd < 0) return (gzFile)Z_NULL; + sprintf(name, "", fd); /* for debugging */ + + return gz_open (name, mode, fd); +} + +/* =========================================================================== + * Update the compression level and strategy + */ +int ZEXPORT gzsetparams (file, level, strategy) + gzFile file; + int level; + int strategy; +{ + gz_stream *s = (gz_stream*)file; + + if (s == NULL || s->mode != 'w') return Z_STREAM_ERROR; + + /* Make room to allow flushing */ + if (s->stream.avail_out == 0) { + + s->stream.next_out = s->outbuf; + if (fwrite(s->outbuf, 1, Z_BUFSIZE, s->file) != Z_BUFSIZE) { + s->z_err = Z_ERRNO; + } + s->stream.avail_out = Z_BUFSIZE; + } + + return deflateParams (&(s->stream), level, strategy); +} + +/* =========================================================================== + Read a byte from a gz_stream; update next_in and avail_in. Return EOF + for end of file. + IN assertion: the stream s has been sucessfully opened for reading. +*/ +local int get_byte(s) + gz_stream *s; +{ + if (s->z_eof) return EOF; + if (s->stream.avail_in == 0) { + errno = 0; + s->stream.avail_in = (uInt)fread(s->inbuf, 1, Z_BUFSIZE, s->file); + if (s->stream.avail_in == 0) { + s->z_eof = 1; + if (ferror(s->file)) s->z_err = Z_ERRNO; + return EOF; + } + s->stream.next_in = s->inbuf; + } + s->stream.avail_in--; + return *(s->stream.next_in)++; +} + +/* =========================================================================== + Check the gzip header of a gz_stream opened for reading. Set the stream + mode to transparent if the gzip magic header is not present; set s->err + to Z_DATA_ERROR if the magic header is present but the rest of the header + is incorrect. + IN assertion: the stream s has already been created sucessfully; + s->stream.avail_in is zero for the first time, but may be non-zero + for concatenated .gz files. +*/ +local void check_header(s) + gz_stream *s; +{ + int method; /* method byte */ + int flags; /* flags byte */ + uInt len; + int c; + + /* Assure two bytes in the buffer so we can peek ahead -- handle case + where first byte of header is at the end of the buffer after the last + gzip segment */ + len = s->stream.avail_in; + if (len < 2) { + if (len) s->inbuf[0] = s->stream.next_in[0]; + errno = 0; + len = (uInt)fread(s->inbuf + len, 1, Z_BUFSIZE >> len, s->file); + if (len == 0 && ferror(s->file)) s->z_err = Z_ERRNO; + s->stream.avail_in += len; + s->stream.next_in = s->inbuf; + if (s->stream.avail_in < 2) { + s->transparent = s->stream.avail_in; + return; + } + } + + /* Peek ahead to check the gzip magic header */ + if (s->stream.next_in[0] != gz_magic[0] || + s->stream.next_in[1] != gz_magic[1]) { + s->transparent = 1; + return; + } + s->stream.avail_in -= 2; + s->stream.next_in += 2; + + /* Check the rest of the gzip header */ + method = get_byte(s); + flags = get_byte(s); + if (method != Z_DEFLATED || (flags & RESERVED) != 0) { + s->z_err = Z_DATA_ERROR; + return; + } + + /* Discard time, xflags and OS code: */ + for (len = 0; len < 6; len++) (void)get_byte(s); + + if ((flags & EXTRA_FIELD) != 0) { /* skip the extra field */ + len = (uInt)get_byte(s); + len += ((uInt)get_byte(s))<<8; + /* len is garbage if EOF but the loop below will quit anyway */ + while (len-- != 0 && get_byte(s) != EOF) ; + } + if ((flags & ORIG_NAME) != 0) { /* skip the original file name */ + while ((c = get_byte(s)) != 0 && c != EOF) ; + } + if ((flags & COMMENT) != 0) { /* skip the .gz file comment */ + while ((c = get_byte(s)) != 0 && c != EOF) ; + } + if ((flags & HEAD_CRC) != 0) { /* skip the header crc */ + for (len = 0; len < 2; len++) (void)get_byte(s); + } + s->z_err = s->z_eof ? Z_DATA_ERROR : Z_OK; +} + + /* =========================================================================== + * Cleanup then free the given gz_stream. Return a zlib error code. + Try freeing in the reverse order of allocations. + */ +local int destroy (s) + gz_stream *s; +{ + int err = Z_OK; + + if (!s) return Z_STREAM_ERROR; + + TRYFREE(s->msg); + + if (s->stream.state != NULL) { + if (s->mode == 'w') { +#ifdef NO_GZCOMPRESS + err = Z_STREAM_ERROR; +#else + err = deflateEnd(&(s->stream)); +#endif + } else if (s->mode == 'r') { + err = inflateEnd(&(s->stream)); + } + } + if (s->file != NULL && fclose(s->file)) { +#ifdef ESPIPE + if (errno != ESPIPE) /* fclose is broken for pipes in HP/UX */ +#endif + err = Z_ERRNO; + } + if (s->z_err < 0) err = s->z_err; + + TRYFREE(s->inbuf); + TRYFREE(s->outbuf); + TRYFREE(s->path); + TRYFREE(s); + return err; +} + +/* =========================================================================== + Reads the given number of uncompressed bytes from the compressed file. + gzread returns the number of bytes actually read (0 for end of file). +*/ +int Q_ZEXPORT gzread (file, buf, len) + gzFile file; + voidp buf; + unsigned len; +{ + gz_stream *s = (gz_stream*)file; + Bytef *start = (Bytef*)buf; /* starting point for crc computation */ + Byte *next_out; /* == stream.next_out but not forced far (for MSDOS) */ + + if (s == NULL || s->mode != 'r') return Z_STREAM_ERROR; + + if (s->z_err == Z_DATA_ERROR || s->z_err == Z_ERRNO) return -1; + if (s->z_err == Z_STREAM_END) return 0; /* EOF */ + + next_out = (Byte*)buf; + s->stream.next_out = (Bytef*)buf; + s->stream.avail_out = len; + + if (s->stream.avail_out && s->back != EOF) { + *next_out++ = s->back; + s->stream.next_out++; + s->stream.avail_out--; + s->back = EOF; + s->out++; + start++; + if (s->last) { + s->z_err = Z_STREAM_END; + return 1; + } + } + + while (s->stream.avail_out != 0) { + + if (s->transparent) { + /* Copy first the lookahead bytes: */ + uInt n = s->stream.avail_in; + if (n > s->stream.avail_out) n = s->stream.avail_out; + if (n > 0) { + zmemcpy(s->stream.next_out, s->stream.next_in, n); + next_out += n; + s->stream.next_out = next_out; + s->stream.next_in += n; + s->stream.avail_out -= n; + s->stream.avail_in -= n; + } + if (s->stream.avail_out > 0) { + s->stream.avail_out -= + (uInt)fread(next_out, 1, s->stream.avail_out, s->file); + } + len -= s->stream.avail_out; + s->in += len; + s->out += len; + if (len == 0) s->z_eof = 1; + return (int)len; + } + if (s->stream.avail_in == 0 && !s->z_eof) { + + errno = 0; + s->stream.avail_in = (uInt)fread(s->inbuf, 1, Z_BUFSIZE, s->file); + if (s->stream.avail_in == 0) { + s->z_eof = 1; + if (ferror(s->file)) { + s->z_err = Z_ERRNO; + break; + } + } + s->stream.next_in = s->inbuf; + } + s->in += s->stream.avail_in; + s->out += s->stream.avail_out; + s->z_err = inflate(&(s->stream), Z_NO_FLUSH); + s->in -= s->stream.avail_in; + s->out -= s->stream.avail_out; + + if (s->z_err == Z_STREAM_END) { + /* Check CRC and original size */ + s->crc = crc32(s->crc, start, (uInt)(s->stream.next_out - start)); + start = s->stream.next_out; + + if (getLong(s) != s->crc) { + s->z_err = Z_DATA_ERROR; + } else { + (void)getLong(s); + /* The uncompressed length returned by above getlong() may be + * different from s->out in case of concatenated .gz files. + * Check for such files: + */ + check_header(s); + if (s->z_err == Z_OK) { + inflateReset(&(s->stream)); + s->crc = crc32(0L, Z_NULL, 0); + } + } + } + if (s->z_err != Z_OK || s->z_eof) break; + } + s->crc = crc32(s->crc, start, (uInt)(s->stream.next_out - start)); + + if (len == s->stream.avail_out && + (s->z_err == Z_DATA_ERROR || s->z_err == Z_ERRNO)) + return -1; + return (int)(len - s->stream.avail_out); +} + + +/* =========================================================================== + Reads one byte from the compressed file. gzgetc returns this byte + or -1 in case of end of file or error. +*/ +int ZEXPORT gzgetc(file) + gzFile file; +{ + unsigned char c; + + return gzread(file, &c, 1) == 1 ? c : -1; +} + + +/* =========================================================================== + Push one byte back onto the stream. +*/ +int ZEXPORT gzungetc(c, file) + int c; + gzFile file; +{ + gz_stream *s = (gz_stream*)file; + + if (s == NULL || s->mode != 'r' || c == EOF || s->back != EOF) return EOF; + s->back = c; + s->out--; + s->last = (s->z_err == Z_STREAM_END); + if (s->last) s->z_err = Z_OK; + s->z_eof = 0; + return c; +} + + +/* =========================================================================== + Reads bytes from the compressed file until len-1 characters are + read, or a newline character is read and transferred to buf, or an + end-of-file condition is encountered. The string is then terminated + with a null character. + gzgets returns buf, or Z_NULL in case of error. + + The current implementation is not optimized at all. +*/ +char * ZEXPORT gzgets(file, buf, len) + gzFile file; + char *buf; + int len; +{ + char *b = buf; + if (buf == Z_NULL || len <= 0) return Z_NULL; + + while (--len > 0 && gzread(file, buf, 1) == 1 && *buf++ != '\n') ; + *buf = '\0'; + return b == buf && len > 0 ? Z_NULL : b; +} + + +#ifndef NO_GZCOMPRESS +/* =========================================================================== + Writes the given number of uncompressed bytes into the compressed file. + gzwrite returns the number of bytes actually written (0 in case of error). +*/ +int ZEXPORT gzwrite (file, buf, len) + gzFile file; + voidpc buf; + unsigned len; +{ + gz_stream *s = (gz_stream*)file; + + if (s == NULL || s->mode != 'w') return Z_STREAM_ERROR; + + s->stream.next_in = (Bytef*)buf; + s->stream.avail_in = len; + + while (s->stream.avail_in != 0) { + + if (s->stream.avail_out == 0) { + + s->stream.next_out = s->outbuf; + if (fwrite(s->outbuf, 1, Z_BUFSIZE, s->file) != Z_BUFSIZE) { + s->z_err = Z_ERRNO; + break; + } + s->stream.avail_out = Z_BUFSIZE; + } + s->in += s->stream.avail_in; + s->out += s->stream.avail_out; + s->z_err = deflate(&(s->stream), Z_NO_FLUSH); + s->in -= s->stream.avail_in; + s->out -= s->stream.avail_out; + if (s->z_err != Z_OK) break; + } + s->crc = crc32(s->crc, (const Bytef *)buf, len); + + return (int)(len - s->stream.avail_in); +} + + +/* =========================================================================== + Converts, formats, and writes the args to the compressed file under + control of the format string, as in fprintf. gzprintf returns the number of + uncompressed bytes actually written (0 in case of error). +*/ +#ifdef STDC +#include + +int Q_ZEXPORT gzprintf (gzFile file, const char *format, /* args */ ...) +{ + char buf[Z_PRINTF_BUFSIZE]; + va_list va; + int len; + + buf[sizeof(buf) - 1] = 0; + va_start(va, format); +#ifdef NO_vsnprintf +# ifdef HAS_vsprintf_void + (void)vsprintf(buf, format, va); + va_end(va); + for (len = 0; len < sizeof(buf); len++) + if (buf[len] == 0) break; +# else + len = vsprintf(buf, format, va); + va_end(va); +# endif +#else +# ifdef HAS_vsnprintf_void + (void)vsnprintf(buf, sizeof(buf), format, va); + va_end(va); + len = strlen(buf); +# else + len = vsnprintf(buf, sizeof(buf), format, va); + va_end(va); +# endif +#endif + if (len <= 0 || len >= (int)sizeof(buf) || buf[sizeof(buf) - 1] != 0) + return 0; + return gzwrite(file, buf, (unsigned)len); +} +#else /* not ANSI C */ + +int Q_ZEXPORT gzprintf (file, format, a1, a2, a3, a4, a5, a6, a7, a8, a9, a10, + a11, a12, a13, a14, a15, a16, a17, a18, a19, a20) + gzFile file; + const char *format; + int a1, a2, a3, a4, a5, a6, a7, a8, a9, a10, + a11, a12, a13, a14, a15, a16, a17, a18, a19, a20; +{ + char buf[Z_PRINTF_BUFSIZE]; + int len; + + buf[sizeof(buf) - 1] = 0; +#ifdef NO_snprintf +# ifdef HAS_sprintf_void + sprintf(buf, format, a1, a2, a3, a4, a5, a6, a7, a8, + a9, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a20); + for (len = 0; len < sizeof(buf); len++) + if (buf[len] == 0) break; +# else + len = sprintf(buf, format, a1, a2, a3, a4, a5, a6, a7, a8, + a9, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a20); +# endif +#else +# ifdef HAS_snprintf_void + snprintf(buf, sizeof(buf), format, a1, a2, a3, a4, a5, a6, a7, a8, + a9, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a20); + len = strlen(buf); +# else + len = snprintf(buf, sizeof(buf), format, a1, a2, a3, a4, a5, a6, a7, a8, + a9, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a20); +# endif +#endif + if (len <= 0 || len >= sizeof(buf) || buf[sizeof(buf) - 1] != 0) + return 0; + return gzwrite(file, buf, len); +} +#endif + +/* =========================================================================== + Writes c, converted to an unsigned char, into the compressed file. + gzputc returns the value that was written, or -1 in case of error. +*/ +int ZEXPORT gzputc(file, c) + gzFile file; + int c; +{ + unsigned char cc = (unsigned char) c; /* required for big endian systems */ + + return gzwrite(file, &cc, 1) == 1 ? (int)cc : -1; +} + + +/* =========================================================================== + Writes the given null-terminated string to the compressed file, excluding + the terminating null character. + gzputs returns the number of characters written, or -1 in case of error. +*/ +int ZEXPORT gzputs(file, s) + gzFile file; + const char *s; +{ + return gzwrite(file, (char*)s, (unsigned)strlen(s)); +} + + +/* =========================================================================== + Flushes all pending output into the compressed file. The parameter + flush is as in the deflate() function. +*/ +local int do_flush (file, flush) + gzFile file; + int flush; +{ + uInt len; + int done = 0; + gz_stream *s = (gz_stream*)file; + + if (s == NULL || s->mode != 'w') return Z_STREAM_ERROR; + + s->stream.avail_in = 0; /* should be zero already anyway */ + + for (;;) { + len = Z_BUFSIZE - s->stream.avail_out; + + if (len != 0) { + if ((uInt)fwrite(s->outbuf, 1, len, s->file) != len) { + s->z_err = Z_ERRNO; + return Z_ERRNO; + } + s->stream.next_out = s->outbuf; + s->stream.avail_out = Z_BUFSIZE; + } + if (done) break; + s->out += s->stream.avail_out; + s->z_err = deflate(&(s->stream), flush); + s->out -= s->stream.avail_out; + + /* Ignore the second of two consecutive flushes: */ + if (len == 0 && s->z_err == Z_BUF_ERROR) s->z_err = Z_OK; + + /* deflate has finished flushing only when it hasn't used up + * all the available space in the output buffer: + */ + done = (s->stream.avail_out != 0 || s->z_err == Z_STREAM_END); + + if (s->z_err != Z_OK && s->z_err != Z_STREAM_END) break; + } + return s->z_err == Z_STREAM_END ? Z_OK : s->z_err; +} + +int ZEXPORT gzflush (file, flush) + gzFile file; + int flush; +{ + gz_stream *s = (gz_stream*)file; + int err = do_flush (file, flush); + + if (err) return err; + fflush(s->file); + return s->z_err == Z_STREAM_END ? Z_OK : s->z_err; +} +#endif /* NO_GZCOMPRESS */ + +/* =========================================================================== + Sets the starting position for the next gzread or gzwrite on the given + compressed file. The offset represents a number of bytes in the + gzseek returns the resulting offset location as measured in bytes from + the beginning of the uncompressed stream, or -1 in case of error. + SEEK_END is not implemented, returns error. + In this version of the library, gzseek can be extremely slow. +*/ +z_off_t ZEXPORT gzseek (file, offset, whence) + gzFile file; + z_off_t offset; + int whence; +{ + gz_stream *s = (gz_stream*)file; + + if (s == NULL || whence == SEEK_END || + s->z_err == Z_ERRNO || s->z_err == Z_DATA_ERROR) { + return -1L; + } + + if (s->mode == 'w') { +#ifdef NO_GZCOMPRESS + return -1L; +#else + if (whence == SEEK_SET) { + offset -= s->in; + } + if (offset < 0) return -1L; + + /* At this point, offset is the number of zero bytes to write. */ + if (s->inbuf == Z_NULL) { + s->inbuf = (Byte*)ALLOC(Z_BUFSIZE); /* for seeking */ + if (s->inbuf == Z_NULL) return -1L; + zmemzero(s->inbuf, Z_BUFSIZE); + } + while (offset > 0) { + uInt size = Z_BUFSIZE; + if (offset < Z_BUFSIZE) size = (uInt)offset; + + size = gzwrite(file, s->inbuf, size); + if (size == 0) return -1L; + + offset -= size; + } + return s->in; +#endif + } + /* Rest of function is for reading only */ + + /* compute absolute position */ + if (whence == SEEK_CUR) { + offset += s->out; + } + if (offset < 0) return -1L; + + if (s->transparent) { + /* map to fseek */ + s->back = EOF; + s->stream.avail_in = 0; + s->stream.next_in = s->inbuf; + if (fseek(s->file, offset, SEEK_SET) < 0) return -1L; + + s->in = s->out = offset; + return offset; + } + + /* For a negative seek, rewind and use positive seek */ + if (offset >= s->out) { + offset -= s->out; + } else if (gzrewind(file) < 0) { + return -1L; + } + /* offset is now the number of bytes to skip. */ + + if (offset != 0 && s->outbuf == Z_NULL) { + s->outbuf = (Byte*)ALLOC(Z_BUFSIZE); + if (s->outbuf == Z_NULL) return -1L; + } + if (offset && s->back != EOF) { + s->back = EOF; + s->out++; + offset--; + if (s->last) s->z_err = Z_STREAM_END; + } + while (offset > 0) { + int size = Z_BUFSIZE; + if (offset < Z_BUFSIZE) size = (int)offset; + + size = gzread(file, s->outbuf, (uInt)size); + if (size <= 0) return -1L; + offset -= size; + } + return s->out; +} + +/* =========================================================================== + Rewinds input file. +*/ +int ZEXPORT gzrewind (file) + gzFile file; +{ + gz_stream *s = (gz_stream*)file; + + if (s == NULL || s->mode != 'r') return -1; + + s->z_err = Z_OK; + s->z_eof = 0; + s->back = EOF; + s->stream.avail_in = 0; + s->stream.next_in = s->inbuf; + s->crc = crc32(0L, Z_NULL, 0); + if (!s->transparent) (void)inflateReset(&s->stream); + s->in = 0; + s->out = 0; + return fseek(s->file, s->start, SEEK_SET); +} + +/* =========================================================================== + Returns the starting position for the next gzread or gzwrite on the + given compressed file. This position represents a number of bytes in the + uncompressed data stream. +*/ +z_off_t ZEXPORT gztell (file) + gzFile file; +{ + return gzseek(file, 0L, SEEK_CUR); +} + +/* =========================================================================== + Returns 1 when EOF has previously been detected reading the given + input stream, otherwise zero. +*/ +int ZEXPORT gzeof (file) + gzFile file; +{ + gz_stream *s = (gz_stream*)file; + + /* With concatenated compressed files that can have embedded + * crc trailers, z_eof is no longer the only/best indicator of EOF + * on a gz_stream. Handle end-of-stream error explicitly here. + */ + if (s == NULL || s->mode != 'r') return 0; + if (s->z_eof) return 1; + return s->z_err == Z_STREAM_END; +} + +/* =========================================================================== + Returns 1 if reading and doing so transparently, otherwise zero. +*/ +int ZEXPORT gzdirect (file) + gzFile file; +{ + gz_stream *s = (gz_stream*)file; + + if (s == NULL || s->mode != 'r') return 0; + return s->transparent; +} + +/* =========================================================================== + Outputs a long in LSB order to the given file +*/ +local void putLong (file, x) + FILE *file; + uLong x; +{ + int n; + for (n = 0; n < 4; n++) { + fputc((int)(x & 0xff), file); + x >>= 8; + } +} + +/* =========================================================================== + Reads a long in LSB order from the given gz_stream. Sets z_err in case + of error. +*/ +local uLong getLong (s) + gz_stream *s; +{ + uLong x = (uLong)get_byte(s); + int c; + + x += ((uLong)get_byte(s))<<8; + x += ((uLong)get_byte(s))<<16; + c = get_byte(s); + if (c == EOF) s->z_err = Z_DATA_ERROR; + x += ((uLong)c)<<24; + return x; +} + +/* =========================================================================== + Flushes all pending output if necessary, closes the compressed file + and deallocates all the (de)compression state. +*/ +int Q_ZEXPORT gzclose (file) + gzFile file; +{ + gz_stream *s = (gz_stream*)file; + + if (s == NULL) return Z_STREAM_ERROR; + + if (s->mode == 'w') { +#ifdef NO_GZCOMPRESS + return Z_STREAM_ERROR; +#else + if (do_flush (file, Z_FINISH) != Z_OK) + return destroy((gz_stream*)file); + + putLong (s->file, s->crc); + putLong (s->file, (uLong)(s->in & 0xffffffff)); +#endif + } + return destroy((gz_stream*)file); +} + +#if defined(STDC) && !defined(_WIN32_WCE) +# define zstrerror(errnum) strerror(errnum) +#else +# define zstrerror(errnum) "" +#endif + +/* =========================================================================== + Returns the error message for the last error which occurred on the + given compressed file. errnum is set to zlib error number. If an + error occurred in the file system and not in the compression library, + errnum is set to Z_ERRNO and the application may consult errno + to get the exact error code. +*/ +const char * ZEXPORT gzerror (file, errnum) + gzFile file; + int *errnum; +{ + char *m; + gz_stream *s = (gz_stream*)file; + + if (s == NULL) { + *errnum = Z_STREAM_ERROR; + return (const char*)ERR_MSG(Z_STREAM_ERROR); + } + *errnum = s->z_err; + if (*errnum == Z_OK) return (const char*)""; + + m = (char*)(*errnum == Z_ERRNO ? zstrerror(errno) : s->stream.msg); + + if (m == NULL || *m == '\0') m = (char*)ERR_MSG(s->z_err); + + TRYFREE(s->msg); + s->msg = (char*)ALLOC(strlen(s->path) + strlen(m) + 3); + if (s->msg == Z_NULL) return (const char*)ERR_MSG(Z_MEM_ERROR); + strcpy(s->msg, s->path); + strcat(s->msg, ": "); + strcat(s->msg, m); + return (const char*)s->msg; +} + +/* =========================================================================== + Clear the error and end-of-file flags, and do the same for the real file. +*/ +void ZEXPORT gzclearerr (file) + gzFile file; +{ + gz_stream *s = (gz_stream*)file; + + if (s == NULL) return; + if (s->z_err != Z_STREAM_END) s->z_err = Z_OK; + s->z_eof = 0; + clearerr(s->file); +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/infback.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/infback.c index 1e03e1bab..455dbc9ee 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/infback.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/infback.c @@ -1,623 +1,623 @@ -/* infback.c -- inflate using a call-back interface - * Copyright (C) 1995-2005 Mark Adler - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* - This code is largely copied from inflate.c. Normally either infback.o or - inflate.o would be linked into an application--not both. The interface - with inffast.c is retained so that optimized assembler-coded versions of - inflate_fast() can be used with either inflate.c or infback.c. - */ - -#include "zutil.h" -#include "inftrees.h" -#include "inflate.h" -#include "inffast.h" - -/* function prototypes */ -local void fixedtables OF((struct inflate_state FAR *state)); - -/* - strm provides memory allocation functions in zalloc and zfree, or - Z_NULL to use the library memory allocation functions. - - windowBits is in the range 8..15, and window is a user-supplied - window and output buffer that is 2**windowBits bytes. - */ -int ZEXPORT inflateBackInit_(strm, windowBits, window, version, stream_size) -z_streamp strm; -int windowBits; -unsigned char FAR *window; -const char *version; -int stream_size; -{ - struct inflate_state FAR *state; - - if (version == Z_NULL || version[0] != ZLIB_VERSION[0] || - stream_size != (int)(sizeof(z_stream))) - return Z_VERSION_ERROR; - if (strm == Z_NULL || window == Z_NULL || - windowBits < 8 || windowBits > 15) - return Z_STREAM_ERROR; - strm->msg = Z_NULL; /* in case we return an error */ - if (strm->zalloc == (alloc_func)0) { - strm->zalloc = zcalloc; - strm->opaque = (voidpf)0; - } - if (strm->zfree == (free_func)0) strm->zfree = zcfree; - state = (struct inflate_state FAR *)ZALLOC(strm, 1, - sizeof(struct inflate_state)); - if (state == Z_NULL) return Z_MEM_ERROR; - Tracev((stderr, "inflate: allocated\n")); - strm->state = (struct internal_state FAR *)state; - state->dmax = 32768U; - state->wbits = windowBits; - state->wsize = 1U << windowBits; - state->window = window; - state->write = 0; - state->whave = 0; - return Z_OK; -} - -/* - Return state with length and distance decoding tables and index sizes set to - fixed code decoding. Normally this returns fixed tables from inffixed.h. - If BUILDFIXED is defined, then instead this routine builds the tables the - first time it's called, and returns those tables the first time and - thereafter. This reduces the size of the code by about 2K bytes, in - exchange for a little execution time. However, BUILDFIXED should not be - used for threaded applications, since the rewriting of the tables and virgin - may not be thread-safe. - */ -local void fixedtables(state) -struct inflate_state FAR *state; -{ -#ifdef BUILDFIXED - static int virgin = 1; - static code *lenfix, *distfix; - static code fixed[544]; - - /* build fixed huffman tables if first call (may not be thread safe) */ - if (virgin) { - unsigned sym, bits; - static code *next; - - /* literal/length table */ - sym = 0; - while (sym < 144) state->lens[sym++] = 8; - while (sym < 256) state->lens[sym++] = 9; - while (sym < 280) state->lens[sym++] = 7; - while (sym < 288) state->lens[sym++] = 8; - next = fixed; - lenfix = next; - bits = 9; - inflate_table(LENS, state->lens, 288, &(next), &(bits), state->work); - - /* distance table */ - sym = 0; - while (sym < 32) state->lens[sym++] = 5; - distfix = next; - bits = 5; - inflate_table(DISTS, state->lens, 32, &(next), &(bits), state->work); - - /* do this just once */ - virgin = 0; - } -#else /* !BUILDFIXED */ -# include "inffixed.h" -#endif /* BUILDFIXED */ - state->lencode = lenfix; - state->lenbits = 9; - state->distcode = distfix; - state->distbits = 5; -} - -/* Macros for inflateBack(): */ - -/* Load returned state from inflate_fast() */ -#define LOAD() \ - do { \ - put = strm->next_out; \ - left = strm->avail_out; \ - next = strm->next_in; \ - have = strm->avail_in; \ - hold = state->hold; \ - bits = state->bits; \ - } while (0) - -/* Set state from registers for inflate_fast() */ -#define RESTORE() \ - do { \ - strm->next_out = put; \ - strm->avail_out = left; \ - strm->next_in = next; \ - strm->avail_in = have; \ - state->hold = hold; \ - state->bits = bits; \ - } while (0) - -/* Clear the input bit accumulator */ -#define INITBITS() \ - do { \ - hold = 0; \ - bits = 0; \ - } while (0) - -/* Assure that some input is available. If input is requested, but denied, - then return a Z_BUF_ERROR from inflateBack(). */ -#define PULL() \ - do { \ - if (have == 0) { \ - have = in(in_desc, &next); \ - if (have == 0) { \ - next = Z_NULL; \ - ret = Z_BUF_ERROR; \ - goto inf_leave; \ - } \ - } \ - } while (0) - -/* Get a byte of input into the bit accumulator, or return from inflateBack() - with an error if there is no input available. */ -#define PULLBYTE() \ - do { \ - PULL(); \ - have--; \ - hold += (unsigned long)(*next++) << bits; \ - bits += 8; \ - } while (0) - -/* Assure that there are at least n bits in the bit accumulator. If there is - not enough available input to do that, then return from inflateBack() with - an error. */ -#define NEEDBITS(n) \ - do { \ - while (bits < (unsigned)(n)) \ - PULLBYTE(); \ - } while (0) - -/* Return the low n bits of the bit accumulator (n < 16) */ -#define BITS(n) \ - ((unsigned)hold & ((1U << (n)) - 1)) - -/* Remove n bits from the bit accumulator */ -#define DROPBITS(n) \ - do { \ - hold >>= (n); \ - bits -= (unsigned)(n); \ - } while (0) - -/* Remove zero to seven bits as needed to go to a byte boundary */ -#define BYTEBITS() \ - do { \ - hold >>= bits & 7; \ - bits -= bits & 7; \ - } while (0) - -/* Assure that some output space is available, by writing out the window - if it's full. If the write fails, return from inflateBack() with a - Z_BUF_ERROR. */ -#define ROOM() \ - do { \ - if (left == 0) { \ - put = state->window; \ - left = state->wsize; \ - state->whave = left; \ - if (out(out_desc, put, left)) { \ - ret = Z_BUF_ERROR; \ - goto inf_leave; \ - } \ - } \ - } while (0) - -/* - strm provides the memory allocation functions and window buffer on input, - and provides information on the unused input on return. For Z_DATA_ERROR - returns, strm will also provide an error message. - - in() and out() are the call-back input and output functions. When - inflateBack() needs more input, it calls in(). When inflateBack() has - filled the window with output, or when it completes with data in the - window, it calls out() to write out the data. The application must not - change the provided input until in() is called again or inflateBack() - returns. The application must not change the window/output buffer until - inflateBack() returns. - - in() and out() are called with a descriptor parameter provided in the - inflateBack() call. This parameter can be a structure that provides the - information required to do the read or write, as well as accumulated - information on the input and output such as totals and check values. - - in() should return zero on failure. out() should return non-zero on - failure. If either in() or out() fails, than inflateBack() returns a - Z_BUF_ERROR. strm->next_in can be checked for Z_NULL to see whether it - was in() or out() that caused in the error. Otherwise, inflateBack() - returns Z_STREAM_END on success, Z_DATA_ERROR for an deflate format - error, or Z_MEM_ERROR if it could not allocate memory for the state. - inflateBack() can also return Z_STREAM_ERROR if the input parameters - are not correct, i.e. strm is Z_NULL or the state was not initialized. - */ -int ZEXPORT inflateBack(strm, in, in_desc, out, out_desc) -z_streamp strm; -in_func in; -void FAR *in_desc; -out_func out; -void FAR *out_desc; -{ - struct inflate_state FAR *state; - unsigned char FAR *next; /* next input */ - unsigned char FAR *put; /* next output */ - unsigned have, left; /* available input and output */ - unsigned long hold; /* bit buffer */ - unsigned bits; /* bits in bit buffer */ - unsigned copy; /* number of stored or match bytes to copy */ - unsigned char FAR *from; /* where to copy match bytes from */ - code this; /* current decoding table entry */ - code last; /* parent table entry */ - unsigned len; /* length to copy for repeats, bits to drop */ - int ret; /* return code */ - static const unsigned short order[19] = /* permutation of code lengths */ - {16, 17, 18, 0, 8, 7, 9, 6, 10, 5, 11, 4, 12, 3, 13, 2, 14, 1, 15}; - - /* Check that the strm exists and that the state was initialized */ - if (strm == Z_NULL || strm->state == Z_NULL) - return Z_STREAM_ERROR; - state = (struct inflate_state FAR *)strm->state; - - /* Reset the state */ - strm->msg = Z_NULL; - state->mode = TYPE; - state->last = 0; - state->whave = 0; - next = strm->next_in; - have = next != Z_NULL ? strm->avail_in : 0; - hold = 0; - bits = 0; - put = state->window; - left = state->wsize; - - /* Inflate until end of block marked as last */ - for (;;) - switch (state->mode) { - case TYPE: - /* determine and dispatch block type */ - if (state->last) { - BYTEBITS(); - state->mode = DONE; - break; - } - NEEDBITS(3); - state->last = BITS(1); - DROPBITS(1); - switch (BITS(2)) { - case 0: /* stored block */ - Tracev((stderr, "inflate: stored block%s\n", - state->last ? " (last)" : "")); - state->mode = STORED; - break; - case 1: /* fixed block */ - fixedtables(state); - Tracev((stderr, "inflate: fixed codes block%s\n", - state->last ? " (last)" : "")); - state->mode = LEN; /* decode codes */ - break; - case 2: /* dynamic block */ - Tracev((stderr, "inflate: dynamic codes block%s\n", - state->last ? " (last)" : "")); - state->mode = TABLE; - break; - case 3: - strm->msg = (char *)"invalid block type"; - state->mode = BAD; - } - DROPBITS(2); - break; - - case STORED: - /* get and verify stored block length */ - BYTEBITS(); /* go to byte boundary */ - NEEDBITS(32); - if ((hold & 0xffff) != ((hold >> 16) ^ 0xffff)) { - strm->msg = (char *)"invalid stored block lengths"; - state->mode = BAD; - break; - } - state->length = (unsigned)hold & 0xffff; - Tracev((stderr, "inflate: stored length %u\n", - state->length)); - INITBITS(); - - /* copy stored block from input to output */ - while (state->length != 0) { - copy = state->length; - PULL(); - ROOM(); - if (copy > have) copy = have; - if (copy > left) copy = left; - zmemcpy(put, next, copy); - have -= copy; - next += copy; - left -= copy; - put += copy; - state->length -= copy; - } - Tracev((stderr, "inflate: stored end\n")); - state->mode = TYPE; - break; - - case TABLE: - /* get dynamic table entries descriptor */ - NEEDBITS(14); - state->nlen = BITS(5) + 257; - DROPBITS(5); - state->ndist = BITS(5) + 1; - DROPBITS(5); - state->ncode = BITS(4) + 4; - DROPBITS(4); -#ifndef PKZIP_BUG_WORKAROUND - if (state->nlen > 286 || state->ndist > 30) { - strm->msg = (char *)"too many length or distance symbols"; - state->mode = BAD; - break; - } -#endif - Tracev((stderr, "inflate: table sizes ok\n")); - - /* get code length code lengths (not a typo) */ - state->have = 0; - while (state->have < state->ncode) { - NEEDBITS(3); - state->lens[order[state->have++]] = (unsigned short)BITS(3); - DROPBITS(3); - } - while (state->have < 19) - state->lens[order[state->have++]] = 0; - state->next = state->codes; - state->lencode = (code const FAR *)(state->next); - state->lenbits = 7; - ret = inflate_table(CODES, state->lens, 19, &(state->next), - &(state->lenbits), state->work); - if (ret) { - strm->msg = (char *)"invalid code lengths set"; - state->mode = BAD; - break; - } - Tracev((stderr, "inflate: code lengths ok\n")); - - /* get length and distance code code lengths */ - state->have = 0; - while (state->have < state->nlen + state->ndist) { - for (;;) { - this = state->lencode[BITS(state->lenbits)]; - if ((unsigned)(this.bits) <= bits) break; - PULLBYTE(); - } - if (this.val < 16) { - NEEDBITS(this.bits); - DROPBITS(this.bits); - state->lens[state->have++] = this.val; - } - else { - if (this.val == 16) { - NEEDBITS(this.bits + 2); - DROPBITS(this.bits); - if (state->have == 0) { - strm->msg = (char *)"invalid bit length repeat"; - state->mode = BAD; - break; - } - len = (unsigned)(state->lens[state->have - 1]); - copy = 3 + BITS(2); - DROPBITS(2); - } - else if (this.val == 17) { - NEEDBITS(this.bits + 3); - DROPBITS(this.bits); - len = 0; - copy = 3 + BITS(3); - DROPBITS(3); - } - else { - NEEDBITS(this.bits + 7); - DROPBITS(this.bits); - len = 0; - copy = 11 + BITS(7); - DROPBITS(7); - } - if (state->have + copy > state->nlen + state->ndist) { - strm->msg = (char *)"invalid bit length repeat"; - state->mode = BAD; - break; - } - while (copy--) - state->lens[state->have++] = (unsigned short)len; - } - } - - /* handle error breaks in while */ - if (state->mode == BAD) break; - - /* build code tables */ - state->next = state->codes; - state->lencode = (code const FAR *)(state->next); - state->lenbits = 9; - ret = inflate_table(LENS, state->lens, state->nlen, &(state->next), - &(state->lenbits), state->work); - if (ret) { - strm->msg = (char *)"invalid literal/lengths set"; - state->mode = BAD; - break; - } - state->distcode = (code const FAR *)(state->next); - state->distbits = 6; - ret = inflate_table(DISTS, state->lens + state->nlen, state->ndist, - &(state->next), &(state->distbits), state->work); - if (ret) { - strm->msg = (char *)"invalid distances set"; - state->mode = BAD; - break; - } - Tracev((stderr, "inflate: codes ok\n")); - state->mode = LEN; - - case LEN: - /* use inflate_fast() if we have enough input and output */ - if (have >= 6 && left >= 258) { - RESTORE(); - if (state->whave < state->wsize) - state->whave = state->wsize - left; - inflate_fast(strm, state->wsize); - LOAD(); - break; - } - - /* get a literal, length, or end-of-block code */ - for (;;) { - this = state->lencode[BITS(state->lenbits)]; - if ((unsigned)(this.bits) <= bits) break; - PULLBYTE(); - } - if (this.op && (this.op & 0xf0) == 0) { - last = this; - for (;;) { - this = state->lencode[last.val + - (BITS(last.bits + last.op) >> last.bits)]; - if ((unsigned)(last.bits + this.bits) <= bits) break; - PULLBYTE(); - } - DROPBITS(last.bits); - } - DROPBITS(this.bits); - state->length = (unsigned)this.val; - - /* process literal */ - if (this.op == 0) { - Tracevv((stderr, this.val >= 0x20 && this.val < 0x7f ? - "inflate: literal '%c'\n" : - "inflate: literal 0x%02x\n", this.val)); - ROOM(); - *put++ = (unsigned char)(state->length); - left--; - state->mode = LEN; - break; - } - - /* process end of block */ - if (this.op & 32) { - Tracevv((stderr, "inflate: end of block\n")); - state->mode = TYPE; - break; - } - - /* invalid code */ - if (this.op & 64) { - strm->msg = (char *)"invalid literal/length code"; - state->mode = BAD; - break; - } - - /* length code -- get extra bits, if any */ - state->extra = (unsigned)(this.op) & 15; - if (state->extra != 0) { - NEEDBITS(state->extra); - state->length += BITS(state->extra); - DROPBITS(state->extra); - } - Tracevv((stderr, "inflate: length %u\n", state->length)); - - /* get distance code */ - for (;;) { - this = state->distcode[BITS(state->distbits)]; - if ((unsigned)(this.bits) <= bits) break; - PULLBYTE(); - } - if ((this.op & 0xf0) == 0) { - last = this; - for (;;) { - this = state->distcode[last.val + - (BITS(last.bits + last.op) >> last.bits)]; - if ((unsigned)(last.bits + this.bits) <= bits) break; - PULLBYTE(); - } - DROPBITS(last.bits); - } - DROPBITS(this.bits); - if (this.op & 64) { - strm->msg = (char *)"invalid distance code"; - state->mode = BAD; - break; - } - state->offset = (unsigned)this.val; - - /* get distance extra bits, if any */ - state->extra = (unsigned)(this.op) & 15; - if (state->extra != 0) { - NEEDBITS(state->extra); - state->offset += BITS(state->extra); - DROPBITS(state->extra); - } - if (state->offset > state->wsize - (state->whave < state->wsize ? - left : 0)) { - strm->msg = (char *)"invalid distance too far back"; - state->mode = BAD; - break; - } - Tracevv((stderr, "inflate: distance %u\n", state->offset)); - - /* copy match from window to output */ - do { - ROOM(); - copy = state->wsize - state->offset; - if (copy < left) { - from = put + copy; - copy = left - copy; - } - else { - from = put - state->offset; - copy = left; - } - if (copy > state->length) copy = state->length; - state->length -= copy; - left -= copy; - do { - *put++ = *from++; - } while (--copy); - } while (state->length != 0); - break; - - case DONE: - /* inflate stream terminated properly -- write leftover output */ - ret = Z_STREAM_END; - if (left < state->wsize) { - if (out(out_desc, state->window, state->wsize - left)) - ret = Z_BUF_ERROR; - } - goto inf_leave; - - case BAD: - ret = Z_DATA_ERROR; - goto inf_leave; - - default: /* can't happen, but makes compilers happy */ - ret = Z_STREAM_ERROR; - goto inf_leave; - } - - /* Return unused input */ - inf_leave: - strm->next_in = next; - strm->avail_in = have; - return ret; -} - -int ZEXPORT inflateBackEnd(strm) -z_streamp strm; -{ - if (strm == Z_NULL || strm->state == Z_NULL || strm->zfree == (free_func)0) - return Z_STREAM_ERROR; - ZFREE(strm, strm->state); - strm->state = Z_NULL; - Tracev((stderr, "inflate: end\n")); - return Z_OK; -} +/* infback.c -- inflate using a call-back interface + * Copyright (C) 1995-2005 Mark Adler + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* + This code is largely copied from inflate.c. Normally either infback.o or + inflate.o would be linked into an application--not both. The interface + with inffast.c is retained so that optimized assembler-coded versions of + inflate_fast() can be used with either inflate.c or infback.c. + */ + +#include "zutil.h" +#include "inftrees.h" +#include "inflate.h" +#include "inffast.h" + +/* function prototypes */ +local void fixedtables OF((struct inflate_state FAR *state)); + +/* + strm provides memory allocation functions in zalloc and zfree, or + Z_NULL to use the library memory allocation functions. + + windowBits is in the range 8..15, and window is a user-supplied + window and output buffer that is 2**windowBits bytes. + */ +int ZEXPORT inflateBackInit_(strm, windowBits, window, version, stream_size) +z_streamp strm; +int windowBits; +unsigned char FAR *window; +const char *version; +int stream_size; +{ + struct inflate_state FAR *state; + + if (version == Z_NULL || version[0] != ZLIB_VERSION[0] || + stream_size != (int)(sizeof(z_stream))) + return Z_VERSION_ERROR; + if (strm == Z_NULL || window == Z_NULL || + windowBits < 8 || windowBits > 15) + return Z_STREAM_ERROR; + strm->msg = Z_NULL; /* in case we return an error */ + if (strm->zalloc == (alloc_func)0) { + strm->zalloc = zcalloc; + strm->opaque = (voidpf)0; + } + if (strm->zfree == (free_func)0) strm->zfree = zcfree; + state = (struct inflate_state FAR *)ZALLOC(strm, 1, + sizeof(struct inflate_state)); + if (state == Z_NULL) return Z_MEM_ERROR; + Tracev((stderr, "inflate: allocated\n")); + strm->state = (struct internal_state FAR *)state; + state->dmax = 32768U; + state->wbits = windowBits; + state->wsize = 1U << windowBits; + state->window = window; + state->write = 0; + state->whave = 0; + return Z_OK; +} + +/* + Return state with length and distance decoding tables and index sizes set to + fixed code decoding. Normally this returns fixed tables from inffixed.h. + If BUILDFIXED is defined, then instead this routine builds the tables the + first time it's called, and returns those tables the first time and + thereafter. This reduces the size of the code by about 2K bytes, in + exchange for a little execution time. However, BUILDFIXED should not be + used for threaded applications, since the rewriting of the tables and virgin + may not be thread-safe. + */ +local void fixedtables(state) +struct inflate_state FAR *state; +{ +#ifdef BUILDFIXED + static int virgin = 1; + static code *lenfix, *distfix; + static code fixed[544]; + + /* build fixed huffman tables if first call (may not be thread safe) */ + if (virgin) { + unsigned sym, bits; + static code *next; + + /* literal/length table */ + sym = 0; + while (sym < 144) state->lens[sym++] = 8; + while (sym < 256) state->lens[sym++] = 9; + while (sym < 280) state->lens[sym++] = 7; + while (sym < 288) state->lens[sym++] = 8; + next = fixed; + lenfix = next; + bits = 9; + inflate_table(LENS, state->lens, 288, &(next), &(bits), state->work); + + /* distance table */ + sym = 0; + while (sym < 32) state->lens[sym++] = 5; + distfix = next; + bits = 5; + inflate_table(DISTS, state->lens, 32, &(next), &(bits), state->work); + + /* do this just once */ + virgin = 0; + } +#else /* !BUILDFIXED */ +# include "inffixed.h" +#endif /* BUILDFIXED */ + state->lencode = lenfix; + state->lenbits = 9; + state->distcode = distfix; + state->distbits = 5; +} + +/* Macros for inflateBack(): */ + +/* Load returned state from inflate_fast() */ +#define LOAD() \ + do { \ + put = strm->next_out; \ + left = strm->avail_out; \ + next = strm->next_in; \ + have = strm->avail_in; \ + hold = state->hold; \ + bits = state->bits; \ + } while (0) + +/* Set state from registers for inflate_fast() */ +#define RESTORE() \ + do { \ + strm->next_out = put; \ + strm->avail_out = left; \ + strm->next_in = next; \ + strm->avail_in = have; \ + state->hold = hold; \ + state->bits = bits; \ + } while (0) + +/* Clear the input bit accumulator */ +#define INITBITS() \ + do { \ + hold = 0; \ + bits = 0; \ + } while (0) + +/* Assure that some input is available. If input is requested, but denied, + then return a Z_BUF_ERROR from inflateBack(). */ +#define PULL() \ + do { \ + if (have == 0) { \ + have = in(in_desc, &next); \ + if (have == 0) { \ + next = Z_NULL; \ + ret = Z_BUF_ERROR; \ + goto inf_leave; \ + } \ + } \ + } while (0) + +/* Get a byte of input into the bit accumulator, or return from inflateBack() + with an error if there is no input available. */ +#define PULLBYTE() \ + do { \ + PULL(); \ + have--; \ + hold += (unsigned long)(*next++) << bits; \ + bits += 8; \ + } while (0) + +/* Assure that there are at least n bits in the bit accumulator. If there is + not enough available input to do that, then return from inflateBack() with + an error. */ +#define NEEDBITS(n) \ + do { \ + while (bits < (unsigned)(n)) \ + PULLBYTE(); \ + } while (0) + +/* Return the low n bits of the bit accumulator (n < 16) */ +#define BITS(n) \ + ((unsigned)hold & ((1U << (n)) - 1)) + +/* Remove n bits from the bit accumulator */ +#define DROPBITS(n) \ + do { \ + hold >>= (n); \ + bits -= (unsigned)(n); \ + } while (0) + +/* Remove zero to seven bits as needed to go to a byte boundary */ +#define BYTEBITS() \ + do { \ + hold >>= bits & 7; \ + bits -= bits & 7; \ + } while (0) + +/* Assure that some output space is available, by writing out the window + if it's full. If the write fails, return from inflateBack() with a + Z_BUF_ERROR. */ +#define ROOM() \ + do { \ + if (left == 0) { \ + put = state->window; \ + left = state->wsize; \ + state->whave = left; \ + if (out(out_desc, put, left)) { \ + ret = Z_BUF_ERROR; \ + goto inf_leave; \ + } \ + } \ + } while (0) + +/* + strm provides the memory allocation functions and window buffer on input, + and provides information on the unused input on return. For Z_DATA_ERROR + returns, strm will also provide an error message. + + in() and out() are the call-back input and output functions. When + inflateBack() needs more input, it calls in(). When inflateBack() has + filled the window with output, or when it completes with data in the + window, it calls out() to write out the data. The application must not + change the provided input until in() is called again or inflateBack() + returns. The application must not change the window/output buffer until + inflateBack() returns. + + in() and out() are called with a descriptor parameter provided in the + inflateBack() call. This parameter can be a structure that provides the + information required to do the read or write, as well as accumulated + information on the input and output such as totals and check values. + + in() should return zero on failure. out() should return non-zero on + failure. If either in() or out() fails, than inflateBack() returns a + Z_BUF_ERROR. strm->next_in can be checked for Z_NULL to see whether it + was in() or out() that caused in the error. Otherwise, inflateBack() + returns Z_STREAM_END on success, Z_DATA_ERROR for an deflate format + error, or Z_MEM_ERROR if it could not allocate memory for the state. + inflateBack() can also return Z_STREAM_ERROR if the input parameters + are not correct, i.e. strm is Z_NULL or the state was not initialized. + */ +int ZEXPORT inflateBack(strm, in, in_desc, out, out_desc) +z_streamp strm; +in_func in; +void FAR *in_desc; +out_func out; +void FAR *out_desc; +{ + struct inflate_state FAR *state; + unsigned char FAR *next; /* next input */ + unsigned char FAR *put; /* next output */ + unsigned have, left; /* available input and output */ + unsigned long hold; /* bit buffer */ + unsigned bits; /* bits in bit buffer */ + unsigned copy; /* number of stored or match bytes to copy */ + unsigned char FAR *from; /* where to copy match bytes from */ + code this; /* current decoding table entry */ + code last; /* parent table entry */ + unsigned len; /* length to copy for repeats, bits to drop */ + int ret; /* return code */ + static const unsigned short order[19] = /* permutation of code lengths */ + {16, 17, 18, 0, 8, 7, 9, 6, 10, 5, 11, 4, 12, 3, 13, 2, 14, 1, 15}; + + /* Check that the strm exists and that the state was initialized */ + if (strm == Z_NULL || strm->state == Z_NULL) + return Z_STREAM_ERROR; + state = (struct inflate_state FAR *)strm->state; + + /* Reset the state */ + strm->msg = Z_NULL; + state->mode = TYPE; + state->last = 0; + state->whave = 0; + next = strm->next_in; + have = next != Z_NULL ? strm->avail_in : 0; + hold = 0; + bits = 0; + put = state->window; + left = state->wsize; + + /* Inflate until end of block marked as last */ + for (;;) + switch (state->mode) { + case TYPE: + /* determine and dispatch block type */ + if (state->last) { + BYTEBITS(); + state->mode = DONE; + break; + } + NEEDBITS(3); + state->last = BITS(1); + DROPBITS(1); + switch (BITS(2)) { + case 0: /* stored block */ + Tracev((stderr, "inflate: stored block%s\n", + state->last ? " (last)" : "")); + state->mode = STORED; + break; + case 1: /* fixed block */ + fixedtables(state); + Tracev((stderr, "inflate: fixed codes block%s\n", + state->last ? " (last)" : "")); + state->mode = LEN; /* decode codes */ + break; + case 2: /* dynamic block */ + Tracev((stderr, "inflate: dynamic codes block%s\n", + state->last ? " (last)" : "")); + state->mode = TABLE; + break; + case 3: + strm->msg = (char *)"invalid block type"; + state->mode = BAD; + } + DROPBITS(2); + break; + + case STORED: + /* get and verify stored block length */ + BYTEBITS(); /* go to byte boundary */ + NEEDBITS(32); + if ((hold & 0xffff) != ((hold >> 16) ^ 0xffff)) { + strm->msg = (char *)"invalid stored block lengths"; + state->mode = BAD; + break; + } + state->length = (unsigned)hold & 0xffff; + Tracev((stderr, "inflate: stored length %u\n", + state->length)); + INITBITS(); + + /* copy stored block from input to output */ + while (state->length != 0) { + copy = state->length; + PULL(); + ROOM(); + if (copy > have) copy = have; + if (copy > left) copy = left; + zmemcpy(put, next, copy); + have -= copy; + next += copy; + left -= copy; + put += copy; + state->length -= copy; + } + Tracev((stderr, "inflate: stored end\n")); + state->mode = TYPE; + break; + + case TABLE: + /* get dynamic table entries descriptor */ + NEEDBITS(14); + state->nlen = BITS(5) + 257; + DROPBITS(5); + state->ndist = BITS(5) + 1; + DROPBITS(5); + state->ncode = BITS(4) + 4; + DROPBITS(4); +#ifndef PKZIP_BUG_WORKAROUND + if (state->nlen > 286 || state->ndist > 30) { + strm->msg = (char *)"too many length or distance symbols"; + state->mode = BAD; + break; + } +#endif + Tracev((stderr, "inflate: table sizes ok\n")); + + /* get code length code lengths (not a typo) */ + state->have = 0; + while (state->have < state->ncode) { + NEEDBITS(3); + state->lens[order[state->have++]] = (unsigned short)BITS(3); + DROPBITS(3); + } + while (state->have < 19) + state->lens[order[state->have++]] = 0; + state->next = state->codes; + state->lencode = (code const FAR *)(state->next); + state->lenbits = 7; + ret = inflate_table(CODES, state->lens, 19, &(state->next), + &(state->lenbits), state->work); + if (ret) { + strm->msg = (char *)"invalid code lengths set"; + state->mode = BAD; + break; + } + Tracev((stderr, "inflate: code lengths ok\n")); + + /* get length and distance code code lengths */ + state->have = 0; + while (state->have < state->nlen + state->ndist) { + for (;;) { + this = state->lencode[BITS(state->lenbits)]; + if ((unsigned)(this.bits) <= bits) break; + PULLBYTE(); + } + if (this.val < 16) { + NEEDBITS(this.bits); + DROPBITS(this.bits); + state->lens[state->have++] = this.val; + } + else { + if (this.val == 16) { + NEEDBITS(this.bits + 2); + DROPBITS(this.bits); + if (state->have == 0) { + strm->msg = (char *)"invalid bit length repeat"; + state->mode = BAD; + break; + } + len = (unsigned)(state->lens[state->have - 1]); + copy = 3 + BITS(2); + DROPBITS(2); + } + else if (this.val == 17) { + NEEDBITS(this.bits + 3); + DROPBITS(this.bits); + len = 0; + copy = 3 + BITS(3); + DROPBITS(3); + } + else { + NEEDBITS(this.bits + 7); + DROPBITS(this.bits); + len = 0; + copy = 11 + BITS(7); + DROPBITS(7); + } + if (state->have + copy > state->nlen + state->ndist) { + strm->msg = (char *)"invalid bit length repeat"; + state->mode = BAD; + break; + } + while (copy--) + state->lens[state->have++] = (unsigned short)len; + } + } + + /* handle error breaks in while */ + if (state->mode == BAD) break; + + /* build code tables */ + state->next = state->codes; + state->lencode = (code const FAR *)(state->next); + state->lenbits = 9; + ret = inflate_table(LENS, state->lens, state->nlen, &(state->next), + &(state->lenbits), state->work); + if (ret) { + strm->msg = (char *)"invalid literal/lengths set"; + state->mode = BAD; + break; + } + state->distcode = (code const FAR *)(state->next); + state->distbits = 6; + ret = inflate_table(DISTS, state->lens + state->nlen, state->ndist, + &(state->next), &(state->distbits), state->work); + if (ret) { + strm->msg = (char *)"invalid distances set"; + state->mode = BAD; + break; + } + Tracev((stderr, "inflate: codes ok\n")); + state->mode = LEN; + + case LEN: + /* use inflate_fast() if we have enough input and output */ + if (have >= 6 && left >= 258) { + RESTORE(); + if (state->whave < state->wsize) + state->whave = state->wsize - left; + inflate_fast(strm, state->wsize); + LOAD(); + break; + } + + /* get a literal, length, or end-of-block code */ + for (;;) { + this = state->lencode[BITS(state->lenbits)]; + if ((unsigned)(this.bits) <= bits) break; + PULLBYTE(); + } + if (this.op && (this.op & 0xf0) == 0) { + last = this; + for (;;) { + this = state->lencode[last.val + + (BITS(last.bits + last.op) >> last.bits)]; + if ((unsigned)(last.bits + this.bits) <= bits) break; + PULLBYTE(); + } + DROPBITS(last.bits); + } + DROPBITS(this.bits); + state->length = (unsigned)this.val; + + /* process literal */ + if (this.op == 0) { + Tracevv((stderr, this.val >= 0x20 && this.val < 0x7f ? + "inflate: literal '%c'\n" : + "inflate: literal 0x%02x\n", this.val)); + ROOM(); + *put++ = (unsigned char)(state->length); + left--; + state->mode = LEN; + break; + } + + /* process end of block */ + if (this.op & 32) { + Tracevv((stderr, "inflate: end of block\n")); + state->mode = TYPE; + break; + } + + /* invalid code */ + if (this.op & 64) { + strm->msg = (char *)"invalid literal/length code"; + state->mode = BAD; + break; + } + + /* length code -- get extra bits, if any */ + state->extra = (unsigned)(this.op) & 15; + if (state->extra != 0) { + NEEDBITS(state->extra); + state->length += BITS(state->extra); + DROPBITS(state->extra); + } + Tracevv((stderr, "inflate: length %u\n", state->length)); + + /* get distance code */ + for (;;) { + this = state->distcode[BITS(state->distbits)]; + if ((unsigned)(this.bits) <= bits) break; + PULLBYTE(); + } + if ((this.op & 0xf0) == 0) { + last = this; + for (;;) { + this = state->distcode[last.val + + (BITS(last.bits + last.op) >> last.bits)]; + if ((unsigned)(last.bits + this.bits) <= bits) break; + PULLBYTE(); + } + DROPBITS(last.bits); + } + DROPBITS(this.bits); + if (this.op & 64) { + strm->msg = (char *)"invalid distance code"; + state->mode = BAD; + break; + } + state->offset = (unsigned)this.val; + + /* get distance extra bits, if any */ + state->extra = (unsigned)(this.op) & 15; + if (state->extra != 0) { + NEEDBITS(state->extra); + state->offset += BITS(state->extra); + DROPBITS(state->extra); + } + if (state->offset > state->wsize - (state->whave < state->wsize ? + left : 0)) { + strm->msg = (char *)"invalid distance too far back"; + state->mode = BAD; + break; + } + Tracevv((stderr, "inflate: distance %u\n", state->offset)); + + /* copy match from window to output */ + do { + ROOM(); + copy = state->wsize - state->offset; + if (copy < left) { + from = put + copy; + copy = left - copy; + } + else { + from = put - state->offset; + copy = left; + } + if (copy > state->length) copy = state->length; + state->length -= copy; + left -= copy; + do { + *put++ = *from++; + } while (--copy); + } while (state->length != 0); + break; + + case DONE: + /* inflate stream terminated properly -- write leftover output */ + ret = Z_STREAM_END; + if (left < state->wsize) { + if (out(out_desc, state->window, state->wsize - left)) + ret = Z_BUF_ERROR; + } + goto inf_leave; + + case BAD: + ret = Z_DATA_ERROR; + goto inf_leave; + + default: /* can't happen, but makes compilers happy */ + ret = Z_STREAM_ERROR; + goto inf_leave; + } + + /* Return unused input */ + inf_leave: + strm->next_in = next; + strm->avail_in = have; + return ret; +} + +int ZEXPORT inflateBackEnd(strm) +z_streamp strm; +{ + if (strm == Z_NULL || strm->state == Z_NULL || strm->zfree == (free_func)0) + return Z_STREAM_ERROR; + ZFREE(strm, strm->state); + strm->state = Z_NULL; + Tracev((stderr, "inflate: end\n")); + return Z_OK; +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffast.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffast.c index fa31cad90..bbee92ed1 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffast.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffast.c @@ -1,318 +1,318 @@ -/* inffast.c -- fast decoding - * Copyright (C) 1995-2004 Mark Adler - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -#include "zutil.h" -#include "inftrees.h" -#include "inflate.h" -#include "inffast.h" - -#ifndef ASMINF - -/* Allow machine dependent optimization for post-increment or pre-increment. - Based on testing to date, - Pre-increment preferred for: - - PowerPC G3 (Adler) - - MIPS R5000 (Randers-Pehrson) - Post-increment preferred for: - - none - No measurable difference: - - Pentium III (Anderson) - - M68060 (Nikl) - */ -#ifdef POSTINC -# define OFF 0 -# define PUP(a) *(a)++ -#else -# define OFF 1 -# define PUP(a) *++(a) -#endif - -/* - Decode literal, length, and distance codes and write out the resulting - literal and match bytes until either not enough input or output is - available, an end-of-block is encountered, or a data error is encountered. - When large enough input and output buffers are supplied to inflate(), for - example, a 16K input buffer and a 64K output buffer, more than 95% of the - inflate execution time is spent in this routine. - - Entry assumptions: - - state->mode == LEN - strm->avail_in >= 6 - strm->avail_out >= 258 - start >= strm->avail_out - state->bits < 8 - - On return, state->mode is one of: - - LEN -- ran out of enough output space or enough available input - TYPE -- reached end of block code, inflate() to interpret next block - BAD -- error in block data - - Notes: - - - The maximum input bits used by a length/distance pair is 15 bits for the - length code, 5 bits for the length extra, 15 bits for the distance code, - and 13 bits for the distance extra. This totals 48 bits, or six bytes. - Therefore if strm->avail_in >= 6, then there is enough input to avoid - checking for available input while decoding. - - - The maximum bytes that a single length/distance pair can output is 258 - bytes, which is the maximum length that can be coded. inflate_fast() - requires strm->avail_out >= 258 for each loop to avoid checking for - output space. - */ -void inflate_fast(strm, start) -z_streamp strm; -unsigned start; /* inflate()'s starting value for strm->avail_out */ -{ - struct inflate_state FAR *state; - unsigned char FAR *in; /* local strm->next_in */ - unsigned char FAR *last; /* while in < last, enough input available */ - unsigned char FAR *out; /* local strm->next_out */ - unsigned char FAR *beg; /* inflate()'s initial strm->next_out */ - unsigned char FAR *end; /* while out < end, enough space available */ -#ifdef INFLATE_STRICT - unsigned dmax; /* maximum distance from zlib header */ -#endif - unsigned wsize; /* window size or zero if not using window */ - unsigned whave; /* valid bytes in the window */ - unsigned write; /* window write index */ - unsigned char FAR *window; /* allocated sliding window, if wsize != 0 */ - unsigned long hold; /* local strm->hold */ - unsigned bits; /* local strm->bits */ - code const FAR *lcode; /* local strm->lencode */ - code const FAR *dcode; /* local strm->distcode */ - unsigned lmask; /* mask for first level of length codes */ - unsigned dmask; /* mask for first level of distance codes */ - code this; /* retrieved table entry */ - unsigned op; /* code bits, operation, extra bits, or */ - /* window position, window bytes to copy */ - unsigned len; /* match length, unused bytes */ - unsigned dist; /* match distance */ - unsigned char FAR *from; /* where to copy match from */ - - /* copy state to local variables */ - state = (struct inflate_state FAR *)strm->state; - in = strm->next_in - OFF; - last = in + (strm->avail_in - 5); - out = strm->next_out - OFF; - beg = out - (start - strm->avail_out); - end = out + (strm->avail_out - 257); -#ifdef INFLATE_STRICT - dmax = state->dmax; -#endif - wsize = state->wsize; - whave = state->whave; - write = state->write; - window = state->window; - hold = state->hold; - bits = state->bits; - lcode = state->lencode; - dcode = state->distcode; - lmask = (1U << state->lenbits) - 1; - dmask = (1U << state->distbits) - 1; - - /* decode literals and length/distances until end-of-block or not enough - input data or output space */ - do { - if (bits < 15) { - hold += (unsigned long)(PUP(in)) << bits; - bits += 8; - hold += (unsigned long)(PUP(in)) << bits; - bits += 8; - } - this = lcode[hold & lmask]; - dolen: - op = (unsigned)(this.bits); - hold >>= op; - bits -= op; - op = (unsigned)(this.op); - if (op == 0) { /* literal */ - Tracevv((stderr, this.val >= 0x20 && this.val < 0x7f ? - "inflate: literal '%c'\n" : - "inflate: literal 0x%02x\n", this.val)); - PUP(out) = (unsigned char)(this.val); - } - else if (op & 16) { /* length base */ - len = (unsigned)(this.val); - op &= 15; /* number of extra bits */ - if (op) { - if (bits < op) { - hold += (unsigned long)(PUP(in)) << bits; - bits += 8; - } - len += (unsigned)hold & ((1U << op) - 1); - hold >>= op; - bits -= op; - } - Tracevv((stderr, "inflate: length %u\n", len)); - if (bits < 15) { - hold += (unsigned long)(PUP(in)) << bits; - bits += 8; - hold += (unsigned long)(PUP(in)) << bits; - bits += 8; - } - this = dcode[hold & dmask]; - dodist: - op = (unsigned)(this.bits); - hold >>= op; - bits -= op; - op = (unsigned)(this.op); - if (op & 16) { /* distance base */ - dist = (unsigned)(this.val); - op &= 15; /* number of extra bits */ - if (bits < op) { - hold += (unsigned long)(PUP(in)) << bits; - bits += 8; - if (bits < op) { - hold += (unsigned long)(PUP(in)) << bits; - bits += 8; - } - } - dist += (unsigned)hold & ((1U << op) - 1); -#ifdef INFLATE_STRICT - if (dist > dmax) { - strm->msg = (char *)"invalid distance too far back"; - state->mode = BAD; - break; - } -#endif - hold >>= op; - bits -= op; - Tracevv((stderr, "inflate: distance %u\n", dist)); - op = (unsigned)(out - beg); /* max distance in output */ - if (dist > op) { /* see if copy from window */ - op = dist - op; /* distance back in window */ - if (op > whave) { - strm->msg = (char *)"invalid distance too far back"; - state->mode = BAD; - break; - } - from = window - OFF; - if (write == 0) { /* very common case */ - from += wsize - op; - if (op < len) { /* some from window */ - len -= op; - do { - PUP(out) = PUP(from); - } while (--op); - from = out - dist; /* rest from output */ - } - } - else if (write < op) { /* wrap around window */ - from += wsize + write - op; - op -= write; - if (op < len) { /* some from end of window */ - len -= op; - do { - PUP(out) = PUP(from); - } while (--op); - from = window - OFF; - if (write < len) { /* some from start of window */ - op = write; - len -= op; - do { - PUP(out) = PUP(from); - } while (--op); - from = out - dist; /* rest from output */ - } - } - } - else { /* contiguous in window */ - from += write - op; - if (op < len) { /* some from window */ - len -= op; - do { - PUP(out) = PUP(from); - } while (--op); - from = out - dist; /* rest from output */ - } - } - while (len > 2) { - PUP(out) = PUP(from); - PUP(out) = PUP(from); - PUP(out) = PUP(from); - len -= 3; - } - if (len) { - PUP(out) = PUP(from); - if (len > 1) - PUP(out) = PUP(from); - } - } - else { - from = out - dist; /* copy direct from output */ - do { /* minimum length is three */ - PUP(out) = PUP(from); - PUP(out) = PUP(from); - PUP(out) = PUP(from); - len -= 3; - } while (len > 2); - if (len) { - PUP(out) = PUP(from); - if (len > 1) - PUP(out) = PUP(from); - } - } - } - else if ((op & 64) == 0) { /* 2nd level distance code */ - this = dcode[this.val + (hold & ((1U << op) - 1))]; - goto dodist; - } - else { - strm->msg = (char *)"invalid distance code"; - state->mode = BAD; - break; - } - } - else if ((op & 64) == 0) { /* 2nd level length code */ - this = lcode[this.val + (hold & ((1U << op) - 1))]; - goto dolen; - } - else if (op & 32) { /* end-of-block */ - Tracevv((stderr, "inflate: end of block\n")); - state->mode = TYPE; - break; - } - else { - strm->msg = (char *)"invalid literal/length code"; - state->mode = BAD; - break; - } - } while (in < last && out < end); - - /* return unused bytes (on entry, bits < 8, so in won't go too far back) */ - len = bits >> 3; - in -= len; - bits -= len << 3; - hold &= (1U << bits) - 1; - - /* update state and return */ - strm->next_in = in + OFF; - strm->next_out = out + OFF; - strm->avail_in = (unsigned)(in < last ? 5 + (last - in) : 5 - (in - last)); - strm->avail_out = (unsigned)(out < end ? - 257 + (end - out) : 257 - (out - end)); - state->hold = hold; - state->bits = bits; - return; -} - -/* - inflate_fast() speedups that turned out slower (on a PowerPC G3 750CXe): - - Using bit fields for code structure - - Different op definition to avoid & for extra bits (do & for table bits) - - Three separate decoding do-loops for direct, window, and write == 0 - - Special case for distance > 1 copies to do overlapped load and store copy - - Explicit branch predictions (based on measured branch probabilities) - - Deferring match copy and interspersed it with decoding subsequent codes - - Swapping literal/length else - - Swapping window/direct else - - Larger unrolled copy loops (three is about right) - - Moving len -= 3 statement into middle of loop - */ - -#endif /* !ASMINF */ +/* inffast.c -- fast decoding + * Copyright (C) 1995-2004 Mark Adler + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +#include "zutil.h" +#include "inftrees.h" +#include "inflate.h" +#include "inffast.h" + +#ifndef ASMINF + +/* Allow machine dependent optimization for post-increment or pre-increment. + Based on testing to date, + Pre-increment preferred for: + - PowerPC G3 (Adler) + - MIPS R5000 (Randers-Pehrson) + Post-increment preferred for: + - none + No measurable difference: + - Pentium III (Anderson) + - M68060 (Nikl) + */ +#ifdef POSTINC +# define OFF 0 +# define PUP(a) *(a)++ +#else +# define OFF 1 +# define PUP(a) *++(a) +#endif + +/* + Decode literal, length, and distance codes and write out the resulting + literal and match bytes until either not enough input or output is + available, an end-of-block is encountered, or a data error is encountered. + When large enough input and output buffers are supplied to inflate(), for + example, a 16K input buffer and a 64K output buffer, more than 95% of the + inflate execution time is spent in this routine. + + Entry assumptions: + + state->mode == LEN + strm->avail_in >= 6 + strm->avail_out >= 258 + start >= strm->avail_out + state->bits < 8 + + On return, state->mode is one of: + + LEN -- ran out of enough output space or enough available input + TYPE -- reached end of block code, inflate() to interpret next block + BAD -- error in block data + + Notes: + + - The maximum input bits used by a length/distance pair is 15 bits for the + length code, 5 bits for the length extra, 15 bits for the distance code, + and 13 bits for the distance extra. This totals 48 bits, or six bytes. + Therefore if strm->avail_in >= 6, then there is enough input to avoid + checking for available input while decoding. + + - The maximum bytes that a single length/distance pair can output is 258 + bytes, which is the maximum length that can be coded. inflate_fast() + requires strm->avail_out >= 258 for each loop to avoid checking for + output space. + */ +void inflate_fast(strm, start) +z_streamp strm; +unsigned start; /* inflate()'s starting value for strm->avail_out */ +{ + struct inflate_state FAR *state; + unsigned char FAR *in; /* local strm->next_in */ + unsigned char FAR *last; /* while in < last, enough input available */ + unsigned char FAR *out; /* local strm->next_out */ + unsigned char FAR *beg; /* inflate()'s initial strm->next_out */ + unsigned char FAR *end; /* while out < end, enough space available */ +#ifdef INFLATE_STRICT + unsigned dmax; /* maximum distance from zlib header */ +#endif + unsigned wsize; /* window size or zero if not using window */ + unsigned whave; /* valid bytes in the window */ + unsigned write; /* window write index */ + unsigned char FAR *window; /* allocated sliding window, if wsize != 0 */ + unsigned long hold; /* local strm->hold */ + unsigned bits; /* local strm->bits */ + code const FAR *lcode; /* local strm->lencode */ + code const FAR *dcode; /* local strm->distcode */ + unsigned lmask; /* mask for first level of length codes */ + unsigned dmask; /* mask for first level of distance codes */ + code this; /* retrieved table entry */ + unsigned op; /* code bits, operation, extra bits, or */ + /* window position, window bytes to copy */ + unsigned len; /* match length, unused bytes */ + unsigned dist; /* match distance */ + unsigned char FAR *from; /* where to copy match from */ + + /* copy state to local variables */ + state = (struct inflate_state FAR *)strm->state; + in = strm->next_in - OFF; + last = in + (strm->avail_in - 5); + out = strm->next_out - OFF; + beg = out - (start - strm->avail_out); + end = out + (strm->avail_out - 257); +#ifdef INFLATE_STRICT + dmax = state->dmax; +#endif + wsize = state->wsize; + whave = state->whave; + write = state->write; + window = state->window; + hold = state->hold; + bits = state->bits; + lcode = state->lencode; + dcode = state->distcode; + lmask = (1U << state->lenbits) - 1; + dmask = (1U << state->distbits) - 1; + + /* decode literals and length/distances until end-of-block or not enough + input data or output space */ + do { + if (bits < 15) { + hold += (unsigned long)(PUP(in)) << bits; + bits += 8; + hold += (unsigned long)(PUP(in)) << bits; + bits += 8; + } + this = lcode[hold & lmask]; + dolen: + op = (unsigned)(this.bits); + hold >>= op; + bits -= op; + op = (unsigned)(this.op); + if (op == 0) { /* literal */ + Tracevv((stderr, this.val >= 0x20 && this.val < 0x7f ? + "inflate: literal '%c'\n" : + "inflate: literal 0x%02x\n", this.val)); + PUP(out) = (unsigned char)(this.val); + } + else if (op & 16) { /* length base */ + len = (unsigned)(this.val); + op &= 15; /* number of extra bits */ + if (op) { + if (bits < op) { + hold += (unsigned long)(PUP(in)) << bits; + bits += 8; + } + len += (unsigned)hold & ((1U << op) - 1); + hold >>= op; + bits -= op; + } + Tracevv((stderr, "inflate: length %u\n", len)); + if (bits < 15) { + hold += (unsigned long)(PUP(in)) << bits; + bits += 8; + hold += (unsigned long)(PUP(in)) << bits; + bits += 8; + } + this = dcode[hold & dmask]; + dodist: + op = (unsigned)(this.bits); + hold >>= op; + bits -= op; + op = (unsigned)(this.op); + if (op & 16) { /* distance base */ + dist = (unsigned)(this.val); + op &= 15; /* number of extra bits */ + if (bits < op) { + hold += (unsigned long)(PUP(in)) << bits; + bits += 8; + if (bits < op) { + hold += (unsigned long)(PUP(in)) << bits; + bits += 8; + } + } + dist += (unsigned)hold & ((1U << op) - 1); +#ifdef INFLATE_STRICT + if (dist > dmax) { + strm->msg = (char *)"invalid distance too far back"; + state->mode = BAD; + break; + } +#endif + hold >>= op; + bits -= op; + Tracevv((stderr, "inflate: distance %u\n", dist)); + op = (unsigned)(out - beg); /* max distance in output */ + if (dist > op) { /* see if copy from window */ + op = dist - op; /* distance back in window */ + if (op > whave) { + strm->msg = (char *)"invalid distance too far back"; + state->mode = BAD; + break; + } + from = window - OFF; + if (write == 0) { /* very common case */ + from += wsize - op; + if (op < len) { /* some from window */ + len -= op; + do { + PUP(out) = PUP(from); + } while (--op); + from = out - dist; /* rest from output */ + } + } + else if (write < op) { /* wrap around window */ + from += wsize + write - op; + op -= write; + if (op < len) { /* some from end of window */ + len -= op; + do { + PUP(out) = PUP(from); + } while (--op); + from = window - OFF; + if (write < len) { /* some from start of window */ + op = write; + len -= op; + do { + PUP(out) = PUP(from); + } while (--op); + from = out - dist; /* rest from output */ + } + } + } + else { /* contiguous in window */ + from += write - op; + if (op < len) { /* some from window */ + len -= op; + do { + PUP(out) = PUP(from); + } while (--op); + from = out - dist; /* rest from output */ + } + } + while (len > 2) { + PUP(out) = PUP(from); + PUP(out) = PUP(from); + PUP(out) = PUP(from); + len -= 3; + } + if (len) { + PUP(out) = PUP(from); + if (len > 1) + PUP(out) = PUP(from); + } + } + else { + from = out - dist; /* copy direct from output */ + do { /* minimum length is three */ + PUP(out) = PUP(from); + PUP(out) = PUP(from); + PUP(out) = PUP(from); + len -= 3; + } while (len > 2); + if (len) { + PUP(out) = PUP(from); + if (len > 1) + PUP(out) = PUP(from); + } + } + } + else if ((op & 64) == 0) { /* 2nd level distance code */ + this = dcode[this.val + (hold & ((1U << op) - 1))]; + goto dodist; + } + else { + strm->msg = (char *)"invalid distance code"; + state->mode = BAD; + break; + } + } + else if ((op & 64) == 0) { /* 2nd level length code */ + this = lcode[this.val + (hold & ((1U << op) - 1))]; + goto dolen; + } + else if (op & 32) { /* end-of-block */ + Tracevv((stderr, "inflate: end of block\n")); + state->mode = TYPE; + break; + } + else { + strm->msg = (char *)"invalid literal/length code"; + state->mode = BAD; + break; + } + } while (in < last && out < end); + + /* return unused bytes (on entry, bits < 8, so in won't go too far back) */ + len = bits >> 3; + in -= len; + bits -= len << 3; + hold &= (1U << bits) - 1; + + /* update state and return */ + strm->next_in = in + OFF; + strm->next_out = out + OFF; + strm->avail_in = (unsigned)(in < last ? 5 + (last - in) : 5 - (in - last)); + strm->avail_out = (unsigned)(out < end ? + 257 + (end - out) : 257 - (out - end)); + state->hold = hold; + state->bits = bits; + return; +} + +/* + inflate_fast() speedups that turned out slower (on a PowerPC G3 750CXe): + - Using bit fields for code structure + - Different op definition to avoid & for extra bits (do & for table bits) + - Three separate decoding do-loops for direct, window, and write == 0 + - Special case for distance > 1 copies to do overlapped load and store copy + - Explicit branch predictions (based on measured branch probabilities) + - Deferring match copy and interspersed it with decoding subsequent codes + - Swapping literal/length else + - Swapping window/direct else + - Larger unrolled copy loops (three is about right) + - Moving len -= 3 statement into middle of loop + */ + +#endif /* !ASMINF */ diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffast.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffast.h index 614fa7877..1e88d2d97 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffast.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffast.h @@ -1,11 +1,11 @@ -/* inffast.h -- header to use inffast.c - * Copyright (C) 1995-2003 Mark Adler - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* WARNING: this file should *not* be used by applications. It is - part of the implementation of the compression library and is - subject to change. Applications should only use zlib.h. - */ - -void inflate_fast OF((z_streamp strm, unsigned start)); +/* inffast.h -- header to use inffast.c + * Copyright (C) 1995-2003 Mark Adler + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* WARNING: this file should *not* be used by applications. It is + part of the implementation of the compression library and is + subject to change. Applications should only use zlib.h. + */ + +void inflate_fast OF((z_streamp strm, unsigned start)); diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffixed.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffixed.h index 423d5c5b5..75ed4b597 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffixed.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inffixed.h @@ -1,94 +1,94 @@ - /* inffixed.h -- table for decoding fixed codes - * Generated automatically by makefixed(). - */ - - /* WARNING: this file should *not* be used by applications. It - is part of the implementation of the compression library and - is subject to change. Applications should only use zlib.h. - */ - - static const code lenfix[512] = { - {96,7,0},{0,8,80},{0,8,16},{20,8,115},{18,7,31},{0,8,112},{0,8,48}, - {0,9,192},{16,7,10},{0,8,96},{0,8,32},{0,9,160},{0,8,0},{0,8,128}, - {0,8,64},{0,9,224},{16,7,6},{0,8,88},{0,8,24},{0,9,144},{19,7,59}, - {0,8,120},{0,8,56},{0,9,208},{17,7,17},{0,8,104},{0,8,40},{0,9,176}, - {0,8,8},{0,8,136},{0,8,72},{0,9,240},{16,7,4},{0,8,84},{0,8,20}, - {21,8,227},{19,7,43},{0,8,116},{0,8,52},{0,9,200},{17,7,13},{0,8,100}, - {0,8,36},{0,9,168},{0,8,4},{0,8,132},{0,8,68},{0,9,232},{16,7,8}, - {0,8,92},{0,8,28},{0,9,152},{20,7,83},{0,8,124},{0,8,60},{0,9,216}, - {18,7,23},{0,8,108},{0,8,44},{0,9,184},{0,8,12},{0,8,140},{0,8,76}, - {0,9,248},{16,7,3},{0,8,82},{0,8,18},{21,8,163},{19,7,35},{0,8,114}, - {0,8,50},{0,9,196},{17,7,11},{0,8,98},{0,8,34},{0,9,164},{0,8,2}, - {0,8,130},{0,8,66},{0,9,228},{16,7,7},{0,8,90},{0,8,26},{0,9,148}, - {20,7,67},{0,8,122},{0,8,58},{0,9,212},{18,7,19},{0,8,106},{0,8,42}, - {0,9,180},{0,8,10},{0,8,138},{0,8,74},{0,9,244},{16,7,5},{0,8,86}, - {0,8,22},{64,8,0},{19,7,51},{0,8,118},{0,8,54},{0,9,204},{17,7,15}, - {0,8,102},{0,8,38},{0,9,172},{0,8,6},{0,8,134},{0,8,70},{0,9,236}, - {16,7,9},{0,8,94},{0,8,30},{0,9,156},{20,7,99},{0,8,126},{0,8,62}, - {0,9,220},{18,7,27},{0,8,110},{0,8,46},{0,9,188},{0,8,14},{0,8,142}, - {0,8,78},{0,9,252},{96,7,0},{0,8,81},{0,8,17},{21,8,131},{18,7,31}, - {0,8,113},{0,8,49},{0,9,194},{16,7,10},{0,8,97},{0,8,33},{0,9,162}, - {0,8,1},{0,8,129},{0,8,65},{0,9,226},{16,7,6},{0,8,89},{0,8,25}, - {0,9,146},{19,7,59},{0,8,121},{0,8,57},{0,9,210},{17,7,17},{0,8,105}, - {0,8,41},{0,9,178},{0,8,9},{0,8,137},{0,8,73},{0,9,242},{16,7,4}, - {0,8,85},{0,8,21},{16,8,258},{19,7,43},{0,8,117},{0,8,53},{0,9,202}, - {17,7,13},{0,8,101},{0,8,37},{0,9,170},{0,8,5},{0,8,133},{0,8,69}, - {0,9,234},{16,7,8},{0,8,93},{0,8,29},{0,9,154},{20,7,83},{0,8,125}, - {0,8,61},{0,9,218},{18,7,23},{0,8,109},{0,8,45},{0,9,186},{0,8,13}, - {0,8,141},{0,8,77},{0,9,250},{16,7,3},{0,8,83},{0,8,19},{21,8,195}, - {19,7,35},{0,8,115},{0,8,51},{0,9,198},{17,7,11},{0,8,99},{0,8,35}, - {0,9,166},{0,8,3},{0,8,131},{0,8,67},{0,9,230},{16,7,7},{0,8,91}, - {0,8,27},{0,9,150},{20,7,67},{0,8,123},{0,8,59},{0,9,214},{18,7,19}, - {0,8,107},{0,8,43},{0,9,182},{0,8,11},{0,8,139},{0,8,75},{0,9,246}, - {16,7,5},{0,8,87},{0,8,23},{64,8,0},{19,7,51},{0,8,119},{0,8,55}, - {0,9,206},{17,7,15},{0,8,103},{0,8,39},{0,9,174},{0,8,7},{0,8,135}, - {0,8,71},{0,9,238},{16,7,9},{0,8,95},{0,8,31},{0,9,158},{20,7,99}, - {0,8,127},{0,8,63},{0,9,222},{18,7,27},{0,8,111},{0,8,47},{0,9,190}, - {0,8,15},{0,8,143},{0,8,79},{0,9,254},{96,7,0},{0,8,80},{0,8,16}, - {20,8,115},{18,7,31},{0,8,112},{0,8,48},{0,9,193},{16,7,10},{0,8,96}, - {0,8,32},{0,9,161},{0,8,0},{0,8,128},{0,8,64},{0,9,225},{16,7,6}, - {0,8,88},{0,8,24},{0,9,145},{19,7,59},{0,8,120},{0,8,56},{0,9,209}, - {17,7,17},{0,8,104},{0,8,40},{0,9,177},{0,8,8},{0,8,136},{0,8,72}, - {0,9,241},{16,7,4},{0,8,84},{0,8,20},{21,8,227},{19,7,43},{0,8,116}, - {0,8,52},{0,9,201},{17,7,13},{0,8,100},{0,8,36},{0,9,169},{0,8,4}, - {0,8,132},{0,8,68},{0,9,233},{16,7,8},{0,8,92},{0,8,28},{0,9,153}, - {20,7,83},{0,8,124},{0,8,60},{0,9,217},{18,7,23},{0,8,108},{0,8,44}, - {0,9,185},{0,8,12},{0,8,140},{0,8,76},{0,9,249},{16,7,3},{0,8,82}, - {0,8,18},{21,8,163},{19,7,35},{0,8,114},{0,8,50},{0,9,197},{17,7,11}, - {0,8,98},{0,8,34},{0,9,165},{0,8,2},{0,8,130},{0,8,66},{0,9,229}, - {16,7,7},{0,8,90},{0,8,26},{0,9,149},{20,7,67},{0,8,122},{0,8,58}, - {0,9,213},{18,7,19},{0,8,106},{0,8,42},{0,9,181},{0,8,10},{0,8,138}, - {0,8,74},{0,9,245},{16,7,5},{0,8,86},{0,8,22},{64,8,0},{19,7,51}, - {0,8,118},{0,8,54},{0,9,205},{17,7,15},{0,8,102},{0,8,38},{0,9,173}, - {0,8,6},{0,8,134},{0,8,70},{0,9,237},{16,7,9},{0,8,94},{0,8,30}, - {0,9,157},{20,7,99},{0,8,126},{0,8,62},{0,9,221},{18,7,27},{0,8,110}, - {0,8,46},{0,9,189},{0,8,14},{0,8,142},{0,8,78},{0,9,253},{96,7,0}, - {0,8,81},{0,8,17},{21,8,131},{18,7,31},{0,8,113},{0,8,49},{0,9,195}, - {16,7,10},{0,8,97},{0,8,33},{0,9,163},{0,8,1},{0,8,129},{0,8,65}, - {0,9,227},{16,7,6},{0,8,89},{0,8,25},{0,9,147},{19,7,59},{0,8,121}, - {0,8,57},{0,9,211},{17,7,17},{0,8,105},{0,8,41},{0,9,179},{0,8,9}, - {0,8,137},{0,8,73},{0,9,243},{16,7,4},{0,8,85},{0,8,21},{16,8,258}, - {19,7,43},{0,8,117},{0,8,53},{0,9,203},{17,7,13},{0,8,101},{0,8,37}, - {0,9,171},{0,8,5},{0,8,133},{0,8,69},{0,9,235},{16,7,8},{0,8,93}, - {0,8,29},{0,9,155},{20,7,83},{0,8,125},{0,8,61},{0,9,219},{18,7,23}, - {0,8,109},{0,8,45},{0,9,187},{0,8,13},{0,8,141},{0,8,77},{0,9,251}, - {16,7,3},{0,8,83},{0,8,19},{21,8,195},{19,7,35},{0,8,115},{0,8,51}, - {0,9,199},{17,7,11},{0,8,99},{0,8,35},{0,9,167},{0,8,3},{0,8,131}, - {0,8,67},{0,9,231},{16,7,7},{0,8,91},{0,8,27},{0,9,151},{20,7,67}, - {0,8,123},{0,8,59},{0,9,215},{18,7,19},{0,8,107},{0,8,43},{0,9,183}, - {0,8,11},{0,8,139},{0,8,75},{0,9,247},{16,7,5},{0,8,87},{0,8,23}, - {64,8,0},{19,7,51},{0,8,119},{0,8,55},{0,9,207},{17,7,15},{0,8,103}, - {0,8,39},{0,9,175},{0,8,7},{0,8,135},{0,8,71},{0,9,239},{16,7,9}, - {0,8,95},{0,8,31},{0,9,159},{20,7,99},{0,8,127},{0,8,63},{0,9,223}, - {18,7,27},{0,8,111},{0,8,47},{0,9,191},{0,8,15},{0,8,143},{0,8,79}, - {0,9,255} - }; - - static const code distfix[32] = { - {16,5,1},{23,5,257},{19,5,17},{27,5,4097},{17,5,5},{25,5,1025}, - {21,5,65},{29,5,16385},{16,5,3},{24,5,513},{20,5,33},{28,5,8193}, - {18,5,9},{26,5,2049},{22,5,129},{64,5,0},{16,5,2},{23,5,385}, - {19,5,25},{27,5,6145},{17,5,7},{25,5,1537},{21,5,97},{29,5,24577}, - {16,5,4},{24,5,769},{20,5,49},{28,5,12289},{18,5,13},{26,5,3073}, - {22,5,193},{64,5,0} - }; + /* inffixed.h -- table for decoding fixed codes + * Generated automatically by makefixed(). + */ + + /* WARNING: this file should *not* be used by applications. It + is part of the implementation of the compression library and + is subject to change. Applications should only use zlib.h. + */ + + static const code lenfix[512] = { + {96,7,0},{0,8,80},{0,8,16},{20,8,115},{18,7,31},{0,8,112},{0,8,48}, + {0,9,192},{16,7,10},{0,8,96},{0,8,32},{0,9,160},{0,8,0},{0,8,128}, + {0,8,64},{0,9,224},{16,7,6},{0,8,88},{0,8,24},{0,9,144},{19,7,59}, + {0,8,120},{0,8,56},{0,9,208},{17,7,17},{0,8,104},{0,8,40},{0,9,176}, + {0,8,8},{0,8,136},{0,8,72},{0,9,240},{16,7,4},{0,8,84},{0,8,20}, + {21,8,227},{19,7,43},{0,8,116},{0,8,52},{0,9,200},{17,7,13},{0,8,100}, + {0,8,36},{0,9,168},{0,8,4},{0,8,132},{0,8,68},{0,9,232},{16,7,8}, + {0,8,92},{0,8,28},{0,9,152},{20,7,83},{0,8,124},{0,8,60},{0,9,216}, + {18,7,23},{0,8,108},{0,8,44},{0,9,184},{0,8,12},{0,8,140},{0,8,76}, + {0,9,248},{16,7,3},{0,8,82},{0,8,18},{21,8,163},{19,7,35},{0,8,114}, + {0,8,50},{0,9,196},{17,7,11},{0,8,98},{0,8,34},{0,9,164},{0,8,2}, + {0,8,130},{0,8,66},{0,9,228},{16,7,7},{0,8,90},{0,8,26},{0,9,148}, + {20,7,67},{0,8,122},{0,8,58},{0,9,212},{18,7,19},{0,8,106},{0,8,42}, + {0,9,180},{0,8,10},{0,8,138},{0,8,74},{0,9,244},{16,7,5},{0,8,86}, + {0,8,22},{64,8,0},{19,7,51},{0,8,118},{0,8,54},{0,9,204},{17,7,15}, + {0,8,102},{0,8,38},{0,9,172},{0,8,6},{0,8,134},{0,8,70},{0,9,236}, + {16,7,9},{0,8,94},{0,8,30},{0,9,156},{20,7,99},{0,8,126},{0,8,62}, + {0,9,220},{18,7,27},{0,8,110},{0,8,46},{0,9,188},{0,8,14},{0,8,142}, + {0,8,78},{0,9,252},{96,7,0},{0,8,81},{0,8,17},{21,8,131},{18,7,31}, + {0,8,113},{0,8,49},{0,9,194},{16,7,10},{0,8,97},{0,8,33},{0,9,162}, + {0,8,1},{0,8,129},{0,8,65},{0,9,226},{16,7,6},{0,8,89},{0,8,25}, + {0,9,146},{19,7,59},{0,8,121},{0,8,57},{0,9,210},{17,7,17},{0,8,105}, + {0,8,41},{0,9,178},{0,8,9},{0,8,137},{0,8,73},{0,9,242},{16,7,4}, + {0,8,85},{0,8,21},{16,8,258},{19,7,43},{0,8,117},{0,8,53},{0,9,202}, + {17,7,13},{0,8,101},{0,8,37},{0,9,170},{0,8,5},{0,8,133},{0,8,69}, + {0,9,234},{16,7,8},{0,8,93},{0,8,29},{0,9,154},{20,7,83},{0,8,125}, + {0,8,61},{0,9,218},{18,7,23},{0,8,109},{0,8,45},{0,9,186},{0,8,13}, + {0,8,141},{0,8,77},{0,9,250},{16,7,3},{0,8,83},{0,8,19},{21,8,195}, + {19,7,35},{0,8,115},{0,8,51},{0,9,198},{17,7,11},{0,8,99},{0,8,35}, + {0,9,166},{0,8,3},{0,8,131},{0,8,67},{0,9,230},{16,7,7},{0,8,91}, + {0,8,27},{0,9,150},{20,7,67},{0,8,123},{0,8,59},{0,9,214},{18,7,19}, + {0,8,107},{0,8,43},{0,9,182},{0,8,11},{0,8,139},{0,8,75},{0,9,246}, + {16,7,5},{0,8,87},{0,8,23},{64,8,0},{19,7,51},{0,8,119},{0,8,55}, + {0,9,206},{17,7,15},{0,8,103},{0,8,39},{0,9,174},{0,8,7},{0,8,135}, + {0,8,71},{0,9,238},{16,7,9},{0,8,95},{0,8,31},{0,9,158},{20,7,99}, + {0,8,127},{0,8,63},{0,9,222},{18,7,27},{0,8,111},{0,8,47},{0,9,190}, + {0,8,15},{0,8,143},{0,8,79},{0,9,254},{96,7,0},{0,8,80},{0,8,16}, + {20,8,115},{18,7,31},{0,8,112},{0,8,48},{0,9,193},{16,7,10},{0,8,96}, + {0,8,32},{0,9,161},{0,8,0},{0,8,128},{0,8,64},{0,9,225},{16,7,6}, + {0,8,88},{0,8,24},{0,9,145},{19,7,59},{0,8,120},{0,8,56},{0,9,209}, + {17,7,17},{0,8,104},{0,8,40},{0,9,177},{0,8,8},{0,8,136},{0,8,72}, + {0,9,241},{16,7,4},{0,8,84},{0,8,20},{21,8,227},{19,7,43},{0,8,116}, + {0,8,52},{0,9,201},{17,7,13},{0,8,100},{0,8,36},{0,9,169},{0,8,4}, + {0,8,132},{0,8,68},{0,9,233},{16,7,8},{0,8,92},{0,8,28},{0,9,153}, + {20,7,83},{0,8,124},{0,8,60},{0,9,217},{18,7,23},{0,8,108},{0,8,44}, + {0,9,185},{0,8,12},{0,8,140},{0,8,76},{0,9,249},{16,7,3},{0,8,82}, + {0,8,18},{21,8,163},{19,7,35},{0,8,114},{0,8,50},{0,9,197},{17,7,11}, + {0,8,98},{0,8,34},{0,9,165},{0,8,2},{0,8,130},{0,8,66},{0,9,229}, + {16,7,7},{0,8,90},{0,8,26},{0,9,149},{20,7,67},{0,8,122},{0,8,58}, + {0,9,213},{18,7,19},{0,8,106},{0,8,42},{0,9,181},{0,8,10},{0,8,138}, + {0,8,74},{0,9,245},{16,7,5},{0,8,86},{0,8,22},{64,8,0},{19,7,51}, + {0,8,118},{0,8,54},{0,9,205},{17,7,15},{0,8,102},{0,8,38},{0,9,173}, + {0,8,6},{0,8,134},{0,8,70},{0,9,237},{16,7,9},{0,8,94},{0,8,30}, + {0,9,157},{20,7,99},{0,8,126},{0,8,62},{0,9,221},{18,7,27},{0,8,110}, + {0,8,46},{0,9,189},{0,8,14},{0,8,142},{0,8,78},{0,9,253},{96,7,0}, + {0,8,81},{0,8,17},{21,8,131},{18,7,31},{0,8,113},{0,8,49},{0,9,195}, + {16,7,10},{0,8,97},{0,8,33},{0,9,163},{0,8,1},{0,8,129},{0,8,65}, + {0,9,227},{16,7,6},{0,8,89},{0,8,25},{0,9,147},{19,7,59},{0,8,121}, + {0,8,57},{0,9,211},{17,7,17},{0,8,105},{0,8,41},{0,9,179},{0,8,9}, + {0,8,137},{0,8,73},{0,9,243},{16,7,4},{0,8,85},{0,8,21},{16,8,258}, + {19,7,43},{0,8,117},{0,8,53},{0,9,203},{17,7,13},{0,8,101},{0,8,37}, + {0,9,171},{0,8,5},{0,8,133},{0,8,69},{0,9,235},{16,7,8},{0,8,93}, + {0,8,29},{0,9,155},{20,7,83},{0,8,125},{0,8,61},{0,9,219},{18,7,23}, + {0,8,109},{0,8,45},{0,9,187},{0,8,13},{0,8,141},{0,8,77},{0,9,251}, + {16,7,3},{0,8,83},{0,8,19},{21,8,195},{19,7,35},{0,8,115},{0,8,51}, + {0,9,199},{17,7,11},{0,8,99},{0,8,35},{0,9,167},{0,8,3},{0,8,131}, + {0,8,67},{0,9,231},{16,7,7},{0,8,91},{0,8,27},{0,9,151},{20,7,67}, + {0,8,123},{0,8,59},{0,9,215},{18,7,19},{0,8,107},{0,8,43},{0,9,183}, + {0,8,11},{0,8,139},{0,8,75},{0,9,247},{16,7,5},{0,8,87},{0,8,23}, + {64,8,0},{19,7,51},{0,8,119},{0,8,55},{0,9,207},{17,7,15},{0,8,103}, + {0,8,39},{0,9,175},{0,8,7},{0,8,135},{0,8,71},{0,9,239},{16,7,9}, + {0,8,95},{0,8,31},{0,9,159},{20,7,99},{0,8,127},{0,8,63},{0,9,223}, + {18,7,27},{0,8,111},{0,8,47},{0,9,191},{0,8,15},{0,8,143},{0,8,79}, + {0,9,255} + }; + + static const code distfix[32] = { + {16,5,1},{23,5,257},{19,5,17},{27,5,4097},{17,5,5},{25,5,1025}, + {21,5,65},{29,5,16385},{16,5,3},{24,5,513},{20,5,33},{28,5,8193}, + {18,5,9},{26,5,2049},{22,5,129},{64,5,0},{16,5,2},{23,5,385}, + {19,5,25},{27,5,6145},{17,5,7},{25,5,1537},{21,5,97},{29,5,24577}, + {16,5,4},{24,5,769},{20,5,49},{28,5,12289},{18,5,13},{26,5,3073}, + {22,5,193},{64,5,0} + }; diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inflate.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inflate.c index 33ea90292..792fdee8e 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inflate.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inflate.c @@ -1,1368 +1,1368 @@ -/* inflate.c -- zlib decompression - * Copyright (C) 1995-2005 Mark Adler - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* - * Change history: - * - * 1.2.beta0 24 Nov 2002 - * - First version -- complete rewrite of inflate to simplify code, avoid - * creation of window when not needed, minimize use of window when it is - * needed, make inffast.c even faster, implement gzip decoding, and to - * improve code readability and style over the previous zlib inflate code - * - * 1.2.beta1 25 Nov 2002 - * - Use pointers for available input and output checking in inffast.c - * - Remove input and output counters in inffast.c - * - Change inffast.c entry and loop from avail_in >= 7 to >= 6 - * - Remove unnecessary second byte pull from length extra in inffast.c - * - Unroll direct copy to three copies per loop in inffast.c - * - * 1.2.beta2 4 Dec 2002 - * - Change external routine names to reduce potential conflicts - * - Correct filename to inffixed.h for fixed tables in inflate.c - * - Make hbuf[] unsigned char to match parameter type in inflate.c - * - Change strm->next_out[-state->offset] to *(strm->next_out - state->offset) - * to avoid negation problem on Alphas (64 bit) in inflate.c - * - * 1.2.beta3 22 Dec 2002 - * - Add comments on state->bits assertion in inffast.c - * - Add comments on op field in inftrees.h - * - Fix bug in reuse of allocated window after inflateReset() - * - Remove bit fields--back to byte structure for speed - * - Remove distance extra == 0 check in inflate_fast()--only helps for lengths - * - Change post-increments to pre-increments in inflate_fast(), PPC biased? - * - Add compile time option, POSTINC, to use post-increments instead (Intel?) - * - Make MATCH copy in inflate() much faster for when inflate_fast() not used - * - Use local copies of stream next and avail values, as well as local bit - * buffer and bit count in inflate()--for speed when inflate_fast() not used - * - * 1.2.beta4 1 Jan 2003 - * - Split ptr - 257 statements in inflate_table() to avoid compiler warnings - * - Move a comment on output buffer sizes from inffast.c to inflate.c - * - Add comments in inffast.c to introduce the inflate_fast() routine - * - Rearrange window copies in inflate_fast() for speed and simplification - * - Unroll last copy for window match in inflate_fast() - * - Use local copies of window variables in inflate_fast() for speed - * - Pull out common write == 0 case for speed in inflate_fast() - * - Make op and len in inflate_fast() unsigned for consistency - * - Add FAR to lcode and dcode declarations in inflate_fast() - * - Simplified bad distance check in inflate_fast() - * - Added inflateBackInit(), inflateBack(), and inflateBackEnd() in new - * source file infback.c to provide a call-back interface to inflate for - * programs like gzip and unzip -- uses window as output buffer to avoid - * window copying - * - * 1.2.beta5 1 Jan 2003 - * - Improved inflateBack() interface to allow the caller to provide initial - * input in strm. - * - Fixed stored blocks bug in inflateBack() - * - * 1.2.beta6 4 Jan 2003 - * - Added comments in inffast.c on effectiveness of POSTINC - * - Typecasting all around to reduce compiler warnings - * - Changed loops from while (1) or do {} while (1) to for (;;), again to - * make compilers happy - * - Changed type of window in inflateBackInit() to unsigned char * - * - * 1.2.beta7 27 Jan 2003 - * - Changed many types to unsigned or unsigned short to avoid warnings - * - Added inflateCopy() function - * - * 1.2.0 9 Mar 2003 - * - Changed inflateBack() interface to provide separate opaque descriptors - * for the in() and out() functions - * - Changed inflateBack() argument and in_func typedef to swap the length - * and buffer address return values for the input function - * - Check next_in and next_out for Z_NULL on entry to inflate() - * - * The history for versions after 1.2.0 are in ChangeLog in zlib distribution. - */ - -#include "zutil.h" -#include "inftrees.h" -#include "inflate.h" -#include "inffast.h" - -#ifdef MAKEFIXED -# ifndef BUILDFIXED -# define BUILDFIXED -# endif -#endif - -/* function prototypes */ -local void fixedtables OF((struct inflate_state FAR *state)); -local int updatewindow OF((z_streamp strm, unsigned out)); -#ifdef BUILDFIXED - void makefixed OF((void)); -#endif -local unsigned syncsearch OF((unsigned FAR *have, unsigned char FAR *buf, - unsigned len)); - -int ZEXPORT inflateReset(strm) -z_streamp strm; -{ - struct inflate_state FAR *state; - - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - state = (struct inflate_state FAR *)strm->state; - strm->total_in = strm->total_out = state->total = 0; - strm->msg = Z_NULL; - strm->adler = 1; /* to support ill-conceived Java test suite */ - state->mode = HEAD; - state->last = 0; - state->havedict = 0; - state->dmax = 32768U; - state->head = Z_NULL; - state->wsize = 0; - state->whave = 0; - state->write = 0; - state->hold = 0; - state->bits = 0; - state->lencode = state->distcode = state->next = state->codes; - Tracev((stderr, "inflate: reset\n")); - return Z_OK; -} - -int ZEXPORT inflatePrime(strm, bits, value) -z_streamp strm; -int bits; -int value; -{ - struct inflate_state FAR *state; - - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - state = (struct inflate_state FAR *)strm->state; - if (bits > 16 || state->bits + bits > 32) return Z_STREAM_ERROR; - value &= (1L << bits) - 1; - state->hold += value << state->bits; - state->bits += bits; - return Z_OK; -} - -int ZEXPORT inflateInit2_(strm, windowBits, version, stream_size) -z_streamp strm; -int windowBits; -const char *version; -int stream_size; -{ - struct inflate_state FAR *state; - - if (version == Z_NULL || version[0] != ZLIB_VERSION[0] || - stream_size != (int)(sizeof(z_stream))) - return Z_VERSION_ERROR; - if (strm == Z_NULL) return Z_STREAM_ERROR; - strm->msg = Z_NULL; /* in case we return an error */ - if (strm->zalloc == (alloc_func)0) { - strm->zalloc = zcalloc; - strm->opaque = (voidpf)0; - } - if (strm->zfree == (free_func)0) strm->zfree = zcfree; - state = (struct inflate_state FAR *) - ZALLOC(strm, 1, sizeof(struct inflate_state)); - if (state == Z_NULL) return Z_MEM_ERROR; - Tracev((stderr, "inflate: allocated\n")); - strm->state = (struct internal_state FAR *)state; - if (windowBits < 0) { - state->wrap = 0; - windowBits = -windowBits; - } - else { - state->wrap = (windowBits >> 4) + 1; -#ifdef GUNZIP - if (windowBits < 48) windowBits &= 15; -#endif - } - if (windowBits < 8 || windowBits > 15) { - ZFREE(strm, state); - strm->state = Z_NULL; - return Z_STREAM_ERROR; - } - state->wbits = (unsigned)windowBits; - state->window = Z_NULL; - return inflateReset(strm); -} - -int ZEXPORT inflateInit_(strm, version, stream_size) -z_streamp strm; -const char *version; -int stream_size; -{ - return inflateInit2_(strm, DEF_WBITS, version, stream_size); -} - -/* - Return state with length and distance decoding tables and index sizes set to - fixed code decoding. Normally this returns fixed tables from inffixed.h. - If BUILDFIXED is defined, then instead this routine builds the tables the - first time it's called, and returns those tables the first time and - thereafter. This reduces the size of the code by about 2K bytes, in - exchange for a little execution time. However, BUILDFIXED should not be - used for threaded applications, since the rewriting of the tables and virgin - may not be thread-safe. - */ -local void fixedtables(state) -struct inflate_state FAR *state; -{ -#ifdef BUILDFIXED - static int virgin = 1; - static code *lenfix, *distfix; - static code fixed[544]; - - /* build fixed huffman tables if first call (may not be thread safe) */ - if (virgin) { - unsigned sym, bits; - static code *next; - - /* literal/length table */ - sym = 0; - while (sym < 144) state->lens[sym++] = 8; - while (sym < 256) state->lens[sym++] = 9; - while (sym < 280) state->lens[sym++] = 7; - while (sym < 288) state->lens[sym++] = 8; - next = fixed; - lenfix = next; - bits = 9; - inflate_table(LENS, state->lens, 288, &(next), &(bits), state->work); - - /* distance table */ - sym = 0; - while (sym < 32) state->lens[sym++] = 5; - distfix = next; - bits = 5; - inflate_table(DISTS, state->lens, 32, &(next), &(bits), state->work); - - /* do this just once */ - virgin = 0; - } -#else /* !BUILDFIXED */ -# include "inffixed.h" -#endif /* BUILDFIXED */ - state->lencode = lenfix; - state->lenbits = 9; - state->distcode = distfix; - state->distbits = 5; -} - -#ifdef MAKEFIXED -#include - -/* - Write out the inffixed.h that is #include'd above. Defining MAKEFIXED also - defines BUILDFIXED, so the tables are built on the fly. makefixed() writes - those tables to stdout, which would be piped to inffixed.h. A small program - can simply call makefixed to do this: - - void makefixed(void); - - int main(void) - { - makefixed(); - return 0; - } - - Then that can be linked with zlib built with MAKEFIXED defined and run: - - a.out > inffixed.h - */ -void makefixed() -{ - unsigned low, size; - struct inflate_state state; - - fixedtables(&state); - puts(" /* inffixed.h -- table for decoding fixed codes"); - puts(" * Generated automatically by makefixed()."); - puts(" */"); - puts(""); - puts(" /* WARNING: this file should *not* be used by applications."); - puts(" It is part of the implementation of this library and is"); - puts(" subject to change. Applications should only use zlib.h."); - puts(" */"); - puts(""); - size = 1U << 9; - printf(" static const code lenfix[%u] = {", size); - low = 0; - for (;;) { - if ((low % 7) == 0) printf("\n "); - printf("{%u,%u,%d}", state.lencode[low].op, state.lencode[low].bits, - state.lencode[low].val); - if (++low == size) break; - putchar(','); - } - puts("\n };"); - size = 1U << 5; - printf("\n static const code distfix[%u] = {", size); - low = 0; - for (;;) { - if ((low % 6) == 0) printf("\n "); - printf("{%u,%u,%d}", state.distcode[low].op, state.distcode[low].bits, - state.distcode[low].val); - if (++low == size) break; - putchar(','); - } - puts("\n };"); -} -#endif /* MAKEFIXED */ - -/* - Update the window with the last wsize (normally 32K) bytes written before - returning. If window does not exist yet, create it. This is only called - when a window is already in use, or when output has been written during this - inflate call, but the end of the deflate stream has not been reached yet. - It is also called to create a window for dictionary data when a dictionary - is loaded. - - Providing output buffers larger than 32K to inflate() should provide a speed - advantage, since only the last 32K of output is copied to the sliding window - upon return from inflate(), and since all distances after the first 32K of - output will fall in the output data, making match copies simpler and faster. - The advantage may be dependent on the size of the processor's data caches. - */ -local int updatewindow(strm, out) -z_streamp strm; -unsigned out; -{ - struct inflate_state FAR *state; - unsigned copy, dist; - - state = (struct inflate_state FAR *)strm->state; - - /* if it hasn't been done already, allocate space for the window */ - if (state->window == Z_NULL) { - state->window = (unsigned char FAR *) - ZALLOC(strm, 1U << state->wbits, - sizeof(unsigned char)); - if (state->window == Z_NULL) return 1; - } - - /* if window not in use yet, initialize */ - if (state->wsize == 0) { - state->wsize = 1U << state->wbits; - state->write = 0; - state->whave = 0; - } - - /* copy state->wsize or less output bytes into the circular window */ - copy = out - strm->avail_out; - if (copy >= state->wsize) { - zmemcpy(state->window, strm->next_out - state->wsize, state->wsize); - state->write = 0; - state->whave = state->wsize; - } - else { - dist = state->wsize - state->write; - if (dist > copy) dist = copy; - zmemcpy(state->window + state->write, strm->next_out - copy, dist); - copy -= dist; - if (copy) { - zmemcpy(state->window, strm->next_out - copy, copy); - state->write = copy; - state->whave = state->wsize; - } - else { - state->write += dist; - if (state->write == state->wsize) state->write = 0; - if (state->whave < state->wsize) state->whave += dist; - } - } - return 0; -} - -/* Macros for inflate(): */ - -/* check function to use adler32() for zlib or crc32() for gzip */ -#ifdef GUNZIP -# define UPDATE(check, buf, len) \ - (state->flags ? crc32(check, buf, len) : adler32(check, buf, len)) -#else -# define UPDATE(check, buf, len) adler32(check, buf, len) -#endif - -/* check macros for header crc */ -#ifdef GUNZIP -# define CRC2(check, word) \ - do { \ - hbuf[0] = (unsigned char)(word); \ - hbuf[1] = (unsigned char)((word) >> 8); \ - check = crc32(check, hbuf, 2); \ - } while (0) - -# define CRC4(check, word) \ - do { \ - hbuf[0] = (unsigned char)(word); \ - hbuf[1] = (unsigned char)((word) >> 8); \ - hbuf[2] = (unsigned char)((word) >> 16); \ - hbuf[3] = (unsigned char)((word) >> 24); \ - check = crc32(check, hbuf, 4); \ - } while (0) -#endif - -/* Load registers with state in inflate() for speed */ -#define LOAD() \ - do { \ - put = strm->next_out; \ - left = strm->avail_out; \ - next = strm->next_in; \ - have = strm->avail_in; \ - hold = state->hold; \ - bits = state->bits; \ - } while (0) - -/* Restore state from registers in inflate() */ -#define RESTORE() \ - do { \ - strm->next_out = put; \ - strm->avail_out = left; \ - strm->next_in = next; \ - strm->avail_in = have; \ - state->hold = hold; \ - state->bits = bits; \ - } while (0) - -/* Clear the input bit accumulator */ -#define INITBITS() \ - do { \ - hold = 0; \ - bits = 0; \ - } while (0) - -/* Get a byte of input into the bit accumulator, or return from inflate() - if there is no input available. */ -#define PULLBYTE() \ - do { \ - if (have == 0) goto inf_leave; \ - have--; \ - hold += (unsigned long)(*next++) << bits; \ - bits += 8; \ - } while (0) - -/* Assure that there are at least n bits in the bit accumulator. If there is - not enough available input to do that, then return from inflate(). */ -#define NEEDBITS(n) \ - do { \ - while (bits < (unsigned)(n)) \ - PULLBYTE(); \ - } while (0) - -/* Return the low n bits of the bit accumulator (n < 16) */ -#define BITS(n) \ - ((unsigned)hold & ((1U << (n)) - 1)) - -/* Remove n bits from the bit accumulator */ -#define DROPBITS(n) \ - do { \ - hold >>= (n); \ - bits -= (unsigned)(n); \ - } while (0) - -/* Remove zero to seven bits as needed to go to a byte boundary */ -#define BYTEBITS() \ - do { \ - hold >>= bits & 7; \ - bits -= bits & 7; \ - } while (0) - -/* Reverse the bytes in a 32-bit value */ -#define REVERSE(q) \ - ((((q) >> 24) & 0xff) + (((q) >> 8) & 0xff00) + \ - (((q) & 0xff00) << 8) + (((q) & 0xff) << 24)) - -/* - inflate() uses a state machine to process as much input data and generate as - much output data as possible before returning. The state machine is - structured roughly as follows: - - for (;;) switch (state) { - ... - case STATEn: - if (not enough input data or output space to make progress) - return; - ... make progress ... - state = STATEm; - break; - ... - } - - so when inflate() is called again, the same case is attempted again, and - if the appropriate resources are provided, the machine proceeds to the - next state. The NEEDBITS() macro is usually the way the state evaluates - whether it can proceed or should return. NEEDBITS() does the return if - the requested bits are not available. The typical use of the BITS macros - is: - - NEEDBITS(n); - ... do something with BITS(n) ... - DROPBITS(n); - - where NEEDBITS(n) either returns from inflate() if there isn't enough - input left to load n bits into the accumulator, or it continues. BITS(n) - gives the low n bits in the accumulator. When done, DROPBITS(n) drops - the low n bits off the accumulator. INITBITS() clears the accumulator - and sets the number of available bits to zero. BYTEBITS() discards just - enough bits to put the accumulator on a byte boundary. After BYTEBITS() - and a NEEDBITS(8), then BITS(8) would return the next byte in the stream. - - NEEDBITS(n) uses PULLBYTE() to get an available byte of input, or to return - if there is no input available. The decoding of variable length codes uses - PULLBYTE() directly in order to pull just enough bytes to decode the next - code, and no more. - - Some states loop until they get enough input, making sure that enough - state information is maintained to continue the loop where it left off - if NEEDBITS() returns in the loop. For example, want, need, and keep - would all have to actually be part of the saved state in case NEEDBITS() - returns: - - case STATEw: - while (want < need) { - NEEDBITS(n); - keep[want++] = BITS(n); - DROPBITS(n); - } - state = STATEx; - case STATEx: - - As shown above, if the next state is also the next case, then the break - is omitted. - - A state may also return if there is not enough output space available to - complete that state. Those states are copying stored data, writing a - literal byte, and copying a matching string. - - When returning, a "goto inf_leave" is used to update the total counters, - update the check value, and determine whether any progress has been made - during that inflate() call in order to return the proper return code. - Progress is defined as a change in either strm->avail_in or strm->avail_out. - When there is a window, goto inf_leave will update the window with the last - output written. If a goto inf_leave occurs in the middle of decompression - and there is no window currently, goto inf_leave will create one and copy - output to the window for the next call of inflate(). - - In this implementation, the flush parameter of inflate() only affects the - return code (per zlib.h). inflate() always writes as much as possible to - strm->next_out, given the space available and the provided input--the effect - documented in zlib.h of Z_SYNC_FLUSH. Furthermore, inflate() always defers - the allocation of and copying into a sliding window until necessary, which - provides the effect documented in zlib.h for Z_FINISH when the entire input - stream available. So the only thing the flush parameter actually does is: - when flush is set to Z_FINISH, inflate() cannot return Z_OK. Instead it - will return Z_BUF_ERROR if it has not reached the end of the stream. - */ - -int ZEXPORT inflate(strm, flush) -z_streamp strm; -int flush; -{ - struct inflate_state FAR *state; - unsigned char FAR *next; /* next input */ - unsigned char FAR *put; /* next output */ - unsigned have, left; /* available input and output */ - unsigned long hold; /* bit buffer */ - unsigned bits; /* bits in bit buffer */ - unsigned in, out; /* save starting available input and output */ - unsigned copy; /* number of stored or match bytes to copy */ - unsigned char FAR *from; /* where to copy match bytes from */ - code this; /* current decoding table entry */ - code last; /* parent table entry */ - unsigned len; /* length to copy for repeats, bits to drop */ - int ret; /* return code */ -#ifdef GUNZIP - unsigned char hbuf[4]; /* buffer for gzip header crc calculation */ -#endif - static const unsigned short order[19] = /* permutation of code lengths */ - {16, 17, 18, 0, 8, 7, 9, 6, 10, 5, 11, 4, 12, 3, 13, 2, 14, 1, 15}; - - if (strm == Z_NULL || strm->state == Z_NULL || strm->next_out == Z_NULL || - (strm->next_in == Z_NULL && strm->avail_in != 0)) - return Z_STREAM_ERROR; - - state = (struct inflate_state FAR *)strm->state; - if (state->mode == TYPE) state->mode = TYPEDO; /* skip check */ - LOAD(); - in = have; - out = left; - ret = Z_OK; - for (;;) - switch (state->mode) { - case HEAD: - if (state->wrap == 0) { - state->mode = TYPEDO; - break; - } - NEEDBITS(16); -#ifdef GUNZIP - if ((state->wrap & 2) && hold == 0x8b1f) { /* gzip header */ - state->check = crc32(0L, Z_NULL, 0); - CRC2(state->check, hold); - INITBITS(); - state->mode = FLAGS; - break; - } - state->flags = 0; /* expect zlib header */ - if (state->head != Z_NULL) - state->head->done = -1; - if (!(state->wrap & 1) || /* check if zlib header allowed */ -#else - if ( -#endif - ((BITS(8) << 8) + (hold >> 8)) % 31) { - strm->msg = (char *)"incorrect header check"; - state->mode = BAD; - break; - } - if (BITS(4) != Z_DEFLATED) { - strm->msg = (char *)"unknown compression method"; - state->mode = BAD; - break; - } - DROPBITS(4); - len = BITS(4) + 8; - if (len > state->wbits) { - strm->msg = (char *)"invalid window size"; - state->mode = BAD; - break; - } - state->dmax = 1U << len; - Tracev((stderr, "inflate: zlib header ok\n")); - strm->adler = state->check = adler32(0L, Z_NULL, 0); - state->mode = hold & 0x200 ? DICTID : TYPE; - INITBITS(); - break; -#ifdef GUNZIP - case FLAGS: - NEEDBITS(16); - state->flags = (int)(hold); - if ((state->flags & 0xff) != Z_DEFLATED) { - strm->msg = (char *)"unknown compression method"; - state->mode = BAD; - break; - } - if (state->flags & 0xe000) { - strm->msg = (char *)"unknown header flags set"; - state->mode = BAD; - break; - } - if (state->head != Z_NULL) - state->head->text = (int)((hold >> 8) & 1); - if (state->flags & 0x0200) CRC2(state->check, hold); - INITBITS(); - state->mode = TIME; - case TIME: - NEEDBITS(32); - if (state->head != Z_NULL) - state->head->time = hold; - if (state->flags & 0x0200) CRC4(state->check, hold); - INITBITS(); - state->mode = OS; - case OS: - NEEDBITS(16); - if (state->head != Z_NULL) { - state->head->xflags = (int)(hold & 0xff); - state->head->os = (int)(hold >> 8); - } - if (state->flags & 0x0200) CRC2(state->check, hold); - INITBITS(); - state->mode = EXLEN; - case EXLEN: - if (state->flags & 0x0400) { - NEEDBITS(16); - state->length = (unsigned)(hold); - if (state->head != Z_NULL) - state->head->extra_len = (unsigned)hold; - if (state->flags & 0x0200) CRC2(state->check, hold); - INITBITS(); - } - else if (state->head != Z_NULL) - state->head->extra = Z_NULL; - state->mode = EXTRA; - case EXTRA: - if (state->flags & 0x0400) { - copy = state->length; - if (copy > have) copy = have; - if (copy) { - if (state->head != Z_NULL && - state->head->extra != Z_NULL) { - len = state->head->extra_len - state->length; - zmemcpy(state->head->extra + len, next, - len + copy > state->head->extra_max ? - state->head->extra_max - len : copy); - } - if (state->flags & 0x0200) - state->check = crc32(state->check, next, copy); - have -= copy; - next += copy; - state->length -= copy; - } - if (state->length) goto inf_leave; - } - state->length = 0; - state->mode = NAME; - case NAME: - if (state->flags & 0x0800) { - if (have == 0) goto inf_leave; - copy = 0; - do { - len = (unsigned)(next[copy++]); - if (state->head != Z_NULL && - state->head->name != Z_NULL && - state->length < state->head->name_max) - state->head->name[state->length++] = len; - } while (len && copy < have); - if (state->flags & 0x0200) - state->check = crc32(state->check, next, copy); - have -= copy; - next += copy; - if (len) goto inf_leave; - } - else if (state->head != Z_NULL) - state->head->name = Z_NULL; - state->length = 0; - state->mode = COMMENT; - case COMMENT: - if (state->flags & 0x1000) { - if (have == 0) goto inf_leave; - copy = 0; - do { - len = (unsigned)(next[copy++]); - if (state->head != Z_NULL && - state->head->comment != Z_NULL && - state->length < state->head->comm_max) - state->head->comment[state->length++] = len; - } while (len && copy < have); - if (state->flags & 0x0200) - state->check = crc32(state->check, next, copy); - have -= copy; - next += copy; - if (len) goto inf_leave; - } - else if (state->head != Z_NULL) - state->head->comment = Z_NULL; - state->mode = HCRC; - case HCRC: - if (state->flags & 0x0200) { - NEEDBITS(16); - if (hold != (state->check & 0xffff)) { - strm->msg = (char *)"header crc mismatch"; - state->mode = BAD; - break; - } - INITBITS(); - } - if (state->head != Z_NULL) { - state->head->hcrc = (int)((state->flags >> 9) & 1); - state->head->done = 1; - } - strm->adler = state->check = crc32(0L, Z_NULL, 0); - state->mode = TYPE; - break; -#endif - case DICTID: - NEEDBITS(32); - strm->adler = state->check = REVERSE(hold); - INITBITS(); - state->mode = DICT; - case DICT: - if (state->havedict == 0) { - RESTORE(); - return Z_NEED_DICT; - } - strm->adler = state->check = adler32(0L, Z_NULL, 0); - state->mode = TYPE; - case TYPE: - if (flush == Z_BLOCK) goto inf_leave; - case TYPEDO: - if (state->last) { - BYTEBITS(); - state->mode = CHECK; - break; - } - NEEDBITS(3); - state->last = BITS(1); - DROPBITS(1); - switch (BITS(2)) { - case 0: /* stored block */ - Tracev((stderr, "inflate: stored block%s\n", - state->last ? " (last)" : "")); - state->mode = STORED; - break; - case 1: /* fixed block */ - fixedtables(state); - Tracev((stderr, "inflate: fixed codes block%s\n", - state->last ? " (last)" : "")); - state->mode = LEN; /* decode codes */ - break; - case 2: /* dynamic block */ - Tracev((stderr, "inflate: dynamic codes block%s\n", - state->last ? " (last)" : "")); - state->mode = TABLE; - break; - case 3: - strm->msg = (char *)"invalid block type"; - state->mode = BAD; - } - DROPBITS(2); - break; - case STORED: - BYTEBITS(); /* go to byte boundary */ - NEEDBITS(32); - if ((hold & 0xffff) != ((hold >> 16) ^ 0xffff)) { - strm->msg = (char *)"invalid stored block lengths"; - state->mode = BAD; - break; - } - state->length = (unsigned)hold & 0xffff; - Tracev((stderr, "inflate: stored length %u\n", - state->length)); - INITBITS(); - state->mode = COPY; - case COPY: - copy = state->length; - if (copy) { - if (copy > have) copy = have; - if (copy > left) copy = left; - if (copy == 0) goto inf_leave; - zmemcpy(put, next, copy); - have -= copy; - next += copy; - left -= copy; - put += copy; - state->length -= copy; - break; - } - Tracev((stderr, "inflate: stored end\n")); - state->mode = TYPE; - break; - case TABLE: - NEEDBITS(14); - state->nlen = BITS(5) + 257; - DROPBITS(5); - state->ndist = BITS(5) + 1; - DROPBITS(5); - state->ncode = BITS(4) + 4; - DROPBITS(4); -#ifndef PKZIP_BUG_WORKAROUND - if (state->nlen > 286 || state->ndist > 30) { - strm->msg = (char *)"too many length or distance symbols"; - state->mode = BAD; - break; - } -#endif - Tracev((stderr, "inflate: table sizes ok\n")); - state->have = 0; - state->mode = LENLENS; - case LENLENS: - while (state->have < state->ncode) { - NEEDBITS(3); - state->lens[order[state->have++]] = (unsigned short)BITS(3); - DROPBITS(3); - } - while (state->have < 19) - state->lens[order[state->have++]] = 0; - state->next = state->codes; - state->lencode = (code const FAR *)(state->next); - state->lenbits = 7; - ret = inflate_table(CODES, state->lens, 19, &(state->next), - &(state->lenbits), state->work); - if (ret) { - strm->msg = (char *)"invalid code lengths set"; - state->mode = BAD; - break; - } - Tracev((stderr, "inflate: code lengths ok\n")); - state->have = 0; - state->mode = CODELENS; - case CODELENS: - while (state->have < state->nlen + state->ndist) { - for (;;) { - this = state->lencode[BITS(state->lenbits)]; - if ((unsigned)(this.bits) <= bits) break; - PULLBYTE(); - } - if (this.val < 16) { - NEEDBITS(this.bits); - DROPBITS(this.bits); - state->lens[state->have++] = this.val; - } - else { - if (this.val == 16) { - NEEDBITS(this.bits + 2); - DROPBITS(this.bits); - if (state->have == 0) { - strm->msg = (char *)"invalid bit length repeat"; - state->mode = BAD; - break; - } - len = state->lens[state->have - 1]; - copy = 3 + BITS(2); - DROPBITS(2); - } - else if (this.val == 17) { - NEEDBITS(this.bits + 3); - DROPBITS(this.bits); - len = 0; - copy = 3 + BITS(3); - DROPBITS(3); - } - else { - NEEDBITS(this.bits + 7); - DROPBITS(this.bits); - len = 0; - copy = 11 + BITS(7); - DROPBITS(7); - } - if (state->have + copy > state->nlen + state->ndist) { - strm->msg = (char *)"invalid bit length repeat"; - state->mode = BAD; - break; - } - while (copy--) - state->lens[state->have++] = (unsigned short)len; - } - } - - /* handle error breaks in while */ - if (state->mode == BAD) break; - - /* build code tables */ - state->next = state->codes; - state->lencode = (code const FAR *)(state->next); - state->lenbits = 9; - ret = inflate_table(LENS, state->lens, state->nlen, &(state->next), - &(state->lenbits), state->work); - if (ret) { - strm->msg = (char *)"invalid literal/lengths set"; - state->mode = BAD; - break; - } - state->distcode = (code const FAR *)(state->next); - state->distbits = 6; - ret = inflate_table(DISTS, state->lens + state->nlen, state->ndist, - &(state->next), &(state->distbits), state->work); - if (ret) { - strm->msg = (char *)"invalid distances set"; - state->mode = BAD; - break; - } - Tracev((stderr, "inflate: codes ok\n")); - state->mode = LEN; - case LEN: - if (have >= 6 && left >= 258) { - RESTORE(); - inflate_fast(strm, out); - LOAD(); - break; - } - for (;;) { - this = state->lencode[BITS(state->lenbits)]; - if ((unsigned)(this.bits) <= bits) break; - PULLBYTE(); - } - if (this.op && (this.op & 0xf0) == 0) { - last = this; - for (;;) { - this = state->lencode[last.val + - (BITS(last.bits + last.op) >> last.bits)]; - if ((unsigned)(last.bits + this.bits) <= bits) break; - PULLBYTE(); - } - DROPBITS(last.bits); - } - DROPBITS(this.bits); - state->length = (unsigned)this.val; - if ((int)(this.op) == 0) { - Tracevv((stderr, this.val >= 0x20 && this.val < 0x7f ? - "inflate: literal '%c'\n" : - "inflate: literal 0x%02x\n", this.val)); - state->mode = LIT; - break; - } - if (this.op & 32) { - Tracevv((stderr, "inflate: end of block\n")); - state->mode = TYPE; - break; - } - if (this.op & 64) { - strm->msg = (char *)"invalid literal/length code"; - state->mode = BAD; - break; - } - state->extra = (unsigned)(this.op) & 15; - state->mode = LENEXT; - case LENEXT: - if (state->extra) { - NEEDBITS(state->extra); - state->length += BITS(state->extra); - DROPBITS(state->extra); - } - Tracevv((stderr, "inflate: length %u\n", state->length)); - state->mode = DIST; - case DIST: - for (;;) { - this = state->distcode[BITS(state->distbits)]; - if ((unsigned)(this.bits) <= bits) break; - PULLBYTE(); - } - if ((this.op & 0xf0) == 0) { - last = this; - for (;;) { - this = state->distcode[last.val + - (BITS(last.bits + last.op) >> last.bits)]; - if ((unsigned)(last.bits + this.bits) <= bits) break; - PULLBYTE(); - } - DROPBITS(last.bits); - } - DROPBITS(this.bits); - if (this.op & 64) { - strm->msg = (char *)"invalid distance code"; - state->mode = BAD; - break; - } - state->offset = (unsigned)this.val; - state->extra = (unsigned)(this.op) & 15; - state->mode = DISTEXT; - case DISTEXT: - if (state->extra) { - NEEDBITS(state->extra); - state->offset += BITS(state->extra); - DROPBITS(state->extra); - } -#ifdef INFLATE_STRICT - if (state->offset > state->dmax) { - strm->msg = (char *)"invalid distance too far back"; - state->mode = BAD; - break; - } -#endif - if (state->offset > state->whave + out - left) { - strm->msg = (char *)"invalid distance too far back"; - state->mode = BAD; - break; - } - Tracevv((stderr, "inflate: distance %u\n", state->offset)); - state->mode = MATCH; - case MATCH: - if (left == 0) goto inf_leave; - copy = out - left; - if (state->offset > copy) { /* copy from window */ - copy = state->offset - copy; - if (copy > state->write) { - copy -= state->write; - from = state->window + (state->wsize - copy); - } - else - from = state->window + (state->write - copy); - if (copy > state->length) copy = state->length; - } - else { /* copy from output */ - from = put - state->offset; - copy = state->length; - } - if (copy > left) copy = left; - left -= copy; - state->length -= copy; - do { - *put++ = *from++; - } while (--copy); - if (state->length == 0) state->mode = LEN; - break; - case LIT: - if (left == 0) goto inf_leave; - *put++ = (unsigned char)(state->length); - left--; - state->mode = LEN; - break; - case CHECK: - if (state->wrap) { - NEEDBITS(32); - out -= left; - strm->total_out += out; - state->total += out; - if (out) - strm->adler = state->check = - UPDATE(state->check, put - out, out); - out = left; - if (( -#ifdef GUNZIP - state->flags ? hold : -#endif - REVERSE(hold)) != state->check) { - strm->msg = (char *)"incorrect data check"; - state->mode = BAD; - break; - } - INITBITS(); - Tracev((stderr, "inflate: check matches trailer\n")); - } -#ifdef GUNZIP - state->mode = LENGTH; - case LENGTH: - if (state->wrap && state->flags) { - NEEDBITS(32); - if (hold != (state->total & 0xffffffffUL)) { - strm->msg = (char *)"incorrect length check"; - state->mode = BAD; - break; - } - INITBITS(); - Tracev((stderr, "inflate: length matches trailer\n")); - } -#endif - state->mode = DONE; - case DONE: - ret = Z_STREAM_END; - goto inf_leave; - case BAD: - ret = Z_DATA_ERROR; - goto inf_leave; - case MEM: - return Z_MEM_ERROR; - case SYNC: - default: - return Z_STREAM_ERROR; - } - - /* - Return from inflate(), updating the total counts and the check value. - If there was no progress during the inflate() call, return a buffer - error. Call updatewindow() to create and/or update the window state. - Note: a memory error from inflate() is non-recoverable. - */ - inf_leave: - RESTORE(); - if (state->wsize || (state->mode < CHECK && out != strm->avail_out)) - if (updatewindow(strm, out)) { - state->mode = MEM; - return Z_MEM_ERROR; - } - in -= strm->avail_in; - out -= strm->avail_out; - strm->total_in += in; - strm->total_out += out; - state->total += out; - if (state->wrap && out) - strm->adler = state->check = - UPDATE(state->check, strm->next_out - out, out); - strm->data_type = state->bits + (state->last ? 64 : 0) + - (state->mode == TYPE ? 128 : 0); - if (((in == 0 && out == 0) || flush == Z_FINISH) && ret == Z_OK) - ret = Z_BUF_ERROR; - return ret; -} - -int ZEXPORT inflateEnd(strm) -z_streamp strm; -{ - struct inflate_state FAR *state; - if (strm == Z_NULL || strm->state == Z_NULL || strm->zfree == (free_func)0) - return Z_STREAM_ERROR; - state = (struct inflate_state FAR *)strm->state; - if (state->window != Z_NULL) ZFREE(strm, state->window); - ZFREE(strm, strm->state); - strm->state = Z_NULL; - Tracev((stderr, "inflate: end\n")); - return Z_OK; -} - -int ZEXPORT inflateSetDictionary(strm, dictionary, dictLength) -z_streamp strm; -const Bytef *dictionary; -uInt dictLength; -{ - struct inflate_state FAR *state; - unsigned long id; - - /* check state */ - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - state = (struct inflate_state FAR *)strm->state; - if (state->wrap != 0 && state->mode != DICT) - return Z_STREAM_ERROR; - - /* check for correct dictionary id */ - if (state->mode == DICT) { - id = adler32(0L, Z_NULL, 0); - id = adler32(id, dictionary, dictLength); - if (id != state->check) - return Z_DATA_ERROR; - } - - /* copy dictionary to window */ - if (updatewindow(strm, strm->avail_out)) { - state->mode = MEM; - return Z_MEM_ERROR; - } - if (dictLength > state->wsize) { - zmemcpy(state->window, dictionary + dictLength - state->wsize, - state->wsize); - state->whave = state->wsize; - } - else { - zmemcpy(state->window + state->wsize - dictLength, dictionary, - dictLength); - state->whave = dictLength; - } - state->havedict = 1; - Tracev((stderr, "inflate: dictionary set\n")); - return Z_OK; -} - -int ZEXPORT inflateGetHeader(strm, head) -z_streamp strm; -gz_headerp head; -{ - struct inflate_state FAR *state; - - /* check state */ - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - state = (struct inflate_state FAR *)strm->state; - if ((state->wrap & 2) == 0) return Z_STREAM_ERROR; - - /* save header structure */ - state->head = head; - head->done = 0; - return Z_OK; -} - -/* - Search buf[0..len-1] for the pattern: 0, 0, 0xff, 0xff. Return when found - or when out of input. When called, *have is the number of pattern bytes - found in order so far, in 0..3. On return *have is updated to the new - state. If on return *have equals four, then the pattern was found and the - return value is how many bytes were read including the last byte of the - pattern. If *have is less than four, then the pattern has not been found - yet and the return value is len. In the latter case, syncsearch() can be - called again with more data and the *have state. *have is initialized to - zero for the first call. - */ -local unsigned syncsearch(have, buf, len) -unsigned FAR *have; -unsigned char FAR *buf; -unsigned len; -{ - unsigned got; - unsigned next; - - got = *have; - next = 0; - while (next < len && got < 4) { - if ((int)(buf[next]) == (got < 2 ? 0 : 0xff)) - got++; - else if (buf[next]) - got = 0; - else - got = 4 - got; - next++; - } - *have = got; - return next; -} - -int ZEXPORT inflateSync(strm) -z_streamp strm; -{ - unsigned len; /* number of bytes to look at or looked at */ - unsigned long in, out; /* temporary to save total_in and total_out */ - unsigned char buf[4]; /* to restore bit buffer to byte string */ - struct inflate_state FAR *state; - - /* check parameters */ - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - state = (struct inflate_state FAR *)strm->state; - if (strm->avail_in == 0 && state->bits < 8) return Z_BUF_ERROR; - - /* if first time, start search in bit buffer */ - if (state->mode != SYNC) { - state->mode = SYNC; - state->hold <<= state->bits & 7; - state->bits -= state->bits & 7; - len = 0; - while (state->bits >= 8) { - buf[len++] = (unsigned char)(state->hold); - state->hold >>= 8; - state->bits -= 8; - } - state->have = 0; - syncsearch(&(state->have), buf, len); - } - - /* search available input */ - len = syncsearch(&(state->have), strm->next_in, strm->avail_in); - strm->avail_in -= len; - strm->next_in += len; - strm->total_in += len; - - /* return no joy or set up to restart inflate() on a new block */ - if (state->have != 4) return Z_DATA_ERROR; - in = strm->total_in; out = strm->total_out; - inflateReset(strm); - strm->total_in = in; strm->total_out = out; - state->mode = TYPE; - return Z_OK; -} - -/* - Returns true if inflate is currently at the end of a block generated by - Z_SYNC_FLUSH or Z_FULL_FLUSH. This function is used by one PPP - implementation to provide an additional safety check. PPP uses - Z_SYNC_FLUSH but removes the length bytes of the resulting empty stored - block. When decompressing, PPP checks that at the end of input packet, - inflate is waiting for these length bytes. - */ -int ZEXPORT inflateSyncPoint(strm) -z_streamp strm; -{ - struct inflate_state FAR *state; - - if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; - state = (struct inflate_state FAR *)strm->state; - return state->mode == STORED && state->bits == 0; -} - -int ZEXPORT inflateCopy(dest, source) -z_streamp dest; -z_streamp source; -{ - struct inflate_state FAR *state; - struct inflate_state FAR *copy; - unsigned char FAR *window; - unsigned wsize; - - /* check input */ - if (dest == Z_NULL || source == Z_NULL || source->state == Z_NULL || - source->zalloc == (alloc_func)0 || source->zfree == (free_func)0) - return Z_STREAM_ERROR; - state = (struct inflate_state FAR *)source->state; - - /* allocate space */ - copy = (struct inflate_state FAR *) - ZALLOC(source, 1, sizeof(struct inflate_state)); - if (copy == Z_NULL) return Z_MEM_ERROR; - window = Z_NULL; - if (state->window != Z_NULL) { - window = (unsigned char FAR *) - ZALLOC(source, 1U << state->wbits, sizeof(unsigned char)); - if (window == Z_NULL) { - ZFREE(source, copy); - return Z_MEM_ERROR; - } - } - - /* copy state */ - zmemcpy(dest, source, sizeof(z_stream)); - zmemcpy(copy, state, sizeof(struct inflate_state)); - if (state->lencode >= state->codes && - state->lencode <= state->codes + ENOUGH - 1) { - copy->lencode = copy->codes + (state->lencode - state->codes); - copy->distcode = copy->codes + (state->distcode - state->codes); - } - copy->next = copy->codes + (state->next - state->codes); - if (window != Z_NULL) { - wsize = 1U << state->wbits; - zmemcpy(window, state->window, wsize); - } - copy->window = window; - dest->state = (struct internal_state FAR *)copy; - return Z_OK; -} +/* inflate.c -- zlib decompression + * Copyright (C) 1995-2005 Mark Adler + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* + * Change history: + * + * 1.2.beta0 24 Nov 2002 + * - First version -- complete rewrite of inflate to simplify code, avoid + * creation of window when not needed, minimize use of window when it is + * needed, make inffast.c even faster, implement gzip decoding, and to + * improve code readability and style over the previous zlib inflate code + * + * 1.2.beta1 25 Nov 2002 + * - Use pointers for available input and output checking in inffast.c + * - Remove input and output counters in inffast.c + * - Change inffast.c entry and loop from avail_in >= 7 to >= 6 + * - Remove unnecessary second byte pull from length extra in inffast.c + * - Unroll direct copy to three copies per loop in inffast.c + * + * 1.2.beta2 4 Dec 2002 + * - Change external routine names to reduce potential conflicts + * - Correct filename to inffixed.h for fixed tables in inflate.c + * - Make hbuf[] unsigned char to match parameter type in inflate.c + * - Change strm->next_out[-state->offset] to *(strm->next_out - state->offset) + * to avoid negation problem on Alphas (64 bit) in inflate.c + * + * 1.2.beta3 22 Dec 2002 + * - Add comments on state->bits assertion in inffast.c + * - Add comments on op field in inftrees.h + * - Fix bug in reuse of allocated window after inflateReset() + * - Remove bit fields--back to byte structure for speed + * - Remove distance extra == 0 check in inflate_fast()--only helps for lengths + * - Change post-increments to pre-increments in inflate_fast(), PPC biased? + * - Add compile time option, POSTINC, to use post-increments instead (Intel?) + * - Make MATCH copy in inflate() much faster for when inflate_fast() not used + * - Use local copies of stream next and avail values, as well as local bit + * buffer and bit count in inflate()--for speed when inflate_fast() not used + * + * 1.2.beta4 1 Jan 2003 + * - Split ptr - 257 statements in inflate_table() to avoid compiler warnings + * - Move a comment on output buffer sizes from inffast.c to inflate.c + * - Add comments in inffast.c to introduce the inflate_fast() routine + * - Rearrange window copies in inflate_fast() for speed and simplification + * - Unroll last copy for window match in inflate_fast() + * - Use local copies of window variables in inflate_fast() for speed + * - Pull out common write == 0 case for speed in inflate_fast() + * - Make op and len in inflate_fast() unsigned for consistency + * - Add FAR to lcode and dcode declarations in inflate_fast() + * - Simplified bad distance check in inflate_fast() + * - Added inflateBackInit(), inflateBack(), and inflateBackEnd() in new + * source file infback.c to provide a call-back interface to inflate for + * programs like gzip and unzip -- uses window as output buffer to avoid + * window copying + * + * 1.2.beta5 1 Jan 2003 + * - Improved inflateBack() interface to allow the caller to provide initial + * input in strm. + * - Fixed stored blocks bug in inflateBack() + * + * 1.2.beta6 4 Jan 2003 + * - Added comments in inffast.c on effectiveness of POSTINC + * - Typecasting all around to reduce compiler warnings + * - Changed loops from while (1) or do {} while (1) to for (;;), again to + * make compilers happy + * - Changed type of window in inflateBackInit() to unsigned char * + * + * 1.2.beta7 27 Jan 2003 + * - Changed many types to unsigned or unsigned short to avoid warnings + * - Added inflateCopy() function + * + * 1.2.0 9 Mar 2003 + * - Changed inflateBack() interface to provide separate opaque descriptors + * for the in() and out() functions + * - Changed inflateBack() argument and in_func typedef to swap the length + * and buffer address return values for the input function + * - Check next_in and next_out for Z_NULL on entry to inflate() + * + * The history for versions after 1.2.0 are in ChangeLog in zlib distribution. + */ + +#include "zutil.h" +#include "inftrees.h" +#include "inflate.h" +#include "inffast.h" + +#ifdef MAKEFIXED +# ifndef BUILDFIXED +# define BUILDFIXED +# endif +#endif + +/* function prototypes */ +local void fixedtables OF((struct inflate_state FAR *state)); +local int updatewindow OF((z_streamp strm, unsigned out)); +#ifdef BUILDFIXED + void makefixed OF((void)); +#endif +local unsigned syncsearch OF((unsigned FAR *have, unsigned char FAR *buf, + unsigned len)); + +int ZEXPORT inflateReset(strm) +z_streamp strm; +{ + struct inflate_state FAR *state; + + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + state = (struct inflate_state FAR *)strm->state; + strm->total_in = strm->total_out = state->total = 0; + strm->msg = Z_NULL; + strm->adler = 1; /* to support ill-conceived Java test suite */ + state->mode = HEAD; + state->last = 0; + state->havedict = 0; + state->dmax = 32768U; + state->head = Z_NULL; + state->wsize = 0; + state->whave = 0; + state->write = 0; + state->hold = 0; + state->bits = 0; + state->lencode = state->distcode = state->next = state->codes; + Tracev((stderr, "inflate: reset\n")); + return Z_OK; +} + +int ZEXPORT inflatePrime(strm, bits, value) +z_streamp strm; +int bits; +int value; +{ + struct inflate_state FAR *state; + + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + state = (struct inflate_state FAR *)strm->state; + if (bits > 16 || state->bits + bits > 32) return Z_STREAM_ERROR; + value &= (1L << bits) - 1; + state->hold += value << state->bits; + state->bits += bits; + return Z_OK; +} + +int ZEXPORT inflateInit2_(strm, windowBits, version, stream_size) +z_streamp strm; +int windowBits; +const char *version; +int stream_size; +{ + struct inflate_state FAR *state; + + if (version == Z_NULL || version[0] != ZLIB_VERSION[0] || + stream_size != (int)(sizeof(z_stream))) + return Z_VERSION_ERROR; + if (strm == Z_NULL) return Z_STREAM_ERROR; + strm->msg = Z_NULL; /* in case we return an error */ + if (strm->zalloc == (alloc_func)0) { + strm->zalloc = zcalloc; + strm->opaque = (voidpf)0; + } + if (strm->zfree == (free_func)0) strm->zfree = zcfree; + state = (struct inflate_state FAR *) + ZALLOC(strm, 1, sizeof(struct inflate_state)); + if (state == Z_NULL) return Z_MEM_ERROR; + Tracev((stderr, "inflate: allocated\n")); + strm->state = (struct internal_state FAR *)state; + if (windowBits < 0) { + state->wrap = 0; + windowBits = -windowBits; + } + else { + state->wrap = (windowBits >> 4) + 1; +#ifdef GUNZIP + if (windowBits < 48) windowBits &= 15; +#endif + } + if (windowBits < 8 || windowBits > 15) { + ZFREE(strm, state); + strm->state = Z_NULL; + return Z_STREAM_ERROR; + } + state->wbits = (unsigned)windowBits; + state->window = Z_NULL; + return inflateReset(strm); +} + +int ZEXPORT inflateInit_(strm, version, stream_size) +z_streamp strm; +const char *version; +int stream_size; +{ + return inflateInit2_(strm, DEF_WBITS, version, stream_size); +} + +/* + Return state with length and distance decoding tables and index sizes set to + fixed code decoding. Normally this returns fixed tables from inffixed.h. + If BUILDFIXED is defined, then instead this routine builds the tables the + first time it's called, and returns those tables the first time and + thereafter. This reduces the size of the code by about 2K bytes, in + exchange for a little execution time. However, BUILDFIXED should not be + used for threaded applications, since the rewriting of the tables and virgin + may not be thread-safe. + */ +local void fixedtables(state) +struct inflate_state FAR *state; +{ +#ifdef BUILDFIXED + static int virgin = 1; + static code *lenfix, *distfix; + static code fixed[544]; + + /* build fixed huffman tables if first call (may not be thread safe) */ + if (virgin) { + unsigned sym, bits; + static code *next; + + /* literal/length table */ + sym = 0; + while (sym < 144) state->lens[sym++] = 8; + while (sym < 256) state->lens[sym++] = 9; + while (sym < 280) state->lens[sym++] = 7; + while (sym < 288) state->lens[sym++] = 8; + next = fixed; + lenfix = next; + bits = 9; + inflate_table(LENS, state->lens, 288, &(next), &(bits), state->work); + + /* distance table */ + sym = 0; + while (sym < 32) state->lens[sym++] = 5; + distfix = next; + bits = 5; + inflate_table(DISTS, state->lens, 32, &(next), &(bits), state->work); + + /* do this just once */ + virgin = 0; + } +#else /* !BUILDFIXED */ +# include "inffixed.h" +#endif /* BUILDFIXED */ + state->lencode = lenfix; + state->lenbits = 9; + state->distcode = distfix; + state->distbits = 5; +} + +#ifdef MAKEFIXED +#include + +/* + Write out the inffixed.h that is #include'd above. Defining MAKEFIXED also + defines BUILDFIXED, so the tables are built on the fly. makefixed() writes + those tables to stdout, which would be piped to inffixed.h. A small program + can simply call makefixed to do this: + + void makefixed(void); + + int main(void) + { + makefixed(); + return 0; + } + + Then that can be linked with zlib built with MAKEFIXED defined and run: + + a.out > inffixed.h + */ +void makefixed() +{ + unsigned low, size; + struct inflate_state state; + + fixedtables(&state); + puts(" /* inffixed.h -- table for decoding fixed codes"); + puts(" * Generated automatically by makefixed()."); + puts(" */"); + puts(""); + puts(" /* WARNING: this file should *not* be used by applications."); + puts(" It is part of the implementation of this library and is"); + puts(" subject to change. Applications should only use zlib.h."); + puts(" */"); + puts(""); + size = 1U << 9; + printf(" static const code lenfix[%u] = {", size); + low = 0; + for (;;) { + if ((low % 7) == 0) printf("\n "); + printf("{%u,%u,%d}", state.lencode[low].op, state.lencode[low].bits, + state.lencode[low].val); + if (++low == size) break; + putchar(','); + } + puts("\n };"); + size = 1U << 5; + printf("\n static const code distfix[%u] = {", size); + low = 0; + for (;;) { + if ((low % 6) == 0) printf("\n "); + printf("{%u,%u,%d}", state.distcode[low].op, state.distcode[low].bits, + state.distcode[low].val); + if (++low == size) break; + putchar(','); + } + puts("\n };"); +} +#endif /* MAKEFIXED */ + +/* + Update the window with the last wsize (normally 32K) bytes written before + returning. If window does not exist yet, create it. This is only called + when a window is already in use, or when output has been written during this + inflate call, but the end of the deflate stream has not been reached yet. + It is also called to create a window for dictionary data when a dictionary + is loaded. + + Providing output buffers larger than 32K to inflate() should provide a speed + advantage, since only the last 32K of output is copied to the sliding window + upon return from inflate(), and since all distances after the first 32K of + output will fall in the output data, making match copies simpler and faster. + The advantage may be dependent on the size of the processor's data caches. + */ +local int updatewindow(strm, out) +z_streamp strm; +unsigned out; +{ + struct inflate_state FAR *state; + unsigned copy, dist; + + state = (struct inflate_state FAR *)strm->state; + + /* if it hasn't been done already, allocate space for the window */ + if (state->window == Z_NULL) { + state->window = (unsigned char FAR *) + ZALLOC(strm, 1U << state->wbits, + sizeof(unsigned char)); + if (state->window == Z_NULL) return 1; + } + + /* if window not in use yet, initialize */ + if (state->wsize == 0) { + state->wsize = 1U << state->wbits; + state->write = 0; + state->whave = 0; + } + + /* copy state->wsize or less output bytes into the circular window */ + copy = out - strm->avail_out; + if (copy >= state->wsize) { + zmemcpy(state->window, strm->next_out - state->wsize, state->wsize); + state->write = 0; + state->whave = state->wsize; + } + else { + dist = state->wsize - state->write; + if (dist > copy) dist = copy; + zmemcpy(state->window + state->write, strm->next_out - copy, dist); + copy -= dist; + if (copy) { + zmemcpy(state->window, strm->next_out - copy, copy); + state->write = copy; + state->whave = state->wsize; + } + else { + state->write += dist; + if (state->write == state->wsize) state->write = 0; + if (state->whave < state->wsize) state->whave += dist; + } + } + return 0; +} + +/* Macros for inflate(): */ + +/* check function to use adler32() for zlib or crc32() for gzip */ +#ifdef GUNZIP +# define UPDATE(check, buf, len) \ + (state->flags ? crc32(check, buf, len) : adler32(check, buf, len)) +#else +# define UPDATE(check, buf, len) adler32(check, buf, len) +#endif + +/* check macros for header crc */ +#ifdef GUNZIP +# define CRC2(check, word) \ + do { \ + hbuf[0] = (unsigned char)(word); \ + hbuf[1] = (unsigned char)((word) >> 8); \ + check = crc32(check, hbuf, 2); \ + } while (0) + +# define CRC4(check, word) \ + do { \ + hbuf[0] = (unsigned char)(word); \ + hbuf[1] = (unsigned char)((word) >> 8); \ + hbuf[2] = (unsigned char)((word) >> 16); \ + hbuf[3] = (unsigned char)((word) >> 24); \ + check = crc32(check, hbuf, 4); \ + } while (0) +#endif + +/* Load registers with state in inflate() for speed */ +#define LOAD() \ + do { \ + put = strm->next_out; \ + left = strm->avail_out; \ + next = strm->next_in; \ + have = strm->avail_in; \ + hold = state->hold; \ + bits = state->bits; \ + } while (0) + +/* Restore state from registers in inflate() */ +#define RESTORE() \ + do { \ + strm->next_out = put; \ + strm->avail_out = left; \ + strm->next_in = next; \ + strm->avail_in = have; \ + state->hold = hold; \ + state->bits = bits; \ + } while (0) + +/* Clear the input bit accumulator */ +#define INITBITS() \ + do { \ + hold = 0; \ + bits = 0; \ + } while (0) + +/* Get a byte of input into the bit accumulator, or return from inflate() + if there is no input available. */ +#define PULLBYTE() \ + do { \ + if (have == 0) goto inf_leave; \ + have--; \ + hold += (unsigned long)(*next++) << bits; \ + bits += 8; \ + } while (0) + +/* Assure that there are at least n bits in the bit accumulator. If there is + not enough available input to do that, then return from inflate(). */ +#define NEEDBITS(n) \ + do { \ + while (bits < (unsigned)(n)) \ + PULLBYTE(); \ + } while (0) + +/* Return the low n bits of the bit accumulator (n < 16) */ +#define BITS(n) \ + ((unsigned)hold & ((1U << (n)) - 1)) + +/* Remove n bits from the bit accumulator */ +#define DROPBITS(n) \ + do { \ + hold >>= (n); \ + bits -= (unsigned)(n); \ + } while (0) + +/* Remove zero to seven bits as needed to go to a byte boundary */ +#define BYTEBITS() \ + do { \ + hold >>= bits & 7; \ + bits -= bits & 7; \ + } while (0) + +/* Reverse the bytes in a 32-bit value */ +#define REVERSE(q) \ + ((((q) >> 24) & 0xff) + (((q) >> 8) & 0xff00) + \ + (((q) & 0xff00) << 8) + (((q) & 0xff) << 24)) + +/* + inflate() uses a state machine to process as much input data and generate as + much output data as possible before returning. The state machine is + structured roughly as follows: + + for (;;) switch (state) { + ... + case STATEn: + if (not enough input data or output space to make progress) + return; + ... make progress ... + state = STATEm; + break; + ... + } + + so when inflate() is called again, the same case is attempted again, and + if the appropriate resources are provided, the machine proceeds to the + next state. The NEEDBITS() macro is usually the way the state evaluates + whether it can proceed or should return. NEEDBITS() does the return if + the requested bits are not available. The typical use of the BITS macros + is: + + NEEDBITS(n); + ... do something with BITS(n) ... + DROPBITS(n); + + where NEEDBITS(n) either returns from inflate() if there isn't enough + input left to load n bits into the accumulator, or it continues. BITS(n) + gives the low n bits in the accumulator. When done, DROPBITS(n) drops + the low n bits off the accumulator. INITBITS() clears the accumulator + and sets the number of available bits to zero. BYTEBITS() discards just + enough bits to put the accumulator on a byte boundary. After BYTEBITS() + and a NEEDBITS(8), then BITS(8) would return the next byte in the stream. + + NEEDBITS(n) uses PULLBYTE() to get an available byte of input, or to return + if there is no input available. The decoding of variable length codes uses + PULLBYTE() directly in order to pull just enough bytes to decode the next + code, and no more. + + Some states loop until they get enough input, making sure that enough + state information is maintained to continue the loop where it left off + if NEEDBITS() returns in the loop. For example, want, need, and keep + would all have to actually be part of the saved state in case NEEDBITS() + returns: + + case STATEw: + while (want < need) { + NEEDBITS(n); + keep[want++] = BITS(n); + DROPBITS(n); + } + state = STATEx; + case STATEx: + + As shown above, if the next state is also the next case, then the break + is omitted. + + A state may also return if there is not enough output space available to + complete that state. Those states are copying stored data, writing a + literal byte, and copying a matching string. + + When returning, a "goto inf_leave" is used to update the total counters, + update the check value, and determine whether any progress has been made + during that inflate() call in order to return the proper return code. + Progress is defined as a change in either strm->avail_in or strm->avail_out. + When there is a window, goto inf_leave will update the window with the last + output written. If a goto inf_leave occurs in the middle of decompression + and there is no window currently, goto inf_leave will create one and copy + output to the window for the next call of inflate(). + + In this implementation, the flush parameter of inflate() only affects the + return code (per zlib.h). inflate() always writes as much as possible to + strm->next_out, given the space available and the provided input--the effect + documented in zlib.h of Z_SYNC_FLUSH. Furthermore, inflate() always defers + the allocation of and copying into a sliding window until necessary, which + provides the effect documented in zlib.h for Z_FINISH when the entire input + stream available. So the only thing the flush parameter actually does is: + when flush is set to Z_FINISH, inflate() cannot return Z_OK. Instead it + will return Z_BUF_ERROR if it has not reached the end of the stream. + */ + +int ZEXPORT inflate(strm, flush) +z_streamp strm; +int flush; +{ + struct inflate_state FAR *state; + unsigned char FAR *next; /* next input */ + unsigned char FAR *put; /* next output */ + unsigned have, left; /* available input and output */ + unsigned long hold; /* bit buffer */ + unsigned bits; /* bits in bit buffer */ + unsigned in, out; /* save starting available input and output */ + unsigned copy; /* number of stored or match bytes to copy */ + unsigned char FAR *from; /* where to copy match bytes from */ + code this; /* current decoding table entry */ + code last; /* parent table entry */ + unsigned len; /* length to copy for repeats, bits to drop */ + int ret; /* return code */ +#ifdef GUNZIP + unsigned char hbuf[4]; /* buffer for gzip header crc calculation */ +#endif + static const unsigned short order[19] = /* permutation of code lengths */ + {16, 17, 18, 0, 8, 7, 9, 6, 10, 5, 11, 4, 12, 3, 13, 2, 14, 1, 15}; + + if (strm == Z_NULL || strm->state == Z_NULL || strm->next_out == Z_NULL || + (strm->next_in == Z_NULL && strm->avail_in != 0)) + return Z_STREAM_ERROR; + + state = (struct inflate_state FAR *)strm->state; + if (state->mode == TYPE) state->mode = TYPEDO; /* skip check */ + LOAD(); + in = have; + out = left; + ret = Z_OK; + for (;;) + switch (state->mode) { + case HEAD: + if (state->wrap == 0) { + state->mode = TYPEDO; + break; + } + NEEDBITS(16); +#ifdef GUNZIP + if ((state->wrap & 2) && hold == 0x8b1f) { /* gzip header */ + state->check = crc32(0L, Z_NULL, 0); + CRC2(state->check, hold); + INITBITS(); + state->mode = FLAGS; + break; + } + state->flags = 0; /* expect zlib header */ + if (state->head != Z_NULL) + state->head->done = -1; + if (!(state->wrap & 1) || /* check if zlib header allowed */ +#else + if ( +#endif + ((BITS(8) << 8) + (hold >> 8)) % 31) { + strm->msg = (char *)"incorrect header check"; + state->mode = BAD; + break; + } + if (BITS(4) != Z_DEFLATED) { + strm->msg = (char *)"unknown compression method"; + state->mode = BAD; + break; + } + DROPBITS(4); + len = BITS(4) + 8; + if (len > state->wbits) { + strm->msg = (char *)"invalid window size"; + state->mode = BAD; + break; + } + state->dmax = 1U << len; + Tracev((stderr, "inflate: zlib header ok\n")); + strm->adler = state->check = adler32(0L, Z_NULL, 0); + state->mode = hold & 0x200 ? DICTID : TYPE; + INITBITS(); + break; +#ifdef GUNZIP + case FLAGS: + NEEDBITS(16); + state->flags = (int)(hold); + if ((state->flags & 0xff) != Z_DEFLATED) { + strm->msg = (char *)"unknown compression method"; + state->mode = BAD; + break; + } + if (state->flags & 0xe000) { + strm->msg = (char *)"unknown header flags set"; + state->mode = BAD; + break; + } + if (state->head != Z_NULL) + state->head->text = (int)((hold >> 8) & 1); + if (state->flags & 0x0200) CRC2(state->check, hold); + INITBITS(); + state->mode = TIME; + case TIME: + NEEDBITS(32); + if (state->head != Z_NULL) + state->head->time = hold; + if (state->flags & 0x0200) CRC4(state->check, hold); + INITBITS(); + state->mode = OS; + case OS: + NEEDBITS(16); + if (state->head != Z_NULL) { + state->head->xflags = (int)(hold & 0xff); + state->head->os = (int)(hold >> 8); + } + if (state->flags & 0x0200) CRC2(state->check, hold); + INITBITS(); + state->mode = EXLEN; + case EXLEN: + if (state->flags & 0x0400) { + NEEDBITS(16); + state->length = (unsigned)(hold); + if (state->head != Z_NULL) + state->head->extra_len = (unsigned)hold; + if (state->flags & 0x0200) CRC2(state->check, hold); + INITBITS(); + } + else if (state->head != Z_NULL) + state->head->extra = Z_NULL; + state->mode = EXTRA; + case EXTRA: + if (state->flags & 0x0400) { + copy = state->length; + if (copy > have) copy = have; + if (copy) { + if (state->head != Z_NULL && + state->head->extra != Z_NULL) { + len = state->head->extra_len - state->length; + zmemcpy(state->head->extra + len, next, + len + copy > state->head->extra_max ? + state->head->extra_max - len : copy); + } + if (state->flags & 0x0200) + state->check = crc32(state->check, next, copy); + have -= copy; + next += copy; + state->length -= copy; + } + if (state->length) goto inf_leave; + } + state->length = 0; + state->mode = NAME; + case NAME: + if (state->flags & 0x0800) { + if (have == 0) goto inf_leave; + copy = 0; + do { + len = (unsigned)(next[copy++]); + if (state->head != Z_NULL && + state->head->name != Z_NULL && + state->length < state->head->name_max) + state->head->name[state->length++] = len; + } while (len && copy < have); + if (state->flags & 0x0200) + state->check = crc32(state->check, next, copy); + have -= copy; + next += copy; + if (len) goto inf_leave; + } + else if (state->head != Z_NULL) + state->head->name = Z_NULL; + state->length = 0; + state->mode = COMMENT; + case COMMENT: + if (state->flags & 0x1000) { + if (have == 0) goto inf_leave; + copy = 0; + do { + len = (unsigned)(next[copy++]); + if (state->head != Z_NULL && + state->head->comment != Z_NULL && + state->length < state->head->comm_max) + state->head->comment[state->length++] = len; + } while (len && copy < have); + if (state->flags & 0x0200) + state->check = crc32(state->check, next, copy); + have -= copy; + next += copy; + if (len) goto inf_leave; + } + else if (state->head != Z_NULL) + state->head->comment = Z_NULL; + state->mode = HCRC; + case HCRC: + if (state->flags & 0x0200) { + NEEDBITS(16); + if (hold != (state->check & 0xffff)) { + strm->msg = (char *)"header crc mismatch"; + state->mode = BAD; + break; + } + INITBITS(); + } + if (state->head != Z_NULL) { + state->head->hcrc = (int)((state->flags >> 9) & 1); + state->head->done = 1; + } + strm->adler = state->check = crc32(0L, Z_NULL, 0); + state->mode = TYPE; + break; +#endif + case DICTID: + NEEDBITS(32); + strm->adler = state->check = REVERSE(hold); + INITBITS(); + state->mode = DICT; + case DICT: + if (state->havedict == 0) { + RESTORE(); + return Z_NEED_DICT; + } + strm->adler = state->check = adler32(0L, Z_NULL, 0); + state->mode = TYPE; + case TYPE: + if (flush == Z_BLOCK) goto inf_leave; + case TYPEDO: + if (state->last) { + BYTEBITS(); + state->mode = CHECK; + break; + } + NEEDBITS(3); + state->last = BITS(1); + DROPBITS(1); + switch (BITS(2)) { + case 0: /* stored block */ + Tracev((stderr, "inflate: stored block%s\n", + state->last ? " (last)" : "")); + state->mode = STORED; + break; + case 1: /* fixed block */ + fixedtables(state); + Tracev((stderr, "inflate: fixed codes block%s\n", + state->last ? " (last)" : "")); + state->mode = LEN; /* decode codes */ + break; + case 2: /* dynamic block */ + Tracev((stderr, "inflate: dynamic codes block%s\n", + state->last ? " (last)" : "")); + state->mode = TABLE; + break; + case 3: + strm->msg = (char *)"invalid block type"; + state->mode = BAD; + } + DROPBITS(2); + break; + case STORED: + BYTEBITS(); /* go to byte boundary */ + NEEDBITS(32); + if ((hold & 0xffff) != ((hold >> 16) ^ 0xffff)) { + strm->msg = (char *)"invalid stored block lengths"; + state->mode = BAD; + break; + } + state->length = (unsigned)hold & 0xffff; + Tracev((stderr, "inflate: stored length %u\n", + state->length)); + INITBITS(); + state->mode = COPY; + case COPY: + copy = state->length; + if (copy) { + if (copy > have) copy = have; + if (copy > left) copy = left; + if (copy == 0) goto inf_leave; + zmemcpy(put, next, copy); + have -= copy; + next += copy; + left -= copy; + put += copy; + state->length -= copy; + break; + } + Tracev((stderr, "inflate: stored end\n")); + state->mode = TYPE; + break; + case TABLE: + NEEDBITS(14); + state->nlen = BITS(5) + 257; + DROPBITS(5); + state->ndist = BITS(5) + 1; + DROPBITS(5); + state->ncode = BITS(4) + 4; + DROPBITS(4); +#ifndef PKZIP_BUG_WORKAROUND + if (state->nlen > 286 || state->ndist > 30) { + strm->msg = (char *)"too many length or distance symbols"; + state->mode = BAD; + break; + } +#endif + Tracev((stderr, "inflate: table sizes ok\n")); + state->have = 0; + state->mode = LENLENS; + case LENLENS: + while (state->have < state->ncode) { + NEEDBITS(3); + state->lens[order[state->have++]] = (unsigned short)BITS(3); + DROPBITS(3); + } + while (state->have < 19) + state->lens[order[state->have++]] = 0; + state->next = state->codes; + state->lencode = (code const FAR *)(state->next); + state->lenbits = 7; + ret = inflate_table(CODES, state->lens, 19, &(state->next), + &(state->lenbits), state->work); + if (ret) { + strm->msg = (char *)"invalid code lengths set"; + state->mode = BAD; + break; + } + Tracev((stderr, "inflate: code lengths ok\n")); + state->have = 0; + state->mode = CODELENS; + case CODELENS: + while (state->have < state->nlen + state->ndist) { + for (;;) { + this = state->lencode[BITS(state->lenbits)]; + if ((unsigned)(this.bits) <= bits) break; + PULLBYTE(); + } + if (this.val < 16) { + NEEDBITS(this.bits); + DROPBITS(this.bits); + state->lens[state->have++] = this.val; + } + else { + if (this.val == 16) { + NEEDBITS(this.bits + 2); + DROPBITS(this.bits); + if (state->have == 0) { + strm->msg = (char *)"invalid bit length repeat"; + state->mode = BAD; + break; + } + len = state->lens[state->have - 1]; + copy = 3 + BITS(2); + DROPBITS(2); + } + else if (this.val == 17) { + NEEDBITS(this.bits + 3); + DROPBITS(this.bits); + len = 0; + copy = 3 + BITS(3); + DROPBITS(3); + } + else { + NEEDBITS(this.bits + 7); + DROPBITS(this.bits); + len = 0; + copy = 11 + BITS(7); + DROPBITS(7); + } + if (state->have + copy > state->nlen + state->ndist) { + strm->msg = (char *)"invalid bit length repeat"; + state->mode = BAD; + break; + } + while (copy--) + state->lens[state->have++] = (unsigned short)len; + } + } + + /* handle error breaks in while */ + if (state->mode == BAD) break; + + /* build code tables */ + state->next = state->codes; + state->lencode = (code const FAR *)(state->next); + state->lenbits = 9; + ret = inflate_table(LENS, state->lens, state->nlen, &(state->next), + &(state->lenbits), state->work); + if (ret) { + strm->msg = (char *)"invalid literal/lengths set"; + state->mode = BAD; + break; + } + state->distcode = (code const FAR *)(state->next); + state->distbits = 6; + ret = inflate_table(DISTS, state->lens + state->nlen, state->ndist, + &(state->next), &(state->distbits), state->work); + if (ret) { + strm->msg = (char *)"invalid distances set"; + state->mode = BAD; + break; + } + Tracev((stderr, "inflate: codes ok\n")); + state->mode = LEN; + case LEN: + if (have >= 6 && left >= 258) { + RESTORE(); + inflate_fast(strm, out); + LOAD(); + break; + } + for (;;) { + this = state->lencode[BITS(state->lenbits)]; + if ((unsigned)(this.bits) <= bits) break; + PULLBYTE(); + } + if (this.op && (this.op & 0xf0) == 0) { + last = this; + for (;;) { + this = state->lencode[last.val + + (BITS(last.bits + last.op) >> last.bits)]; + if ((unsigned)(last.bits + this.bits) <= bits) break; + PULLBYTE(); + } + DROPBITS(last.bits); + } + DROPBITS(this.bits); + state->length = (unsigned)this.val; + if ((int)(this.op) == 0) { + Tracevv((stderr, this.val >= 0x20 && this.val < 0x7f ? + "inflate: literal '%c'\n" : + "inflate: literal 0x%02x\n", this.val)); + state->mode = LIT; + break; + } + if (this.op & 32) { + Tracevv((stderr, "inflate: end of block\n")); + state->mode = TYPE; + break; + } + if (this.op & 64) { + strm->msg = (char *)"invalid literal/length code"; + state->mode = BAD; + break; + } + state->extra = (unsigned)(this.op) & 15; + state->mode = LENEXT; + case LENEXT: + if (state->extra) { + NEEDBITS(state->extra); + state->length += BITS(state->extra); + DROPBITS(state->extra); + } + Tracevv((stderr, "inflate: length %u\n", state->length)); + state->mode = DIST; + case DIST: + for (;;) { + this = state->distcode[BITS(state->distbits)]; + if ((unsigned)(this.bits) <= bits) break; + PULLBYTE(); + } + if ((this.op & 0xf0) == 0) { + last = this; + for (;;) { + this = state->distcode[last.val + + (BITS(last.bits + last.op) >> last.bits)]; + if ((unsigned)(last.bits + this.bits) <= bits) break; + PULLBYTE(); + } + DROPBITS(last.bits); + } + DROPBITS(this.bits); + if (this.op & 64) { + strm->msg = (char *)"invalid distance code"; + state->mode = BAD; + break; + } + state->offset = (unsigned)this.val; + state->extra = (unsigned)(this.op) & 15; + state->mode = DISTEXT; + case DISTEXT: + if (state->extra) { + NEEDBITS(state->extra); + state->offset += BITS(state->extra); + DROPBITS(state->extra); + } +#ifdef INFLATE_STRICT + if (state->offset > state->dmax) { + strm->msg = (char *)"invalid distance too far back"; + state->mode = BAD; + break; + } +#endif + if (state->offset > state->whave + out - left) { + strm->msg = (char *)"invalid distance too far back"; + state->mode = BAD; + break; + } + Tracevv((stderr, "inflate: distance %u\n", state->offset)); + state->mode = MATCH; + case MATCH: + if (left == 0) goto inf_leave; + copy = out - left; + if (state->offset > copy) { /* copy from window */ + copy = state->offset - copy; + if (copy > state->write) { + copy -= state->write; + from = state->window + (state->wsize - copy); + } + else + from = state->window + (state->write - copy); + if (copy > state->length) copy = state->length; + } + else { /* copy from output */ + from = put - state->offset; + copy = state->length; + } + if (copy > left) copy = left; + left -= copy; + state->length -= copy; + do { + *put++ = *from++; + } while (--copy); + if (state->length == 0) state->mode = LEN; + break; + case LIT: + if (left == 0) goto inf_leave; + *put++ = (unsigned char)(state->length); + left--; + state->mode = LEN; + break; + case CHECK: + if (state->wrap) { + NEEDBITS(32); + out -= left; + strm->total_out += out; + state->total += out; + if (out) + strm->adler = state->check = + UPDATE(state->check, put - out, out); + out = left; + if (( +#ifdef GUNZIP + state->flags ? hold : +#endif + REVERSE(hold)) != state->check) { + strm->msg = (char *)"incorrect data check"; + state->mode = BAD; + break; + } + INITBITS(); + Tracev((stderr, "inflate: check matches trailer\n")); + } +#ifdef GUNZIP + state->mode = LENGTH; + case LENGTH: + if (state->wrap && state->flags) { + NEEDBITS(32); + if (hold != (state->total & 0xffffffffUL)) { + strm->msg = (char *)"incorrect length check"; + state->mode = BAD; + break; + } + INITBITS(); + Tracev((stderr, "inflate: length matches trailer\n")); + } +#endif + state->mode = DONE; + case DONE: + ret = Z_STREAM_END; + goto inf_leave; + case BAD: + ret = Z_DATA_ERROR; + goto inf_leave; + case MEM: + return Z_MEM_ERROR; + case SYNC: + default: + return Z_STREAM_ERROR; + } + + /* + Return from inflate(), updating the total counts and the check value. + If there was no progress during the inflate() call, return a buffer + error. Call updatewindow() to create and/or update the window state. + Note: a memory error from inflate() is non-recoverable. + */ + inf_leave: + RESTORE(); + if (state->wsize || (state->mode < CHECK && out != strm->avail_out)) + if (updatewindow(strm, out)) { + state->mode = MEM; + return Z_MEM_ERROR; + } + in -= strm->avail_in; + out -= strm->avail_out; + strm->total_in += in; + strm->total_out += out; + state->total += out; + if (state->wrap && out) + strm->adler = state->check = + UPDATE(state->check, strm->next_out - out, out); + strm->data_type = state->bits + (state->last ? 64 : 0) + + (state->mode == TYPE ? 128 : 0); + if (((in == 0 && out == 0) || flush == Z_FINISH) && ret == Z_OK) + ret = Z_BUF_ERROR; + return ret; +} + +int ZEXPORT inflateEnd(strm) +z_streamp strm; +{ + struct inflate_state FAR *state; + if (strm == Z_NULL || strm->state == Z_NULL || strm->zfree == (free_func)0) + return Z_STREAM_ERROR; + state = (struct inflate_state FAR *)strm->state; + if (state->window != Z_NULL) ZFREE(strm, state->window); + ZFREE(strm, strm->state); + strm->state = Z_NULL; + Tracev((stderr, "inflate: end\n")); + return Z_OK; +} + +int ZEXPORT inflateSetDictionary(strm, dictionary, dictLength) +z_streamp strm; +const Bytef *dictionary; +uInt dictLength; +{ + struct inflate_state FAR *state; + unsigned long id; + + /* check state */ + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + state = (struct inflate_state FAR *)strm->state; + if (state->wrap != 0 && state->mode != DICT) + return Z_STREAM_ERROR; + + /* check for correct dictionary id */ + if (state->mode == DICT) { + id = adler32(0L, Z_NULL, 0); + id = adler32(id, dictionary, dictLength); + if (id != state->check) + return Z_DATA_ERROR; + } + + /* copy dictionary to window */ + if (updatewindow(strm, strm->avail_out)) { + state->mode = MEM; + return Z_MEM_ERROR; + } + if (dictLength > state->wsize) { + zmemcpy(state->window, dictionary + dictLength - state->wsize, + state->wsize); + state->whave = state->wsize; + } + else { + zmemcpy(state->window + state->wsize - dictLength, dictionary, + dictLength); + state->whave = dictLength; + } + state->havedict = 1; + Tracev((stderr, "inflate: dictionary set\n")); + return Z_OK; +} + +int ZEXPORT inflateGetHeader(strm, head) +z_streamp strm; +gz_headerp head; +{ + struct inflate_state FAR *state; + + /* check state */ + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + state = (struct inflate_state FAR *)strm->state; + if ((state->wrap & 2) == 0) return Z_STREAM_ERROR; + + /* save header structure */ + state->head = head; + head->done = 0; + return Z_OK; +} + +/* + Search buf[0..len-1] for the pattern: 0, 0, 0xff, 0xff. Return when found + or when out of input. When called, *have is the number of pattern bytes + found in order so far, in 0..3. On return *have is updated to the new + state. If on return *have equals four, then the pattern was found and the + return value is how many bytes were read including the last byte of the + pattern. If *have is less than four, then the pattern has not been found + yet and the return value is len. In the latter case, syncsearch() can be + called again with more data and the *have state. *have is initialized to + zero for the first call. + */ +local unsigned syncsearch(have, buf, len) +unsigned FAR *have; +unsigned char FAR *buf; +unsigned len; +{ + unsigned got; + unsigned next; + + got = *have; + next = 0; + while (next < len && got < 4) { + if ((int)(buf[next]) == (got < 2 ? 0 : 0xff)) + got++; + else if (buf[next]) + got = 0; + else + got = 4 - got; + next++; + } + *have = got; + return next; +} + +int ZEXPORT inflateSync(strm) +z_streamp strm; +{ + unsigned len; /* number of bytes to look at or looked at */ + unsigned long in, out; /* temporary to save total_in and total_out */ + unsigned char buf[4]; /* to restore bit buffer to byte string */ + struct inflate_state FAR *state; + + /* check parameters */ + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + state = (struct inflate_state FAR *)strm->state; + if (strm->avail_in == 0 && state->bits < 8) return Z_BUF_ERROR; + + /* if first time, start search in bit buffer */ + if (state->mode != SYNC) { + state->mode = SYNC; + state->hold <<= state->bits & 7; + state->bits -= state->bits & 7; + len = 0; + while (state->bits >= 8) { + buf[len++] = (unsigned char)(state->hold); + state->hold >>= 8; + state->bits -= 8; + } + state->have = 0; + syncsearch(&(state->have), buf, len); + } + + /* search available input */ + len = syncsearch(&(state->have), strm->next_in, strm->avail_in); + strm->avail_in -= len; + strm->next_in += len; + strm->total_in += len; + + /* return no joy or set up to restart inflate() on a new block */ + if (state->have != 4) return Z_DATA_ERROR; + in = strm->total_in; out = strm->total_out; + inflateReset(strm); + strm->total_in = in; strm->total_out = out; + state->mode = TYPE; + return Z_OK; +} + +/* + Returns true if inflate is currently at the end of a block generated by + Z_SYNC_FLUSH or Z_FULL_FLUSH. This function is used by one PPP + implementation to provide an additional safety check. PPP uses + Z_SYNC_FLUSH but removes the length bytes of the resulting empty stored + block. When decompressing, PPP checks that at the end of input packet, + inflate is waiting for these length bytes. + */ +int ZEXPORT inflateSyncPoint(strm) +z_streamp strm; +{ + struct inflate_state FAR *state; + + if (strm == Z_NULL || strm->state == Z_NULL) return Z_STREAM_ERROR; + state = (struct inflate_state FAR *)strm->state; + return state->mode == STORED && state->bits == 0; +} + +int ZEXPORT inflateCopy(dest, source) +z_streamp dest; +z_streamp source; +{ + struct inflate_state FAR *state; + struct inflate_state FAR *copy; + unsigned char FAR *window; + unsigned wsize; + + /* check input */ + if (dest == Z_NULL || source == Z_NULL || source->state == Z_NULL || + source->zalloc == (alloc_func)0 || source->zfree == (free_func)0) + return Z_STREAM_ERROR; + state = (struct inflate_state FAR *)source->state; + + /* allocate space */ + copy = (struct inflate_state FAR *) + ZALLOC(source, 1, sizeof(struct inflate_state)); + if (copy == Z_NULL) return Z_MEM_ERROR; + window = Z_NULL; + if (state->window != Z_NULL) { + window = (unsigned char FAR *) + ZALLOC(source, 1U << state->wbits, sizeof(unsigned char)); + if (window == Z_NULL) { + ZFREE(source, copy); + return Z_MEM_ERROR; + } + } + + /* copy state */ + zmemcpy(dest, source, sizeof(z_stream)); + zmemcpy(copy, state, sizeof(struct inflate_state)); + if (state->lencode >= state->codes && + state->lencode <= state->codes + ENOUGH - 1) { + copy->lencode = copy->codes + (state->lencode - state->codes); + copy->distcode = copy->codes + (state->distcode - state->codes); + } + copy->next = copy->codes + (state->next - state->codes); + if (window != Z_NULL) { + wsize = 1U << state->wbits; + zmemcpy(window, state->window, wsize); + } + copy->window = window; + dest->state = (struct internal_state FAR *)copy; + return Z_OK; +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inflate.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inflate.h index fbbc87143..07bd3e78a 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inflate.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inflate.h @@ -1,115 +1,115 @@ -/* inflate.h -- internal inflate state definition - * Copyright (C) 1995-2004 Mark Adler - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* WARNING: this file should *not* be used by applications. It is - part of the implementation of the compression library and is - subject to change. Applications should only use zlib.h. - */ - -/* define NO_GZIP when compiling if you want to disable gzip header and - trailer decoding by inflate(). NO_GZIP would be used to avoid linking in - the crc code when it is not needed. For shared libraries, gzip decoding - should be left enabled. */ -#ifndef NO_GZIP -# define GUNZIP -#endif - -/* Possible inflate modes between inflate() calls */ -typedef enum { - HEAD, /* i: waiting for magic header */ - FLAGS, /* i: waiting for method and flags (gzip) */ - TIME, /* i: waiting for modification time (gzip) */ - OS, /* i: waiting for extra flags and operating system (gzip) */ - EXLEN, /* i: waiting for extra length (gzip) */ - EXTRA, /* i: waiting for extra bytes (gzip) */ - NAME, /* i: waiting for end of file name (gzip) */ - COMMENT, /* i: waiting for end of comment (gzip) */ - HCRC, /* i: waiting for header crc (gzip) */ - DICTID, /* i: waiting for dictionary check value */ - DICT, /* waiting for inflateSetDictionary() call */ - TYPE, /* i: waiting for type bits, including last-flag bit */ - TYPEDO, /* i: same, but skip check to exit inflate on new block */ - STORED, /* i: waiting for stored size (length and complement) */ - COPY, /* i/o: waiting for input or output to copy stored block */ - TABLE, /* i: waiting for dynamic block table lengths */ - LENLENS, /* i: waiting for code length code lengths */ - CODELENS, /* i: waiting for length/lit and distance code lengths */ - LEN, /* i: waiting for length/lit code */ - LENEXT, /* i: waiting for length extra bits */ - DIST, /* i: waiting for distance code */ - DISTEXT, /* i: waiting for distance extra bits */ - MATCH, /* o: waiting for output space to copy string */ - LIT, /* o: waiting for output space to write literal */ - CHECK, /* i: waiting for 32-bit check value */ - LENGTH, /* i: waiting for 32-bit length (gzip) */ - DONE, /* finished check, done -- remain here until reset */ - BAD, /* got a data error -- remain here until reset */ - MEM, /* got an inflate() memory error -- remain here until reset */ - SYNC /* looking for synchronization bytes to restart inflate() */ -} inflate_mode; - -/* - State transitions between above modes - - - (most modes can go to the BAD or MEM mode -- not shown for clarity) - - Process header: - HEAD -> (gzip) or (zlib) - (gzip) -> FLAGS -> TIME -> OS -> EXLEN -> EXTRA -> NAME - NAME -> COMMENT -> HCRC -> TYPE - (zlib) -> DICTID or TYPE - DICTID -> DICT -> TYPE - Read deflate blocks: - TYPE -> STORED or TABLE or LEN or CHECK - STORED -> COPY -> TYPE - TABLE -> LENLENS -> CODELENS -> LEN - Read deflate codes: - LEN -> LENEXT or LIT or TYPE - LENEXT -> DIST -> DISTEXT -> MATCH -> LEN - LIT -> LEN - Process trailer: - CHECK -> LENGTH -> DONE - */ - -/* state maintained between inflate() calls. Approximately 7K bytes. */ -struct inflate_state { - inflate_mode mode; /* current inflate mode */ - int last; /* true if processing last block */ - int wrap; /* bit 0 true for zlib, bit 1 true for gzip */ - int havedict; /* true if dictionary provided */ - int flags; /* gzip header method and flags (0 if zlib) */ - unsigned dmax; /* zlib header max distance (INFLATE_STRICT) */ - unsigned long check; /* protected copy of check value */ - unsigned long total; /* protected copy of output count */ - gz_headerp head; /* where to save gzip header information */ - /* sliding window */ - unsigned wbits; /* log base 2 of requested window size */ - unsigned wsize; /* window size or zero if not using window */ - unsigned whave; /* valid bytes in the window */ - unsigned write; /* window write index */ - unsigned char FAR *window; /* allocated sliding window, if needed */ - /* bit accumulator */ - unsigned long hold; /* input bit accumulator */ - unsigned bits; /* number of bits in "in" */ - /* for string and stored block copying */ - unsigned length; /* literal or length of data to copy */ - unsigned offset; /* distance back to copy string from */ - /* for table and code decoding */ - unsigned extra; /* extra bits needed */ - /* fixed and dynamic code tables */ - code const FAR *lencode; /* starting table for length/literal codes */ - code const FAR *distcode; /* starting table for distance codes */ - unsigned lenbits; /* index bits for lencode */ - unsigned distbits; /* index bits for distcode */ - /* dynamic table building */ - unsigned ncode; /* number of code length code lengths */ - unsigned nlen; /* number of length code lengths */ - unsigned ndist; /* number of distance code lengths */ - unsigned have; /* number of code lengths in lens[] */ - code FAR *next; /* next available space in codes[] */ - unsigned short lens[320]; /* temporary storage for code lengths */ - unsigned short work[288]; /* work area for code table building */ - code codes[ENOUGH]; /* space for code tables */ -}; +/* inflate.h -- internal inflate state definition + * Copyright (C) 1995-2004 Mark Adler + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* WARNING: this file should *not* be used by applications. It is + part of the implementation of the compression library and is + subject to change. Applications should only use zlib.h. + */ + +/* define NO_GZIP when compiling if you want to disable gzip header and + trailer decoding by inflate(). NO_GZIP would be used to avoid linking in + the crc code when it is not needed. For shared libraries, gzip decoding + should be left enabled. */ +#ifndef NO_GZIP +# define GUNZIP +#endif + +/* Possible inflate modes between inflate() calls */ +typedef enum { + HEAD, /* i: waiting for magic header */ + FLAGS, /* i: waiting for method and flags (gzip) */ + TIME, /* i: waiting for modification time (gzip) */ + OS, /* i: waiting for extra flags and operating system (gzip) */ + EXLEN, /* i: waiting for extra length (gzip) */ + EXTRA, /* i: waiting for extra bytes (gzip) */ + NAME, /* i: waiting for end of file name (gzip) */ + COMMENT, /* i: waiting for end of comment (gzip) */ + HCRC, /* i: waiting for header crc (gzip) */ + DICTID, /* i: waiting for dictionary check value */ + DICT, /* waiting for inflateSetDictionary() call */ + TYPE, /* i: waiting for type bits, including last-flag bit */ + TYPEDO, /* i: same, but skip check to exit inflate on new block */ + STORED, /* i: waiting for stored size (length and complement) */ + COPY, /* i/o: waiting for input or output to copy stored block */ + TABLE, /* i: waiting for dynamic block table lengths */ + LENLENS, /* i: waiting for code length code lengths */ + CODELENS, /* i: waiting for length/lit and distance code lengths */ + LEN, /* i: waiting for length/lit code */ + LENEXT, /* i: waiting for length extra bits */ + DIST, /* i: waiting for distance code */ + DISTEXT, /* i: waiting for distance extra bits */ + MATCH, /* o: waiting for output space to copy string */ + LIT, /* o: waiting for output space to write literal */ + CHECK, /* i: waiting for 32-bit check value */ + LENGTH, /* i: waiting for 32-bit length (gzip) */ + DONE, /* finished check, done -- remain here until reset */ + BAD, /* got a data error -- remain here until reset */ + MEM, /* got an inflate() memory error -- remain here until reset */ + SYNC /* looking for synchronization bytes to restart inflate() */ +} inflate_mode; + +/* + State transitions between above modes - + + (most modes can go to the BAD or MEM mode -- not shown for clarity) + + Process header: + HEAD -> (gzip) or (zlib) + (gzip) -> FLAGS -> TIME -> OS -> EXLEN -> EXTRA -> NAME + NAME -> COMMENT -> HCRC -> TYPE + (zlib) -> DICTID or TYPE + DICTID -> DICT -> TYPE + Read deflate blocks: + TYPE -> STORED or TABLE or LEN or CHECK + STORED -> COPY -> TYPE + TABLE -> LENLENS -> CODELENS -> LEN + Read deflate codes: + LEN -> LENEXT or LIT or TYPE + LENEXT -> DIST -> DISTEXT -> MATCH -> LEN + LIT -> LEN + Process trailer: + CHECK -> LENGTH -> DONE + */ + +/* state maintained between inflate() calls. Approximately 7K bytes. */ +struct inflate_state { + inflate_mode mode; /* current inflate mode */ + int last; /* true if processing last block */ + int wrap; /* bit 0 true for zlib, bit 1 true for gzip */ + int havedict; /* true if dictionary provided */ + int flags; /* gzip header method and flags (0 if zlib) */ + unsigned dmax; /* zlib header max distance (INFLATE_STRICT) */ + unsigned long check; /* protected copy of check value */ + unsigned long total; /* protected copy of output count */ + gz_headerp head; /* where to save gzip header information */ + /* sliding window */ + unsigned wbits; /* log base 2 of requested window size */ + unsigned wsize; /* window size or zero if not using window */ + unsigned whave; /* valid bytes in the window */ + unsigned write; /* window write index */ + unsigned char FAR *window; /* allocated sliding window, if needed */ + /* bit accumulator */ + unsigned long hold; /* input bit accumulator */ + unsigned bits; /* number of bits in "in" */ + /* for string and stored block copying */ + unsigned length; /* literal or length of data to copy */ + unsigned offset; /* distance back to copy string from */ + /* for table and code decoding */ + unsigned extra; /* extra bits needed */ + /* fixed and dynamic code tables */ + code const FAR *lencode; /* starting table for length/literal codes */ + code const FAR *distcode; /* starting table for distance codes */ + unsigned lenbits; /* index bits for lencode */ + unsigned distbits; /* index bits for distcode */ + /* dynamic table building */ + unsigned ncode; /* number of code length code lengths */ + unsigned nlen; /* number of length code lengths */ + unsigned ndist; /* number of distance code lengths */ + unsigned have; /* number of code lengths in lens[] */ + code FAR *next; /* next available space in codes[] */ + unsigned short lens[320]; /* temporary storage for code lengths */ + unsigned short work[288]; /* work area for code table building */ + code codes[ENOUGH]; /* space for code tables */ +}; diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inftrees.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inftrees.c index 38ded81c3..8a9c13ff0 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inftrees.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inftrees.c @@ -1,329 +1,329 @@ -/* inftrees.c -- generate Huffman trees for efficient decoding - * Copyright (C) 1995-2005 Mark Adler - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -#include "zutil.h" -#include "inftrees.h" - -#define MAXBITS 15 - -const char inflate_copyright[] = - " inflate 1.2.3 Copyright 1995-2005 Mark Adler "; -/* - If you use the zlib library in a product, an acknowledgment is welcome - in the documentation of your product. If for some reason you cannot - include such an acknowledgment, I would appreciate that you keep this - copyright string in the executable of your product. - */ - -/* - Build a set of tables to decode the provided canonical Huffman code. - The code lengths are lens[0..codes-1]. The result starts at *table, - whose indices are 0..2^bits-1. work is a writable array of at least - lens shorts, which is used as a work area. type is the type of code - to be generated, CODES, LENS, or DISTS. On return, zero is success, - -1 is an invalid code, and +1 means that ENOUGH isn't enough. table - on return points to the next available entry's address. bits is the - requested root table index bits, and on return it is the actual root - table index bits. It will differ if the request is greater than the - longest code or if it is less than the shortest code. - */ -int inflate_table(type, lens, codes, table, bits, work) -codetype type; -unsigned short FAR *lens; -unsigned codes; -code FAR * FAR *table; -unsigned FAR *bits; -unsigned short FAR *work; -{ - unsigned len; /* a code's length in bits */ - unsigned sym; /* index of code symbols */ - unsigned min, max; /* minimum and maximum code lengths */ - unsigned root; /* number of index bits for root table */ - unsigned curr; /* number of index bits for current table */ - unsigned drop; /* code bits to drop for sub-table */ - int left; /* number of prefix codes available */ - unsigned used; /* code entries in table used */ - unsigned huff; /* Huffman code */ - unsigned incr; /* for incrementing code, index */ - unsigned fill; /* index for replicating entries */ - unsigned low; /* low bits for current root entry */ - unsigned mask; /* mask for low root bits */ - code this; /* table entry for duplication */ - code FAR *next; /* next available space in table */ - const unsigned short FAR *base; /* base value table to use */ - const unsigned short FAR *extra; /* extra bits table to use */ - int end; /* use base and extra for symbol > end */ - unsigned short count[MAXBITS+1]; /* number of codes of each length */ - unsigned short offs[MAXBITS+1]; /* offsets in table for each length */ - static const unsigned short lbase[31] = { /* Length codes 257..285 base */ - 3, 4, 5, 6, 7, 8, 9, 10, 11, 13, 15, 17, 19, 23, 27, 31, - 35, 43, 51, 59, 67, 83, 99, 115, 131, 163, 195, 227, 258, 0, 0}; - static const unsigned short lext[31] = { /* Length codes 257..285 extra */ - 16, 16, 16, 16, 16, 16, 16, 16, 17, 17, 17, 17, 18, 18, 18, 18, - 19, 19, 19, 19, 20, 20, 20, 20, 21, 21, 21, 21, 16, 201, 196}; - static const unsigned short dbase[32] = { /* Distance codes 0..29 base */ - 1, 2, 3, 4, 5, 7, 9, 13, 17, 25, 33, 49, 65, 97, 129, 193, - 257, 385, 513, 769, 1025, 1537, 2049, 3073, 4097, 6145, - 8193, 12289, 16385, 24577, 0, 0}; - static const unsigned short dext[32] = { /* Distance codes 0..29 extra */ - 16, 16, 16, 16, 17, 17, 18, 18, 19, 19, 20, 20, 21, 21, 22, 22, - 23, 23, 24, 24, 25, 25, 26, 26, 27, 27, - 28, 28, 29, 29, 64, 64}; - - /* - Process a set of code lengths to create a canonical Huffman code. The - code lengths are lens[0..codes-1]. Each length corresponds to the - symbols 0..codes-1. The Huffman code is generated by first sorting the - symbols by length from short to long, and retaining the symbol order - for codes with equal lengths. Then the code starts with all zero bits - for the first code of the shortest length, and the codes are integer - increments for the same length, and zeros are appended as the length - increases. For the deflate format, these bits are stored backwards - from their more natural integer increment ordering, and so when the - decoding tables are built in the large loop below, the integer codes - are incremented backwards. - - This routine assumes, but does not check, that all of the entries in - lens[] are in the range 0..MAXBITS. The caller must assure this. - 1..MAXBITS is interpreted as that code length. zero means that that - symbol does not occur in this code. - - The codes are sorted by computing a count of codes for each length, - creating from that a table of starting indices for each length in the - sorted table, and then entering the symbols in order in the sorted - table. The sorted table is work[], with that space being provided by - the caller. - - The length counts are used for other purposes as well, i.e. finding - the minimum and maximum length codes, determining if there are any - codes at all, checking for a valid set of lengths, and looking ahead - at length counts to determine sub-table sizes when building the - decoding tables. - */ - - /* accumulate lengths for codes (assumes lens[] all in 0..MAXBITS) */ - for (len = 0; len <= MAXBITS; len++) - count[len] = 0; - for (sym = 0; sym < codes; sym++) - count[lens[sym]]++; - - /* bound code lengths, force root to be within code lengths */ - root = *bits; - for (max = MAXBITS; max >= 1; max--) - if (count[max] != 0) break; - if (root > max) root = max; - if (max == 0) { /* no symbols to code at all */ - this.op = (unsigned char)64; /* invalid code marker */ - this.bits = (unsigned char)1; - this.val = (unsigned short)0; - *(*table)++ = this; /* make a table to force an error */ - *(*table)++ = this; - *bits = 1; - return 0; /* no symbols, but wait for decoding to report error */ - } - for (min = 1; min <= MAXBITS; min++) - if (count[min] != 0) break; - if (root < min) root = min; - - /* check for an over-subscribed or incomplete set of lengths */ - left = 1; - for (len = 1; len <= MAXBITS; len++) { - left <<= 1; - left -= count[len]; - if (left < 0) return -1; /* over-subscribed */ - } - if (left > 0 && (type == CODES || max != 1)) - return -1; /* incomplete set */ - - /* generate offsets into symbol table for each length for sorting */ - offs[1] = 0; - for (len = 1; len < MAXBITS; len++) - offs[len + 1] = offs[len] + count[len]; - - /* sort symbols by length, by symbol order within each length */ - for (sym = 0; sym < codes; sym++) - if (lens[sym] != 0) work[offs[lens[sym]]++] = (unsigned short)sym; - - /* - Create and fill in decoding tables. In this loop, the table being - filled is at next and has curr index bits. The code being used is huff - with length len. That code is converted to an index by dropping drop - bits off of the bottom. For codes where len is less than drop + curr, - those top drop + curr - len bits are incremented through all values to - fill the table with replicated entries. - - root is the number of index bits for the root table. When len exceeds - root, sub-tables are created pointed to by the root entry with an index - of the low root bits of huff. This is saved in low to check for when a - new sub-table should be started. drop is zero when the root table is - being filled, and drop is root when sub-tables are being filled. - - When a new sub-table is needed, it is necessary to look ahead in the - code lengths to determine what size sub-table is needed. The length - counts are used for this, and so count[] is decremented as codes are - entered in the tables. - - used keeps track of how many table entries have been allocated from the - provided *table space. It is checked when a LENS table is being made - against the space in *table, ENOUGH, minus the maximum space needed by - the worst case distance code, MAXD. This should never happen, but the - sufficiency of ENOUGH has not been proven exhaustively, hence the check. - This assumes that when type == LENS, bits == 9. - - sym increments through all symbols, and the loop terminates when - all codes of length max, i.e. all codes, have been processed. This - routine permits incomplete codes, so another loop after this one fills - in the rest of the decoding tables with invalid code markers. - */ - - /* set up for code type */ - switch (type) { - case CODES: - base = extra = work; /* dummy value--not used */ - end = 19; - break; - case LENS: - base = lbase; - base -= 257; - extra = lext; - extra -= 257; - end = 256; - break; - default: /* DISTS */ - base = dbase; - extra = dext; - end = -1; - } - - /* initialize state for loop */ - huff = 0; /* starting code */ - sym = 0; /* starting code symbol */ - len = min; /* starting code length */ - next = *table; /* current table to fill in */ - curr = root; /* current table index bits */ - drop = 0; /* current bits to drop from code for index */ - low = (unsigned)(-1); /* trigger new sub-table when len > root */ - used = 1U << root; /* use root table entries */ - mask = used - 1; /* mask for comparing low */ - - /* check available table space */ - if (type == LENS && used >= ENOUGH - MAXD) - return 1; - - /* process all codes and make table entries */ - for (;;) { - /* create table entry */ - this.bits = (unsigned char)(len - drop); - if ((int)(work[sym]) < end) { - this.op = (unsigned char)0; - this.val = work[sym]; - } - else if ((int)(work[sym]) > end) { - this.op = (unsigned char)(extra[work[sym]]); - this.val = base[work[sym]]; - } - else { - this.op = (unsigned char)(32 + 64); /* end of block */ - this.val = 0; - } - - /* replicate for those indices with low len bits equal to huff */ - incr = 1U << (len - drop); - fill = 1U << curr; - min = fill; /* save offset to next table */ - do { - fill -= incr; - next[(huff >> drop) + fill] = this; - } while (fill != 0); - - /* backwards increment the len-bit code huff */ - incr = 1U << (len - 1); - while (huff & incr) - incr >>= 1; - if (incr != 0) { - huff &= incr - 1; - huff += incr; - } - else - huff = 0; - - /* go to next symbol, update count, len */ - sym++; - if (--(count[len]) == 0) { - if (len == max) break; - len = lens[work[sym]]; - } - - /* create new sub-table if needed */ - if (len > root && (huff & mask) != low) { - /* if first time, transition to sub-tables */ - if (drop == 0) - drop = root; - - /* increment past last table */ - next += min; /* here min is 1 << curr */ - - /* determine length of next table */ - curr = len - drop; - left = (int)(1 << curr); - while (curr + drop < max) { - left -= count[curr + drop]; - if (left <= 0) break; - curr++; - left <<= 1; - } - - /* check for enough space */ - used += 1U << curr; - if (type == LENS && used >= ENOUGH - MAXD) - return 1; - - /* point entry in root table to sub-table */ - low = huff & mask; - (*table)[low].op = (unsigned char)curr; - (*table)[low].bits = (unsigned char)root; - (*table)[low].val = (unsigned short)(next - *table); - } - } - - /* - Fill in rest of table for incomplete codes. This loop is similar to the - loop above in incrementing huff for table indices. It is assumed that - len is equal to curr + drop, so there is no loop needed to increment - through high index bits. When the current sub-table is filled, the loop - drops back to the root table to fill in any remaining entries there. - */ - this.op = (unsigned char)64; /* invalid code marker */ - this.bits = (unsigned char)(len - drop); - this.val = (unsigned short)0; - while (huff != 0) { - /* when done with sub-table, drop back to root table */ - if (drop != 0 && (huff & mask) != low) { - drop = 0; - len = root; - next = *table; - this.bits = (unsigned char)len; - } - - /* put invalid code marker in table */ - next[huff >> drop] = this; - - /* backwards increment the len-bit code huff */ - incr = 1U << (len - 1); - while (huff & incr) - incr >>= 1; - if (incr != 0) { - huff &= incr - 1; - huff += incr; - } - else - huff = 0; - } - - /* set return parameters */ - *table += used; - *bits = root; - return 0; -} +/* inftrees.c -- generate Huffman trees for efficient decoding + * Copyright (C) 1995-2005 Mark Adler + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +#include "zutil.h" +#include "inftrees.h" + +#define MAXBITS 15 + +const char inflate_copyright[] = + " inflate 1.2.3 Copyright 1995-2005 Mark Adler "; +/* + If you use the zlib library in a product, an acknowledgment is welcome + in the documentation of your product. If for some reason you cannot + include such an acknowledgment, I would appreciate that you keep this + copyright string in the executable of your product. + */ + +/* + Build a set of tables to decode the provided canonical Huffman code. + The code lengths are lens[0..codes-1]. The result starts at *table, + whose indices are 0..2^bits-1. work is a writable array of at least + lens shorts, which is used as a work area. type is the type of code + to be generated, CODES, LENS, or DISTS. On return, zero is success, + -1 is an invalid code, and +1 means that ENOUGH isn't enough. table + on return points to the next available entry's address. bits is the + requested root table index bits, and on return it is the actual root + table index bits. It will differ if the request is greater than the + longest code or if it is less than the shortest code. + */ +int inflate_table(type, lens, codes, table, bits, work) +codetype type; +unsigned short FAR *lens; +unsigned codes; +code FAR * FAR *table; +unsigned FAR *bits; +unsigned short FAR *work; +{ + unsigned len; /* a code's length in bits */ + unsigned sym; /* index of code symbols */ + unsigned min, max; /* minimum and maximum code lengths */ + unsigned root; /* number of index bits for root table */ + unsigned curr; /* number of index bits for current table */ + unsigned drop; /* code bits to drop for sub-table */ + int left; /* number of prefix codes available */ + unsigned used; /* code entries in table used */ + unsigned huff; /* Huffman code */ + unsigned incr; /* for incrementing code, index */ + unsigned fill; /* index for replicating entries */ + unsigned low; /* low bits for current root entry */ + unsigned mask; /* mask for low root bits */ + code this; /* table entry for duplication */ + code FAR *next; /* next available space in table */ + const unsigned short FAR *base; /* base value table to use */ + const unsigned short FAR *extra; /* extra bits table to use */ + int end; /* use base and extra for symbol > end */ + unsigned short count[MAXBITS+1]; /* number of codes of each length */ + unsigned short offs[MAXBITS+1]; /* offsets in table for each length */ + static const unsigned short lbase[31] = { /* Length codes 257..285 base */ + 3, 4, 5, 6, 7, 8, 9, 10, 11, 13, 15, 17, 19, 23, 27, 31, + 35, 43, 51, 59, 67, 83, 99, 115, 131, 163, 195, 227, 258, 0, 0}; + static const unsigned short lext[31] = { /* Length codes 257..285 extra */ + 16, 16, 16, 16, 16, 16, 16, 16, 17, 17, 17, 17, 18, 18, 18, 18, + 19, 19, 19, 19, 20, 20, 20, 20, 21, 21, 21, 21, 16, 201, 196}; + static const unsigned short dbase[32] = { /* Distance codes 0..29 base */ + 1, 2, 3, 4, 5, 7, 9, 13, 17, 25, 33, 49, 65, 97, 129, 193, + 257, 385, 513, 769, 1025, 1537, 2049, 3073, 4097, 6145, + 8193, 12289, 16385, 24577, 0, 0}; + static const unsigned short dext[32] = { /* Distance codes 0..29 extra */ + 16, 16, 16, 16, 17, 17, 18, 18, 19, 19, 20, 20, 21, 21, 22, 22, + 23, 23, 24, 24, 25, 25, 26, 26, 27, 27, + 28, 28, 29, 29, 64, 64}; + + /* + Process a set of code lengths to create a canonical Huffman code. The + code lengths are lens[0..codes-1]. Each length corresponds to the + symbols 0..codes-1. The Huffman code is generated by first sorting the + symbols by length from short to long, and retaining the symbol order + for codes with equal lengths. Then the code starts with all zero bits + for the first code of the shortest length, and the codes are integer + increments for the same length, and zeros are appended as the length + increases. For the deflate format, these bits are stored backwards + from their more natural integer increment ordering, and so when the + decoding tables are built in the large loop below, the integer codes + are incremented backwards. + + This routine assumes, but does not check, that all of the entries in + lens[] are in the range 0..MAXBITS. The caller must assure this. + 1..MAXBITS is interpreted as that code length. zero means that that + symbol does not occur in this code. + + The codes are sorted by computing a count of codes for each length, + creating from that a table of starting indices for each length in the + sorted table, and then entering the symbols in order in the sorted + table. The sorted table is work[], with that space being provided by + the caller. + + The length counts are used for other purposes as well, i.e. finding + the minimum and maximum length codes, determining if there are any + codes at all, checking for a valid set of lengths, and looking ahead + at length counts to determine sub-table sizes when building the + decoding tables. + */ + + /* accumulate lengths for codes (assumes lens[] all in 0..MAXBITS) */ + for (len = 0; len <= MAXBITS; len++) + count[len] = 0; + for (sym = 0; sym < codes; sym++) + count[lens[sym]]++; + + /* bound code lengths, force root to be within code lengths */ + root = *bits; + for (max = MAXBITS; max >= 1; max--) + if (count[max] != 0) break; + if (root > max) root = max; + if (max == 0) { /* no symbols to code at all */ + this.op = (unsigned char)64; /* invalid code marker */ + this.bits = (unsigned char)1; + this.val = (unsigned short)0; + *(*table)++ = this; /* make a table to force an error */ + *(*table)++ = this; + *bits = 1; + return 0; /* no symbols, but wait for decoding to report error */ + } + for (min = 1; min <= MAXBITS; min++) + if (count[min] != 0) break; + if (root < min) root = min; + + /* check for an over-subscribed or incomplete set of lengths */ + left = 1; + for (len = 1; len <= MAXBITS; len++) { + left <<= 1; + left -= count[len]; + if (left < 0) return -1; /* over-subscribed */ + } + if (left > 0 && (type == CODES || max != 1)) + return -1; /* incomplete set */ + + /* generate offsets into symbol table for each length for sorting */ + offs[1] = 0; + for (len = 1; len < MAXBITS; len++) + offs[len + 1] = offs[len] + count[len]; + + /* sort symbols by length, by symbol order within each length */ + for (sym = 0; sym < codes; sym++) + if (lens[sym] != 0) work[offs[lens[sym]]++] = (unsigned short)sym; + + /* + Create and fill in decoding tables. In this loop, the table being + filled is at next and has curr index bits. The code being used is huff + with length len. That code is converted to an index by dropping drop + bits off of the bottom. For codes where len is less than drop + curr, + those top drop + curr - len bits are incremented through all values to + fill the table with replicated entries. + + root is the number of index bits for the root table. When len exceeds + root, sub-tables are created pointed to by the root entry with an index + of the low root bits of huff. This is saved in low to check for when a + new sub-table should be started. drop is zero when the root table is + being filled, and drop is root when sub-tables are being filled. + + When a new sub-table is needed, it is necessary to look ahead in the + code lengths to determine what size sub-table is needed. The length + counts are used for this, and so count[] is decremented as codes are + entered in the tables. + + used keeps track of how many table entries have been allocated from the + provided *table space. It is checked when a LENS table is being made + against the space in *table, ENOUGH, minus the maximum space needed by + the worst case distance code, MAXD. This should never happen, but the + sufficiency of ENOUGH has not been proven exhaustively, hence the check. + This assumes that when type == LENS, bits == 9. + + sym increments through all symbols, and the loop terminates when + all codes of length max, i.e. all codes, have been processed. This + routine permits incomplete codes, so another loop after this one fills + in the rest of the decoding tables with invalid code markers. + */ + + /* set up for code type */ + switch (type) { + case CODES: + base = extra = work; /* dummy value--not used */ + end = 19; + break; + case LENS: + base = lbase; + base -= 257; + extra = lext; + extra -= 257; + end = 256; + break; + default: /* DISTS */ + base = dbase; + extra = dext; + end = -1; + } + + /* initialize state for loop */ + huff = 0; /* starting code */ + sym = 0; /* starting code symbol */ + len = min; /* starting code length */ + next = *table; /* current table to fill in */ + curr = root; /* current table index bits */ + drop = 0; /* current bits to drop from code for index */ + low = (unsigned)(-1); /* trigger new sub-table when len > root */ + used = 1U << root; /* use root table entries */ + mask = used - 1; /* mask for comparing low */ + + /* check available table space */ + if (type == LENS && used >= ENOUGH - MAXD) + return 1; + + /* process all codes and make table entries */ + for (;;) { + /* create table entry */ + this.bits = (unsigned char)(len - drop); + if ((int)(work[sym]) < end) { + this.op = (unsigned char)0; + this.val = work[sym]; + } + else if ((int)(work[sym]) > end) { + this.op = (unsigned char)(extra[work[sym]]); + this.val = base[work[sym]]; + } + else { + this.op = (unsigned char)(32 + 64); /* end of block */ + this.val = 0; + } + + /* replicate for those indices with low len bits equal to huff */ + incr = 1U << (len - drop); + fill = 1U << curr; + min = fill; /* save offset to next table */ + do { + fill -= incr; + next[(huff >> drop) + fill] = this; + } while (fill != 0); + + /* backwards increment the len-bit code huff */ + incr = 1U << (len - 1); + while (huff & incr) + incr >>= 1; + if (incr != 0) { + huff &= incr - 1; + huff += incr; + } + else + huff = 0; + + /* go to next symbol, update count, len */ + sym++; + if (--(count[len]) == 0) { + if (len == max) break; + len = lens[work[sym]]; + } + + /* create new sub-table if needed */ + if (len > root && (huff & mask) != low) { + /* if first time, transition to sub-tables */ + if (drop == 0) + drop = root; + + /* increment past last table */ + next += min; /* here min is 1 << curr */ + + /* determine length of next table */ + curr = len - drop; + left = (int)(1 << curr); + while (curr + drop < max) { + left -= count[curr + drop]; + if (left <= 0) break; + curr++; + left <<= 1; + } + + /* check for enough space */ + used += 1U << curr; + if (type == LENS && used >= ENOUGH - MAXD) + return 1; + + /* point entry in root table to sub-table */ + low = huff & mask; + (*table)[low].op = (unsigned char)curr; + (*table)[low].bits = (unsigned char)root; + (*table)[low].val = (unsigned short)(next - *table); + } + } + + /* + Fill in rest of table for incomplete codes. This loop is similar to the + loop above in incrementing huff for table indices. It is assumed that + len is equal to curr + drop, so there is no loop needed to increment + through high index bits. When the current sub-table is filled, the loop + drops back to the root table to fill in any remaining entries there. + */ + this.op = (unsigned char)64; /* invalid code marker */ + this.bits = (unsigned char)(len - drop); + this.val = (unsigned short)0; + while (huff != 0) { + /* when done with sub-table, drop back to root table */ + if (drop != 0 && (huff & mask) != low) { + drop = 0; + len = root; + next = *table; + this.bits = (unsigned char)len; + } + + /* put invalid code marker in table */ + next[huff >> drop] = this; + + /* backwards increment the len-bit code huff */ + incr = 1U << (len - 1); + while (huff & incr) + incr >>= 1; + if (incr != 0) { + huff &= incr - 1; + huff += incr; + } + else + huff = 0; + } + + /* set return parameters */ + *table += used; + *bits = root; + return 0; +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inftrees.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inftrees.h index dc0fd567e..b1104c87e 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inftrees.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/inftrees.h @@ -1,55 +1,55 @@ -/* inftrees.h -- header to use inftrees.c - * Copyright (C) 1995-2005 Mark Adler - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* WARNING: this file should *not* be used by applications. It is - part of the implementation of the compression library and is - subject to change. Applications should only use zlib.h. - */ - -/* Structure for decoding tables. Each entry provides either the - information needed to do the operation requested by the code that - indexed that table entry, or it provides a pointer to another - table that indexes more bits of the code. op indicates whether - the entry is a pointer to another table, a literal, a length or - distance, an end-of-block, or an invalid code. For a table - pointer, the low four bits of op is the number of index bits of - that table. For a length or distance, the low four bits of op - is the number of extra bits to get after the code. bits is - the number of bits in this code or part of the code to drop off - of the bit buffer. val is the actual byte to output in the case - of a literal, the base length or distance, or the offset from - the current table to the next table. Each entry is four bytes. */ -typedef struct { - unsigned char op; /* operation, extra bits, table bits */ - unsigned char bits; /* bits in this part of the code */ - unsigned short val; /* offset in table or code value */ -} code; - -/* op values as set by inflate_table(): - 00000000 - literal - 0000tttt - table link, tttt != 0 is the number of table index bits - 0001eeee - length or distance, eeee is the number of extra bits - 01100000 - end of block - 01000000 - invalid code - */ - -/* Maximum size of dynamic tree. The maximum found in a long but non- - exhaustive search was 1444 code structures (852 for length/literals - and 592 for distances, the latter actually the result of an - exhaustive search). The true maximum is not known, but the value - below is more than safe. */ -#define ENOUGH 2048 -#define MAXD 592 - -/* Type of code to build for inftable() */ -typedef enum { - CODES, - LENS, - DISTS -} codetype; - -extern int inflate_table OF((codetype type, unsigned short FAR *lens, - unsigned codes, code FAR * FAR *table, - unsigned FAR *bits, unsigned short FAR *work)); +/* inftrees.h -- header to use inftrees.c + * Copyright (C) 1995-2005 Mark Adler + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* WARNING: this file should *not* be used by applications. It is + part of the implementation of the compression library and is + subject to change. Applications should only use zlib.h. + */ + +/* Structure for decoding tables. Each entry provides either the + information needed to do the operation requested by the code that + indexed that table entry, or it provides a pointer to another + table that indexes more bits of the code. op indicates whether + the entry is a pointer to another table, a literal, a length or + distance, an end-of-block, or an invalid code. For a table + pointer, the low four bits of op is the number of index bits of + that table. For a length or distance, the low four bits of op + is the number of extra bits to get after the code. bits is + the number of bits in this code or part of the code to drop off + of the bit buffer. val is the actual byte to output in the case + of a literal, the base length or distance, or the offset from + the current table to the next table. Each entry is four bytes. */ +typedef struct { + unsigned char op; /* operation, extra bits, table bits */ + unsigned char bits; /* bits in this part of the code */ + unsigned short val; /* offset in table or code value */ +} code; + +/* op values as set by inflate_table(): + 00000000 - literal + 0000tttt - table link, tttt != 0 is the number of table index bits + 0001eeee - length or distance, eeee is the number of extra bits + 01100000 - end of block + 01000000 - invalid code + */ + +/* Maximum size of dynamic tree. The maximum found in a long but non- + exhaustive search was 1444 code structures (852 for length/literals + and 592 for distances, the latter actually the result of an + exhaustive search). The true maximum is not known, but the value + below is more than safe. */ +#define ENOUGH 2048 +#define MAXD 592 + +/* Type of code to build for inftable() */ +typedef enum { + CODES, + LENS, + DISTS +} codetype; + +extern int inflate_table OF((codetype type, unsigned short FAR *lens, + unsigned codes, code FAR * FAR *table, + unsigned FAR *bits, unsigned short FAR *work)); diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/minigzip.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/minigzip.c index 41996dbc9..4524b96a1 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/minigzip.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/minigzip.c @@ -1,322 +1,322 @@ -/* minigzip.c -- simulate gzip using the zlib compression library - * Copyright (C) 1995-2005 Jean-loup Gailly. - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* - * minigzip is a minimal implementation of the gzip utility. This is - * only an example of using zlib and isn't meant to replace the - * full-featured gzip. No attempt is made to deal with file systems - * limiting names to 14 or 8+3 characters, etc... Error checking is - * very limited. So use minigzip only for testing; use gzip for the - * real thing. On MSDOS, use only on file names without extension - * or in pipe mode. - */ - -/* @(#) $Id$ */ - -#include -#include "zlib.h" - -#ifdef STDC -# include -# include -#endif - -#ifdef USE_MMAP -# include -# include -# include -#endif - -#if defined(MSDOS) || defined(OS2) || defined(WIN32) || defined(__CYGWIN__) -# include -# include -# define SET_BINARY_MODE(file) setmode(fileno(file), O_BINARY) -#else -# define SET_BINARY_MODE(file) -#endif - -#ifdef VMS -# define unlink delete -# define GZ_SUFFIX "-gz" -#endif -#ifdef RISCOS -# define unlink remove -# define GZ_SUFFIX "-gz" -# define fileno(file) file->__file -#endif -#if defined(__MWERKS__) && __dest_os != __be_os && __dest_os != __win32_os -# include /* for fileno */ -#endif - -#ifndef WIN32 /* unlink already in stdio.h for WIN32 */ - extern int unlink OF((const char *)); -#endif - -#ifndef GZ_SUFFIX -# define GZ_SUFFIX ".gz" -#endif -#define SUFFIX_LEN (sizeof(GZ_SUFFIX)-1) - -#define BUFLEN 16384 -#define MAX_NAME_LEN 1024 - -#ifdef MAXSEG_64K -# define local static - /* Needed for systems with limitation on stack size. */ -#else -# define local -#endif - -char *prog; - -void error OF((const char *msg)); -void gz_compress OF((FILE *in, gzFile out)); -#ifdef USE_MMAP -int gz_compress_mmap OF((FILE *in, gzFile out)); -#endif -void gz_uncompress OF((gzFile in, FILE *out)); -void file_compress OF((char *file, char *mode)); -void file_uncompress OF((char *file)); -int main OF((int argc, char *argv[])); - -/* =========================================================================== - * Display error message and exit - */ -void error(msg) - const char *msg; -{ - fprintf(stderr, "%s: %s\n", prog, msg); - exit(1); -} - -/* =========================================================================== - * Compress input to output then close both files. - */ - -void gz_compress(in, out) - FILE *in; - gzFile out; -{ - local char buf[BUFLEN]; - int len; - int err; - -#ifdef USE_MMAP - /* Try first compressing with mmap. If mmap fails (minigzip used in a - * pipe), use the normal fread loop. - */ - if (gz_compress_mmap(in, out) == Z_OK) return; -#endif - for (;;) { - len = (int)fread(buf, 1, sizeof(buf), in); - if (ferror(in)) { - perror("fread"); - exit(1); - } - if (len == 0) break; - - if (gzwrite(out, buf, (unsigned)len) != len) error(gzerror(out, &err)); - } - fclose(in); - if (gzclose(out) != Z_OK) error("failed gzclose"); -} - -#ifdef USE_MMAP /* MMAP version, Miguel Albrecht */ - -/* Try compressing the input file at once using mmap. Return Z_OK if - * if success, Z_ERRNO otherwise. - */ -int gz_compress_mmap(in, out) - FILE *in; - gzFile out; -{ - int len; - int err; - int ifd = fileno(in); - caddr_t buf; /* mmap'ed buffer for the entire input file */ - off_t buf_len; /* length of the input file */ - struct stat sb; - - /* Determine the size of the file, needed for mmap: */ - if (fstat(ifd, &sb) < 0) return Z_ERRNO; - buf_len = sb.st_size; - if (buf_len <= 0) return Z_ERRNO; - - /* Now do the actual mmap: */ - buf = mmap((caddr_t) 0, buf_len, PROT_READ, MAP_SHARED, ifd, (off_t)0); - if (buf == (caddr_t)(-1)) return Z_ERRNO; - - /* Compress the whole file at once: */ - len = gzwrite(out, (char *)buf, (unsigned)buf_len); - - if (len != (int)buf_len) error(gzerror(out, &err)); - - munmap(buf, buf_len); - fclose(in); - if (gzclose(out) != Z_OK) error("failed gzclose"); - return Z_OK; -} -#endif /* USE_MMAP */ - -/* =========================================================================== - * Uncompress input to output then close both files. - */ -void gz_uncompress(in, out) - gzFile in; - FILE *out; -{ - local char buf[BUFLEN]; - int len; - int err; - - for (;;) { - len = gzread(in, buf, sizeof(buf)); - if (len < 0) error (gzerror(in, &err)); - if (len == 0) break; - - if ((int)fwrite(buf, 1, (unsigned)len, out) != len) { - error("failed fwrite"); - } - } - if (fclose(out)) error("failed fclose"); - - if (gzclose(in) != Z_OK) error("failed gzclose"); -} - - -/* =========================================================================== - * Compress the given file: create a corresponding .gz file and remove the - * original. - */ -void file_compress(file, mode) - char *file; - char *mode; -{ - local char outfile[MAX_NAME_LEN]; - FILE *in; - gzFile out; - - strcpy(outfile, file); - strcat(outfile, GZ_SUFFIX); - - in = fopen(file, "rb"); - if (in == NULL) { - perror(file); - exit(1); - } - out = gzopen(outfile, mode); - if (out == NULL) { - fprintf(stderr, "%s: can't gzopen %s\n", prog, outfile); - exit(1); - } - gz_compress(in, out); - - unlink(file); -} - - -/* =========================================================================== - * Uncompress the given file and remove the original. - */ -void file_uncompress(file) - char *file; -{ - local char buf[MAX_NAME_LEN]; - char *infile, *outfile; - FILE *out; - gzFile in; - uInt len = (uInt)strlen(file); - - strcpy(buf, file); - - if (len > SUFFIX_LEN && strcmp(file+len-SUFFIX_LEN, GZ_SUFFIX) == 0) { - infile = file; - outfile = buf; - outfile[len-3] = '\0'; - } else { - outfile = file; - infile = buf; - strcat(infile, GZ_SUFFIX); - } - in = gzopen(infile, "rb"); - if (in == NULL) { - fprintf(stderr, "%s: can't gzopen %s\n", prog, infile); - exit(1); - } - out = fopen(outfile, "wb"); - if (out == NULL) { - perror(file); - exit(1); - } - - gz_uncompress(in, out); - - unlink(infile); -} - - -/* =========================================================================== - * Usage: minigzip [-d] [-f] [-h] [-r] [-1 to -9] [files...] - * -d : decompress - * -f : compress with Z_FILTERED - * -h : compress with Z_HUFFMAN_ONLY - * -r : compress with Z_RLE - * -1 to -9 : compression level - */ - -int main(argc, argv) - int argc; - char *argv[]; -{ - int uncompr = 0; - gzFile file; - char outmode[20]; - - strcpy(outmode, "wb6 "); - - prog = argv[0]; - argc--, argv++; - - while (argc > 0) { - if (strcmp(*argv, "-d") == 0) - uncompr = 1; - else if (strcmp(*argv, "-f") == 0) - outmode[3] = 'f'; - else if (strcmp(*argv, "-h") == 0) - outmode[3] = 'h'; - else if (strcmp(*argv, "-r") == 0) - outmode[3] = 'R'; - else if ((*argv)[0] == '-' && (*argv)[1] >= '1' && (*argv)[1] <= '9' && - (*argv)[2] == 0) - outmode[2] = (*argv)[1]; - else - break; - argc--, argv++; - } - if (outmode[3] == ' ') - outmode[3] = 0; - if (argc == 0) { - SET_BINARY_MODE(stdin); - SET_BINARY_MODE(stdout); - if (uncompr) { - file = gzdopen(fileno(stdin), "rb"); - if (file == NULL) error("can't gzdopen stdin"); - gz_uncompress(file, stdout); - } else { - file = gzdopen(fileno(stdout), outmode); - if (file == NULL) error("can't gzdopen stdout"); - gz_compress(stdin, file); - } - } else { - do { - if (uncompr) { - file_uncompress(*argv); - } else { - file_compress(*argv, outmode); - } - } while (argv++, --argc); - } - return 0; -} +/* minigzip.c -- simulate gzip using the zlib compression library + * Copyright (C) 1995-2005 Jean-loup Gailly. + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* + * minigzip is a minimal implementation of the gzip utility. This is + * only an example of using zlib and isn't meant to replace the + * full-featured gzip. No attempt is made to deal with file systems + * limiting names to 14 or 8+3 characters, etc... Error checking is + * very limited. So use minigzip only for testing; use gzip for the + * real thing. On MSDOS, use only on file names without extension + * or in pipe mode. + */ + +/* @(#) $Id$ */ + +#include +#include "zlib.h" + +#ifdef STDC +# include +# include +#endif + +#ifdef USE_MMAP +# include +# include +# include +#endif + +#if defined(MSDOS) || defined(OS2) || defined(WIN32) || defined(__CYGWIN__) +# include +# include +# define SET_BINARY_MODE(file) setmode(fileno(file), O_BINARY) +#else +# define SET_BINARY_MODE(file) +#endif + +#ifdef VMS +# define unlink delete +# define GZ_SUFFIX "-gz" +#endif +#ifdef RISCOS +# define unlink remove +# define GZ_SUFFIX "-gz" +# define fileno(file) file->__file +#endif +#if defined(__MWERKS__) && __dest_os != __be_os && __dest_os != __win32_os +# include /* for fileno */ +#endif + +#ifndef WIN32 /* unlink already in stdio.h for WIN32 */ + extern int unlink OF((const char *)); +#endif + +#ifndef GZ_SUFFIX +# define GZ_SUFFIX ".gz" +#endif +#define SUFFIX_LEN (sizeof(GZ_SUFFIX)-1) + +#define BUFLEN 16384 +#define MAX_NAME_LEN 1024 + +#ifdef MAXSEG_64K +# define local static + /* Needed for systems with limitation on stack size. */ +#else +# define local +#endif + +char *prog; + +void error OF((const char *msg)); +void gz_compress OF((FILE *in, gzFile out)); +#ifdef USE_MMAP +int gz_compress_mmap OF((FILE *in, gzFile out)); +#endif +void gz_uncompress OF((gzFile in, FILE *out)); +void file_compress OF((char *file, char *mode)); +void file_uncompress OF((char *file)); +int main OF((int argc, char *argv[])); + +/* =========================================================================== + * Display error message and exit + */ +void error(msg) + const char *msg; +{ + fprintf(stderr, "%s: %s\n", prog, msg); + exit(1); +} + +/* =========================================================================== + * Compress input to output then close both files. + */ + +void gz_compress(in, out) + FILE *in; + gzFile out; +{ + local char buf[BUFLEN]; + int len; + int err; + +#ifdef USE_MMAP + /* Try first compressing with mmap. If mmap fails (minigzip used in a + * pipe), use the normal fread loop. + */ + if (gz_compress_mmap(in, out) == Z_OK) return; +#endif + for (;;) { + len = (int)fread(buf, 1, sizeof(buf), in); + if (ferror(in)) { + perror("fread"); + exit(1); + } + if (len == 0) break; + + if (gzwrite(out, buf, (unsigned)len) != len) error(gzerror(out, &err)); + } + fclose(in); + if (gzclose(out) != Z_OK) error("failed gzclose"); +} + +#ifdef USE_MMAP /* MMAP version, Miguel Albrecht */ + +/* Try compressing the input file at once using mmap. Return Z_OK if + * if success, Z_ERRNO otherwise. + */ +int gz_compress_mmap(in, out) + FILE *in; + gzFile out; +{ + int len; + int err; + int ifd = fileno(in); + caddr_t buf; /* mmap'ed buffer for the entire input file */ + off_t buf_len; /* length of the input file */ + struct stat sb; + + /* Determine the size of the file, needed for mmap: */ + if (fstat(ifd, &sb) < 0) return Z_ERRNO; + buf_len = sb.st_size; + if (buf_len <= 0) return Z_ERRNO; + + /* Now do the actual mmap: */ + buf = mmap((caddr_t) 0, buf_len, PROT_READ, MAP_SHARED, ifd, (off_t)0); + if (buf == (caddr_t)(-1)) return Z_ERRNO; + + /* Compress the whole file at once: */ + len = gzwrite(out, (char *)buf, (unsigned)buf_len); + + if (len != (int)buf_len) error(gzerror(out, &err)); + + munmap(buf, buf_len); + fclose(in); + if (gzclose(out) != Z_OK) error("failed gzclose"); + return Z_OK; +} +#endif /* USE_MMAP */ + +/* =========================================================================== + * Uncompress input to output then close both files. + */ +void gz_uncompress(in, out) + gzFile in; + FILE *out; +{ + local char buf[BUFLEN]; + int len; + int err; + + for (;;) { + len = gzread(in, buf, sizeof(buf)); + if (len < 0) error (gzerror(in, &err)); + if (len == 0) break; + + if ((int)fwrite(buf, 1, (unsigned)len, out) != len) { + error("failed fwrite"); + } + } + if (fclose(out)) error("failed fclose"); + + if (gzclose(in) != Z_OK) error("failed gzclose"); +} + + +/* =========================================================================== + * Compress the given file: create a corresponding .gz file and remove the + * original. + */ +void file_compress(file, mode) + char *file; + char *mode; +{ + local char outfile[MAX_NAME_LEN]; + FILE *in; + gzFile out; + + strcpy(outfile, file); + strcat(outfile, GZ_SUFFIX); + + in = fopen(file, "rb"); + if (in == NULL) { + perror(file); + exit(1); + } + out = gzopen(outfile, mode); + if (out == NULL) { + fprintf(stderr, "%s: can't gzopen %s\n", prog, outfile); + exit(1); + } + gz_compress(in, out); + + unlink(file); +} + + +/* =========================================================================== + * Uncompress the given file and remove the original. + */ +void file_uncompress(file) + char *file; +{ + local char buf[MAX_NAME_LEN]; + char *infile, *outfile; + FILE *out; + gzFile in; + uInt len = (uInt)strlen(file); + + strcpy(buf, file); + + if (len > SUFFIX_LEN && strcmp(file+len-SUFFIX_LEN, GZ_SUFFIX) == 0) { + infile = file; + outfile = buf; + outfile[len-3] = '\0'; + } else { + outfile = file; + infile = buf; + strcat(infile, GZ_SUFFIX); + } + in = gzopen(infile, "rb"); + if (in == NULL) { + fprintf(stderr, "%s: can't gzopen %s\n", prog, infile); + exit(1); + } + out = fopen(outfile, "wb"); + if (out == NULL) { + perror(file); + exit(1); + } + + gz_uncompress(in, out); + + unlink(infile); +} + + +/* =========================================================================== + * Usage: minigzip [-d] [-f] [-h] [-r] [-1 to -9] [files...] + * -d : decompress + * -f : compress with Z_FILTERED + * -h : compress with Z_HUFFMAN_ONLY + * -r : compress with Z_RLE + * -1 to -9 : compression level + */ + +int main(argc, argv) + int argc; + char *argv[]; +{ + int uncompr = 0; + gzFile file; + char outmode[20]; + + strcpy(outmode, "wb6 "); + + prog = argv[0]; + argc--, argv++; + + while (argc > 0) { + if (strcmp(*argv, "-d") == 0) + uncompr = 1; + else if (strcmp(*argv, "-f") == 0) + outmode[3] = 'f'; + else if (strcmp(*argv, "-h") == 0) + outmode[3] = 'h'; + else if (strcmp(*argv, "-r") == 0) + outmode[3] = 'R'; + else if ((*argv)[0] == '-' && (*argv)[1] >= '1' && (*argv)[1] <= '9' && + (*argv)[2] == 0) + outmode[2] = (*argv)[1]; + else + break; + argc--, argv++; + } + if (outmode[3] == ' ') + outmode[3] = 0; + if (argc == 0) { + SET_BINARY_MODE(stdin); + SET_BINARY_MODE(stdout); + if (uncompr) { + file = gzdopen(fileno(stdin), "rb"); + if (file == NULL) error("can't gzdopen stdin"); + gz_uncompress(file, stdout); + } else { + file = gzdopen(fileno(stdout), outmode); + if (file == NULL) error("can't gzdopen stdout"); + gz_compress(stdin, file); + } + } else { + do { + if (uncompr) { + file_uncompress(*argv); + } else { + file_compress(*argv, outmode); + } + } while (argv++, --argc); + } + return 0; +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/trees.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/trees.c index 7a0480286..395e4e168 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/trees.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/trees.c @@ -1,1219 +1,1219 @@ -/* trees.c -- output deflated data using Huffman coding - * Copyright (C) 1995-2005 Jean-loup Gailly - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* - * ALGORITHM - * - * The "deflation" process uses several Huffman trees. The more - * common source values are represented by shorter bit sequences. - * - * Each code tree is stored in a compressed form which is itself - * a Huffman encoding of the lengths of all the code strings (in - * ascending order by source values). The actual code strings are - * reconstructed from the lengths in the inflate process, as described - * in the deflate specification. - * - * REFERENCES - * - * Deutsch, L.P.,"'Deflate' Compressed Data Format Specification". - * Available in ftp.uu.net:/pub/archiving/zip/doc/deflate-1.1.doc - * - * Storer, James A. - * Data Compression: Methods and Theory, pp. 49-50. - * Computer Science Press, 1988. ISBN 0-7167-8156-5. - * - * Sedgewick, R. - * Algorithms, p290. - * Addison-Wesley, 1983. ISBN 0-201-06672-6. - */ - -/* @(#) $Id$ */ - -/* #define GEN_TREES_H */ - -#include "deflate.h" - -#ifdef DEBUG -# include -#endif - -/* =========================================================================== - * Constants - */ - -#define MAX_BL_BITS 7 -/* Bit length codes must not exceed MAX_BL_BITS bits */ - -#define END_BLOCK 256 -/* end of block literal code */ - -#define REP_3_6 16 -/* repeat previous bit length 3-6 times (2 bits of repeat count) */ - -#define REPZ_3_10 17 -/* repeat a zero length 3-10 times (3 bits of repeat count) */ - -#define REPZ_11_138 18 -/* repeat a zero length 11-138 times (7 bits of repeat count) */ - -local const int extra_lbits[LENGTH_CODES] /* extra bits for each length code */ - = {0,0,0,0,0,0,0,0,1,1,1,1,2,2,2,2,3,3,3,3,4,4,4,4,5,5,5,5,0}; - -local const int extra_dbits[D_CODES] /* extra bits for each distance code */ - = {0,0,0,0,1,1,2,2,3,3,4,4,5,5,6,6,7,7,8,8,9,9,10,10,11,11,12,12,13,13}; - -local const int extra_blbits[BL_CODES]/* extra bits for each bit length code */ - = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,2,3,7}; - -local const uch bl_order[BL_CODES] - = {16,17,18,0,8,7,9,6,10,5,11,4,12,3,13,2,14,1,15}; -/* The lengths of the bit length codes are sent in order of decreasing - * probability, to avoid transmitting the lengths for unused bit length codes. - */ - -#define Buf_size (8 * 2*sizeof(char)) -/* Number of bits used within bi_buf. (bi_buf might be implemented on - * more than 16 bits on some systems.) - */ - -/* =========================================================================== - * Local data. These are initialized only once. - */ - -#define DIST_CODE_LEN 512 /* see definition of array dist_code below */ - -#if defined(GEN_TREES_H) || !defined(STDC) -/* non ANSI compilers may not accept trees.h */ - -local ct_data static_ltree[L_CODES+2]; -/* The static literal tree. Since the bit lengths are imposed, there is no - * need for the L_CODES extra codes used during heap construction. However - * The codes 286 and 287 are needed to build a canonical tree (see _tr_init - * below). - */ - -local ct_data static_dtree[D_CODES]; -/* The static distance tree. (Actually a trivial tree since all codes use - * 5 bits.) - */ - -uch _dist_code[DIST_CODE_LEN]; -/* Distance codes. The first 256 values correspond to the distances - * 3 .. 258, the last 256 values correspond to the top 8 bits of - * the 15 bit distances. - */ - -uch _length_code[MAX_MATCH-MIN_MATCH+1]; -/* length code for each normalized match length (0 == MIN_MATCH) */ - -local int base_length[LENGTH_CODES]; -/* First normalized length for each code (0 = MIN_MATCH) */ - -local int base_dist[D_CODES]; -/* First normalized distance for each code (0 = distance of 1) */ - -#else -# include "trees.h" -#endif /* GEN_TREES_H */ - -struct static_tree_desc_s { - const ct_data *static_tree; /* static tree or NULL */ - const intf *extra_bits; /* extra bits for each code or NULL */ - int extra_base; /* base index for extra_bits */ - int elems; /* max number of elements in the tree */ - int max_length; /* max bit length for the codes */ -}; - -local static_tree_desc static_l_desc = -{static_ltree, extra_lbits, LITERALS+1, L_CODES, MAX_BITS}; - -local static_tree_desc static_d_desc = -{static_dtree, extra_dbits, 0, D_CODES, MAX_BITS}; - -local static_tree_desc static_bl_desc = -{(const ct_data *)0, extra_blbits, 0, BL_CODES, MAX_BL_BITS}; - -/* =========================================================================== - * Local (static) routines in this file. - */ - -local void tr_static_init OF((void)); -local void init_block OF((deflate_state *s)); -local void pqdownheap OF((deflate_state *s, ct_data *tree, int k)); -local void gen_bitlen OF((deflate_state *s, tree_desc *desc)); -local void gen_codes OF((ct_data *tree, int max_code, ushf *bl_count)); -local void build_tree OF((deflate_state *s, tree_desc *desc)); -local void scan_tree OF((deflate_state *s, ct_data *tree, int max_code)); -local void send_tree OF((deflate_state *s, ct_data *tree, int max_code)); -local int build_bl_tree OF((deflate_state *s)); -local void send_all_trees OF((deflate_state *s, int lcodes, int dcodes, - int blcodes)); -local void compress_block OF((deflate_state *s, ct_data *ltree, - ct_data *dtree)); -local void set_data_type OF((deflate_state *s)); -local unsigned bi_reverse OF((unsigned value, int length)); -local void bi_windup OF((deflate_state *s)); -local void bi_flush OF((deflate_state *s)); -local void copy_block OF((deflate_state *s, charf *buf, unsigned len, - int header)); - -#ifdef GEN_TREES_H -local void gen_trees_header OF((void)); -#endif - -#ifndef DEBUG -# define send_code(s, c, tree) send_bits(s, tree[c].Code, tree[c].Len) - /* Send a code of the given tree. c and tree must not have side effects */ - -#else /* DEBUG */ -# define send_code(s, c, tree) \ - { if (z_verbose>2) fprintf(stderr,"\ncd %3d ",(c)); \ - send_bits(s, tree[c].Code, tree[c].Len); } -#endif - -/* =========================================================================== - * Output a short LSB first on the stream. - * IN assertion: there is enough room in pendingBuf. - */ -#define put_short(s, w) { \ - put_byte(s, (uch)((w) & 0xff)); \ - put_byte(s, (uch)((ush)(w) >> 8)); \ -} - -/* =========================================================================== - * Send a value on a given number of bits. - * IN assertion: length <= 16 and value fits in length bits. - */ -#ifdef DEBUG -local void send_bits OF((deflate_state *s, int value, int length)); - -local void send_bits(s, value, length) - deflate_state *s; - int value; /* value to send */ - int length; /* number of bits */ -{ - Tracevv((stderr," l %2d v %4x ", length, value)); - Assert(length > 0 && length <= 15, "invalid length"); - s->bits_sent += (ulg)length; - - /* If not enough room in bi_buf, use (valid) bits from bi_buf and - * (16 - bi_valid) bits from value, leaving (width - (16-bi_valid)) - * unused bits in value. - */ - if (s->bi_valid > (int)Buf_size - length) { - s->bi_buf |= (value << s->bi_valid); - put_short(s, s->bi_buf); - s->bi_buf = (ush)value >> (Buf_size - s->bi_valid); - s->bi_valid += length - Buf_size; - } else { - s->bi_buf |= value << s->bi_valid; - s->bi_valid += length; - } -} -#else /* !DEBUG */ - -#define send_bits(s, value, length) \ -{ int len = length;\ - if (s->bi_valid > (int)Buf_size - len) {\ - int val = value;\ - s->bi_buf |= (val << s->bi_valid);\ - put_short(s, s->bi_buf);\ - s->bi_buf = (ush)val >> (Buf_size - s->bi_valid);\ - s->bi_valid += len - Buf_size;\ - } else {\ - s->bi_buf |= (value) << s->bi_valid;\ - s->bi_valid += len;\ - }\ -} -#endif /* DEBUG */ - - -/* the arguments must not have side effects */ - -/* =========================================================================== - * Initialize the various 'constant' tables. - */ -local void tr_static_init() -{ -#if defined(GEN_TREES_H) || !defined(STDC) - static int static_init_done = 0; - int n; /* iterates over tree elements */ - int bits; /* bit counter */ - int length; /* length value */ - int code; /* code value */ - int dist; /* distance index */ - ush bl_count[MAX_BITS+1]; - /* number of codes at each bit length for an optimal tree */ - - if (static_init_done) return; - - /* For some embedded targets, global variables are not initialized: */ - static_l_desc.static_tree = static_ltree; - static_l_desc.extra_bits = extra_lbits; - static_d_desc.static_tree = static_dtree; - static_d_desc.extra_bits = extra_dbits; - static_bl_desc.extra_bits = extra_blbits; - - /* Initialize the mapping length (0..255) -> length code (0..28) */ - length = 0; - for (code = 0; code < LENGTH_CODES-1; code++) { - base_length[code] = length; - for (n = 0; n < (1< dist code (0..29) */ - dist = 0; - for (code = 0 ; code < 16; code++) { - base_dist[code] = dist; - for (n = 0; n < (1<>= 7; /* from now on, all distances are divided by 128 */ - for ( ; code < D_CODES; code++) { - base_dist[code] = dist << 7; - for (n = 0; n < (1<<(extra_dbits[code]-7)); n++) { - _dist_code[256 + dist++] = (uch)code; - } - } - Assert (dist == 256, "tr_static_init: 256+dist != 512"); - - /* Construct the codes of the static literal tree */ - for (bits = 0; bits <= MAX_BITS; bits++) bl_count[bits] = 0; - n = 0; - while (n <= 143) static_ltree[n++].Len = 8, bl_count[8]++; - while (n <= 255) static_ltree[n++].Len = 9, bl_count[9]++; - while (n <= 279) static_ltree[n++].Len = 7, bl_count[7]++; - while (n <= 287) static_ltree[n++].Len = 8, bl_count[8]++; - /* Codes 286 and 287 do not exist, but we must include them in the - * tree construction to get a canonical Huffman tree (longest code - * all ones) - */ - gen_codes((ct_data *)static_ltree, L_CODES+1, bl_count); - - /* The static distance tree is trivial: */ - for (n = 0; n < D_CODES; n++) { - static_dtree[n].Len = 5; - static_dtree[n].Code = bi_reverse((unsigned)n, 5); - } - static_init_done = 1; - -# ifdef GEN_TREES_H - gen_trees_header(); -# endif -#endif /* defined(GEN_TREES_H) || !defined(STDC) */ -} - -/* =========================================================================== - * Genererate the file trees.h describing the static trees. - */ -#ifdef GEN_TREES_H -# ifndef DEBUG -# include -# endif - -# define SEPARATOR(i, last, width) \ - ((i) == (last)? "\n};\n\n" : \ - ((i) % (width) == (width)-1 ? ",\n" : ", ")) - -void gen_trees_header() -{ - FILE *header = fopen("trees.h", "w"); - int i; - - Assert (header != NULL, "Can't open trees.h"); - fprintf(header, - "/* header created automatically with -DGEN_TREES_H */\n\n"); - - fprintf(header, "local const ct_data static_ltree[L_CODES+2] = {\n"); - for (i = 0; i < L_CODES+2; i++) { - fprintf(header, "{{%3u},{%3u}}%s", static_ltree[i].Code, - static_ltree[i].Len, SEPARATOR(i, L_CODES+1, 5)); - } - - fprintf(header, "local const ct_data static_dtree[D_CODES] = {\n"); - for (i = 0; i < D_CODES; i++) { - fprintf(header, "{{%2u},{%2u}}%s", static_dtree[i].Code, - static_dtree[i].Len, SEPARATOR(i, D_CODES-1, 5)); - } - - fprintf(header, "const uch _dist_code[DIST_CODE_LEN] = {\n"); - for (i = 0; i < DIST_CODE_LEN; i++) { - fprintf(header, "%2u%s", _dist_code[i], - SEPARATOR(i, DIST_CODE_LEN-1, 20)); - } - - fprintf(header, "const uch _length_code[MAX_MATCH-MIN_MATCH+1]= {\n"); - for (i = 0; i < MAX_MATCH-MIN_MATCH+1; i++) { - fprintf(header, "%2u%s", _length_code[i], - SEPARATOR(i, MAX_MATCH-MIN_MATCH, 20)); - } - - fprintf(header, "local const int base_length[LENGTH_CODES] = {\n"); - for (i = 0; i < LENGTH_CODES; i++) { - fprintf(header, "%1u%s", base_length[i], - SEPARATOR(i, LENGTH_CODES-1, 20)); - } - - fprintf(header, "local const int base_dist[D_CODES] = {\n"); - for (i = 0; i < D_CODES; i++) { - fprintf(header, "%5u%s", base_dist[i], - SEPARATOR(i, D_CODES-1, 10)); - } - - fclose(header); -} -#endif /* GEN_TREES_H */ - -/* =========================================================================== - * Initialize the tree data structures for a new zlib stream. - */ -void _tr_init(s) - deflate_state *s; -{ - tr_static_init(); - - s->l_desc.dyn_tree = s->dyn_ltree; - s->l_desc.stat_desc = &static_l_desc; - - s->d_desc.dyn_tree = s->dyn_dtree; - s->d_desc.stat_desc = &static_d_desc; - - s->bl_desc.dyn_tree = s->bl_tree; - s->bl_desc.stat_desc = &static_bl_desc; - - s->bi_buf = 0; - s->bi_valid = 0; - s->last_eob_len = 8; /* enough lookahead for inflate */ -#ifdef DEBUG - s->compressed_len = 0L; - s->bits_sent = 0L; -#endif - - /* Initialize the first block of the first file: */ - init_block(s); -} - -/* =========================================================================== - * Initialize a new block. - */ -local void init_block(s) - deflate_state *s; -{ - int n; /* iterates over tree elements */ - - /* Initialize the trees. */ - for (n = 0; n < L_CODES; n++) s->dyn_ltree[n].Freq = 0; - for (n = 0; n < D_CODES; n++) s->dyn_dtree[n].Freq = 0; - for (n = 0; n < BL_CODES; n++) s->bl_tree[n].Freq = 0; - - s->dyn_ltree[END_BLOCK].Freq = 1; - s->opt_len = s->static_len = 0L; - s->last_lit = s->matches = 0; -} - -#define SMALLEST 1 -/* Index within the heap array of least frequent node in the Huffman tree */ - - -/* =========================================================================== - * Remove the smallest element from the heap and recreate the heap with - * one less element. Updates heap and heap_len. - */ -#define pqremove(s, tree, top) \ -{\ - top = s->heap[SMALLEST]; \ - s->heap[SMALLEST] = s->heap[s->heap_len--]; \ - pqdownheap(s, tree, SMALLEST); \ -} - -/* =========================================================================== - * Compares to subtrees, using the tree depth as tie breaker when - * the subtrees have equal frequency. This minimizes the worst case length. - */ -#define smaller(tree, n, m, depth) \ - (tree[n].Freq < tree[m].Freq || \ - (tree[n].Freq == tree[m].Freq && depth[n] <= depth[m])) - -/* =========================================================================== - * Restore the heap property by moving down the tree starting at node k, - * exchanging a node with the smallest of its two sons if necessary, stopping - * when the heap property is re-established (each father smaller than its - * two sons). - */ -local void pqdownheap(s, tree, k) - deflate_state *s; - ct_data *tree; /* the tree to restore */ - int k; /* node to move down */ -{ - int v = s->heap[k]; - int j = k << 1; /* left son of k */ - while (j <= s->heap_len) { - /* Set j to the smallest of the two sons: */ - if (j < s->heap_len && - smaller(tree, s->heap[j+1], s->heap[j], s->depth)) { - j++; - } - /* Exit if v is smaller than both sons */ - if (smaller(tree, v, s->heap[j], s->depth)) break; - - /* Exchange v with the smallest son */ - s->heap[k] = s->heap[j]; k = j; - - /* And continue down the tree, setting j to the left son of k */ - j <<= 1; - } - s->heap[k] = v; -} - -/* =========================================================================== - * Compute the optimal bit lengths for a tree and update the total bit length - * for the current block. - * IN assertion: the fields freq and dad are set, heap[heap_max] and - * above are the tree nodes sorted by increasing frequency. - * OUT assertions: the field len is set to the optimal bit length, the - * array bl_count contains the frequencies for each bit length. - * The length opt_len is updated; static_len is also updated if stree is - * not null. - */ -local void gen_bitlen(s, desc) - deflate_state *s; - tree_desc *desc; /* the tree descriptor */ -{ - ct_data *tree = desc->dyn_tree; - int max_code = desc->max_code; - const ct_data *stree = desc->stat_desc->static_tree; - const intf *extra = desc->stat_desc->extra_bits; - int base = desc->stat_desc->extra_base; - int max_length = desc->stat_desc->max_length; - int h; /* heap index */ - int n, m; /* iterate over the tree elements */ - int bits; /* bit length */ - int xbits; /* extra bits */ - ush f; /* frequency */ - int overflow = 0; /* number of elements with bit length too large */ - - for (bits = 0; bits <= MAX_BITS; bits++) s->bl_count[bits] = 0; - - /* In a first pass, compute the optimal bit lengths (which may - * overflow in the case of the bit length tree). - */ - tree[s->heap[s->heap_max]].Len = 0; /* root of the heap */ - - for (h = s->heap_max+1; h < HEAP_SIZE; h++) { - n = s->heap[h]; - bits = tree[tree[n].Dad].Len + 1; - if (bits > max_length) bits = max_length, overflow++; - tree[n].Len = (ush)bits; - /* We overwrite tree[n].Dad which is no longer needed */ - - if (n > max_code) continue; /* not a leaf node */ - - s->bl_count[bits]++; - xbits = 0; - if (n >= base) xbits = extra[n-base]; - f = tree[n].Freq; - s->opt_len += (ulg)f * (bits + xbits); - if (stree) s->static_len += (ulg)f * (stree[n].Len + xbits); - } - if (overflow == 0) return; - - Trace((stderr,"\nbit length overflow\n")); - /* This happens for example on obj2 and pic of the Calgary corpus */ - - /* Find the first bit length which could increase: */ - do { - bits = max_length-1; - while (s->bl_count[bits] == 0) bits--; - s->bl_count[bits]--; /* move one leaf down the tree */ - s->bl_count[bits+1] += 2; /* move one overflow item as its brother */ - s->bl_count[max_length]--; - /* The brother of the overflow item also moves one step up, - * but this does not affect bl_count[max_length] - */ - overflow -= 2; - } while (overflow > 0); - - /* Now recompute all bit lengths, scanning in increasing frequency. - * h is still equal to HEAP_SIZE. (It is simpler to reconstruct all - * lengths instead of fixing only the wrong ones. This idea is taken - * from 'ar' written by Haruhiko Okumura.) - */ - for (bits = max_length; bits != 0; bits--) { - n = s->bl_count[bits]; - while (n != 0) { - m = s->heap[--h]; - if (m > max_code) continue; - if ((unsigned) tree[m].Len != (unsigned) bits) { - Trace((stderr,"code %d bits %d->%d\n", m, tree[m].Len, bits)); - s->opt_len += ((long)bits - (long)tree[m].Len) - *(long)tree[m].Freq; - tree[m].Len = (ush)bits; - } - n--; - } - } -} - -/* =========================================================================== - * Generate the codes for a given tree and bit counts (which need not be - * optimal). - * IN assertion: the array bl_count contains the bit length statistics for - * the given tree and the field len is set for all tree elements. - * OUT assertion: the field code is set for all tree elements of non - * zero code length. - */ -local void gen_codes (tree, max_code, bl_count) - ct_data *tree; /* the tree to decorate */ - int max_code; /* largest code with non zero frequency */ - ushf *bl_count; /* number of codes at each bit length */ -{ - ush next_code[MAX_BITS+1]; /* next code value for each bit length */ - ush code = 0; /* running code value */ - int bits; /* bit index */ - int n; /* code index */ - - /* The distribution counts are first used to generate the code values - * without bit reversal. - */ - for (bits = 1; bits <= MAX_BITS; bits++) { - next_code[bits] = code = (code + bl_count[bits-1]) << 1; - } - /* Check that the bit counts in bl_count are consistent. The last code - * must be all ones. - */ - Assert (code + bl_count[MAX_BITS]-1 == (1<dyn_tree; - const ct_data *stree = desc->stat_desc->static_tree; - int elems = desc->stat_desc->elems; - int n, m; /* iterate over heap elements */ - int max_code = -1; /* largest code with non zero frequency */ - int node; /* new node being created */ - - /* Construct the initial heap, with least frequent element in - * heap[SMALLEST]. The sons of heap[n] are heap[2*n] and heap[2*n+1]. - * heap[0] is not used. - */ - s->heap_len = 0, s->heap_max = HEAP_SIZE; - - for (n = 0; n < elems; n++) { - if (tree[n].Freq != 0) { - s->heap[++(s->heap_len)] = max_code = n; - s->depth[n] = 0; - } else { - tree[n].Len = 0; - } - } - - /* The pkzip format requires that at least one distance code exists, - * and that at least one bit should be sent even if there is only one - * possible code. So to avoid special checks later on we force at least - * two codes of non zero frequency. - */ - while (s->heap_len < 2) { - node = s->heap[++(s->heap_len)] = (max_code < 2 ? ++max_code : 0); - tree[node].Freq = 1; - s->depth[node] = 0; - s->opt_len--; if (stree) s->static_len -= stree[node].Len; - /* node is 0 or 1 so it does not have extra bits */ - } - desc->max_code = max_code; - - /* The elements heap[heap_len/2+1 .. heap_len] are leaves of the tree, - * establish sub-heaps of increasing lengths: - */ - for (n = s->heap_len/2; n >= 1; n--) pqdownheap(s, tree, n); - - /* Construct the Huffman tree by repeatedly combining the least two - * frequent nodes. - */ - node = elems; /* next internal node of the tree */ - do { - pqremove(s, tree, n); /* n = node of least frequency */ - m = s->heap[SMALLEST]; /* m = node of next least frequency */ - - s->heap[--(s->heap_max)] = n; /* keep the nodes sorted by frequency */ - s->heap[--(s->heap_max)] = m; - - /* Create a new node father of n and m */ - tree[node].Freq = tree[n].Freq + tree[m].Freq; - s->depth[node] = (uch)((s->depth[n] >= s->depth[m] ? - s->depth[n] : s->depth[m]) + 1); - tree[n].Dad = tree[m].Dad = (ush)node; -#ifdef DUMP_BL_TREE - if (tree == s->bl_tree) { - fprintf(stderr,"\nnode %d(%d), sons %d(%d) %d(%d)", - node, tree[node].Freq, n, tree[n].Freq, m, tree[m].Freq); - } -#endif - /* and insert the new node in the heap */ - s->heap[SMALLEST] = node++; - pqdownheap(s, tree, SMALLEST); - - } while (s->heap_len >= 2); - - s->heap[--(s->heap_max)] = s->heap[SMALLEST]; - - /* At this point, the fields freq and dad are set. We can now - * generate the bit lengths. - */ - gen_bitlen(s, (tree_desc *)desc); - - /* The field len is now set, we can generate the bit codes */ - gen_codes ((ct_data *)tree, max_code, s->bl_count); -} - -/* =========================================================================== - * Scan a literal or distance tree to determine the frequencies of the codes - * in the bit length tree. - */ -local void scan_tree (s, tree, max_code) - deflate_state *s; - ct_data *tree; /* the tree to be scanned */ - int max_code; /* and its largest code of non zero frequency */ -{ - int n; /* iterates over all tree elements */ - int prevlen = -1; /* last emitted length */ - int curlen; /* length of current code */ - int nextlen = tree[0].Len; /* length of next code */ - int count = 0; /* repeat count of the current code */ - int max_count = 7; /* max repeat count */ - int min_count = 4; /* min repeat count */ - - if (nextlen == 0) max_count = 138, min_count = 3; - tree[max_code+1].Len = (ush)0xffff; /* guard */ - - for (n = 0; n <= max_code; n++) { - curlen = nextlen; nextlen = tree[n+1].Len; - if (++count < max_count && curlen == nextlen) { - continue; - } else if (count < min_count) { - s->bl_tree[curlen].Freq += count; - } else if (curlen != 0) { - if (curlen != prevlen) s->bl_tree[curlen].Freq++; - s->bl_tree[REP_3_6].Freq++; - } else if (count <= 10) { - s->bl_tree[REPZ_3_10].Freq++; - } else { - s->bl_tree[REPZ_11_138].Freq++; - } - count = 0; prevlen = curlen; - if (nextlen == 0) { - max_count = 138, min_count = 3; - } else if (curlen == nextlen) { - max_count = 6, min_count = 3; - } else { - max_count = 7, min_count = 4; - } - } -} - -/* =========================================================================== - * Send a literal or distance tree in compressed form, using the codes in - * bl_tree. - */ -local void send_tree (s, tree, max_code) - deflate_state *s; - ct_data *tree; /* the tree to be scanned */ - int max_code; /* and its largest code of non zero frequency */ -{ - int n; /* iterates over all tree elements */ - int prevlen = -1; /* last emitted length */ - int curlen; /* length of current code */ - int nextlen = tree[0].Len; /* length of next code */ - int count = 0; /* repeat count of the current code */ - int max_count = 7; /* max repeat count */ - int min_count = 4; /* min repeat count */ - - /* tree[max_code+1].Len = -1; */ /* guard already set */ - if (nextlen == 0) max_count = 138, min_count = 3; - - for (n = 0; n <= max_code; n++) { - curlen = nextlen; nextlen = tree[n+1].Len; - if (++count < max_count && curlen == nextlen) { - continue; - } else if (count < min_count) { - do { send_code(s, curlen, s->bl_tree); } while (--count != 0); - - } else if (curlen != 0) { - if (curlen != prevlen) { - send_code(s, curlen, s->bl_tree); count--; - } - Assert(count >= 3 && count <= 6, " 3_6?"); - send_code(s, REP_3_6, s->bl_tree); send_bits(s, count-3, 2); - - } else if (count <= 10) { - send_code(s, REPZ_3_10, s->bl_tree); send_bits(s, count-3, 3); - - } else { - send_code(s, REPZ_11_138, s->bl_tree); send_bits(s, count-11, 7); - } - count = 0; prevlen = curlen; - if (nextlen == 0) { - max_count = 138, min_count = 3; - } else if (curlen == nextlen) { - max_count = 6, min_count = 3; - } else { - max_count = 7, min_count = 4; - } - } -} - -/* =========================================================================== - * Construct the Huffman tree for the bit lengths and return the index in - * bl_order of the last bit length code to send. - */ -local int build_bl_tree(s) - deflate_state *s; -{ - int max_blindex; /* index of last bit length code of non zero freq */ - - /* Determine the bit length frequencies for literal and distance trees */ - scan_tree(s, (ct_data *)s->dyn_ltree, s->l_desc.max_code); - scan_tree(s, (ct_data *)s->dyn_dtree, s->d_desc.max_code); - - /* Build the bit length tree: */ - build_tree(s, (tree_desc *)(&(s->bl_desc))); - /* opt_len now includes the length of the tree representations, except - * the lengths of the bit lengths codes and the 5+5+4 bits for the counts. - */ - - /* Determine the number of bit length codes to send. The pkzip format - * requires that at least 4 bit length codes be sent. (appnote.txt says - * 3 but the actual value used is 4.) - */ - for (max_blindex = BL_CODES-1; max_blindex >= 3; max_blindex--) { - if (s->bl_tree[bl_order[max_blindex]].Len != 0) break; - } - /* Update opt_len to include the bit length tree and counts */ - s->opt_len += 3*(max_blindex+1) + 5+5+4; - Tracev((stderr, "\ndyn trees: dyn %ld, stat %ld", - s->opt_len, s->static_len)); - - return max_blindex; -} - -/* =========================================================================== - * Send the header for a block using dynamic Huffman trees: the counts, the - * lengths of the bit length codes, the literal tree and the distance tree. - * IN assertion: lcodes >= 257, dcodes >= 1, blcodes >= 4. - */ -local void send_all_trees(s, lcodes, dcodes, blcodes) - deflate_state *s; - int lcodes, dcodes, blcodes; /* number of codes for each tree */ -{ - int rank; /* index in bl_order */ - - Assert (lcodes >= 257 && dcodes >= 1 && blcodes >= 4, "not enough codes"); - Assert (lcodes <= L_CODES && dcodes <= D_CODES && blcodes <= BL_CODES, - "too many codes"); - Tracev((stderr, "\nbl counts: ")); - send_bits(s, lcodes-257, 5); /* not +255 as stated in appnote.txt */ - send_bits(s, dcodes-1, 5); - send_bits(s, blcodes-4, 4); /* not -3 as stated in appnote.txt */ - for (rank = 0; rank < blcodes; rank++) { - Tracev((stderr, "\nbl code %2d ", bl_order[rank])); - send_bits(s, s->bl_tree[bl_order[rank]].Len, 3); - } - Tracev((stderr, "\nbl tree: sent %ld", s->bits_sent)); - - send_tree(s, (ct_data *)s->dyn_ltree, lcodes-1); /* literal tree */ - Tracev((stderr, "\nlit tree: sent %ld", s->bits_sent)); - - send_tree(s, (ct_data *)s->dyn_dtree, dcodes-1); /* distance tree */ - Tracev((stderr, "\ndist tree: sent %ld", s->bits_sent)); -} - -/* =========================================================================== - * Send a stored block - */ -void _tr_stored_block(s, buf, stored_len, eof) - deflate_state *s; - charf *buf; /* input block */ - ulg stored_len; /* length of input block */ - int eof; /* true if this is the last block for a file */ -{ - send_bits(s, (STORED_BLOCK<<1)+eof, 3); /* send block type */ -#ifdef DEBUG - s->compressed_len = (s->compressed_len + 3 + 7) & (ulg)~7L; - s->compressed_len += (stored_len + 4) << 3; -#endif - copy_block(s, buf, (unsigned)stored_len, 1); /* with header */ -} - -/* =========================================================================== - * Send one empty static block to give enough lookahead for inflate. - * This takes 10 bits, of which 7 may remain in the bit buffer. - * The current inflate code requires 9 bits of lookahead. If the - * last two codes for the previous block (real code plus EOB) were coded - * on 5 bits or less, inflate may have only 5+3 bits of lookahead to decode - * the last real code. In this case we send two empty static blocks instead - * of one. (There are no problems if the previous block is stored or fixed.) - * To simplify the code, we assume the worst case of last real code encoded - * on one bit only. - */ -void _tr_align(s) - deflate_state *s; -{ - send_bits(s, STATIC_TREES<<1, 3); - send_code(s, END_BLOCK, static_ltree); -#ifdef DEBUG - s->compressed_len += 10L; /* 3 for block type, 7 for EOB */ -#endif - bi_flush(s); - /* Of the 10 bits for the empty block, we have already sent - * (10 - bi_valid) bits. The lookahead for the last real code (before - * the EOB of the previous block) was thus at least one plus the length - * of the EOB plus what we have just sent of the empty static block. - */ - if (1 + s->last_eob_len + 10 - s->bi_valid < 9) { - send_bits(s, STATIC_TREES<<1, 3); - send_code(s, END_BLOCK, static_ltree); -#ifdef DEBUG - s->compressed_len += 10L; -#endif - bi_flush(s); - } - s->last_eob_len = 7; -} - -/* =========================================================================== - * Determine the best encoding for the current block: dynamic trees, static - * trees or store, and output the encoded block to the zip file. - */ -void _tr_flush_block(s, buf, stored_len, eof) - deflate_state *s; - charf *buf; /* input block, or NULL if too old */ - ulg stored_len; /* length of input block */ - int eof; /* true if this is the last block for a file */ -{ - ulg opt_lenb, static_lenb; /* opt_len and static_len in bytes */ - int max_blindex = 0; /* index of last bit length code of non zero freq */ - - /* Build the Huffman trees unless a stored block is forced */ - if (s->level > 0) { - - /* Check if the file is binary or text */ - if (stored_len > 0 && s->strm->data_type == Z_UNKNOWN) - set_data_type(s); - - /* Construct the literal and distance trees */ - build_tree(s, (tree_desc *)(&(s->l_desc))); - Tracev((stderr, "\nlit data: dyn %ld, stat %ld", s->opt_len, - s->static_len)); - - build_tree(s, (tree_desc *)(&(s->d_desc))); - Tracev((stderr, "\ndist data: dyn %ld, stat %ld", s->opt_len, - s->static_len)); - /* At this point, opt_len and static_len are the total bit lengths of - * the compressed block data, excluding the tree representations. - */ - - /* Build the bit length tree for the above two trees, and get the index - * in bl_order of the last bit length code to send. - */ - max_blindex = build_bl_tree(s); - - /* Determine the best encoding. Compute the block lengths in bytes. */ - opt_lenb = (s->opt_len+3+7)>>3; - static_lenb = (s->static_len+3+7)>>3; - - Tracev((stderr, "\nopt %lu(%lu) stat %lu(%lu) stored %lu lit %u ", - opt_lenb, s->opt_len, static_lenb, s->static_len, stored_len, - s->last_lit)); - - if (static_lenb <= opt_lenb) opt_lenb = static_lenb; - - } else { - Assert(buf != (char*)0, "lost buf"); - opt_lenb = static_lenb = stored_len + 5; /* force a stored block */ - } - -#ifdef FORCE_STORED - if (buf != (char*)0) { /* force stored block */ -#else - if (stored_len+4 <= opt_lenb && buf != (char*)0) { - /* 4: two words for the lengths */ -#endif - /* The test buf != NULL is only necessary if LIT_BUFSIZE > WSIZE. - * Otherwise we can't have processed more than WSIZE input bytes since - * the last block flush, because compression would have been - * successful. If LIT_BUFSIZE <= WSIZE, it is never too late to - * transform a block into a stored block. - */ - _tr_stored_block(s, buf, stored_len, eof); - -#ifdef FORCE_STATIC - } else if (static_lenb >= 0) { /* force static trees */ -#else - } else if (s->strategy == Z_FIXED || static_lenb == opt_lenb) { -#endif - send_bits(s, (STATIC_TREES<<1)+eof, 3); - compress_block(s, (ct_data *)static_ltree, (ct_data *)static_dtree); -#ifdef DEBUG - s->compressed_len += 3 + s->static_len; -#endif - } else { - send_bits(s, (DYN_TREES<<1)+eof, 3); - send_all_trees(s, s->l_desc.max_code+1, s->d_desc.max_code+1, - max_blindex+1); - compress_block(s, (ct_data *)s->dyn_ltree, (ct_data *)s->dyn_dtree); -#ifdef DEBUG - s->compressed_len += 3 + s->opt_len; -#endif - } - Assert (s->compressed_len == s->bits_sent, "bad compressed size"); - /* The above check is made mod 2^32, for files larger than 512 MB - * and uLong implemented on 32 bits. - */ - init_block(s); - - if (eof) { - bi_windup(s); -#ifdef DEBUG - s->compressed_len += 7; /* align on byte boundary */ -#endif - } - Tracev((stderr,"\ncomprlen %lu(%lu) ", s->compressed_len>>3, - s->compressed_len-7*eof)); -} - -/* =========================================================================== - * Save the match info and tally the frequency counts. Return true if - * the current block must be flushed. - */ -int _tr_tally (s, dist, lc) - deflate_state *s; - unsigned dist; /* distance of matched string */ - unsigned lc; /* match length-MIN_MATCH or unmatched char (if dist==0) */ -{ - s->d_buf[s->last_lit] = (ush)dist; - s->l_buf[s->last_lit++] = (uch)lc; - if (dist == 0) { - /* lc is the unmatched char */ - s->dyn_ltree[lc].Freq++; - } else { - s->matches++; - /* Here, lc is the match length - MIN_MATCH */ - dist--; /* dist = match distance - 1 */ - Assert((ush)dist < (ush)MAX_DIST(s) && - (ush)lc <= (ush)(MAX_MATCH-MIN_MATCH) && - (ush)d_code(dist) < (ush)D_CODES, "_tr_tally: bad match"); - - s->dyn_ltree[_length_code[lc]+LITERALS+1].Freq++; - s->dyn_dtree[d_code(dist)].Freq++; - } - -#ifdef TRUNCATE_BLOCK - /* Try to guess if it is profitable to stop the current block here */ - if ((s->last_lit & 0x1fff) == 0 && s->level > 2) { - /* Compute an upper bound for the compressed length */ - ulg out_length = (ulg)s->last_lit*8L; - ulg in_length = (ulg)((long)s->strstart - s->block_start); - int dcode; - for (dcode = 0; dcode < D_CODES; dcode++) { - out_length += (ulg)s->dyn_dtree[dcode].Freq * - (5L+extra_dbits[dcode]); - } - out_length >>= 3; - Tracev((stderr,"\nlast_lit %u, in %ld, out ~%ld(%ld%%) ", - s->last_lit, in_length, out_length, - 100L - out_length*100L/in_length)); - if (s->matches < s->last_lit/2 && out_length < in_length/2) return 1; - } -#endif - return (s->last_lit == s->lit_bufsize-1); - /* We avoid equality with lit_bufsize because of wraparound at 64K - * on 16 bit machines and because stored blocks are restricted to - * 64K-1 bytes. - */ -} - -/* =========================================================================== - * Send the block data compressed using the given Huffman trees - */ -local void compress_block(s, ltree, dtree) - deflate_state *s; - ct_data *ltree; /* literal tree */ - ct_data *dtree; /* distance tree */ -{ - unsigned dist; /* distance of matched string */ - int lc; /* match length or unmatched char (if dist == 0) */ - unsigned lx = 0; /* running index in l_buf */ - unsigned code; /* the code to send */ - int extra; /* number of extra bits to send */ - - if (s->last_lit != 0) do { - dist = s->d_buf[lx]; - lc = s->l_buf[lx++]; - if (dist == 0) { - send_code(s, lc, ltree); /* send a literal byte */ - Tracecv(isgraph(lc), (stderr," '%c' ", lc)); - } else { - /* Here, lc is the match length - MIN_MATCH */ - code = _length_code[lc]; - send_code(s, code+LITERALS+1, ltree); /* send the length code */ - extra = extra_lbits[code]; - if (extra != 0) { - lc -= base_length[code]; - send_bits(s, lc, extra); /* send the extra length bits */ - } - dist--; /* dist is now the match distance - 1 */ - code = d_code(dist); - Assert (code < D_CODES, "bad d_code"); - - send_code(s, code, dtree); /* send the distance code */ - extra = extra_dbits[code]; - if (extra != 0) { - dist -= base_dist[code]; - send_bits(s, dist, extra); /* send the extra distance bits */ - } - } /* literal or match pair ? */ - - /* Check that the overlay between pending_buf and d_buf+l_buf is ok: */ - Assert((uInt)(s->pending) < s->lit_bufsize + 2*lx, - "pendingBuf overflow"); - - } while (lx < s->last_lit); - - send_code(s, END_BLOCK, ltree); - s->last_eob_len = ltree[END_BLOCK].Len; -} - -/* =========================================================================== - * Set the data type to BINARY or TEXT, using a crude approximation: - * set it to Z_TEXT if all symbols are either printable characters (33 to 255) - * or white spaces (9 to 13, or 32); or set it to Z_BINARY otherwise. - * IN assertion: the fields Freq of dyn_ltree are set. - */ -local void set_data_type(s) - deflate_state *s; -{ - int n; - - for (n = 0; n < 9; n++) - if (s->dyn_ltree[n].Freq != 0) - break; - if (n == 9) - for (n = 14; n < 32; n++) - if (s->dyn_ltree[n].Freq != 0) - break; - s->strm->data_type = (n == 32) ? Z_TEXT : Z_BINARY; -} - -/* =========================================================================== - * Reverse the first len bits of a code, using straightforward code (a faster - * method would use a table) - * IN assertion: 1 <= len <= 15 - */ -local unsigned bi_reverse(code, len) - unsigned code; /* the value to invert */ - int len; /* its bit length */ -{ - register unsigned res = 0; - do { - res |= code & 1; - code >>= 1, res <<= 1; - } while (--len > 0); - return res >> 1; -} - -/* =========================================================================== - * Flush the bit buffer, keeping at most 7 bits in it. - */ -local void bi_flush(s) - deflate_state *s; -{ - if (s->bi_valid == 16) { - put_short(s, s->bi_buf); - s->bi_buf = 0; - s->bi_valid = 0; - } else if (s->bi_valid >= 8) { - put_byte(s, (Byte)s->bi_buf); - s->bi_buf >>= 8; - s->bi_valid -= 8; - } -} - -/* =========================================================================== - * Flush the bit buffer and align the output on a byte boundary - */ -local void bi_windup(s) - deflate_state *s; -{ - if (s->bi_valid > 8) { - put_short(s, s->bi_buf); - } else if (s->bi_valid > 0) { - put_byte(s, (Byte)s->bi_buf); - } - s->bi_buf = 0; - s->bi_valid = 0; -#ifdef DEBUG - s->bits_sent = (s->bits_sent+7) & ~7; -#endif -} - -/* =========================================================================== - * Copy a stored block, storing first the length and its - * one's complement if requested. - */ -local void copy_block(s, buf, len, header) - deflate_state *s; - charf *buf; /* the input data */ - unsigned len; /* its length */ - int header; /* true if block header must be written */ -{ - bi_windup(s); /* align on byte boundary */ - s->last_eob_len = 8; /* enough lookahead for inflate */ - - if (header) { - put_short(s, (ush)len); - put_short(s, (ush)~len); -#ifdef DEBUG - s->bits_sent += 2*16; -#endif - } -#ifdef DEBUG - s->bits_sent += (ulg)len<<3; -#endif - while (len--) { - put_byte(s, *buf++); - } -} +/* trees.c -- output deflated data using Huffman coding + * Copyright (C) 1995-2005 Jean-loup Gailly + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* + * ALGORITHM + * + * The "deflation" process uses several Huffman trees. The more + * common source values are represented by shorter bit sequences. + * + * Each code tree is stored in a compressed form which is itself + * a Huffman encoding of the lengths of all the code strings (in + * ascending order by source values). The actual code strings are + * reconstructed from the lengths in the inflate process, as described + * in the deflate specification. + * + * REFERENCES + * + * Deutsch, L.P.,"'Deflate' Compressed Data Format Specification". + * Available in ftp.uu.net:/pub/archiving/zip/doc/deflate-1.1.doc + * + * Storer, James A. + * Data Compression: Methods and Theory, pp. 49-50. + * Computer Science Press, 1988. ISBN 0-7167-8156-5. + * + * Sedgewick, R. + * Algorithms, p290. + * Addison-Wesley, 1983. ISBN 0-201-06672-6. + */ + +/* @(#) $Id$ */ + +/* #define GEN_TREES_H */ + +#include "deflate.h" + +#ifdef DEBUG +# include +#endif + +/* =========================================================================== + * Constants + */ + +#define MAX_BL_BITS 7 +/* Bit length codes must not exceed MAX_BL_BITS bits */ + +#define END_BLOCK 256 +/* end of block literal code */ + +#define REP_3_6 16 +/* repeat previous bit length 3-6 times (2 bits of repeat count) */ + +#define REPZ_3_10 17 +/* repeat a zero length 3-10 times (3 bits of repeat count) */ + +#define REPZ_11_138 18 +/* repeat a zero length 11-138 times (7 bits of repeat count) */ + +local const int extra_lbits[LENGTH_CODES] /* extra bits for each length code */ + = {0,0,0,0,0,0,0,0,1,1,1,1,2,2,2,2,3,3,3,3,4,4,4,4,5,5,5,5,0}; + +local const int extra_dbits[D_CODES] /* extra bits for each distance code */ + = {0,0,0,0,1,1,2,2,3,3,4,4,5,5,6,6,7,7,8,8,9,9,10,10,11,11,12,12,13,13}; + +local const int extra_blbits[BL_CODES]/* extra bits for each bit length code */ + = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,2,3,7}; + +local const uch bl_order[BL_CODES] + = {16,17,18,0,8,7,9,6,10,5,11,4,12,3,13,2,14,1,15}; +/* The lengths of the bit length codes are sent in order of decreasing + * probability, to avoid transmitting the lengths for unused bit length codes. + */ + +#define Buf_size (8 * 2*sizeof(char)) +/* Number of bits used within bi_buf. (bi_buf might be implemented on + * more than 16 bits on some systems.) + */ + +/* =========================================================================== + * Local data. These are initialized only once. + */ + +#define DIST_CODE_LEN 512 /* see definition of array dist_code below */ + +#if defined(GEN_TREES_H) || !defined(STDC) +/* non ANSI compilers may not accept trees.h */ + +local ct_data static_ltree[L_CODES+2]; +/* The static literal tree. Since the bit lengths are imposed, there is no + * need for the L_CODES extra codes used during heap construction. However + * The codes 286 and 287 are needed to build a canonical tree (see _tr_init + * below). + */ + +local ct_data static_dtree[D_CODES]; +/* The static distance tree. (Actually a trivial tree since all codes use + * 5 bits.) + */ + +uch _dist_code[DIST_CODE_LEN]; +/* Distance codes. The first 256 values correspond to the distances + * 3 .. 258, the last 256 values correspond to the top 8 bits of + * the 15 bit distances. + */ + +uch _length_code[MAX_MATCH-MIN_MATCH+1]; +/* length code for each normalized match length (0 == MIN_MATCH) */ + +local int base_length[LENGTH_CODES]; +/* First normalized length for each code (0 = MIN_MATCH) */ + +local int base_dist[D_CODES]; +/* First normalized distance for each code (0 = distance of 1) */ + +#else +# include "trees.h" +#endif /* GEN_TREES_H */ + +struct static_tree_desc_s { + const ct_data *static_tree; /* static tree or NULL */ + const intf *extra_bits; /* extra bits for each code or NULL */ + int extra_base; /* base index for extra_bits */ + int elems; /* max number of elements in the tree */ + int max_length; /* max bit length for the codes */ +}; + +local static_tree_desc static_l_desc = +{static_ltree, extra_lbits, LITERALS+1, L_CODES, MAX_BITS}; + +local static_tree_desc static_d_desc = +{static_dtree, extra_dbits, 0, D_CODES, MAX_BITS}; + +local static_tree_desc static_bl_desc = +{(const ct_data *)0, extra_blbits, 0, BL_CODES, MAX_BL_BITS}; + +/* =========================================================================== + * Local (static) routines in this file. + */ + +local void tr_static_init OF((void)); +local void init_block OF((deflate_state *s)); +local void pqdownheap OF((deflate_state *s, ct_data *tree, int k)); +local void gen_bitlen OF((deflate_state *s, tree_desc *desc)); +local void gen_codes OF((ct_data *tree, int max_code, ushf *bl_count)); +local void build_tree OF((deflate_state *s, tree_desc *desc)); +local void scan_tree OF((deflate_state *s, ct_data *tree, int max_code)); +local void send_tree OF((deflate_state *s, ct_data *tree, int max_code)); +local int build_bl_tree OF((deflate_state *s)); +local void send_all_trees OF((deflate_state *s, int lcodes, int dcodes, + int blcodes)); +local void compress_block OF((deflate_state *s, ct_data *ltree, + ct_data *dtree)); +local void set_data_type OF((deflate_state *s)); +local unsigned bi_reverse OF((unsigned value, int length)); +local void bi_windup OF((deflate_state *s)); +local void bi_flush OF((deflate_state *s)); +local void copy_block OF((deflate_state *s, charf *buf, unsigned len, + int header)); + +#ifdef GEN_TREES_H +local void gen_trees_header OF((void)); +#endif + +#ifndef DEBUG +# define send_code(s, c, tree) send_bits(s, tree[c].Code, tree[c].Len) + /* Send a code of the given tree. c and tree must not have side effects */ + +#else /* DEBUG */ +# define send_code(s, c, tree) \ + { if (z_verbose>2) fprintf(stderr,"\ncd %3d ",(c)); \ + send_bits(s, tree[c].Code, tree[c].Len); } +#endif + +/* =========================================================================== + * Output a short LSB first on the stream. + * IN assertion: there is enough room in pendingBuf. + */ +#define put_short(s, w) { \ + put_byte(s, (uch)((w) & 0xff)); \ + put_byte(s, (uch)((ush)(w) >> 8)); \ +} + +/* =========================================================================== + * Send a value on a given number of bits. + * IN assertion: length <= 16 and value fits in length bits. + */ +#ifdef DEBUG +local void send_bits OF((deflate_state *s, int value, int length)); + +local void send_bits(s, value, length) + deflate_state *s; + int value; /* value to send */ + int length; /* number of bits */ +{ + Tracevv((stderr," l %2d v %4x ", length, value)); + Assert(length > 0 && length <= 15, "invalid length"); + s->bits_sent += (ulg)length; + + /* If not enough room in bi_buf, use (valid) bits from bi_buf and + * (16 - bi_valid) bits from value, leaving (width - (16-bi_valid)) + * unused bits in value. + */ + if (s->bi_valid > (int)Buf_size - length) { + s->bi_buf |= (value << s->bi_valid); + put_short(s, s->bi_buf); + s->bi_buf = (ush)value >> (Buf_size - s->bi_valid); + s->bi_valid += length - Buf_size; + } else { + s->bi_buf |= value << s->bi_valid; + s->bi_valid += length; + } +} +#else /* !DEBUG */ + +#define send_bits(s, value, length) \ +{ int len = length;\ + if (s->bi_valid > (int)Buf_size - len) {\ + int val = value;\ + s->bi_buf |= (val << s->bi_valid);\ + put_short(s, s->bi_buf);\ + s->bi_buf = (ush)val >> (Buf_size - s->bi_valid);\ + s->bi_valid += len - Buf_size;\ + } else {\ + s->bi_buf |= (value) << s->bi_valid;\ + s->bi_valid += len;\ + }\ +} +#endif /* DEBUG */ + + +/* the arguments must not have side effects */ + +/* =========================================================================== + * Initialize the various 'constant' tables. + */ +local void tr_static_init() +{ +#if defined(GEN_TREES_H) || !defined(STDC) + static int static_init_done = 0; + int n; /* iterates over tree elements */ + int bits; /* bit counter */ + int length; /* length value */ + int code; /* code value */ + int dist; /* distance index */ + ush bl_count[MAX_BITS+1]; + /* number of codes at each bit length for an optimal tree */ + + if (static_init_done) return; + + /* For some embedded targets, global variables are not initialized: */ + static_l_desc.static_tree = static_ltree; + static_l_desc.extra_bits = extra_lbits; + static_d_desc.static_tree = static_dtree; + static_d_desc.extra_bits = extra_dbits; + static_bl_desc.extra_bits = extra_blbits; + + /* Initialize the mapping length (0..255) -> length code (0..28) */ + length = 0; + for (code = 0; code < LENGTH_CODES-1; code++) { + base_length[code] = length; + for (n = 0; n < (1< dist code (0..29) */ + dist = 0; + for (code = 0 ; code < 16; code++) { + base_dist[code] = dist; + for (n = 0; n < (1<>= 7; /* from now on, all distances are divided by 128 */ + for ( ; code < D_CODES; code++) { + base_dist[code] = dist << 7; + for (n = 0; n < (1<<(extra_dbits[code]-7)); n++) { + _dist_code[256 + dist++] = (uch)code; + } + } + Assert (dist == 256, "tr_static_init: 256+dist != 512"); + + /* Construct the codes of the static literal tree */ + for (bits = 0; bits <= MAX_BITS; bits++) bl_count[bits] = 0; + n = 0; + while (n <= 143) static_ltree[n++].Len = 8, bl_count[8]++; + while (n <= 255) static_ltree[n++].Len = 9, bl_count[9]++; + while (n <= 279) static_ltree[n++].Len = 7, bl_count[7]++; + while (n <= 287) static_ltree[n++].Len = 8, bl_count[8]++; + /* Codes 286 and 287 do not exist, but we must include them in the + * tree construction to get a canonical Huffman tree (longest code + * all ones) + */ + gen_codes((ct_data *)static_ltree, L_CODES+1, bl_count); + + /* The static distance tree is trivial: */ + for (n = 0; n < D_CODES; n++) { + static_dtree[n].Len = 5; + static_dtree[n].Code = bi_reverse((unsigned)n, 5); + } + static_init_done = 1; + +# ifdef GEN_TREES_H + gen_trees_header(); +# endif +#endif /* defined(GEN_TREES_H) || !defined(STDC) */ +} + +/* =========================================================================== + * Genererate the file trees.h describing the static trees. + */ +#ifdef GEN_TREES_H +# ifndef DEBUG +# include +# endif + +# define SEPARATOR(i, last, width) \ + ((i) == (last)? "\n};\n\n" : \ + ((i) % (width) == (width)-1 ? ",\n" : ", ")) + +void gen_trees_header() +{ + FILE *header = fopen("trees.h", "w"); + int i; + + Assert (header != NULL, "Can't open trees.h"); + fprintf(header, + "/* header created automatically with -DGEN_TREES_H */\n\n"); + + fprintf(header, "local const ct_data static_ltree[L_CODES+2] = {\n"); + for (i = 0; i < L_CODES+2; i++) { + fprintf(header, "{{%3u},{%3u}}%s", static_ltree[i].Code, + static_ltree[i].Len, SEPARATOR(i, L_CODES+1, 5)); + } + + fprintf(header, "local const ct_data static_dtree[D_CODES] = {\n"); + for (i = 0; i < D_CODES; i++) { + fprintf(header, "{{%2u},{%2u}}%s", static_dtree[i].Code, + static_dtree[i].Len, SEPARATOR(i, D_CODES-1, 5)); + } + + fprintf(header, "const uch _dist_code[DIST_CODE_LEN] = {\n"); + for (i = 0; i < DIST_CODE_LEN; i++) { + fprintf(header, "%2u%s", _dist_code[i], + SEPARATOR(i, DIST_CODE_LEN-1, 20)); + } + + fprintf(header, "const uch _length_code[MAX_MATCH-MIN_MATCH+1]= {\n"); + for (i = 0; i < MAX_MATCH-MIN_MATCH+1; i++) { + fprintf(header, "%2u%s", _length_code[i], + SEPARATOR(i, MAX_MATCH-MIN_MATCH, 20)); + } + + fprintf(header, "local const int base_length[LENGTH_CODES] = {\n"); + for (i = 0; i < LENGTH_CODES; i++) { + fprintf(header, "%1u%s", base_length[i], + SEPARATOR(i, LENGTH_CODES-1, 20)); + } + + fprintf(header, "local const int base_dist[D_CODES] = {\n"); + for (i = 0; i < D_CODES; i++) { + fprintf(header, "%5u%s", base_dist[i], + SEPARATOR(i, D_CODES-1, 10)); + } + + fclose(header); +} +#endif /* GEN_TREES_H */ + +/* =========================================================================== + * Initialize the tree data structures for a new zlib stream. + */ +void _tr_init(s) + deflate_state *s; +{ + tr_static_init(); + + s->l_desc.dyn_tree = s->dyn_ltree; + s->l_desc.stat_desc = &static_l_desc; + + s->d_desc.dyn_tree = s->dyn_dtree; + s->d_desc.stat_desc = &static_d_desc; + + s->bl_desc.dyn_tree = s->bl_tree; + s->bl_desc.stat_desc = &static_bl_desc; + + s->bi_buf = 0; + s->bi_valid = 0; + s->last_eob_len = 8; /* enough lookahead for inflate */ +#ifdef DEBUG + s->compressed_len = 0L; + s->bits_sent = 0L; +#endif + + /* Initialize the first block of the first file: */ + init_block(s); +} + +/* =========================================================================== + * Initialize a new block. + */ +local void init_block(s) + deflate_state *s; +{ + int n; /* iterates over tree elements */ + + /* Initialize the trees. */ + for (n = 0; n < L_CODES; n++) s->dyn_ltree[n].Freq = 0; + for (n = 0; n < D_CODES; n++) s->dyn_dtree[n].Freq = 0; + for (n = 0; n < BL_CODES; n++) s->bl_tree[n].Freq = 0; + + s->dyn_ltree[END_BLOCK].Freq = 1; + s->opt_len = s->static_len = 0L; + s->last_lit = s->matches = 0; +} + +#define SMALLEST 1 +/* Index within the heap array of least frequent node in the Huffman tree */ + + +/* =========================================================================== + * Remove the smallest element from the heap and recreate the heap with + * one less element. Updates heap and heap_len. + */ +#define pqremove(s, tree, top) \ +{\ + top = s->heap[SMALLEST]; \ + s->heap[SMALLEST] = s->heap[s->heap_len--]; \ + pqdownheap(s, tree, SMALLEST); \ +} + +/* =========================================================================== + * Compares to subtrees, using the tree depth as tie breaker when + * the subtrees have equal frequency. This minimizes the worst case length. + */ +#define smaller(tree, n, m, depth) \ + (tree[n].Freq < tree[m].Freq || \ + (tree[n].Freq == tree[m].Freq && depth[n] <= depth[m])) + +/* =========================================================================== + * Restore the heap property by moving down the tree starting at node k, + * exchanging a node with the smallest of its two sons if necessary, stopping + * when the heap property is re-established (each father smaller than its + * two sons). + */ +local void pqdownheap(s, tree, k) + deflate_state *s; + ct_data *tree; /* the tree to restore */ + int k; /* node to move down */ +{ + int v = s->heap[k]; + int j = k << 1; /* left son of k */ + while (j <= s->heap_len) { + /* Set j to the smallest of the two sons: */ + if (j < s->heap_len && + smaller(tree, s->heap[j+1], s->heap[j], s->depth)) { + j++; + } + /* Exit if v is smaller than both sons */ + if (smaller(tree, v, s->heap[j], s->depth)) break; + + /* Exchange v with the smallest son */ + s->heap[k] = s->heap[j]; k = j; + + /* And continue down the tree, setting j to the left son of k */ + j <<= 1; + } + s->heap[k] = v; +} + +/* =========================================================================== + * Compute the optimal bit lengths for a tree and update the total bit length + * for the current block. + * IN assertion: the fields freq and dad are set, heap[heap_max] and + * above are the tree nodes sorted by increasing frequency. + * OUT assertions: the field len is set to the optimal bit length, the + * array bl_count contains the frequencies for each bit length. + * The length opt_len is updated; static_len is also updated if stree is + * not null. + */ +local void gen_bitlen(s, desc) + deflate_state *s; + tree_desc *desc; /* the tree descriptor */ +{ + ct_data *tree = desc->dyn_tree; + int max_code = desc->max_code; + const ct_data *stree = desc->stat_desc->static_tree; + const intf *extra = desc->stat_desc->extra_bits; + int base = desc->stat_desc->extra_base; + int max_length = desc->stat_desc->max_length; + int h; /* heap index */ + int n, m; /* iterate over the tree elements */ + int bits; /* bit length */ + int xbits; /* extra bits */ + ush f; /* frequency */ + int overflow = 0; /* number of elements with bit length too large */ + + for (bits = 0; bits <= MAX_BITS; bits++) s->bl_count[bits] = 0; + + /* In a first pass, compute the optimal bit lengths (which may + * overflow in the case of the bit length tree). + */ + tree[s->heap[s->heap_max]].Len = 0; /* root of the heap */ + + for (h = s->heap_max+1; h < HEAP_SIZE; h++) { + n = s->heap[h]; + bits = tree[tree[n].Dad].Len + 1; + if (bits > max_length) bits = max_length, overflow++; + tree[n].Len = (ush)bits; + /* We overwrite tree[n].Dad which is no longer needed */ + + if (n > max_code) continue; /* not a leaf node */ + + s->bl_count[bits]++; + xbits = 0; + if (n >= base) xbits = extra[n-base]; + f = tree[n].Freq; + s->opt_len += (ulg)f * (bits + xbits); + if (stree) s->static_len += (ulg)f * (stree[n].Len + xbits); + } + if (overflow == 0) return; + + Trace((stderr,"\nbit length overflow\n")); + /* This happens for example on obj2 and pic of the Calgary corpus */ + + /* Find the first bit length which could increase: */ + do { + bits = max_length-1; + while (s->bl_count[bits] == 0) bits--; + s->bl_count[bits]--; /* move one leaf down the tree */ + s->bl_count[bits+1] += 2; /* move one overflow item as its brother */ + s->bl_count[max_length]--; + /* The brother of the overflow item also moves one step up, + * but this does not affect bl_count[max_length] + */ + overflow -= 2; + } while (overflow > 0); + + /* Now recompute all bit lengths, scanning in increasing frequency. + * h is still equal to HEAP_SIZE. (It is simpler to reconstruct all + * lengths instead of fixing only the wrong ones. This idea is taken + * from 'ar' written by Haruhiko Okumura.) + */ + for (bits = max_length; bits != 0; bits--) { + n = s->bl_count[bits]; + while (n != 0) { + m = s->heap[--h]; + if (m > max_code) continue; + if ((unsigned) tree[m].Len != (unsigned) bits) { + Trace((stderr,"code %d bits %d->%d\n", m, tree[m].Len, bits)); + s->opt_len += ((long)bits - (long)tree[m].Len) + *(long)tree[m].Freq; + tree[m].Len = (ush)bits; + } + n--; + } + } +} + +/* =========================================================================== + * Generate the codes for a given tree and bit counts (which need not be + * optimal). + * IN assertion: the array bl_count contains the bit length statistics for + * the given tree and the field len is set for all tree elements. + * OUT assertion: the field code is set for all tree elements of non + * zero code length. + */ +local void gen_codes (tree, max_code, bl_count) + ct_data *tree; /* the tree to decorate */ + int max_code; /* largest code with non zero frequency */ + ushf *bl_count; /* number of codes at each bit length */ +{ + ush next_code[MAX_BITS+1]; /* next code value for each bit length */ + ush code = 0; /* running code value */ + int bits; /* bit index */ + int n; /* code index */ + + /* The distribution counts are first used to generate the code values + * without bit reversal. + */ + for (bits = 1; bits <= MAX_BITS; bits++) { + next_code[bits] = code = (code + bl_count[bits-1]) << 1; + } + /* Check that the bit counts in bl_count are consistent. The last code + * must be all ones. + */ + Assert (code + bl_count[MAX_BITS]-1 == (1<dyn_tree; + const ct_data *stree = desc->stat_desc->static_tree; + int elems = desc->stat_desc->elems; + int n, m; /* iterate over heap elements */ + int max_code = -1; /* largest code with non zero frequency */ + int node; /* new node being created */ + + /* Construct the initial heap, with least frequent element in + * heap[SMALLEST]. The sons of heap[n] are heap[2*n] and heap[2*n+1]. + * heap[0] is not used. + */ + s->heap_len = 0, s->heap_max = HEAP_SIZE; + + for (n = 0; n < elems; n++) { + if (tree[n].Freq != 0) { + s->heap[++(s->heap_len)] = max_code = n; + s->depth[n] = 0; + } else { + tree[n].Len = 0; + } + } + + /* The pkzip format requires that at least one distance code exists, + * and that at least one bit should be sent even if there is only one + * possible code. So to avoid special checks later on we force at least + * two codes of non zero frequency. + */ + while (s->heap_len < 2) { + node = s->heap[++(s->heap_len)] = (max_code < 2 ? ++max_code : 0); + tree[node].Freq = 1; + s->depth[node] = 0; + s->opt_len--; if (stree) s->static_len -= stree[node].Len; + /* node is 0 or 1 so it does not have extra bits */ + } + desc->max_code = max_code; + + /* The elements heap[heap_len/2+1 .. heap_len] are leaves of the tree, + * establish sub-heaps of increasing lengths: + */ + for (n = s->heap_len/2; n >= 1; n--) pqdownheap(s, tree, n); + + /* Construct the Huffman tree by repeatedly combining the least two + * frequent nodes. + */ + node = elems; /* next internal node of the tree */ + do { + pqremove(s, tree, n); /* n = node of least frequency */ + m = s->heap[SMALLEST]; /* m = node of next least frequency */ + + s->heap[--(s->heap_max)] = n; /* keep the nodes sorted by frequency */ + s->heap[--(s->heap_max)] = m; + + /* Create a new node father of n and m */ + tree[node].Freq = tree[n].Freq + tree[m].Freq; + s->depth[node] = (uch)((s->depth[n] >= s->depth[m] ? + s->depth[n] : s->depth[m]) + 1); + tree[n].Dad = tree[m].Dad = (ush)node; +#ifdef DUMP_BL_TREE + if (tree == s->bl_tree) { + fprintf(stderr,"\nnode %d(%d), sons %d(%d) %d(%d)", + node, tree[node].Freq, n, tree[n].Freq, m, tree[m].Freq); + } +#endif + /* and insert the new node in the heap */ + s->heap[SMALLEST] = node++; + pqdownheap(s, tree, SMALLEST); + + } while (s->heap_len >= 2); + + s->heap[--(s->heap_max)] = s->heap[SMALLEST]; + + /* At this point, the fields freq and dad are set. We can now + * generate the bit lengths. + */ + gen_bitlen(s, (tree_desc *)desc); + + /* The field len is now set, we can generate the bit codes */ + gen_codes ((ct_data *)tree, max_code, s->bl_count); +} + +/* =========================================================================== + * Scan a literal or distance tree to determine the frequencies of the codes + * in the bit length tree. + */ +local void scan_tree (s, tree, max_code) + deflate_state *s; + ct_data *tree; /* the tree to be scanned */ + int max_code; /* and its largest code of non zero frequency */ +{ + int n; /* iterates over all tree elements */ + int prevlen = -1; /* last emitted length */ + int curlen; /* length of current code */ + int nextlen = tree[0].Len; /* length of next code */ + int count = 0; /* repeat count of the current code */ + int max_count = 7; /* max repeat count */ + int min_count = 4; /* min repeat count */ + + if (nextlen == 0) max_count = 138, min_count = 3; + tree[max_code+1].Len = (ush)0xffff; /* guard */ + + for (n = 0; n <= max_code; n++) { + curlen = nextlen; nextlen = tree[n+1].Len; + if (++count < max_count && curlen == nextlen) { + continue; + } else if (count < min_count) { + s->bl_tree[curlen].Freq += count; + } else if (curlen != 0) { + if (curlen != prevlen) s->bl_tree[curlen].Freq++; + s->bl_tree[REP_3_6].Freq++; + } else if (count <= 10) { + s->bl_tree[REPZ_3_10].Freq++; + } else { + s->bl_tree[REPZ_11_138].Freq++; + } + count = 0; prevlen = curlen; + if (nextlen == 0) { + max_count = 138, min_count = 3; + } else if (curlen == nextlen) { + max_count = 6, min_count = 3; + } else { + max_count = 7, min_count = 4; + } + } +} + +/* =========================================================================== + * Send a literal or distance tree in compressed form, using the codes in + * bl_tree. + */ +local void send_tree (s, tree, max_code) + deflate_state *s; + ct_data *tree; /* the tree to be scanned */ + int max_code; /* and its largest code of non zero frequency */ +{ + int n; /* iterates over all tree elements */ + int prevlen = -1; /* last emitted length */ + int curlen; /* length of current code */ + int nextlen = tree[0].Len; /* length of next code */ + int count = 0; /* repeat count of the current code */ + int max_count = 7; /* max repeat count */ + int min_count = 4; /* min repeat count */ + + /* tree[max_code+1].Len = -1; */ /* guard already set */ + if (nextlen == 0) max_count = 138, min_count = 3; + + for (n = 0; n <= max_code; n++) { + curlen = nextlen; nextlen = tree[n+1].Len; + if (++count < max_count && curlen == nextlen) { + continue; + } else if (count < min_count) { + do { send_code(s, curlen, s->bl_tree); } while (--count != 0); + + } else if (curlen != 0) { + if (curlen != prevlen) { + send_code(s, curlen, s->bl_tree); count--; + } + Assert(count >= 3 && count <= 6, " 3_6?"); + send_code(s, REP_3_6, s->bl_tree); send_bits(s, count-3, 2); + + } else if (count <= 10) { + send_code(s, REPZ_3_10, s->bl_tree); send_bits(s, count-3, 3); + + } else { + send_code(s, REPZ_11_138, s->bl_tree); send_bits(s, count-11, 7); + } + count = 0; prevlen = curlen; + if (nextlen == 0) { + max_count = 138, min_count = 3; + } else if (curlen == nextlen) { + max_count = 6, min_count = 3; + } else { + max_count = 7, min_count = 4; + } + } +} + +/* =========================================================================== + * Construct the Huffman tree for the bit lengths and return the index in + * bl_order of the last bit length code to send. + */ +local int build_bl_tree(s) + deflate_state *s; +{ + int max_blindex; /* index of last bit length code of non zero freq */ + + /* Determine the bit length frequencies for literal and distance trees */ + scan_tree(s, (ct_data *)s->dyn_ltree, s->l_desc.max_code); + scan_tree(s, (ct_data *)s->dyn_dtree, s->d_desc.max_code); + + /* Build the bit length tree: */ + build_tree(s, (tree_desc *)(&(s->bl_desc))); + /* opt_len now includes the length of the tree representations, except + * the lengths of the bit lengths codes and the 5+5+4 bits for the counts. + */ + + /* Determine the number of bit length codes to send. The pkzip format + * requires that at least 4 bit length codes be sent. (appnote.txt says + * 3 but the actual value used is 4.) + */ + for (max_blindex = BL_CODES-1; max_blindex >= 3; max_blindex--) { + if (s->bl_tree[bl_order[max_blindex]].Len != 0) break; + } + /* Update opt_len to include the bit length tree and counts */ + s->opt_len += 3*(max_blindex+1) + 5+5+4; + Tracev((stderr, "\ndyn trees: dyn %ld, stat %ld", + s->opt_len, s->static_len)); + + return max_blindex; +} + +/* =========================================================================== + * Send the header for a block using dynamic Huffman trees: the counts, the + * lengths of the bit length codes, the literal tree and the distance tree. + * IN assertion: lcodes >= 257, dcodes >= 1, blcodes >= 4. + */ +local void send_all_trees(s, lcodes, dcodes, blcodes) + deflate_state *s; + int lcodes, dcodes, blcodes; /* number of codes for each tree */ +{ + int rank; /* index in bl_order */ + + Assert (lcodes >= 257 && dcodes >= 1 && blcodes >= 4, "not enough codes"); + Assert (lcodes <= L_CODES && dcodes <= D_CODES && blcodes <= BL_CODES, + "too many codes"); + Tracev((stderr, "\nbl counts: ")); + send_bits(s, lcodes-257, 5); /* not +255 as stated in appnote.txt */ + send_bits(s, dcodes-1, 5); + send_bits(s, blcodes-4, 4); /* not -3 as stated in appnote.txt */ + for (rank = 0; rank < blcodes; rank++) { + Tracev((stderr, "\nbl code %2d ", bl_order[rank])); + send_bits(s, s->bl_tree[bl_order[rank]].Len, 3); + } + Tracev((stderr, "\nbl tree: sent %ld", s->bits_sent)); + + send_tree(s, (ct_data *)s->dyn_ltree, lcodes-1); /* literal tree */ + Tracev((stderr, "\nlit tree: sent %ld", s->bits_sent)); + + send_tree(s, (ct_data *)s->dyn_dtree, dcodes-1); /* distance tree */ + Tracev((stderr, "\ndist tree: sent %ld", s->bits_sent)); +} + +/* =========================================================================== + * Send a stored block + */ +void _tr_stored_block(s, buf, stored_len, eof) + deflate_state *s; + charf *buf; /* input block */ + ulg stored_len; /* length of input block */ + int eof; /* true if this is the last block for a file */ +{ + send_bits(s, (STORED_BLOCK<<1)+eof, 3); /* send block type */ +#ifdef DEBUG + s->compressed_len = (s->compressed_len + 3 + 7) & (ulg)~7L; + s->compressed_len += (stored_len + 4) << 3; +#endif + copy_block(s, buf, (unsigned)stored_len, 1); /* with header */ +} + +/* =========================================================================== + * Send one empty static block to give enough lookahead for inflate. + * This takes 10 bits, of which 7 may remain in the bit buffer. + * The current inflate code requires 9 bits of lookahead. If the + * last two codes for the previous block (real code plus EOB) were coded + * on 5 bits or less, inflate may have only 5+3 bits of lookahead to decode + * the last real code. In this case we send two empty static blocks instead + * of one. (There are no problems if the previous block is stored or fixed.) + * To simplify the code, we assume the worst case of last real code encoded + * on one bit only. + */ +void _tr_align(s) + deflate_state *s; +{ + send_bits(s, STATIC_TREES<<1, 3); + send_code(s, END_BLOCK, static_ltree); +#ifdef DEBUG + s->compressed_len += 10L; /* 3 for block type, 7 for EOB */ +#endif + bi_flush(s); + /* Of the 10 bits for the empty block, we have already sent + * (10 - bi_valid) bits. The lookahead for the last real code (before + * the EOB of the previous block) was thus at least one plus the length + * of the EOB plus what we have just sent of the empty static block. + */ + if (1 + s->last_eob_len + 10 - s->bi_valid < 9) { + send_bits(s, STATIC_TREES<<1, 3); + send_code(s, END_BLOCK, static_ltree); +#ifdef DEBUG + s->compressed_len += 10L; +#endif + bi_flush(s); + } + s->last_eob_len = 7; +} + +/* =========================================================================== + * Determine the best encoding for the current block: dynamic trees, static + * trees or store, and output the encoded block to the zip file. + */ +void _tr_flush_block(s, buf, stored_len, eof) + deflate_state *s; + charf *buf; /* input block, or NULL if too old */ + ulg stored_len; /* length of input block */ + int eof; /* true if this is the last block for a file */ +{ + ulg opt_lenb, static_lenb; /* opt_len and static_len in bytes */ + int max_blindex = 0; /* index of last bit length code of non zero freq */ + + /* Build the Huffman trees unless a stored block is forced */ + if (s->level > 0) { + + /* Check if the file is binary or text */ + if (stored_len > 0 && s->strm->data_type == Z_UNKNOWN) + set_data_type(s); + + /* Construct the literal and distance trees */ + build_tree(s, (tree_desc *)(&(s->l_desc))); + Tracev((stderr, "\nlit data: dyn %ld, stat %ld", s->opt_len, + s->static_len)); + + build_tree(s, (tree_desc *)(&(s->d_desc))); + Tracev((stderr, "\ndist data: dyn %ld, stat %ld", s->opt_len, + s->static_len)); + /* At this point, opt_len and static_len are the total bit lengths of + * the compressed block data, excluding the tree representations. + */ + + /* Build the bit length tree for the above two trees, and get the index + * in bl_order of the last bit length code to send. + */ + max_blindex = build_bl_tree(s); + + /* Determine the best encoding. Compute the block lengths in bytes. */ + opt_lenb = (s->opt_len+3+7)>>3; + static_lenb = (s->static_len+3+7)>>3; + + Tracev((stderr, "\nopt %lu(%lu) stat %lu(%lu) stored %lu lit %u ", + opt_lenb, s->opt_len, static_lenb, s->static_len, stored_len, + s->last_lit)); + + if (static_lenb <= opt_lenb) opt_lenb = static_lenb; + + } else { + Assert(buf != (char*)0, "lost buf"); + opt_lenb = static_lenb = stored_len + 5; /* force a stored block */ + } + +#ifdef FORCE_STORED + if (buf != (char*)0) { /* force stored block */ +#else + if (stored_len+4 <= opt_lenb && buf != (char*)0) { + /* 4: two words for the lengths */ +#endif + /* The test buf != NULL is only necessary if LIT_BUFSIZE > WSIZE. + * Otherwise we can't have processed more than WSIZE input bytes since + * the last block flush, because compression would have been + * successful. If LIT_BUFSIZE <= WSIZE, it is never too late to + * transform a block into a stored block. + */ + _tr_stored_block(s, buf, stored_len, eof); + +#ifdef FORCE_STATIC + } else if (static_lenb >= 0) { /* force static trees */ +#else + } else if (s->strategy == Z_FIXED || static_lenb == opt_lenb) { +#endif + send_bits(s, (STATIC_TREES<<1)+eof, 3); + compress_block(s, (ct_data *)static_ltree, (ct_data *)static_dtree); +#ifdef DEBUG + s->compressed_len += 3 + s->static_len; +#endif + } else { + send_bits(s, (DYN_TREES<<1)+eof, 3); + send_all_trees(s, s->l_desc.max_code+1, s->d_desc.max_code+1, + max_blindex+1); + compress_block(s, (ct_data *)s->dyn_ltree, (ct_data *)s->dyn_dtree); +#ifdef DEBUG + s->compressed_len += 3 + s->opt_len; +#endif + } + Assert (s->compressed_len == s->bits_sent, "bad compressed size"); + /* The above check is made mod 2^32, for files larger than 512 MB + * and uLong implemented on 32 bits. + */ + init_block(s); + + if (eof) { + bi_windup(s); +#ifdef DEBUG + s->compressed_len += 7; /* align on byte boundary */ +#endif + } + Tracev((stderr,"\ncomprlen %lu(%lu) ", s->compressed_len>>3, + s->compressed_len-7*eof)); +} + +/* =========================================================================== + * Save the match info and tally the frequency counts. Return true if + * the current block must be flushed. + */ +int _tr_tally (s, dist, lc) + deflate_state *s; + unsigned dist; /* distance of matched string */ + unsigned lc; /* match length-MIN_MATCH or unmatched char (if dist==0) */ +{ + s->d_buf[s->last_lit] = (ush)dist; + s->l_buf[s->last_lit++] = (uch)lc; + if (dist == 0) { + /* lc is the unmatched char */ + s->dyn_ltree[lc].Freq++; + } else { + s->matches++; + /* Here, lc is the match length - MIN_MATCH */ + dist--; /* dist = match distance - 1 */ + Assert((ush)dist < (ush)MAX_DIST(s) && + (ush)lc <= (ush)(MAX_MATCH-MIN_MATCH) && + (ush)d_code(dist) < (ush)D_CODES, "_tr_tally: bad match"); + + s->dyn_ltree[_length_code[lc]+LITERALS+1].Freq++; + s->dyn_dtree[d_code(dist)].Freq++; + } + +#ifdef TRUNCATE_BLOCK + /* Try to guess if it is profitable to stop the current block here */ + if ((s->last_lit & 0x1fff) == 0 && s->level > 2) { + /* Compute an upper bound for the compressed length */ + ulg out_length = (ulg)s->last_lit*8L; + ulg in_length = (ulg)((long)s->strstart - s->block_start); + int dcode; + for (dcode = 0; dcode < D_CODES; dcode++) { + out_length += (ulg)s->dyn_dtree[dcode].Freq * + (5L+extra_dbits[dcode]); + } + out_length >>= 3; + Tracev((stderr,"\nlast_lit %u, in %ld, out ~%ld(%ld%%) ", + s->last_lit, in_length, out_length, + 100L - out_length*100L/in_length)); + if (s->matches < s->last_lit/2 && out_length < in_length/2) return 1; + } +#endif + return (s->last_lit == s->lit_bufsize-1); + /* We avoid equality with lit_bufsize because of wraparound at 64K + * on 16 bit machines and because stored blocks are restricted to + * 64K-1 bytes. + */ +} + +/* =========================================================================== + * Send the block data compressed using the given Huffman trees + */ +local void compress_block(s, ltree, dtree) + deflate_state *s; + ct_data *ltree; /* literal tree */ + ct_data *dtree; /* distance tree */ +{ + unsigned dist; /* distance of matched string */ + int lc; /* match length or unmatched char (if dist == 0) */ + unsigned lx = 0; /* running index in l_buf */ + unsigned code; /* the code to send */ + int extra; /* number of extra bits to send */ + + if (s->last_lit != 0) do { + dist = s->d_buf[lx]; + lc = s->l_buf[lx++]; + if (dist == 0) { + send_code(s, lc, ltree); /* send a literal byte */ + Tracecv(isgraph(lc), (stderr," '%c' ", lc)); + } else { + /* Here, lc is the match length - MIN_MATCH */ + code = _length_code[lc]; + send_code(s, code+LITERALS+1, ltree); /* send the length code */ + extra = extra_lbits[code]; + if (extra != 0) { + lc -= base_length[code]; + send_bits(s, lc, extra); /* send the extra length bits */ + } + dist--; /* dist is now the match distance - 1 */ + code = d_code(dist); + Assert (code < D_CODES, "bad d_code"); + + send_code(s, code, dtree); /* send the distance code */ + extra = extra_dbits[code]; + if (extra != 0) { + dist -= base_dist[code]; + send_bits(s, dist, extra); /* send the extra distance bits */ + } + } /* literal or match pair ? */ + + /* Check that the overlay between pending_buf and d_buf+l_buf is ok: */ + Assert((uInt)(s->pending) < s->lit_bufsize + 2*lx, + "pendingBuf overflow"); + + } while (lx < s->last_lit); + + send_code(s, END_BLOCK, ltree); + s->last_eob_len = ltree[END_BLOCK].Len; +} + +/* =========================================================================== + * Set the data type to BINARY or TEXT, using a crude approximation: + * set it to Z_TEXT if all symbols are either printable characters (33 to 255) + * or white spaces (9 to 13, or 32); or set it to Z_BINARY otherwise. + * IN assertion: the fields Freq of dyn_ltree are set. + */ +local void set_data_type(s) + deflate_state *s; +{ + int n; + + for (n = 0; n < 9; n++) + if (s->dyn_ltree[n].Freq != 0) + break; + if (n == 9) + for (n = 14; n < 32; n++) + if (s->dyn_ltree[n].Freq != 0) + break; + s->strm->data_type = (n == 32) ? Z_TEXT : Z_BINARY; +} + +/* =========================================================================== + * Reverse the first len bits of a code, using straightforward code (a faster + * method would use a table) + * IN assertion: 1 <= len <= 15 + */ +local unsigned bi_reverse(code, len) + unsigned code; /* the value to invert */ + int len; /* its bit length */ +{ + register unsigned res = 0; + do { + res |= code & 1; + code >>= 1, res <<= 1; + } while (--len > 0); + return res >> 1; +} + +/* =========================================================================== + * Flush the bit buffer, keeping at most 7 bits in it. + */ +local void bi_flush(s) + deflate_state *s; +{ + if (s->bi_valid == 16) { + put_short(s, s->bi_buf); + s->bi_buf = 0; + s->bi_valid = 0; + } else if (s->bi_valid >= 8) { + put_byte(s, (Byte)s->bi_buf); + s->bi_buf >>= 8; + s->bi_valid -= 8; + } +} + +/* =========================================================================== + * Flush the bit buffer and align the output on a byte boundary + */ +local void bi_windup(s) + deflate_state *s; +{ + if (s->bi_valid > 8) { + put_short(s, s->bi_buf); + } else if (s->bi_valid > 0) { + put_byte(s, (Byte)s->bi_buf); + } + s->bi_buf = 0; + s->bi_valid = 0; +#ifdef DEBUG + s->bits_sent = (s->bits_sent+7) & ~7; +#endif +} + +/* =========================================================================== + * Copy a stored block, storing first the length and its + * one's complement if requested. + */ +local void copy_block(s, buf, len, header) + deflate_state *s; + charf *buf; /* the input data */ + unsigned len; /* its length */ + int header; /* true if block header must be written */ +{ + bi_windup(s); /* align on byte boundary */ + s->last_eob_len = 8; /* enough lookahead for inflate */ + + if (header) { + put_short(s, (ush)len); + put_short(s, (ush)~len); +#ifdef DEBUG + s->bits_sent += 2*16; +#endif + } +#ifdef DEBUG + s->bits_sent += (ulg)len<<3; +#endif + while (len--) { + put_byte(s, *buf++); + } +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/trees.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/trees.h index 1ca868b84..72facf900 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/trees.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/trees.h @@ -1,128 +1,128 @@ -/* header created automatically with -DGEN_TREES_H */ - -local const ct_data static_ltree[L_CODES+2] = { -{{ 12},{ 8}}, {{140},{ 8}}, {{ 76},{ 8}}, {{204},{ 8}}, {{ 44},{ 8}}, -{{172},{ 8}}, {{108},{ 8}}, {{236},{ 8}}, {{ 28},{ 8}}, {{156},{ 8}}, -{{ 92},{ 8}}, {{220},{ 8}}, {{ 60},{ 8}}, {{188},{ 8}}, {{124},{ 8}}, -{{252},{ 8}}, {{ 2},{ 8}}, {{130},{ 8}}, {{ 66},{ 8}}, {{194},{ 8}}, -{{ 34},{ 8}}, {{162},{ 8}}, {{ 98},{ 8}}, {{226},{ 8}}, {{ 18},{ 8}}, -{{146},{ 8}}, {{ 82},{ 8}}, {{210},{ 8}}, {{ 50},{ 8}}, {{178},{ 8}}, -{{114},{ 8}}, {{242},{ 8}}, {{ 10},{ 8}}, {{138},{ 8}}, {{ 74},{ 8}}, -{{202},{ 8}}, {{ 42},{ 8}}, {{170},{ 8}}, {{106},{ 8}}, {{234},{ 8}}, -{{ 26},{ 8}}, {{154},{ 8}}, {{ 90},{ 8}}, {{218},{ 8}}, {{ 58},{ 8}}, -{{186},{ 8}}, {{122},{ 8}}, {{250},{ 8}}, {{ 6},{ 8}}, {{134},{ 8}}, -{{ 70},{ 8}}, {{198},{ 8}}, {{ 38},{ 8}}, {{166},{ 8}}, {{102},{ 8}}, -{{230},{ 8}}, {{ 22},{ 8}}, {{150},{ 8}}, {{ 86},{ 8}}, {{214},{ 8}}, -{{ 54},{ 8}}, {{182},{ 8}}, {{118},{ 8}}, {{246},{ 8}}, {{ 14},{ 8}}, -{{142},{ 8}}, {{ 78},{ 8}}, {{206},{ 8}}, {{ 46},{ 8}}, {{174},{ 8}}, -{{110},{ 8}}, {{238},{ 8}}, {{ 30},{ 8}}, {{158},{ 8}}, {{ 94},{ 8}}, -{{222},{ 8}}, {{ 62},{ 8}}, {{190},{ 8}}, {{126},{ 8}}, {{254},{ 8}}, -{{ 1},{ 8}}, {{129},{ 8}}, {{ 65},{ 8}}, {{193},{ 8}}, {{ 33},{ 8}}, -{{161},{ 8}}, {{ 97},{ 8}}, {{225},{ 8}}, {{ 17},{ 8}}, {{145},{ 8}}, -{{ 81},{ 8}}, {{209},{ 8}}, {{ 49},{ 8}}, {{177},{ 8}}, {{113},{ 8}}, -{{241},{ 8}}, {{ 9},{ 8}}, {{137},{ 8}}, {{ 73},{ 8}}, {{201},{ 8}}, -{{ 41},{ 8}}, {{169},{ 8}}, {{105},{ 8}}, {{233},{ 8}}, {{ 25},{ 8}}, -{{153},{ 8}}, {{ 89},{ 8}}, {{217},{ 8}}, {{ 57},{ 8}}, {{185},{ 8}}, -{{121},{ 8}}, {{249},{ 8}}, {{ 5},{ 8}}, {{133},{ 8}}, {{ 69},{ 8}}, -{{197},{ 8}}, {{ 37},{ 8}}, {{165},{ 8}}, {{101},{ 8}}, {{229},{ 8}}, -{{ 21},{ 8}}, {{149},{ 8}}, {{ 85},{ 8}}, {{213},{ 8}}, {{ 53},{ 8}}, -{{181},{ 8}}, {{117},{ 8}}, {{245},{ 8}}, {{ 13},{ 8}}, {{141},{ 8}}, -{{ 77},{ 8}}, {{205},{ 8}}, {{ 45},{ 8}}, {{173},{ 8}}, {{109},{ 8}}, -{{237},{ 8}}, {{ 29},{ 8}}, {{157},{ 8}}, {{ 93},{ 8}}, {{221},{ 8}}, -{{ 61},{ 8}}, {{189},{ 8}}, {{125},{ 8}}, {{253},{ 8}}, {{ 19},{ 9}}, -{{275},{ 9}}, {{147},{ 9}}, {{403},{ 9}}, {{ 83},{ 9}}, {{339},{ 9}}, -{{211},{ 9}}, {{467},{ 9}}, {{ 51},{ 9}}, {{307},{ 9}}, {{179},{ 9}}, -{{435},{ 9}}, {{115},{ 9}}, {{371},{ 9}}, {{243},{ 9}}, {{499},{ 9}}, -{{ 11},{ 9}}, {{267},{ 9}}, {{139},{ 9}}, {{395},{ 9}}, {{ 75},{ 9}}, -{{331},{ 9}}, {{203},{ 9}}, {{459},{ 9}}, {{ 43},{ 9}}, {{299},{ 9}}, -{{171},{ 9}}, {{427},{ 9}}, {{107},{ 9}}, {{363},{ 9}}, {{235},{ 9}}, -{{491},{ 9}}, {{ 27},{ 9}}, {{283},{ 9}}, {{155},{ 9}}, {{411},{ 9}}, -{{ 91},{ 9}}, {{347},{ 9}}, {{219},{ 9}}, {{475},{ 9}}, {{ 59},{ 9}}, -{{315},{ 9}}, {{187},{ 9}}, {{443},{ 9}}, {{123},{ 9}}, {{379},{ 9}}, -{{251},{ 9}}, {{507},{ 9}}, {{ 7},{ 9}}, {{263},{ 9}}, {{135},{ 9}}, -{{391},{ 9}}, {{ 71},{ 9}}, {{327},{ 9}}, {{199},{ 9}}, {{455},{ 9}}, -{{ 39},{ 9}}, {{295},{ 9}}, {{167},{ 9}}, {{423},{ 9}}, {{103},{ 9}}, -{{359},{ 9}}, {{231},{ 9}}, {{487},{ 9}}, {{ 23},{ 9}}, {{279},{ 9}}, -{{151},{ 9}}, {{407},{ 9}}, {{ 87},{ 9}}, {{343},{ 9}}, {{215},{ 9}}, -{{471},{ 9}}, {{ 55},{ 9}}, {{311},{ 9}}, {{183},{ 9}}, {{439},{ 9}}, -{{119},{ 9}}, {{375},{ 9}}, {{247},{ 9}}, {{503},{ 9}}, {{ 15},{ 9}}, -{{271},{ 9}}, {{143},{ 9}}, {{399},{ 9}}, {{ 79},{ 9}}, {{335},{ 9}}, -{{207},{ 9}}, {{463},{ 9}}, {{ 47},{ 9}}, {{303},{ 9}}, {{175},{ 9}}, -{{431},{ 9}}, {{111},{ 9}}, {{367},{ 9}}, {{239},{ 9}}, {{495},{ 9}}, -{{ 31},{ 9}}, {{287},{ 9}}, {{159},{ 9}}, {{415},{ 9}}, {{ 95},{ 9}}, -{{351},{ 9}}, {{223},{ 9}}, {{479},{ 9}}, {{ 63},{ 9}}, {{319},{ 9}}, -{{191},{ 9}}, {{447},{ 9}}, {{127},{ 9}}, {{383},{ 9}}, {{255},{ 9}}, -{{511},{ 9}}, {{ 0},{ 7}}, {{ 64},{ 7}}, {{ 32},{ 7}}, {{ 96},{ 7}}, -{{ 16},{ 7}}, {{ 80},{ 7}}, {{ 48},{ 7}}, {{112},{ 7}}, {{ 8},{ 7}}, -{{ 72},{ 7}}, {{ 40},{ 7}}, {{104},{ 7}}, {{ 24},{ 7}}, {{ 88},{ 7}}, -{{ 56},{ 7}}, {{120},{ 7}}, {{ 4},{ 7}}, {{ 68},{ 7}}, {{ 36},{ 7}}, -{{100},{ 7}}, {{ 20},{ 7}}, {{ 84},{ 7}}, {{ 52},{ 7}}, {{116},{ 7}}, -{{ 3},{ 8}}, {{131},{ 8}}, {{ 67},{ 8}}, {{195},{ 8}}, {{ 35},{ 8}}, -{{163},{ 8}}, {{ 99},{ 8}}, {{227},{ 8}} -}; - -local const ct_data static_dtree[D_CODES] = { -{{ 0},{ 5}}, {{16},{ 5}}, {{ 8},{ 5}}, {{24},{ 5}}, {{ 4},{ 5}}, -{{20},{ 5}}, {{12},{ 5}}, {{28},{ 5}}, {{ 2},{ 5}}, {{18},{ 5}}, -{{10},{ 5}}, {{26},{ 5}}, {{ 6},{ 5}}, {{22},{ 5}}, {{14},{ 5}}, -{{30},{ 5}}, {{ 1},{ 5}}, {{17},{ 5}}, {{ 9},{ 5}}, {{25},{ 5}}, -{{ 5},{ 5}}, {{21},{ 5}}, {{13},{ 5}}, {{29},{ 5}}, {{ 3},{ 5}}, -{{19},{ 5}}, {{11},{ 5}}, {{27},{ 5}}, {{ 7},{ 5}}, {{23},{ 5}} -}; - -const uch _dist_code[DIST_CODE_LEN] = { - 0, 1, 2, 3, 4, 4, 5, 5, 6, 6, 6, 6, 7, 7, 7, 7, 8, 8, 8, 8, - 8, 8, 8, 8, 9, 9, 9, 9, 9, 9, 9, 9, 10, 10, 10, 10, 10, 10, 10, 10, -10, 10, 10, 10, 10, 10, 10, 10, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, -11, 11, 11, 11, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, -12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 13, 13, 13, 13, -13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, -13, 13, 13, 13, 13, 13, 13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, -14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, -14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, -14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15, 15, 15, -15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, -15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, -15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 16, 17, -18, 18, 19, 19, 20, 20, 20, 20, 21, 21, 21, 21, 22, 22, 22, 22, 22, 22, 22, 22, -23, 23, 23, 23, 23, 23, 23, 23, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, -24, 24, 24, 24, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, -26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, -26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 27, 27, 27, 27, 27, 27, 27, 27, -27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, -27, 27, 27, 27, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, -28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, -28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, -28, 28, 28, 28, 28, 28, 28, 28, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, -29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, -29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, -29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29 -}; - -const uch _length_code[MAX_MATCH-MIN_MATCH+1]= { - 0, 1, 2, 3, 4, 5, 6, 7, 8, 8, 9, 9, 10, 10, 11, 11, 12, 12, 12, 12, -13, 13, 13, 13, 14, 14, 14, 14, 15, 15, 15, 15, 16, 16, 16, 16, 16, 16, 16, 16, -17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 19, 19, 19, 19, -19, 19, 19, 19, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, -21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 22, 22, 22, 22, -22, 22, 22, 22, 22, 22, 22, 22, 22, 22, 22, 22, 23, 23, 23, 23, 23, 23, 23, 23, -23, 23, 23, 23, 23, 23, 23, 23, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, -24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, -25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, -25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 26, 26, 26, 26, 26, 26, 26, 26, -26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, -26, 26, 26, 26, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, -27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 28 -}; - -local const int base_length[LENGTH_CODES] = { -0, 1, 2, 3, 4, 5, 6, 7, 8, 10, 12, 14, 16, 20, 24, 28, 32, 40, 48, 56, -64, 80, 96, 112, 128, 160, 192, 224, 0 -}; - -local const int base_dist[D_CODES] = { - 0, 1, 2, 3, 4, 6, 8, 12, 16, 24, - 32, 48, 64, 96, 128, 192, 256, 384, 512, 768, - 1024, 1536, 2048, 3072, 4096, 6144, 8192, 12288, 16384, 24576 -}; - +/* header created automatically with -DGEN_TREES_H */ + +local const ct_data static_ltree[L_CODES+2] = { +{{ 12},{ 8}}, {{140},{ 8}}, {{ 76},{ 8}}, {{204},{ 8}}, {{ 44},{ 8}}, +{{172},{ 8}}, {{108},{ 8}}, {{236},{ 8}}, {{ 28},{ 8}}, {{156},{ 8}}, +{{ 92},{ 8}}, {{220},{ 8}}, {{ 60},{ 8}}, {{188},{ 8}}, {{124},{ 8}}, +{{252},{ 8}}, {{ 2},{ 8}}, {{130},{ 8}}, {{ 66},{ 8}}, {{194},{ 8}}, +{{ 34},{ 8}}, {{162},{ 8}}, {{ 98},{ 8}}, {{226},{ 8}}, {{ 18},{ 8}}, +{{146},{ 8}}, {{ 82},{ 8}}, {{210},{ 8}}, {{ 50},{ 8}}, {{178},{ 8}}, +{{114},{ 8}}, {{242},{ 8}}, {{ 10},{ 8}}, {{138},{ 8}}, {{ 74},{ 8}}, +{{202},{ 8}}, {{ 42},{ 8}}, {{170},{ 8}}, {{106},{ 8}}, {{234},{ 8}}, +{{ 26},{ 8}}, {{154},{ 8}}, {{ 90},{ 8}}, {{218},{ 8}}, {{ 58},{ 8}}, +{{186},{ 8}}, {{122},{ 8}}, {{250},{ 8}}, {{ 6},{ 8}}, {{134},{ 8}}, +{{ 70},{ 8}}, {{198},{ 8}}, {{ 38},{ 8}}, {{166},{ 8}}, {{102},{ 8}}, +{{230},{ 8}}, {{ 22},{ 8}}, {{150},{ 8}}, {{ 86},{ 8}}, {{214},{ 8}}, +{{ 54},{ 8}}, {{182},{ 8}}, {{118},{ 8}}, {{246},{ 8}}, {{ 14},{ 8}}, +{{142},{ 8}}, {{ 78},{ 8}}, {{206},{ 8}}, {{ 46},{ 8}}, {{174},{ 8}}, +{{110},{ 8}}, {{238},{ 8}}, {{ 30},{ 8}}, {{158},{ 8}}, {{ 94},{ 8}}, +{{222},{ 8}}, {{ 62},{ 8}}, {{190},{ 8}}, {{126},{ 8}}, {{254},{ 8}}, +{{ 1},{ 8}}, {{129},{ 8}}, {{ 65},{ 8}}, {{193},{ 8}}, {{ 33},{ 8}}, +{{161},{ 8}}, {{ 97},{ 8}}, {{225},{ 8}}, {{ 17},{ 8}}, {{145},{ 8}}, +{{ 81},{ 8}}, {{209},{ 8}}, {{ 49},{ 8}}, {{177},{ 8}}, {{113},{ 8}}, +{{241},{ 8}}, {{ 9},{ 8}}, {{137},{ 8}}, {{ 73},{ 8}}, {{201},{ 8}}, +{{ 41},{ 8}}, {{169},{ 8}}, {{105},{ 8}}, {{233},{ 8}}, {{ 25},{ 8}}, +{{153},{ 8}}, {{ 89},{ 8}}, {{217},{ 8}}, {{ 57},{ 8}}, {{185},{ 8}}, +{{121},{ 8}}, {{249},{ 8}}, {{ 5},{ 8}}, {{133},{ 8}}, {{ 69},{ 8}}, +{{197},{ 8}}, {{ 37},{ 8}}, {{165},{ 8}}, {{101},{ 8}}, {{229},{ 8}}, +{{ 21},{ 8}}, {{149},{ 8}}, {{ 85},{ 8}}, {{213},{ 8}}, {{ 53},{ 8}}, +{{181},{ 8}}, {{117},{ 8}}, {{245},{ 8}}, {{ 13},{ 8}}, {{141},{ 8}}, +{{ 77},{ 8}}, {{205},{ 8}}, {{ 45},{ 8}}, {{173},{ 8}}, {{109},{ 8}}, +{{237},{ 8}}, {{ 29},{ 8}}, {{157},{ 8}}, {{ 93},{ 8}}, {{221},{ 8}}, +{{ 61},{ 8}}, {{189},{ 8}}, {{125},{ 8}}, {{253},{ 8}}, {{ 19},{ 9}}, +{{275},{ 9}}, {{147},{ 9}}, {{403},{ 9}}, {{ 83},{ 9}}, {{339},{ 9}}, +{{211},{ 9}}, {{467},{ 9}}, {{ 51},{ 9}}, {{307},{ 9}}, {{179},{ 9}}, +{{435},{ 9}}, {{115},{ 9}}, {{371},{ 9}}, {{243},{ 9}}, {{499},{ 9}}, +{{ 11},{ 9}}, {{267},{ 9}}, {{139},{ 9}}, {{395},{ 9}}, {{ 75},{ 9}}, +{{331},{ 9}}, {{203},{ 9}}, {{459},{ 9}}, {{ 43},{ 9}}, {{299},{ 9}}, +{{171},{ 9}}, {{427},{ 9}}, {{107},{ 9}}, {{363},{ 9}}, {{235},{ 9}}, +{{491},{ 9}}, {{ 27},{ 9}}, {{283},{ 9}}, {{155},{ 9}}, {{411},{ 9}}, +{{ 91},{ 9}}, {{347},{ 9}}, {{219},{ 9}}, {{475},{ 9}}, {{ 59},{ 9}}, +{{315},{ 9}}, {{187},{ 9}}, {{443},{ 9}}, {{123},{ 9}}, {{379},{ 9}}, +{{251},{ 9}}, {{507},{ 9}}, {{ 7},{ 9}}, {{263},{ 9}}, {{135},{ 9}}, +{{391},{ 9}}, {{ 71},{ 9}}, {{327},{ 9}}, {{199},{ 9}}, {{455},{ 9}}, +{{ 39},{ 9}}, {{295},{ 9}}, {{167},{ 9}}, {{423},{ 9}}, {{103},{ 9}}, +{{359},{ 9}}, {{231},{ 9}}, {{487},{ 9}}, {{ 23},{ 9}}, {{279},{ 9}}, +{{151},{ 9}}, {{407},{ 9}}, {{ 87},{ 9}}, {{343},{ 9}}, {{215},{ 9}}, +{{471},{ 9}}, {{ 55},{ 9}}, {{311},{ 9}}, {{183},{ 9}}, {{439},{ 9}}, +{{119},{ 9}}, {{375},{ 9}}, {{247},{ 9}}, {{503},{ 9}}, {{ 15},{ 9}}, +{{271},{ 9}}, {{143},{ 9}}, {{399},{ 9}}, {{ 79},{ 9}}, {{335},{ 9}}, +{{207},{ 9}}, {{463},{ 9}}, {{ 47},{ 9}}, {{303},{ 9}}, {{175},{ 9}}, +{{431},{ 9}}, {{111},{ 9}}, {{367},{ 9}}, {{239},{ 9}}, {{495},{ 9}}, +{{ 31},{ 9}}, {{287},{ 9}}, {{159},{ 9}}, {{415},{ 9}}, {{ 95},{ 9}}, +{{351},{ 9}}, {{223},{ 9}}, {{479},{ 9}}, {{ 63},{ 9}}, {{319},{ 9}}, +{{191},{ 9}}, {{447},{ 9}}, {{127},{ 9}}, {{383},{ 9}}, {{255},{ 9}}, +{{511},{ 9}}, {{ 0},{ 7}}, {{ 64},{ 7}}, {{ 32},{ 7}}, {{ 96},{ 7}}, +{{ 16},{ 7}}, {{ 80},{ 7}}, {{ 48},{ 7}}, {{112},{ 7}}, {{ 8},{ 7}}, +{{ 72},{ 7}}, {{ 40},{ 7}}, {{104},{ 7}}, {{ 24},{ 7}}, {{ 88},{ 7}}, +{{ 56},{ 7}}, {{120},{ 7}}, {{ 4},{ 7}}, {{ 68},{ 7}}, {{ 36},{ 7}}, +{{100},{ 7}}, {{ 20},{ 7}}, {{ 84},{ 7}}, {{ 52},{ 7}}, {{116},{ 7}}, +{{ 3},{ 8}}, {{131},{ 8}}, {{ 67},{ 8}}, {{195},{ 8}}, {{ 35},{ 8}}, +{{163},{ 8}}, {{ 99},{ 8}}, {{227},{ 8}} +}; + +local const ct_data static_dtree[D_CODES] = { +{{ 0},{ 5}}, {{16},{ 5}}, {{ 8},{ 5}}, {{24},{ 5}}, {{ 4},{ 5}}, +{{20},{ 5}}, {{12},{ 5}}, {{28},{ 5}}, {{ 2},{ 5}}, {{18},{ 5}}, +{{10},{ 5}}, {{26},{ 5}}, {{ 6},{ 5}}, {{22},{ 5}}, {{14},{ 5}}, +{{30},{ 5}}, {{ 1},{ 5}}, {{17},{ 5}}, {{ 9},{ 5}}, {{25},{ 5}}, +{{ 5},{ 5}}, {{21},{ 5}}, {{13},{ 5}}, {{29},{ 5}}, {{ 3},{ 5}}, +{{19},{ 5}}, {{11},{ 5}}, {{27},{ 5}}, {{ 7},{ 5}}, {{23},{ 5}} +}; + +const uch _dist_code[DIST_CODE_LEN] = { + 0, 1, 2, 3, 4, 4, 5, 5, 6, 6, 6, 6, 7, 7, 7, 7, 8, 8, 8, 8, + 8, 8, 8, 8, 9, 9, 9, 9, 9, 9, 9, 9, 10, 10, 10, 10, 10, 10, 10, 10, +10, 10, 10, 10, 10, 10, 10, 10, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, +11, 11, 11, 11, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, +12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 13, 13, 13, 13, +13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, +13, 13, 13, 13, 13, 13, 13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, +14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, +14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, +14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15, 15, 15, +15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, +15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, +15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 16, 17, +18, 18, 19, 19, 20, 20, 20, 20, 21, 21, 21, 21, 22, 22, 22, 22, 22, 22, 22, 22, +23, 23, 23, 23, 23, 23, 23, 23, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, +24, 24, 24, 24, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, +26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, +26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 27, 27, 27, 27, 27, 27, 27, 27, +27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, +27, 27, 27, 27, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, +28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, +28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, +28, 28, 28, 28, 28, 28, 28, 28, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, +29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, +29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, +29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29, 29 +}; + +const uch _length_code[MAX_MATCH-MIN_MATCH+1]= { + 0, 1, 2, 3, 4, 5, 6, 7, 8, 8, 9, 9, 10, 10, 11, 11, 12, 12, 12, 12, +13, 13, 13, 13, 14, 14, 14, 14, 15, 15, 15, 15, 16, 16, 16, 16, 16, 16, 16, 16, +17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 19, 19, 19, 19, +19, 19, 19, 19, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, 20, +21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 21, 22, 22, 22, 22, +22, 22, 22, 22, 22, 22, 22, 22, 22, 22, 22, 22, 23, 23, 23, 23, 23, 23, 23, 23, +23, 23, 23, 23, 23, 23, 23, 23, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, +24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, 24, +25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, +25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 25, 26, 26, 26, 26, 26, 26, 26, 26, +26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, 26, +26, 26, 26, 26, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, +27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 27, 28 +}; + +local const int base_length[LENGTH_CODES] = { +0, 1, 2, 3, 4, 5, 6, 7, 8, 10, 12, 14, 16, 20, 24, 28, 32, 40, 48, 56, +64, 80, 96, 112, 128, 160, 192, 224, 0 +}; + +local const int base_dist[D_CODES] = { + 0, 1, 2, 3, 4, 6, 8, 12, 16, 24, + 32, 48, 64, 96, 128, 192, 256, 384, 512, 768, + 1024, 1536, 2048, 3072, 4096, 6144, 8192, 12288, 16384, 24576 +}; + diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/uncompr.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/uncompr.c index 62161b004..9304b9d1f 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/uncompr.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/uncompr.c @@ -1,61 +1,61 @@ -/* uncompr.c -- decompress a memory buffer - * Copyright (C) 1995-2003 Jean-loup Gailly. - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* @(#) $Id$ */ - -#define ZLIB_INTERNAL -#include "zlib.h" - -/* =========================================================================== - Decompresses the source buffer into the destination buffer. sourceLen is - the byte length of the source buffer. Upon entry, destLen is the total - size of the destination buffer, which must be large enough to hold the - entire uncompressed data. (The size of the uncompressed data must have - been saved previously by the compressor and transmitted to the decompressor - by some mechanism outside the scope of this compression library.) - Upon exit, destLen is the actual size of the compressed buffer. - This function can be used to decompress a whole file at once if the - input file is mmap'ed. - - uncompress returns Z_OK if success, Z_MEM_ERROR if there was not - enough memory, Z_BUF_ERROR if there was not enough room in the output - buffer, or Z_DATA_ERROR if the input data was corrupted. -*/ -int Q_ZEXPORT uncompress (dest, destLen, source, sourceLen) - Bytef *dest; - uLongf *destLen; - const Bytef *source; - uLong sourceLen; -{ - z_stream stream; - int err; - - stream.next_in = (Bytef*)source; - stream.avail_in = (uInt)sourceLen; - /* Check for source > 64K on 16-bit machine: */ - if ((uLong)stream.avail_in != sourceLen) return Z_BUF_ERROR; - - stream.next_out = dest; - stream.avail_out = (uInt)*destLen; - if ((uLong)stream.avail_out != *destLen) return Z_BUF_ERROR; - - stream.zalloc = (alloc_func)0; - stream.zfree = (free_func)0; - - err = inflateInit(&stream); - if (err != Z_OK) return err; - - err = inflate(&stream, Z_FINISH); - if (err != Z_STREAM_END) { - inflateEnd(&stream); - if (err == Z_NEED_DICT || (err == Z_BUF_ERROR && stream.avail_in == 0)) - return Z_DATA_ERROR; - return err; - } - *destLen = stream.total_out; - - err = inflateEnd(&stream); - return err; -} +/* uncompr.c -- decompress a memory buffer + * Copyright (C) 1995-2003 Jean-loup Gailly. + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* @(#) $Id$ */ + +#define ZLIB_INTERNAL +#include "zlib.h" + +/* =========================================================================== + Decompresses the source buffer into the destination buffer. sourceLen is + the byte length of the source buffer. Upon entry, destLen is the total + size of the destination buffer, which must be large enough to hold the + entire uncompressed data. (The size of the uncompressed data must have + been saved previously by the compressor and transmitted to the decompressor + by some mechanism outside the scope of this compression library.) + Upon exit, destLen is the actual size of the compressed buffer. + This function can be used to decompress a whole file at once if the + input file is mmap'ed. + + uncompress returns Z_OK if success, Z_MEM_ERROR if there was not + enough memory, Z_BUF_ERROR if there was not enough room in the output + buffer, or Z_DATA_ERROR if the input data was corrupted. +*/ +int Q_ZEXPORT uncompress (dest, destLen, source, sourceLen) + Bytef *dest; + uLongf *destLen; + const Bytef *source; + uLong sourceLen; +{ + z_stream stream; + int err; + + stream.next_in = (Bytef*)source; + stream.avail_in = (uInt)sourceLen; + /* Check for source > 64K on 16-bit machine: */ + if ((uLong)stream.avail_in != sourceLen) return Z_BUF_ERROR; + + stream.next_out = dest; + stream.avail_out = (uInt)*destLen; + if ((uLong)stream.avail_out != *destLen) return Z_BUF_ERROR; + + stream.zalloc = (alloc_func)0; + stream.zfree = (free_func)0; + + err = inflateInit(&stream); + if (err != Z_OK) return err; + + err = inflate(&stream, Z_FINISH); + if (err != Z_STREAM_END) { + inflateEnd(&stream); + if (err == Z_NEED_DICT || (err == Z_BUF_ERROR && stream.avail_in == 0)) + return Z_DATA_ERROR; + return err; + } + *destLen = stream.total_out; + + err = inflateEnd(&stream); + return err; +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zconf.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zconf.h index e3b0c962e..03a9431c8 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zconf.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zconf.h @@ -1,332 +1,332 @@ -/* zconf.h -- configuration of the zlib compression library - * Copyright (C) 1995-2005 Jean-loup Gailly. - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* @(#) $Id$ */ - -#ifndef ZCONF_H -#define ZCONF_H - -/* - * If you *really* need a unique prefix for all types and library functions, - * compile with -DZ_PREFIX. The "standard" zlib should be compiled without it. - */ -#ifdef Z_PREFIX -# define deflateInit_ z_deflateInit_ -# define deflate z_deflate -# define deflateEnd z_deflateEnd -# define inflateInit_ z_inflateInit_ -# define inflate z_inflate -# define inflateEnd z_inflateEnd -# define deflateInit2_ z_deflateInit2_ -# define deflateSetDictionary z_deflateSetDictionary -# define deflateCopy z_deflateCopy -# define deflateReset z_deflateReset -# define deflateParams z_deflateParams -# define deflateBound z_deflateBound -# define deflatePrime z_deflatePrime -# define inflateInit2_ z_inflateInit2_ -# define inflateSetDictionary z_inflateSetDictionary -# define inflateSync z_inflateSync -# define inflateSyncPoint z_inflateSyncPoint -# define inflateCopy z_inflateCopy -# define inflateReset z_inflateReset -# define inflateBack z_inflateBack -# define inflateBackEnd z_inflateBackEnd -# define compress z_compress -# define compress2 z_compress2 -# define compressBound z_compressBound -# define uncompress z_uncompress -# define adler32 z_adler32 -# define crc32 z_crc32 -# define get_crc_table z_get_crc_table -# define zError z_zError - -# define alloc_func z_alloc_func -# define free_func z_free_func -# define in_func z_in_func -# define out_func z_out_func -# define Byte z_Byte -# define uInt z_uInt -# define uLong z_uLong -# define Bytef z_Bytef -# define charf z_charf -# define intf z_intf -# define uIntf z_uIntf -# define uLongf z_uLongf -# define voidpf z_voidpf -# define voidp z_voidp -#endif - -#if defined(__MSDOS__) && !defined(MSDOS) -# define MSDOS -#endif -#if (defined(OS_2) || defined(__OS2__)) && !defined(OS2) -# define OS2 -#endif -#if defined(_WINDOWS) && !defined(WINDOWS) -# define WINDOWS -#endif -#if defined(_WIN32) || defined(_WIN32_WCE) || defined(__WIN32__) -# ifndef WIN32 -# define WIN32 -# endif -#endif -#if (defined(MSDOS) || defined(OS2) || defined(WINDOWS)) && !defined(WIN32) -# if !defined(__GNUC__) && !defined(__FLAT__) && !defined(__386__) -# ifndef SYS16BIT -# define SYS16BIT -# endif -# endif -#endif - -/* - * Compile with -DMAXSEG_64K if the alloc function cannot allocate more - * than 64k bytes at a time (needed on systems with 16-bit int). - */ -#ifdef SYS16BIT -# define MAXSEG_64K -#endif -#ifdef MSDOS -# define UNALIGNED_OK -#endif - -#ifdef __STDC_VERSION__ -# ifndef STDC -# define STDC -# endif -# if __STDC_VERSION__ >= 199901L -# ifndef STDC99 -# define STDC99 -# endif -# endif -#endif -#if !defined(STDC) && (defined(__STDC__) || defined(__cplusplus)) -# define STDC -#endif -#if !defined(STDC) && (defined(__GNUC__) || defined(__BORLANDC__)) -# define STDC -#endif -#if !defined(STDC) && (defined(MSDOS) || defined(WINDOWS) || defined(WIN32)) -# define STDC -#endif -#if !defined(STDC) && (defined(OS2) || defined(__HOS_AIX__)) -# define STDC -#endif - -#if defined(__OS400__) && !defined(STDC) /* iSeries (formerly AS/400). */ -# define STDC -#endif - -#ifndef STDC -# ifndef const /* cannot use !defined(STDC) && !defined(const) on Mac */ -# define const /* note: need a more gentle solution here */ -# endif -#endif - -/* Some Mac compilers merge all .h files incorrectly: */ -#if defined(__MWERKS__)||defined(applec)||defined(THINK_C)||defined(__SC__) -# define NO_DUMMY_DECL -#endif - -/* Maximum value for memLevel in deflateInit2 */ -#ifndef MAX_MEM_LEVEL -# ifdef MAXSEG_64K -# define MAX_MEM_LEVEL 8 -# else -# define MAX_MEM_LEVEL 9 -# endif -#endif - -/* Maximum value for windowBits in deflateInit2 and inflateInit2. - * WARNING: reducing MAX_WBITS makes minigzip unable to extract .gz files - * created by gzip. (Files created by minigzip can still be extracted by - * gzip.) - */ -#ifndef MAX_WBITS -# define MAX_WBITS 15 /* 32K LZ77 window */ -#endif - -/* The memory requirements for deflate are (in bytes): - (1 << (windowBits+2)) + (1 << (memLevel+9)) - that is: 128K for windowBits=15 + 128K for memLevel = 8 (default values) - plus a few kilobytes for small objects. For example, if you want to reduce - the default memory requirements from 256K to 128K, compile with - make CFLAGS="-O -DMAX_WBITS=14 -DMAX_MEM_LEVEL=7" - Of course this will generally degrade compression (there's no free lunch). - - The memory requirements for inflate are (in bytes) 1 << windowBits - that is, 32K for windowBits=15 (default value) plus a few kilobytes - for small objects. -*/ - - /* Type declarations */ - -#ifndef OF /* function prototypes */ -# ifdef STDC -# define OF(args) args -# else -# define OF(args) () -# endif -#endif - -/* The following definitions for FAR are needed only for MSDOS mixed - * model programming (small or medium model with some far allocations). - * This was tested only with MSC; for other MSDOS compilers you may have - * to define NO_MEMCPY in zutil.h. If you don't need the mixed model, - * just define FAR to be empty. - */ -#ifdef SYS16BIT -# if defined(M_I86SM) || defined(M_I86MM) - /* MSC small or medium model */ -# define SMALL_MEDIUM -# ifdef _MSC_VER -# define FAR _far -# else -# define FAR far -# endif -# endif -# if (defined(__SMALL__) || defined(__MEDIUM__)) - /* Turbo C small or medium model */ -# define SMALL_MEDIUM -# ifdef __BORLANDC__ -# define FAR _far -# else -# define FAR far -# endif -# endif -#endif - -#if defined(WINDOWS) || defined(WIN32) - /* If building or using zlib as a DLL, define ZLIB_DLL. - * This is not mandatory, but it offers a little performance increase. - */ -# ifdef ZLIB_DLL -# if defined(WIN32) && (!defined(__BORLANDC__) || (__BORLANDC__ >= 0x500)) -# ifdef ZLIB_INTERNAL -# define ZEXTERN extern __declspec(dllexport) -# else -# define ZEXTERN extern __declspec(dllimport) -# endif -# endif -# endif /* ZLIB_DLL */ - /* If building or using zlib with the WINAPI/WINAPIV calling convention, - * define ZLIB_WINAPI. - * Caution: the standard ZLIB1.DLL is NOT compiled using ZLIB_WINAPI. - */ -# ifdef ZLIB_WINAPI -# ifdef FAR -# undef FAR -# endif -# include - /* No need for _export, use ZLIB.DEF instead. */ - /* For complete Windows compatibility, use WINAPI, not __stdcall. */ -# define ZEXPORT WINAPI -# ifdef WIN32 -# define ZEXPORTVA WINAPIV -# else -# define ZEXPORTVA FAR CDECL -# endif -# endif -#endif - -#if defined (__BEOS__) -# ifdef ZLIB_DLL -# ifdef ZLIB_INTERNAL -# define ZEXPORT __declspec(dllexport) -# define ZEXPORTVA __declspec(dllexport) -# else -# define ZEXPORT __declspec(dllimport) -# define ZEXPORTVA __declspec(dllimport) -# endif -# endif -#endif - -#ifndef ZEXTERN -# define ZEXTERN extern -#endif -#ifndef ZEXPORT -# define ZEXPORT -#endif -#ifndef ZEXPORTVA -# define ZEXPORTVA -#endif - -#ifndef FAR -# define FAR -#endif - -#if !defined(__MACTYPES__) -typedef unsigned char Byte; /* 8 bits */ -#endif -typedef unsigned int uInt; /* 16 bits or more */ -typedef unsigned long uLong; /* 32 bits or more */ - -#ifdef SMALL_MEDIUM - /* Borland C/C++ and some old MSC versions ignore FAR inside typedef */ -# define Bytef Byte FAR -#else - typedef Byte FAR Bytef; -#endif -typedef char FAR charf; -typedef int FAR intf; -typedef uInt FAR uIntf; -typedef uLong FAR uLongf; - -#ifdef STDC - typedef void const *voidpc; - typedef void FAR *voidpf; - typedef void *voidp; -#else - typedef Byte const *voidpc; - typedef Byte FAR *voidpf; - typedef Byte *voidp; -#endif - -#if 0 /* HAVE_UNISTD_H -- this line is updated by ./configure */ -# include /* for off_t */ -# include /* for SEEK_* and off_t */ -# ifdef VMS -# include /* for off_t */ -# endif -# define z_off_t off_t -#endif -#ifndef SEEK_SET -# define SEEK_SET 0 /* Seek from beginning of file. */ -# define SEEK_CUR 1 /* Seek from current position. */ -# define SEEK_END 2 /* Set file pointer to EOF plus "offset" */ -#endif -#ifndef z_off_t -# define z_off_t long -#endif - -#if defined(__OS400__) -# define NO_vsnprintf -#endif - -#if defined(__MVS__) -# define NO_vsnprintf -# ifdef FAR -# undef FAR -# endif -#endif - -/* MVS linker does not support external names larger than 8 bytes */ -#if defined(__MVS__) -# pragma map(deflateInit_,"DEIN") -# pragma map(deflateInit2_,"DEIN2") -# pragma map(deflateEnd,"DEEND") -# pragma map(deflateBound,"DEBND") -# pragma map(inflateInit_,"ININ") -# pragma map(inflateInit2_,"ININ2") -# pragma map(inflateEnd,"INEND") -# pragma map(inflateSync,"INSY") -# pragma map(inflateSetDictionary,"INSEDI") -# pragma map(compressBound,"CMBND") -# pragma map(inflate_table,"INTABL") -# pragma map(inflate_fast,"INFA") -# pragma map(inflate_copyright,"INCOPY") -#endif - -#endif /* ZCONF_H */ +/* zconf.h -- configuration of the zlib compression library + * Copyright (C) 1995-2005 Jean-loup Gailly. + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* @(#) $Id$ */ + +#ifndef ZCONF_H +#define ZCONF_H + +/* + * If you *really* need a unique prefix for all types and library functions, + * compile with -DZ_PREFIX. The "standard" zlib should be compiled without it. + */ +#ifdef Z_PREFIX +# define deflateInit_ z_deflateInit_ +# define deflate z_deflate +# define deflateEnd z_deflateEnd +# define inflateInit_ z_inflateInit_ +# define inflate z_inflate +# define inflateEnd z_inflateEnd +# define deflateInit2_ z_deflateInit2_ +# define deflateSetDictionary z_deflateSetDictionary +# define deflateCopy z_deflateCopy +# define deflateReset z_deflateReset +# define deflateParams z_deflateParams +# define deflateBound z_deflateBound +# define deflatePrime z_deflatePrime +# define inflateInit2_ z_inflateInit2_ +# define inflateSetDictionary z_inflateSetDictionary +# define inflateSync z_inflateSync +# define inflateSyncPoint z_inflateSyncPoint +# define inflateCopy z_inflateCopy +# define inflateReset z_inflateReset +# define inflateBack z_inflateBack +# define inflateBackEnd z_inflateBackEnd +# define compress z_compress +# define compress2 z_compress2 +# define compressBound z_compressBound +# define uncompress z_uncompress +# define adler32 z_adler32 +# define crc32 z_crc32 +# define get_crc_table z_get_crc_table +# define zError z_zError + +# define alloc_func z_alloc_func +# define free_func z_free_func +# define in_func z_in_func +# define out_func z_out_func +# define Byte z_Byte +# define uInt z_uInt +# define uLong z_uLong +# define Bytef z_Bytef +# define charf z_charf +# define intf z_intf +# define uIntf z_uIntf +# define uLongf z_uLongf +# define voidpf z_voidpf +# define voidp z_voidp +#endif + +#if defined(__MSDOS__) && !defined(MSDOS) +# define MSDOS +#endif +#if (defined(OS_2) || defined(__OS2__)) && !defined(OS2) +# define OS2 +#endif +#if defined(_WINDOWS) && !defined(WINDOWS) +# define WINDOWS +#endif +#if defined(_WIN32) || defined(_WIN32_WCE) || defined(__WIN32__) +# ifndef WIN32 +# define WIN32 +# endif +#endif +#if (defined(MSDOS) || defined(OS2) || defined(WINDOWS)) && !defined(WIN32) +# if !defined(__GNUC__) && !defined(__FLAT__) && !defined(__386__) +# ifndef SYS16BIT +# define SYS16BIT +# endif +# endif +#endif + +/* + * Compile with -DMAXSEG_64K if the alloc function cannot allocate more + * than 64k bytes at a time (needed on systems with 16-bit int). + */ +#ifdef SYS16BIT +# define MAXSEG_64K +#endif +#ifdef MSDOS +# define UNALIGNED_OK +#endif + +#ifdef __STDC_VERSION__ +# ifndef STDC +# define STDC +# endif +# if __STDC_VERSION__ >= 199901L +# ifndef STDC99 +# define STDC99 +# endif +# endif +#endif +#if !defined(STDC) && (defined(__STDC__) || defined(__cplusplus)) +# define STDC +#endif +#if !defined(STDC) && (defined(__GNUC__) || defined(__BORLANDC__)) +# define STDC +#endif +#if !defined(STDC) && (defined(MSDOS) || defined(WINDOWS) || defined(WIN32)) +# define STDC +#endif +#if !defined(STDC) && (defined(OS2) || defined(__HOS_AIX__)) +# define STDC +#endif + +#if defined(__OS400__) && !defined(STDC) /* iSeries (formerly AS/400). */ +# define STDC +#endif + +#ifndef STDC +# ifndef const /* cannot use !defined(STDC) && !defined(const) on Mac */ +# define const /* note: need a more gentle solution here */ +# endif +#endif + +/* Some Mac compilers merge all .h files incorrectly: */ +#if defined(__MWERKS__)||defined(applec)||defined(THINK_C)||defined(__SC__) +# define NO_DUMMY_DECL +#endif + +/* Maximum value for memLevel in deflateInit2 */ +#ifndef MAX_MEM_LEVEL +# ifdef MAXSEG_64K +# define MAX_MEM_LEVEL 8 +# else +# define MAX_MEM_LEVEL 9 +# endif +#endif + +/* Maximum value for windowBits in deflateInit2 and inflateInit2. + * WARNING: reducing MAX_WBITS makes minigzip unable to extract .gz files + * created by gzip. (Files created by minigzip can still be extracted by + * gzip.) + */ +#ifndef MAX_WBITS +# define MAX_WBITS 15 /* 32K LZ77 window */ +#endif + +/* The memory requirements for deflate are (in bytes): + (1 << (windowBits+2)) + (1 << (memLevel+9)) + that is: 128K for windowBits=15 + 128K for memLevel = 8 (default values) + plus a few kilobytes for small objects. For example, if you want to reduce + the default memory requirements from 256K to 128K, compile with + make CFLAGS="-O -DMAX_WBITS=14 -DMAX_MEM_LEVEL=7" + Of course this will generally degrade compression (there's no free lunch). + + The memory requirements for inflate are (in bytes) 1 << windowBits + that is, 32K for windowBits=15 (default value) plus a few kilobytes + for small objects. +*/ + + /* Type declarations */ + +#ifndef OF /* function prototypes */ +# ifdef STDC +# define OF(args) args +# else +# define OF(args) () +# endif +#endif + +/* The following definitions for FAR are needed only for MSDOS mixed + * model programming (small or medium model with some far allocations). + * This was tested only with MSC; for other MSDOS compilers you may have + * to define NO_MEMCPY in zutil.h. If you don't need the mixed model, + * just define FAR to be empty. + */ +#ifdef SYS16BIT +# if defined(M_I86SM) || defined(M_I86MM) + /* MSC small or medium model */ +# define SMALL_MEDIUM +# ifdef _MSC_VER +# define FAR _far +# else +# define FAR far +# endif +# endif +# if (defined(__SMALL__) || defined(__MEDIUM__)) + /* Turbo C small or medium model */ +# define SMALL_MEDIUM +# ifdef __BORLANDC__ +# define FAR _far +# else +# define FAR far +# endif +# endif +#endif + +#if defined(WINDOWS) || defined(WIN32) + /* If building or using zlib as a DLL, define ZLIB_DLL. + * This is not mandatory, but it offers a little performance increase. + */ +# ifdef ZLIB_DLL +# if defined(WIN32) && (!defined(__BORLANDC__) || (__BORLANDC__ >= 0x500)) +# ifdef ZLIB_INTERNAL +# define ZEXTERN extern __declspec(dllexport) +# else +# define ZEXTERN extern __declspec(dllimport) +# endif +# endif +# endif /* ZLIB_DLL */ + /* If building or using zlib with the WINAPI/WINAPIV calling convention, + * define ZLIB_WINAPI. + * Caution: the standard ZLIB1.DLL is NOT compiled using ZLIB_WINAPI. + */ +# ifdef ZLIB_WINAPI +# ifdef FAR +# undef FAR +# endif +# include + /* No need for _export, use ZLIB.DEF instead. */ + /* For complete Windows compatibility, use WINAPI, not __stdcall. */ +# define ZEXPORT WINAPI +# ifdef WIN32 +# define ZEXPORTVA WINAPIV +# else +# define ZEXPORTVA FAR CDECL +# endif +# endif +#endif + +#if defined (__BEOS__) +# ifdef ZLIB_DLL +# ifdef ZLIB_INTERNAL +# define ZEXPORT __declspec(dllexport) +# define ZEXPORTVA __declspec(dllexport) +# else +# define ZEXPORT __declspec(dllimport) +# define ZEXPORTVA __declspec(dllimport) +# endif +# endif +#endif + +#ifndef ZEXTERN +# define ZEXTERN extern +#endif +#ifndef ZEXPORT +# define ZEXPORT +#endif +#ifndef ZEXPORTVA +# define ZEXPORTVA +#endif + +#ifndef FAR +# define FAR +#endif + +#if !defined(__MACTYPES__) +typedef unsigned char Byte; /* 8 bits */ +#endif +typedef unsigned int uInt; /* 16 bits or more */ +typedef unsigned long uLong; /* 32 bits or more */ + +#ifdef SMALL_MEDIUM + /* Borland C/C++ and some old MSC versions ignore FAR inside typedef */ +# define Bytef Byte FAR +#else + typedef Byte FAR Bytef; +#endif +typedef char FAR charf; +typedef int FAR intf; +typedef uInt FAR uIntf; +typedef uLong FAR uLongf; + +#ifdef STDC + typedef void const *voidpc; + typedef void FAR *voidpf; + typedef void *voidp; +#else + typedef Byte const *voidpc; + typedef Byte FAR *voidpf; + typedef Byte *voidp; +#endif + +#if 0 /* HAVE_UNISTD_H -- this line is updated by ./configure */ +# include /* for off_t */ +# include /* for SEEK_* and off_t */ +# ifdef VMS +# include /* for off_t */ +# endif +# define z_off_t off_t +#endif +#ifndef SEEK_SET +# define SEEK_SET 0 /* Seek from beginning of file. */ +# define SEEK_CUR 1 /* Seek from current position. */ +# define SEEK_END 2 /* Set file pointer to EOF plus "offset" */ +#endif +#ifndef z_off_t +# define z_off_t long +#endif + +#if defined(__OS400__) +# define NO_vsnprintf +#endif + +#if defined(__MVS__) +# define NO_vsnprintf +# ifdef FAR +# undef FAR +# endif +#endif + +/* MVS linker does not support external names larger than 8 bytes */ +#if defined(__MVS__) +# pragma map(deflateInit_,"DEIN") +# pragma map(deflateInit2_,"DEIN2") +# pragma map(deflateEnd,"DEEND") +# pragma map(deflateBound,"DEBND") +# pragma map(inflateInit_,"ININ") +# pragma map(inflateInit2_,"ININ2") +# pragma map(inflateEnd,"INEND") +# pragma map(inflateSync,"INSY") +# pragma map(inflateSetDictionary,"INSEDI") +# pragma map(compressBound,"CMBND") +# pragma map(inflate_table,"INTABL") +# pragma map(inflate_fast,"INFA") +# pragma map(inflate_copyright,"INCOPY") +#endif + +#endif /* ZCONF_H */ diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zconf.in.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zconf.in.h index e3b0c962e..03a9431c8 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zconf.in.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zconf.in.h @@ -1,332 +1,332 @@ -/* zconf.h -- configuration of the zlib compression library - * Copyright (C) 1995-2005 Jean-loup Gailly. - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* @(#) $Id$ */ - -#ifndef ZCONF_H -#define ZCONF_H - -/* - * If you *really* need a unique prefix for all types and library functions, - * compile with -DZ_PREFIX. The "standard" zlib should be compiled without it. - */ -#ifdef Z_PREFIX -# define deflateInit_ z_deflateInit_ -# define deflate z_deflate -# define deflateEnd z_deflateEnd -# define inflateInit_ z_inflateInit_ -# define inflate z_inflate -# define inflateEnd z_inflateEnd -# define deflateInit2_ z_deflateInit2_ -# define deflateSetDictionary z_deflateSetDictionary -# define deflateCopy z_deflateCopy -# define deflateReset z_deflateReset -# define deflateParams z_deflateParams -# define deflateBound z_deflateBound -# define deflatePrime z_deflatePrime -# define inflateInit2_ z_inflateInit2_ -# define inflateSetDictionary z_inflateSetDictionary -# define inflateSync z_inflateSync -# define inflateSyncPoint z_inflateSyncPoint -# define inflateCopy z_inflateCopy -# define inflateReset z_inflateReset -# define inflateBack z_inflateBack -# define inflateBackEnd z_inflateBackEnd -# define compress z_compress -# define compress2 z_compress2 -# define compressBound z_compressBound -# define uncompress z_uncompress -# define adler32 z_adler32 -# define crc32 z_crc32 -# define get_crc_table z_get_crc_table -# define zError z_zError - -# define alloc_func z_alloc_func -# define free_func z_free_func -# define in_func z_in_func -# define out_func z_out_func -# define Byte z_Byte -# define uInt z_uInt -# define uLong z_uLong -# define Bytef z_Bytef -# define charf z_charf -# define intf z_intf -# define uIntf z_uIntf -# define uLongf z_uLongf -# define voidpf z_voidpf -# define voidp z_voidp -#endif - -#if defined(__MSDOS__) && !defined(MSDOS) -# define MSDOS -#endif -#if (defined(OS_2) || defined(__OS2__)) && !defined(OS2) -# define OS2 -#endif -#if defined(_WINDOWS) && !defined(WINDOWS) -# define WINDOWS -#endif -#if defined(_WIN32) || defined(_WIN32_WCE) || defined(__WIN32__) -# ifndef WIN32 -# define WIN32 -# endif -#endif -#if (defined(MSDOS) || defined(OS2) || defined(WINDOWS)) && !defined(WIN32) -# if !defined(__GNUC__) && !defined(__FLAT__) && !defined(__386__) -# ifndef SYS16BIT -# define SYS16BIT -# endif -# endif -#endif - -/* - * Compile with -DMAXSEG_64K if the alloc function cannot allocate more - * than 64k bytes at a time (needed on systems with 16-bit int). - */ -#ifdef SYS16BIT -# define MAXSEG_64K -#endif -#ifdef MSDOS -# define UNALIGNED_OK -#endif - -#ifdef __STDC_VERSION__ -# ifndef STDC -# define STDC -# endif -# if __STDC_VERSION__ >= 199901L -# ifndef STDC99 -# define STDC99 -# endif -# endif -#endif -#if !defined(STDC) && (defined(__STDC__) || defined(__cplusplus)) -# define STDC -#endif -#if !defined(STDC) && (defined(__GNUC__) || defined(__BORLANDC__)) -# define STDC -#endif -#if !defined(STDC) && (defined(MSDOS) || defined(WINDOWS) || defined(WIN32)) -# define STDC -#endif -#if !defined(STDC) && (defined(OS2) || defined(__HOS_AIX__)) -# define STDC -#endif - -#if defined(__OS400__) && !defined(STDC) /* iSeries (formerly AS/400). */ -# define STDC -#endif - -#ifndef STDC -# ifndef const /* cannot use !defined(STDC) && !defined(const) on Mac */ -# define const /* note: need a more gentle solution here */ -# endif -#endif - -/* Some Mac compilers merge all .h files incorrectly: */ -#if defined(__MWERKS__)||defined(applec)||defined(THINK_C)||defined(__SC__) -# define NO_DUMMY_DECL -#endif - -/* Maximum value for memLevel in deflateInit2 */ -#ifndef MAX_MEM_LEVEL -# ifdef MAXSEG_64K -# define MAX_MEM_LEVEL 8 -# else -# define MAX_MEM_LEVEL 9 -# endif -#endif - -/* Maximum value for windowBits in deflateInit2 and inflateInit2. - * WARNING: reducing MAX_WBITS makes minigzip unable to extract .gz files - * created by gzip. (Files created by minigzip can still be extracted by - * gzip.) - */ -#ifndef MAX_WBITS -# define MAX_WBITS 15 /* 32K LZ77 window */ -#endif - -/* The memory requirements for deflate are (in bytes): - (1 << (windowBits+2)) + (1 << (memLevel+9)) - that is: 128K for windowBits=15 + 128K for memLevel = 8 (default values) - plus a few kilobytes for small objects. For example, if you want to reduce - the default memory requirements from 256K to 128K, compile with - make CFLAGS="-O -DMAX_WBITS=14 -DMAX_MEM_LEVEL=7" - Of course this will generally degrade compression (there's no free lunch). - - The memory requirements for inflate are (in bytes) 1 << windowBits - that is, 32K for windowBits=15 (default value) plus a few kilobytes - for small objects. -*/ - - /* Type declarations */ - -#ifndef OF /* function prototypes */ -# ifdef STDC -# define OF(args) args -# else -# define OF(args) () -# endif -#endif - -/* The following definitions for FAR are needed only for MSDOS mixed - * model programming (small or medium model with some far allocations). - * This was tested only with MSC; for other MSDOS compilers you may have - * to define NO_MEMCPY in zutil.h. If you don't need the mixed model, - * just define FAR to be empty. - */ -#ifdef SYS16BIT -# if defined(M_I86SM) || defined(M_I86MM) - /* MSC small or medium model */ -# define SMALL_MEDIUM -# ifdef _MSC_VER -# define FAR _far -# else -# define FAR far -# endif -# endif -# if (defined(__SMALL__) || defined(__MEDIUM__)) - /* Turbo C small or medium model */ -# define SMALL_MEDIUM -# ifdef __BORLANDC__ -# define FAR _far -# else -# define FAR far -# endif -# endif -#endif - -#if defined(WINDOWS) || defined(WIN32) - /* If building or using zlib as a DLL, define ZLIB_DLL. - * This is not mandatory, but it offers a little performance increase. - */ -# ifdef ZLIB_DLL -# if defined(WIN32) && (!defined(__BORLANDC__) || (__BORLANDC__ >= 0x500)) -# ifdef ZLIB_INTERNAL -# define ZEXTERN extern __declspec(dllexport) -# else -# define ZEXTERN extern __declspec(dllimport) -# endif -# endif -# endif /* ZLIB_DLL */ - /* If building or using zlib with the WINAPI/WINAPIV calling convention, - * define ZLIB_WINAPI. - * Caution: the standard ZLIB1.DLL is NOT compiled using ZLIB_WINAPI. - */ -# ifdef ZLIB_WINAPI -# ifdef FAR -# undef FAR -# endif -# include - /* No need for _export, use ZLIB.DEF instead. */ - /* For complete Windows compatibility, use WINAPI, not __stdcall. */ -# define ZEXPORT WINAPI -# ifdef WIN32 -# define ZEXPORTVA WINAPIV -# else -# define ZEXPORTVA FAR CDECL -# endif -# endif -#endif - -#if defined (__BEOS__) -# ifdef ZLIB_DLL -# ifdef ZLIB_INTERNAL -# define ZEXPORT __declspec(dllexport) -# define ZEXPORTVA __declspec(dllexport) -# else -# define ZEXPORT __declspec(dllimport) -# define ZEXPORTVA __declspec(dllimport) -# endif -# endif -#endif - -#ifndef ZEXTERN -# define ZEXTERN extern -#endif -#ifndef ZEXPORT -# define ZEXPORT -#endif -#ifndef ZEXPORTVA -# define ZEXPORTVA -#endif - -#ifndef FAR -# define FAR -#endif - -#if !defined(__MACTYPES__) -typedef unsigned char Byte; /* 8 bits */ -#endif -typedef unsigned int uInt; /* 16 bits or more */ -typedef unsigned long uLong; /* 32 bits or more */ - -#ifdef SMALL_MEDIUM - /* Borland C/C++ and some old MSC versions ignore FAR inside typedef */ -# define Bytef Byte FAR -#else - typedef Byte FAR Bytef; -#endif -typedef char FAR charf; -typedef int FAR intf; -typedef uInt FAR uIntf; -typedef uLong FAR uLongf; - -#ifdef STDC - typedef void const *voidpc; - typedef void FAR *voidpf; - typedef void *voidp; -#else - typedef Byte const *voidpc; - typedef Byte FAR *voidpf; - typedef Byte *voidp; -#endif - -#if 0 /* HAVE_UNISTD_H -- this line is updated by ./configure */ -# include /* for off_t */ -# include /* for SEEK_* and off_t */ -# ifdef VMS -# include /* for off_t */ -# endif -# define z_off_t off_t -#endif -#ifndef SEEK_SET -# define SEEK_SET 0 /* Seek from beginning of file. */ -# define SEEK_CUR 1 /* Seek from current position. */ -# define SEEK_END 2 /* Set file pointer to EOF plus "offset" */ -#endif -#ifndef z_off_t -# define z_off_t long -#endif - -#if defined(__OS400__) -# define NO_vsnprintf -#endif - -#if defined(__MVS__) -# define NO_vsnprintf -# ifdef FAR -# undef FAR -# endif -#endif - -/* MVS linker does not support external names larger than 8 bytes */ -#if defined(__MVS__) -# pragma map(deflateInit_,"DEIN") -# pragma map(deflateInit2_,"DEIN2") -# pragma map(deflateEnd,"DEEND") -# pragma map(deflateBound,"DEBND") -# pragma map(inflateInit_,"ININ") -# pragma map(inflateInit2_,"ININ2") -# pragma map(inflateEnd,"INEND") -# pragma map(inflateSync,"INSY") -# pragma map(inflateSetDictionary,"INSEDI") -# pragma map(compressBound,"CMBND") -# pragma map(inflate_table,"INTABL") -# pragma map(inflate_fast,"INFA") -# pragma map(inflate_copyright,"INCOPY") -#endif - -#endif /* ZCONF_H */ +/* zconf.h -- configuration of the zlib compression library + * Copyright (C) 1995-2005 Jean-loup Gailly. + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* @(#) $Id$ */ + +#ifndef ZCONF_H +#define ZCONF_H + +/* + * If you *really* need a unique prefix for all types and library functions, + * compile with -DZ_PREFIX. The "standard" zlib should be compiled without it. + */ +#ifdef Z_PREFIX +# define deflateInit_ z_deflateInit_ +# define deflate z_deflate +# define deflateEnd z_deflateEnd +# define inflateInit_ z_inflateInit_ +# define inflate z_inflate +# define inflateEnd z_inflateEnd +# define deflateInit2_ z_deflateInit2_ +# define deflateSetDictionary z_deflateSetDictionary +# define deflateCopy z_deflateCopy +# define deflateReset z_deflateReset +# define deflateParams z_deflateParams +# define deflateBound z_deflateBound +# define deflatePrime z_deflatePrime +# define inflateInit2_ z_inflateInit2_ +# define inflateSetDictionary z_inflateSetDictionary +# define inflateSync z_inflateSync +# define inflateSyncPoint z_inflateSyncPoint +# define inflateCopy z_inflateCopy +# define inflateReset z_inflateReset +# define inflateBack z_inflateBack +# define inflateBackEnd z_inflateBackEnd +# define compress z_compress +# define compress2 z_compress2 +# define compressBound z_compressBound +# define uncompress z_uncompress +# define adler32 z_adler32 +# define crc32 z_crc32 +# define get_crc_table z_get_crc_table +# define zError z_zError + +# define alloc_func z_alloc_func +# define free_func z_free_func +# define in_func z_in_func +# define out_func z_out_func +# define Byte z_Byte +# define uInt z_uInt +# define uLong z_uLong +# define Bytef z_Bytef +# define charf z_charf +# define intf z_intf +# define uIntf z_uIntf +# define uLongf z_uLongf +# define voidpf z_voidpf +# define voidp z_voidp +#endif + +#if defined(__MSDOS__) && !defined(MSDOS) +# define MSDOS +#endif +#if (defined(OS_2) || defined(__OS2__)) && !defined(OS2) +# define OS2 +#endif +#if defined(_WINDOWS) && !defined(WINDOWS) +# define WINDOWS +#endif +#if defined(_WIN32) || defined(_WIN32_WCE) || defined(__WIN32__) +# ifndef WIN32 +# define WIN32 +# endif +#endif +#if (defined(MSDOS) || defined(OS2) || defined(WINDOWS)) && !defined(WIN32) +# if !defined(__GNUC__) && !defined(__FLAT__) && !defined(__386__) +# ifndef SYS16BIT +# define SYS16BIT +# endif +# endif +#endif + +/* + * Compile with -DMAXSEG_64K if the alloc function cannot allocate more + * than 64k bytes at a time (needed on systems with 16-bit int). + */ +#ifdef SYS16BIT +# define MAXSEG_64K +#endif +#ifdef MSDOS +# define UNALIGNED_OK +#endif + +#ifdef __STDC_VERSION__ +# ifndef STDC +# define STDC +# endif +# if __STDC_VERSION__ >= 199901L +# ifndef STDC99 +# define STDC99 +# endif +# endif +#endif +#if !defined(STDC) && (defined(__STDC__) || defined(__cplusplus)) +# define STDC +#endif +#if !defined(STDC) && (defined(__GNUC__) || defined(__BORLANDC__)) +# define STDC +#endif +#if !defined(STDC) && (defined(MSDOS) || defined(WINDOWS) || defined(WIN32)) +# define STDC +#endif +#if !defined(STDC) && (defined(OS2) || defined(__HOS_AIX__)) +# define STDC +#endif + +#if defined(__OS400__) && !defined(STDC) /* iSeries (formerly AS/400). */ +# define STDC +#endif + +#ifndef STDC +# ifndef const /* cannot use !defined(STDC) && !defined(const) on Mac */ +# define const /* note: need a more gentle solution here */ +# endif +#endif + +/* Some Mac compilers merge all .h files incorrectly: */ +#if defined(__MWERKS__)||defined(applec)||defined(THINK_C)||defined(__SC__) +# define NO_DUMMY_DECL +#endif + +/* Maximum value for memLevel in deflateInit2 */ +#ifndef MAX_MEM_LEVEL +# ifdef MAXSEG_64K +# define MAX_MEM_LEVEL 8 +# else +# define MAX_MEM_LEVEL 9 +# endif +#endif + +/* Maximum value for windowBits in deflateInit2 and inflateInit2. + * WARNING: reducing MAX_WBITS makes minigzip unable to extract .gz files + * created by gzip. (Files created by minigzip can still be extracted by + * gzip.) + */ +#ifndef MAX_WBITS +# define MAX_WBITS 15 /* 32K LZ77 window */ +#endif + +/* The memory requirements for deflate are (in bytes): + (1 << (windowBits+2)) + (1 << (memLevel+9)) + that is: 128K for windowBits=15 + 128K for memLevel = 8 (default values) + plus a few kilobytes for small objects. For example, if you want to reduce + the default memory requirements from 256K to 128K, compile with + make CFLAGS="-O -DMAX_WBITS=14 -DMAX_MEM_LEVEL=7" + Of course this will generally degrade compression (there's no free lunch). + + The memory requirements for inflate are (in bytes) 1 << windowBits + that is, 32K for windowBits=15 (default value) plus a few kilobytes + for small objects. +*/ + + /* Type declarations */ + +#ifndef OF /* function prototypes */ +# ifdef STDC +# define OF(args) args +# else +# define OF(args) () +# endif +#endif + +/* The following definitions for FAR are needed only for MSDOS mixed + * model programming (small or medium model with some far allocations). + * This was tested only with MSC; for other MSDOS compilers you may have + * to define NO_MEMCPY in zutil.h. If you don't need the mixed model, + * just define FAR to be empty. + */ +#ifdef SYS16BIT +# if defined(M_I86SM) || defined(M_I86MM) + /* MSC small or medium model */ +# define SMALL_MEDIUM +# ifdef _MSC_VER +# define FAR _far +# else +# define FAR far +# endif +# endif +# if (defined(__SMALL__) || defined(__MEDIUM__)) + /* Turbo C small or medium model */ +# define SMALL_MEDIUM +# ifdef __BORLANDC__ +# define FAR _far +# else +# define FAR far +# endif +# endif +#endif + +#if defined(WINDOWS) || defined(WIN32) + /* If building or using zlib as a DLL, define ZLIB_DLL. + * This is not mandatory, but it offers a little performance increase. + */ +# ifdef ZLIB_DLL +# if defined(WIN32) && (!defined(__BORLANDC__) || (__BORLANDC__ >= 0x500)) +# ifdef ZLIB_INTERNAL +# define ZEXTERN extern __declspec(dllexport) +# else +# define ZEXTERN extern __declspec(dllimport) +# endif +# endif +# endif /* ZLIB_DLL */ + /* If building or using zlib with the WINAPI/WINAPIV calling convention, + * define ZLIB_WINAPI. + * Caution: the standard ZLIB1.DLL is NOT compiled using ZLIB_WINAPI. + */ +# ifdef ZLIB_WINAPI +# ifdef FAR +# undef FAR +# endif +# include + /* No need for _export, use ZLIB.DEF instead. */ + /* For complete Windows compatibility, use WINAPI, not __stdcall. */ +# define ZEXPORT WINAPI +# ifdef WIN32 +# define ZEXPORTVA WINAPIV +# else +# define ZEXPORTVA FAR CDECL +# endif +# endif +#endif + +#if defined (__BEOS__) +# ifdef ZLIB_DLL +# ifdef ZLIB_INTERNAL +# define ZEXPORT __declspec(dllexport) +# define ZEXPORTVA __declspec(dllexport) +# else +# define ZEXPORT __declspec(dllimport) +# define ZEXPORTVA __declspec(dllimport) +# endif +# endif +#endif + +#ifndef ZEXTERN +# define ZEXTERN extern +#endif +#ifndef ZEXPORT +# define ZEXPORT +#endif +#ifndef ZEXPORTVA +# define ZEXPORTVA +#endif + +#ifndef FAR +# define FAR +#endif + +#if !defined(__MACTYPES__) +typedef unsigned char Byte; /* 8 bits */ +#endif +typedef unsigned int uInt; /* 16 bits or more */ +typedef unsigned long uLong; /* 32 bits or more */ + +#ifdef SMALL_MEDIUM + /* Borland C/C++ and some old MSC versions ignore FAR inside typedef */ +# define Bytef Byte FAR +#else + typedef Byte FAR Bytef; +#endif +typedef char FAR charf; +typedef int FAR intf; +typedef uInt FAR uIntf; +typedef uLong FAR uLongf; + +#ifdef STDC + typedef void const *voidpc; + typedef void FAR *voidpf; + typedef void *voidp; +#else + typedef Byte const *voidpc; + typedef Byte FAR *voidpf; + typedef Byte *voidp; +#endif + +#if 0 /* HAVE_UNISTD_H -- this line is updated by ./configure */ +# include /* for off_t */ +# include /* for SEEK_* and off_t */ +# ifdef VMS +# include /* for off_t */ +# endif +# define z_off_t off_t +#endif +#ifndef SEEK_SET +# define SEEK_SET 0 /* Seek from beginning of file. */ +# define SEEK_CUR 1 /* Seek from current position. */ +# define SEEK_END 2 /* Set file pointer to EOF plus "offset" */ +#endif +#ifndef z_off_t +# define z_off_t long +#endif + +#if defined(__OS400__) +# define NO_vsnprintf +#endif + +#if defined(__MVS__) +# define NO_vsnprintf +# ifdef FAR +# undef FAR +# endif +#endif + +/* MVS linker does not support external names larger than 8 bytes */ +#if defined(__MVS__) +# pragma map(deflateInit_,"DEIN") +# pragma map(deflateInit2_,"DEIN2") +# pragma map(deflateEnd,"DEEND") +# pragma map(deflateBound,"DEBND") +# pragma map(inflateInit_,"ININ") +# pragma map(inflateInit2_,"ININ2") +# pragma map(inflateEnd,"INEND") +# pragma map(inflateSync,"INSY") +# pragma map(inflateSetDictionary,"INSEDI") +# pragma map(compressBound,"CMBND") +# pragma map(inflate_table,"INTABL") +# pragma map(inflate_fast,"INFA") +# pragma map(inflate_copyright,"INCOPY") +#endif + +#endif /* ZCONF_H */ diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zlib.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zlib.h index 15c523097..9e5b46727 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zlib.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zlib.h @@ -1,1368 +1,1368 @@ -/* zlib.h -- interface of the 'zlib' general purpose compression library - version 1.2.3, July 18th, 2005 - - Copyright (C) 1995-2005 Jean-loup Gailly and Mark Adler - - This software is provided 'as-is', without any express or implied - warranty. In no event will the authors be held liable for any damages - arising from the use of this software. - - Permission is granted to anyone to use this software for any purpose, - including commercial applications, and to alter it and redistribute it - freely, subject to the following restrictions: - - 1. The origin of this software must not be misrepresented; you must not - claim that you wrote the original software. If you use this software - in a product, an acknowledgment in the product documentation would be - appreciated but is not required. - 2. Altered source versions must be plainly marked as such, and must not be - misrepresented as being the original software. - 3. This notice may not be removed or altered from any source distribution. - - Jean-loup Gailly Mark Adler - jloup@gzip.org madler@alumni.caltech.edu - - - The data format used by the zlib library is described by RFCs (Request for - Comments) 1950 to 1952 in the files http://www.ietf.org/rfc/rfc1950.txt - (zlib format), rfc1951.txt (deflate format) and rfc1952.txt (gzip format). -*/ - -#ifndef ZLIB_H -#define ZLIB_H - -#include "zconf.h" -#include "qconfig.h" - -#ifdef __cplusplus -extern "C" { -#endif - -#define ZLIB_VERSION "1.2.3" -#define ZLIB_VERNUM 0x1230 - -#if defined(QT_VISIBILITY_AVAILABLE) -# define Q_ZEXPORT __attribute__((visibility("default"))) -#else -# ifdef QT_MAKEDLL -# define Q_ZEXPORT __declspec(dllexport) -# else -# define Q_ZEXPORT ZEXPORT -# endif -#endif - -/* - The 'zlib' compression library provides in-memory compression and - decompression functions, including integrity checks of the uncompressed - data. This version of the library supports only one compression method - (deflation) but other algorithms will be added later and will have the same - stream interface. - - Compression can be done in a single step if the buffers are large - enough (for example if an input file is mmap'ed), or can be done by - repeated calls of the compression function. In the latter case, the - application must provide more input and/or consume the output - (providing more output space) before each call. - - The compressed data format used by default by the in-memory functions is - the zlib format, which is a zlib wrapper documented in RFC 1950, wrapped - around a deflate stream, which is itself documented in RFC 1951. - - The library also supports reading and writing files in gzip (.gz) format - with an interface similar to that of stdio using the functions that start - with "gz". The gzip format is different from the zlib format. gzip is a - gzip wrapper, documented in RFC 1952, wrapped around a deflate stream. - - This library can optionally read and write gzip streams in memory as well. - - The zlib format was designed to be compact and fast for use in memory - and on communications channels. The gzip format was designed for single- - file compression on file systems, has a larger header than zlib to maintain - directory information, and uses a different, slower check method than zlib. - - The library does not install any signal handler. The decoder checks - the consistency of the compressed data, so the library should never - crash even in case of corrupted input. -*/ - -typedef voidpf (*alloc_func) OF((voidpf opaque, uInt items, uInt size)); -typedef void (*free_func) OF((voidpf opaque, voidpf address)); - -struct internal_state; - -typedef struct z_stream_s { - Bytef *next_in; /* next input byte */ - uInt avail_in; /* number of bytes available at next_in */ - uLong total_in; /* total nb of input bytes read so far */ - - Bytef *next_out; /* next output byte should be put there */ - uInt avail_out; /* remaining free space at next_out */ - uLong total_out; /* total nb of bytes output so far */ - - char *msg; /* last error message, NULL if no error */ - struct internal_state FAR *state; /* not visible by applications */ - - alloc_func zalloc; /* used to allocate the internal state */ - free_func zfree; /* used to free the internal state */ - voidpf opaque; /* private data object passed to zalloc and zfree */ - - int data_type; /* best guess about the data type: binary or text */ - uLong adler; /* adler32 value of the uncompressed data */ - uLong reserved; /* reserved for future use */ -} z_stream; - -typedef z_stream FAR *z_streamp; - -/* - gzip header information passed to and from zlib routines. See RFC 1952 - for more details on the meanings of these fields. -*/ -typedef struct gz_header_s { - int text; /* true if compressed data believed to be text */ - uLong time; /* modification time */ - int xflags; /* extra flags (not used when writing a gzip file) */ - int os; /* operating system */ - Bytef *extra; /* pointer to extra field or Z_NULL if none */ - uInt extra_len; /* extra field length (valid if extra != Z_NULL) */ - uInt extra_max; /* space at extra (only when reading header) */ - Bytef *name; /* pointer to zero-terminated file name or Z_NULL */ - uInt name_max; /* space at name (only when reading header) */ - Bytef *comment; /* pointer to zero-terminated comment or Z_NULL */ - uInt comm_max; /* space at comment (only when reading header) */ - int hcrc; /* true if there was or will be a header crc */ - int done; /* true when done reading gzip header (not used - when writing a gzip file) */ -} gz_header; - -typedef gz_header FAR *gz_headerp; - -/* - The application must update next_in and avail_in when avail_in has - dropped to zero. It must update next_out and avail_out when avail_out - has dropped to zero. The application must initialize zalloc, zfree and - opaque before calling the init function. All other fields are set by the - compression library and must not be updated by the application. - - The opaque value provided by the application will be passed as the first - parameter for calls of zalloc and zfree. This can be useful for custom - memory management. The compression library attaches no meaning to the - opaque value. - - zalloc must return Z_NULL if there is not enough memory for the object. - If zlib is used in a multi-threaded application, zalloc and zfree must be - thread safe. - - On 16-bit systems, the functions zalloc and zfree must be able to allocate - exactly 65536 bytes, but will not be required to allocate more than this - if the symbol MAXSEG_64K is defined (see zconf.h). WARNING: On MSDOS, - pointers returned by zalloc for objects of exactly 65536 bytes *must* - have their offset normalized to zero. The default allocation function - provided by this library ensures this (see zutil.c). To reduce memory - requirements and avoid any allocation of 64K objects, at the expense of - compression ratio, compile the library with -DMAX_WBITS=14 (see zconf.h). - - The fields total_in and total_out can be used for statistics or - progress reports. After compression, total_in holds the total size of - the uncompressed data and may be saved for use in the decompressor - (particularly if the decompressor wants to decompress everything in - a single step). -*/ - - /* constants */ - -#define Z_NO_FLUSH 0 -#define Z_PARTIAL_FLUSH 1 /* will be removed, use Z_SYNC_FLUSH instead */ -#define Z_SYNC_FLUSH 2 -#define Z_FULL_FLUSH 3 -#define Z_FINISH 4 -#define Z_BLOCK 5 -/* Allowed flush values; see deflate() and inflate() below for details */ - -#define Z_OK 0 -#define Z_STREAM_END 1 -#define Z_NEED_DICT 2 -#define Z_ERRNO (-1) -#define Z_STREAM_ERROR (-2) -#define Z_DATA_ERROR (-3) -#define Z_MEM_ERROR (-4) -#define Z_BUF_ERROR (-5) -#define Z_VERSION_ERROR (-6) -/* Return codes for the compression/decompression functions. Negative - * values are errors, positive values are used for special but normal events. - */ - -#define Z_NO_COMPRESSION 0 -#define Z_BEST_SPEED 1 -#define Z_BEST_COMPRESSION 9 -#define Z_DEFAULT_COMPRESSION (-1) -/* compression levels */ - -#define Z_FILTERED 1 -#define Z_HUFFMAN_ONLY 2 -#define Z_RLE 3 -#define Z_FIXED 4 -#define Z_DEFAULT_STRATEGY 0 -/* compression strategy; see deflateInit2() below for details */ - -#define Z_BINARY 0 -#define Z_TEXT 1 -#define Z_ASCII Z_TEXT /* for compatibility with 1.2.2 and earlier */ -#define Z_UNKNOWN 2 -/* Possible values of the data_type field (though see inflate()) */ - -#define Z_DEFLATED 8 -/* The deflate compression method (the only one supported in this version) */ - -#define Z_NULL 0 /* for initializing zalloc, zfree, opaque */ - -#define zlib_version zlibVersion() -/* for compatibility with versions < 1.0.2 */ - - /* basic functions */ - -ZEXTERN Q_ZEXPORT const char * zlibVersion OF((void)); -/* The application can compare zlibVersion and ZLIB_VERSION for consistency. - If the first character differs, the library code actually used is - not compatible with the zlib.h header file used by the application. - This check is automatically made by deflateInit and inflateInit. - */ - -/* -ZEXTERN int ZEXPORT deflateInit OF((z_streamp strm, int level)); - - Initializes the internal stream state for compression. The fields - zalloc, zfree and opaque must be initialized before by the caller. - If zalloc and zfree are set to Z_NULL, deflateInit updates them to - use default allocation functions. - - The compression level must be Z_DEFAULT_COMPRESSION, or between 0 and 9: - 1 gives best speed, 9 gives best compression, 0 gives no compression at - all (the input data is simply copied a block at a time). - Z_DEFAULT_COMPRESSION requests a default compromise between speed and - compression (currently equivalent to level 6). - - deflateInit returns Z_OK if success, Z_MEM_ERROR if there was not - enough memory, Z_STREAM_ERROR if level is not a valid compression level, - Z_VERSION_ERROR if the zlib library version (zlib_version) is incompatible - with the version assumed by the caller (ZLIB_VERSION). - msg is set to null if there is no error message. deflateInit does not - perform any compression: this will be done by deflate(). -*/ - - -ZEXTERN int Q_ZEXPORT deflate OF((z_streamp strm, int flush)); -/* - deflate compresses as much data as possible, and stops when the input - buffer becomes empty or the output buffer becomes full. It may introduce some - output latency (reading input without producing any output) except when - forced to flush. - - The detailed semantics are as follows. deflate performs one or both of the - following actions: - - - Compress more input starting at next_in and update next_in and avail_in - accordingly. If not all input can be processed (because there is not - enough room in the output buffer), next_in and avail_in are updated and - processing will resume at this point for the next call of deflate(). - - - Provide more output starting at next_out and update next_out and avail_out - accordingly. This action is forced if the parameter flush is non zero. - Forcing flush frequently degrades the compression ratio, so this parameter - should be set only when necessary (in interactive applications). - Some output may be provided even if flush is not set. - - Before the call of deflate(), the application should ensure that at least - one of the actions is possible, by providing more input and/or consuming - more output, and updating avail_in or avail_out accordingly; avail_out - should never be zero before the call. The application can consume the - compressed output when it wants, for example when the output buffer is full - (avail_out == 0), or after each call of deflate(). If deflate returns Z_OK - and with zero avail_out, it must be called again after making room in the - output buffer because there might be more output pending. - - Normally the parameter flush is set to Z_NO_FLUSH, which allows deflate to - decide how much data to accumualte before producing output, in order to - maximize compression. - - If the parameter flush is set to Z_SYNC_FLUSH, all pending output is - flushed to the output buffer and the output is aligned on a byte boundary, so - that the decompressor can get all input data available so far. (In particular - avail_in is zero after the call if enough output space has been provided - before the call.) Flushing may degrade compression for some compression - algorithms and so it should be used only when necessary. - - If flush is set to Z_FULL_FLUSH, all output is flushed as with - Z_SYNC_FLUSH, and the compression state is reset so that decompression can - restart from this point if previous compressed data has been damaged or if - random access is desired. Using Z_FULL_FLUSH too often can seriously degrade - compression. - - If deflate returns with avail_out == 0, this function must be called again - with the same value of the flush parameter and more output space (updated - avail_out), until the flush is complete (deflate returns with non-zero - avail_out). In the case of a Z_FULL_FLUSH or Z_SYNC_FLUSH, make sure that - avail_out is greater than six to avoid repeated flush markers due to - avail_out == 0 on return. - - If the parameter flush is set to Z_FINISH, pending input is processed, - pending output is flushed and deflate returns with Z_STREAM_END if there - was enough output space; if deflate returns with Z_OK, this function must be - called again with Z_FINISH and more output space (updated avail_out) but no - more input data, until it returns with Z_STREAM_END or an error. After - deflate has returned Z_STREAM_END, the only possible operations on the - stream are deflateReset or deflateEnd. - - Z_FINISH can be used immediately after deflateInit if all the compression - is to be done in a single step. In this case, avail_out must be at least - the value returned by deflateBound (see below). If deflate does not return - Z_STREAM_END, then it must be called again as described above. - - deflate() sets strm->adler to the adler32 checksum of all input read - so far (that is, total_in bytes). - - deflate() may update strm->data_type if it can make a good guess about - the input data type (Z_BINARY or Z_TEXT). In doubt, the data is considered - binary. This field is only for information purposes and does not affect - the compression algorithm in any manner. - - deflate() returns Z_OK if some progress has been made (more input - processed or more output produced), Z_STREAM_END if all input has been - consumed and all output has been produced (only when flush is set to - Z_FINISH), Z_STREAM_ERROR if the stream state was inconsistent (for example - if next_in or next_out was NULL), Z_BUF_ERROR if no progress is possible - (for example avail_in or avail_out was zero). Note that Z_BUF_ERROR is not - fatal, and deflate() can be called again with more input and more output - space to continue compressing. -*/ - - -ZEXTERN int Q_ZEXPORT deflateEnd OF((z_streamp strm)); -/* - All dynamically allocated data structures for this stream are freed. - This function discards any unprocessed input and does not flush any - pending output. - - deflateEnd returns Z_OK if success, Z_STREAM_ERROR if the - stream state was inconsistent, Z_DATA_ERROR if the stream was freed - prematurely (some input or output was discarded). In the error case, - msg may be set but then points to a static string (which must not be - deallocated). -*/ - - -/* -ZEXTERN int ZEXPORT inflateInit OF((z_streamp strm)); - - Initializes the internal stream state for decompression. The fields - next_in, avail_in, zalloc, zfree and opaque must be initialized before by - the caller. If next_in is not Z_NULL and avail_in is large enough (the exact - value depends on the compression method), inflateInit determines the - compression method from the zlib header and allocates all data structures - accordingly; otherwise the allocation will be deferred to the first call of - inflate. If zalloc and zfree are set to Z_NULL, inflateInit updates them to - use default allocation functions. - - inflateInit returns Z_OK if success, Z_MEM_ERROR if there was not enough - memory, Z_VERSION_ERROR if the zlib library version is incompatible with the - version assumed by the caller. msg is set to null if there is no error - message. inflateInit does not perform any decompression apart from reading - the zlib header if present: this will be done by inflate(). (So next_in and - avail_in may be modified, but next_out and avail_out are unchanged.) -*/ - - -ZEXTERN int Q_ZEXPORT inflate OF((z_streamp strm, int flush)); -/* - inflate decompresses as much data as possible, and stops when the input - buffer becomes empty or the output buffer becomes full. It may introduce - some output latency (reading input without producing any output) except when - forced to flush. - - The detailed semantics are as follows. inflate performs one or both of the - following actions: - - - Decompress more input starting at next_in and update next_in and avail_in - accordingly. If not all input can be processed (because there is not - enough room in the output buffer), next_in is updated and processing - will resume at this point for the next call of inflate(). - - - Provide more output starting at next_out and update next_out and avail_out - accordingly. inflate() provides as much output as possible, until there - is no more input data or no more space in the output buffer (see below - about the flush parameter). - - Before the call of inflate(), the application should ensure that at least - one of the actions is possible, by providing more input and/or consuming - more output, and updating the next_* and avail_* values accordingly. - The application can consume the uncompressed output when it wants, for - example when the output buffer is full (avail_out == 0), or after each - call of inflate(). If inflate returns Z_OK and with zero avail_out, it - must be called again after making room in the output buffer because there - might be more output pending. - - The flush parameter of inflate() can be Z_NO_FLUSH, Z_SYNC_FLUSH, - Z_FINISH, or Z_BLOCK. Z_SYNC_FLUSH requests that inflate() flush as much - output as possible to the output buffer. Z_BLOCK requests that inflate() stop - if and when it gets to the next deflate block boundary. When decoding the - zlib or gzip format, this will cause inflate() to return immediately after - the header and before the first block. When doing a raw inflate, inflate() - will go ahead and process the first block, and will return when it gets to - the end of that block, or when it runs out of data. - - The Z_BLOCK option assists in appending to or combining deflate streams. - Also to assist in this, on return inflate() will set strm->data_type to the - number of unused bits in the last byte taken from strm->next_in, plus 64 - if inflate() is currently decoding the last block in the deflate stream, - plus 128 if inflate() returned immediately after decoding an end-of-block - code or decoding the complete header up to just before the first byte of the - deflate stream. The end-of-block will not be indicated until all of the - uncompressed data from that block has been written to strm->next_out. The - number of unused bits may in general be greater than seven, except when - bit 7 of data_type is set, in which case the number of unused bits will be - less than eight. - - inflate() should normally be called until it returns Z_STREAM_END or an - error. However if all decompression is to be performed in a single step - (a single call of inflate), the parameter flush should be set to - Z_FINISH. In this case all pending input is processed and all pending - output is flushed; avail_out must be large enough to hold all the - uncompressed data. (The size of the uncompressed data may have been saved - by the compressor for this purpose.) The next operation on this stream must - be inflateEnd to deallocate the decompression state. The use of Z_FINISH - is never required, but can be used to inform inflate that a faster approach - may be used for the single inflate() call. - - In this implementation, inflate() always flushes as much output as - possible to the output buffer, and always uses the faster approach on the - first call. So the only effect of the flush parameter in this implementation - is on the return value of inflate(), as noted below, or when it returns early - because Z_BLOCK is used. - - If a preset dictionary is needed after this call (see inflateSetDictionary - below), inflate sets strm->adler to the adler32 checksum of the dictionary - chosen by the compressor and returns Z_NEED_DICT; otherwise it sets - strm->adler to the adler32 checksum of all output produced so far (that is, - total_out bytes) and returns Z_OK, Z_STREAM_END or an error code as described - below. At the end of the stream, inflate() checks that its computed adler32 - checksum is equal to that saved by the compressor and returns Z_STREAM_END - only if the checksum is correct. - - inflate() will decompress and check either zlib-wrapped or gzip-wrapped - deflate data. The header type is detected automatically. Any information - contained in the gzip header is not retained, so applications that need that - information should instead use raw inflate, see inflateInit2() below, or - inflateBack() and perform their own processing of the gzip header and - trailer. - - inflate() returns Z_OK if some progress has been made (more input processed - or more output produced), Z_STREAM_END if the end of the compressed data has - been reached and all uncompressed output has been produced, Z_NEED_DICT if a - preset dictionary is needed at this point, Z_DATA_ERROR if the input data was - corrupted (input stream not conforming to the zlib format or incorrect check - value), Z_STREAM_ERROR if the stream structure was inconsistent (for example - if next_in or next_out was NULL), Z_MEM_ERROR if there was not enough memory, - Z_BUF_ERROR if no progress is possible or if there was not enough room in the - output buffer when Z_FINISH is used. Note that Z_BUF_ERROR is not fatal, and - inflate() can be called again with more input and more output space to - continue decompressing. If Z_DATA_ERROR is returned, the application may then - call inflateSync() to look for a good compression block if a partial recovery - of the data is desired. -*/ - - -ZEXTERN int Q_ZEXPORT inflateEnd OF((z_streamp strm)); -/* - All dynamically allocated data structures for this stream are freed. - This function discards any unprocessed input and does not flush any - pending output. - - inflateEnd returns Z_OK if success, Z_STREAM_ERROR if the stream state - was inconsistent. In the error case, msg may be set but then points to a - static string (which must not be deallocated). -*/ - - /* Advanced functions */ - -/* - The following functions are needed only in some special applications. -*/ - -/* -ZEXTERN int ZEXPORT deflateInit2 OF((z_streamp strm, - int level, - int method, - int windowBits, - int memLevel, - int strategy)); - - This is another version of deflateInit with more compression options. The - fields next_in, zalloc, zfree and opaque must be initialized before by - the caller. - - The method parameter is the compression method. It must be Z_DEFLATED in - this version of the library. - - The windowBits parameter is the base two logarithm of the window size - (the size of the history buffer). It should be in the range 8..15 for this - version of the library. Larger values of this parameter result in better - compression at the expense of memory usage. The default value is 15 if - deflateInit is used instead. - - windowBits can also be -8..-15 for raw deflate. In this case, -windowBits - determines the window size. deflate() will then generate raw deflate data - with no zlib header or trailer, and will not compute an adler32 check value. - - windowBits can also be greater than 15 for optional gzip encoding. Add - 16 to windowBits to write a simple gzip header and trailer around the - compressed data instead of a zlib wrapper. The gzip header will have no - file name, no extra data, no comment, no modification time (set to zero), - no header crc, and the operating system will be set to 255 (unknown). If a - gzip stream is being written, strm->adler is a crc32 instead of an adler32. - - The memLevel parameter specifies how much memory should be allocated - for the internal compression state. memLevel=1 uses minimum memory but - is slow and reduces compression ratio; memLevel=9 uses maximum memory - for optimal speed. The default value is 8. See zconf.h for total memory - usage as a function of windowBits and memLevel. - - The strategy parameter is used to tune the compression algorithm. Use the - value Z_DEFAULT_STRATEGY for normal data, Z_FILTERED for data produced by a - filter (or predictor), Z_HUFFMAN_ONLY to force Huffman encoding only (no - string match), or Z_RLE to limit match distances to one (run-length - encoding). Filtered data consists mostly of small values with a somewhat - random distribution. In this case, the compression algorithm is tuned to - compress them better. The effect of Z_FILTERED is to force more Huffman - coding and less string matching; it is somewhat intermediate between - Z_DEFAULT and Z_HUFFMAN_ONLY. Z_RLE is designed to be almost as fast as - Z_HUFFMAN_ONLY, but give better compression for PNG image data. The strategy - parameter only affects the compression ratio but not the correctness of the - compressed output even if it is not set appropriately. Z_FIXED prevents the - use of dynamic Huffman codes, allowing for a simpler decoder for special - applications. - - deflateInit2 returns Z_OK if success, Z_MEM_ERROR if there was not enough - memory, Z_STREAM_ERROR if a parameter is invalid (such as an invalid - method). msg is set to null if there is no error message. deflateInit2 does - not perform any compression: this will be done by deflate(). -*/ - -ZEXTERN int Q_ZEXPORT deflateSetDictionary OF((z_streamp strm, - const Bytef *dictionary, - uInt dictLength)); -/* - Initializes the compression dictionary from the given byte sequence - without producing any compressed output. This function must be called - immediately after deflateInit, deflateInit2 or deflateReset, before any - call of deflate. The compressor and decompressor must use exactly the same - dictionary (see inflateSetDictionary). - - The dictionary should consist of strings (byte sequences) that are likely - to be encountered later in the data to be compressed, with the most commonly - used strings preferably put towards the end of the dictionary. Using a - dictionary is most useful when the data to be compressed is short and can be - predicted with good accuracy; the data can then be compressed better than - with the default empty dictionary. - - Depending on the size of the compression data structures selected by - deflateInit or deflateInit2, a part of the dictionary may in effect be - discarded, for example if the dictionary is larger than the window size in - deflate or deflate2. Thus the strings most likely to be useful should be - put at the end of the dictionary, not at the front. In addition, the - current implementation of deflate will use at most the window size minus - 262 bytes of the provided dictionary. - - Upon return of this function, strm->adler is set to the adler32 value - of the dictionary; the decompressor may later use this value to determine - which dictionary has been used by the compressor. (The adler32 value - applies to the whole dictionary even if only a subset of the dictionary is - actually used by the compressor.) If a raw deflate was requested, then the - adler32 value is not computed and strm->adler is not set. - - deflateSetDictionary returns Z_OK if success, or Z_STREAM_ERROR if a - parameter is invalid (such as NULL dictionary) or the stream state is - inconsistent (for example if deflate has already been called for this stream - or if the compression method is bsort). deflateSetDictionary does not - perform any compression: this will be done by deflate(). -*/ - -ZEXTERN int Q_ZEXPORT deflateCopy OF((z_streamp dest, - z_streamp source)); -/* - Sets the destination stream as a complete copy of the source stream. - - This function can be useful when several compression strategies will be - tried, for example when there are several ways of pre-processing the input - data with a filter. The streams that will be discarded should then be freed - by calling deflateEnd. Note that deflateCopy duplicates the internal - compression state which can be quite large, so this strategy is slow and - can consume lots of memory. - - deflateCopy returns Z_OK if success, Z_MEM_ERROR if there was not - enough memory, Z_STREAM_ERROR if the source stream state was inconsistent - (such as zalloc being NULL). msg is left unchanged in both source and - destination. -*/ - -ZEXTERN int Q_ZEXPORT deflateReset OF((z_streamp strm)); -/* - This function is equivalent to deflateEnd followed by deflateInit, - but does not free and reallocate all the internal compression state. - The stream will keep the same compression level and any other attributes - that may have been set by deflateInit2. - - deflateReset returns Z_OK if success, or Z_STREAM_ERROR if the source - stream state was inconsistent (such as zalloc or state being NULL). -*/ - -ZEXTERN int Q_ZEXPORT deflateParams OF((z_streamp strm, - int level, - int strategy)); -/* - Dynamically update the compression level and compression strategy. The - interpretation of level and strategy is as in deflateInit2. This can be - used to switch between compression and straight copy of the input data, or - to switch to a different kind of input data requiring a different - strategy. If the compression level is changed, the input available so far - is compressed with the old level (and may be flushed); the new level will - take effect only at the next call of deflate(). - - Before the call of deflateParams, the stream state must be set as for - a call of deflate(), since the currently available input may have to - be compressed and flushed. In particular, strm->avail_out must be non-zero. - - deflateParams returns Z_OK if success, Z_STREAM_ERROR if the source - stream state was inconsistent or if a parameter was invalid, Z_BUF_ERROR - if strm->avail_out was zero. -*/ - -ZEXTERN int ZEXPORT deflateTune OF((z_streamp strm, - int good_length, - int max_lazy, - int nice_length, - int max_chain)); -/* - Fine tune deflate's internal compression parameters. This should only be - used by someone who understands the algorithm used by zlib's deflate for - searching for the best matching string, and even then only by the most - fanatic optimizer trying to squeeze out the last compressed bit for their - specific input data. Read the deflate.c source code for the meaning of the - max_lazy, good_length, nice_length, and max_chain parameters. - - deflateTune() can be called after deflateInit() or deflateInit2(), and - returns Z_OK on success, or Z_STREAM_ERROR for an invalid deflate stream. - */ - -ZEXTERN uLong ZEXPORT deflateBound OF((z_streamp strm, - uLong sourceLen)); -/* - deflateBound() returns an upper bound on the compressed size after - deflation of sourceLen bytes. It must be called after deflateInit() - or deflateInit2(). This would be used to allocate an output buffer - for deflation in a single pass, and so would be called before deflate(). -*/ - -ZEXTERN int ZEXPORT deflatePrime OF((z_streamp strm, - int bits, - int value)); -/* - deflatePrime() inserts bits in the deflate output stream. The intent - is that this function is used to start off the deflate output with the - bits leftover from a previous deflate stream when appending to it. As such, - this function can only be used for raw deflate, and must be used before the - first deflate() call after a deflateInit2() or deflateReset(). bits must be - less than or equal to 16, and that many of the least significant bits of - value will be inserted in the output. - - deflatePrime returns Z_OK if success, or Z_STREAM_ERROR if the source - stream state was inconsistent. -*/ - -ZEXTERN int ZEXPORT deflateSetHeader OF((z_streamp strm, - gz_headerp head)); -/* - deflateSetHeader() provides gzip header information for when a gzip - stream is requested by deflateInit2(). deflateSetHeader() may be called - after deflateInit2() or deflateReset() and before the first call of - deflate(). The text, time, os, extra field, name, and comment information - in the provided gz_header structure are written to the gzip header (xflag is - ignored -- the extra flags are set according to the compression level). The - caller must assure that, if not Z_NULL, name and comment are terminated with - a zero byte, and that if extra is not Z_NULL, that extra_len bytes are - available there. If hcrc is true, a gzip header crc is included. Note that - the current versions of the command-line version of gzip (up through version - 1.3.x) do not support header crc's, and will report that it is a "multi-part - gzip file" and give up. - - If deflateSetHeader is not used, the default gzip header has text false, - the time set to zero, and os set to 255, with no extra, name, or comment - fields. The gzip header is returned to the default state by deflateReset(). - - deflateSetHeader returns Z_OK if success, or Z_STREAM_ERROR if the source - stream state was inconsistent. -*/ - -/* -ZEXTERN int ZEXPORT inflateInit2 OF((z_streamp strm, - int windowBits)); - - This is another version of inflateInit with an extra parameter. The - fields next_in, avail_in, zalloc, zfree and opaque must be initialized - before by the caller. - - The windowBits parameter is the base two logarithm of the maximum window - size (the size of the history buffer). It should be in the range 8..15 for - this version of the library. The default value is 15 if inflateInit is used - instead. windowBits must be greater than or equal to the windowBits value - provided to deflateInit2() while compressing, or it must be equal to 15 if - deflateInit2() was not used. If a compressed stream with a larger window - size is given as input, inflate() will return with the error code - Z_DATA_ERROR instead of trying to allocate a larger window. - - windowBits can also be -8..-15 for raw inflate. In this case, -windowBits - determines the window size. inflate() will then process raw deflate data, - not looking for a zlib or gzip header, not generating a check value, and not - looking for any check values for comparison at the end of the stream. This - is for use with other formats that use the deflate compressed data format - such as zip. Those formats provide their own check values. If a custom - format is developed using the raw deflate format for compressed data, it is - recommended that a check value such as an adler32 or a crc32 be applied to - the uncompressed data as is done in the zlib, gzip, and zip formats. For - most applications, the zlib format should be used as is. Note that comments - above on the use in deflateInit2() applies to the magnitude of windowBits. - - windowBits can also be greater than 15 for optional gzip decoding. Add - 32 to windowBits to enable zlib and gzip decoding with automatic header - detection, or add 16 to decode only the gzip format (the zlib format will - return a Z_DATA_ERROR). If a gzip stream is being decoded, strm->adler is - a crc32 instead of an adler32. - - inflateInit2 returns Z_OK if success, Z_MEM_ERROR if there was not enough - memory, Z_STREAM_ERROR if a parameter is invalid (such as a null strm). msg - is set to null if there is no error message. inflateInit2 does not perform - any decompression apart from reading the zlib header if present: this will - be done by inflate(). (So next_in and avail_in may be modified, but next_out - and avail_out are unchanged.) -*/ - -ZEXTERN int Q_ZEXPORT inflateSetDictionary OF((z_streamp strm, - const Bytef *dictionary, - uInt dictLength)); -/* - Initializes the decompression dictionary from the given uncompressed byte - sequence. This function must be called immediately after a call of inflate, - if that call returned Z_NEED_DICT. The dictionary chosen by the compressor - can be determined from the adler32 value returned by that call of inflate. - The compressor and decompressor must use exactly the same dictionary (see - deflateSetDictionary). For raw inflate, this function can be called - immediately after inflateInit2() or inflateReset() and before any call of - inflate() to set the dictionary. The application must insure that the - dictionary that was used for compression is provided. - - inflateSetDictionary returns Z_OK if success, Z_STREAM_ERROR if a - parameter is invalid (such as NULL dictionary) or the stream state is - inconsistent, Z_DATA_ERROR if the given dictionary doesn't match the - expected one (incorrect adler32 value). inflateSetDictionary does not - perform any decompression: this will be done by subsequent calls of - inflate(). -*/ - -ZEXTERN int Q_ZEXPORT inflateSync OF((z_streamp strm)); -/* - Skips invalid compressed data until a full flush point (see above the - description of deflate with Z_FULL_FLUSH) can be found, or until all - available input is skipped. No output is provided. - - inflateSync returns Z_OK if a full flush point has been found, Z_BUF_ERROR - if no more input was provided, Z_DATA_ERROR if no flush point has been found, - or Z_STREAM_ERROR if the stream structure was inconsistent. In the success - case, the application may save the current current value of total_in which - indicates where valid compressed data was found. In the error case, the - application may repeatedly call inflateSync, providing more input each time, - until success or end of the input data. -*/ - -ZEXTERN int ZEXPORT inflateCopy OF((z_streamp dest, - z_streamp source)); -/* - Sets the destination stream as a complete copy of the source stream. - - This function can be useful when randomly accessing a large stream. The - first pass through the stream can periodically record the inflate state, - allowing restarting inflate at those points when randomly accessing the - stream. - - inflateCopy returns Z_OK if success, Z_MEM_ERROR if there was not - enough memory, Z_STREAM_ERROR if the source stream state was inconsistent - (such as zalloc being NULL). msg is left unchanged in both source and - destination. -*/ - -ZEXTERN int Q_ZEXPORT inflateReset OF((z_streamp strm)); -/* - This function is equivalent to inflateEnd followed by inflateInit, - but does not free and reallocate all the internal decompression state. - The stream will keep attributes that may have been set by inflateInit2. - - inflateReset returns Z_OK if success, or Z_STREAM_ERROR if the source - stream state was inconsistent (such as zalloc or state being NULL). -*/ - -ZEXTERN int ZEXPORT inflatePrime OF((z_streamp strm, - int bits, - int value)); -/* - This function inserts bits in the inflate input stream. The intent is - that this function is used to start inflating at a bit position in the - middle of a byte. The provided bits will be used before any bytes are used - from next_in. This function should only be used with raw inflate, and - should be used before the first inflate() call after inflateInit2() or - inflateReset(). bits must be less than or equal to 16, and that many of the - least significant bits of value will be inserted in the input. - - inflatePrime returns Z_OK if success, or Z_STREAM_ERROR if the source - stream state was inconsistent. -*/ - -ZEXTERN int ZEXPORT inflateGetHeader OF((z_streamp strm, - gz_headerp head)); -/* - inflateGetHeader() requests that gzip header information be stored in the - provided gz_header structure. inflateGetHeader() may be called after - inflateInit2() or inflateReset(), and before the first call of inflate(). - As inflate() processes the gzip stream, head->done is zero until the header - is completed, at which time head->done is set to one. If a zlib stream is - being decoded, then head->done is set to -1 to indicate that there will be - no gzip header information forthcoming. Note that Z_BLOCK can be used to - force inflate() to return immediately after header processing is complete - and before any actual data is decompressed. - - The text, time, xflags, and os fields are filled in with the gzip header - contents. hcrc is set to true if there is a header CRC. (The header CRC - was valid if done is set to one.) If extra is not Z_NULL, then extra_max - contains the maximum number of bytes to write to extra. Once done is true, - extra_len contains the actual extra field length, and extra contains the - extra field, or that field truncated if extra_max is less than extra_len. - If name is not Z_NULL, then up to name_max characters are written there, - terminated with a zero unless the length is greater than name_max. If - comment is not Z_NULL, then up to comm_max characters are written there, - terminated with a zero unless the length is greater than comm_max. When - any of extra, name, or comment are not Z_NULL and the respective field is - not present in the header, then that field is set to Z_NULL to signal its - absence. This allows the use of deflateSetHeader() with the returned - structure to duplicate the header. However if those fields are set to - allocated memory, then the application will need to save those pointers - elsewhere so that they can be eventually freed. - - If inflateGetHeader is not used, then the header information is simply - discarded. The header is always checked for validity, including the header - CRC if present. inflateReset() will reset the process to discard the header - information. The application would need to call inflateGetHeader() again to - retrieve the header from the next gzip stream. - - inflateGetHeader returns Z_OK if success, or Z_STREAM_ERROR if the source - stream state was inconsistent. -*/ - -/* -ZEXTERN int ZEXPORT inflateBackInit OF((z_streamp strm, int windowBits, - unsigned char FAR *window)); - - Initialize the internal stream state for decompression using inflateBack() - calls. The fields zalloc, zfree and opaque in strm must be initialized - before the call. If zalloc and zfree are Z_NULL, then the default library- - derived memory allocation routines are used. windowBits is the base two - logarithm of the window size, in the range 8..15. window is a caller - supplied buffer of that size. Except for special applications where it is - assured that deflate was used with small window sizes, windowBits must be 15 - and a 32K byte window must be supplied to be able to decompress general - deflate streams. - - See inflateBack() for the usage of these routines. - - inflateBackInit will return Z_OK on success, Z_STREAM_ERROR if any of - the paramaters are invalid, Z_MEM_ERROR if the internal state could not - be allocated, or Z_VERSION_ERROR if the version of the library does not - match the version of the header file. -*/ - -typedef unsigned (*in_func) OF((void FAR *, unsigned char FAR * FAR *)); -typedef int (*out_func) OF((void FAR *, unsigned char FAR *, unsigned)); - -ZEXTERN int ZEXPORT inflateBack OF((z_streamp strm, - in_func in, void FAR *in_desc, - out_func out, void FAR *out_desc)); -/* - inflateBack() does a raw inflate with a single call using a call-back - interface for input and output. This is more efficient than inflate() for - file i/o applications in that it avoids copying between the output and the - sliding window by simply making the window itself the output buffer. This - function trusts the application to not change the output buffer passed by - the output function, at least until inflateBack() returns. - - inflateBackInit() must be called first to allocate the internal state - and to initialize the state with the user-provided window buffer. - inflateBack() may then be used multiple times to inflate a complete, raw - deflate stream with each call. inflateBackEnd() is then called to free - the allocated state. - - A raw deflate stream is one with no zlib or gzip header or trailer. - This routine would normally be used in a utility that reads zip or gzip - files and writes out uncompressed files. The utility would decode the - header and process the trailer on its own, hence this routine expects - only the raw deflate stream to decompress. This is different from the - normal behavior of inflate(), which expects either a zlib or gzip header and - trailer around the deflate stream. - - inflateBack() uses two subroutines supplied by the caller that are then - called by inflateBack() for input and output. inflateBack() calls those - routines until it reads a complete deflate stream and writes out all of the - uncompressed data, or until it encounters an error. The function's - parameters and return types are defined above in the in_func and out_func - typedefs. inflateBack() will call in(in_desc, &buf) which should return the - number of bytes of provided input, and a pointer to that input in buf. If - there is no input available, in() must return zero--buf is ignored in that - case--and inflateBack() will return a buffer error. inflateBack() will call - out(out_desc, buf, len) to write the uncompressed data buf[0..len-1]. out() - should return zero on success, or non-zero on failure. If out() returns - non-zero, inflateBack() will return with an error. Neither in() nor out() - are permitted to change the contents of the window provided to - inflateBackInit(), which is also the buffer that out() uses to write from. - The length written by out() will be at most the window size. Any non-zero - amount of input may be provided by in(). - - For convenience, inflateBack() can be provided input on the first call by - setting strm->next_in and strm->avail_in. If that input is exhausted, then - in() will be called. Therefore strm->next_in must be initialized before - calling inflateBack(). If strm->next_in is Z_NULL, then in() will be called - immediately for input. If strm->next_in is not Z_NULL, then strm->avail_in - must also be initialized, and then if strm->avail_in is not zero, input will - initially be taken from strm->next_in[0 .. strm->avail_in - 1]. - - The in_desc and out_desc parameters of inflateBack() is passed as the - first parameter of in() and out() respectively when they are called. These - descriptors can be optionally used to pass any information that the caller- - supplied in() and out() functions need to do their job. - - On return, inflateBack() will set strm->next_in and strm->avail_in to - pass back any unused input that was provided by the last in() call. The - return values of inflateBack() can be Z_STREAM_END on success, Z_BUF_ERROR - if in() or out() returned an error, Z_DATA_ERROR if there was a format - error in the deflate stream (in which case strm->msg is set to indicate the - nature of the error), or Z_STREAM_ERROR if the stream was not properly - initialized. In the case of Z_BUF_ERROR, an input or output error can be - distinguished using strm->next_in which will be Z_NULL only if in() returned - an error. If strm->next is not Z_NULL, then the Z_BUF_ERROR was due to - out() returning non-zero. (in() will always be called before out(), so - strm->next_in is assured to be defined if out() returns non-zero.) Note - that inflateBack() cannot return Z_OK. -*/ - -ZEXTERN int ZEXPORT inflateBackEnd OF((z_streamp strm)); -/* - All memory allocated by inflateBackInit() is freed. - - inflateBackEnd() returns Z_OK on success, or Z_STREAM_ERROR if the stream - state was inconsistent. -*/ - -ZEXTERN uLong ZEXPORT zlibCompileFlags OF((void)); -/* Return flags indicating compile-time options. - - Type sizes, two bits each, 00 = 16 bits, 01 = 32, 10 = 64, 11 = other: - 1.0: size of uInt - 3.2: size of uLong - 5.4: size of voidpf (pointer) - 7.6: size of z_off_t - - Compiler, assembler, and debug options: - 8: DEBUG - 9: ASMV or ASMINF -- use ASM code - 10: ZLIB_WINAPI -- exported functions use the WINAPI calling convention - 11: 0 (reserved) - - One-time table building (smaller code, but not thread-safe if true): - 12: BUILDFIXED -- build static block decoding tables when needed - 13: DYNAMIC_CRC_TABLE -- build CRC calculation tables when needed - 14,15: 0 (reserved) - - Library content (indicates missing functionality): - 16: NO_GZCOMPRESS -- gz* functions cannot compress (to avoid linking - deflate code when not needed) - 17: NO_GZIP -- deflate can't write gzip streams, and inflate can't detect - and decode gzip streams (to avoid linking crc code) - 18-19: 0 (reserved) - - Operation variations (changes in library functionality): - 20: PKZIP_BUG_WORKAROUND -- slightly more permissive inflate - 21: FASTEST -- deflate algorithm with only one, lowest compression level - 22,23: 0 (reserved) - - The sprintf variant used by gzprintf (zero is best): - 24: 0 = vs*, 1 = s* -- 1 means limited to 20 arguments after the format - 25: 0 = *nprintf, 1 = *printf -- 1 means gzprintf() not secure! - 26: 0 = returns value, 1 = void -- 1 means inferred string length returned - - Remainder: - 27-31: 0 (reserved) - */ - - - /* utility functions */ - -/* - The following utility functions are implemented on top of the - basic stream-oriented functions. To simplify the interface, some - default options are assumed (compression level and memory usage, - standard memory allocation functions). The source code of these - utility functions can easily be modified if you need special options. -*/ - -ZEXTERN int Q_ZEXPORT compress OF((Bytef *dest, uLongf *destLen, - const Bytef *source, uLong sourceLen)); -/* - Compresses the source buffer into the destination buffer. sourceLen is - the byte length of the source buffer. Upon entry, destLen is the total - size of the destination buffer, which must be at least the value returned - by compressBound(sourceLen). Upon exit, destLen is the actual size of the - compressed buffer. - This function can be used to compress a whole file at once if the - input file is mmap'ed. - compress returns Z_OK if success, Z_MEM_ERROR if there was not - enough memory, Z_BUF_ERROR if there was not enough room in the output - buffer. -*/ - -ZEXTERN int Q_ZEXPORT compress2 OF((Bytef *dest, uLongf *destLen, - const Bytef *source, uLong sourceLen, - int level)); -/* - Compresses the source buffer into the destination buffer. The level - parameter has the same meaning as in deflateInit. sourceLen is the byte - length of the source buffer. Upon entry, destLen is the total size of the - destination buffer, which must be at least the value returned by - compressBound(sourceLen). Upon exit, destLen is the actual size of the - compressed buffer. - - compress2 returns Z_OK if success, Z_MEM_ERROR if there was not enough - memory, Z_BUF_ERROR if there was not enough room in the output buffer, - Z_STREAM_ERROR if the level parameter is invalid. -*/ - -ZEXTERN uLong ZEXPORT compressBound OF((uLong sourceLen)); -/* - compressBound() returns an upper bound on the compressed size after - compress() or compress2() on sourceLen bytes. It would be used before - a compress() or compress2() call to allocate the destination buffer. -*/ - -ZEXTERN int Q_ZEXPORT uncompress OF((Bytef *dest, uLongf *destLen, - const Bytef *source, uLong sourceLen)); -/* - Decompresses the source buffer into the destination buffer. sourceLen is - the byte length of the source buffer. Upon entry, destLen is the total - size of the destination buffer, which must be large enough to hold the - entire uncompressed data. (The size of the uncompressed data must have - been saved previously by the compressor and transmitted to the decompressor - by some mechanism outside the scope of this compression library.) - Upon exit, destLen is the actual size of the compressed buffer. - This function can be used to decompress a whole file at once if the - input file is mmap'ed. - - uncompress returns Z_OK if success, Z_MEM_ERROR if there was not - enough memory, Z_BUF_ERROR if there was not enough room in the output - buffer, or Z_DATA_ERROR if the input data was corrupted or incomplete. -*/ - - -typedef voidp gzFile; - -ZEXTERN gzFile Q_ZEXPORT gzopen OF((const char *path, const char *mode)); -/* - Opens a gzip (.gz) file for reading or writing. The mode parameter - is as in fopen ("rb" or "wb") but can also include a compression level - ("wb9") or a strategy: 'f' for filtered data as in "wb6f", 'h' for - Huffman only compression as in "wb1h", or 'R' for run-length encoding - as in "wb1R". (See the description of deflateInit2 for more information - about the strategy parameter.) - - gzopen can be used to read a file which is not in gzip format; in this - case gzread will directly read from the file without decompression. - - gzopen returns NULL if the file could not be opened or if there was - insufficient memory to allocate the (de)compression state; errno - can be checked to distinguish the two cases (if errno is zero, the - zlib error is Z_MEM_ERROR). */ - -ZEXTERN gzFile Q_ZEXPORT gzdopen OF((int fd, const char *mode)); -/* - gzdopen() associates a gzFile with the file descriptor fd. File - descriptors are obtained from calls like open, dup, creat, pipe or - fileno (in the file has been previously opened with fopen). - The mode parameter is as in gzopen. - The next call of gzclose on the returned gzFile will also close the - file descriptor fd, just like fclose(fdopen(fd), mode) closes the file - descriptor fd. If you want to keep fd open, use gzdopen(dup(fd), mode). - gzdopen returns NULL if there was insufficient memory to allocate - the (de)compression state. -*/ - -ZEXTERN int Q_ZEXPORT gzsetparams OF((gzFile file, int level, int strategy)); -/* - Dynamically update the compression level or strategy. See the description - of deflateInit2 for the meaning of these parameters. - gzsetparams returns Z_OK if success, or Z_STREAM_ERROR if the file was not - opened for writing. -*/ - -ZEXTERN int Q_ZEXPORT gzread OF((gzFile file, voidp buf, unsigned len)); -/* - Reads the given number of uncompressed bytes from the compressed file. - If the input file was not in gzip format, gzread copies the given number - of bytes into the buffer. - gzread returns the number of uncompressed bytes actually read (0 for - end of file, -1 for error). */ - -ZEXTERN int Q_ZEXPORT gzwrite OF((gzFile file, - voidpc buf, unsigned len)); -/* - Writes the given number of uncompressed bytes into the compressed file. - gzwrite returns the number of uncompressed bytes actually written - (0 in case of error). -*/ - -ZEXTERN int Q_ZEXPORT gzprintf OF((gzFile file, const char *format, ...)); -/* - Converts, formats, and writes the args to the compressed file under - control of the format string, as in fprintf. gzprintf returns the number of - uncompressed bytes actually written (0 in case of error). The number of - uncompressed bytes written is limited to 4095. The caller should assure that - this limit is not exceeded. If it is exceeded, then gzprintf() will return - return an error (0) with nothing written. In this case, there may also be a - buffer overflow with unpredictable consequences, which is possible only if - zlib was compiled with the insecure functions sprintf() or vsprintf() - because the secure snprintf() or vsnprintf() functions were not available. -*/ - -ZEXTERN int Q_ZEXPORT gzputs OF((gzFile file, const char *s)); -/* - Writes the given null-terminated string to the compressed file, excluding - the terminating null character. - gzputs returns the number of characters written, or -1 in case of error. -*/ - -ZEXTERN Q_ZEXPORT char * gzgets OF((gzFile file, char *buf, int len)); -/* - Reads bytes from the compressed file until len-1 characters are read, or - a newline character is read and transferred to buf, or an end-of-file - condition is encountered. The string is then terminated with a null - character. - gzgets returns buf, or Z_NULL in case of error. -*/ - -ZEXTERN int Q_ZEXPORT gzputc OF((gzFile file, int c)); -/* - Writes c, converted to an unsigned char, into the compressed file. - gzputc returns the value that was written, or -1 in case of error. -*/ - -ZEXTERN int Q_ZEXPORT gzgetc OF((gzFile file)); -/* - Reads one byte from the compressed file. gzgetc returns this byte - or -1 in case of end of file or error. -*/ - -ZEXTERN int ZEXPORT gzungetc OF((int c, gzFile file)); -/* - Push one character back onto the stream to be read again later. - Only one character of push-back is allowed. gzungetc() returns the - character pushed, or -1 on failure. gzungetc() will fail if a - character has been pushed but not read yet, or if c is -1. The pushed - character will be discarded if the stream is repositioned with gzseek() - or gzrewind(). -*/ - -ZEXTERN int Q_ZEXPORT gzflush OF((gzFile file, int flush)); -/* - Flushes all pending output into the compressed file. The parameter - flush is as in the deflate() function. The return value is the zlib - error number (see function gzerror below). gzflush returns Z_OK if - the flush parameter is Z_FINISH and all output could be flushed. - gzflush should be called only when strictly necessary because it can - degrade compression. -*/ - -ZEXTERN z_off_t Q_ZEXPORT gzseek OF((gzFile file, - z_off_t offset, int whence)); -/* - Sets the starting position for the next gzread or gzwrite on the - given compressed file. The offset represents a number of bytes in the - uncompressed data stream. The whence parameter is defined as in lseek(2); - the value SEEK_END is not supported. - If the file is opened for reading, this function is emulated but can be - extremely slow. If the file is opened for writing, only forward seeks are - supported; gzseek then compresses a sequence of zeroes up to the new - starting position. - - gzseek returns the resulting offset location as measured in bytes from - the beginning of the uncompressed stream, or -1 in case of error, in - particular if the file is opened for writing and the new starting position - would be before the current position. -*/ - -ZEXTERN int Q_ZEXPORT gzrewind OF((gzFile file)); -/* - Rewinds the given file. This function is supported only for reading. - - gzrewind(file) is equivalent to (int)gzseek(file, 0L, SEEK_SET) -*/ - -ZEXTERN z_off_t Q_ZEXPORT gztell OF((gzFile file)); -/* - Returns the starting position for the next gzread or gzwrite on the - given compressed file. This position represents a number of bytes in the - uncompressed data stream. - - gztell(file) is equivalent to gzseek(file, 0L, SEEK_CUR) -*/ - -ZEXTERN int Q_ZEXPORT gzeof OF((gzFile file)); -/* - Returns 1 when EOF has previously been detected reading the given - input stream, otherwise zero. -*/ - -ZEXTERN int ZEXPORT gzdirect OF((gzFile file)); -/* - Returns 1 if file is being read directly without decompression, otherwise - zero. -*/ - -ZEXTERN int Q_ZEXPORT gzclose OF((gzFile file)); -/* - Flushes all pending output if necessary, closes the compressed file - and deallocates all the (de)compression state. The return value is the zlib - error number (see function gzerror below). -*/ - -ZEXTERN Q_ZEXPORT const char * gzerror OF((gzFile file, int *errnum)); -/* - Returns the error message for the last error which occurred on the - given compressed file. errnum is set to zlib error number. If an - error occurred in the file system and not in the compression library, - errnum is set to Z_ERRNO and the application may consult errno - to get the exact error code. -*/ - -ZEXTERN void ZEXPORT gzclearerr OF((gzFile file)); -/* - Clears the error and end-of-file flags for file. This is analogous to the - clearerr() function in stdio. This is useful for continuing to read a gzip - file that is being written concurrently. -*/ - - /* checksum functions */ - -/* - These functions are not related to compression but are exported - anyway because they might be useful in applications using the - compression library. -*/ - -ZEXTERN uLong Q_ZEXPORT adler32 OF((uLong adler, const Bytef *buf, uInt len)); -/* - Update a running Adler-32 checksum with the bytes buf[0..len-1] and - return the updated checksum. If buf is NULL, this function returns - the required initial value for the checksum. - An Adler-32 checksum is almost as reliable as a CRC32 but can be computed - much faster. Usage example: - - uLong adler = adler32(0L, Z_NULL, 0); - - while (read_buffer(buffer, length) != EOF) { - adler = adler32(adler, buffer, length); - } - if (adler != original_adler) error(); -*/ - -ZEXTERN uLong ZEXPORT adler32_combine OF((uLong adler1, uLong adler2, - z_off_t len2)); -/* - Combine two Adler-32 checksums into one. For two sequences of bytes, seq1 - and seq2 with lengths len1 and len2, Adler-32 checksums were calculated for - each, adler1 and adler2. adler32_combine() returns the Adler-32 checksum of - seq1 and seq2 concatenated, requiring only adler1, adler2, and len2. -*/ - -ZEXTERN uLong Q_ZEXPORT crc32 OF((uLong crc, const Bytef *buf, uInt len)); -/* - Update a running CRC-32 with the bytes buf[0..len-1] and return the - updated CRC-32. If buf is NULL, this function returns the required initial - value for the for the crc. Pre- and post-conditioning (one's complement) is - performed within this function so it shouldn't be done by the application. - Usage example: - - uLong crc = crc32(0L, Z_NULL, 0); - - while (read_buffer(buffer, length) != EOF) { - crc = crc32(crc, buffer, length); - } - if (crc != original_crc) error(); -*/ - -ZEXTERN uLong ZEXPORT crc32_combine OF((uLong crc1, uLong crc2, z_off_t len2)); - -/* - Combine two CRC-32 check values into one. For two sequences of bytes, - seq1 and seq2 with lengths len1 and len2, CRC-32 check values were - calculated for each, crc1 and crc2. crc32_combine() returns the CRC-32 - check value of seq1 and seq2 concatenated, requiring only crc1, crc2, and - len2. -*/ - - - /* various hacks, don't look :) */ - -/* deflateInit and inflateInit are macros to allow checking the zlib version - * and the compiler's view of z_stream: - */ -ZEXTERN int Q_ZEXPORT deflateInit_ OF((z_streamp strm, int level, - const char *version, int stream_size)); -ZEXTERN int Q_ZEXPORT inflateInit_ OF((z_streamp strm, - const char *version, int stream_size)); -ZEXTERN int Q_ZEXPORT deflateInit2_ OF((z_streamp strm, int level, int method, - int windowBits, int memLevel, - int strategy, const char *version, - int stream_size)); -ZEXTERN int Q_ZEXPORT inflateInit2_ OF((z_streamp strm, int windowBits, - const char *version, int stream_size)); -ZEXTERN int ZEXPORT inflateBackInit_ OF((z_streamp strm, int windowBits, - unsigned char FAR *window, - const char *version, - int stream_size)); -#define deflateInit(strm, level) \ - deflateInit_((strm), (level), ZLIB_VERSION, sizeof(z_stream)) -#define inflateInit(strm) \ - inflateInit_((strm), ZLIB_VERSION, sizeof(z_stream)) -#define deflateInit2(strm, level, method, windowBits, memLevel, strategy) \ - deflateInit2_((strm),(level),(method),(windowBits),(memLevel),\ - (strategy), ZLIB_VERSION, sizeof(z_stream)) -#define inflateInit2(strm, windowBits) \ - inflateInit2_((strm), (windowBits), ZLIB_VERSION, sizeof(z_stream)) -#define inflateBackInit(strm, windowBits, window) \ - inflateBackInit_((strm), (windowBits), (window), \ - ZLIB_VERSION, sizeof(z_stream)) - - -#if !defined(ZUTIL_H) && !defined(NO_DUMMY_DECL) - struct internal_state {int dummy;}; /* hack for buggy compilers */ -#endif - -ZEXTERN Q_ZEXPORT const char * zError OF((int)); -ZEXTERN int Q_ZEXPORT inflateSyncPoint OF((z_streamp z)); -ZEXTERN Q_ZEXPORT const uLongf * get_crc_table OF((void)); - -#ifdef __cplusplus -} -#endif - -#endif /* ZLIB_H */ +/* zlib.h -- interface of the 'zlib' general purpose compression library + version 1.2.3, July 18th, 2005 + + Copyright (C) 1995-2005 Jean-loup Gailly and Mark Adler + + This software is provided 'as-is', without any express or implied + warranty. In no event will the authors be held liable for any damages + arising from the use of this software. + + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it + freely, subject to the following restrictions: + + 1. The origin of this software must not be misrepresented; you must not + claim that you wrote the original software. If you use this software + in a product, an acknowledgment in the product documentation would be + appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be + misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + + Jean-loup Gailly Mark Adler + jloup@gzip.org madler@alumni.caltech.edu + + + The data format used by the zlib library is described by RFCs (Request for + Comments) 1950 to 1952 in the files http://www.ietf.org/rfc/rfc1950.txt + (zlib format), rfc1951.txt (deflate format) and rfc1952.txt (gzip format). +*/ + +#ifndef ZLIB_H +#define ZLIB_H + +#include "zconf.h" +#include "qconfig.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#define ZLIB_VERSION "1.2.3" +#define ZLIB_VERNUM 0x1230 + +#if defined(QT_VISIBILITY_AVAILABLE) +# define Q_ZEXPORT __attribute__((visibility("default"))) +#else +# ifdef QT_MAKEDLL +# define Q_ZEXPORT __declspec(dllexport) +# else +# define Q_ZEXPORT ZEXPORT +# endif +#endif + +/* + The 'zlib' compression library provides in-memory compression and + decompression functions, including integrity checks of the uncompressed + data. This version of the library supports only one compression method + (deflation) but other algorithms will be added later and will have the same + stream interface. + + Compression can be done in a single step if the buffers are large + enough (for example if an input file is mmap'ed), or can be done by + repeated calls of the compression function. In the latter case, the + application must provide more input and/or consume the output + (providing more output space) before each call. + + The compressed data format used by default by the in-memory functions is + the zlib format, which is a zlib wrapper documented in RFC 1950, wrapped + around a deflate stream, which is itself documented in RFC 1951. + + The library also supports reading and writing files in gzip (.gz) format + with an interface similar to that of stdio using the functions that start + with "gz". The gzip format is different from the zlib format. gzip is a + gzip wrapper, documented in RFC 1952, wrapped around a deflate stream. + + This library can optionally read and write gzip streams in memory as well. + + The zlib format was designed to be compact and fast for use in memory + and on communications channels. The gzip format was designed for single- + file compression on file systems, has a larger header than zlib to maintain + directory information, and uses a different, slower check method than zlib. + + The library does not install any signal handler. The decoder checks + the consistency of the compressed data, so the library should never + crash even in case of corrupted input. +*/ + +typedef voidpf (*alloc_func) OF((voidpf opaque, uInt items, uInt size)); +typedef void (*free_func) OF((voidpf opaque, voidpf address)); + +struct internal_state; + +typedef struct z_stream_s { + Bytef *next_in; /* next input byte */ + uInt avail_in; /* number of bytes available at next_in */ + uLong total_in; /* total nb of input bytes read so far */ + + Bytef *next_out; /* next output byte should be put there */ + uInt avail_out; /* remaining free space at next_out */ + uLong total_out; /* total nb of bytes output so far */ + + char *msg; /* last error message, NULL if no error */ + struct internal_state FAR *state; /* not visible by applications */ + + alloc_func zalloc; /* used to allocate the internal state */ + free_func zfree; /* used to free the internal state */ + voidpf opaque; /* private data object passed to zalloc and zfree */ + + int data_type; /* best guess about the data type: binary or text */ + uLong adler; /* adler32 value of the uncompressed data */ + uLong reserved; /* reserved for future use */ +} z_stream; + +typedef z_stream FAR *z_streamp; + +/* + gzip header information passed to and from zlib routines. See RFC 1952 + for more details on the meanings of these fields. +*/ +typedef struct gz_header_s { + int text; /* true if compressed data believed to be text */ + uLong time; /* modification time */ + int xflags; /* extra flags (not used when writing a gzip file) */ + int os; /* operating system */ + Bytef *extra; /* pointer to extra field or Z_NULL if none */ + uInt extra_len; /* extra field length (valid if extra != Z_NULL) */ + uInt extra_max; /* space at extra (only when reading header) */ + Bytef *name; /* pointer to zero-terminated file name or Z_NULL */ + uInt name_max; /* space at name (only when reading header) */ + Bytef *comment; /* pointer to zero-terminated comment or Z_NULL */ + uInt comm_max; /* space at comment (only when reading header) */ + int hcrc; /* true if there was or will be a header crc */ + int done; /* true when done reading gzip header (not used + when writing a gzip file) */ +} gz_header; + +typedef gz_header FAR *gz_headerp; + +/* + The application must update next_in and avail_in when avail_in has + dropped to zero. It must update next_out and avail_out when avail_out + has dropped to zero. The application must initialize zalloc, zfree and + opaque before calling the init function. All other fields are set by the + compression library and must not be updated by the application. + + The opaque value provided by the application will be passed as the first + parameter for calls of zalloc and zfree. This can be useful for custom + memory management. The compression library attaches no meaning to the + opaque value. + + zalloc must return Z_NULL if there is not enough memory for the object. + If zlib is used in a multi-threaded application, zalloc and zfree must be + thread safe. + + On 16-bit systems, the functions zalloc and zfree must be able to allocate + exactly 65536 bytes, but will not be required to allocate more than this + if the symbol MAXSEG_64K is defined (see zconf.h). WARNING: On MSDOS, + pointers returned by zalloc for objects of exactly 65536 bytes *must* + have their offset normalized to zero. The default allocation function + provided by this library ensures this (see zutil.c). To reduce memory + requirements and avoid any allocation of 64K objects, at the expense of + compression ratio, compile the library with -DMAX_WBITS=14 (see zconf.h). + + The fields total_in and total_out can be used for statistics or + progress reports. After compression, total_in holds the total size of + the uncompressed data and may be saved for use in the decompressor + (particularly if the decompressor wants to decompress everything in + a single step). +*/ + + /* constants */ + +#define Z_NO_FLUSH 0 +#define Z_PARTIAL_FLUSH 1 /* will be removed, use Z_SYNC_FLUSH instead */ +#define Z_SYNC_FLUSH 2 +#define Z_FULL_FLUSH 3 +#define Z_FINISH 4 +#define Z_BLOCK 5 +/* Allowed flush values; see deflate() and inflate() below for details */ + +#define Z_OK 0 +#define Z_STREAM_END 1 +#define Z_NEED_DICT 2 +#define Z_ERRNO (-1) +#define Z_STREAM_ERROR (-2) +#define Z_DATA_ERROR (-3) +#define Z_MEM_ERROR (-4) +#define Z_BUF_ERROR (-5) +#define Z_VERSION_ERROR (-6) +/* Return codes for the compression/decompression functions. Negative + * values are errors, positive values are used for special but normal events. + */ + +#define Z_NO_COMPRESSION 0 +#define Z_BEST_SPEED 1 +#define Z_BEST_COMPRESSION 9 +#define Z_DEFAULT_COMPRESSION (-1) +/* compression levels */ + +#define Z_FILTERED 1 +#define Z_HUFFMAN_ONLY 2 +#define Z_RLE 3 +#define Z_FIXED 4 +#define Z_DEFAULT_STRATEGY 0 +/* compression strategy; see deflateInit2() below for details */ + +#define Z_BINARY 0 +#define Z_TEXT 1 +#define Z_ASCII Z_TEXT /* for compatibility with 1.2.2 and earlier */ +#define Z_UNKNOWN 2 +/* Possible values of the data_type field (though see inflate()) */ + +#define Z_DEFLATED 8 +/* The deflate compression method (the only one supported in this version) */ + +#define Z_NULL 0 /* for initializing zalloc, zfree, opaque */ + +#define zlib_version zlibVersion() +/* for compatibility with versions < 1.0.2 */ + + /* basic functions */ + +ZEXTERN Q_ZEXPORT const char * zlibVersion OF((void)); +/* The application can compare zlibVersion and ZLIB_VERSION for consistency. + If the first character differs, the library code actually used is + not compatible with the zlib.h header file used by the application. + This check is automatically made by deflateInit and inflateInit. + */ + +/* +ZEXTERN int ZEXPORT deflateInit OF((z_streamp strm, int level)); + + Initializes the internal stream state for compression. The fields + zalloc, zfree and opaque must be initialized before by the caller. + If zalloc and zfree are set to Z_NULL, deflateInit updates them to + use default allocation functions. + + The compression level must be Z_DEFAULT_COMPRESSION, or between 0 and 9: + 1 gives best speed, 9 gives best compression, 0 gives no compression at + all (the input data is simply copied a block at a time). + Z_DEFAULT_COMPRESSION requests a default compromise between speed and + compression (currently equivalent to level 6). + + deflateInit returns Z_OK if success, Z_MEM_ERROR if there was not + enough memory, Z_STREAM_ERROR if level is not a valid compression level, + Z_VERSION_ERROR if the zlib library version (zlib_version) is incompatible + with the version assumed by the caller (ZLIB_VERSION). + msg is set to null if there is no error message. deflateInit does not + perform any compression: this will be done by deflate(). +*/ + + +ZEXTERN int Q_ZEXPORT deflate OF((z_streamp strm, int flush)); +/* + deflate compresses as much data as possible, and stops when the input + buffer becomes empty or the output buffer becomes full. It may introduce some + output latency (reading input without producing any output) except when + forced to flush. + + The detailed semantics are as follows. deflate performs one or both of the + following actions: + + - Compress more input starting at next_in and update next_in and avail_in + accordingly. If not all input can be processed (because there is not + enough room in the output buffer), next_in and avail_in are updated and + processing will resume at this point for the next call of deflate(). + + - Provide more output starting at next_out and update next_out and avail_out + accordingly. This action is forced if the parameter flush is non zero. + Forcing flush frequently degrades the compression ratio, so this parameter + should be set only when necessary (in interactive applications). + Some output may be provided even if flush is not set. + + Before the call of deflate(), the application should ensure that at least + one of the actions is possible, by providing more input and/or consuming + more output, and updating avail_in or avail_out accordingly; avail_out + should never be zero before the call. The application can consume the + compressed output when it wants, for example when the output buffer is full + (avail_out == 0), or after each call of deflate(). If deflate returns Z_OK + and with zero avail_out, it must be called again after making room in the + output buffer because there might be more output pending. + + Normally the parameter flush is set to Z_NO_FLUSH, which allows deflate to + decide how much data to accumualte before producing output, in order to + maximize compression. + + If the parameter flush is set to Z_SYNC_FLUSH, all pending output is + flushed to the output buffer and the output is aligned on a byte boundary, so + that the decompressor can get all input data available so far. (In particular + avail_in is zero after the call if enough output space has been provided + before the call.) Flushing may degrade compression for some compression + algorithms and so it should be used only when necessary. + + If flush is set to Z_FULL_FLUSH, all output is flushed as with + Z_SYNC_FLUSH, and the compression state is reset so that decompression can + restart from this point if previous compressed data has been damaged or if + random access is desired. Using Z_FULL_FLUSH too often can seriously degrade + compression. + + If deflate returns with avail_out == 0, this function must be called again + with the same value of the flush parameter and more output space (updated + avail_out), until the flush is complete (deflate returns with non-zero + avail_out). In the case of a Z_FULL_FLUSH or Z_SYNC_FLUSH, make sure that + avail_out is greater than six to avoid repeated flush markers due to + avail_out == 0 on return. + + If the parameter flush is set to Z_FINISH, pending input is processed, + pending output is flushed and deflate returns with Z_STREAM_END if there + was enough output space; if deflate returns with Z_OK, this function must be + called again with Z_FINISH and more output space (updated avail_out) but no + more input data, until it returns with Z_STREAM_END or an error. After + deflate has returned Z_STREAM_END, the only possible operations on the + stream are deflateReset or deflateEnd. + + Z_FINISH can be used immediately after deflateInit if all the compression + is to be done in a single step. In this case, avail_out must be at least + the value returned by deflateBound (see below). If deflate does not return + Z_STREAM_END, then it must be called again as described above. + + deflate() sets strm->adler to the adler32 checksum of all input read + so far (that is, total_in bytes). + + deflate() may update strm->data_type if it can make a good guess about + the input data type (Z_BINARY or Z_TEXT). In doubt, the data is considered + binary. This field is only for information purposes and does not affect + the compression algorithm in any manner. + + deflate() returns Z_OK if some progress has been made (more input + processed or more output produced), Z_STREAM_END if all input has been + consumed and all output has been produced (only when flush is set to + Z_FINISH), Z_STREAM_ERROR if the stream state was inconsistent (for example + if next_in or next_out was NULL), Z_BUF_ERROR if no progress is possible + (for example avail_in or avail_out was zero). Note that Z_BUF_ERROR is not + fatal, and deflate() can be called again with more input and more output + space to continue compressing. +*/ + + +ZEXTERN int Q_ZEXPORT deflateEnd OF((z_streamp strm)); +/* + All dynamically allocated data structures for this stream are freed. + This function discards any unprocessed input and does not flush any + pending output. + + deflateEnd returns Z_OK if success, Z_STREAM_ERROR if the + stream state was inconsistent, Z_DATA_ERROR if the stream was freed + prematurely (some input or output was discarded). In the error case, + msg may be set but then points to a static string (which must not be + deallocated). +*/ + + +/* +ZEXTERN int ZEXPORT inflateInit OF((z_streamp strm)); + + Initializes the internal stream state for decompression. The fields + next_in, avail_in, zalloc, zfree and opaque must be initialized before by + the caller. If next_in is not Z_NULL and avail_in is large enough (the exact + value depends on the compression method), inflateInit determines the + compression method from the zlib header and allocates all data structures + accordingly; otherwise the allocation will be deferred to the first call of + inflate. If zalloc and zfree are set to Z_NULL, inflateInit updates them to + use default allocation functions. + + inflateInit returns Z_OK if success, Z_MEM_ERROR if there was not enough + memory, Z_VERSION_ERROR if the zlib library version is incompatible with the + version assumed by the caller. msg is set to null if there is no error + message. inflateInit does not perform any decompression apart from reading + the zlib header if present: this will be done by inflate(). (So next_in and + avail_in may be modified, but next_out and avail_out are unchanged.) +*/ + + +ZEXTERN int Q_ZEXPORT inflate OF((z_streamp strm, int flush)); +/* + inflate decompresses as much data as possible, and stops when the input + buffer becomes empty or the output buffer becomes full. It may introduce + some output latency (reading input without producing any output) except when + forced to flush. + + The detailed semantics are as follows. inflate performs one or both of the + following actions: + + - Decompress more input starting at next_in and update next_in and avail_in + accordingly. If not all input can be processed (because there is not + enough room in the output buffer), next_in is updated and processing + will resume at this point for the next call of inflate(). + + - Provide more output starting at next_out and update next_out and avail_out + accordingly. inflate() provides as much output as possible, until there + is no more input data or no more space in the output buffer (see below + about the flush parameter). + + Before the call of inflate(), the application should ensure that at least + one of the actions is possible, by providing more input and/or consuming + more output, and updating the next_* and avail_* values accordingly. + The application can consume the uncompressed output when it wants, for + example when the output buffer is full (avail_out == 0), or after each + call of inflate(). If inflate returns Z_OK and with zero avail_out, it + must be called again after making room in the output buffer because there + might be more output pending. + + The flush parameter of inflate() can be Z_NO_FLUSH, Z_SYNC_FLUSH, + Z_FINISH, or Z_BLOCK. Z_SYNC_FLUSH requests that inflate() flush as much + output as possible to the output buffer. Z_BLOCK requests that inflate() stop + if and when it gets to the next deflate block boundary. When decoding the + zlib or gzip format, this will cause inflate() to return immediately after + the header and before the first block. When doing a raw inflate, inflate() + will go ahead and process the first block, and will return when it gets to + the end of that block, or when it runs out of data. + + The Z_BLOCK option assists in appending to or combining deflate streams. + Also to assist in this, on return inflate() will set strm->data_type to the + number of unused bits in the last byte taken from strm->next_in, plus 64 + if inflate() is currently decoding the last block in the deflate stream, + plus 128 if inflate() returned immediately after decoding an end-of-block + code or decoding the complete header up to just before the first byte of the + deflate stream. The end-of-block will not be indicated until all of the + uncompressed data from that block has been written to strm->next_out. The + number of unused bits may in general be greater than seven, except when + bit 7 of data_type is set, in which case the number of unused bits will be + less than eight. + + inflate() should normally be called until it returns Z_STREAM_END or an + error. However if all decompression is to be performed in a single step + (a single call of inflate), the parameter flush should be set to + Z_FINISH. In this case all pending input is processed and all pending + output is flushed; avail_out must be large enough to hold all the + uncompressed data. (The size of the uncompressed data may have been saved + by the compressor for this purpose.) The next operation on this stream must + be inflateEnd to deallocate the decompression state. The use of Z_FINISH + is never required, but can be used to inform inflate that a faster approach + may be used for the single inflate() call. + + In this implementation, inflate() always flushes as much output as + possible to the output buffer, and always uses the faster approach on the + first call. So the only effect of the flush parameter in this implementation + is on the return value of inflate(), as noted below, or when it returns early + because Z_BLOCK is used. + + If a preset dictionary is needed after this call (see inflateSetDictionary + below), inflate sets strm->adler to the adler32 checksum of the dictionary + chosen by the compressor and returns Z_NEED_DICT; otherwise it sets + strm->adler to the adler32 checksum of all output produced so far (that is, + total_out bytes) and returns Z_OK, Z_STREAM_END or an error code as described + below. At the end of the stream, inflate() checks that its computed adler32 + checksum is equal to that saved by the compressor and returns Z_STREAM_END + only if the checksum is correct. + + inflate() will decompress and check either zlib-wrapped or gzip-wrapped + deflate data. The header type is detected automatically. Any information + contained in the gzip header is not retained, so applications that need that + information should instead use raw inflate, see inflateInit2() below, or + inflateBack() and perform their own processing of the gzip header and + trailer. + + inflate() returns Z_OK if some progress has been made (more input processed + or more output produced), Z_STREAM_END if the end of the compressed data has + been reached and all uncompressed output has been produced, Z_NEED_DICT if a + preset dictionary is needed at this point, Z_DATA_ERROR if the input data was + corrupted (input stream not conforming to the zlib format or incorrect check + value), Z_STREAM_ERROR if the stream structure was inconsistent (for example + if next_in or next_out was NULL), Z_MEM_ERROR if there was not enough memory, + Z_BUF_ERROR if no progress is possible or if there was not enough room in the + output buffer when Z_FINISH is used. Note that Z_BUF_ERROR is not fatal, and + inflate() can be called again with more input and more output space to + continue decompressing. If Z_DATA_ERROR is returned, the application may then + call inflateSync() to look for a good compression block if a partial recovery + of the data is desired. +*/ + + +ZEXTERN int Q_ZEXPORT inflateEnd OF((z_streamp strm)); +/* + All dynamically allocated data structures for this stream are freed. + This function discards any unprocessed input and does not flush any + pending output. + + inflateEnd returns Z_OK if success, Z_STREAM_ERROR if the stream state + was inconsistent. In the error case, msg may be set but then points to a + static string (which must not be deallocated). +*/ + + /* Advanced functions */ + +/* + The following functions are needed only in some special applications. +*/ + +/* +ZEXTERN int ZEXPORT deflateInit2 OF((z_streamp strm, + int level, + int method, + int windowBits, + int memLevel, + int strategy)); + + This is another version of deflateInit with more compression options. The + fields next_in, zalloc, zfree and opaque must be initialized before by + the caller. + + The method parameter is the compression method. It must be Z_DEFLATED in + this version of the library. + + The windowBits parameter is the base two logarithm of the window size + (the size of the history buffer). It should be in the range 8..15 for this + version of the library. Larger values of this parameter result in better + compression at the expense of memory usage. The default value is 15 if + deflateInit is used instead. + + windowBits can also be -8..-15 for raw deflate. In this case, -windowBits + determines the window size. deflate() will then generate raw deflate data + with no zlib header or trailer, and will not compute an adler32 check value. + + windowBits can also be greater than 15 for optional gzip encoding. Add + 16 to windowBits to write a simple gzip header and trailer around the + compressed data instead of a zlib wrapper. The gzip header will have no + file name, no extra data, no comment, no modification time (set to zero), + no header crc, and the operating system will be set to 255 (unknown). If a + gzip stream is being written, strm->adler is a crc32 instead of an adler32. + + The memLevel parameter specifies how much memory should be allocated + for the internal compression state. memLevel=1 uses minimum memory but + is slow and reduces compression ratio; memLevel=9 uses maximum memory + for optimal speed. The default value is 8. See zconf.h for total memory + usage as a function of windowBits and memLevel. + + The strategy parameter is used to tune the compression algorithm. Use the + value Z_DEFAULT_STRATEGY for normal data, Z_FILTERED for data produced by a + filter (or predictor), Z_HUFFMAN_ONLY to force Huffman encoding only (no + string match), or Z_RLE to limit match distances to one (run-length + encoding). Filtered data consists mostly of small values with a somewhat + random distribution. In this case, the compression algorithm is tuned to + compress them better. The effect of Z_FILTERED is to force more Huffman + coding and less string matching; it is somewhat intermediate between + Z_DEFAULT and Z_HUFFMAN_ONLY. Z_RLE is designed to be almost as fast as + Z_HUFFMAN_ONLY, but give better compression for PNG image data. The strategy + parameter only affects the compression ratio but not the correctness of the + compressed output even if it is not set appropriately. Z_FIXED prevents the + use of dynamic Huffman codes, allowing for a simpler decoder for special + applications. + + deflateInit2 returns Z_OK if success, Z_MEM_ERROR if there was not enough + memory, Z_STREAM_ERROR if a parameter is invalid (such as an invalid + method). msg is set to null if there is no error message. deflateInit2 does + not perform any compression: this will be done by deflate(). +*/ + +ZEXTERN int Q_ZEXPORT deflateSetDictionary OF((z_streamp strm, + const Bytef *dictionary, + uInt dictLength)); +/* + Initializes the compression dictionary from the given byte sequence + without producing any compressed output. This function must be called + immediately after deflateInit, deflateInit2 or deflateReset, before any + call of deflate. The compressor and decompressor must use exactly the same + dictionary (see inflateSetDictionary). + + The dictionary should consist of strings (byte sequences) that are likely + to be encountered later in the data to be compressed, with the most commonly + used strings preferably put towards the end of the dictionary. Using a + dictionary is most useful when the data to be compressed is short and can be + predicted with good accuracy; the data can then be compressed better than + with the default empty dictionary. + + Depending on the size of the compression data structures selected by + deflateInit or deflateInit2, a part of the dictionary may in effect be + discarded, for example if the dictionary is larger than the window size in + deflate or deflate2. Thus the strings most likely to be useful should be + put at the end of the dictionary, not at the front. In addition, the + current implementation of deflate will use at most the window size minus + 262 bytes of the provided dictionary. + + Upon return of this function, strm->adler is set to the adler32 value + of the dictionary; the decompressor may later use this value to determine + which dictionary has been used by the compressor. (The adler32 value + applies to the whole dictionary even if only a subset of the dictionary is + actually used by the compressor.) If a raw deflate was requested, then the + adler32 value is not computed and strm->adler is not set. + + deflateSetDictionary returns Z_OK if success, or Z_STREAM_ERROR if a + parameter is invalid (such as NULL dictionary) or the stream state is + inconsistent (for example if deflate has already been called for this stream + or if the compression method is bsort). deflateSetDictionary does not + perform any compression: this will be done by deflate(). +*/ + +ZEXTERN int Q_ZEXPORT deflateCopy OF((z_streamp dest, + z_streamp source)); +/* + Sets the destination stream as a complete copy of the source stream. + + This function can be useful when several compression strategies will be + tried, for example when there are several ways of pre-processing the input + data with a filter. The streams that will be discarded should then be freed + by calling deflateEnd. Note that deflateCopy duplicates the internal + compression state which can be quite large, so this strategy is slow and + can consume lots of memory. + + deflateCopy returns Z_OK if success, Z_MEM_ERROR if there was not + enough memory, Z_STREAM_ERROR if the source stream state was inconsistent + (such as zalloc being NULL). msg is left unchanged in both source and + destination. +*/ + +ZEXTERN int Q_ZEXPORT deflateReset OF((z_streamp strm)); +/* + This function is equivalent to deflateEnd followed by deflateInit, + but does not free and reallocate all the internal compression state. + The stream will keep the same compression level and any other attributes + that may have been set by deflateInit2. + + deflateReset returns Z_OK if success, or Z_STREAM_ERROR if the source + stream state was inconsistent (such as zalloc or state being NULL). +*/ + +ZEXTERN int Q_ZEXPORT deflateParams OF((z_streamp strm, + int level, + int strategy)); +/* + Dynamically update the compression level and compression strategy. The + interpretation of level and strategy is as in deflateInit2. This can be + used to switch between compression and straight copy of the input data, or + to switch to a different kind of input data requiring a different + strategy. If the compression level is changed, the input available so far + is compressed with the old level (and may be flushed); the new level will + take effect only at the next call of deflate(). + + Before the call of deflateParams, the stream state must be set as for + a call of deflate(), since the currently available input may have to + be compressed and flushed. In particular, strm->avail_out must be non-zero. + + deflateParams returns Z_OK if success, Z_STREAM_ERROR if the source + stream state was inconsistent or if a parameter was invalid, Z_BUF_ERROR + if strm->avail_out was zero. +*/ + +ZEXTERN int ZEXPORT deflateTune OF((z_streamp strm, + int good_length, + int max_lazy, + int nice_length, + int max_chain)); +/* + Fine tune deflate's internal compression parameters. This should only be + used by someone who understands the algorithm used by zlib's deflate for + searching for the best matching string, and even then only by the most + fanatic optimizer trying to squeeze out the last compressed bit for their + specific input data. Read the deflate.c source code for the meaning of the + max_lazy, good_length, nice_length, and max_chain parameters. + + deflateTune() can be called after deflateInit() or deflateInit2(), and + returns Z_OK on success, or Z_STREAM_ERROR for an invalid deflate stream. + */ + +ZEXTERN uLong ZEXPORT deflateBound OF((z_streamp strm, + uLong sourceLen)); +/* + deflateBound() returns an upper bound on the compressed size after + deflation of sourceLen bytes. It must be called after deflateInit() + or deflateInit2(). This would be used to allocate an output buffer + for deflation in a single pass, and so would be called before deflate(). +*/ + +ZEXTERN int ZEXPORT deflatePrime OF((z_streamp strm, + int bits, + int value)); +/* + deflatePrime() inserts bits in the deflate output stream. The intent + is that this function is used to start off the deflate output with the + bits leftover from a previous deflate stream when appending to it. As such, + this function can only be used for raw deflate, and must be used before the + first deflate() call after a deflateInit2() or deflateReset(). bits must be + less than or equal to 16, and that many of the least significant bits of + value will be inserted in the output. + + deflatePrime returns Z_OK if success, or Z_STREAM_ERROR if the source + stream state was inconsistent. +*/ + +ZEXTERN int ZEXPORT deflateSetHeader OF((z_streamp strm, + gz_headerp head)); +/* + deflateSetHeader() provides gzip header information for when a gzip + stream is requested by deflateInit2(). deflateSetHeader() may be called + after deflateInit2() or deflateReset() and before the first call of + deflate(). The text, time, os, extra field, name, and comment information + in the provided gz_header structure are written to the gzip header (xflag is + ignored -- the extra flags are set according to the compression level). The + caller must assure that, if not Z_NULL, name and comment are terminated with + a zero byte, and that if extra is not Z_NULL, that extra_len bytes are + available there. If hcrc is true, a gzip header crc is included. Note that + the current versions of the command-line version of gzip (up through version + 1.3.x) do not support header crc's, and will report that it is a "multi-part + gzip file" and give up. + + If deflateSetHeader is not used, the default gzip header has text false, + the time set to zero, and os set to 255, with no extra, name, or comment + fields. The gzip header is returned to the default state by deflateReset(). + + deflateSetHeader returns Z_OK if success, or Z_STREAM_ERROR if the source + stream state was inconsistent. +*/ + +/* +ZEXTERN int ZEXPORT inflateInit2 OF((z_streamp strm, + int windowBits)); + + This is another version of inflateInit with an extra parameter. The + fields next_in, avail_in, zalloc, zfree and opaque must be initialized + before by the caller. + + The windowBits parameter is the base two logarithm of the maximum window + size (the size of the history buffer). It should be in the range 8..15 for + this version of the library. The default value is 15 if inflateInit is used + instead. windowBits must be greater than or equal to the windowBits value + provided to deflateInit2() while compressing, or it must be equal to 15 if + deflateInit2() was not used. If a compressed stream with a larger window + size is given as input, inflate() will return with the error code + Z_DATA_ERROR instead of trying to allocate a larger window. + + windowBits can also be -8..-15 for raw inflate. In this case, -windowBits + determines the window size. inflate() will then process raw deflate data, + not looking for a zlib or gzip header, not generating a check value, and not + looking for any check values for comparison at the end of the stream. This + is for use with other formats that use the deflate compressed data format + such as zip. Those formats provide their own check values. If a custom + format is developed using the raw deflate format for compressed data, it is + recommended that a check value such as an adler32 or a crc32 be applied to + the uncompressed data as is done in the zlib, gzip, and zip formats. For + most applications, the zlib format should be used as is. Note that comments + above on the use in deflateInit2() applies to the magnitude of windowBits. + + windowBits can also be greater than 15 for optional gzip decoding. Add + 32 to windowBits to enable zlib and gzip decoding with automatic header + detection, or add 16 to decode only the gzip format (the zlib format will + return a Z_DATA_ERROR). If a gzip stream is being decoded, strm->adler is + a crc32 instead of an adler32. + + inflateInit2 returns Z_OK if success, Z_MEM_ERROR if there was not enough + memory, Z_STREAM_ERROR if a parameter is invalid (such as a null strm). msg + is set to null if there is no error message. inflateInit2 does not perform + any decompression apart from reading the zlib header if present: this will + be done by inflate(). (So next_in and avail_in may be modified, but next_out + and avail_out are unchanged.) +*/ + +ZEXTERN int Q_ZEXPORT inflateSetDictionary OF((z_streamp strm, + const Bytef *dictionary, + uInt dictLength)); +/* + Initializes the decompression dictionary from the given uncompressed byte + sequence. This function must be called immediately after a call of inflate, + if that call returned Z_NEED_DICT. The dictionary chosen by the compressor + can be determined from the adler32 value returned by that call of inflate. + The compressor and decompressor must use exactly the same dictionary (see + deflateSetDictionary). For raw inflate, this function can be called + immediately after inflateInit2() or inflateReset() and before any call of + inflate() to set the dictionary. The application must insure that the + dictionary that was used for compression is provided. + + inflateSetDictionary returns Z_OK if success, Z_STREAM_ERROR if a + parameter is invalid (such as NULL dictionary) or the stream state is + inconsistent, Z_DATA_ERROR if the given dictionary doesn't match the + expected one (incorrect adler32 value). inflateSetDictionary does not + perform any decompression: this will be done by subsequent calls of + inflate(). +*/ + +ZEXTERN int Q_ZEXPORT inflateSync OF((z_streamp strm)); +/* + Skips invalid compressed data until a full flush point (see above the + description of deflate with Z_FULL_FLUSH) can be found, or until all + available input is skipped. No output is provided. + + inflateSync returns Z_OK if a full flush point has been found, Z_BUF_ERROR + if no more input was provided, Z_DATA_ERROR if no flush point has been found, + or Z_STREAM_ERROR if the stream structure was inconsistent. In the success + case, the application may save the current current value of total_in which + indicates where valid compressed data was found. In the error case, the + application may repeatedly call inflateSync, providing more input each time, + until success or end of the input data. +*/ + +ZEXTERN int ZEXPORT inflateCopy OF((z_streamp dest, + z_streamp source)); +/* + Sets the destination stream as a complete copy of the source stream. + + This function can be useful when randomly accessing a large stream. The + first pass through the stream can periodically record the inflate state, + allowing restarting inflate at those points when randomly accessing the + stream. + + inflateCopy returns Z_OK if success, Z_MEM_ERROR if there was not + enough memory, Z_STREAM_ERROR if the source stream state was inconsistent + (such as zalloc being NULL). msg is left unchanged in both source and + destination. +*/ + +ZEXTERN int Q_ZEXPORT inflateReset OF((z_streamp strm)); +/* + This function is equivalent to inflateEnd followed by inflateInit, + but does not free and reallocate all the internal decompression state. + The stream will keep attributes that may have been set by inflateInit2. + + inflateReset returns Z_OK if success, or Z_STREAM_ERROR if the source + stream state was inconsistent (such as zalloc or state being NULL). +*/ + +ZEXTERN int ZEXPORT inflatePrime OF((z_streamp strm, + int bits, + int value)); +/* + This function inserts bits in the inflate input stream. The intent is + that this function is used to start inflating at a bit position in the + middle of a byte. The provided bits will be used before any bytes are used + from next_in. This function should only be used with raw inflate, and + should be used before the first inflate() call after inflateInit2() or + inflateReset(). bits must be less than or equal to 16, and that many of the + least significant bits of value will be inserted in the input. + + inflatePrime returns Z_OK if success, or Z_STREAM_ERROR if the source + stream state was inconsistent. +*/ + +ZEXTERN int ZEXPORT inflateGetHeader OF((z_streamp strm, + gz_headerp head)); +/* + inflateGetHeader() requests that gzip header information be stored in the + provided gz_header structure. inflateGetHeader() may be called after + inflateInit2() or inflateReset(), and before the first call of inflate(). + As inflate() processes the gzip stream, head->done is zero until the header + is completed, at which time head->done is set to one. If a zlib stream is + being decoded, then head->done is set to -1 to indicate that there will be + no gzip header information forthcoming. Note that Z_BLOCK can be used to + force inflate() to return immediately after header processing is complete + and before any actual data is decompressed. + + The text, time, xflags, and os fields are filled in with the gzip header + contents. hcrc is set to true if there is a header CRC. (The header CRC + was valid if done is set to one.) If extra is not Z_NULL, then extra_max + contains the maximum number of bytes to write to extra. Once done is true, + extra_len contains the actual extra field length, and extra contains the + extra field, or that field truncated if extra_max is less than extra_len. + If name is not Z_NULL, then up to name_max characters are written there, + terminated with a zero unless the length is greater than name_max. If + comment is not Z_NULL, then up to comm_max characters are written there, + terminated with a zero unless the length is greater than comm_max. When + any of extra, name, or comment are not Z_NULL and the respective field is + not present in the header, then that field is set to Z_NULL to signal its + absence. This allows the use of deflateSetHeader() with the returned + structure to duplicate the header. However if those fields are set to + allocated memory, then the application will need to save those pointers + elsewhere so that they can be eventually freed. + + If inflateGetHeader is not used, then the header information is simply + discarded. The header is always checked for validity, including the header + CRC if present. inflateReset() will reset the process to discard the header + information. The application would need to call inflateGetHeader() again to + retrieve the header from the next gzip stream. + + inflateGetHeader returns Z_OK if success, or Z_STREAM_ERROR if the source + stream state was inconsistent. +*/ + +/* +ZEXTERN int ZEXPORT inflateBackInit OF((z_streamp strm, int windowBits, + unsigned char FAR *window)); + + Initialize the internal stream state for decompression using inflateBack() + calls. The fields zalloc, zfree and opaque in strm must be initialized + before the call. If zalloc and zfree are Z_NULL, then the default library- + derived memory allocation routines are used. windowBits is the base two + logarithm of the window size, in the range 8..15. window is a caller + supplied buffer of that size. Except for special applications where it is + assured that deflate was used with small window sizes, windowBits must be 15 + and a 32K byte window must be supplied to be able to decompress general + deflate streams. + + See inflateBack() for the usage of these routines. + + inflateBackInit will return Z_OK on success, Z_STREAM_ERROR if any of + the paramaters are invalid, Z_MEM_ERROR if the internal state could not + be allocated, or Z_VERSION_ERROR if the version of the library does not + match the version of the header file. +*/ + +typedef unsigned (*in_func) OF((void FAR *, unsigned char FAR * FAR *)); +typedef int (*out_func) OF((void FAR *, unsigned char FAR *, unsigned)); + +ZEXTERN int ZEXPORT inflateBack OF((z_streamp strm, + in_func in, void FAR *in_desc, + out_func out, void FAR *out_desc)); +/* + inflateBack() does a raw inflate with a single call using a call-back + interface for input and output. This is more efficient than inflate() for + file i/o applications in that it avoids copying between the output and the + sliding window by simply making the window itself the output buffer. This + function trusts the application to not change the output buffer passed by + the output function, at least until inflateBack() returns. + + inflateBackInit() must be called first to allocate the internal state + and to initialize the state with the user-provided window buffer. + inflateBack() may then be used multiple times to inflate a complete, raw + deflate stream with each call. inflateBackEnd() is then called to free + the allocated state. + + A raw deflate stream is one with no zlib or gzip header or trailer. + This routine would normally be used in a utility that reads zip or gzip + files and writes out uncompressed files. The utility would decode the + header and process the trailer on its own, hence this routine expects + only the raw deflate stream to decompress. This is different from the + normal behavior of inflate(), which expects either a zlib or gzip header and + trailer around the deflate stream. + + inflateBack() uses two subroutines supplied by the caller that are then + called by inflateBack() for input and output. inflateBack() calls those + routines until it reads a complete deflate stream and writes out all of the + uncompressed data, or until it encounters an error. The function's + parameters and return types are defined above in the in_func and out_func + typedefs. inflateBack() will call in(in_desc, &buf) which should return the + number of bytes of provided input, and a pointer to that input in buf. If + there is no input available, in() must return zero--buf is ignored in that + case--and inflateBack() will return a buffer error. inflateBack() will call + out(out_desc, buf, len) to write the uncompressed data buf[0..len-1]. out() + should return zero on success, or non-zero on failure. If out() returns + non-zero, inflateBack() will return with an error. Neither in() nor out() + are permitted to change the contents of the window provided to + inflateBackInit(), which is also the buffer that out() uses to write from. + The length written by out() will be at most the window size. Any non-zero + amount of input may be provided by in(). + + For convenience, inflateBack() can be provided input on the first call by + setting strm->next_in and strm->avail_in. If that input is exhausted, then + in() will be called. Therefore strm->next_in must be initialized before + calling inflateBack(). If strm->next_in is Z_NULL, then in() will be called + immediately for input. If strm->next_in is not Z_NULL, then strm->avail_in + must also be initialized, and then if strm->avail_in is not zero, input will + initially be taken from strm->next_in[0 .. strm->avail_in - 1]. + + The in_desc and out_desc parameters of inflateBack() is passed as the + first parameter of in() and out() respectively when they are called. These + descriptors can be optionally used to pass any information that the caller- + supplied in() and out() functions need to do their job. + + On return, inflateBack() will set strm->next_in and strm->avail_in to + pass back any unused input that was provided by the last in() call. The + return values of inflateBack() can be Z_STREAM_END on success, Z_BUF_ERROR + if in() or out() returned an error, Z_DATA_ERROR if there was a format + error in the deflate stream (in which case strm->msg is set to indicate the + nature of the error), or Z_STREAM_ERROR if the stream was not properly + initialized. In the case of Z_BUF_ERROR, an input or output error can be + distinguished using strm->next_in which will be Z_NULL only if in() returned + an error. If strm->next is not Z_NULL, then the Z_BUF_ERROR was due to + out() returning non-zero. (in() will always be called before out(), so + strm->next_in is assured to be defined if out() returns non-zero.) Note + that inflateBack() cannot return Z_OK. +*/ + +ZEXTERN int ZEXPORT inflateBackEnd OF((z_streamp strm)); +/* + All memory allocated by inflateBackInit() is freed. + + inflateBackEnd() returns Z_OK on success, or Z_STREAM_ERROR if the stream + state was inconsistent. +*/ + +ZEXTERN uLong ZEXPORT zlibCompileFlags OF((void)); +/* Return flags indicating compile-time options. + + Type sizes, two bits each, 00 = 16 bits, 01 = 32, 10 = 64, 11 = other: + 1.0: size of uInt + 3.2: size of uLong + 5.4: size of voidpf (pointer) + 7.6: size of z_off_t + + Compiler, assembler, and debug options: + 8: DEBUG + 9: ASMV or ASMINF -- use ASM code + 10: ZLIB_WINAPI -- exported functions use the WINAPI calling convention + 11: 0 (reserved) + + One-time table building (smaller code, but not thread-safe if true): + 12: BUILDFIXED -- build static block decoding tables when needed + 13: DYNAMIC_CRC_TABLE -- build CRC calculation tables when needed + 14,15: 0 (reserved) + + Library content (indicates missing functionality): + 16: NO_GZCOMPRESS -- gz* functions cannot compress (to avoid linking + deflate code when not needed) + 17: NO_GZIP -- deflate can't write gzip streams, and inflate can't detect + and decode gzip streams (to avoid linking crc code) + 18-19: 0 (reserved) + + Operation variations (changes in library functionality): + 20: PKZIP_BUG_WORKAROUND -- slightly more permissive inflate + 21: FASTEST -- deflate algorithm with only one, lowest compression level + 22,23: 0 (reserved) + + The sprintf variant used by gzprintf (zero is best): + 24: 0 = vs*, 1 = s* -- 1 means limited to 20 arguments after the format + 25: 0 = *nprintf, 1 = *printf -- 1 means gzprintf() not secure! + 26: 0 = returns value, 1 = void -- 1 means inferred string length returned + + Remainder: + 27-31: 0 (reserved) + */ + + + /* utility functions */ + +/* + The following utility functions are implemented on top of the + basic stream-oriented functions. To simplify the interface, some + default options are assumed (compression level and memory usage, + standard memory allocation functions). The source code of these + utility functions can easily be modified if you need special options. +*/ + +ZEXTERN int Q_ZEXPORT compress OF((Bytef *dest, uLongf *destLen, + const Bytef *source, uLong sourceLen)); +/* + Compresses the source buffer into the destination buffer. sourceLen is + the byte length of the source buffer. Upon entry, destLen is the total + size of the destination buffer, which must be at least the value returned + by compressBound(sourceLen). Upon exit, destLen is the actual size of the + compressed buffer. + This function can be used to compress a whole file at once if the + input file is mmap'ed. + compress returns Z_OK if success, Z_MEM_ERROR if there was not + enough memory, Z_BUF_ERROR if there was not enough room in the output + buffer. +*/ + +ZEXTERN int Q_ZEXPORT compress2 OF((Bytef *dest, uLongf *destLen, + const Bytef *source, uLong sourceLen, + int level)); +/* + Compresses the source buffer into the destination buffer. The level + parameter has the same meaning as in deflateInit. sourceLen is the byte + length of the source buffer. Upon entry, destLen is the total size of the + destination buffer, which must be at least the value returned by + compressBound(sourceLen). Upon exit, destLen is the actual size of the + compressed buffer. + + compress2 returns Z_OK if success, Z_MEM_ERROR if there was not enough + memory, Z_BUF_ERROR if there was not enough room in the output buffer, + Z_STREAM_ERROR if the level parameter is invalid. +*/ + +ZEXTERN uLong ZEXPORT compressBound OF((uLong sourceLen)); +/* + compressBound() returns an upper bound on the compressed size after + compress() or compress2() on sourceLen bytes. It would be used before + a compress() or compress2() call to allocate the destination buffer. +*/ + +ZEXTERN int Q_ZEXPORT uncompress OF((Bytef *dest, uLongf *destLen, + const Bytef *source, uLong sourceLen)); +/* + Decompresses the source buffer into the destination buffer. sourceLen is + the byte length of the source buffer. Upon entry, destLen is the total + size of the destination buffer, which must be large enough to hold the + entire uncompressed data. (The size of the uncompressed data must have + been saved previously by the compressor and transmitted to the decompressor + by some mechanism outside the scope of this compression library.) + Upon exit, destLen is the actual size of the compressed buffer. + This function can be used to decompress a whole file at once if the + input file is mmap'ed. + + uncompress returns Z_OK if success, Z_MEM_ERROR if there was not + enough memory, Z_BUF_ERROR if there was not enough room in the output + buffer, or Z_DATA_ERROR if the input data was corrupted or incomplete. +*/ + + +typedef voidp gzFile; + +ZEXTERN gzFile Q_ZEXPORT gzopen OF((const char *path, const char *mode)); +/* + Opens a gzip (.gz) file for reading or writing. The mode parameter + is as in fopen ("rb" or "wb") but can also include a compression level + ("wb9") or a strategy: 'f' for filtered data as in "wb6f", 'h' for + Huffman only compression as in "wb1h", or 'R' for run-length encoding + as in "wb1R". (See the description of deflateInit2 for more information + about the strategy parameter.) + + gzopen can be used to read a file which is not in gzip format; in this + case gzread will directly read from the file without decompression. + + gzopen returns NULL if the file could not be opened or if there was + insufficient memory to allocate the (de)compression state; errno + can be checked to distinguish the two cases (if errno is zero, the + zlib error is Z_MEM_ERROR). */ + +ZEXTERN gzFile Q_ZEXPORT gzdopen OF((int fd, const char *mode)); +/* + gzdopen() associates a gzFile with the file descriptor fd. File + descriptors are obtained from calls like open, dup, creat, pipe or + fileno (in the file has been previously opened with fopen). + The mode parameter is as in gzopen. + The next call of gzclose on the returned gzFile will also close the + file descriptor fd, just like fclose(fdopen(fd), mode) closes the file + descriptor fd. If you want to keep fd open, use gzdopen(dup(fd), mode). + gzdopen returns NULL if there was insufficient memory to allocate + the (de)compression state. +*/ + +ZEXTERN int Q_ZEXPORT gzsetparams OF((gzFile file, int level, int strategy)); +/* + Dynamically update the compression level or strategy. See the description + of deflateInit2 for the meaning of these parameters. + gzsetparams returns Z_OK if success, or Z_STREAM_ERROR if the file was not + opened for writing. +*/ + +ZEXTERN int Q_ZEXPORT gzread OF((gzFile file, voidp buf, unsigned len)); +/* + Reads the given number of uncompressed bytes from the compressed file. + If the input file was not in gzip format, gzread copies the given number + of bytes into the buffer. + gzread returns the number of uncompressed bytes actually read (0 for + end of file, -1 for error). */ + +ZEXTERN int Q_ZEXPORT gzwrite OF((gzFile file, + voidpc buf, unsigned len)); +/* + Writes the given number of uncompressed bytes into the compressed file. + gzwrite returns the number of uncompressed bytes actually written + (0 in case of error). +*/ + +ZEXTERN int Q_ZEXPORT gzprintf OF((gzFile file, const char *format, ...)); +/* + Converts, formats, and writes the args to the compressed file under + control of the format string, as in fprintf. gzprintf returns the number of + uncompressed bytes actually written (0 in case of error). The number of + uncompressed bytes written is limited to 4095. The caller should assure that + this limit is not exceeded. If it is exceeded, then gzprintf() will return + return an error (0) with nothing written. In this case, there may also be a + buffer overflow with unpredictable consequences, which is possible only if + zlib was compiled with the insecure functions sprintf() or vsprintf() + because the secure snprintf() or vsnprintf() functions were not available. +*/ + +ZEXTERN int Q_ZEXPORT gzputs OF((gzFile file, const char *s)); +/* + Writes the given null-terminated string to the compressed file, excluding + the terminating null character. + gzputs returns the number of characters written, or -1 in case of error. +*/ + +ZEXTERN Q_ZEXPORT char * gzgets OF((gzFile file, char *buf, int len)); +/* + Reads bytes from the compressed file until len-1 characters are read, or + a newline character is read and transferred to buf, or an end-of-file + condition is encountered. The string is then terminated with a null + character. + gzgets returns buf, or Z_NULL in case of error. +*/ + +ZEXTERN int Q_ZEXPORT gzputc OF((gzFile file, int c)); +/* + Writes c, converted to an unsigned char, into the compressed file. + gzputc returns the value that was written, or -1 in case of error. +*/ + +ZEXTERN int Q_ZEXPORT gzgetc OF((gzFile file)); +/* + Reads one byte from the compressed file. gzgetc returns this byte + or -1 in case of end of file or error. +*/ + +ZEXTERN int ZEXPORT gzungetc OF((int c, gzFile file)); +/* + Push one character back onto the stream to be read again later. + Only one character of push-back is allowed. gzungetc() returns the + character pushed, or -1 on failure. gzungetc() will fail if a + character has been pushed but not read yet, or if c is -1. The pushed + character will be discarded if the stream is repositioned with gzseek() + or gzrewind(). +*/ + +ZEXTERN int Q_ZEXPORT gzflush OF((gzFile file, int flush)); +/* + Flushes all pending output into the compressed file. The parameter + flush is as in the deflate() function. The return value is the zlib + error number (see function gzerror below). gzflush returns Z_OK if + the flush parameter is Z_FINISH and all output could be flushed. + gzflush should be called only when strictly necessary because it can + degrade compression. +*/ + +ZEXTERN z_off_t Q_ZEXPORT gzseek OF((gzFile file, + z_off_t offset, int whence)); +/* + Sets the starting position for the next gzread or gzwrite on the + given compressed file. The offset represents a number of bytes in the + uncompressed data stream. The whence parameter is defined as in lseek(2); + the value SEEK_END is not supported. + If the file is opened for reading, this function is emulated but can be + extremely slow. If the file is opened for writing, only forward seeks are + supported; gzseek then compresses a sequence of zeroes up to the new + starting position. + + gzseek returns the resulting offset location as measured in bytes from + the beginning of the uncompressed stream, or -1 in case of error, in + particular if the file is opened for writing and the new starting position + would be before the current position. +*/ + +ZEXTERN int Q_ZEXPORT gzrewind OF((gzFile file)); +/* + Rewinds the given file. This function is supported only for reading. + + gzrewind(file) is equivalent to (int)gzseek(file, 0L, SEEK_SET) +*/ + +ZEXTERN z_off_t Q_ZEXPORT gztell OF((gzFile file)); +/* + Returns the starting position for the next gzread or gzwrite on the + given compressed file. This position represents a number of bytes in the + uncompressed data stream. + + gztell(file) is equivalent to gzseek(file, 0L, SEEK_CUR) +*/ + +ZEXTERN int Q_ZEXPORT gzeof OF((gzFile file)); +/* + Returns 1 when EOF has previously been detected reading the given + input stream, otherwise zero. +*/ + +ZEXTERN int ZEXPORT gzdirect OF((gzFile file)); +/* + Returns 1 if file is being read directly without decompression, otherwise + zero. +*/ + +ZEXTERN int Q_ZEXPORT gzclose OF((gzFile file)); +/* + Flushes all pending output if necessary, closes the compressed file + and deallocates all the (de)compression state. The return value is the zlib + error number (see function gzerror below). +*/ + +ZEXTERN Q_ZEXPORT const char * gzerror OF((gzFile file, int *errnum)); +/* + Returns the error message for the last error which occurred on the + given compressed file. errnum is set to zlib error number. If an + error occurred in the file system and not in the compression library, + errnum is set to Z_ERRNO and the application may consult errno + to get the exact error code. +*/ + +ZEXTERN void ZEXPORT gzclearerr OF((gzFile file)); +/* + Clears the error and end-of-file flags for file. This is analogous to the + clearerr() function in stdio. This is useful for continuing to read a gzip + file that is being written concurrently. +*/ + + /* checksum functions */ + +/* + These functions are not related to compression but are exported + anyway because they might be useful in applications using the + compression library. +*/ + +ZEXTERN uLong Q_ZEXPORT adler32 OF((uLong adler, const Bytef *buf, uInt len)); +/* + Update a running Adler-32 checksum with the bytes buf[0..len-1] and + return the updated checksum. If buf is NULL, this function returns + the required initial value for the checksum. + An Adler-32 checksum is almost as reliable as a CRC32 but can be computed + much faster. Usage example: + + uLong adler = adler32(0L, Z_NULL, 0); + + while (read_buffer(buffer, length) != EOF) { + adler = adler32(adler, buffer, length); + } + if (adler != original_adler) error(); +*/ + +ZEXTERN uLong ZEXPORT adler32_combine OF((uLong adler1, uLong adler2, + z_off_t len2)); +/* + Combine two Adler-32 checksums into one. For two sequences of bytes, seq1 + and seq2 with lengths len1 and len2, Adler-32 checksums were calculated for + each, adler1 and adler2. adler32_combine() returns the Adler-32 checksum of + seq1 and seq2 concatenated, requiring only adler1, adler2, and len2. +*/ + +ZEXTERN uLong Q_ZEXPORT crc32 OF((uLong crc, const Bytef *buf, uInt len)); +/* + Update a running CRC-32 with the bytes buf[0..len-1] and return the + updated CRC-32. If buf is NULL, this function returns the required initial + value for the for the crc. Pre- and post-conditioning (one's complement) is + performed within this function so it shouldn't be done by the application. + Usage example: + + uLong crc = crc32(0L, Z_NULL, 0); + + while (read_buffer(buffer, length) != EOF) { + crc = crc32(crc, buffer, length); + } + if (crc != original_crc) error(); +*/ + +ZEXTERN uLong ZEXPORT crc32_combine OF((uLong crc1, uLong crc2, z_off_t len2)); + +/* + Combine two CRC-32 check values into one. For two sequences of bytes, + seq1 and seq2 with lengths len1 and len2, CRC-32 check values were + calculated for each, crc1 and crc2. crc32_combine() returns the CRC-32 + check value of seq1 and seq2 concatenated, requiring only crc1, crc2, and + len2. +*/ + + + /* various hacks, don't look :) */ + +/* deflateInit and inflateInit are macros to allow checking the zlib version + * and the compiler's view of z_stream: + */ +ZEXTERN int Q_ZEXPORT deflateInit_ OF((z_streamp strm, int level, + const char *version, int stream_size)); +ZEXTERN int Q_ZEXPORT inflateInit_ OF((z_streamp strm, + const char *version, int stream_size)); +ZEXTERN int Q_ZEXPORT deflateInit2_ OF((z_streamp strm, int level, int method, + int windowBits, int memLevel, + int strategy, const char *version, + int stream_size)); +ZEXTERN int Q_ZEXPORT inflateInit2_ OF((z_streamp strm, int windowBits, + const char *version, int stream_size)); +ZEXTERN int ZEXPORT inflateBackInit_ OF((z_streamp strm, int windowBits, + unsigned char FAR *window, + const char *version, + int stream_size)); +#define deflateInit(strm, level) \ + deflateInit_((strm), (level), ZLIB_VERSION, sizeof(z_stream)) +#define inflateInit(strm) \ + inflateInit_((strm), ZLIB_VERSION, sizeof(z_stream)) +#define deflateInit2(strm, level, method, windowBits, memLevel, strategy) \ + deflateInit2_((strm),(level),(method),(windowBits),(memLevel),\ + (strategy), ZLIB_VERSION, sizeof(z_stream)) +#define inflateInit2(strm, windowBits) \ + inflateInit2_((strm), (windowBits), ZLIB_VERSION, sizeof(z_stream)) +#define inflateBackInit(strm, windowBits, window) \ + inflateBackInit_((strm), (windowBits), (window), \ + ZLIB_VERSION, sizeof(z_stream)) + + +#if !defined(ZUTIL_H) && !defined(NO_DUMMY_DECL) + struct internal_state {int dummy;}; /* hack for buggy compilers */ +#endif + +ZEXTERN Q_ZEXPORT const char * zError OF((int)); +ZEXTERN int Q_ZEXPORT inflateSyncPoint OF((z_streamp z)); +ZEXTERN Q_ZEXPORT const uLongf * get_crc_table OF((void)); + +#ifdef __cplusplus +} +#endif + +#endif /* ZLIB_H */ diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zutil.c b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zutil.c index 0f4bd7871..d55f5948a 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zutil.c +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zutil.c @@ -1,318 +1,318 @@ -/* zutil.c -- target dependent utility functions for the compression library - * Copyright (C) 1995-2005 Jean-loup Gailly. - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* @(#) $Id$ */ - -#include "zutil.h" - -#ifndef NO_DUMMY_DECL -struct internal_state {int dummy;}; /* for buggy compilers */ -#endif - -const char * const z_errmsg[10] = { -"need dictionary", /* Z_NEED_DICT 2 */ -"stream end", /* Z_STREAM_END 1 */ -"", /* Z_OK 0 */ -"file error", /* Z_ERRNO (-1) */ -"stream error", /* Z_STREAM_ERROR (-2) */ -"data error", /* Z_DATA_ERROR (-3) */ -"insufficient memory", /* Z_MEM_ERROR (-4) */ -"buffer error", /* Z_BUF_ERROR (-5) */ -"incompatible version",/* Z_VERSION_ERROR (-6) */ -""}; - - -const char * ZEXPORT zlibVersion() -{ - return ZLIB_VERSION; -} - -uLong ZEXPORT zlibCompileFlags() -{ - uLong flags; - - flags = 0; - switch (sizeof(uInt)) { - case 2: break; - case 4: flags += 1; break; - case 8: flags += 2; break; - default: flags += 3; - } - switch (sizeof(uLong)) { - case 2: break; - case 4: flags += 1 << 2; break; - case 8: flags += 2 << 2; break; - default: flags += 3 << 2; - } - switch (sizeof(voidpf)) { - case 2: break; - case 4: flags += 1 << 4; break; - case 8: flags += 2 << 4; break; - default: flags += 3 << 4; - } - switch (sizeof(z_off_t)) { - case 2: break; - case 4: flags += 1 << 6; break; - case 8: flags += 2 << 6; break; - default: flags += 3 << 6; - } -#ifdef DEBUG - flags += 1 << 8; -#endif -#if defined(ASMV) || defined(ASMINF) - flags += 1 << 9; -#endif -#ifdef ZLIB_WINAPI - flags += 1 << 10; -#endif -#ifdef BUILDFIXED - flags += 1 << 12; -#endif -#ifdef DYNAMIC_CRC_TABLE - flags += 1 << 13; -#endif -#ifdef NO_GZCOMPRESS - flags += 1L << 16; -#endif -#ifdef NO_GZIP - flags += 1L << 17; -#endif -#ifdef PKZIP_BUG_WORKAROUND - flags += 1L << 20; -#endif -#ifdef FASTEST - flags += 1L << 21; -#endif -#ifdef STDC -# ifdef NO_vsnprintf - flags += 1L << 25; -# ifdef HAS_vsprintf_void - flags += 1L << 26; -# endif -# else -# ifdef HAS_vsnprintf_void - flags += 1L << 26; -# endif -# endif -#else - flags += 1L << 24; -# ifdef NO_snprintf - flags += 1L << 25; -# ifdef HAS_sprintf_void - flags += 1L << 26; -# endif -# else -# ifdef HAS_snprintf_void - flags += 1L << 26; -# endif -# endif -#endif - return flags; -} - -#ifdef DEBUG - -# ifndef verbose -# define verbose 0 -# endif -int z_verbose = verbose; - -void z_error (m) - char *m; -{ - fprintf(stderr, "%s\n", m); - exit(1); -} -#endif - -/* exported to allow conversion of error code to string for compress() and - * uncompress() - */ -const char * ZEXPORT zError(err) - int err; -{ - return ERR_MSG(err); -} - -#if defined(_WIN32_WCE) - /* The Microsoft C Run-Time Library for Windows CE doesn't have - * errno. We define it as a global variable to simplify porting. - * Its value is always 0 and should not be used. - */ - int errno = 0; -#endif - -#ifndef HAVE_MEMCPY - -void zmemcpy(dest, source, len) - Bytef* dest; - const Bytef* source; - uInt len; -{ - if (len == 0) return; - do { - *dest++ = *source++; /* ??? to be unrolled */ - } while (--len != 0); -} - -int zmemcmp(s1, s2, len) - const Bytef* s1; - const Bytef* s2; - uInt len; -{ - uInt j; - - for (j = 0; j < len; j++) { - if (s1[j] != s2[j]) return 2*(s1[j] > s2[j])-1; - } - return 0; -} - -void zmemzero(dest, len) - Bytef* dest; - uInt len; -{ - if (len == 0) return; - do { - *dest++ = 0; /* ??? to be unrolled */ - } while (--len != 0); -} -#endif - - -#ifdef SYS16BIT - -#ifdef __TURBOC__ -/* Turbo C in 16-bit mode */ - -# define MY_ZCALLOC - -/* Turbo C malloc() does not allow dynamic allocation of 64K bytes - * and farmalloc(64K) returns a pointer with an offset of 8, so we - * must fix the pointer. Warning: the pointer must be put back to its - * original form in order to free it, use zcfree(). - */ - -#define MAX_PTR 10 -/* 10*64K = 640K */ - -local int next_ptr = 0; - -typedef struct ptr_table_s { - voidpf org_ptr; - voidpf new_ptr; -} ptr_table; - -local ptr_table table[MAX_PTR]; -/* This table is used to remember the original form of pointers - * to large buffers (64K). Such pointers are normalized with a zero offset. - * Since MSDOS is not a preemptive multitasking OS, this table is not - * protected from concurrent access. This hack doesn't work anyway on - * a protected system like OS/2. Use Microsoft C instead. - */ - -voidpf zcalloc (voidpf opaque, unsigned items, unsigned size) -{ - voidpf buf = opaque; /* just to make some compilers happy */ - ulg bsize = (ulg)items*size; - - /* If we allocate less than 65520 bytes, we assume that farmalloc - * will return a usable pointer which doesn't have to be normalized. - */ - if (bsize < 65520L) { - buf = farmalloc(bsize); - if (*(ush*)&buf != 0) return buf; - } else { - buf = farmalloc(bsize + 16L); - } - if (buf == NULL || next_ptr >= MAX_PTR) return NULL; - table[next_ptr].org_ptr = buf; - - /* Normalize the pointer to seg:0 */ - *((ush*)&buf+1) += ((ush)((uch*)buf-0) + 15) >> 4; - *(ush*)&buf = 0; - table[next_ptr++].new_ptr = buf; - return buf; -} - -void zcfree (voidpf opaque, voidpf ptr) -{ - int n; - if (*(ush*)&ptr != 0) { /* object < 64K */ - farfree(ptr); - return; - } - /* Find the original pointer */ - for (n = 0; n < next_ptr; n++) { - if (ptr != table[n].new_ptr) continue; - - farfree(table[n].org_ptr); - while (++n < next_ptr) { - table[n-1] = table[n]; - } - next_ptr--; - return; - } - ptr = opaque; /* just to make some compilers happy */ - Assert(0, "zcfree: ptr not found"); -} - -#endif /* __TURBOC__ */ - - -#ifdef M_I86 -/* Microsoft C in 16-bit mode */ - -# define MY_ZCALLOC - -#if (!defined(_MSC_VER) || (_MSC_VER <= 600)) -# define _halloc halloc -# define _hfree hfree -#endif - -voidpf zcalloc (voidpf opaque, unsigned items, unsigned size) -{ - if (opaque) opaque = 0; /* to make compiler happy */ - return _halloc((long)items, size); -} - -void zcfree (voidpf opaque, voidpf ptr) -{ - if (opaque) opaque = 0; /* to make compiler happy */ - _hfree(ptr); -} - -#endif /* M_I86 */ - -#endif /* SYS16BIT */ - - -#ifndef MY_ZCALLOC /* Any system without a special alloc function */ - -#ifndef STDC -extern voidp malloc OF((uInt size)); -extern voidp calloc OF((uInt items, uInt size)); -extern void free OF((voidpf ptr)); -#endif - -voidpf zcalloc (opaque, items, size) - voidpf opaque; - unsigned items; - unsigned size; -{ - if (opaque) items += size - size; /* make compiler happy */ - return sizeof(uInt) > 2 ? (voidpf)malloc(items * size) : - (voidpf)calloc(items, size); -} - -void zcfree (opaque, ptr) - voidpf opaque; - voidpf ptr; -{ - free(ptr); - if (opaque) return; /* make compiler happy */ -} - -#endif /* MY_ZCALLOC */ +/* zutil.c -- target dependent utility functions for the compression library + * Copyright (C) 1995-2005 Jean-loup Gailly. + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* @(#) $Id$ */ + +#include "zutil.h" + +#ifndef NO_DUMMY_DECL +struct internal_state {int dummy;}; /* for buggy compilers */ +#endif + +const char * const z_errmsg[10] = { +"need dictionary", /* Z_NEED_DICT 2 */ +"stream end", /* Z_STREAM_END 1 */ +"", /* Z_OK 0 */ +"file error", /* Z_ERRNO (-1) */ +"stream error", /* Z_STREAM_ERROR (-2) */ +"data error", /* Z_DATA_ERROR (-3) */ +"insufficient memory", /* Z_MEM_ERROR (-4) */ +"buffer error", /* Z_BUF_ERROR (-5) */ +"incompatible version",/* Z_VERSION_ERROR (-6) */ +""}; + + +const char * ZEXPORT zlibVersion() +{ + return ZLIB_VERSION; +} + +uLong ZEXPORT zlibCompileFlags() +{ + uLong flags; + + flags = 0; + switch (sizeof(uInt)) { + case 2: break; + case 4: flags += 1; break; + case 8: flags += 2; break; + default: flags += 3; + } + switch (sizeof(uLong)) { + case 2: break; + case 4: flags += 1 << 2; break; + case 8: flags += 2 << 2; break; + default: flags += 3 << 2; + } + switch (sizeof(voidpf)) { + case 2: break; + case 4: flags += 1 << 4; break; + case 8: flags += 2 << 4; break; + default: flags += 3 << 4; + } + switch (sizeof(z_off_t)) { + case 2: break; + case 4: flags += 1 << 6; break; + case 8: flags += 2 << 6; break; + default: flags += 3 << 6; + } +#ifdef DEBUG + flags += 1 << 8; +#endif +#if defined(ASMV) || defined(ASMINF) + flags += 1 << 9; +#endif +#ifdef ZLIB_WINAPI + flags += 1 << 10; +#endif +#ifdef BUILDFIXED + flags += 1 << 12; +#endif +#ifdef DYNAMIC_CRC_TABLE + flags += 1 << 13; +#endif +#ifdef NO_GZCOMPRESS + flags += 1L << 16; +#endif +#ifdef NO_GZIP + flags += 1L << 17; +#endif +#ifdef PKZIP_BUG_WORKAROUND + flags += 1L << 20; +#endif +#ifdef FASTEST + flags += 1L << 21; +#endif +#ifdef STDC +# ifdef NO_vsnprintf + flags += 1L << 25; +# ifdef HAS_vsprintf_void + flags += 1L << 26; +# endif +# else +# ifdef HAS_vsnprintf_void + flags += 1L << 26; +# endif +# endif +#else + flags += 1L << 24; +# ifdef NO_snprintf + flags += 1L << 25; +# ifdef HAS_sprintf_void + flags += 1L << 26; +# endif +# else +# ifdef HAS_snprintf_void + flags += 1L << 26; +# endif +# endif +#endif + return flags; +} + +#ifdef DEBUG + +# ifndef verbose +# define verbose 0 +# endif +int z_verbose = verbose; + +void z_error (m) + char *m; +{ + fprintf(stderr, "%s\n", m); + exit(1); +} +#endif + +/* exported to allow conversion of error code to string for compress() and + * uncompress() + */ +const char * ZEXPORT zError(err) + int err; +{ + return ERR_MSG(err); +} + +#if defined(_WIN32_WCE) + /* The Microsoft C Run-Time Library for Windows CE doesn't have + * errno. We define it as a global variable to simplify porting. + * Its value is always 0 and should not be used. + */ + int errno = 0; +#endif + +#ifndef HAVE_MEMCPY + +void zmemcpy(dest, source, len) + Bytef* dest; + const Bytef* source; + uInt len; +{ + if (len == 0) return; + do { + *dest++ = *source++; /* ??? to be unrolled */ + } while (--len != 0); +} + +int zmemcmp(s1, s2, len) + const Bytef* s1; + const Bytef* s2; + uInt len; +{ + uInt j; + + for (j = 0; j < len; j++) { + if (s1[j] != s2[j]) return 2*(s1[j] > s2[j])-1; + } + return 0; +} + +void zmemzero(dest, len) + Bytef* dest; + uInt len; +{ + if (len == 0) return; + do { + *dest++ = 0; /* ??? to be unrolled */ + } while (--len != 0); +} +#endif + + +#ifdef SYS16BIT + +#ifdef __TURBOC__ +/* Turbo C in 16-bit mode */ + +# define MY_ZCALLOC + +/* Turbo C malloc() does not allow dynamic allocation of 64K bytes + * and farmalloc(64K) returns a pointer with an offset of 8, so we + * must fix the pointer. Warning: the pointer must be put back to its + * original form in order to free it, use zcfree(). + */ + +#define MAX_PTR 10 +/* 10*64K = 640K */ + +local int next_ptr = 0; + +typedef struct ptr_table_s { + voidpf org_ptr; + voidpf new_ptr; +} ptr_table; + +local ptr_table table[MAX_PTR]; +/* This table is used to remember the original form of pointers + * to large buffers (64K). Such pointers are normalized with a zero offset. + * Since MSDOS is not a preemptive multitasking OS, this table is not + * protected from concurrent access. This hack doesn't work anyway on + * a protected system like OS/2. Use Microsoft C instead. + */ + +voidpf zcalloc (voidpf opaque, unsigned items, unsigned size) +{ + voidpf buf = opaque; /* just to make some compilers happy */ + ulg bsize = (ulg)items*size; + + /* If we allocate less than 65520 bytes, we assume that farmalloc + * will return a usable pointer which doesn't have to be normalized. + */ + if (bsize < 65520L) { + buf = farmalloc(bsize); + if (*(ush*)&buf != 0) return buf; + } else { + buf = farmalloc(bsize + 16L); + } + if (buf == NULL || next_ptr >= MAX_PTR) return NULL; + table[next_ptr].org_ptr = buf; + + /* Normalize the pointer to seg:0 */ + *((ush*)&buf+1) += ((ush)((uch*)buf-0) + 15) >> 4; + *(ush*)&buf = 0; + table[next_ptr++].new_ptr = buf; + return buf; +} + +void zcfree (voidpf opaque, voidpf ptr) +{ + int n; + if (*(ush*)&ptr != 0) { /* object < 64K */ + farfree(ptr); + return; + } + /* Find the original pointer */ + for (n = 0; n < next_ptr; n++) { + if (ptr != table[n].new_ptr) continue; + + farfree(table[n].org_ptr); + while (++n < next_ptr) { + table[n-1] = table[n]; + } + next_ptr--; + return; + } + ptr = opaque; /* just to make some compilers happy */ + Assert(0, "zcfree: ptr not found"); +} + +#endif /* __TURBOC__ */ + + +#ifdef M_I86 +/* Microsoft C in 16-bit mode */ + +# define MY_ZCALLOC + +#if (!defined(_MSC_VER) || (_MSC_VER <= 600)) +# define _halloc halloc +# define _hfree hfree +#endif + +voidpf zcalloc (voidpf opaque, unsigned items, unsigned size) +{ + if (opaque) opaque = 0; /* to make compiler happy */ + return _halloc((long)items, size); +} + +void zcfree (voidpf opaque, voidpf ptr) +{ + if (opaque) opaque = 0; /* to make compiler happy */ + _hfree(ptr); +} + +#endif /* M_I86 */ + +#endif /* SYS16BIT */ + + +#ifndef MY_ZCALLOC /* Any system without a special alloc function */ + +#ifndef STDC +extern voidp malloc OF((uInt size)); +extern voidp calloc OF((uInt items, uInt size)); +extern void free OF((voidpf ptr)); +#endif + +voidpf zcalloc (opaque, items, size) + voidpf opaque; + unsigned items; + unsigned size; +{ + if (opaque) items += size - size; /* make compiler happy */ + return sizeof(uInt) > 2 ? (voidpf)malloc(items * size) : + (voidpf)calloc(items, size); +} + +void zcfree (opaque, ptr) + voidpf opaque; + voidpf ptr; +{ + free(ptr); + if (opaque) return; /* make compiler happy */ +} + +#endif /* MY_ZCALLOC */ diff --git a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zutil.h b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zutil.h index 0ba6e0208..b7d5eff81 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zutil.h +++ b/ground/openpilotgcs/src/libs/glc_lib/3rdparty/zlib/zutil.h @@ -1,269 +1,269 @@ -/* zutil.h -- internal interface and configuration of the compression library - * Copyright (C) 1995-2005 Jean-loup Gailly. - * For conditions of distribution and use, see copyright notice in zlib.h - */ - -/* WARNING: this file should *not* be used by applications. It is - part of the implementation of the compression library and is - subject to change. Applications should only use zlib.h. - */ - -/* @(#) $Id$ */ - -#ifndef ZUTIL_H -#define ZUTIL_H - -#define ZLIB_INTERNAL -#include "zlib.h" - -#ifdef STDC -# ifndef _WIN32_WCE -# include -# endif -# include -# include -#endif -#ifdef NO_ERRNO_H -# ifdef _WIN32_WCE - /* The Microsoft C Run-Time Library for Windows CE doesn't have - * errno. We define it as a global variable to simplify porting. - * Its value is always 0 and should not be used. We rename it to - * avoid conflict with other libraries that use the same workaround. - */ -# define errno z_errno -# endif - extern int errno; -#else -# ifndef _WIN32_WCE -# include -# endif -#endif - -#ifndef local -# define local static -#endif -/* compile with -Dlocal if your debugger can't find static symbols */ - -typedef unsigned char uch; -typedef uch FAR uchf; -typedef unsigned short ush; -typedef ush FAR ushf; -typedef unsigned long ulg; - -extern const char * const z_errmsg[10]; /* indexed by 2-zlib_error */ -/* (size given to avoid silly warnings with Visual C++) */ - -#define ERR_MSG(err) z_errmsg[Z_NEED_DICT-(err)] - -#define ERR_RETURN(strm,err) \ - return (strm->msg = (char*)ERR_MSG(err), (err)) -/* To be used only when the state is known to be valid */ - - /* common constants */ - -#ifndef DEF_WBITS -# define DEF_WBITS MAX_WBITS -#endif -/* default windowBits for decompression. MAX_WBITS is for compression only */ - -#if MAX_MEM_LEVEL >= 8 -# define DEF_MEM_LEVEL 8 -#else -# define DEF_MEM_LEVEL MAX_MEM_LEVEL -#endif -/* default memLevel */ - -#define STORED_BLOCK 0 -#define STATIC_TREES 1 -#define DYN_TREES 2 -/* The three kinds of block type */ - -#define MIN_MATCH 3 -#define MAX_MATCH 258 -/* The minimum and maximum match lengths */ - -#define PRESET_DICT 0x20 /* preset dictionary flag in zlib header */ - - /* target dependencies */ - -#if defined(MSDOS) || (defined(WINDOWS) && !defined(WIN32)) -# define OS_CODE 0x00 -# if defined(__TURBOC__) || defined(__BORLANDC__) -# if(__STDC__ == 1) && (defined(__LARGE__) || defined(__COMPACT__)) - /* Allow compilation with ANSI keywords only enabled */ - void _Cdecl farfree( void *block ); - void *_Cdecl farmalloc( unsigned long nbytes ); -# else -# include -# endif -# else /* MSC or DJGPP */ -# include -# endif -#endif - -#ifdef AMIGA -# define OS_CODE 0x01 -#endif - -#if defined(VAXC) || defined(VMS) -# define OS_CODE 0x02 -# define F_OPEN(name, mode) \ - fopen((name), (mode), "mbc=60", "ctx=stm", "rfm=fix", "mrs=512") -#endif - -#if defined(ATARI) || defined(atarist) -# define OS_CODE 0x05 -#endif - -#ifdef OS2 -# define OS_CODE 0x06 -# ifdef M_I86 - #include -# endif -#endif - -#if defined(MACOS) || defined(TARGET_OS_MAC) -# define OS_CODE 0x07 -# if defined(__MWERKS__) && __dest_os != __be_os && __dest_os != __win32_os -# include /* for fdopen */ -# else -# ifndef fdopen -# define fdopen(fd,mode) NULL /* No fdopen() */ -# endif -# endif -#endif - -#ifdef TOPS20 -# define OS_CODE 0x0a -#endif - -#ifdef WIN32 -# ifndef __CYGWIN__ /* Cygwin is Unix, not Win32 */ -# define OS_CODE 0x0b -# endif -#endif - -#ifdef __50SERIES /* Prime/PRIMOS */ -# define OS_CODE 0x0f -#endif - -#if defined(_BEOS_) || defined(RISCOS) -# define fdopen(fd,mode) NULL /* No fdopen() */ -#endif - -#if (defined(_MSC_VER) && (_MSC_VER > 600)) -# if defined(_WIN32_WCE) -# define fdopen(fd,mode) NULL /* No fdopen() */ -# ifndef _PTRDIFF_T_DEFINED - typedef int ptrdiff_t; -# define _PTRDIFF_T_DEFINED -# endif -# else -# define fdopen(fd,type) _fdopen(fd,type) -# endif -#endif - - /* common defaults */ - -#ifndef OS_CODE -# define OS_CODE 0x03 /* assume Unix */ -#endif - -#ifndef F_OPEN -# define F_OPEN(name, mode) fopen((name), (mode)) -#endif - - /* functions */ - -#if defined(STDC99) || (defined(__TURBOC__) && __TURBOC__ >= 0x550) -# ifndef HAVE_VSNPRINTF -# define HAVE_VSNPRINTF -# endif -#endif -#if defined(__CYGWIN__) -# ifndef HAVE_VSNPRINTF -# define HAVE_VSNPRINTF -# endif -#endif -#ifndef HAVE_VSNPRINTF -# ifdef MSDOS - /* vsnprintf may exist on some MS-DOS compilers (DJGPP?), - but for now we just assume it doesn't. */ -# define NO_vsnprintf -# endif -# ifdef __TURBOC__ -# define NO_vsnprintf -# endif -# ifdef WIN32 - /* In Win32, vsnprintf is available as the "non-ANSI" _vsnprintf. */ -# if !defined(vsnprintf) && !defined(NO_vsnprintf) -# define vsnprintf _vsnprintf -# endif -# endif -# ifdef __SASC -# define NO_vsnprintf -# endif -#endif -#ifdef VMS -# define NO_vsnprintf -#endif - -#if defined(pyr) -# define NO_MEMCPY -#endif -#if defined(SMALL_MEDIUM) && !defined(_MSC_VER) && !defined(__SC__) - /* Use our own functions for small and medium model with MSC <= 5.0. - * You may have to use the same strategy for Borland C (untested). - * The __SC__ check is for Symantec. - */ -# define NO_MEMCPY -#endif -#if defined(STDC) && !defined(HAVE_MEMCPY) && !defined(NO_MEMCPY) -# define HAVE_MEMCPY -#endif -#ifdef HAVE_MEMCPY -# ifdef SMALL_MEDIUM /* MSDOS small or medium model */ -# define zmemcpy _fmemcpy -# define zmemcmp _fmemcmp -# define zmemzero(dest, len) _fmemset(dest, 0, len) -# else -# define zmemcpy memcpy -# define zmemcmp memcmp -# define zmemzero(dest, len) memset(dest, 0, len) -# endif -#else - extern void zmemcpy OF((Bytef* dest, const Bytef* source, uInt len)); - extern int zmemcmp OF((const Bytef* s1, const Bytef* s2, uInt len)); - extern void zmemzero OF((Bytef* dest, uInt len)); -#endif - -/* Diagnostic functions */ -#ifdef DEBUG -# include - extern int z_verbose; - extern void z_error OF((char *m)); -# define Assert(cond,msg) {if(!(cond)) z_error(msg);} -# define Trace(x) {if (z_verbose>=0) fprintf x ;} -# define Tracev(x) {if (z_verbose>0) fprintf x ;} -# define Tracevv(x) {if (z_verbose>1) fprintf x ;} -# define Tracec(c,x) {if (z_verbose>0 && (c)) fprintf x ;} -# define Tracecv(c,x) {if (z_verbose>1 && (c)) fprintf x ;} -#else -# define Assert(cond,msg) -# define Trace(x) -# define Tracev(x) -# define Tracevv(x) -# define Tracec(c,x) -# define Tracecv(c,x) -#endif - - -voidpf zcalloc OF((voidpf opaque, unsigned items, unsigned size)); -void zcfree OF((voidpf opaque, voidpf ptr)); - -#define ZALLOC(strm, items, size) \ - (*((strm)->zalloc))((strm)->opaque, (items), (size)) -#define ZFREE(strm, addr) (*((strm)->zfree))((strm)->opaque, (voidpf)(addr)) -#define TRY_FREE(s, p) {if (p) ZFREE(s, p);} - -#endif /* ZUTIL_H */ +/* zutil.h -- internal interface and configuration of the compression library + * Copyright (C) 1995-2005 Jean-loup Gailly. + * For conditions of distribution and use, see copyright notice in zlib.h + */ + +/* WARNING: this file should *not* be used by applications. It is + part of the implementation of the compression library and is + subject to change. Applications should only use zlib.h. + */ + +/* @(#) $Id$ */ + +#ifndef ZUTIL_H +#define ZUTIL_H + +#define ZLIB_INTERNAL +#include "zlib.h" + +#ifdef STDC +# ifndef _WIN32_WCE +# include +# endif +# include +# include +#endif +#ifdef NO_ERRNO_H +# ifdef _WIN32_WCE + /* The Microsoft C Run-Time Library for Windows CE doesn't have + * errno. We define it as a global variable to simplify porting. + * Its value is always 0 and should not be used. We rename it to + * avoid conflict with other libraries that use the same workaround. + */ +# define errno z_errno +# endif + extern int errno; +#else +# ifndef _WIN32_WCE +# include +# endif +#endif + +#ifndef local +# define local static +#endif +/* compile with -Dlocal if your debugger can't find static symbols */ + +typedef unsigned char uch; +typedef uch FAR uchf; +typedef unsigned short ush; +typedef ush FAR ushf; +typedef unsigned long ulg; + +extern const char * const z_errmsg[10]; /* indexed by 2-zlib_error */ +/* (size given to avoid silly warnings with Visual C++) */ + +#define ERR_MSG(err) z_errmsg[Z_NEED_DICT-(err)] + +#define ERR_RETURN(strm,err) \ + return (strm->msg = (char*)ERR_MSG(err), (err)) +/* To be used only when the state is known to be valid */ + + /* common constants */ + +#ifndef DEF_WBITS +# define DEF_WBITS MAX_WBITS +#endif +/* default windowBits for decompression. MAX_WBITS is for compression only */ + +#if MAX_MEM_LEVEL >= 8 +# define DEF_MEM_LEVEL 8 +#else +# define DEF_MEM_LEVEL MAX_MEM_LEVEL +#endif +/* default memLevel */ + +#define STORED_BLOCK 0 +#define STATIC_TREES 1 +#define DYN_TREES 2 +/* The three kinds of block type */ + +#define MIN_MATCH 3 +#define MAX_MATCH 258 +/* The minimum and maximum match lengths */ + +#define PRESET_DICT 0x20 /* preset dictionary flag in zlib header */ + + /* target dependencies */ + +#if defined(MSDOS) || (defined(WINDOWS) && !defined(WIN32)) +# define OS_CODE 0x00 +# if defined(__TURBOC__) || defined(__BORLANDC__) +# if(__STDC__ == 1) && (defined(__LARGE__) || defined(__COMPACT__)) + /* Allow compilation with ANSI keywords only enabled */ + void _Cdecl farfree( void *block ); + void *_Cdecl farmalloc( unsigned long nbytes ); +# else +# include +# endif +# else /* MSC or DJGPP */ +# include +# endif +#endif + +#ifdef AMIGA +# define OS_CODE 0x01 +#endif + +#if defined(VAXC) || defined(VMS) +# define OS_CODE 0x02 +# define F_OPEN(name, mode) \ + fopen((name), (mode), "mbc=60", "ctx=stm", "rfm=fix", "mrs=512") +#endif + +#if defined(ATARI) || defined(atarist) +# define OS_CODE 0x05 +#endif + +#ifdef OS2 +# define OS_CODE 0x06 +# ifdef M_I86 + #include +# endif +#endif + +#if defined(MACOS) || defined(TARGET_OS_MAC) +# define OS_CODE 0x07 +# if defined(__MWERKS__) && __dest_os != __be_os && __dest_os != __win32_os +# include /* for fdopen */ +# else +# ifndef fdopen +# define fdopen(fd,mode) NULL /* No fdopen() */ +# endif +# endif +#endif + +#ifdef TOPS20 +# define OS_CODE 0x0a +#endif + +#ifdef WIN32 +# ifndef __CYGWIN__ /* Cygwin is Unix, not Win32 */ +# define OS_CODE 0x0b +# endif +#endif + +#ifdef __50SERIES /* Prime/PRIMOS */ +# define OS_CODE 0x0f +#endif + +#if defined(_BEOS_) || defined(RISCOS) +# define fdopen(fd,mode) NULL /* No fdopen() */ +#endif + +#if (defined(_MSC_VER) && (_MSC_VER > 600)) +# if defined(_WIN32_WCE) +# define fdopen(fd,mode) NULL /* No fdopen() */ +# ifndef _PTRDIFF_T_DEFINED + typedef int ptrdiff_t; +# define _PTRDIFF_T_DEFINED +# endif +# else +# define fdopen(fd,type) _fdopen(fd,type) +# endif +#endif + + /* common defaults */ + +#ifndef OS_CODE +# define OS_CODE 0x03 /* assume Unix */ +#endif + +#ifndef F_OPEN +# define F_OPEN(name, mode) fopen((name), (mode)) +#endif + + /* functions */ + +#if defined(STDC99) || (defined(__TURBOC__) && __TURBOC__ >= 0x550) +# ifndef HAVE_VSNPRINTF +# define HAVE_VSNPRINTF +# endif +#endif +#if defined(__CYGWIN__) +# ifndef HAVE_VSNPRINTF +# define HAVE_VSNPRINTF +# endif +#endif +#ifndef HAVE_VSNPRINTF +# ifdef MSDOS + /* vsnprintf may exist on some MS-DOS compilers (DJGPP?), + but for now we just assume it doesn't. */ +# define NO_vsnprintf +# endif +# ifdef __TURBOC__ +# define NO_vsnprintf +# endif +# ifdef WIN32 + /* In Win32, vsnprintf is available as the "non-ANSI" _vsnprintf. */ +# if !defined(vsnprintf) && !defined(NO_vsnprintf) +# define vsnprintf _vsnprintf +# endif +# endif +# ifdef __SASC +# define NO_vsnprintf +# endif +#endif +#ifdef VMS +# define NO_vsnprintf +#endif + +#if defined(pyr) +# define NO_MEMCPY +#endif +#if defined(SMALL_MEDIUM) && !defined(_MSC_VER) && !defined(__SC__) + /* Use our own functions for small and medium model with MSC <= 5.0. + * You may have to use the same strategy for Borland C (untested). + * The __SC__ check is for Symantec. + */ +# define NO_MEMCPY +#endif +#if defined(STDC) && !defined(HAVE_MEMCPY) && !defined(NO_MEMCPY) +# define HAVE_MEMCPY +#endif +#ifdef HAVE_MEMCPY +# ifdef SMALL_MEDIUM /* MSDOS small or medium model */ +# define zmemcpy _fmemcpy +# define zmemcmp _fmemcmp +# define zmemzero(dest, len) _fmemset(dest, 0, len) +# else +# define zmemcpy memcpy +# define zmemcmp memcmp +# define zmemzero(dest, len) memset(dest, 0, len) +# endif +#else + extern void zmemcpy OF((Bytef* dest, const Bytef* source, uInt len)); + extern int zmemcmp OF((const Bytef* s1, const Bytef* s2, uInt len)); + extern void zmemzero OF((Bytef* dest, uInt len)); +#endif + +/* Diagnostic functions */ +#ifdef DEBUG +# include + extern int z_verbose; + extern void z_error OF((char *m)); +# define Assert(cond,msg) {if(!(cond)) z_error(msg);} +# define Trace(x) {if (z_verbose>=0) fprintf x ;} +# define Tracev(x) {if (z_verbose>0) fprintf x ;} +# define Tracevv(x) {if (z_verbose>1) fprintf x ;} +# define Tracec(c,x) {if (z_verbose>0 && (c)) fprintf x ;} +# define Tracecv(c,x) {if (z_verbose>1 && (c)) fprintf x ;} +#else +# define Assert(cond,msg) +# define Trace(x) +# define Tracev(x) +# define Tracevv(x) +# define Tracec(c,x) +# define Tracecv(c,x) +#endif + + +voidpf zcalloc OF((voidpf opaque, unsigned items, unsigned size)); +void zcfree OF((voidpf opaque, voidpf ptr)); + +#define ZALLOC(strm, items, size) \ + (*((strm)->zalloc))((strm)->opaque, (items), (size)) +#define ZFREE(strm, addr) (*((strm)->zfree))((strm)->opaque, (voidpf)(addr)) +#define TRY_FREE(s, p) {if (p) ZFREE(s, p);} + +#endif /* ZUTIL_H */ diff --git a/ground/openpilotgcs/src/libs/glc_lib/glc_config.h b/ground/openpilotgcs/src/libs/glc_lib/glc_config.h index 3fd0eabd8..45646d152 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/glc_config.h +++ b/ground/openpilotgcs/src/libs/glc_lib/glc_config.h @@ -1,44 +1,44 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ - -//! \file glc_config.h the GLC_lib configuration file - -#ifndef GLC_CONFIG_H -#define GLC_CONFIG_H - -#include - -// Dynamic library export macros -#ifndef GLC_LIB_STATIC -# ifdef CREATE_GLC_LIB_DLL -# define GLC_LIB_EXPORT Q_DECL_EXPORT -# else -# define GLC_LIB_EXPORT Q_DECL_IMPORT -# endif -#endif - -// For static library, this macro is empty -#ifndef GLC_LIB_EXPORT -# define GLC_LIB_EXPORT -#endif - -#endif // GLC_CONFIG_H +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ + +//! \file glc_config.h the GLC_lib configuration file + +#ifndef GLC_CONFIG_H +#define GLC_CONFIG_H + +#include + +// Dynamic library export macros +#ifndef GLC_LIB_STATIC +# ifdef CREATE_GLC_LIB_DLL +# define GLC_LIB_EXPORT Q_DECL_EXPORT +# else +# define GLC_LIB_EXPORT Q_DECL_IMPORT +# endif +#endif + +// For static library, this macro is empty +#ifndef GLC_LIB_EXPORT +# define GLC_LIB_EXPORT +#endif + +#endif // GLC_CONFIG_H diff --git a/ground/openpilotgcs/src/libs/glc_lib/glc_fileformatexception.cpp b/ground/openpilotgcs/src/libs/glc_lib/glc_fileformatexception.cpp index 12dc0b408..41ad0d65b 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/glc_fileformatexception.cpp +++ b/ground/openpilotgcs/src/libs/glc_lib/glc_fileformatexception.cpp @@ -1,51 +1,51 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ - -//! \file glc_fileformatexception.cpp implementation of the GLC_FileFormatException class. - -#include "glc_fileformatexception.h" - -GLC_FileFormatException::GLC_FileFormatException(const QString &message, const QString &fileName, ExceptionType exceptionType) -: GLC_Exception(message) -, m_FileName(fileName) -, m_ExceptionType(exceptionType) -{ - -} - -GLC_FileFormatException::~GLC_FileFormatException() throw() -{ -} - -////////////////////////////////////////////////////////////////////// -// Get Functions -////////////////////////////////////////////////////////////////////// - -// Return exception description -const char* GLC_FileFormatException::what() const throw() -{ - QString exceptionmsg("GLC_FileFormatException : "); - exceptionmsg.append(m_ErrorDescription); - exceptionmsg.append(" in file : "); - exceptionmsg.append(m_FileName); - return exceptionmsg.toAscii().data(); -} +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ + +//! \file glc_fileformatexception.cpp implementation of the GLC_FileFormatException class. + +#include "glc_fileformatexception.h" + +GLC_FileFormatException::GLC_FileFormatException(const QString &message, const QString &fileName, ExceptionType exceptionType) +: GLC_Exception(message) +, m_FileName(fileName) +, m_ExceptionType(exceptionType) +{ + +} + +GLC_FileFormatException::~GLC_FileFormatException() throw() +{ +} + +////////////////////////////////////////////////////////////////////// +// Get Functions +////////////////////////////////////////////////////////////////////// + +// Return exception description +const char* GLC_FileFormatException::what() const throw() +{ + QString exceptionmsg("GLC_FileFormatException : "); + exceptionmsg.append(m_ErrorDescription); + exceptionmsg.append(" in file : "); + exceptionmsg.append(m_FileName); + return exceptionmsg.toAscii().data(); +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/glc_fileformatexception.h b/ground/openpilotgcs/src/libs/glc_lib/glc_fileformatexception.h index 860b32db1..944b1b886 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/glc_fileformatexception.h +++ b/ground/openpilotgcs/src/libs/glc_lib/glc_fileformatexception.h @@ -1,77 +1,77 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ - -//! \file glc_fileformatexception.h Interface for the GLC_FileFormatException class. - -#ifndef GLC_FILEFORMATEXCEPTION_H_ -#define GLC_FILEFORMATEXCEPTION_H_ -#include "glc_exception.h" - -#include "glc_config.h" - -////////////////////////////////////////////////////////////////////// -//! \class GLC_FileFormatException -/*! \brief GLC_FileFormatException : Class for all File Format ERROR - */ -////////////////////////////////////////////////////////////////////// -class GLC_LIB_EXPORT GLC_FileFormatException : public GLC_Exception -{ -public: - //! Enum of exception Type - enum ExceptionType - { - FileNotFound= 1, - FileNotSupported, - WrongFileFormat, - NoMeshFound - }; - - GLC_FileFormatException(const QString&, const QString&, ExceptionType); - virtual ~GLC_FileFormatException() throw(); - -////////////////////////////////////////////////////////////////////// -/*! \name Get Functions*/ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Return exception description - virtual const char* what() const throw(); - - //! Return exception type - inline ExceptionType exceptionType() const - {return m_ExceptionType;} - -//@} -////////////////////////////////////////////////////////////////////// -// private members -////////////////////////////////////////////////////////////////////// -private: - - //! The name of the file - QString m_FileName; - - //! The Exception type - ExceptionType m_ExceptionType; - -}; - -#endif /*GLC_FILEFORMATEXCEPTION_H_*/ +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ + +//! \file glc_fileformatexception.h Interface for the GLC_FileFormatException class. + +#ifndef GLC_FILEFORMATEXCEPTION_H_ +#define GLC_FILEFORMATEXCEPTION_H_ +#include "glc_exception.h" + +#include "glc_config.h" + +////////////////////////////////////////////////////////////////////// +//! \class GLC_FileFormatException +/*! \brief GLC_FileFormatException : Class for all File Format ERROR + */ +////////////////////////////////////////////////////////////////////// +class GLC_LIB_EXPORT GLC_FileFormatException : public GLC_Exception +{ +public: + //! Enum of exception Type + enum ExceptionType + { + FileNotFound= 1, + FileNotSupported, + WrongFileFormat, + NoMeshFound + }; + + GLC_FileFormatException(const QString&, const QString&, ExceptionType); + virtual ~GLC_FileFormatException() throw(); + +////////////////////////////////////////////////////////////////////// +/*! \name Get Functions*/ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Return exception description + virtual const char* what() const throw(); + + //! Return exception type + inline ExceptionType exceptionType() const + {return m_ExceptionType;} + +//@} +////////////////////////////////////////////////////////////////////// +// private members +////////////////////////////////////////////////////////////////////// +private: + + //! The name of the file + QString m_FileName; + + //! The Exception type + ExceptionType m_ExceptionType; + +}; + +#endif /*GLC_FILEFORMATEXCEPTION_H_*/ diff --git a/ground/openpilotgcs/src/libs/glc_lib/io/glc_objmtlloader.cpp b/ground/openpilotgcs/src/libs/glc_lib/io/glc_objmtlloader.cpp index 7a3ae5cda..894e5441f 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/io/glc_objmtlloader.cpp +++ b/ground/openpilotgcs/src/libs/glc_lib/io/glc_objmtlloader.cpp @@ -1,395 +1,395 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - Version 2.0.0, packaged on July 2010. - - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ - -//! \file glc_objmtlloader.cpp implementation of the GLC_ObjMtlLoader class. - -#include "glc_objmtlloader.h" -#include "../glc_fileformatexception.h" -#include -#include -#include -#include -#include - -GLC_ObjMtlLoader::GLC_ObjMtlLoader(const QString& fileName) -: m_FileName(fileName) -, m_pCurrentMaterial(NULL) -, m_Materials() -, m_LoadStatus() -, m_ListOfAttachedFileName() -{ -} - -GLC_ObjMtlLoader::~GLC_ObjMtlLoader() -{ - // Remove unused material - QHash::iterator i; - for (i= m_Materials.begin(); i != m_Materials.end(); ++i) - { - if (i.value()->isUnused()) delete i.value(); - } - m_Materials.clear(); - m_ListOfAttachedFileName.clear(); -} -///////////////////////////////////////////////////////////////////// -// Get functions -////////////////////////////////////////////////////////////////////// -// Get a material from is name -GLC_Material* GLC_ObjMtlLoader::material(const QString& materialName) -{ - if (m_Materials.contains(materialName)) - { - return m_Materials[materialName]; - } - else - { - return NULL; - } -} - -///////////////////////////////////////////////////////////////////// -// Set functions -////////////////////////////////////////////////////////////////////// -// Load the materials -bool GLC_ObjMtlLoader::loadMaterials() -{ - - // Create the input file stream - QFile mtlFile(m_FileName); - - if (!mtlFile.open(QIODevice::ReadOnly)) - { - qDebug() << "GLC_ObjMtlLoader::LoadMaterial File " << m_FileName << " doesn't exist"; - return false; - } - else - { - //qDebug() << "GLC_ObjMtlLoader::LoadMaterial OK File " << m_FileName << " exist"; - } - - QTextStream mtlStream(&mtlFile); - - QString lineBuff; - QString header; - - while (!mtlStream.atEnd()) - { - lineBuff= mtlStream.readLine(); - //qDebug() << lineBuff; - QTextStream streamLine(lineBuff.toAscii()); - - if ((streamLine >> header).status() ==QTextStream::Ok) - { - - // Search New material - if (header =="newmtl") - { - //qDebug() << "New material find"; - - if (NULL != m_pCurrentMaterial) - { // It's not the first material - //qDebug() << "Add material : " << m_pCurrentMaterial->name(); - processMayaSpecific(); - m_Materials.insert(m_pCurrentMaterial->name(), m_pCurrentMaterial); - m_pCurrentMaterial= NULL; - } - - m_pCurrentMaterial= new GLC_Material; - if (!extractMaterialName(lineBuff)) return false; - //qDebug() << "New Material " << m_pCurrentMaterial->name(); - - } - else if ((header == "Ka") || (header == "Kd") || (header == "Ks")) // ambiant, diffuse and specular color - { - if (!extractRGBValue(lineBuff)) return false; - } - - else if ((header == "Ns") || (header == "d")) // shiness Or transparency - { - if (!extractOneValue(lineBuff)) return false; - } - else if ((header == "map_Kd") || (header == "map_Ka")) // Texture - { - //qDebug() << "Texture detected"; - extractTextureFileName(lineBuff); - } - - } - } - - if (NULL != m_pCurrentMaterial) - { - //qDebug() << "Add material : " << m_pCurrentMaterial->name(); - m_Materials.insert(m_pCurrentMaterial->name(), m_pCurrentMaterial); - m_pCurrentMaterial= NULL; - } - - mtlFile.close(); - return true; - -} -///////////////////////////////////////////////////////////////////// -// Private services functions -////////////////////////////////////////////////////////////////////// - -// Extract the material name -bool GLC_ObjMtlLoader::extractMaterialName(QString &ligne) -{ - bool result= false; - QTextStream stream(&ligne); - QString valueString; - QString header; - if ((stream >> header >> valueString).status() == QTextStream::Ok) - { - // If There is an space in the string to extracts - QString valueString2; - while ((stream >> valueString2).status() == QTextStream::Ok) - { - valueString.append(" "); - valueString.append(valueString2); - } - m_pCurrentMaterial->setName(valueString); - //qDebug() << "Material name is : " << valueString; - result= true; - } - else - { - m_LoadStatus= "GLC_ObjMtlLoader::extractMaterialName : something is wrong!!"; - result= false; - } - return result; -} -// Extract the texture file name -void GLC_ObjMtlLoader::extractTextureFileName(QString &ligne) -{ - QTextStream stream(&ligne); - QString valueString; - QString header; - if ((stream >> header >> valueString).status() == QTextStream::Ok) - { - // Retrieve the .obj file path - QFileInfo fileInfo(m_FileName); - - QString textureFileName(fileInfo.absolutePath() + QDir::separator()); - // concatenate File Path with texture filename - textureFileName.append(getTextureName(stream, valueString)); - - QFile textureFile(textureFileName); - - if (!textureFile.open(QIODevice::ReadOnly)) - { - QStringList stringList(m_FileName); - stringList.append("Open File : " + textureFileName + " failed"); - GLC_ErrorLog::addError(stringList); - } - else if ((textureFileName.right(3).contains("TGA", Qt::CaseInsensitive))) - { - QStringList stringList(m_FileName); - stringList.append("Image : " + textureFileName + " not suported"); - GLC_ErrorLog::addError(stringList); - } - else - { - m_ListOfAttachedFileName << textureFileName; - // Create the texture and assign it to current material - GLC_Texture *pTexture = new GLC_Texture(textureFile); - m_pCurrentMaterial->setTexture(pTexture); - //qDebug() << "Texture File is : " << valueString; - } - textureFile.close(); - } -} - -// Extract RGB value -bool GLC_ObjMtlLoader::extractRGBValue(QString &ligne) -{ - bool result= false; - QTextStream stream(&ligne); - QString header; - QString rColor, gColor, bColor; - QColor color(Qt::white); - - if ((stream >> header >> rColor >> gColor >> bColor).status() == QTextStream::Ok) - { - bool okr, okg, okb; - color.setRedF(rColor.toDouble(&okr)); - color.setGreenF(gColor.toDouble(&okg)); - color.setBlueF(bColor.toDouble(&okb)); - if (!(okr && okg && okb)) - { - m_LoadStatus= "GLC_ObjMtlLoader::ExtractRGBValue : Wrong format of rgb color value!!"; - qDebug() << m_LoadStatus; - result= false; - } - else - { - color.setAlphaF(1.0); - if (header == "Ka") // Ambiant Color - { - m_pCurrentMaterial->setAmbientColor(color); - //qDebug() << "Ambiant Color : " << color.redF() << " " << color.greenF() << " " << color.blueF(); - result= true; - } - - else if (header == "Kd") // Diffuse Color - { - m_pCurrentMaterial->setDiffuseColor(color); - //qDebug() << "Diffuse Color : " << color.redF() << " " << color.greenF() << " " << color.blueF(); - result= true; - } - - else if (header == "Ks") // Specular Color - { - m_pCurrentMaterial->setSpecularColor(color); - //qDebug() << "Specular Color : " << color.redF() << " " << color.greenF() << " " << color.blueF(); - result= true; - } - - else - { - m_LoadStatus= "GLC_ObjMtlLoader::ExtractRGBValue : something is wrong!!"; - result= false; - } - } - - }else - { - m_LoadStatus= "GLC_ObjMtlLoader::ExtractRGBValue : something is wrong!!"; - qDebug() << m_LoadStatus; - result= false; - } - - return result; - -} - -// Extract One value -bool GLC_ObjMtlLoader::extractOneValue(QString &ligne) -{ - QTextStream stream(&ligne); - QString valueString; - QString header; - GLfloat value; - - if ((stream >> header >> valueString).status() == QTextStream::Ok) - { - if (header == "Ns") // Ambient color - { - bool ok; - value= valueString.toFloat(&ok); - if (!ok) - { - m_LoadStatus= "GLC_ObjMtlLoader::ExtractOneValue : Wrong format of Shiness !"; - qDebug() << m_LoadStatus; - return false; - } - m_pCurrentMaterial->setShininess(value); - return true; - } - else if (header == "d") // Transparancy - { - bool ok; - value= valueString.toFloat(&ok); - if (!ok) - { - m_LoadStatus= "GLC_ObjMtlLoader::ExtractOneValue : Wrong format Transparency!"; - qDebug() << m_LoadStatus; - return false; - } - m_pCurrentMaterial->setOpacity(static_cast(value)); - return true; - } - - else - { - m_LoadStatus= "GLC_ObjMtlLoader::ExtractOneValue : Ambient Color not found!!"; - qDebug() << m_LoadStatus; - return false; - } - } - else - { - m_LoadStatus= "GLC_ObjMtlLoader::ExtractOneValue : something is wrong!!"; - qDebug() << m_LoadStatus; - GLC_FileFormatException fileFormatException(m_LoadStatus, m_FileName, GLC_FileFormatException::WrongFileFormat); - return false; - } - -} - -// Get texture file name without parameters -QString GLC_ObjMtlLoader::getTextureName(QTextStream &inputStream, const QString &input) -{ - QString textureName(input); - int numberOfStringToSkip= 0; - // Check if there is a map parameter and count - if ((input == "-o") || (input == "-s") || (input == "-t")) - { - numberOfStringToSkip= 3; - } - else if (input == "-mm") - { - numberOfStringToSkip= 2; - } - else if ((input == "-blendu") || (input == "-blendv") || (input == "-cc") - || (input == "-clamp") || (input == "-texres")) - { - numberOfStringToSkip= 1; - } - - if (numberOfStringToSkip != 0) - { - // Skip unread map parameters - for (int i= 0; i < numberOfStringToSkip; ++i) - { - inputStream >> textureName; - } - - if ((inputStream >> textureName).status() == QTextStream::Ok) - { - textureName= getTextureName(inputStream, textureName); - } - else - { - m_LoadStatus== "GLC_ObjToMesh2::extractString : Error occur when trying to decode map option"; - GLC_FileFormatException fileFormatException(m_LoadStatus, m_FileName, GLC_FileFormatException::WrongFileFormat); - throw(fileFormatException); - } - } - return textureName; -} -// Process Maya specific obj -void GLC_ObjMtlLoader::processMayaSpecific() -{ - // Test if the current material have a texture - if (m_pCurrentMaterial->hasTexture()) - { - // Test if the diffuse color of material is black - if (m_pCurrentMaterial->diffuseColor() == Qt::black) - { - // Change the material's diffuse color in order to see the texture - m_pCurrentMaterial->setDiffuseColor(Qt::lightGray); - } - } -} +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + Version 2.0.0, packaged on July 2010. + + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ + +//! \file glc_objmtlloader.cpp implementation of the GLC_ObjMtlLoader class. + +#include "glc_objmtlloader.h" +#include "../glc_fileformatexception.h" +#include +#include +#include +#include +#include + +GLC_ObjMtlLoader::GLC_ObjMtlLoader(const QString& fileName) +: m_FileName(fileName) +, m_pCurrentMaterial(NULL) +, m_Materials() +, m_LoadStatus() +, m_ListOfAttachedFileName() +{ +} + +GLC_ObjMtlLoader::~GLC_ObjMtlLoader() +{ + // Remove unused material + QHash::iterator i; + for (i= m_Materials.begin(); i != m_Materials.end(); ++i) + { + if (i.value()->isUnused()) delete i.value(); + } + m_Materials.clear(); + m_ListOfAttachedFileName.clear(); +} +///////////////////////////////////////////////////////////////////// +// Get functions +////////////////////////////////////////////////////////////////////// +// Get a material from is name +GLC_Material* GLC_ObjMtlLoader::material(const QString& materialName) +{ + if (m_Materials.contains(materialName)) + { + return m_Materials[materialName]; + } + else + { + return NULL; + } +} + +///////////////////////////////////////////////////////////////////// +// Set functions +////////////////////////////////////////////////////////////////////// +// Load the materials +bool GLC_ObjMtlLoader::loadMaterials() +{ + + // Create the input file stream + QFile mtlFile(m_FileName); + + if (!mtlFile.open(QIODevice::ReadOnly)) + { + qDebug() << "GLC_ObjMtlLoader::LoadMaterial File " << m_FileName << " doesn't exist"; + return false; + } + else + { + //qDebug() << "GLC_ObjMtlLoader::LoadMaterial OK File " << m_FileName << " exist"; + } + + QTextStream mtlStream(&mtlFile); + + QString lineBuff; + QString header; + + while (!mtlStream.atEnd()) + { + lineBuff= mtlStream.readLine(); + //qDebug() << lineBuff; + QTextStream streamLine(lineBuff.toAscii()); + + if ((streamLine >> header).status() ==QTextStream::Ok) + { + + // Search New material + if (header =="newmtl") + { + //qDebug() << "New material find"; + + if (NULL != m_pCurrentMaterial) + { // It's not the first material + //qDebug() << "Add material : " << m_pCurrentMaterial->name(); + processMayaSpecific(); + m_Materials.insert(m_pCurrentMaterial->name(), m_pCurrentMaterial); + m_pCurrentMaterial= NULL; + } + + m_pCurrentMaterial= new GLC_Material; + if (!extractMaterialName(lineBuff)) return false; + //qDebug() << "New Material " << m_pCurrentMaterial->name(); + + } + else if ((header == "Ka") || (header == "Kd") || (header == "Ks")) // ambiant, diffuse and specular color + { + if (!extractRGBValue(lineBuff)) return false; + } + + else if ((header == "Ns") || (header == "d")) // shiness Or transparency + { + if (!extractOneValue(lineBuff)) return false; + } + else if ((header == "map_Kd") || (header == "map_Ka")) // Texture + { + //qDebug() << "Texture detected"; + extractTextureFileName(lineBuff); + } + + } + } + + if (NULL != m_pCurrentMaterial) + { + //qDebug() << "Add material : " << m_pCurrentMaterial->name(); + m_Materials.insert(m_pCurrentMaterial->name(), m_pCurrentMaterial); + m_pCurrentMaterial= NULL; + } + + mtlFile.close(); + return true; + +} +///////////////////////////////////////////////////////////////////// +// Private services functions +////////////////////////////////////////////////////////////////////// + +// Extract the material name +bool GLC_ObjMtlLoader::extractMaterialName(QString &ligne) +{ + bool result= false; + QTextStream stream(&ligne); + QString valueString; + QString header; + if ((stream >> header >> valueString).status() == QTextStream::Ok) + { + // If There is an space in the string to extracts + QString valueString2; + while ((stream >> valueString2).status() == QTextStream::Ok) + { + valueString.append(" "); + valueString.append(valueString2); + } + m_pCurrentMaterial->setName(valueString); + //qDebug() << "Material name is : " << valueString; + result= true; + } + else + { + m_LoadStatus= "GLC_ObjMtlLoader::extractMaterialName : something is wrong!!"; + result= false; + } + return result; +} +// Extract the texture file name +void GLC_ObjMtlLoader::extractTextureFileName(QString &ligne) +{ + QTextStream stream(&ligne); + QString valueString; + QString header; + if ((stream >> header >> valueString).status() == QTextStream::Ok) + { + // Retrieve the .obj file path + QFileInfo fileInfo(m_FileName); + + QString textureFileName(fileInfo.absolutePath() + QDir::separator()); + // concatenate File Path with texture filename + textureFileName.append(getTextureName(stream, valueString)); + + QFile textureFile(textureFileName); + + if (!textureFile.open(QIODevice::ReadOnly)) + { + QStringList stringList(m_FileName); + stringList.append("Open File : " + textureFileName + " failed"); + GLC_ErrorLog::addError(stringList); + } + else if ((textureFileName.right(3).contains("TGA", Qt::CaseInsensitive))) + { + QStringList stringList(m_FileName); + stringList.append("Image : " + textureFileName + " not suported"); + GLC_ErrorLog::addError(stringList); + } + else + { + m_ListOfAttachedFileName << textureFileName; + // Create the texture and assign it to current material + GLC_Texture *pTexture = new GLC_Texture(textureFile); + m_pCurrentMaterial->setTexture(pTexture); + //qDebug() << "Texture File is : " << valueString; + } + textureFile.close(); + } +} + +// Extract RGB value +bool GLC_ObjMtlLoader::extractRGBValue(QString &ligne) +{ + bool result= false; + QTextStream stream(&ligne); + QString header; + QString rColor, gColor, bColor; + QColor color(Qt::white); + + if ((stream >> header >> rColor >> gColor >> bColor).status() == QTextStream::Ok) + { + bool okr, okg, okb; + color.setRedF(rColor.toDouble(&okr)); + color.setGreenF(gColor.toDouble(&okg)); + color.setBlueF(bColor.toDouble(&okb)); + if (!(okr && okg && okb)) + { + m_LoadStatus= "GLC_ObjMtlLoader::ExtractRGBValue : Wrong format of rgb color value!!"; + qDebug() << m_LoadStatus; + result= false; + } + else + { + color.setAlphaF(1.0); + if (header == "Ka") // Ambiant Color + { + m_pCurrentMaterial->setAmbientColor(color); + //qDebug() << "Ambiant Color : " << color.redF() << " " << color.greenF() << " " << color.blueF(); + result= true; + } + + else if (header == "Kd") // Diffuse Color + { + m_pCurrentMaterial->setDiffuseColor(color); + //qDebug() << "Diffuse Color : " << color.redF() << " " << color.greenF() << " " << color.blueF(); + result= true; + } + + else if (header == "Ks") // Specular Color + { + m_pCurrentMaterial->setSpecularColor(color); + //qDebug() << "Specular Color : " << color.redF() << " " << color.greenF() << " " << color.blueF(); + result= true; + } + + else + { + m_LoadStatus= "GLC_ObjMtlLoader::ExtractRGBValue : something is wrong!!"; + result= false; + } + } + + }else + { + m_LoadStatus= "GLC_ObjMtlLoader::ExtractRGBValue : something is wrong!!"; + qDebug() << m_LoadStatus; + result= false; + } + + return result; + +} + +// Extract One value +bool GLC_ObjMtlLoader::extractOneValue(QString &ligne) +{ + QTextStream stream(&ligne); + QString valueString; + QString header; + GLfloat value; + + if ((stream >> header >> valueString).status() == QTextStream::Ok) + { + if (header == "Ns") // Ambient color + { + bool ok; + value= valueString.toFloat(&ok); + if (!ok) + { + m_LoadStatus= "GLC_ObjMtlLoader::ExtractOneValue : Wrong format of Shiness !"; + qDebug() << m_LoadStatus; + return false; + } + m_pCurrentMaterial->setShininess(value); + return true; + } + else if (header == "d") // Transparancy + { + bool ok; + value= valueString.toFloat(&ok); + if (!ok) + { + m_LoadStatus= "GLC_ObjMtlLoader::ExtractOneValue : Wrong format Transparency!"; + qDebug() << m_LoadStatus; + return false; + } + m_pCurrentMaterial->setOpacity(static_cast(value)); + return true; + } + + else + { + m_LoadStatus= "GLC_ObjMtlLoader::ExtractOneValue : Ambient Color not found!!"; + qDebug() << m_LoadStatus; + return false; + } + } + else + { + m_LoadStatus= "GLC_ObjMtlLoader::ExtractOneValue : something is wrong!!"; + qDebug() << m_LoadStatus; + GLC_FileFormatException fileFormatException(m_LoadStatus, m_FileName, GLC_FileFormatException::WrongFileFormat); + return false; + } + +} + +// Get texture file name without parameters +QString GLC_ObjMtlLoader::getTextureName(QTextStream &inputStream, const QString &input) +{ + QString textureName(input); + int numberOfStringToSkip= 0; + // Check if there is a map parameter and count + if ((input == "-o") || (input == "-s") || (input == "-t")) + { + numberOfStringToSkip= 3; + } + else if (input == "-mm") + { + numberOfStringToSkip= 2; + } + else if ((input == "-blendu") || (input == "-blendv") || (input == "-cc") + || (input == "-clamp") || (input == "-texres")) + { + numberOfStringToSkip= 1; + } + + if (numberOfStringToSkip != 0) + { + // Skip unread map parameters + for (int i= 0; i < numberOfStringToSkip; ++i) + { + inputStream >> textureName; + } + + if ((inputStream >> textureName).status() == QTextStream::Ok) + { + textureName= getTextureName(inputStream, textureName); + } + else + { + m_LoadStatus== "GLC_ObjToMesh2::extractString : Error occur when trying to decode map option"; + GLC_FileFormatException fileFormatException(m_LoadStatus, m_FileName, GLC_FileFormatException::WrongFileFormat); + throw(fileFormatException); + } + } + return textureName; +} +// Process Maya specific obj +void GLC_ObjMtlLoader::processMayaSpecific() +{ + // Test if the current material have a texture + if (m_pCurrentMaterial->hasTexture()) + { + // Test if the diffuse color of material is black + if (m_pCurrentMaterial->diffuseColor() == Qt::black) + { + // Change the material's diffuse color in order to see the texture + m_pCurrentMaterial->setDiffuseColor(Qt::lightGray); + } + } +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/io/glc_objmtlloader.h b/ground/openpilotgcs/src/libs/glc_lib/io/glc_objmtlloader.h index 9c9f34c5d..4700d2f1e 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/io/glc_objmtlloader.h +++ b/ground/openpilotgcs/src/libs/glc_lib/io/glc_objmtlloader.h @@ -1,132 +1,132 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - Version 2.0.0, packaged on July 2010. - - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ - -//! \file glc_objmtlloader.h interface for the GLC_ObjMtlLoader class. - -#ifndef GLC_OBJMTLLOADER_H_ -#define GLC_OBJMTLLOADER_H_ - -#include -#include -#include -#include "../shading/glc_material.h" - -#include "../glc_config.h" - -class QGLContext; -////////////////////////////////////////////////////////////////////// -//! \class GLC_ObjMtlLoader -/*! \brief GLC_ObjMtlLoader : Load the mtl file associated to a OBJ File */ - -/*! An GLC_ObjMtlLoader create GLC_Material from the .mtl file \n - */ -////////////////////////////////////////////////////////////////////// -class GLC_LIB_EXPORT GLC_ObjMtlLoader -{ - -////////////////////////////////////////////////////////////////////// -/*! @name Constructor / Destructor */ -//@{ -////////////////////////////////////////////////////////////////////// -public: - GLC_ObjMtlLoader(const QString&); - - virtual ~GLC_ObjMtlLoader(); -//@} -////////////////////////////////////////////////////////////////////// -/*! \name Get Functions*/ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Return true if the material name is found - inline bool contains(const QString &name) const - {return m_Materials.contains(name);} - - //! Get a material from is name - GLC_Material* material(const QString&); - - //! Get the list of attached files - inline QStringList listOfAttachedFileName() const - {return m_ListOfAttachedFileName.toList();} - -//@} - -////////////////////////////////////////////////////////////////////// -/*! \name Set Functions*/ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Load the materials - bool loadMaterials(); - -//@} -////////////////////////////////////////////////////////////////////// -/*! \name Private services functions*/ -//@{ -////////////////////////////////////////////////////////////////////// -private: - //! Extract the material name - bool extractMaterialName(QString &); - - //! Extract the texture file name - void extractTextureFileName(QString &); - - //! Extract RGB value - bool extractRGBValue(QString &); - - //! Extract One value - bool extractOneValue(QString &); - - //! Get texture file name without parameters - QString getTextureName(QTextStream &, const QString &); - - //! Process Maya specific obj - void processMayaSpecific(); - - -//@} - -////////////////////////////////////////////////////////////////////// -// Private members -////////////////////////////////////////////////////////////////////// -private: - //! The mtl file name - QString m_FileName; - - //! Current material - GLC_Material* m_pCurrentMaterial; - - //! The GLC_Material Hash Table - QHash m_Materials; - - //! the Load status - QString m_LoadStatus; - - //! The list of attached file name - QSet m_ListOfAttachedFileName; - - -}; - -#endif /*GLC_OBJMTLLOADER_H_*/ +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + Version 2.0.0, packaged on July 2010. + + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ + +//! \file glc_objmtlloader.h interface for the GLC_ObjMtlLoader class. + +#ifndef GLC_OBJMTLLOADER_H_ +#define GLC_OBJMTLLOADER_H_ + +#include +#include +#include +#include "../shading/glc_material.h" + +#include "../glc_config.h" + +class QGLContext; +////////////////////////////////////////////////////////////////////// +//! \class GLC_ObjMtlLoader +/*! \brief GLC_ObjMtlLoader : Load the mtl file associated to a OBJ File */ + +/*! An GLC_ObjMtlLoader create GLC_Material from the .mtl file \n + */ +////////////////////////////////////////////////////////////////////// +class GLC_LIB_EXPORT GLC_ObjMtlLoader +{ + +////////////////////////////////////////////////////////////////////// +/*! @name Constructor / Destructor */ +//@{ +////////////////////////////////////////////////////////////////////// +public: + GLC_ObjMtlLoader(const QString&); + + virtual ~GLC_ObjMtlLoader(); +//@} +////////////////////////////////////////////////////////////////////// +/*! \name Get Functions*/ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Return true if the material name is found + inline bool contains(const QString &name) const + {return m_Materials.contains(name);} + + //! Get a material from is name + GLC_Material* material(const QString&); + + //! Get the list of attached files + inline QStringList listOfAttachedFileName() const + {return m_ListOfAttachedFileName.toList();} + +//@} + +////////////////////////////////////////////////////////////////////// +/*! \name Set Functions*/ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Load the materials + bool loadMaterials(); + +//@} +////////////////////////////////////////////////////////////////////// +/*! \name Private services functions*/ +//@{ +////////////////////////////////////////////////////////////////////// +private: + //! Extract the material name + bool extractMaterialName(QString &); + + //! Extract the texture file name + void extractTextureFileName(QString &); + + //! Extract RGB value + bool extractRGBValue(QString &); + + //! Extract One value + bool extractOneValue(QString &); + + //! Get texture file name without parameters + QString getTextureName(QTextStream &, const QString &); + + //! Process Maya specific obj + void processMayaSpecific(); + + +//@} + +////////////////////////////////////////////////////////////////////// +// Private members +////////////////////////////////////////////////////////////////////// +private: + //! The mtl file name + QString m_FileName; + + //! Current material + GLC_Material* m_pCurrentMaterial; + + //! The GLC_Material Hash Table + QHash m_Materials; + + //! the Load status + QString m_LoadStatus; + + //! The list of attached file name + QSet m_ListOfAttachedFileName; + + +}; + +#endif /*GLC_OBJMTLLOADER_H_*/ diff --git a/ground/openpilotgcs/src/libs/glc_lib/io/glc_objtoworld.cpp b/ground/openpilotgcs/src/libs/glc_lib/io/glc_objtoworld.cpp index 66b6ec224..a7ba2f8d4 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/io/glc_objtoworld.cpp +++ b/ground/openpilotgcs/src/libs/glc_lib/io/glc_objtoworld.cpp @@ -1,898 +1,898 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - Version 2.0.0, packaged on July 2010. - - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ - -//! \file glc_objToworld.cpp implementation of the GLC_ObjToWorld class. - - -#include "glc_objtoworld.h" -#include "../sceneGraph/glc_world.h" -#include "glc_objmtlloader.h" -#include "../glc_fileformatexception.h" -#include "../maths/glc_geomtools.h" -#include "../sceneGraph/glc_structreference.h" -#include "../sceneGraph/glc_structinstance.h" -#include "../sceneGraph/glc_structoccurence.h" -#include -#include -#include - -////////////////////////////////////////////////////////////////////// -// Constructor -////////////////////////////////////////////////////////////////////// -GLC_ObjToWorld::GLC_ObjToWorld() -: m_pWorld(NULL) -, m_FileName() -, m_pMtlLoader(NULL) -, m_CurrentLineNumber(0) -, m_pCurrentObjMesh(NULL) -, m_FaceType(notSet) -, m_CurrentMeshMaterials() -, m_CurrentMaterialName("GLC_Default") -, m_ListOfAttachedFileName() -, m_Positions() -, m_Normals() -, m_Texels() -{ -} - -GLC_ObjToWorld::~GLC_ObjToWorld() -{ - clear(); -} - -///////////////////////////////////////////////////////////////////// -// Set Functions -////////////////////////////////////////////////////////////////////// - -// Create an GLC_World from an input OBJ File -GLC_World* GLC_ObjToWorld::CreateWorldFromObj(QFile &file) -{ - m_ListOfAttachedFileName.clear(); - m_FileName= file.fileName(); - ////////////////////////////////////////////////////////////////// - // Test if the file exist and can be opened - ////////////////////////////////////////////////////////////////// - if (!file.open(QIODevice::ReadOnly)) - { - QString message(QString("GLC_ObjToWorld::CreateWorldFromObj File ") + m_FileName + QString(" doesn't exist")); - //qDebug() << message; - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotFound); - throw(fileFormatException); - } - - ////////////////////////////////////////////////////////////////// - // Init member - ////////////////////////////////////////////////////////////////// - m_pWorld= new GLC_World; - - // Create Working variables - int currentQuantumValue= 0; - int previousQuantumValue= 0; - int numberOfLine= 0; - - // Create the input file stream - QTextStream objStream(&file); - - // QString buffer - QString lineBuff; - - QString mtlLibLine; - - ////////////////////////////////////////////////////////////////// - // Searching mtllib attribute - ////////////////////////////////////////////////////////////////// - while (!objStream.atEnd() && !lineBuff.contains("mtllib")) - { - ++numberOfLine; - lineBuff= objStream.readLine(); - if (lineBuff.contains("mtllib")) mtlLibLine= lineBuff; - } - - ////////////////////////////////////////////////////////////////// - // Count the number of lines of the OBJ file - ////////////////////////////////////////////////////////////////// - while (!objStream.atEnd()) - { - ++numberOfLine; - objStream.readLine(); - } - - ////////////////////////////////////////////////////////////////// - // Reset the stream - ////////////////////////////////////////////////////////////////// - objStream.resetStatus(); - objStream.seek(0); - - ////////////////////////////////////////////////////////////////// - // if mtl file found, load it - ////////////////////////////////////////////////////////////////// - QString mtlLibFileName(getMtlLibFileName(mtlLibLine)); - if (!mtlLibFileName.isEmpty()) - { - m_pMtlLoader= new GLC_ObjMtlLoader(mtlLibFileName); - if (!m_pMtlLoader->loadMaterials()) - { - delete m_pMtlLoader; - m_pMtlLoader= NULL; - if (!mtlLibLine.isEmpty()) - { - QStringList stringList(m_FileName); - stringList.append("Open Material File : " + mtlLibFileName + " failed"); - GLC_ErrorLog::addError(stringList); - } - } - else - { - // Update Attached file name list - m_ListOfAttachedFileName << mtlLibFileName; - m_ListOfAttachedFileName << m_pMtlLoader->listOfAttachedFileName(); - } - } - else - { - //qDebug() << "GLC_ObjToWorld::CreateWorldFromObj: mtl file not found"; - } - - ////////////////////////////////////////////////////////////////// - // Read Buffer and create the world - ////////////////////////////////////////////////////////////////// - emit currentQuantum(currentQuantumValue); - m_CurrentLineNumber= 0; - while (!objStream.atEnd()) - { - ++m_CurrentLineNumber; - lineBuff= objStream.readLine(); - - mergeLines(&lineBuff, &objStream); - - scanLigne(lineBuff); - currentQuantumValue = static_cast((static_cast(m_CurrentLineNumber) / numberOfLine) * 100); - if (currentQuantumValue > previousQuantumValue) - { - emit currentQuantum(currentQuantumValue); - } - previousQuantumValue= currentQuantumValue; - - } - file.close(); - - addCurrentObjMeshToWorld(); - - //! Test if there is meshes in the world - if (m_pWorld->rootOccurence()->childCount() == 0) - { - QString message= "GLC_ObjToWorld::CreateWorldFromObj " + m_FileName + " No mesh found!"; - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::NoMeshFound); - clear(); - throw(fileFormatException); - } - return m_pWorld; - -} - -////////////////////////////////////////////////////////////////////// -// Private services functions -////////////////////////////////////////////////////////////////////// - -// Return the name of the mtl file -QString GLC_ObjToWorld::getMtlLibFileName(QString line) -{ - // Search mtl file with the same name than the OBJ file Name - QString mtlFileName(m_FileName); - mtlFileName.replace(m_FileName.size() - 3, 3, "mtl"); - QFile mtlFile(mtlFileName); - if (!mtlFile.exists())// mtl file with same name not found - { - QTextStream stream(&line); - QString header; - if ((stream >> header >> mtlFileName).status() == QTextStream::Ok) - { - // If There is spaces in the string to extracts - QString valueString2; - while ((stream >> valueString2).status() == QTextStream::Ok) - { - mtlFileName.append(" "); - mtlFileName.append(valueString2); - } - QFileInfo fileInfo(m_FileName); - mtlFileName= fileInfo.absolutePath() + QDir::separator() + mtlFileName; - } - else - { - // There is no mtl file to load - mtlFileName.clear(); - } - } - return mtlFileName; -} - -// Scan a line previously extracted from OBJ file -void GLC_ObjToWorld::scanLigne(QString &line) -{ - line= line.trimmed(); - // Search Vertexs vectors - if (line.startsWith("v ")|| line.startsWith(QString("v") + QString(QChar(9)))) - { - line.remove(0,2); // Remove first 2 char - m_Positions.append(extract3dVect(line)); - m_FaceType = notSet; - } - - // Search texture coordinate vectors - else if (line.startsWith("vt ")|| line.startsWith(QString("vt") + QString(QChar(9)))) - { - line.remove(0,3); // Remove first 3 char - m_Texels.append(extract2dVect(line)); - m_FaceType = notSet; - } - - // Search normals vectors - else if (line.startsWith("vn ") || line.startsWith(QString("vn") + QString(QChar(9)))) - { - line.remove(0,3); // Remove first 3 char - m_Normals.append(extract3dVect(line)); - m_FaceType = notSet; - } - - // Search faces to update index - else if (line.startsWith("f ") || line.startsWith(QString("f") + QString(QChar(9)))) - { - // If there is no group or object in the OBJ file - if (NULL == m_pCurrentObjMesh) - { - changeGroup("GLC_Default"); - //qDebug() << "Default group " << line; - } - line.remove(0,2); // Remove first 2 char - extractFaceIndex(line); - } - - // Search Material - else if (line.startsWith("usemtl ") || line.startsWith(QString("usemtl") + QString(QChar(9)))) - { - line.remove(0,7); // Remove first 7 char - setCurrentMaterial(line); - m_FaceType = notSet; - } - - // Search Group - else if (line.startsWith("g ") || line.startsWith("o ") || line.startsWith(QString("g") + QString(QChar(9))) - || line.startsWith(QString("o") + QString(QChar(9)))) - { - m_FaceType = notSet; - line.remove(0,2); // Remove first 2 char - changeGroup(line); - } - -} -// Change current group -void GLC_ObjToWorld::changeGroup(QString line) -{ - //qDebug() << "GLC_ObjToWorld::changeGroup at Line :" << line; - ////////////////////////////////////////////////////////////////// - // Parse the line containing the group name - ////////////////////////////////////////////////////////////////// - QTextStream stream(&line); - QString groupName; - if ((stream >> groupName).status() == QTextStream::Ok) - { - // If There is an space in the string to extracts - QString valueString2; - while ((stream >> valueString2).status() == QTextStream::Ok) - { - groupName.append(" "); - groupName.append(valueString2); - } - ////////////////////////////////////////////////////////////// - // If the groupName == "default" nothing to do - ////////////////////////////////////////////////////////////// - if("default" != groupName) - { - addCurrentObjMeshToWorld(); - m_pCurrentObjMesh= new CurrentObjMesh(m_CurrentMaterialName); - m_pCurrentObjMesh->m_pMesh->setName(groupName); - - } - } - else - { - QString message= "GLC_ObjToWorld::changeGroup " + m_FileName + " something is wrong!!"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); - clear(); - throw(fileFormatException); - } - -} - -// Extract a Vector from a string -QList GLC_ObjToWorld::extract3dVect(QString &line) -{ - float x=0.0f; - float y=0.0f; - float z=0.0f; - - QList vectResult; - QTextStream stringVecteur(&line); - - QString xString, yString, zString; - - if (((stringVecteur >> xString >> yString >> zString).status() == QTextStream::Ok)) - { - bool xOk, yOk, zOk; - x= xString.toFloat(&xOk); - y= yString.toFloat(&yOk); - z= zString.toFloat(&zOk); - if (!(xOk && yOk && zOk)) - { - QString message= "GLC_ObjToWorld::extract3dVect " + m_FileName + " failed to convert vector component to float"; - message.append("\nAt ligne : "); - message.append(QString::number(m_CurrentLineNumber)); - QStringList stringList(m_FileName); - stringList.append(message); - GLC_ErrorLog::addError(stringList); - - //GLC_FileFormatException fileFormatException(message, m_FileName); - //clear(); - //throw(fileFormatException); - } - else - { - vectResult << x << y << z; - } - } - - return vectResult; - -} - -// Extract a Vector from a string -QList GLC_ObjToWorld::extract2dVect(QString &line) -{ - float x=0.0f; - float y=0.0f; - QList vectResult; - QTextStream stringVecteur(&line); - - QString xString, yString; - - if (((stringVecteur >> xString >> yString).status() == QTextStream::Ok)) - { - bool xOk, yOk; - x= xString.toFloat(&xOk); - y= yString.toFloat(&yOk); - if (!(xOk && yOk)) - { - QString message= "GLC_ObjToWorld::extract2dVect " + m_FileName + " failed to convert vector component to double"; - message.append("\nAt ligne : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); - clear(); - throw(fileFormatException); - } - vectResult << x << y; - } - - return vectResult; -} - -// Extract a face from a string -void GLC_ObjToWorld::extractFaceIndex(QString &line) -{ - QString buff; - - int coordinateIndex; - int normalIndex; - int textureCoordinateIndex; - - QList currentFaceIndex; - ////////////////////////////////////////////////////////////////// - // Parse the line containing face index - ////////////////////////////////////////////////////////////////// - QTextStream streamFace(&line); - while ((!streamFace.atEnd())) - { - streamFace >> buff; - extractVertexIndex(buff, coordinateIndex, normalIndex, textureCoordinateIndex); - - ObjVertice currentVertice(coordinateIndex, normalIndex, textureCoordinateIndex); - if (m_pCurrentObjMesh->m_ObjVerticeIndexMap.contains(currentVertice)) - { - currentFaceIndex.append(m_pCurrentObjMesh->m_ObjVerticeIndexMap.value(currentVertice)); - } - else - { - // Add Vertex to the mesh bulk data - m_pCurrentObjMesh->m_Positions.append(m_Positions.value(coordinateIndex * 3)); - m_pCurrentObjMesh->m_Positions.append(m_Positions.value(coordinateIndex * 3 + 1)); - m_pCurrentObjMesh->m_Positions.append(m_Positions.value(coordinateIndex * 3 + 2)); - if (-1 != normalIndex) - { - // Add Normal to the mesh bulk data - m_pCurrentObjMesh->m_Normals.append(m_Normals.value(normalIndex * 3)); - m_pCurrentObjMesh->m_Normals.append(m_Normals.value(normalIndex * 3 + 1)); - m_pCurrentObjMesh->m_Normals.append(m_Normals.value(normalIndex * 3 + 2)); - } - else - { - // Add Null Normal to the mesh bulk data - m_pCurrentObjMesh->m_Normals.append(0.0f); - m_pCurrentObjMesh->m_Normals.append(0.0f); - m_pCurrentObjMesh->m_Normals.append(0.0f); - } - if (-1 != textureCoordinateIndex) - { - // Add texture coordinate to the mesh bulk data - m_pCurrentObjMesh->m_Texels.append(m_Texels.value(textureCoordinateIndex * 2)); - m_pCurrentObjMesh->m_Texels.append(m_Texels.value(textureCoordinateIndex * 2 + 1)); - } - else if (!m_pCurrentObjMesh->m_Texels.isEmpty()) - { - // Add epmty texture coordinate - m_pCurrentObjMesh->m_Texels.append(0.0f); - m_pCurrentObjMesh->m_Texels.append(0.0f); - } - // Add the index to current face index - currentFaceIndex.append(m_pCurrentObjMesh->m_NextFreeIndex); - // Add ObjVertice to ObjVertice Map - m_pCurrentObjMesh->m_ObjVerticeIndexMap.insert(currentVertice, m_pCurrentObjMesh->m_NextFreeIndex); - // Increment next free index - ++(m_pCurrentObjMesh->m_NextFreeIndex); - } - - } - ////////////////////////////////////////////////////////////////// - // Check the number of face's vertex - ////////////////////////////////////////////////////////////////// - const int size= currentFaceIndex.size(); - if (size < 3) - { - QStringList stringList(m_FileName); - stringList.append("GLC_ObjToWorld::extractFaceIndex Face with less than 3 vertex found"); - GLC_ErrorLog::addError(stringList); - return; - } - ////////////////////////////////////////////////////////////////// - // Add the face to the current mesh - ////////////////////////////////////////////////////////////////// - if ((m_FaceType == coordinateAndNormal) || (m_FaceType == coordinateAndTextureAndNormal)) - { - if (size > 3) - { - glc::triangulatePolygon(¤tFaceIndex, m_pCurrentObjMesh->m_Positions); - } - m_pCurrentObjMesh->m_Index.append(currentFaceIndex); - } - else if (m_FaceType != notSet) - { - if (size > 3) - { - glc::triangulatePolygon(¤tFaceIndex, m_pCurrentObjMesh->m_Positions); - } - // Comput the face normal - if (currentFaceIndex.size() < 3) return; - GLC_Vector3df normal= computeNormal(currentFaceIndex.at(0), currentFaceIndex.at(1), currentFaceIndex.at(2)); - - // Add Face normal to bulk data - QSet indexSet= currentFaceIndex.toSet(); - QSet::iterator iIndexSet= indexSet.begin(); - while (indexSet.constEnd() != iIndexSet) - { - m_pCurrentObjMesh->m_Normals[*iIndexSet * 3]= normal.x(); - m_pCurrentObjMesh->m_Normals[*iIndexSet * 3 + 1]= normal.y(); - m_pCurrentObjMesh->m_Normals[*iIndexSet * 3 + 2]= normal.z(); - - ++iIndexSet; - } - - m_pCurrentObjMesh->m_Index.append(currentFaceIndex); - - } - else - { - QString message= "GLC_ObjToWorld::extractFaceIndex " + m_FileName + " unknow face type"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); - clear(); - throw(fileFormatException); - } -} -//! Set Current material index -void GLC_ObjToWorld::setCurrentMaterial(QString &line) -{ - QTextStream streamString(&line); - QString materialName; - - if (!((streamString >> materialName).status() == QTextStream::Ok)) - { - QString message= "GLC_ObjToWorld::SetCurrentMaterial " + m_FileName + " : failed to extract materialName"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); - clear(); - throw(fileFormatException); - } - ////////////////////////////////////////////////////////////////// - // Check if the material is already loaded from the current mesh - ////////////////////////////////////////////////////////////////// - if ((NULL != m_pMtlLoader) && m_pMtlLoader->contains(materialName)) - { - if (NULL == m_pCurrentObjMesh) - { - changeGroup("GLC_Default"); - } - Q_ASSERT(NULL != m_pCurrentObjMesh->m_pLastOffsetSize); - - if (m_pCurrentObjMesh->m_Index.size() != m_pCurrentObjMesh->m_pLastOffsetSize->m_Offset) - { - // Update last material offsetSize - m_pCurrentObjMesh->m_pLastOffsetSize->m_size= m_pCurrentObjMesh->m_Index.size() - m_pCurrentObjMesh->m_pLastOffsetSize->m_Offset; - } - else - { - QHash::iterator iMat= m_pCurrentObjMesh->m_Materials.begin(); - while (m_pCurrentObjMesh->m_Materials.constEnd() != iMat) - { - if (iMat.value() == m_pCurrentObjMesh->m_pLastOffsetSize) - { - iMat= m_pCurrentObjMesh->m_Materials.erase(iMat); - } - else - { - ++iMat; - } - } - } - // Create this material offsetSize - MatOffsetSize* pMatOffsetSize= new MatOffsetSize(); - pMatOffsetSize->m_Offset= m_pCurrentObjMesh->m_Index.size(); - // Update current Obj mesh - m_pCurrentObjMesh->m_pLastOffsetSize= pMatOffsetSize; - m_pCurrentObjMesh->m_Materials.insertMulti(materialName, pMatOffsetSize); - // Update current material name - m_CurrentMaterialName= materialName; - } - -} -// Extract a vertex from a string -void GLC_ObjToWorld::extractVertexIndex(QString line, int &Coordinate, int &Normal, int &TextureCoordinate) -{ - if (m_FaceType == notSet) - { - setObjType(line); - } - - if (m_FaceType == coordinateAndTextureAndNormal) - { - // Replace "/" with " " - line.replace('/', ' '); - QTextStream streamVertex(&line); - QString coordinateString, textureCoordinateString, normalString; - if ((streamVertex >> coordinateString >> textureCoordinateString >> normalString).status() == QTextStream::Ok) - { - bool coordinateOk, textureCoordinateOk, normalOk; - Coordinate= coordinateString.toInt(&coordinateOk); - --Coordinate; - TextureCoordinate= textureCoordinateString.toInt(&textureCoordinateOk); - --TextureCoordinate; - Normal= normalString.toInt(&normalOk); - --Normal; - if (!(coordinateOk && textureCoordinateOk && normalOk)) - { - QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + " failed to convert String to int"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); - clear(); - throw(fileFormatException); - } - } - else - { - QString message= "GLC_ObjToWorld::extractVertexIndex Obj file " + m_FileName + " type is not supported"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); - clear(); - throw(fileFormatException); - } - - } - else if (m_FaceType == coordinateAndTexture) - { - // Replace "/" with " " - line.replace('/', ' '); - QTextStream streamVertex(&line); - QString coordinateString, textureCoordinateString; - if ((streamVertex >> coordinateString >> textureCoordinateString).status() == QTextStream::Ok) - { - bool coordinateOk, textureCoordinateOk; - Coordinate= coordinateString.toInt(&coordinateOk); - --Coordinate; - TextureCoordinate= textureCoordinateString.toInt(&textureCoordinateOk); - --TextureCoordinate; - Normal= -1; - if (!(coordinateOk && textureCoordinateOk)) - { - QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + "failed to convert String to int"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); - clear(); - throw(fileFormatException); - } - } - else - { - QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + " this Obj file type is not supported"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); - clear(); - throw(fileFormatException); - } - } - else if (m_FaceType == coordinateAndNormal) - { - // Replace "/" with " " - line.replace('/', ' '); - QTextStream streamVertex(&line); - QString coordinateString, normalString; - if ((streamVertex >> coordinateString >> normalString).status() == QTextStream::Ok) - { - bool coordinateOk, normalOk; - Coordinate= coordinateString.toInt(&coordinateOk); - --Coordinate; - TextureCoordinate= -1; - Normal= normalString.toInt(&normalOk); - --Normal; - if (!(coordinateOk && normalOk)) - { - QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + " failed to convert String to int"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); - clear(); - throw(fileFormatException); - } - } - else - { - QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + " this Obj file type is not supported"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); - clear(); - throw(fileFormatException); - } - } - else if (m_FaceType == coordinate) - { - QTextStream streamVertex(&line); - QString coordinateString; - if ((streamVertex >> coordinateString).status() == QTextStream::Ok) - { - bool coordinateOk; - Coordinate= coordinateString.toInt(&coordinateOk); - --Coordinate; - TextureCoordinate= -1; - Normal= -1; - if (!coordinateOk) - { - QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + " failed to convert String to int"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); - clear(); - throw(fileFormatException); - } - } - else - { - QString message= "GLC_ObjToWorld::extractVertexIndex Obj " + m_FileName + " file type is not supported"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); - clear(); - throw(fileFormatException); - } - } - else - { - QString message= "GLC_ObjToWorld::extractVertexIndex OBJ file " + m_FileName + " not reconize"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); - clear(); - throw(fileFormatException); - } -} - -// set the OBJ File type -void GLC_ObjToWorld::setObjType(QString& ligne) -{ - const QRegExp coordinateOnlyRegExp("^\\d{1,}$"); // ex. 10 - const QRegExp coordinateTextureNormalRegExp("^\\d{1,}/\\d{1,}/\\d{1,}$"); // ex. 10/30/54 - const QRegExp coordinateNormalRegExp("^\\d{1,}//\\d{1,}$"); // ex. 10//54 - const QRegExp coordinateTextureRegExp("^\\d{1,}/\\d{1,}$"); // ex. 10/56 - - if (coordinateTextureNormalRegExp.exactMatch(ligne)) - { - m_FaceType= coordinateAndTextureAndNormal; - } - else if (coordinateTextureRegExp.exactMatch(ligne)) - { - m_FaceType= coordinateAndTexture; - } - else if (coordinateNormalRegExp.exactMatch(ligne)) - { - m_FaceType= coordinateAndNormal; - } - else if (coordinateOnlyRegExp.exactMatch(ligne)) - { - m_FaceType= coordinate; - } - else - { - QString message= "GLC_ObjToWorld::setObjType OBJ file " + m_FileName + " not reconize"; - message.append("\nAt line : "); - message.append(QString::number(m_CurrentLineNumber)); - GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); - clear(); - throw(fileFormatException); - } -} - -// compute face normal -GLC_Vector3df GLC_ObjToWorld::computeNormal(GLuint index1, GLuint index2, GLuint index3) -{ - double xn, yn, zn; - - // Vertex 1 - xn= m_pCurrentObjMesh->m_Positions.at(index1 * 3); - yn= m_pCurrentObjMesh->m_Positions.at(index1 * 3 + 1); - zn= m_pCurrentObjMesh->m_Positions.at(index1 * 3 + 2); - const GLC_Vector3d vect1(xn, yn, zn); - - // Vertex 2 - xn= m_pCurrentObjMesh->m_Positions.at(index2 * 3); - yn= m_pCurrentObjMesh->m_Positions.at(index2 * 3 + 1); - zn= m_pCurrentObjMesh->m_Positions.at(index2 * 3 + 2); - const GLC_Vector3d vect2(xn, yn, zn); - - // Vertex 3 - xn= m_pCurrentObjMesh->m_Positions.at(index3 * 3); - yn= m_pCurrentObjMesh->m_Positions.at(index3 * 3 + 1); - zn= m_pCurrentObjMesh->m_Positions.at(index3 * 3 + 2); - const GLC_Vector3d vect3(xn, yn, zn); - - const GLC_Vector3d edge1(vect3 - vect2); - const GLC_Vector3d edge2(vect1 - vect2); - - GLC_Vector3d normal(edge1 ^ edge2); - normal.normalize(); - - return normal.toVector3df(); -} - -// clear objToWorld allocate memmory -void GLC_ObjToWorld::clear() -{ - m_CurrentMeshMaterials.clear(); - m_ListOfAttachedFileName.clear(); - - if (NULL != m_pMtlLoader) - { - delete m_pMtlLoader; - m_pMtlLoader= NULL; - } - if (NULL != m_pCurrentObjMesh) - { - delete m_pCurrentObjMesh; - m_pCurrentObjMesh= NULL; - } - -} -// Merge Mutli line in one -void GLC_ObjToWorld::mergeLines(QString* pLineBuff, QTextStream* p0bjStream) -{ - if (pLineBuff->endsWith(QChar('\\'))) - { - pLineBuff->replace(QChar('\\'), QChar(' ')); - pLineBuff->append(p0bjStream->readLine()); - ++m_CurrentLineNumber; - mergeLines(pLineBuff, p0bjStream); - } -} - -// Add the current Obj mesh to the world -void GLC_ObjToWorld::addCurrentObjMeshToWorld() -{ - if (NULL != m_pCurrentObjMesh) - { - if (!m_pCurrentObjMesh->m_Positions.isEmpty()) - { - m_pCurrentObjMesh->m_pMesh->addVertice(m_pCurrentObjMesh->m_Positions.toVector()); - m_pCurrentObjMesh->m_Positions.clear(); - m_pCurrentObjMesh->m_pMesh->addNormals(m_pCurrentObjMesh->m_Normals.toVector()); - m_pCurrentObjMesh->m_Normals.clear(); - if (!m_pCurrentObjMesh->m_Texels.isEmpty()) - { - m_pCurrentObjMesh->m_pMesh->addTexels(m_pCurrentObjMesh->m_Texels.toVector()); - m_pCurrentObjMesh->m_Texels.clear(); - } - QHash::iterator iMat= m_pCurrentObjMesh->m_Materials.begin(); - while (m_pCurrentObjMesh->m_Materials.constEnd() != iMat) - { - GLC_Material* pCurrentMaterial= NULL; - if ((NULL != m_pMtlLoader) && (m_pMtlLoader->contains(iMat.key()))) - { - pCurrentMaterial= m_pMtlLoader->material(iMat.key()); - } - // Create the list of triangles to add to the mesh - const int offset= iMat.value()->m_Offset; - int size= iMat.value()->m_size; - if (0 == size) - { - size= m_pCurrentObjMesh->m_Index.size() - offset; - } - //qDebug() << "Offset : " << offset << " size : " << size; - QList triangles; - for (int i= offset; i < (offset + size); ++i) - { - triangles.append(m_pCurrentObjMesh->m_Index.at(i)); - } - // Add the list of triangle to the mesh - if (!triangles.isEmpty()) - { - m_pCurrentObjMesh->m_pMesh->addTriangles(pCurrentMaterial, triangles); - } - - ++iMat; - } - if (m_pCurrentObjMesh->m_pMesh->faceCount(0) > 0) - { - m_pCurrentObjMesh->m_pMesh->finish(); - GLC_3DRep* pRep= new GLC_3DRep(m_pCurrentObjMesh->m_pMesh); - m_pWorld->rootOccurence()->addChild((new GLC_StructInstance(pRep))); - } - else - { - delete m_pCurrentObjMesh->m_pMesh; - } - - } - else - { - delete m_pCurrentObjMesh->m_pMesh; - } - - delete m_pCurrentObjMesh; - m_pCurrentObjMesh= NULL; - } -} - - +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + Version 2.0.0, packaged on July 2010. + + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ + +//! \file glc_objToworld.cpp implementation of the GLC_ObjToWorld class. + + +#include "glc_objtoworld.h" +#include "../sceneGraph/glc_world.h" +#include "glc_objmtlloader.h" +#include "../glc_fileformatexception.h" +#include "../maths/glc_geomtools.h" +#include "../sceneGraph/glc_structreference.h" +#include "../sceneGraph/glc_structinstance.h" +#include "../sceneGraph/glc_structoccurence.h" +#include +#include +#include + +////////////////////////////////////////////////////////////////////// +// Constructor +////////////////////////////////////////////////////////////////////// +GLC_ObjToWorld::GLC_ObjToWorld() +: m_pWorld(NULL) +, m_FileName() +, m_pMtlLoader(NULL) +, m_CurrentLineNumber(0) +, m_pCurrentObjMesh(NULL) +, m_FaceType(notSet) +, m_CurrentMeshMaterials() +, m_CurrentMaterialName("GLC_Default") +, m_ListOfAttachedFileName() +, m_Positions() +, m_Normals() +, m_Texels() +{ +} + +GLC_ObjToWorld::~GLC_ObjToWorld() +{ + clear(); +} + +///////////////////////////////////////////////////////////////////// +// Set Functions +////////////////////////////////////////////////////////////////////// + +// Create an GLC_World from an input OBJ File +GLC_World* GLC_ObjToWorld::CreateWorldFromObj(QFile &file) +{ + m_ListOfAttachedFileName.clear(); + m_FileName= file.fileName(); + ////////////////////////////////////////////////////////////////// + // Test if the file exist and can be opened + ////////////////////////////////////////////////////////////////// + if (!file.open(QIODevice::ReadOnly)) + { + QString message(QString("GLC_ObjToWorld::CreateWorldFromObj File ") + m_FileName + QString(" doesn't exist")); + //qDebug() << message; + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotFound); + throw(fileFormatException); + } + + ////////////////////////////////////////////////////////////////// + // Init member + ////////////////////////////////////////////////////////////////// + m_pWorld= new GLC_World; + + // Create Working variables + int currentQuantumValue= 0; + int previousQuantumValue= 0; + int numberOfLine= 0; + + // Create the input file stream + QTextStream objStream(&file); + + // QString buffer + QString lineBuff; + + QString mtlLibLine; + + ////////////////////////////////////////////////////////////////// + // Searching mtllib attribute + ////////////////////////////////////////////////////////////////// + while (!objStream.atEnd() && !lineBuff.contains("mtllib")) + { + ++numberOfLine; + lineBuff= objStream.readLine(); + if (lineBuff.contains("mtllib")) mtlLibLine= lineBuff; + } + + ////////////////////////////////////////////////////////////////// + // Count the number of lines of the OBJ file + ////////////////////////////////////////////////////////////////// + while (!objStream.atEnd()) + { + ++numberOfLine; + objStream.readLine(); + } + + ////////////////////////////////////////////////////////////////// + // Reset the stream + ////////////////////////////////////////////////////////////////// + objStream.resetStatus(); + objStream.seek(0); + + ////////////////////////////////////////////////////////////////// + // if mtl file found, load it + ////////////////////////////////////////////////////////////////// + QString mtlLibFileName(getMtlLibFileName(mtlLibLine)); + if (!mtlLibFileName.isEmpty()) + { + m_pMtlLoader= new GLC_ObjMtlLoader(mtlLibFileName); + if (!m_pMtlLoader->loadMaterials()) + { + delete m_pMtlLoader; + m_pMtlLoader= NULL; + if (!mtlLibLine.isEmpty()) + { + QStringList stringList(m_FileName); + stringList.append("Open Material File : " + mtlLibFileName + " failed"); + GLC_ErrorLog::addError(stringList); + } + } + else + { + // Update Attached file name list + m_ListOfAttachedFileName << mtlLibFileName; + m_ListOfAttachedFileName << m_pMtlLoader->listOfAttachedFileName(); + } + } + else + { + //qDebug() << "GLC_ObjToWorld::CreateWorldFromObj: mtl file not found"; + } + + ////////////////////////////////////////////////////////////////// + // Read Buffer and create the world + ////////////////////////////////////////////////////////////////// + emit currentQuantum(currentQuantumValue); + m_CurrentLineNumber= 0; + while (!objStream.atEnd()) + { + ++m_CurrentLineNumber; + lineBuff= objStream.readLine(); + + mergeLines(&lineBuff, &objStream); + + scanLigne(lineBuff); + currentQuantumValue = static_cast((static_cast(m_CurrentLineNumber) / numberOfLine) * 100); + if (currentQuantumValue > previousQuantumValue) + { + emit currentQuantum(currentQuantumValue); + } + previousQuantumValue= currentQuantumValue; + + } + file.close(); + + addCurrentObjMeshToWorld(); + + //! Test if there is meshes in the world + if (m_pWorld->rootOccurence()->childCount() == 0) + { + QString message= "GLC_ObjToWorld::CreateWorldFromObj " + m_FileName + " No mesh found!"; + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::NoMeshFound); + clear(); + throw(fileFormatException); + } + return m_pWorld; + +} + +////////////////////////////////////////////////////////////////////// +// Private services functions +////////////////////////////////////////////////////////////////////// + +// Return the name of the mtl file +QString GLC_ObjToWorld::getMtlLibFileName(QString line) +{ + // Search mtl file with the same name than the OBJ file Name + QString mtlFileName(m_FileName); + mtlFileName.replace(m_FileName.size() - 3, 3, "mtl"); + QFile mtlFile(mtlFileName); + if (!mtlFile.exists())// mtl file with same name not found + { + QTextStream stream(&line); + QString header; + if ((stream >> header >> mtlFileName).status() == QTextStream::Ok) + { + // If There is spaces in the string to extracts + QString valueString2; + while ((stream >> valueString2).status() == QTextStream::Ok) + { + mtlFileName.append(" "); + mtlFileName.append(valueString2); + } + QFileInfo fileInfo(m_FileName); + mtlFileName= fileInfo.absolutePath() + QDir::separator() + mtlFileName; + } + else + { + // There is no mtl file to load + mtlFileName.clear(); + } + } + return mtlFileName; +} + +// Scan a line previously extracted from OBJ file +void GLC_ObjToWorld::scanLigne(QString &line) +{ + line= line.trimmed(); + // Search Vertexs vectors + if (line.startsWith("v ")|| line.startsWith(QString("v") + QString(QChar(9)))) + { + line.remove(0,2); // Remove first 2 char + m_Positions.append(extract3dVect(line)); + m_FaceType = notSet; + } + + // Search texture coordinate vectors + else if (line.startsWith("vt ")|| line.startsWith(QString("vt") + QString(QChar(9)))) + { + line.remove(0,3); // Remove first 3 char + m_Texels.append(extract2dVect(line)); + m_FaceType = notSet; + } + + // Search normals vectors + else if (line.startsWith("vn ") || line.startsWith(QString("vn") + QString(QChar(9)))) + { + line.remove(0,3); // Remove first 3 char + m_Normals.append(extract3dVect(line)); + m_FaceType = notSet; + } + + // Search faces to update index + else if (line.startsWith("f ") || line.startsWith(QString("f") + QString(QChar(9)))) + { + // If there is no group or object in the OBJ file + if (NULL == m_pCurrentObjMesh) + { + changeGroup("GLC_Default"); + //qDebug() << "Default group " << line; + } + line.remove(0,2); // Remove first 2 char + extractFaceIndex(line); + } + + // Search Material + else if (line.startsWith("usemtl ") || line.startsWith(QString("usemtl") + QString(QChar(9)))) + { + line.remove(0,7); // Remove first 7 char + setCurrentMaterial(line); + m_FaceType = notSet; + } + + // Search Group + else if (line.startsWith("g ") || line.startsWith("o ") || line.startsWith(QString("g") + QString(QChar(9))) + || line.startsWith(QString("o") + QString(QChar(9)))) + { + m_FaceType = notSet; + line.remove(0,2); // Remove first 2 char + changeGroup(line); + } + +} +// Change current group +void GLC_ObjToWorld::changeGroup(QString line) +{ + //qDebug() << "GLC_ObjToWorld::changeGroup at Line :" << line; + ////////////////////////////////////////////////////////////////// + // Parse the line containing the group name + ////////////////////////////////////////////////////////////////// + QTextStream stream(&line); + QString groupName; + if ((stream >> groupName).status() == QTextStream::Ok) + { + // If There is an space in the string to extracts + QString valueString2; + while ((stream >> valueString2).status() == QTextStream::Ok) + { + groupName.append(" "); + groupName.append(valueString2); + } + ////////////////////////////////////////////////////////////// + // If the groupName == "default" nothing to do + ////////////////////////////////////////////////////////////// + if("default" != groupName) + { + addCurrentObjMeshToWorld(); + m_pCurrentObjMesh= new CurrentObjMesh(m_CurrentMaterialName); + m_pCurrentObjMesh->m_pMesh->setName(groupName); + + } + } + else + { + QString message= "GLC_ObjToWorld::changeGroup " + m_FileName + " something is wrong!!"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); + clear(); + throw(fileFormatException); + } + +} + +// Extract a Vector from a string +QList GLC_ObjToWorld::extract3dVect(QString &line) +{ + float x=0.0f; + float y=0.0f; + float z=0.0f; + + QList vectResult; + QTextStream stringVecteur(&line); + + QString xString, yString, zString; + + if (((stringVecteur >> xString >> yString >> zString).status() == QTextStream::Ok)) + { + bool xOk, yOk, zOk; + x= xString.toFloat(&xOk); + y= yString.toFloat(&yOk); + z= zString.toFloat(&zOk); + if (!(xOk && yOk && zOk)) + { + QString message= "GLC_ObjToWorld::extract3dVect " + m_FileName + " failed to convert vector component to float"; + message.append("\nAt ligne : "); + message.append(QString::number(m_CurrentLineNumber)); + QStringList stringList(m_FileName); + stringList.append(message); + GLC_ErrorLog::addError(stringList); + + //GLC_FileFormatException fileFormatException(message, m_FileName); + //clear(); + //throw(fileFormatException); + } + else + { + vectResult << x << y << z; + } + } + + return vectResult; + +} + +// Extract a Vector from a string +QList GLC_ObjToWorld::extract2dVect(QString &line) +{ + float x=0.0f; + float y=0.0f; + QList vectResult; + QTextStream stringVecteur(&line); + + QString xString, yString; + + if (((stringVecteur >> xString >> yString).status() == QTextStream::Ok)) + { + bool xOk, yOk; + x= xString.toFloat(&xOk); + y= yString.toFloat(&yOk); + if (!(xOk && yOk)) + { + QString message= "GLC_ObjToWorld::extract2dVect " + m_FileName + " failed to convert vector component to double"; + message.append("\nAt ligne : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); + clear(); + throw(fileFormatException); + } + vectResult << x << y; + } + + return vectResult; +} + +// Extract a face from a string +void GLC_ObjToWorld::extractFaceIndex(QString &line) +{ + QString buff; + + int coordinateIndex; + int normalIndex; + int textureCoordinateIndex; + + QList currentFaceIndex; + ////////////////////////////////////////////////////////////////// + // Parse the line containing face index + ////////////////////////////////////////////////////////////////// + QTextStream streamFace(&line); + while ((!streamFace.atEnd())) + { + streamFace >> buff; + extractVertexIndex(buff, coordinateIndex, normalIndex, textureCoordinateIndex); + + ObjVertice currentVertice(coordinateIndex, normalIndex, textureCoordinateIndex); + if (m_pCurrentObjMesh->m_ObjVerticeIndexMap.contains(currentVertice)) + { + currentFaceIndex.append(m_pCurrentObjMesh->m_ObjVerticeIndexMap.value(currentVertice)); + } + else + { + // Add Vertex to the mesh bulk data + m_pCurrentObjMesh->m_Positions.append(m_Positions.value(coordinateIndex * 3)); + m_pCurrentObjMesh->m_Positions.append(m_Positions.value(coordinateIndex * 3 + 1)); + m_pCurrentObjMesh->m_Positions.append(m_Positions.value(coordinateIndex * 3 + 2)); + if (-1 != normalIndex) + { + // Add Normal to the mesh bulk data + m_pCurrentObjMesh->m_Normals.append(m_Normals.value(normalIndex * 3)); + m_pCurrentObjMesh->m_Normals.append(m_Normals.value(normalIndex * 3 + 1)); + m_pCurrentObjMesh->m_Normals.append(m_Normals.value(normalIndex * 3 + 2)); + } + else + { + // Add Null Normal to the mesh bulk data + m_pCurrentObjMesh->m_Normals.append(0.0f); + m_pCurrentObjMesh->m_Normals.append(0.0f); + m_pCurrentObjMesh->m_Normals.append(0.0f); + } + if (-1 != textureCoordinateIndex) + { + // Add texture coordinate to the mesh bulk data + m_pCurrentObjMesh->m_Texels.append(m_Texels.value(textureCoordinateIndex * 2)); + m_pCurrentObjMesh->m_Texels.append(m_Texels.value(textureCoordinateIndex * 2 + 1)); + } + else if (!m_pCurrentObjMesh->m_Texels.isEmpty()) + { + // Add epmty texture coordinate + m_pCurrentObjMesh->m_Texels.append(0.0f); + m_pCurrentObjMesh->m_Texels.append(0.0f); + } + // Add the index to current face index + currentFaceIndex.append(m_pCurrentObjMesh->m_NextFreeIndex); + // Add ObjVertice to ObjVertice Map + m_pCurrentObjMesh->m_ObjVerticeIndexMap.insert(currentVertice, m_pCurrentObjMesh->m_NextFreeIndex); + // Increment next free index + ++(m_pCurrentObjMesh->m_NextFreeIndex); + } + + } + ////////////////////////////////////////////////////////////////// + // Check the number of face's vertex + ////////////////////////////////////////////////////////////////// + const int size= currentFaceIndex.size(); + if (size < 3) + { + QStringList stringList(m_FileName); + stringList.append("GLC_ObjToWorld::extractFaceIndex Face with less than 3 vertex found"); + GLC_ErrorLog::addError(stringList); + return; + } + ////////////////////////////////////////////////////////////////// + // Add the face to the current mesh + ////////////////////////////////////////////////////////////////// + if ((m_FaceType == coordinateAndNormal) || (m_FaceType == coordinateAndTextureAndNormal)) + { + if (size > 3) + { + glc::triangulatePolygon(¤tFaceIndex, m_pCurrentObjMesh->m_Positions); + } + m_pCurrentObjMesh->m_Index.append(currentFaceIndex); + } + else if (m_FaceType != notSet) + { + if (size > 3) + { + glc::triangulatePolygon(¤tFaceIndex, m_pCurrentObjMesh->m_Positions); + } + // Comput the face normal + if (currentFaceIndex.size() < 3) return; + GLC_Vector3df normal= computeNormal(currentFaceIndex.at(0), currentFaceIndex.at(1), currentFaceIndex.at(2)); + + // Add Face normal to bulk data + QSet indexSet= currentFaceIndex.toSet(); + QSet::iterator iIndexSet= indexSet.begin(); + while (indexSet.constEnd() != iIndexSet) + { + m_pCurrentObjMesh->m_Normals[*iIndexSet * 3]= normal.x(); + m_pCurrentObjMesh->m_Normals[*iIndexSet * 3 + 1]= normal.y(); + m_pCurrentObjMesh->m_Normals[*iIndexSet * 3 + 2]= normal.z(); + + ++iIndexSet; + } + + m_pCurrentObjMesh->m_Index.append(currentFaceIndex); + + } + else + { + QString message= "GLC_ObjToWorld::extractFaceIndex " + m_FileName + " unknow face type"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); + clear(); + throw(fileFormatException); + } +} +//! Set Current material index +void GLC_ObjToWorld::setCurrentMaterial(QString &line) +{ + QTextStream streamString(&line); + QString materialName; + + if (!((streamString >> materialName).status() == QTextStream::Ok)) + { + QString message= "GLC_ObjToWorld::SetCurrentMaterial " + m_FileName + " : failed to extract materialName"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); + clear(); + throw(fileFormatException); + } + ////////////////////////////////////////////////////////////////// + // Check if the material is already loaded from the current mesh + ////////////////////////////////////////////////////////////////// + if ((NULL != m_pMtlLoader) && m_pMtlLoader->contains(materialName)) + { + if (NULL == m_pCurrentObjMesh) + { + changeGroup("GLC_Default"); + } + Q_ASSERT(NULL != m_pCurrentObjMesh->m_pLastOffsetSize); + + if (m_pCurrentObjMesh->m_Index.size() != m_pCurrentObjMesh->m_pLastOffsetSize->m_Offset) + { + // Update last material offsetSize + m_pCurrentObjMesh->m_pLastOffsetSize->m_size= m_pCurrentObjMesh->m_Index.size() - m_pCurrentObjMesh->m_pLastOffsetSize->m_Offset; + } + else + { + QHash::iterator iMat= m_pCurrentObjMesh->m_Materials.begin(); + while (m_pCurrentObjMesh->m_Materials.constEnd() != iMat) + { + if (iMat.value() == m_pCurrentObjMesh->m_pLastOffsetSize) + { + iMat= m_pCurrentObjMesh->m_Materials.erase(iMat); + } + else + { + ++iMat; + } + } + } + // Create this material offsetSize + MatOffsetSize* pMatOffsetSize= new MatOffsetSize(); + pMatOffsetSize->m_Offset= m_pCurrentObjMesh->m_Index.size(); + // Update current Obj mesh + m_pCurrentObjMesh->m_pLastOffsetSize= pMatOffsetSize; + m_pCurrentObjMesh->m_Materials.insertMulti(materialName, pMatOffsetSize); + // Update current material name + m_CurrentMaterialName= materialName; + } + +} +// Extract a vertex from a string +void GLC_ObjToWorld::extractVertexIndex(QString line, int &Coordinate, int &Normal, int &TextureCoordinate) +{ + if (m_FaceType == notSet) + { + setObjType(line); + } + + if (m_FaceType == coordinateAndTextureAndNormal) + { + // Replace "/" with " " + line.replace('/', ' '); + QTextStream streamVertex(&line); + QString coordinateString, textureCoordinateString, normalString; + if ((streamVertex >> coordinateString >> textureCoordinateString >> normalString).status() == QTextStream::Ok) + { + bool coordinateOk, textureCoordinateOk, normalOk; + Coordinate= coordinateString.toInt(&coordinateOk); + --Coordinate; + TextureCoordinate= textureCoordinateString.toInt(&textureCoordinateOk); + --TextureCoordinate; + Normal= normalString.toInt(&normalOk); + --Normal; + if (!(coordinateOk && textureCoordinateOk && normalOk)) + { + QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + " failed to convert String to int"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); + clear(); + throw(fileFormatException); + } + } + else + { + QString message= "GLC_ObjToWorld::extractVertexIndex Obj file " + m_FileName + " type is not supported"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); + clear(); + throw(fileFormatException); + } + + } + else if (m_FaceType == coordinateAndTexture) + { + // Replace "/" with " " + line.replace('/', ' '); + QTextStream streamVertex(&line); + QString coordinateString, textureCoordinateString; + if ((streamVertex >> coordinateString >> textureCoordinateString).status() == QTextStream::Ok) + { + bool coordinateOk, textureCoordinateOk; + Coordinate= coordinateString.toInt(&coordinateOk); + --Coordinate; + TextureCoordinate= textureCoordinateString.toInt(&textureCoordinateOk); + --TextureCoordinate; + Normal= -1; + if (!(coordinateOk && textureCoordinateOk)) + { + QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + "failed to convert String to int"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); + clear(); + throw(fileFormatException); + } + } + else + { + QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + " this Obj file type is not supported"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); + clear(); + throw(fileFormatException); + } + } + else if (m_FaceType == coordinateAndNormal) + { + // Replace "/" with " " + line.replace('/', ' '); + QTextStream streamVertex(&line); + QString coordinateString, normalString; + if ((streamVertex >> coordinateString >> normalString).status() == QTextStream::Ok) + { + bool coordinateOk, normalOk; + Coordinate= coordinateString.toInt(&coordinateOk); + --Coordinate; + TextureCoordinate= -1; + Normal= normalString.toInt(&normalOk); + --Normal; + if (!(coordinateOk && normalOk)) + { + QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + " failed to convert String to int"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); + clear(); + throw(fileFormatException); + } + } + else + { + QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + " this Obj file type is not supported"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); + clear(); + throw(fileFormatException); + } + } + else if (m_FaceType == coordinate) + { + QTextStream streamVertex(&line); + QString coordinateString; + if ((streamVertex >> coordinateString).status() == QTextStream::Ok) + { + bool coordinateOk; + Coordinate= coordinateString.toInt(&coordinateOk); + --Coordinate; + TextureCoordinate= -1; + Normal= -1; + if (!coordinateOk) + { + QString message= "GLC_ObjToWorld::extractVertexIndex " + m_FileName + " failed to convert String to int"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::WrongFileFormat); + clear(); + throw(fileFormatException); + } + } + else + { + QString message= "GLC_ObjToWorld::extractVertexIndex Obj " + m_FileName + " file type is not supported"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); + clear(); + throw(fileFormatException); + } + } + else + { + QString message= "GLC_ObjToWorld::extractVertexIndex OBJ file " + m_FileName + " not reconize"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); + clear(); + throw(fileFormatException); + } +} + +// set the OBJ File type +void GLC_ObjToWorld::setObjType(QString& ligne) +{ + const QRegExp coordinateOnlyRegExp("^\\d{1,}$"); // ex. 10 + const QRegExp coordinateTextureNormalRegExp("^\\d{1,}/\\d{1,}/\\d{1,}$"); // ex. 10/30/54 + const QRegExp coordinateNormalRegExp("^\\d{1,}//\\d{1,}$"); // ex. 10//54 + const QRegExp coordinateTextureRegExp("^\\d{1,}/\\d{1,}$"); // ex. 10/56 + + if (coordinateTextureNormalRegExp.exactMatch(ligne)) + { + m_FaceType= coordinateAndTextureAndNormal; + } + else if (coordinateTextureRegExp.exactMatch(ligne)) + { + m_FaceType= coordinateAndTexture; + } + else if (coordinateNormalRegExp.exactMatch(ligne)) + { + m_FaceType= coordinateAndNormal; + } + else if (coordinateOnlyRegExp.exactMatch(ligne)) + { + m_FaceType= coordinate; + } + else + { + QString message= "GLC_ObjToWorld::setObjType OBJ file " + m_FileName + " not reconize"; + message.append("\nAt line : "); + message.append(QString::number(m_CurrentLineNumber)); + GLC_FileFormatException fileFormatException(message, m_FileName, GLC_FileFormatException::FileNotSupported); + clear(); + throw(fileFormatException); + } +} + +// compute face normal +GLC_Vector3df GLC_ObjToWorld::computeNormal(GLuint index1, GLuint index2, GLuint index3) +{ + double xn, yn, zn; + + // Vertex 1 + xn= m_pCurrentObjMesh->m_Positions.at(index1 * 3); + yn= m_pCurrentObjMesh->m_Positions.at(index1 * 3 + 1); + zn= m_pCurrentObjMesh->m_Positions.at(index1 * 3 + 2); + const GLC_Vector3d vect1(xn, yn, zn); + + // Vertex 2 + xn= m_pCurrentObjMesh->m_Positions.at(index2 * 3); + yn= m_pCurrentObjMesh->m_Positions.at(index2 * 3 + 1); + zn= m_pCurrentObjMesh->m_Positions.at(index2 * 3 + 2); + const GLC_Vector3d vect2(xn, yn, zn); + + // Vertex 3 + xn= m_pCurrentObjMesh->m_Positions.at(index3 * 3); + yn= m_pCurrentObjMesh->m_Positions.at(index3 * 3 + 1); + zn= m_pCurrentObjMesh->m_Positions.at(index3 * 3 + 2); + const GLC_Vector3d vect3(xn, yn, zn); + + const GLC_Vector3d edge1(vect3 - vect2); + const GLC_Vector3d edge2(vect1 - vect2); + + GLC_Vector3d normal(edge1 ^ edge2); + normal.normalize(); + + return normal.toVector3df(); +} + +// clear objToWorld allocate memmory +void GLC_ObjToWorld::clear() +{ + m_CurrentMeshMaterials.clear(); + m_ListOfAttachedFileName.clear(); + + if (NULL != m_pMtlLoader) + { + delete m_pMtlLoader; + m_pMtlLoader= NULL; + } + if (NULL != m_pCurrentObjMesh) + { + delete m_pCurrentObjMesh; + m_pCurrentObjMesh= NULL; + } + +} +// Merge Mutli line in one +void GLC_ObjToWorld::mergeLines(QString* pLineBuff, QTextStream* p0bjStream) +{ + if (pLineBuff->endsWith(QChar('\\'))) + { + pLineBuff->replace(QChar('\\'), QChar(' ')); + pLineBuff->append(p0bjStream->readLine()); + ++m_CurrentLineNumber; + mergeLines(pLineBuff, p0bjStream); + } +} + +// Add the current Obj mesh to the world +void GLC_ObjToWorld::addCurrentObjMeshToWorld() +{ + if (NULL != m_pCurrentObjMesh) + { + if (!m_pCurrentObjMesh->m_Positions.isEmpty()) + { + m_pCurrentObjMesh->m_pMesh->addVertice(m_pCurrentObjMesh->m_Positions.toVector()); + m_pCurrentObjMesh->m_Positions.clear(); + m_pCurrentObjMesh->m_pMesh->addNormals(m_pCurrentObjMesh->m_Normals.toVector()); + m_pCurrentObjMesh->m_Normals.clear(); + if (!m_pCurrentObjMesh->m_Texels.isEmpty()) + { + m_pCurrentObjMesh->m_pMesh->addTexels(m_pCurrentObjMesh->m_Texels.toVector()); + m_pCurrentObjMesh->m_Texels.clear(); + } + QHash::iterator iMat= m_pCurrentObjMesh->m_Materials.begin(); + while (m_pCurrentObjMesh->m_Materials.constEnd() != iMat) + { + GLC_Material* pCurrentMaterial= NULL; + if ((NULL != m_pMtlLoader) && (m_pMtlLoader->contains(iMat.key()))) + { + pCurrentMaterial= m_pMtlLoader->material(iMat.key()); + } + // Create the list of triangles to add to the mesh + const int offset= iMat.value()->m_Offset; + int size= iMat.value()->m_size; + if (0 == size) + { + size= m_pCurrentObjMesh->m_Index.size() - offset; + } + //qDebug() << "Offset : " << offset << " size : " << size; + QList triangles; + for (int i= offset; i < (offset + size); ++i) + { + triangles.append(m_pCurrentObjMesh->m_Index.at(i)); + } + // Add the list of triangle to the mesh + if (!triangles.isEmpty()) + { + m_pCurrentObjMesh->m_pMesh->addTriangles(pCurrentMaterial, triangles); + } + + ++iMat; + } + if (m_pCurrentObjMesh->m_pMesh->faceCount(0) > 0) + { + m_pCurrentObjMesh->m_pMesh->finish(); + GLC_3DRep* pRep= new GLC_3DRep(m_pCurrentObjMesh->m_pMesh); + m_pWorld->rootOccurence()->addChild((new GLC_StructInstance(pRep))); + } + else + { + delete m_pCurrentObjMesh->m_pMesh; + } + + } + else + { + delete m_pCurrentObjMesh->m_pMesh; + } + + delete m_pCurrentObjMesh; + m_pCurrentObjMesh= NULL; + } +} + + diff --git a/ground/openpilotgcs/src/libs/glc_lib/io/glc_objtoworld.h b/ground/openpilotgcs/src/libs/glc_lib/io/glc_objtoworld.h index 5d8585e7d..092a625e2 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/io/glc_objtoworld.h +++ b/ground/openpilotgcs/src/libs/glc_lib/io/glc_objtoworld.h @@ -1,269 +1,269 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - Version 2.0.0, packaged on July 2010. - - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ - -//! \file glc_objToworld.h interface for the GLC_ObjToWorld class. - -#ifndef GLC_OBJTOWORLD_H_ -#define GLC_OBJTOWORLD_H_ - -#include -#include -#include -#include -#include -#include - -#include "../maths/glc_vector3d.h" -#include "../maths/glc_vector2df.h" -#include "../maths/glc_vector3df.h" -#include "../geometry/glc_mesh.h" - -#include "../glc_config.h" - -enum FaceType -{ - notSet, - coordinate, - coordinateAndTexture, - coordinateAndNormal, - coordinateAndTextureAndNormal -}; - -class GLC_World; -class GLC_ObjMtlLoader; -class QGLContext; - -////////////////////////////////////////////////////////////////////// -//! \class GLC_ObjToWorld -/*! \brief GLC_ObjToWorld : Create an GLC_World from obj file */ - -/*! An GLC_ObjToWorld extract the meshs from an .obj file \n - * List of elements extracted from the OBJ - * - Vertex - * - Face - * - Texture coordinate - * - Normal coordinate - */ -////////////////////////////////////////////////////////////////////// -class GLC_LIB_EXPORT GLC_ObjToWorld : public QObject -{ - Q_OBJECT - -public: - // OBJ Vertice (Position index, Normal index and TexCoord index) - struct ObjVertice - { - ObjVertice() - : m_Values(3) - { - m_Values[0]= 0; - m_Values[1]= 0; - m_Values[2]= 0; - } - ObjVertice(int v1, int v2, int v3) - : m_Values(3) - { - m_Values[0]= v1; - m_Values[1]= v2; - m_Values[2]= v3; - } - - QVector m_Values; - }; - - // Material assignement - struct MatOffsetSize - { - MatOffsetSize() - : m_Offset(0) - , m_size(0) - {} - int m_Offset; - int m_size; - }; - - // Current OBJ Mesh - struct CurrentObjMesh - { - CurrentObjMesh(const QString materialName) - : m_pMesh(new GLC_Mesh()) - , m_Positions() - , m_Normals() - , m_Texels() - , m_Index() - , m_pLastOffsetSize(new MatOffsetSize()) - , m_Materials() - , m_NextFreeIndex(0) - , m_ObjVerticeIndexMap() - { - m_Materials.insert(materialName, m_pLastOffsetSize); - } - ~CurrentObjMesh() - { - QHash::iterator i= m_Materials.begin(); - while (m_Materials.constEnd() != i) - { - delete i.value(); - ++i; - } - } - GLC_Mesh* m_pMesh; - QList m_Positions; - QList m_Normals; - QList m_Texels; - //! The index of the current Mesh - IndexList m_Index; - // Pointer to the last matOffsetSize - MatOffsetSize* m_pLastOffsetSize; - // QHash containing material id and associated offset and size - QHash m_Materials; - //! The next free index - int m_NextFreeIndex; - //! The Hash table of obj vertice mapping to index - QHash m_ObjVerticeIndexMap; - }; - -////////////////////////////////////////////////////////////////////// -/*! @name Constructor / Destructor */ -//@{ -////////////////////////////////////////////////////////////////////// - -public: - GLC_ObjToWorld(); - virtual ~GLC_ObjToWorld(); -//@} - -////////////////////////////////////////////////////////////////////// -/*! \name Set Functions*/ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Create an GLC_World from an input OBJ File - GLC_World* CreateWorldFromObj(QFile &file); - - //! Get the list of attached files - inline QStringList listOfAttachedFileName() const{return m_ListOfAttachedFileName;} -//@} - -////////////////////////////////////////////////////////////////////// -// Private services functions -////////////////////////////////////////////////////////////////////// -private: - //! Return the name of the mtl file - QString getMtlLibFileName(QString); - - //! Scan a line previously extracted from OBJ file - void scanLigne(QString &); - - //! Change current group - void changeGroup(QString); - - //! Extract a 3D Vector from a string - QList extract3dVect(QString &); - - //! Extract a 2D Vector from a string - QList extract2dVect(QString &); - - //! Extract a face from a string - void extractFaceIndex(QString &); - - //! Set Current material index - void setCurrentMaterial(QString &line); - - //! Extract a vertex from a string - void extractVertexIndex(QString ligne, int &Coordinate, int &Normal, int &TextureCoordinate); - - //! set the OBJ File type - void setObjType(QString &); - - //! compute face normal - GLC_Vector3df computeNormal(GLuint, GLuint, GLuint); - - //! clear objToWorld allocate memmory - void clear(); - - //! Merge Mutli line in one - void mergeLines(QString*, QTextStream*); - - //! Add the current Obj mesh to the world - void addCurrentObjMeshToWorld(); - - - -////////////////////////////////////////////////////////////////////// -// Qt Signals -////////////////////////////////////////////////////////////////////// - signals: - void currentQuantum(int); - -////////////////////////////////////////////////////////////////////// -// Private members -////////////////////////////////////////////////////////////////////// -private: - //! pointer to a GLC_World - GLC_World* m_pWorld; - - //! The Obj File name - QString m_FileName; - - //! the Obj Mtl loader - GLC_ObjMtlLoader* m_pMtlLoader; - - //! The current line number - int m_CurrentLineNumber; - - //! The current mesh - CurrentObjMesh* m_pCurrentObjMesh; - - //! Face type - FaceType m_FaceType; - - //! List of material already used by the current mesh - QHash m_CurrentMeshMaterials; - - //! Current material name - QString m_CurrentMaterialName; - - //! The list of attached file name - QStringList m_ListOfAttachedFileName; - - //! The position bulk data - QList m_Positions; - - //! The normal bulk data - QList m_Normals; - - //! The texture coordinate bulk data - QList m_Texels; -}; - -// To use ObjVertice as a QHash key -inline bool operator==(const GLC_ObjToWorld::ObjVertice& vertice1, const GLC_ObjToWorld::ObjVertice& vertice2) -{ return (vertice1.m_Values == vertice2.m_Values);} - -inline uint qHash(const GLC_ObjToWorld::ObjVertice& vertice) -{ return qHash(QString::number(vertice.m_Values.at(0)) + QString::number(vertice.m_Values.at(1)) + QString::number(vertice.m_Values.at(2)));} - - -#endif /*GLC_OBJTOWORLD_H_*/ +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + Version 2.0.0, packaged on July 2010. + + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ + +//! \file glc_objToworld.h interface for the GLC_ObjToWorld class. + +#ifndef GLC_OBJTOWORLD_H_ +#define GLC_OBJTOWORLD_H_ + +#include +#include +#include +#include +#include +#include + +#include "../maths/glc_vector3d.h" +#include "../maths/glc_vector2df.h" +#include "../maths/glc_vector3df.h" +#include "../geometry/glc_mesh.h" + +#include "../glc_config.h" + +enum FaceType +{ + notSet, + coordinate, + coordinateAndTexture, + coordinateAndNormal, + coordinateAndTextureAndNormal +}; + +class GLC_World; +class GLC_ObjMtlLoader; +class QGLContext; + +////////////////////////////////////////////////////////////////////// +//! \class GLC_ObjToWorld +/*! \brief GLC_ObjToWorld : Create an GLC_World from obj file */ + +/*! An GLC_ObjToWorld extract the meshs from an .obj file \n + * List of elements extracted from the OBJ + * - Vertex + * - Face + * - Texture coordinate + * - Normal coordinate + */ +////////////////////////////////////////////////////////////////////// +class GLC_LIB_EXPORT GLC_ObjToWorld : public QObject +{ + Q_OBJECT + +public: + // OBJ Vertice (Position index, Normal index and TexCoord index) + struct ObjVertice + { + ObjVertice() + : m_Values(3) + { + m_Values[0]= 0; + m_Values[1]= 0; + m_Values[2]= 0; + } + ObjVertice(int v1, int v2, int v3) + : m_Values(3) + { + m_Values[0]= v1; + m_Values[1]= v2; + m_Values[2]= v3; + } + + QVector m_Values; + }; + + // Material assignement + struct MatOffsetSize + { + MatOffsetSize() + : m_Offset(0) + , m_size(0) + {} + int m_Offset; + int m_size; + }; + + // Current OBJ Mesh + struct CurrentObjMesh + { + CurrentObjMesh(const QString materialName) + : m_pMesh(new GLC_Mesh()) + , m_Positions() + , m_Normals() + , m_Texels() + , m_Index() + , m_pLastOffsetSize(new MatOffsetSize()) + , m_Materials() + , m_NextFreeIndex(0) + , m_ObjVerticeIndexMap() + { + m_Materials.insert(materialName, m_pLastOffsetSize); + } + ~CurrentObjMesh() + { + QHash::iterator i= m_Materials.begin(); + while (m_Materials.constEnd() != i) + { + delete i.value(); + ++i; + } + } + GLC_Mesh* m_pMesh; + QList m_Positions; + QList m_Normals; + QList m_Texels; + //! The index of the current Mesh + IndexList m_Index; + // Pointer to the last matOffsetSize + MatOffsetSize* m_pLastOffsetSize; + // QHash containing material id and associated offset and size + QHash m_Materials; + //! The next free index + int m_NextFreeIndex; + //! The Hash table of obj vertice mapping to index + QHash m_ObjVerticeIndexMap; + }; + +////////////////////////////////////////////////////////////////////// +/*! @name Constructor / Destructor */ +//@{ +////////////////////////////////////////////////////////////////////// + +public: + GLC_ObjToWorld(); + virtual ~GLC_ObjToWorld(); +//@} + +////////////////////////////////////////////////////////////////////// +/*! \name Set Functions*/ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Create an GLC_World from an input OBJ File + GLC_World* CreateWorldFromObj(QFile &file); + + //! Get the list of attached files + inline QStringList listOfAttachedFileName() const{return m_ListOfAttachedFileName;} +//@} + +////////////////////////////////////////////////////////////////////// +// Private services functions +////////////////////////////////////////////////////////////////////// +private: + //! Return the name of the mtl file + QString getMtlLibFileName(QString); + + //! Scan a line previously extracted from OBJ file + void scanLigne(QString &); + + //! Change current group + void changeGroup(QString); + + //! Extract a 3D Vector from a string + QList extract3dVect(QString &); + + //! Extract a 2D Vector from a string + QList extract2dVect(QString &); + + //! Extract a face from a string + void extractFaceIndex(QString &); + + //! Set Current material index + void setCurrentMaterial(QString &line); + + //! Extract a vertex from a string + void extractVertexIndex(QString ligne, int &Coordinate, int &Normal, int &TextureCoordinate); + + //! set the OBJ File type + void setObjType(QString &); + + //! compute face normal + GLC_Vector3df computeNormal(GLuint, GLuint, GLuint); + + //! clear objToWorld allocate memmory + void clear(); + + //! Merge Mutli line in one + void mergeLines(QString*, QTextStream*); + + //! Add the current Obj mesh to the world + void addCurrentObjMeshToWorld(); + + + +////////////////////////////////////////////////////////////////////// +// Qt Signals +////////////////////////////////////////////////////////////////////// + signals: + void currentQuantum(int); + +////////////////////////////////////////////////////////////////////// +// Private members +////////////////////////////////////////////////////////////////////// +private: + //! pointer to a GLC_World + GLC_World* m_pWorld; + + //! The Obj File name + QString m_FileName; + + //! the Obj Mtl loader + GLC_ObjMtlLoader* m_pMtlLoader; + + //! The current line number + int m_CurrentLineNumber; + + //! The current mesh + CurrentObjMesh* m_pCurrentObjMesh; + + //! Face type + FaceType m_FaceType; + + //! List of material already used by the current mesh + QHash m_CurrentMeshMaterials; + + //! Current material name + QString m_CurrentMaterialName; + + //! The list of attached file name + QStringList m_ListOfAttachedFileName; + + //! The position bulk data + QList m_Positions; + + //! The normal bulk data + QList m_Normals; + + //! The texture coordinate bulk data + QList m_Texels; +}; + +// To use ObjVertice as a QHash key +inline bool operator==(const GLC_ObjToWorld::ObjVertice& vertice1, const GLC_ObjToWorld::ObjVertice& vertice2) +{ return (vertice1.m_Values == vertice2.m_Values);} + +inline uint qHash(const GLC_ObjToWorld::ObjVertice& vertice) +{ return qHash(QString::number(vertice.m_Values.at(0)) + QString::number(vertice.m_Values.at(1)) + QString::number(vertice.m_Values.at(2)));} + + +#endif /*GLC_OBJTOWORLD_H_*/ diff --git a/ground/openpilotgcs/src/libs/glc_lib/sceneGraph/glc_world.cpp b/ground/openpilotgcs/src/libs/glc_lib/sceneGraph/glc_world.cpp index 24dcafe0f..ea3157883 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/sceneGraph/glc_world.cpp +++ b/ground/openpilotgcs/src/libs/glc_lib/sceneGraph/glc_world.cpp @@ -1,100 +1,100 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ - -//! \file glc_world.cpp implementation of the GLC_World class. - -#include "glc_world.h" -#include "glc_structinstance.h" -#include "glc_structreference.h" - -// Default constructor -GLC_World::GLC_World() -: m_pWorldHandle(new GLC_WorldHandle()) -, m_pRoot(new GLC_StructOccurence()) -{ - m_pRoot->setWorldHandle(m_pWorldHandle); -} - -// Copy constructor -GLC_World::GLC_World(const GLC_World& world) -: m_pWorldHandle(world.m_pWorldHandle) -, m_pRoot(world.m_pRoot) -{ - //qDebug() << "GLC_World::GLC_World() : " << (*m_pNumberOfWorld) << " " << this; - // Increment the number of world - m_pWorldHandle->increment(); - -} - -GLC_World::~GLC_World() -{ - // Decrement the number of world - m_pWorldHandle->decrement(); - if (m_pWorldHandle->isOrphan()) - { - // this is the last World, delete the root product and collection - //m_pWorldHandle->collection()->clear(); // Clear collection first (performance) - delete m_pRoot; - delete m_pWorldHandle; - } -} - -// Merge this world with another world -void GLC_World::mergeWithAnotherWorld(GLC_World& anotherWorld) -{ - GLC_StructOccurence* pAnotherRoot= anotherWorld.rootOccurence(); - if (pAnotherRoot->childCount() > 0) - { - QList childs= pAnotherRoot->children(); - const int size= childs.size(); - for (int i= 0; i < size; ++i) - { - m_pRoot->addChild(childs.at(i)->clone(m_pWorldHandle, false)); - } - m_pRoot->updateChildrenAbsoluteMatrix(); - } - else - { - m_pRoot->addChild(anotherWorld.rootOccurence()->clone(m_pWorldHandle, false)); - } -} - -// Assignment operator -GLC_World& GLC_World::operator=(const GLC_World& world) -{ - if (this != &world) - { - // Decrement the number of world - m_pWorldHandle->decrement(); - if (m_pWorldHandle->isOrphan()) - { - // this is the last World, delete the root product and collection - //m_pWorldHandle->collection()->clear(); // Clear collection first (performance) - delete m_pRoot; - delete m_pWorldHandle; - } - m_pRoot= world.m_pRoot; - m_pWorldHandle= world.m_pWorldHandle; - m_pWorldHandle->increment(); - } - return *this; -} +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ + +//! \file glc_world.cpp implementation of the GLC_World class. + +#include "glc_world.h" +#include "glc_structinstance.h" +#include "glc_structreference.h" + +// Default constructor +GLC_World::GLC_World() +: m_pWorldHandle(new GLC_WorldHandle()) +, m_pRoot(new GLC_StructOccurence()) +{ + m_pRoot->setWorldHandle(m_pWorldHandle); +} + +// Copy constructor +GLC_World::GLC_World(const GLC_World& world) +: m_pWorldHandle(world.m_pWorldHandle) +, m_pRoot(world.m_pRoot) +{ + //qDebug() << "GLC_World::GLC_World() : " << (*m_pNumberOfWorld) << " " << this; + // Increment the number of world + m_pWorldHandle->increment(); + +} + +GLC_World::~GLC_World() +{ + // Decrement the number of world + m_pWorldHandle->decrement(); + if (m_pWorldHandle->isOrphan()) + { + // this is the last World, delete the root product and collection + //m_pWorldHandle->collection()->clear(); // Clear collection first (performance) + delete m_pRoot; + delete m_pWorldHandle; + } +} + +// Merge this world with another world +void GLC_World::mergeWithAnotherWorld(GLC_World& anotherWorld) +{ + GLC_StructOccurence* pAnotherRoot= anotherWorld.rootOccurence(); + if (pAnotherRoot->childCount() > 0) + { + QList childs= pAnotherRoot->children(); + const int size= childs.size(); + for (int i= 0; i < size; ++i) + { + m_pRoot->addChild(childs.at(i)->clone(m_pWorldHandle, false)); + } + m_pRoot->updateChildrenAbsoluteMatrix(); + } + else + { + m_pRoot->addChild(anotherWorld.rootOccurence()->clone(m_pWorldHandle, false)); + } +} + +// Assignment operator +GLC_World& GLC_World::operator=(const GLC_World& world) +{ + if (this != &world) + { + // Decrement the number of world + m_pWorldHandle->decrement(); + if (m_pWorldHandle->isOrphan()) + { + // this is the last World, delete the root product and collection + //m_pWorldHandle->collection()->clear(); // Clear collection first (performance) + delete m_pRoot; + delete m_pWorldHandle; + } + m_pRoot= world.m_pRoot; + m_pWorldHandle= world.m_pWorldHandle; + m_pWorldHandle->increment(); + } + return *this; +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/sceneGraph/glc_world.h b/ground/openpilotgcs/src/libs/glc_lib/sceneGraph/glc_world.h index 8f9efe94c..714440f5a 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/sceneGraph/glc_world.h +++ b/ground/openpilotgcs/src/libs/glc_lib/sceneGraph/glc_world.h @@ -1,285 +1,285 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ - -//! \file glc_world.h interface for the GLC_World class. - -#ifndef GLC_WORLD_H_ -#define GLC_WORLD_H_ - -#include "glc_3dviewcollection.h" -#include "glc_structoccurence.h" -#include "glc_structreference.h" -#include "glc_structinstance.h" -#include "glc_worldhandle.h" - -#include "../glc_config.h" - -////////////////////////////////////////////////////////////////////// -//! \class GLC_World -/*! \brief GLC_World : The Root of GLC_Lib Scene Graph*/ -/*! - * GLC_World contain : - * - The Scene root GLC_Product. - * - a GLC_3DViewCollection which manage all scene shapes (GLC_3DViewInstance) - * - */ -////////////////////////////////////////////////////////////////////// -class GLC_LIB_EXPORT GLC_World -{ -////////////////////////////////////////////////////////////////////// -/*! @name Constructor / Destructor */ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Default constructor - GLC_World(); - - //! Copy constructor - GLC_World(const GLC_World&); - - //! Destructor - virtual ~GLC_World(); -//@} - -////////////////////////////////////////////////////////////////////// -/*! \name Get Functions*/ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Return the entire world Bounding Box - inline GLC_BoundingBox boundingBox() - { return m_pWorldHandle->collection()->boundingBox();} - - //! Return the root of the world - inline GLC_StructOccurence* rootOccurence() const - {return m_pRoot;} - - //! Return the world collection - inline GLC_3DViewCollection* collection() - {return m_pWorldHandle->collection();} - - //! Return the size of the world - inline int size() const - {return m_pWorldHandle->collection()->size();} - - //! Return true if the world is empty - inline bool isEmpty() const - {return m_pWorldHandle->collection()->isEmpty() && !m_pRoot->hasChild();} - - //! Return number of faces - inline int numberOfFaces() const - {return m_pRoot->numberOfFaces();} - - //! Return number of vertex - inline int numberOfVertex() const - {return m_pRoot->numberOfVertex();} - - //! Return the number of materials - inline int numberOfMaterials() const - {return m_pRoot->numberOfMaterials();} - - //! Return the list of material - inline QList listOfMaterials() const - {return m_pRoot->materialSet().toList();} - - //! Return list of world's instances - inline QList instancesHandle() const - {return m_pWorldHandle->collection()->instancesHandle();} - - //! Return all visible GLC_3DViewInstance from the world - inline QList visibleInstancesHandle() const - {return m_pWorldHandle->collection()->visibleInstancesHandle();} - - //! Return instances name from the specified shading group - inline QList instanceNamesFromShadingGroup(GLuint id) const - {return m_pWorldHandle->collection()->instanceNamesFromShadingGroup(id);} - - //! Return the number of used shading group - inline int numberOfUsedShadingGroup() const - {return m_pWorldHandle->collection()->numberOfUsedShadingGroup();} - - //! Return the worldHandle of this world - inline GLC_WorldHandle* worldHandle() - {return m_pWorldHandle;} - - //! Return the occurence specified by an id - /*! Id must be a valid identifier*/ - inline GLC_StructOccurence* occurence(GLC_uint id) const - {return m_pWorldHandle->getOccurence(id);} - - //! Return the list off occurences - inline QList listOfOccurence() const - {return m_pWorldHandle->occurences();} - - //! Return the number of occurence - inline int numberOfOccurence() const - {return m_pWorldHandle->numberOfOccurence();} - - //! Return true if the world contians specified id - inline int containsOccurence(GLC_uint id) const - {return m_pWorldHandle->containsOccurence(id);} - - //! Return the list of instance - inline QList instances() const - {return m_pWorldHandle->instances();} - - //! Return the list of Reference - inline QList references() const - {return m_pWorldHandle->references();} - - //! Return the number of body - inline int numberOfBody() const - {return m_pWorldHandle->numberOfBody();} - - //! Return the number of representation - inline int representationCount() const - {return m_pWorldHandle->representationCount();} - - //! Return the world Up vector - inline GLC_Vector3d upVector() const - {return m_pWorldHandle->upVector();} - - //! Return the number of selected occurence - int selectionSize() const - {return m_pWorldHandle->selectionSetHandle()->size();} - - //! Return true if the given occurence is selected - inline bool isSelected(const GLC_StructOccurence* pOccurence) const - {return m_pWorldHandle->selectionSetHandle()->contains(pOccurence);} - - //! Return true if the given occurence id is selected - inline bool isSelected(GLC_uint selectionId) const - {return m_pWorldHandle->selectionSetHandle()->contains(selectionId);} - - //! Return the list of selected occurences - inline QList selectedOccurenceList() const - {return m_pWorldHandle->selectionSetHandle()->occurencesList();} - - //! Return the list of selected occurences - inline QList selectedPrimitiveOccurenceList() const - {return m_pWorldHandle->selectionSetHandle()->occurencesListWithSelectedPrimitive();} - -//@} - -////////////////////////////////////////////////////////////////////// -/*! \name Set Functions*/ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Merge this world with another world - void mergeWithAnotherWorld(GLC_World &); - - //! Reverse worlds part normal - inline void reversePartNormal() {m_pRoot->reverseNormals();} - - //! Clear this world - GLC_World& clear() {return *this= GLC_World();} - - //! Set the World root Name - inline void setRootName(const QString& name) - {m_pRoot->setName(name);} - - //! Set the world Up Vector - inline void setUpVector(const GLC_Vector3d& vect) - {m_pWorldHandle->setUpVector(vect);} - - //! Set the attached viewport of this world - inline void setAttachedViewport(GLC_Viewport* pViewport) - {m_pWorldHandle->setAttachedViewport(pViewport);} - - //! Select the given occurence - /*! The given occurence must belong to the world handle of this world*/ - inline void select(const GLC_StructOccurence* pOccurence) - {m_pWorldHandle->select(pOccurence->id());} - - //! Select the given occurence id - /*! The given occurence id must belong to the world handle of this world*/ - inline void select(GLC_uint occurenceId) - {m_pWorldHandle->select(occurenceId);} - - //! Unselect the given occurence id - /*! The given occurence id must belong to the world handle of this world*/ - inline void unselect(GLC_uint occurenceId) - {m_pWorldHandle->unselect(occurenceId);} - - //! Select all occurence of this world with a 3DViewInstance - inline void selectAllWith3DViewInstance() - {m_pWorldHandle->selectAllWith3DViewInstance(true);} - - //! Select all occurence of this world with a 3DViewInstance in the current show state - inline void selectAllWith3DViewInstanceInCurrentShowState() - {m_pWorldHandle->selectAllWith3DViewInstance(false);} - - //! Unselect all occurence of this world - inline void unselectAll() - {m_pWorldHandle->unselectAll();} - - //! Show / Hide selected 3DViewInstance - inline void showHideSelected3DViewInstance() - {m_pWorldHandle->showHideSelected3DViewInstance();} - - //! Show selected 3DViewInstance - inline void showSelected3DViewInstance() - {m_pWorldHandle->setSelected3DViewInstanceVisibility(true);} - - //! Hide selected 3DViewInstance - inline void hideSelected3DViewInstance() - {m_pWorldHandle->setSelected3DViewInstanceVisibility(false);} - - -//@} - -////////////////////////////////////////////////////////////////////// -/*! @name Operator Overload */ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Assignement operator - GLC_World& operator=(const GLC_World&); -//@} - -////////////////////////////////////////////////////////////////////// -/*! \name OpenGL Functions*/ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Display the world - inline void render(GLuint groupId, glc::RenderFlag renderFlag= glc::ShadingFlag) - {m_pWorldHandle->collection()->render(groupId, renderFlag);} - - //! Display the world's shader group - inline void renderShaderGroup(glc::RenderFlag renderFlag= glc::ShadingFlag) - {m_pWorldHandle->collection()->renderShaderGroup(renderFlag);} - -//@} -////////////////////////////////////////////////////////////////////// -// private members -////////////////////////////////////////////////////////////////////// -private: - //! The World Handle - GLC_WorldHandle* m_pWorldHandle; - - //! The root of the structure - GLC_StructOccurence* m_pRoot; -}; - -#endif /*GLC_WORLD_H_*/ +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ + +//! \file glc_world.h interface for the GLC_World class. + +#ifndef GLC_WORLD_H_ +#define GLC_WORLD_H_ + +#include "glc_3dviewcollection.h" +#include "glc_structoccurence.h" +#include "glc_structreference.h" +#include "glc_structinstance.h" +#include "glc_worldhandle.h" + +#include "../glc_config.h" + +////////////////////////////////////////////////////////////////////// +//! \class GLC_World +/*! \brief GLC_World : The Root of GLC_Lib Scene Graph*/ +/*! + * GLC_World contain : + * - The Scene root GLC_Product. + * - a GLC_3DViewCollection which manage all scene shapes (GLC_3DViewInstance) + * + */ +////////////////////////////////////////////////////////////////////// +class GLC_LIB_EXPORT GLC_World +{ +////////////////////////////////////////////////////////////////////// +/*! @name Constructor / Destructor */ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Default constructor + GLC_World(); + + //! Copy constructor + GLC_World(const GLC_World&); + + //! Destructor + virtual ~GLC_World(); +//@} + +////////////////////////////////////////////////////////////////////// +/*! \name Get Functions*/ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Return the entire world Bounding Box + inline GLC_BoundingBox boundingBox() + { return m_pWorldHandle->collection()->boundingBox();} + + //! Return the root of the world + inline GLC_StructOccurence* rootOccurence() const + {return m_pRoot;} + + //! Return the world collection + inline GLC_3DViewCollection* collection() + {return m_pWorldHandle->collection();} + + //! Return the size of the world + inline int size() const + {return m_pWorldHandle->collection()->size();} + + //! Return true if the world is empty + inline bool isEmpty() const + {return m_pWorldHandle->collection()->isEmpty() && !m_pRoot->hasChild();} + + //! Return number of faces + inline int numberOfFaces() const + {return m_pRoot->numberOfFaces();} + + //! Return number of vertex + inline int numberOfVertex() const + {return m_pRoot->numberOfVertex();} + + //! Return the number of materials + inline int numberOfMaterials() const + {return m_pRoot->numberOfMaterials();} + + //! Return the list of material + inline QList listOfMaterials() const + {return m_pRoot->materialSet().toList();} + + //! Return list of world's instances + inline QList instancesHandle() const + {return m_pWorldHandle->collection()->instancesHandle();} + + //! Return all visible GLC_3DViewInstance from the world + inline QList visibleInstancesHandle() const + {return m_pWorldHandle->collection()->visibleInstancesHandle();} + + //! Return instances name from the specified shading group + inline QList instanceNamesFromShadingGroup(GLuint id) const + {return m_pWorldHandle->collection()->instanceNamesFromShadingGroup(id);} + + //! Return the number of used shading group + inline int numberOfUsedShadingGroup() const + {return m_pWorldHandle->collection()->numberOfUsedShadingGroup();} + + //! Return the worldHandle of this world + inline GLC_WorldHandle* worldHandle() + {return m_pWorldHandle;} + + //! Return the occurence specified by an id + /*! Id must be a valid identifier*/ + inline GLC_StructOccurence* occurence(GLC_uint id) const + {return m_pWorldHandle->getOccurence(id);} + + //! Return the list off occurences + inline QList listOfOccurence() const + {return m_pWorldHandle->occurences();} + + //! Return the number of occurence + inline int numberOfOccurence() const + {return m_pWorldHandle->numberOfOccurence();} + + //! Return true if the world contians specified id + inline int containsOccurence(GLC_uint id) const + {return m_pWorldHandle->containsOccurence(id);} + + //! Return the list of instance + inline QList instances() const + {return m_pWorldHandle->instances();} + + //! Return the list of Reference + inline QList references() const + {return m_pWorldHandle->references();} + + //! Return the number of body + inline int numberOfBody() const + {return m_pWorldHandle->numberOfBody();} + + //! Return the number of representation + inline int representationCount() const + {return m_pWorldHandle->representationCount();} + + //! Return the world Up vector + inline GLC_Vector3d upVector() const + {return m_pWorldHandle->upVector();} + + //! Return the number of selected occurence + int selectionSize() const + {return m_pWorldHandle->selectionSetHandle()->size();} + + //! Return true if the given occurence is selected + inline bool isSelected(const GLC_StructOccurence* pOccurence) const + {return m_pWorldHandle->selectionSetHandle()->contains(pOccurence);} + + //! Return true if the given occurence id is selected + inline bool isSelected(GLC_uint selectionId) const + {return m_pWorldHandle->selectionSetHandle()->contains(selectionId);} + + //! Return the list of selected occurences + inline QList selectedOccurenceList() const + {return m_pWorldHandle->selectionSetHandle()->occurencesList();} + + //! Return the list of selected occurences + inline QList selectedPrimitiveOccurenceList() const + {return m_pWorldHandle->selectionSetHandle()->occurencesListWithSelectedPrimitive();} + +//@} + +////////////////////////////////////////////////////////////////////// +/*! \name Set Functions*/ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Merge this world with another world + void mergeWithAnotherWorld(GLC_World &); + + //! Reverse worlds part normal + inline void reversePartNormal() {m_pRoot->reverseNormals();} + + //! Clear this world + GLC_World& clear() {return *this= GLC_World();} + + //! Set the World root Name + inline void setRootName(const QString& name) + {m_pRoot->setName(name);} + + //! Set the world Up Vector + inline void setUpVector(const GLC_Vector3d& vect) + {m_pWorldHandle->setUpVector(vect);} + + //! Set the attached viewport of this world + inline void setAttachedViewport(GLC_Viewport* pViewport) + {m_pWorldHandle->setAttachedViewport(pViewport);} + + //! Select the given occurence + /*! The given occurence must belong to the world handle of this world*/ + inline void select(const GLC_StructOccurence* pOccurence) + {m_pWorldHandle->select(pOccurence->id());} + + //! Select the given occurence id + /*! The given occurence id must belong to the world handle of this world*/ + inline void select(GLC_uint occurenceId) + {m_pWorldHandle->select(occurenceId);} + + //! Unselect the given occurence id + /*! The given occurence id must belong to the world handle of this world*/ + inline void unselect(GLC_uint occurenceId) + {m_pWorldHandle->unselect(occurenceId);} + + //! Select all occurence of this world with a 3DViewInstance + inline void selectAllWith3DViewInstance() + {m_pWorldHandle->selectAllWith3DViewInstance(true);} + + //! Select all occurence of this world with a 3DViewInstance in the current show state + inline void selectAllWith3DViewInstanceInCurrentShowState() + {m_pWorldHandle->selectAllWith3DViewInstance(false);} + + //! Unselect all occurence of this world + inline void unselectAll() + {m_pWorldHandle->unselectAll();} + + //! Show / Hide selected 3DViewInstance + inline void showHideSelected3DViewInstance() + {m_pWorldHandle->showHideSelected3DViewInstance();} + + //! Show selected 3DViewInstance + inline void showSelected3DViewInstance() + {m_pWorldHandle->setSelected3DViewInstanceVisibility(true);} + + //! Hide selected 3DViewInstance + inline void hideSelected3DViewInstance() + {m_pWorldHandle->setSelected3DViewInstanceVisibility(false);} + + +//@} + +////////////////////////////////////////////////////////////////////// +/*! @name Operator Overload */ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Assignement operator + GLC_World& operator=(const GLC_World&); +//@} + +////////////////////////////////////////////////////////////////////// +/*! \name OpenGL Functions*/ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Display the world + inline void render(GLuint groupId, glc::RenderFlag renderFlag= glc::ShadingFlag) + {m_pWorldHandle->collection()->render(groupId, renderFlag);} + + //! Display the world's shader group + inline void renderShaderGroup(glc::RenderFlag renderFlag= glc::ShadingFlag) + {m_pWorldHandle->collection()->renderShaderGroup(renderFlag);} + +//@} +////////////////////////////////////////////////////////////////////// +// private members +////////////////////////////////////////////////////////////////////// +private: + //! The World Handle + GLC_WorldHandle* m_pWorldHandle; + + //! The root of the structure + GLC_StructOccurence* m_pRoot; +}; + +#endif /*GLC_WORLD_H_*/ diff --git a/ground/openpilotgcs/src/libs/glc_lib/shading/glc_selectionmaterial.cpp b/ground/openpilotgcs/src/libs/glc_lib/shading/glc_selectionmaterial.cpp index 7b341e5d7..22ccc77b4 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/shading/glc_selectionmaterial.cpp +++ b/ground/openpilotgcs/src/libs/glc_lib/shading/glc_selectionmaterial.cpp @@ -1,180 +1,180 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ -//! \file glc_selectionmaterial.cpp implementation of the GLC_SelectionMaterial class. - -#include - -#include "glc_selectionmaterial.h" -#include "glc_material.h" - - -QHash GLC_SelectionMaterial::m_SelectionShaderHash; -GLC_uint GLC_SelectionMaterial::m_SelectionMaterialId= 0; -GLC_Material* GLC_SelectionMaterial::m_pMaterial= NULL; - -GLC_SelectionMaterial::GLC_SelectionMaterial() -{ - -} - -void GLC_SelectionMaterial::useMaterial(GLC_Material* pMaterial) -{ - if (0 == m_SelectionMaterialId) - { - m_SelectionMaterialId= glc::GLC_GenUserID(); - } - Q_ASSERT(NULL != pMaterial); - if (NULL != m_pMaterial) - { - m_pMaterial->delUsage(m_SelectionMaterialId); - if (m_pMaterial->isUnused()) - { - delete m_pMaterial; - } - } - m_pMaterial= pMaterial; - m_pMaterial->addUsage(m_SelectionMaterialId); -} - -void GLC_SelectionMaterial::useDefautSelectionColor() -{ - if (NULL != m_pMaterial) - { - m_pMaterial->delUsage(m_SelectionMaterialId); - if (m_pMaterial->isUnused()) - { - delete m_pMaterial; - } - m_pMaterial= NULL; - } -} - - -// Execute OpenGL Material -void GLC_SelectionMaterial::glExecute() -{ - if (NULL != m_pMaterial) - { - m_pMaterial->glExecute(); - } - else - { - // Use default selection color - static GLfloat pAmbientColor[4]= {1.0f, 0.376f, 0.223f, 1.0f}; - - static GLfloat pDiffuseColor[4]= {1.0f, 0.376f, 0.223f, 1.0f}; - - static GLfloat pSpecularColor[4]= {1.0f, 1.0f, 1.0f, 1.0f}; - - static GLfloat pLightEmission[4]= {0.0f, 0.0f, 0.0f, 1.0f}; - - static float shininess= 50.0f; - - glColor4fv(pAmbientColor); - - glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT, pAmbientColor); - glMaterialfv(GL_FRONT_AND_BACK, GL_DIFFUSE, pDiffuseColor); - glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR, pSpecularColor); - glMaterialfv(GL_FRONT_AND_BACK, GL_EMISSION, pLightEmission); - glMaterialfv(GL_FRONT_AND_BACK, GL_SHININESS, &shininess); - } -} - -void GLC_SelectionMaterial::initShader(const QGLContext* pContext) -{ - Q_ASSERT(m_SelectionShaderHash.contains(pContext)); - m_SelectionShaderHash.value(pContext)->createAndCompileProgrammShader(); -} - -void GLC_SelectionMaterial::setShaders(QFile& vertex, QFile& fragment, const QGLContext* pContext) -{ - if (m_SelectionShaderHash.contains(pContext)) - { - deleteShader(pContext); - } - GLC_Shader* pShader= new GLC_Shader; - - pShader->setVertexAndFragmentShader(vertex, fragment); - m_SelectionShaderHash.insert(pContext, pShader); -} - - -void GLC_SelectionMaterial::useShader() -{ - QGLContext* pContext= const_cast(QGLContext::currentContext()); - Q_ASSERT(NULL != pContext); - Q_ASSERT(pContext->isValid()); - if(!m_SelectionShaderHash.contains(pContext)) - { - Q_ASSERT(pContext->isSharing()); - pContext= sharingContext(pContext); - Q_ASSERT(NULL != pContext); - } - - m_SelectionShaderHash.value(pContext)->use(); -} - -void GLC_SelectionMaterial::unUseShader() -{ - QGLContext* pContext= const_cast(QGLContext::currentContext()); - Q_ASSERT(NULL != pContext); - Q_ASSERT(pContext->isValid()); - if(!m_SelectionShaderHash.contains(pContext)) - { - Q_ASSERT(pContext->isSharing()); - pContext= sharingContext(pContext); - Q_ASSERT(NULL != pContext); - } - - m_SelectionShaderHash.value(pContext)->unuse(); -} - -////////////////////////////////////////////////////////////////////// -// Private services fonction -////////////////////////////////////////////////////////////////////// -QGLContext* GLC_SelectionMaterial::sharingContext(const QGLContext* pContext) -{ - QGLContext* pSharingContext= NULL; - QHash::const_iterator iContext= m_SelectionShaderHash.constBegin(); - - while ((NULL == pSharingContext) && (iContext != m_SelectionShaderHash.constEnd())) - { - const QGLContext* pCurrentContext= iContext.key(); - if (QGLContext::areSharing(pContext, pCurrentContext)) - { - pSharingContext= const_cast(pCurrentContext); - } - ++iContext; - } - - return pSharingContext; -} - -//! delete shader -void GLC_SelectionMaterial::deleteShader(const QGLContext* pContext) -{ - Q_ASSERT(m_SelectionShaderHash.contains(pContext)); - GLC_Shader* pShader= m_SelectionShaderHash.value(pContext); - pShader->deleteShader(); - delete pShader; - m_SelectionShaderHash.remove(pContext); -} +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ +//! \file glc_selectionmaterial.cpp implementation of the GLC_SelectionMaterial class. + +#include + +#include "glc_selectionmaterial.h" +#include "glc_material.h" + + +QHash GLC_SelectionMaterial::m_SelectionShaderHash; +GLC_uint GLC_SelectionMaterial::m_SelectionMaterialId= 0; +GLC_Material* GLC_SelectionMaterial::m_pMaterial= NULL; + +GLC_SelectionMaterial::GLC_SelectionMaterial() +{ + +} + +void GLC_SelectionMaterial::useMaterial(GLC_Material* pMaterial) +{ + if (0 == m_SelectionMaterialId) + { + m_SelectionMaterialId= glc::GLC_GenUserID(); + } + Q_ASSERT(NULL != pMaterial); + if (NULL != m_pMaterial) + { + m_pMaterial->delUsage(m_SelectionMaterialId); + if (m_pMaterial->isUnused()) + { + delete m_pMaterial; + } + } + m_pMaterial= pMaterial; + m_pMaterial->addUsage(m_SelectionMaterialId); +} + +void GLC_SelectionMaterial::useDefautSelectionColor() +{ + if (NULL != m_pMaterial) + { + m_pMaterial->delUsage(m_SelectionMaterialId); + if (m_pMaterial->isUnused()) + { + delete m_pMaterial; + } + m_pMaterial= NULL; + } +} + + +// Execute OpenGL Material +void GLC_SelectionMaterial::glExecute() +{ + if (NULL != m_pMaterial) + { + m_pMaterial->glExecute(); + } + else + { + // Use default selection color + static GLfloat pAmbientColor[4]= {1.0f, 0.376f, 0.223f, 1.0f}; + + static GLfloat pDiffuseColor[4]= {1.0f, 0.376f, 0.223f, 1.0f}; + + static GLfloat pSpecularColor[4]= {1.0f, 1.0f, 1.0f, 1.0f}; + + static GLfloat pLightEmission[4]= {0.0f, 0.0f, 0.0f, 1.0f}; + + static float shininess= 50.0f; + + glColor4fv(pAmbientColor); + + glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT, pAmbientColor); + glMaterialfv(GL_FRONT_AND_BACK, GL_DIFFUSE, pDiffuseColor); + glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR, pSpecularColor); + glMaterialfv(GL_FRONT_AND_BACK, GL_EMISSION, pLightEmission); + glMaterialfv(GL_FRONT_AND_BACK, GL_SHININESS, &shininess); + } +} + +void GLC_SelectionMaterial::initShader(const QGLContext* pContext) +{ + Q_ASSERT(m_SelectionShaderHash.contains(pContext)); + m_SelectionShaderHash.value(pContext)->createAndCompileProgrammShader(); +} + +void GLC_SelectionMaterial::setShaders(QFile& vertex, QFile& fragment, const QGLContext* pContext) +{ + if (m_SelectionShaderHash.contains(pContext)) + { + deleteShader(pContext); + } + GLC_Shader* pShader= new GLC_Shader; + + pShader->setVertexAndFragmentShader(vertex, fragment); + m_SelectionShaderHash.insert(pContext, pShader); +} + + +void GLC_SelectionMaterial::useShader() +{ + QGLContext* pContext= const_cast(QGLContext::currentContext()); + Q_ASSERT(NULL != pContext); + Q_ASSERT(pContext->isValid()); + if(!m_SelectionShaderHash.contains(pContext)) + { + Q_ASSERT(pContext->isSharing()); + pContext= sharingContext(pContext); + Q_ASSERT(NULL != pContext); + } + + m_SelectionShaderHash.value(pContext)->use(); +} + +void GLC_SelectionMaterial::unUseShader() +{ + QGLContext* pContext= const_cast(QGLContext::currentContext()); + Q_ASSERT(NULL != pContext); + Q_ASSERT(pContext->isValid()); + if(!m_SelectionShaderHash.contains(pContext)) + { + Q_ASSERT(pContext->isSharing()); + pContext= sharingContext(pContext); + Q_ASSERT(NULL != pContext); + } + + m_SelectionShaderHash.value(pContext)->unuse(); +} + +////////////////////////////////////////////////////////////////////// +// Private services fonction +////////////////////////////////////////////////////////////////////// +QGLContext* GLC_SelectionMaterial::sharingContext(const QGLContext* pContext) +{ + QGLContext* pSharingContext= NULL; + QHash::const_iterator iContext= m_SelectionShaderHash.constBegin(); + + while ((NULL == pSharingContext) && (iContext != m_SelectionShaderHash.constEnd())) + { + const QGLContext* pCurrentContext= iContext.key(); + if (QGLContext::areSharing(pContext, pCurrentContext)) + { + pSharingContext= const_cast(pCurrentContext); + } + ++iContext; + } + + return pSharingContext; +} + +//! delete shader +void GLC_SelectionMaterial::deleteShader(const QGLContext* pContext) +{ + Q_ASSERT(m_SelectionShaderHash.contains(pContext)); + GLC_Shader* pShader= m_SelectionShaderHash.value(pContext); + pShader->deleteShader(); + delete pShader; + m_SelectionShaderHash.remove(pContext); +} diff --git a/ground/openpilotgcs/src/libs/glc_lib/shading/glc_selectionmaterial.h b/ground/openpilotgcs/src/libs/glc_lib/shading/glc_selectionmaterial.h index 01fd89f4d..ca3345742 100644 --- a/ground/openpilotgcs/src/libs/glc_lib/shading/glc_selectionmaterial.h +++ b/ground/openpilotgcs/src/libs/glc_lib/shading/glc_selectionmaterial.h @@ -1,108 +1,108 @@ -/**************************************************************************** - - This file is part of the GLC-lib library. - Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) - http://glc-lib.sourceforge.net - - GLC-lib is free software; you can redistribute it and/or modify - it under the terms of the GNU Lesser General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - GLC-lib is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU Lesser General Public License for more details. - - You should have received a copy of the GNU Lesser General Public License - along with GLC-lib; if not, write to the Free Software - Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -*****************************************************************************/ -//! \file glc_selectionmaterial.h interface for the GLC_SelectionMaterial class. - -#ifndef GLC_SELECTIONMATERIAL_H_ -#define GLC_SELECTIONMATERIAL_H_ - -#include -#include -#include - -#include "../glc_ext.h" -#include "glc_shader.h" - -#include "../glc_config.h" - -class QGLContext; -class GLC_Material; - -////////////////////////////////////////////////////////////////////// -//! \class GLC_SelectionMaterial -/*! \brief GLC_SelectionMaterial : Material used for selection feedback*/ - -////////////////////////////////////////////////////////////////////// - -class GLC_LIB_EXPORT GLC_SelectionMaterial -{ -private: - GLC_SelectionMaterial(); - - -////////////////////////////////////////////////////////////////////// -/*! \name Set Functions*/ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Use the given material as selection material - static void useMaterial(GLC_Material* pMaterial); - - //! Use the default selection color - /*! if a selection material is used, unused it*/ - static void useDefautSelectionColor(); - -//@} - -////////////////////////////////////////////////////////////////////// -/*! \name OpenGL Functions*/ -//@{ -////////////////////////////////////////////////////////////////////// -public: - //! Execute OpenGL Material - static void glExecute(); - //! Init shader - static void initShader(const QGLContext* pContext); - //! delete shader - static void deleteShader(const QGLContext* pContext); - //! Set shader - static void setShaders(QFile& vertex, QFile& fragment, const QGLContext* pContext); - //! Use shader - static void useShader(); - //! Unused shader - static void unUseShader(); - -//@} - -////////////////////////////////////////////////////////////////////// -// Private services fonction -////////////////////////////////////////////////////////////////////// -private: - //! Return the sharing context of the given context - static QGLContext* sharingContext(const QGLContext* pContext); - -////////////////////////////////////////////////////////////////////// -// Private members -////////////////////////////////////////////////////////////////////// - -private: - //! Selection Shader - static QHash m_SelectionShaderHash; - - //! Selection material id - static GLC_uint m_SelectionMaterialId; - - //! Material of this selection material - static GLC_Material* m_pMaterial; - -}; - -#endif /*GLC_SELECTIONMATERIAL_H_*/ +/**************************************************************************** + + This file is part of the GLC-lib library. + Copyright (C) 2005-2008 Laurent Ribon (laumaya@users.sourceforge.net) + http://glc-lib.sourceforge.net + + GLC-lib is free software; you can redistribute it and/or modify + it under the terms of the GNU Lesser General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + GLC-lib is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public License + along with GLC-lib; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + +*****************************************************************************/ +//! \file glc_selectionmaterial.h interface for the GLC_SelectionMaterial class. + +#ifndef GLC_SELECTIONMATERIAL_H_ +#define GLC_SELECTIONMATERIAL_H_ + +#include +#include +#include + +#include "../glc_ext.h" +#include "glc_shader.h" + +#include "../glc_config.h" + +class QGLContext; +class GLC_Material; + +////////////////////////////////////////////////////////////////////// +//! \class GLC_SelectionMaterial +/*! \brief GLC_SelectionMaterial : Material used for selection feedback*/ + +////////////////////////////////////////////////////////////////////// + +class GLC_LIB_EXPORT GLC_SelectionMaterial +{ +private: + GLC_SelectionMaterial(); + + +////////////////////////////////////////////////////////////////////// +/*! \name Set Functions*/ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Use the given material as selection material + static void useMaterial(GLC_Material* pMaterial); + + //! Use the default selection color + /*! if a selection material is used, unused it*/ + static void useDefautSelectionColor(); + +//@} + +////////////////////////////////////////////////////////////////////// +/*! \name OpenGL Functions*/ +//@{ +////////////////////////////////////////////////////////////////////// +public: + //! Execute OpenGL Material + static void glExecute(); + //! Init shader + static void initShader(const QGLContext* pContext); + //! delete shader + static void deleteShader(const QGLContext* pContext); + //! Set shader + static void setShaders(QFile& vertex, QFile& fragment, const QGLContext* pContext); + //! Use shader + static void useShader(); + //! Unused shader + static void unUseShader(); + +//@} + +////////////////////////////////////////////////////////////////////// +// Private services fonction +////////////////////////////////////////////////////////////////////// +private: + //! Return the sharing context of the given context + static QGLContext* sharingContext(const QGLContext* pContext); + +////////////////////////////////////////////////////////////////////// +// Private members +////////////////////////////////////////////////////////////////////// + +private: + //! Selection Shader + static QHash m_SelectionShaderHash; + + //! Selection material id + static GLC_uint m_SelectionMaterialId; + + //! Material of this selection material + static GLC_Material* m_pMaterial; + +}; + +#endif /*GLC_SELECTIONMATERIAL_H_*/ diff --git a/ground/openpilotgcs/src/libs/libqxt/src/berkeley/qxtbdbtree.cpp b/ground/openpilotgcs/src/libs/libqxt/src/berkeley/qxtbdbtree.cpp index 668571edf..7dd9a0522 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/berkeley/qxtbdbtree.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/berkeley/qxtbdbtree.cpp @@ -221,27 +221,27 @@ If insertion fails, an invalid iterator is returned. */ -/*! - \fn QxtBdbTreeIterator QxtBdbTreeIterator::erase() - TODO returns -*/ - -/*! - \fn void QxtBdbTreeIterator::invalidate() - TODO -*/ - -/*! - \fn quint64 QxtBdbTreeIterator::level() const - TODO returns -*/ - -/*! - \fn QxtBdbTreeIterator QxtBdbTreeIterator::prepend(const T& t) - TODO \a t -*/ - -/*! - \fn bool QxtBdbTreeIterator::setValue(T value) - TODO \a value -*/ +/*! + \fn QxtBdbTreeIterator QxtBdbTreeIterator::erase() + TODO returns +*/ + +/*! + \fn void QxtBdbTreeIterator::invalidate() + TODO +*/ + +/*! + \fn quint64 QxtBdbTreeIterator::level() const + TODO returns +*/ + +/*! + \fn QxtBdbTreeIterator QxtBdbTreeIterator::prepend(const T& t) + TODO \a t +*/ + +/*! + \fn bool QxtBdbTreeIterator::setValue(T value) + TODO \a value +*/ diff --git a/ground/openpilotgcs/src/libs/libqxt/src/core/qxtnull.cpp b/ground/openpilotgcs/src/libs/libqxt/src/core/qxtnull.cpp index 68f342be3..ad504770d 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/core/qxtnull.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/core/qxtnull.cpp @@ -1,27 +1,27 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtCore module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include "qxtnull.h" - -// nothing here +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtCore module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include "qxtnull.h" + +// nothing here diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication.cpp index 1f9be2465..65720f5e7 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication.cpp @@ -1,129 +1,129 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include "qxtapplication.h" -#include "qxtapplication_p.h" - -/*! - \class QxtApplication - \inmodule QxtGui - \brief The QxtApplication class is an extended QApplication with support for native event filters. - - QxtApplication lets you install native event filters. This gives an - easy and straightforward access to platform specific native events. - - \sa QxtNativeEventFilter - */ - -/*! - \fn QxtApplication::instance() - - Returns a pointer to the instance of the application object. - - A convenience macro \l qxtApp is also available. - */ - -/*! - \macro qxtApp - \relates QxtApplication - \inmodule QxtGui - - A global pointer referring to the unique application object. It is - equivalent to the pointer returned by QxtApplication::instance(). - - \sa QxtApplication::instance() -*/ - -/*! - Constructs a new QxtApplication with \a argc and \a argv. - - \sa QApplication::QApplication() - */ -QxtApplication::QxtApplication(int& argc, char** argv) - : QApplication(argc, argv) -{ -} - -/*! - Constructs a new QxtApplication with \a argc, \a argv and \a GUIenabled. - - \sa QApplication::QApplication() - */ -QxtApplication::QxtApplication(int& argc, char** argv, bool GUIenabled) - : QApplication(argc, argv, GUIenabled) -{ -} - -/*! - Constructs a new QxtApplication with \a argc, \a argv and \a type. - - \sa QApplication::QApplication() - */ -QxtApplication::QxtApplication(int& argc, char** argv, Type type) - : QApplication(argc, argv, type) -{ -} - -/*! - Destructs the QxtApplication. - - \sa QApplication::~QApplication() - */ -QxtApplication::~QxtApplication() -{ -} - -/*! - Installs a native event \a filter. - - A native event filter is an object that receives all native events before they reach - the application object. The filter can either stop the native event or forward it to - the application object. The filter receives native events via its platform specific - native event filter function. The native event filter function must return \c true - if the event should be filtered, (i.e. stopped); otherwise it must return \c false. - - If multiple native event filters are installed, the filter that was installed last - is activated first. - - \sa removeNativeEventFilter() -*/ -void QxtApplication::installNativeEventFilter(QxtNativeEventFilter* filter) -{ - if (!filter) - return; - - qxt_d().nativeFilters.removeAll(filter); - qxt_d().nativeFilters.prepend(filter); -} - -/*! - Removes a native event \a filter. The request is ignored if such a native - event filter has not been installed. - - \sa installNativeEventFilter() -*/ -void QxtApplication::removeNativeEventFilter(QxtNativeEventFilter* filter) -{ - qxt_d().nativeFilters.removeAll(filter); -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include "qxtapplication.h" +#include "qxtapplication_p.h" + +/*! + \class QxtApplication + \inmodule QxtGui + \brief The QxtApplication class is an extended QApplication with support for native event filters. + + QxtApplication lets you install native event filters. This gives an + easy and straightforward access to platform specific native events. + + \sa QxtNativeEventFilter + */ + +/*! + \fn QxtApplication::instance() + + Returns a pointer to the instance of the application object. + + A convenience macro \l qxtApp is also available. + */ + +/*! + \macro qxtApp + \relates QxtApplication + \inmodule QxtGui + + A global pointer referring to the unique application object. It is + equivalent to the pointer returned by QxtApplication::instance(). + + \sa QxtApplication::instance() +*/ + +/*! + Constructs a new QxtApplication with \a argc and \a argv. + + \sa QApplication::QApplication() + */ +QxtApplication::QxtApplication(int& argc, char** argv) + : QApplication(argc, argv) +{ +} + +/*! + Constructs a new QxtApplication with \a argc, \a argv and \a GUIenabled. + + \sa QApplication::QApplication() + */ +QxtApplication::QxtApplication(int& argc, char** argv, bool GUIenabled) + : QApplication(argc, argv, GUIenabled) +{ +} + +/*! + Constructs a new QxtApplication with \a argc, \a argv and \a type. + + \sa QApplication::QApplication() + */ +QxtApplication::QxtApplication(int& argc, char** argv, Type type) + : QApplication(argc, argv, type) +{ +} + +/*! + Destructs the QxtApplication. + + \sa QApplication::~QApplication() + */ +QxtApplication::~QxtApplication() +{ +} + +/*! + Installs a native event \a filter. + + A native event filter is an object that receives all native events before they reach + the application object. The filter can either stop the native event or forward it to + the application object. The filter receives native events via its platform specific + native event filter function. The native event filter function must return \c true + if the event should be filtered, (i.e. stopped); otherwise it must return \c false. + + If multiple native event filters are installed, the filter that was installed last + is activated first. + + \sa removeNativeEventFilter() +*/ +void QxtApplication::installNativeEventFilter(QxtNativeEventFilter* filter) +{ + if (!filter) + return; + + qxt_d().nativeFilters.removeAll(filter); + qxt_d().nativeFilters.prepend(filter); +} + +/*! + Removes a native event \a filter. The request is ignored if such a native + event filter has not been installed. + + \sa installNativeEventFilter() +*/ +void QxtApplication::removeNativeEventFilter(QxtNativeEventFilter* filter) +{ + qxt_d().nativeFilters.removeAll(filter); +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication.h index f455f5c59..75d2f8373 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication.h @@ -1,68 +1,68 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#ifndef QXTAPPLICATION_H -#define QXTAPPLICATION_H - -#include -#include "qxtglobal.h" - -class QxtApplicationPrivate; -class QxtNativeEventFilter; - -#define qxtApp (QxtApplication::instance()) - -class QXT_GUI_EXPORT QxtApplication : public QApplication -{ - Q_OBJECT - QXT_DECLARE_PRIVATE(QxtApplication) - -public: - QxtApplication(int& argc, char** argv); - QxtApplication(int& argc, char** argv, bool GUIenabled); - QxtApplication(int& argc, char** argv, Type type); -#if defined(Q_WS_X11) - explicit QxtApplication(Display* display, Qt::HANDLE visual = 0, Qt::HANDLE colormap = 0); - QxtApplication(Display* display, int& argc, char** argv, Qt::HANDLE visual = 0, Qt::HANDLE colormap = 0); -#endif // Q_WS_X11 - virtual ~QxtApplication(); - - void installNativeEventFilter(QxtNativeEventFilter* filter); - void removeNativeEventFilter(QxtNativeEventFilter* filter); - -#if defined(Q_WS_X11) - virtual bool x11EventFilter(XEvent* event); -#elif defined(Q_WS_WIN) - virtual bool winEventFilter(MSG* msg, long* result); -#elif defined(Q_WS_MAC) - virtual bool macEventFilter(EventHandlerCallRef caller, EventRef event); -#endif // Q_WS_* - - inline static QxtApplication* instance() - { - return qobject_cast(QApplication::instance()); - } -}; - -#endif // QXTAPPLICATION_H +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#ifndef QXTAPPLICATION_H +#define QXTAPPLICATION_H + +#include +#include "qxtglobal.h" + +class QxtApplicationPrivate; +class QxtNativeEventFilter; + +#define qxtApp (QxtApplication::instance()) + +class QXT_GUI_EXPORT QxtApplication : public QApplication +{ + Q_OBJECT + QXT_DECLARE_PRIVATE(QxtApplication) + +public: + QxtApplication(int& argc, char** argv); + QxtApplication(int& argc, char** argv, bool GUIenabled); + QxtApplication(int& argc, char** argv, Type type); +#if defined(Q_WS_X11) + explicit QxtApplication(Display* display, Qt::HANDLE visual = 0, Qt::HANDLE colormap = 0); + QxtApplication(Display* display, int& argc, char** argv, Qt::HANDLE visual = 0, Qt::HANDLE colormap = 0); +#endif // Q_WS_X11 + virtual ~QxtApplication(); + + void installNativeEventFilter(QxtNativeEventFilter* filter); + void removeNativeEventFilter(QxtNativeEventFilter* filter); + +#if defined(Q_WS_X11) + virtual bool x11EventFilter(XEvent* event); +#elif defined(Q_WS_WIN) + virtual bool winEventFilter(MSG* msg, long* result); +#elif defined(Q_WS_MAC) + virtual bool macEventFilter(EventHandlerCallRef caller, EventRef event); +#endif // Q_WS_* + + inline static QxtApplication* instance() + { + return qobject_cast(QApplication::instance()); + } +}; + +#endif // QXTAPPLICATION_H diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_mac.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_mac.cpp index 16b818c76..11c40aad0 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_mac.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_mac.cpp @@ -1,26 +1,26 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** ****************************************************************************/ #include "qxtapplication.h" #include "qxtapplication_p.h" diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_p.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_p.h index cd49a8c41..d911d6d0e 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_p.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_p.h @@ -1,40 +1,40 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#ifndef QXTAPPLICATION_P_H -#define QXTAPPLICATION_P_H - -#include -#include "qxtapplication.h" - -class QxtNativeEventFilter; - -class QxtApplicationPrivate : public QxtPrivate -{ -public: - QXT_DECLARE_PUBLIC(QxtApplication) - QList nativeFilters; -}; - -#endif // QXTAPPLICATION_P_H +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#ifndef QXTAPPLICATION_P_H +#define QXTAPPLICATION_P_H + +#include +#include "qxtapplication.h" + +class QxtNativeEventFilter; + +class QxtApplicationPrivate : public QxtPrivate +{ +public: + QXT_DECLARE_PUBLIC(QxtApplication) + QList nativeFilters; +}; + +#endif // QXTAPPLICATION_P_H diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_win.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_win.cpp index 11064f0d3..8aaf7aac6 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_win.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_win.cpp @@ -1,40 +1,40 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include "qxtapplication.h" -#include "qxtapplication_p.h" -#include "qxtnativeeventfilter.h" - -/*! - \reimp - */ -bool QxtApplication::winEventFilter(MSG* msg, long* result) -{ - foreach (QxtNativeEventFilter* filter, qxt_d().nativeFilters) - { - if (filter && filter->winEventFilter(msg, result)) - return true; - } - return QApplication::winEventFilter(msg, result); -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include "qxtapplication.h" +#include "qxtapplication_p.h" +#include "qxtnativeeventfilter.h" + +/*! + \reimp + */ +bool QxtApplication::winEventFilter(MSG* msg, long* result) +{ + foreach (QxtNativeEventFilter* filter, qxt_d().nativeFilters) + { + if (filter && filter->winEventFilter(msg, result)) + return true; + } + return QApplication::winEventFilter(msg, result); +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_x11.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_x11.cpp index a07543d0c..a6f461ac3 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_x11.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtapplication_x11.cpp @@ -1,26 +1,26 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** ****************************************************************************/ #include "qxtapplication.h" #include "qxtapplication_p.h" diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtbasespinbox.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtbasespinbox.cpp index 8e98d052e..66e67b28a 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtbasespinbox.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtbasespinbox.cpp @@ -1,217 +1,217 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include "qxtbasespinbox.h" - -class QxtBaseSpinBoxPrivate : public QxtPrivate -{ -public: - QXT_DECLARE_PUBLIC(QxtBaseSpinBox) - QxtBaseSpinBoxPrivate(); - - int base; - bool upper; -}; - -QxtBaseSpinBoxPrivate::QxtBaseSpinBoxPrivate() : base(10), upper(false) -{ -} - -/*! - \class QxtBaseSpinBox - \inmodule QxtGui - \brief The QxtBaseSpinBox widget is a spin box with support for numbers - in base between \c 2 and \c 36. - - Example spinbox for hexadecimal input: - \code - QxtBaseSpinBox* spinBox = new QxtBaseSpinBox(16, this); - spinBox->setPrefix("0x"); - spinBox->setValue(0xbabe); - spinBox->setUpperCase(true); - \endcode - - \image qxtbasespinbox.png "QxtBaseSpinBox in action." - - \bold {Note:} Notice that QxtBaseSpinBox is not locale-aware. - */ - -/*! - \fn QxtBaseSpinBox::baseChanged(int base) - - This signal is emitted whenever the number \a base has changed. - */ - -/*! - Constructs a new QxtBaseSpinBox with \a parent. Base defaults to \c 10. - */ -QxtBaseSpinBox::QxtBaseSpinBox(QWidget* parent) : QSpinBox(parent) -{ - QXT_INIT_PRIVATE(QxtBaseSpinBox); -} - -/*! - Constructs a new QxtBaseSpinBox with \a base and \a parent. - */ -QxtBaseSpinBox::QxtBaseSpinBox(int base, QWidget* parent) : QSpinBox(parent) -{ - QXT_INIT_PRIVATE(QxtBaseSpinBox); - qxt_d().base = base; -} - -/*! - Destructs the spin box. - */ -QxtBaseSpinBox::~QxtBaseSpinBox() -{ -} - -/*! - \reimp - */ -void QxtBaseSpinBox::fixup(QString& input) const -{ - QString inputWithoutPrefix = input.mid(prefix().length()); - inputWithoutPrefix = qxt_d().upper ? inputWithoutPrefix.toUpper() : inputWithoutPrefix.toLower(); - input = prefix() + inputWithoutPrefix; -} - -/*! - \reimp - */ -QValidator::State QxtBaseSpinBox::validate(QString& input, int& pos) const -{ - // quick rejects - const QString prefix = QSpinBox::prefix(); - const QString inputWithoutPrefix = input.mid(prefix.length()); - if (pos < prefix.length()) - { - // do not let modify prefix - return QValidator::Invalid; - } - else if (inputWithoutPrefix.isEmpty()) - { - // allow empty input => intermediate - return QValidator::Intermediate; - } - - // Invalid: input is invalid according to the string list - // Intermediate: it is likely that a little more editing will make the input acceptable - // Acceptable: the input is valid. - Q_UNUSED(pos); - - bool ok = false; - const int min = minimum(); - const int max = maximum(); - const int number = inputWithoutPrefix.toInt(&ok, qxt_d().base); - - QValidator::State state = QValidator::Invalid; - if (!ok) - { - // cannot convert => invalid - state = QValidator::Invalid; - } - else if (number >= min && number <= max) - { - // converts ok, between boundaries => acceptable if case matches - if (qxt_d().upper) - return (input == prefix + inputWithoutPrefix.toUpper() ? QValidator::Acceptable : QValidator::Intermediate); - else - return (input == prefix + inputWithoutPrefix.toLower() ? QValidator::Acceptable : QValidator::Intermediate); - } - else - { - // converts ok, outside boundaries => intermediate - state = QValidator::Intermediate; - } - return state; -} - -/*! - \property QxtBaseSpinBox::base - \brief the number base. - - The base must be between \c 2 and \c 36. - - The default value is \c 10. - */ -int QxtBaseSpinBox::base() const -{ - return qxt_d().base; -} - -void QxtBaseSpinBox::setBase(int base) -{ - if (base < 2 || base > 36) - qWarning("QxtBaseSpinBox: base must be between 2 and 36"); - - base = qBound(2, base, 36); - if (qxt_d().base != base) - { - qxt_d().base = base; - emit baseChanged(base); - setValue(value()); - } -} - -/*! - \property QxtBaseSpinBox::upperCase - \brief whether letters are shown in upper case. - - Naturally, this applies to only bases which can contain letters. - - The default value is \c false. - */ -bool QxtBaseSpinBox::isUpperCase() const -{ - return qxt_d().upper; -} - -void QxtBaseSpinBox::setUpperCase(bool upperCase) -{ - if (qxt_d().upper != upperCase) - { - qxt_d().upper = upperCase; - setValue(value()); - } -} - -/*! - \reimp - */ -QString QxtBaseSpinBox::textFromValue(int value) const -{ - QString text = QString::number(value, qxt_d().base); - if (qxt_d().upper) - return text.toUpper(); - return text; -} - -/*! - \reimp - */ -int QxtBaseSpinBox::valueFromText(const QString& text) const -{ - return text.toInt(0, qxt_d().base); -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include "qxtbasespinbox.h" + +class QxtBaseSpinBoxPrivate : public QxtPrivate +{ +public: + QXT_DECLARE_PUBLIC(QxtBaseSpinBox) + QxtBaseSpinBoxPrivate(); + + int base; + bool upper; +}; + +QxtBaseSpinBoxPrivate::QxtBaseSpinBoxPrivate() : base(10), upper(false) +{ +} + +/*! + \class QxtBaseSpinBox + \inmodule QxtGui + \brief The QxtBaseSpinBox widget is a spin box with support for numbers + in base between \c 2 and \c 36. + + Example spinbox for hexadecimal input: + \code + QxtBaseSpinBox* spinBox = new QxtBaseSpinBox(16, this); + spinBox->setPrefix("0x"); + spinBox->setValue(0xbabe); + spinBox->setUpperCase(true); + \endcode + + \image qxtbasespinbox.png "QxtBaseSpinBox in action." + + \bold {Note:} Notice that QxtBaseSpinBox is not locale-aware. + */ + +/*! + \fn QxtBaseSpinBox::baseChanged(int base) + + This signal is emitted whenever the number \a base has changed. + */ + +/*! + Constructs a new QxtBaseSpinBox with \a parent. Base defaults to \c 10. + */ +QxtBaseSpinBox::QxtBaseSpinBox(QWidget* parent) : QSpinBox(parent) +{ + QXT_INIT_PRIVATE(QxtBaseSpinBox); +} + +/*! + Constructs a new QxtBaseSpinBox with \a base and \a parent. + */ +QxtBaseSpinBox::QxtBaseSpinBox(int base, QWidget* parent) : QSpinBox(parent) +{ + QXT_INIT_PRIVATE(QxtBaseSpinBox); + qxt_d().base = base; +} + +/*! + Destructs the spin box. + */ +QxtBaseSpinBox::~QxtBaseSpinBox() +{ +} + +/*! + \reimp + */ +void QxtBaseSpinBox::fixup(QString& input) const +{ + QString inputWithoutPrefix = input.mid(prefix().length()); + inputWithoutPrefix = qxt_d().upper ? inputWithoutPrefix.toUpper() : inputWithoutPrefix.toLower(); + input = prefix() + inputWithoutPrefix; +} + +/*! + \reimp + */ +QValidator::State QxtBaseSpinBox::validate(QString& input, int& pos) const +{ + // quick rejects + const QString prefix = QSpinBox::prefix(); + const QString inputWithoutPrefix = input.mid(prefix.length()); + if (pos < prefix.length()) + { + // do not let modify prefix + return QValidator::Invalid; + } + else if (inputWithoutPrefix.isEmpty()) + { + // allow empty input => intermediate + return QValidator::Intermediate; + } + + // Invalid: input is invalid according to the string list + // Intermediate: it is likely that a little more editing will make the input acceptable + // Acceptable: the input is valid. + Q_UNUSED(pos); + + bool ok = false; + const int min = minimum(); + const int max = maximum(); + const int number = inputWithoutPrefix.toInt(&ok, qxt_d().base); + + QValidator::State state = QValidator::Invalid; + if (!ok) + { + // cannot convert => invalid + state = QValidator::Invalid; + } + else if (number >= min && number <= max) + { + // converts ok, between boundaries => acceptable if case matches + if (qxt_d().upper) + return (input == prefix + inputWithoutPrefix.toUpper() ? QValidator::Acceptable : QValidator::Intermediate); + else + return (input == prefix + inputWithoutPrefix.toLower() ? QValidator::Acceptable : QValidator::Intermediate); + } + else + { + // converts ok, outside boundaries => intermediate + state = QValidator::Intermediate; + } + return state; +} + +/*! + \property QxtBaseSpinBox::base + \brief the number base. + + The base must be between \c 2 and \c 36. + + The default value is \c 10. + */ +int QxtBaseSpinBox::base() const +{ + return qxt_d().base; +} + +void QxtBaseSpinBox::setBase(int base) +{ + if (base < 2 || base > 36) + qWarning("QxtBaseSpinBox: base must be between 2 and 36"); + + base = qBound(2, base, 36); + if (qxt_d().base != base) + { + qxt_d().base = base; + emit baseChanged(base); + setValue(value()); + } +} + +/*! + \property QxtBaseSpinBox::upperCase + \brief whether letters are shown in upper case. + + Naturally, this applies to only bases which can contain letters. + + The default value is \c false. + */ +bool QxtBaseSpinBox::isUpperCase() const +{ + return qxt_d().upper; +} + +void QxtBaseSpinBox::setUpperCase(bool upperCase) +{ + if (qxt_d().upper != upperCase) + { + qxt_d().upper = upperCase; + setValue(value()); + } +} + +/*! + \reimp + */ +QString QxtBaseSpinBox::textFromValue(int value) const +{ + QString text = QString::number(value, qxt_d().base); + if (qxt_d().upper) + return text.toUpper(); + return text; +} + +/*! + \reimp + */ +int QxtBaseSpinBox::valueFromText(const QString& text) const +{ + return text.toInt(0, qxt_d().base); +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog.cpp index 0eb51bc7d..5bbe6ef87 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog.cpp @@ -1,300 +1,300 @@ -#include "qxtfilterdialog.h" -#include "qxtfilterdialog_p.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "qxtgroupbox.h" - - -QxtFilterDialogPrivate::QxtFilterDialogPrivate() : QObject(0), - matchCaseOption(0), - filterModeOption(0), - filterMode(0), - listingTreeView(0), - lineEditFilter(0), - proxyModel(0), - lookupColumn(0), - lookupRole(Qt::DisplayRole), - syntax(QRegExp::FixedString), - caseSensitivity(Qt::CaseInsensitive) -{ -} - -void QxtFilterDialogPrivate::createRegExpPattern(const QString &rawText) -{ - - QRegExp regExp(rawText,caseSensitivity,syntax); - if(regExp.isValid()) - proxyModel->setFilterRegExp(regExp); - else - proxyModel->setFilterRegExp(QString()); -} - -void QxtFilterDialogPrivate::updateFilterPattern() -{ - createRegExpPattern(lineEditFilter->text()); -} - -void QxtFilterDialogPrivate::filterModeOptionStateChanged(const int state) -{ - if(state == Qt::Checked) - this->filterMode->setEnabled(true); - else - this->filterMode->setEnabled(false); - -} - -void QxtFilterDialogPrivate::filterModeChoosen(int index) -{ - if(index < 0) - return; - - if( filterMode->itemData(index).isValid()) - { - QRegExp::PatternSyntax mode = static_cast(filterMode->itemData(index).toInt()); - qxt_p().setPatternSyntax(mode); - } - -} - -void QxtFilterDialogPrivate::matchCaseOptionStateChanged(const int state) -{ - if(state == Qt::Checked) - this->caseSensitivity = Qt::CaseSensitive; - else - this->caseSensitivity = Qt::CaseInsensitive; - - updateFilterPattern(); -} - -/*! -\class QxtFilterDialog QxtFilterDialog -\brief The QxtFilterDialog class provides a dialog to select data from a QAbstractItemModel - -Provides a dialog to select data from a QAbstractItemModel, the user can filter the items depending on a -role and column to make the selection easier. - -*/ - -QxtFilterDialog::QxtFilterDialog(QWidget *parent) : QDialog(parent) -{ - QXT_INIT_PRIVATE(QxtFilterDialog); - - qxt_d().proxyModel = new QSortFilterProxyModel(this); - - QVBoxLayout * dlgLayout = new QVBoxLayout(this); - - /*the line edit to type in the filter*/ - qxt_d().lineEditFilter = new QLineEdit(); - dlgLayout->addWidget(qxt_d().lineEditFilter); - connect(qxt_d().lineEditFilter,SIGNAL(textChanged(const QString &)),&qxt_d(),SLOT(createRegExpPattern(const QString &))); - - - /*the treeview that shows the filtered choices */ - qxt_d().listingTreeView = new QTreeView(this); - qxt_d().listingTreeView->setSortingEnabled(true); - //not editable , even if the model supports it - qxt_d().listingTreeView->setEditTriggers(QAbstractItemView::NoEditTriggers); - dlgLayout->addWidget(qxt_d().listingTreeView); - connect(qxt_d().listingTreeView,SIGNAL(activated ( const QModelIndex & )),this,SLOT(accept())); - -#if 1 - /*Group Box for changing search behaviour*/ - QxtGroupBox *group = new QxtGroupBox(this); - // group->setCollapsive(true); - group->setTitle(tr("Filter options")); - - qxt_d().matchCaseOption = new QCheckBox(tr("Match case")); - connect(qxt_d().matchCaseOption,SIGNAL(stateChanged ( int )),&qxt_d(),SLOT(matchCaseOptionStateChanged(int))); - - qxt_d().filterModeOption = new QCheckBox(tr("Filter mode:")); - connect(qxt_d().filterModeOption,SIGNAL(stateChanged ( int )),&qxt_d(),SLOT(filterModeOptionStateChanged(int))); - - qxt_d().filterMode = new QComboBox(); - qxt_d().filterMode->addItem(tr("Fixed String (Default)"),QRegExp::FixedString); - qxt_d().filterMode->addItem(tr("Wildcard"),QRegExp::Wildcard); - qxt_d().filterMode->addItem(tr("Regular Expression"),QRegExp::RegExp); - qxt_d().filterMode->setEnabled(false); - connect(qxt_d().filterMode,SIGNAL(activated (int)),&qxt_d(),SLOT(filterModeChoosen(int))); - - QVBoxLayout * groupBoxLayout = new QVBoxLayout(group); - groupBoxLayout->addWidget(qxt_d().matchCaseOption); - groupBoxLayout->addWidget(qxt_d().filterModeOption); - groupBoxLayout->addWidget(qxt_d().filterMode); - - - group->setLayout(groupBoxLayout); - dlgLayout->addWidget(group); - //group->setCollapsed(); - group->setChecked(false); - /*end group box*/ -#endif - /*a button to cancel the selection*/ - QPushButton *cancelButton = new QPushButton(tr("Cancel")); - dlgLayout->addWidget(cancelButton); - connect(cancelButton,SIGNAL(released()),this,SLOT(reject())); - - QWidget::setTabOrder(qxt_d().lineEditFilter,qxt_d().listingTreeView); - //QWidget::setTabOrder(qxt_d().listingTreeView,group); - //QWidget::setTabOrder(group,qxt_d().matchCaseOption); - QWidget::setTabOrder(qxt_d().listingTreeView,qxt_d().matchCaseOption); - QWidget::setTabOrder(qxt_d().matchCaseOption,qxt_d().filterModeOption); - QWidget::setTabOrder(qxt_d().filterModeOption,qxt_d().filterMode); - QWidget::setTabOrder(qxt_d().filterMode,cancelButton); - - - /*set the layout and title*/ - setLayout(dlgLayout); - setWindowTitle(tr("Filter")); -} - -QRegExp::PatternSyntax QxtFilterDialog::patternSyntax () -{ - return qxt_d().syntax; -} - -void QxtFilterDialog::setPatternSyntax (QRegExp::PatternSyntax syntax) -{ - qxt_d().syntax = syntax; - qxt_d().updateFilterPattern(); -} - -void QxtFilterDialog::setSourceModel(QAbstractItemModel *model) -{ - qxt_d().listingTreeView->setModel(0); - qxt_d().proxyModel->setSourceModel(model); - qxt_d().model = model; - qxt_d().listingTreeView->setModel(qxt_d().proxyModel); - if(model) - qxt_d().listingTreeView->setCurrentIndex(model->index(0,0)); -} - -void QxtFilterDialog::setLookupColumn (int column) -{ - qxt_d().proxyModel->setHeaderData(qxt_d().lookupColumn,Qt::Horizontal,QVariant(),Qt::ForegroundRole); - qxt_d().lookupColumn = column; - qxt_d().proxyModel->setFilterKeyColumn(qxt_d().lookupColumn); - qxt_d().proxyModel->setHeaderData(qxt_d().lookupColumn,Qt::Horizontal,QColor(Qt::red),Qt::ForegroundRole); - -} - -void QxtFilterDialog::setLookupRole (int role) -{ - qxt_d().lookupRole = role; - qxt_d().proxyModel->setFilterRole(qxt_d().lookupRole); -} - -QAbstractItemModel * QxtFilterDialog::sourceModel( ) const -{ - return qxt_d().model; -} - -int QxtFilterDialog::lookupColumn ( ) const -{ - return qxt_d().lookupColumn; -} - -int QxtFilterDialog::lookupRole ( ) const -{ - return qxt_d().lookupRole; -} - -QString QxtFilterDialog::filterText ( ) const -{ - return qxt_d().lineEditFilter->text(); -} - -void QxtFilterDialog::setFilterText (QString text) -{ - qxt_d().lineEditFilter->setText(text); -} - -QModelIndex QxtFilterDialog::selectedIndex() const -{ - return qxt_d().selectedIndex; -} - -void QxtFilterDialog::setCaseSensitivity (Qt::CaseSensitivity caseSensitivity) -{ - qxt_d().caseSensitivity = caseSensitivity; - qxt_d().updateFilterPattern(); -} - -QModelIndex QxtFilterDialog::getIndex(QWidget* parent, QAbstractItemModel *model, int column, int role, QString filterText) -{ - QxtFilterDialog dialog(parent); - - dialog.setSourceModel(model); - dialog.setLookupColumn(column); - dialog.setLookupRole(role); - dialog.setFilterText(filterText); - - if(dialog.qxt_d().proxyModel->rowCount() == 1){ - QModelIndex source; - QModelIndex filtered = dialog.qxt_d().proxyModel->index(0,column); - if(filtered.isValid()){ - source = dialog.qxt_d().proxyModel->mapToSource(filtered); - } - return source; - } - - int ret = dialog.exec(); - - if(ret == QDialog::Accepted) - return dialog.selectedIndex(); - return QModelIndex(); -} - -void QxtFilterDialog::done ( int r ) -{ - if(r==QDialog::Accepted){ - qxt_d().selectedIndex = QModelIndex(); - QModelIndex proxyIndex = qxt_d().listingTreeView->currentIndex(); - proxyIndex = qxt_d().proxyModel->index(proxyIndex.row(),lookupColumn()); - if(proxyIndex.isValid()) - { - qxt_d().selectedIndex = qxt_d().proxyModel->mapToSource(proxyIndex); - } - } - else - qxt_d().selectedIndex = QModelIndex(); - return QDialog::done(r); -} - -void QxtFilterDialog::accept () -{ - - return QDialog::accept(); -} - -void QxtFilterDialog::reject () -{ - return QDialog::reject(); -} - - -void QxtFilterDialog::keyPressEvent(QKeyEvent *e) -{ - //reimplemented to disable the default button ! - if (!e->modifiers() || (e->modifiers() & Qt::KeypadModifier && e->key() == Qt::Key_Enter)) { - switch (e->key()) - { - case Qt::Key_Enter: - case Qt::Key_Return: - accept(); - return; - } - } - QDialog::keyPressEvent(e); -} - +#include "qxtfilterdialog.h" +#include "qxtfilterdialog_p.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "qxtgroupbox.h" + + +QxtFilterDialogPrivate::QxtFilterDialogPrivate() : QObject(0), + matchCaseOption(0), + filterModeOption(0), + filterMode(0), + listingTreeView(0), + lineEditFilter(0), + proxyModel(0), + lookupColumn(0), + lookupRole(Qt::DisplayRole), + syntax(QRegExp::FixedString), + caseSensitivity(Qt::CaseInsensitive) +{ +} + +void QxtFilterDialogPrivate::createRegExpPattern(const QString &rawText) +{ + + QRegExp regExp(rawText,caseSensitivity,syntax); + if(regExp.isValid()) + proxyModel->setFilterRegExp(regExp); + else + proxyModel->setFilterRegExp(QString()); +} + +void QxtFilterDialogPrivate::updateFilterPattern() +{ + createRegExpPattern(lineEditFilter->text()); +} + +void QxtFilterDialogPrivate::filterModeOptionStateChanged(const int state) +{ + if(state == Qt::Checked) + this->filterMode->setEnabled(true); + else + this->filterMode->setEnabled(false); + +} + +void QxtFilterDialogPrivate::filterModeChoosen(int index) +{ + if(index < 0) + return; + + if( filterMode->itemData(index).isValid()) + { + QRegExp::PatternSyntax mode = static_cast(filterMode->itemData(index).toInt()); + qxt_p().setPatternSyntax(mode); + } + +} + +void QxtFilterDialogPrivate::matchCaseOptionStateChanged(const int state) +{ + if(state == Qt::Checked) + this->caseSensitivity = Qt::CaseSensitive; + else + this->caseSensitivity = Qt::CaseInsensitive; + + updateFilterPattern(); +} + +/*! +\class QxtFilterDialog QxtFilterDialog +\brief The QxtFilterDialog class provides a dialog to select data from a QAbstractItemModel + +Provides a dialog to select data from a QAbstractItemModel, the user can filter the items depending on a +role and column to make the selection easier. + +*/ + +QxtFilterDialog::QxtFilterDialog(QWidget *parent) : QDialog(parent) +{ + QXT_INIT_PRIVATE(QxtFilterDialog); + + qxt_d().proxyModel = new QSortFilterProxyModel(this); + + QVBoxLayout * dlgLayout = new QVBoxLayout(this); + + /*the line edit to type in the filter*/ + qxt_d().lineEditFilter = new QLineEdit(); + dlgLayout->addWidget(qxt_d().lineEditFilter); + connect(qxt_d().lineEditFilter,SIGNAL(textChanged(const QString &)),&qxt_d(),SLOT(createRegExpPattern(const QString &))); + + + /*the treeview that shows the filtered choices */ + qxt_d().listingTreeView = new QTreeView(this); + qxt_d().listingTreeView->setSortingEnabled(true); + //not editable , even if the model supports it + qxt_d().listingTreeView->setEditTriggers(QAbstractItemView::NoEditTriggers); + dlgLayout->addWidget(qxt_d().listingTreeView); + connect(qxt_d().listingTreeView,SIGNAL(activated ( const QModelIndex & )),this,SLOT(accept())); + +#if 1 + /*Group Box for changing search behaviour*/ + QxtGroupBox *group = new QxtGroupBox(this); + // group->setCollapsive(true); + group->setTitle(tr("Filter options")); + + qxt_d().matchCaseOption = new QCheckBox(tr("Match case")); + connect(qxt_d().matchCaseOption,SIGNAL(stateChanged ( int )),&qxt_d(),SLOT(matchCaseOptionStateChanged(int))); + + qxt_d().filterModeOption = new QCheckBox(tr("Filter mode:")); + connect(qxt_d().filterModeOption,SIGNAL(stateChanged ( int )),&qxt_d(),SLOT(filterModeOptionStateChanged(int))); + + qxt_d().filterMode = new QComboBox(); + qxt_d().filterMode->addItem(tr("Fixed String (Default)"),QRegExp::FixedString); + qxt_d().filterMode->addItem(tr("Wildcard"),QRegExp::Wildcard); + qxt_d().filterMode->addItem(tr("Regular Expression"),QRegExp::RegExp); + qxt_d().filterMode->setEnabled(false); + connect(qxt_d().filterMode,SIGNAL(activated (int)),&qxt_d(),SLOT(filterModeChoosen(int))); + + QVBoxLayout * groupBoxLayout = new QVBoxLayout(group); + groupBoxLayout->addWidget(qxt_d().matchCaseOption); + groupBoxLayout->addWidget(qxt_d().filterModeOption); + groupBoxLayout->addWidget(qxt_d().filterMode); + + + group->setLayout(groupBoxLayout); + dlgLayout->addWidget(group); + //group->setCollapsed(); + group->setChecked(false); + /*end group box*/ +#endif + /*a button to cancel the selection*/ + QPushButton *cancelButton = new QPushButton(tr("Cancel")); + dlgLayout->addWidget(cancelButton); + connect(cancelButton,SIGNAL(released()),this,SLOT(reject())); + + QWidget::setTabOrder(qxt_d().lineEditFilter,qxt_d().listingTreeView); + //QWidget::setTabOrder(qxt_d().listingTreeView,group); + //QWidget::setTabOrder(group,qxt_d().matchCaseOption); + QWidget::setTabOrder(qxt_d().listingTreeView,qxt_d().matchCaseOption); + QWidget::setTabOrder(qxt_d().matchCaseOption,qxt_d().filterModeOption); + QWidget::setTabOrder(qxt_d().filterModeOption,qxt_d().filterMode); + QWidget::setTabOrder(qxt_d().filterMode,cancelButton); + + + /*set the layout and title*/ + setLayout(dlgLayout); + setWindowTitle(tr("Filter")); +} + +QRegExp::PatternSyntax QxtFilterDialog::patternSyntax () +{ + return qxt_d().syntax; +} + +void QxtFilterDialog::setPatternSyntax (QRegExp::PatternSyntax syntax) +{ + qxt_d().syntax = syntax; + qxt_d().updateFilterPattern(); +} + +void QxtFilterDialog::setSourceModel(QAbstractItemModel *model) +{ + qxt_d().listingTreeView->setModel(0); + qxt_d().proxyModel->setSourceModel(model); + qxt_d().model = model; + qxt_d().listingTreeView->setModel(qxt_d().proxyModel); + if(model) + qxt_d().listingTreeView->setCurrentIndex(model->index(0,0)); +} + +void QxtFilterDialog::setLookupColumn (int column) +{ + qxt_d().proxyModel->setHeaderData(qxt_d().lookupColumn,Qt::Horizontal,QVariant(),Qt::ForegroundRole); + qxt_d().lookupColumn = column; + qxt_d().proxyModel->setFilterKeyColumn(qxt_d().lookupColumn); + qxt_d().proxyModel->setHeaderData(qxt_d().lookupColumn,Qt::Horizontal,QColor(Qt::red),Qt::ForegroundRole); + +} + +void QxtFilterDialog::setLookupRole (int role) +{ + qxt_d().lookupRole = role; + qxt_d().proxyModel->setFilterRole(qxt_d().lookupRole); +} + +QAbstractItemModel * QxtFilterDialog::sourceModel( ) const +{ + return qxt_d().model; +} + +int QxtFilterDialog::lookupColumn ( ) const +{ + return qxt_d().lookupColumn; +} + +int QxtFilterDialog::lookupRole ( ) const +{ + return qxt_d().lookupRole; +} + +QString QxtFilterDialog::filterText ( ) const +{ + return qxt_d().lineEditFilter->text(); +} + +void QxtFilterDialog::setFilterText (QString text) +{ + qxt_d().lineEditFilter->setText(text); +} + +QModelIndex QxtFilterDialog::selectedIndex() const +{ + return qxt_d().selectedIndex; +} + +void QxtFilterDialog::setCaseSensitivity (Qt::CaseSensitivity caseSensitivity) +{ + qxt_d().caseSensitivity = caseSensitivity; + qxt_d().updateFilterPattern(); +} + +QModelIndex QxtFilterDialog::getIndex(QWidget* parent, QAbstractItemModel *model, int column, int role, QString filterText) +{ + QxtFilterDialog dialog(parent); + + dialog.setSourceModel(model); + dialog.setLookupColumn(column); + dialog.setLookupRole(role); + dialog.setFilterText(filterText); + + if(dialog.qxt_d().proxyModel->rowCount() == 1){ + QModelIndex source; + QModelIndex filtered = dialog.qxt_d().proxyModel->index(0,column); + if(filtered.isValid()){ + source = dialog.qxt_d().proxyModel->mapToSource(filtered); + } + return source; + } + + int ret = dialog.exec(); + + if(ret == QDialog::Accepted) + return dialog.selectedIndex(); + return QModelIndex(); +} + +void QxtFilterDialog::done ( int r ) +{ + if(r==QDialog::Accepted){ + qxt_d().selectedIndex = QModelIndex(); + QModelIndex proxyIndex = qxt_d().listingTreeView->currentIndex(); + proxyIndex = qxt_d().proxyModel->index(proxyIndex.row(),lookupColumn()); + if(proxyIndex.isValid()) + { + qxt_d().selectedIndex = qxt_d().proxyModel->mapToSource(proxyIndex); + } + } + else + qxt_d().selectedIndex = QModelIndex(); + return QDialog::done(r); +} + +void QxtFilterDialog::accept () +{ + + return QDialog::accept(); +} + +void QxtFilterDialog::reject () +{ + return QDialog::reject(); +} + + +void QxtFilterDialog::keyPressEvent(QKeyEvent *e) +{ + //reimplemented to disable the default button ! + if (!e->modifiers() || (e->modifiers() & Qt::KeypadModifier && e->key() == Qt::Key_Enter)) { + switch (e->key()) + { + case Qt::Key_Enter: + case Qt::Key_Return: + accept(); + return; + } + } + QDialog::keyPressEvent(e); +} + diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog.h index 747517985..5347567cb 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog.h @@ -1,57 +1,57 @@ -#ifndef QXTFILTERDIALOG_H_INCLUDED -#define QXTFILTERDIALOG_H_INCLUDED - - -#include -#include -#include "qxtglobal.h" -#include "qxtpimpl.h" - -class QAbstractItemModel; -class QxtFilterDialogPrivate; -class QKeyEvent; - -class QXT_GUI_EXPORT QxtFilterDialog : public QDialog -{ - Q_OBJECT - - Q_PROPERTY(int lookupColumn READ lookupColumn WRITE setLookupColumn ) - Q_PROPERTY(int lookupRole READ lookupRole WRITE setLookupRole ) - Q_PROPERTY(QString filterText READ filterText WRITE setFilterText ) - - public: - QxtFilterDialog(QWidget *parent = 0); - - void setSourceModel (QAbstractItemModel *model); - - QRegExp::PatternSyntax patternSyntax (); - - - QAbstractItemModel * sourceModel ( ) const; - int lookupColumn ( ) const; - int lookupRole ( ) const; - QString filterText ( ) const; - QModelIndex selectedIndex ( ) const; - - static QModelIndex getIndex (QWidget* parent = 0, QAbstractItemModel *model = 0 - , int column = 0, int role = Qt::DisplayRole - , QString filterText = QString()); - - protected: - virtual void keyPressEvent (QKeyEvent *e); - - public slots: - virtual void done ( int r ); - virtual void accept (); - virtual void reject (); - void setPatternSyntax (QRegExp::PatternSyntax syntax); - void setCaseSensitivity (Qt::CaseSensitivity caseSensitivity = Qt::CaseSensitive); - void setFilterText (QString text); - void setLookupColumn (int column); - void setLookupRole (int role); - - private: - QXT_DECLARE_PRIVATE(QxtFilterDialog); -}; - -#endif +#ifndef QXTFILTERDIALOG_H_INCLUDED +#define QXTFILTERDIALOG_H_INCLUDED + + +#include +#include +#include "qxtglobal.h" +#include "qxtpimpl.h" + +class QAbstractItemModel; +class QxtFilterDialogPrivate; +class QKeyEvent; + +class QXT_GUI_EXPORT QxtFilterDialog : public QDialog +{ + Q_OBJECT + + Q_PROPERTY(int lookupColumn READ lookupColumn WRITE setLookupColumn ) + Q_PROPERTY(int lookupRole READ lookupRole WRITE setLookupRole ) + Q_PROPERTY(QString filterText READ filterText WRITE setFilterText ) + + public: + QxtFilterDialog(QWidget *parent = 0); + + void setSourceModel (QAbstractItemModel *model); + + QRegExp::PatternSyntax patternSyntax (); + + + QAbstractItemModel * sourceModel ( ) const; + int lookupColumn ( ) const; + int lookupRole ( ) const; + QString filterText ( ) const; + QModelIndex selectedIndex ( ) const; + + static QModelIndex getIndex (QWidget* parent = 0, QAbstractItemModel *model = 0 + , int column = 0, int role = Qt::DisplayRole + , QString filterText = QString()); + + protected: + virtual void keyPressEvent (QKeyEvent *e); + + public slots: + virtual void done ( int r ); + virtual void accept (); + virtual void reject (); + void setPatternSyntax (QRegExp::PatternSyntax syntax); + void setCaseSensitivity (Qt::CaseSensitivity caseSensitivity = Qt::CaseSensitive); + void setFilterText (QString text); + void setLookupColumn (int column); + void setLookupRole (int role); + + private: + QXT_DECLARE_PRIVATE(QxtFilterDialog); +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog_p.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog_p.h index 4ae790908..7440d4eae 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog_p.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtfilterdialog_p.h @@ -1,56 +1,56 @@ -#ifndef QXTFILTERDIALOG_P_H_INCLUDED -#define QXTFILTERDIALOG_P_H_INCLUDED - -#include -#include -#include -#include -#include "qxtpimpl.h" - -class QxtFilterDialog; -class QAbstractItemModel; -class QTreeView; -class QSortFilterProxyModel; -class QLineEdit; -class QCheckBox; -class QComboBox; - -class QxtFilterDialogPrivate : public QObject, public QxtPrivate -{ - Q_OBJECT - public: - QxtFilterDialogPrivate(); - QXT_DECLARE_PUBLIC(QxtFilterDialog); - - /*widgets*/ - QCheckBox * matchCaseOption; - QCheckBox * filterModeOption; - QComboBox * filterMode; - QTreeView * listingTreeView; - QLineEdit * lineEditFilter; - - /*models*/ - QPointer model; - QSortFilterProxyModel* proxyModel; - - /*properties*/ - int lookupColumn; - int lookupRole; - QRegExp::PatternSyntax syntax; - Qt::CaseSensitivity caseSensitivity; - - /*result*/ - QModelIndex selectedIndex; - - /*member functions*/ - void updateFilterPattern(); - - public slots: - void createRegExpPattern(const QString &rawText); - void filterModeOptionStateChanged(const int state); - void matchCaseOptionStateChanged(const int state); - void filterModeChoosen(int index); -}; - - +#ifndef QXTFILTERDIALOG_P_H_INCLUDED +#define QXTFILTERDIALOG_P_H_INCLUDED + +#include +#include +#include +#include +#include "qxtpimpl.h" + +class QxtFilterDialog; +class QAbstractItemModel; +class QTreeView; +class QSortFilterProxyModel; +class QLineEdit; +class QCheckBox; +class QComboBox; + +class QxtFilterDialogPrivate : public QObject, public QxtPrivate +{ + Q_OBJECT + public: + QxtFilterDialogPrivate(); + QXT_DECLARE_PUBLIC(QxtFilterDialog); + + /*widgets*/ + QCheckBox * matchCaseOption; + QCheckBox * filterModeOption; + QComboBox * filterMode; + QTreeView * listingTreeView; + QLineEdit * lineEditFilter; + + /*models*/ + QPointer model; + QSortFilterProxyModel* proxyModel; + + /*properties*/ + int lookupColumn; + int lookupRole; + QRegExp::PatternSyntax syntax; + Qt::CaseSensitivity caseSensitivity; + + /*result*/ + QModelIndex selectedIndex; + + /*member functions*/ + void updateFilterPattern(); + + public slots: + void createRegExpPattern(const QString &rawText); + void filterModeOptionStateChanged(const int state); + void matchCaseOptionStateChanged(const int state); + void filterModeChoosen(int index); +}; + + #endif \ No newline at end of file diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview.cpp index ae79d6520..1debf9185 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview.cpp @@ -1,766 +1,766 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ** - ** This is a derived work of PictureFlow (http://pictureflow.googlecode.com) - ** The original code was distributed under the following terms: - ** - ** Copyright (C) 2008 Ariya Hidayat (ariya@kde.org) - ** Copyright (C) 2007 Ariya Hidayat (ariya@kde.org) - ** - ** Permission is hereby granted, free of charge, to any person obtaining a copy - ** of this software and associated documentation files (the "Software"), to deal - ** in the Software without restriction, including without limitation the rights - ** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - ** copies of the Software, and to permit persons to whom the Software is - ** furnished to do so, subject to the following conditions: - ** - ** The above copyright notice and this permission notice shall be included in - ** all copies or substantial portions of the Software. - ** - ** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - ** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - ** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - ** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - ** LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - ** OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - ** THE SOFTWARE. - ****************************************************************************/ - -#include "qxtflowview_p.h" -#include - -/*! - \class QxtFlowView - \inmodule QxtGui - \brief The QxtFlowView widget is an item view for images with impressive flow effects - - A widget for showin images with animation effects, like Apple's Cover - Flow (in iTunes and iPod). Images are arranged in form of slides, one - main slide is shown at the center with few slides on the left and right - sides of the center slide. When the next or previous slide is brought - to the front, the whole slides flow to the left or to the right with - smooth animation effect; until the new slide is finally placed at the - center. - - \image qxtflowview.png "QxtFlowView in action." - - This is a derived work of \l{http://pictureflow.googlecode.com}{PictureFlow} - */ - -/*! - \enum QxtFlowView::ReflectionEffect - \brief This enum describes available reflection effects. - - \value NoReflection No reflection - \value PlainReflection Plain reflection - \value BlurredReflection Blurred reflection - */ - -/*! - \fn QxtFlowView::currentIndexChanged(QModelIndex index) - - This signal is emitted whenever the current \a index has changed. - */ - -/*! - Constructs a new QxtFlowView with \a parent. - */ -QxtFlowView::QxtFlowView(QWidget* parent): QWidget(parent) -{ - d = new QxtFlowViewPrivate; - - d->model = 0; - d->picrole = Qt::DecorationRole; - d->textrole = Qt::DisplayRole; - d->piccolumn = 0; - d->textcolumn = 0; - - - - d->state = new QxtFlowViewState; - d->state->reset(); - d->state->reposition(); - - d->renderer = new QxtFlowViewSoftwareRenderer; - d->renderer->state = d->state; - d->renderer->widget = this; - d->renderer->init(); - - d->animator = new QxtFlowViewAnimator; - d->animator->state = d->state; - QObject::connect(&d->animator->animateTimer, SIGNAL(timeout()), this, SLOT(updateAnimation())); - - QObject::connect(&d->triggerTimer, SIGNAL(timeout()), this, SLOT(render())); - - setAttribute(Qt::WA_StaticContents, true); - setAttribute(Qt::WA_OpaquePaintEvent, true); - setAttribute(Qt::WA_NoSystemBackground, true); -} - -/*! - Destructs the flow view. - */ -QxtFlowView::~QxtFlowView() -{ - delete d->renderer; - delete d->animator; - delete d->state; - delete d; -} - -/*! - Sets the \a model. - - \bold {Note:} The view does not take ownership of the model unless it is the - model's parent object because it may be shared between many different views. - */ -void QxtFlowView::setModel(QAbstractItemModel * model) -{ - d->setModel(model); -} - -/*! - Returns the model. - */ -QAbstractItemModel * QxtFlowView::model() -{ - return d->model; -} - -/*! - \property QxtFlowView::backgroundColor - \brief the background color - - The default value is black. - */ -QColor QxtFlowView::backgroundColor() const -{ - return QColor(d->state->backgroundColor); -} - -void QxtFlowView::setBackgroundColor(const QColor& c) -{ - d->state->backgroundColor = c.rgb(); - triggerRender(); -} - -/*! - \property QxtFlowView::slideSize - \brief the slide size - - The slide dimensions are in pixels. - - The default value is 150x200. - */ -QSize QxtFlowView::slideSize() const -{ - return QSize(d->state->slideWidth, d->state->slideHeight); -} - -void QxtFlowView::setSlideSize(QSize size) -{ - d->state->slideWidth = size.width(); - d->state->slideHeight = size.height(); - d->state->reposition(); - triggerRender(); -} - -/*! - \property QxtFlowView::reflectionEffect - \brief the reflection effect - - The default value is PlainReflection. - */ -QxtFlowView::ReflectionEffect QxtFlowView::reflectionEffect() const -{ - return d->state->reflectionEffect; -} - -void QxtFlowView::setReflectionEffect(ReflectionEffect effect) -{ - d->state->reflectionEffect = effect; - d->reset(); -} - -/*! - \property QxtFlowView::pictureRole - \brief the picture role - - The default value is Qt::DecorationRole. - */ -int QxtFlowView::pictureRole() -{ - return d->picrole; -} - -void QxtFlowView::setPictureRole(int a) -{ - d->picrole = a; - d->reset(); -} - -/*! - \property QxtFlowView::pictureColumn - \brief the picture column - - The default value is \c 0. - */ -int QxtFlowView::pictureColumn() -{ - return d->piccolumn; -} - -void QxtFlowView::setPictureColumn(int a) -{ - d->piccolumn = a; - d->reset(); -} - -#if 0 -int QxtFlowView::textRole() -{ - return d->textrole; -} - -void QxtFlowView::setTextRole(int a) -{ - d->textrole = a; - d->reset(); -} - -int QxtFlowView::textColumn() -{ - return d->textcolumn; -} - -void QxtFlowView::setTextColumn(int a) -{ - d->textcolumn = a; - d->reset(); -} -#endif - -/*! - \property QxtFlowView::rootIndex - \brief the root index - - The root index is the parent index to the view's toplevel items. The root can be invalid. - */ -QModelIndex QxtFlowView::rootIndex() const -{ - return d->rootindex; -} - -void QxtFlowView::setRootIndex(QModelIndex index) -{ - d->rootindex = index; -} - -/*! - \property QxtFlowView::currentIndex - \brief the current index - - The slide of the current index is shown in the middle of the viewport. - - \bold {Note:} No animation effect will be produced. - \sa showSlide() - */ -QModelIndex QxtFlowView::currentIndex() const -{ - if (!d->model) - return QModelIndex(); - return d->currentcenter; -} - -void QxtFlowView::setCurrentIndex(QModelIndex index) -{ - d->setCurrentIndex(index); -} - -/*! Rerender the widget. Normally this function will be automatically invoked whenever necessary, e.g. during the transition animation. */ -void QxtFlowView::render() -{ - d->renderer->dirty = true; - update(); -} - -/*! Schedules a rendering update. Unlike render(), this function does not cause immediate rendering.*/ -void QxtFlowView::triggerRender() -{ - d->triggerRender(); -} - -/*! Shows previous slide using animation effect. */ -void QxtFlowView::showPrevious() -{ - int step = d->animator->step; - int center = d->state->centerIndex; - - if (step > 0) - d->animator->start(center); - - if (step == 0) - if (center > 0) - d->animator->start(center - 1); - - if (step < 0) - d->animator->target = qMax(0, center - 2); -} - -/*! Shows next slide using animation effect. */ -void QxtFlowView::showNext() -{ - int step = d->animator->step; - int center = d->state->centerIndex; - - if (step < 0) - d->animator->start(center); - - if (step == 0) - if (center < d->state->slideImages.count() - 1) - d->animator->start(center + 1); - - if (step > 0) - d->animator->target = qMin(center + 2, d->state->slideImages.count() - 1); -} - -/*! Go to specified slide at \a index using animation effect. */ -void QxtFlowView::showSlide(QModelIndex index) -{ - int r = d->modelmap.indexOf(index); - if (r < 0) - return; - - d->showSlide(r); -} - -/*! \reimp */ -void QxtFlowView::keyPressEvent(QKeyEvent* event) -{ - if (event->key() == Qt::Key_Left) - { - if (event->modifiers() == Qt::ControlModifier) - d->showSlide(currentIndex().row() - 10); - else - showPrevious(); - event->accept(); - return; - } - - if (event->key() == Qt::Key_Right) - { - if (event->modifiers() == Qt::ControlModifier) - d->showSlide(currentIndex().row() + 10); - else - showNext(); - event->accept(); - return; - } - - event->ignore(); -} - -/*! \reimp */ -void QxtFlowView::mousePressEvent(QMouseEvent* event) -{ - d->lastgrabpos = event->pos(); -} - -/*! \reimp */ -void QxtFlowView::mouseMoveEvent(QMouseEvent * event) -{ - int i = (event->pos() - d->lastgrabpos).x() / (d->state->slideWidth / 4); - if (i > 0) - { - showPrevious(); - d->lastgrabpos = event->pos(); - } - if (i < 0) - { - showNext(); - d->lastgrabpos = event->pos(); - } - -} - -/*! \reimp */ -void QxtFlowView::mouseReleaseEvent(QMouseEvent* event) -{ - Q_UNUSED(event); - -} - -/*! \reimp */ -void QxtFlowView::paintEvent(QPaintEvent* event) -{ - Q_UNUSED(event); - d->renderer->paint(); -} - -/*! \reimp */ -void QxtFlowView::resizeEvent(QResizeEvent* event) -{ - triggerRender(); - QWidget::resizeEvent(event); -} - -/*! \reimp */ -void QxtFlowView::wheelEvent(QWheelEvent * event) -{ - - if (event->orientation() == Qt::Horizontal) - { - event->ignore(); - } - else - { - int numSteps = -((event->delta() / 8) / 15); - - - - if (numSteps > 0) - { - for (int i = 0;i < numSteps;i++) - { - showNext(); - } - } - else - { - for (int i = numSteps;i < 0;i++) - { - showPrevious(); - } - } - event->accept(); - } - - -} - -/*! \internal */ -void QxtFlowView::updateAnimation() -{ - int old_center = d->state->centerIndex; - d->animator->update(); - triggerRender(); - if (d->state->centerIndex != old_center) - { - d->currentcenter = d->modelmap.at(d->state->centerIndex); - emit currentIndexChanged(d->currentcenter); - } -} - - - - - - - - - -void QxtFlowViewPrivate::columnsAboutToBeInserted(const QModelIndex & parent, int start, int end) -{ - Q_UNUSED(parent); - Q_UNUSED(start); - Q_UNUSED(end); - -} - -void QxtFlowViewPrivate::columnsAboutToBeRemoved(const QModelIndex & parent, int start, int end) -{ - Q_UNUSED(parent); - Q_UNUSED(start); - Q_UNUSED(end); - -} - -void QxtFlowViewPrivate::columnsInserted(const QModelIndex & parent, int start, int end) -{ - Q_UNUSED(parent); - Q_UNUSED(start); - Q_UNUSED(end); - -} - -void QxtFlowViewPrivate::columnsRemoved(const QModelIndex & parent, int start, int end) -{ - Q_UNUSED(parent); - Q_UNUSED(start); - Q_UNUSED(end); -} - -void QxtFlowViewPrivate::dataChanged(const QModelIndex & topLeft, const QModelIndex & bottomRight) -{ - Q_UNUSED(topLeft); - Q_UNUSED(bottomRight); - - if (topLeft.parent() != rootindex) - return; - - if (bottomRight.parent() != rootindex) - return; - - - int start = topLeft.row(); - int end = bottomRight.row(); - - for (int i = start;i <= end;i++) - replaceSlide(i, qvariant_cast(model->data(model->index(i, piccolumn, rootindex), picrole))); -} - -void QxtFlowViewPrivate::headerDataChanged(Qt::Orientation orientation, int first, int last) -{ - Q_UNUSED(orientation); - Q_UNUSED(first); - Q_UNUSED(last); - - - - - -} - -void QxtFlowViewPrivate::layoutAboutToBeChanged() -{ - -} - -void QxtFlowViewPrivate::layoutChanged() -{ - reset(); - setCurrentIndex(currentcenter); -} - -void QxtFlowViewPrivate::modelAboutToBeReset() -{ -} - -void QxtFlowViewPrivate::modelReset() -{ - reset(); -} - -void QxtFlowViewPrivate::rowsAboutToBeInserted(const QModelIndex & parent, int start, int end) -{ - Q_UNUSED(parent); - Q_UNUSED(start); - Q_UNUSED(end); -} - -void QxtFlowViewPrivate::rowsAboutToBeRemoved(const QModelIndex & parent, int start, int end) -{ - Q_UNUSED(parent); - Q_UNUSED(start); - Q_UNUSED(end); -} - -void QxtFlowViewPrivate::rowsInserted(const QModelIndex & parent, int start, int end) -{ - if (rootindex != parent) - return; - for (int i = start;i <= end;i++) - { - QModelIndex idx = model->index(i, piccolumn, rootindex); - insertSlide(i, qvariant_cast(model->data(idx, picrole))); - modelmap.insert(i, idx); - } -} - -void QxtFlowViewPrivate::rowsRemoved(const QModelIndex & parent, int start, int end) -{ - if (rootindex != parent) - return; - for (int i = start;i <= end;i++) - { - removeSlide(i); - modelmap.removeAt(i); - } - -} - -void QxtFlowViewPrivate::setModel(QAbstractItemModel * m) -{ - - - if (model) - { - - disconnect(this->model, SIGNAL(columnsAboutToBeInserted(const QModelIndex & , int , int)), - this, SLOT(columnsAboutToBeInserted(const QModelIndex & , int , int))); - disconnect(this->model, SIGNAL(columnsAboutToBeRemoved(const QModelIndex & , int , int)), - this, SLOT(columnsAboutToBeRemoved(const QModelIndex & , int , int))); - disconnect(this->model, SIGNAL(columnsInserted(const QModelIndex & , int , int)), - this, SLOT(columnsInserted(const QModelIndex & , int , int))); - disconnect(this->model, SIGNAL(columnsRemoved(const QModelIndex & , int , int)), - this, SLOT(columnsRemoved(const QModelIndex & , int , int))); - disconnect(this->model, SIGNAL(dataChanged(const QModelIndex & , const QModelIndex &)), - this, SLOT(dataChanged(const QModelIndex & , const QModelIndex &))); - disconnect(this->model, SIGNAL(headerDataChanged(Qt::Orientation , int , int)), - this, SLOT(headerDataChanged(Qt::Orientation , int , int))); - disconnect(this->model, SIGNAL(layoutAboutToBeChanged()), - this, SLOT(layoutAboutToBeChanged())); - disconnect(this->model, SIGNAL(layoutChanged()), - this, SLOT(layoutChanged())); - disconnect(this->model, SIGNAL(modelAboutToBeReset()), - this, SLOT(modelAboutToBeReset())); - disconnect(this->model, SIGNAL(modelReset()), - this, SLOT(modelReset())); - disconnect(this->model, SIGNAL(rowsAboutToBeInserted(const QModelIndex & , int , int)), - this, SLOT(rowsAboutToBeInserted(const QModelIndex & , int , int))); - disconnect(this->model, SIGNAL(rowsAboutToBeRemoved(const QModelIndex & , int , int)), - this, SLOT(rowsAboutToBeRemoved(const QModelIndex & , int , int))); - disconnect(this->model, SIGNAL(rowsInserted(const QModelIndex & , int , int)), - this, SLOT(rowsInserted(const QModelIndex & , int , int))); - disconnect(this->model, SIGNAL(rowsRemoved(const QModelIndex & , int , int)), - this, SLOT(rowsRemoved(const QModelIndex & , int , int))); - } - model = m; - if (model) - { - rootindex = model->parent(QModelIndex()); - - connect(this->model, SIGNAL(columnsAboutToBeInserted(const QModelIndex & , int , int)), - this, SLOT(columnsAboutToBeInserted(const QModelIndex & , int , int))); - connect(this->model, SIGNAL(columnsAboutToBeRemoved(const QModelIndex & , int , int)), - this, SLOT(columnsAboutToBeRemoved(const QModelIndex & , int , int))); - connect(this->model, SIGNAL(columnsInserted(const QModelIndex & , int , int)), - this, SLOT(columnsInserted(const QModelIndex & , int , int))); - connect(this->model, SIGNAL(columnsRemoved(const QModelIndex & , int , int)), - this, SLOT(columnsRemoved(const QModelIndex & , int , int))); - connect(this->model, SIGNAL(dataChanged(const QModelIndex & , const QModelIndex &)), - this, SLOT(dataChanged(const QModelIndex & , const QModelIndex &))); - connect(this->model, SIGNAL(headerDataChanged(Qt::Orientation , int , int)), - this, SLOT(headerDataChanged(Qt::Orientation , int , int))); - connect(this->model, SIGNAL(layoutAboutToBeChanged()), - this, SLOT(layoutAboutToBeChanged())); - connect(this->model, SIGNAL(layoutChanged()), - this, SLOT(layoutChanged())); - connect(this->model, SIGNAL(modelAboutToBeReset()), - this, SLOT(modelAboutToBeReset())); - connect(this->model, SIGNAL(modelReset()), - this, SLOT(modelReset())); - connect(this->model, SIGNAL(rowsAboutToBeInserted(const QModelIndex & , int , int)), - this, SLOT(rowsAboutToBeInserted(const QModelIndex & , int , int))); - connect(this->model, SIGNAL(rowsAboutToBeRemoved(const QModelIndex & , int , int)), - this, SLOT(rowsAboutToBeRemoved(const QModelIndex & , int , int))); - connect(this->model, SIGNAL(rowsInserted(const QModelIndex & , int , int)), - this, SLOT(rowsInserted(const QModelIndex & , int , int))); - connect(this->model, SIGNAL(rowsRemoved(const QModelIndex & , int , int)), - this, SLOT(rowsRemoved(const QModelIndex & , int , int))); - } - - reset(); -} - - -void QxtFlowViewPrivate::clear() -{ - int c = state->slideImages.count(); - for (int i = 0; i < c; i++) - delete state->slideImages[i]; - state->slideImages.resize(0); - - state->reset(); - modelmap.clear(); - triggerRender(); -} - - -void QxtFlowViewPrivate::triggerRender() -{ - triggerTimer.setSingleShot(true); - triggerTimer.start(0); -} - - - -void QxtFlowViewPrivate::insertSlide(int index, const QImage& image) -{ - state->slideImages.insert(index, new QImage(image)); - triggerRender(); -} - -void QxtFlowViewPrivate::replaceSlide(int index, const QImage& image) -{ - Q_ASSERT((index >= 0) && (index < state->slideImages.count())); - - QImage* i = image.isNull() ? 0 : new QImage(image); - delete state->slideImages[index]; - state->slideImages[index] = i; - triggerRender(); -} - -void QxtFlowViewPrivate::removeSlide(int index) -{ - delete state->slideImages[index]; - state->slideImages.remove(index); - triggerRender(); -} - - -void QxtFlowViewPrivate::showSlide(int index) -{ - if (index == state->centerSlide.slideIndex) - return; - animator->start(index); -} - - - -void QxtFlowViewPrivate::reset() -{ - clear(); - if (model) - { - for (int i = 0;i < model->rowCount(rootindex);i++) - { - QModelIndex idx = model->index(i, piccolumn, rootindex); - insertSlide(i, qvariant_cast(model->data(idx, picrole))); - modelmap.insert(i, idx); - } - if(modelmap.count()) - currentcenter=modelmap.at(0); - else - currentcenter=QModelIndex(); - } - triggerRender(); -} - - - -void QxtFlowViewPrivate::setCurrentIndex(QModelIndex index) -{ - if (model->parent(index) != rootindex) - return; - - int r = modelmap.indexOf(index); - if (r < 0) - return; - - state->centerIndex = r; - state->reset(); - animator->stop(r); - triggerRender(); -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ** + ** This is a derived work of PictureFlow (http://pictureflow.googlecode.com) + ** The original code was distributed under the following terms: + ** + ** Copyright (C) 2008 Ariya Hidayat (ariya@kde.org) + ** Copyright (C) 2007 Ariya Hidayat (ariya@kde.org) + ** + ** Permission is hereby granted, free of charge, to any person obtaining a copy + ** of this software and associated documentation files (the "Software"), to deal + ** in the Software without restriction, including without limitation the rights + ** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + ** copies of the Software, and to permit persons to whom the Software is + ** furnished to do so, subject to the following conditions: + ** + ** The above copyright notice and this permission notice shall be included in + ** all copies or substantial portions of the Software. + ** + ** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + ** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + ** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + ** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + ** LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + ** OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + ** THE SOFTWARE. + ****************************************************************************/ + +#include "qxtflowview_p.h" +#include + +/*! + \class QxtFlowView + \inmodule QxtGui + \brief The QxtFlowView widget is an item view for images with impressive flow effects + + A widget for showin images with animation effects, like Apple's Cover + Flow (in iTunes and iPod). Images are arranged in form of slides, one + main slide is shown at the center with few slides on the left and right + sides of the center slide. When the next or previous slide is brought + to the front, the whole slides flow to the left or to the right with + smooth animation effect; until the new slide is finally placed at the + center. + + \image qxtflowview.png "QxtFlowView in action." + + This is a derived work of \l{http://pictureflow.googlecode.com}{PictureFlow} + */ + +/*! + \enum QxtFlowView::ReflectionEffect + \brief This enum describes available reflection effects. + + \value NoReflection No reflection + \value PlainReflection Plain reflection + \value BlurredReflection Blurred reflection + */ + +/*! + \fn QxtFlowView::currentIndexChanged(QModelIndex index) + + This signal is emitted whenever the current \a index has changed. + */ + +/*! + Constructs a new QxtFlowView with \a parent. + */ +QxtFlowView::QxtFlowView(QWidget* parent): QWidget(parent) +{ + d = new QxtFlowViewPrivate; + + d->model = 0; + d->picrole = Qt::DecorationRole; + d->textrole = Qt::DisplayRole; + d->piccolumn = 0; + d->textcolumn = 0; + + + + d->state = new QxtFlowViewState; + d->state->reset(); + d->state->reposition(); + + d->renderer = new QxtFlowViewSoftwareRenderer; + d->renderer->state = d->state; + d->renderer->widget = this; + d->renderer->init(); + + d->animator = new QxtFlowViewAnimator; + d->animator->state = d->state; + QObject::connect(&d->animator->animateTimer, SIGNAL(timeout()), this, SLOT(updateAnimation())); + + QObject::connect(&d->triggerTimer, SIGNAL(timeout()), this, SLOT(render())); + + setAttribute(Qt::WA_StaticContents, true); + setAttribute(Qt::WA_OpaquePaintEvent, true); + setAttribute(Qt::WA_NoSystemBackground, true); +} + +/*! + Destructs the flow view. + */ +QxtFlowView::~QxtFlowView() +{ + delete d->renderer; + delete d->animator; + delete d->state; + delete d; +} + +/*! + Sets the \a model. + + \bold {Note:} The view does not take ownership of the model unless it is the + model's parent object because it may be shared between many different views. + */ +void QxtFlowView::setModel(QAbstractItemModel * model) +{ + d->setModel(model); +} + +/*! + Returns the model. + */ +QAbstractItemModel * QxtFlowView::model() +{ + return d->model; +} + +/*! + \property QxtFlowView::backgroundColor + \brief the background color + + The default value is black. + */ +QColor QxtFlowView::backgroundColor() const +{ + return QColor(d->state->backgroundColor); +} + +void QxtFlowView::setBackgroundColor(const QColor& c) +{ + d->state->backgroundColor = c.rgb(); + triggerRender(); +} + +/*! + \property QxtFlowView::slideSize + \brief the slide size + + The slide dimensions are in pixels. + + The default value is 150x200. + */ +QSize QxtFlowView::slideSize() const +{ + return QSize(d->state->slideWidth, d->state->slideHeight); +} + +void QxtFlowView::setSlideSize(QSize size) +{ + d->state->slideWidth = size.width(); + d->state->slideHeight = size.height(); + d->state->reposition(); + triggerRender(); +} + +/*! + \property QxtFlowView::reflectionEffect + \brief the reflection effect + + The default value is PlainReflection. + */ +QxtFlowView::ReflectionEffect QxtFlowView::reflectionEffect() const +{ + return d->state->reflectionEffect; +} + +void QxtFlowView::setReflectionEffect(ReflectionEffect effect) +{ + d->state->reflectionEffect = effect; + d->reset(); +} + +/*! + \property QxtFlowView::pictureRole + \brief the picture role + + The default value is Qt::DecorationRole. + */ +int QxtFlowView::pictureRole() +{ + return d->picrole; +} + +void QxtFlowView::setPictureRole(int a) +{ + d->picrole = a; + d->reset(); +} + +/*! + \property QxtFlowView::pictureColumn + \brief the picture column + + The default value is \c 0. + */ +int QxtFlowView::pictureColumn() +{ + return d->piccolumn; +} + +void QxtFlowView::setPictureColumn(int a) +{ + d->piccolumn = a; + d->reset(); +} + +#if 0 +int QxtFlowView::textRole() +{ + return d->textrole; +} + +void QxtFlowView::setTextRole(int a) +{ + d->textrole = a; + d->reset(); +} + +int QxtFlowView::textColumn() +{ + return d->textcolumn; +} + +void QxtFlowView::setTextColumn(int a) +{ + d->textcolumn = a; + d->reset(); +} +#endif + +/*! + \property QxtFlowView::rootIndex + \brief the root index + + The root index is the parent index to the view's toplevel items. The root can be invalid. + */ +QModelIndex QxtFlowView::rootIndex() const +{ + return d->rootindex; +} + +void QxtFlowView::setRootIndex(QModelIndex index) +{ + d->rootindex = index; +} + +/*! + \property QxtFlowView::currentIndex + \brief the current index + + The slide of the current index is shown in the middle of the viewport. + + \bold {Note:} No animation effect will be produced. + \sa showSlide() + */ +QModelIndex QxtFlowView::currentIndex() const +{ + if (!d->model) + return QModelIndex(); + return d->currentcenter; +} + +void QxtFlowView::setCurrentIndex(QModelIndex index) +{ + d->setCurrentIndex(index); +} + +/*! Rerender the widget. Normally this function will be automatically invoked whenever necessary, e.g. during the transition animation. */ +void QxtFlowView::render() +{ + d->renderer->dirty = true; + update(); +} + +/*! Schedules a rendering update. Unlike render(), this function does not cause immediate rendering.*/ +void QxtFlowView::triggerRender() +{ + d->triggerRender(); +} + +/*! Shows previous slide using animation effect. */ +void QxtFlowView::showPrevious() +{ + int step = d->animator->step; + int center = d->state->centerIndex; + + if (step > 0) + d->animator->start(center); + + if (step == 0) + if (center > 0) + d->animator->start(center - 1); + + if (step < 0) + d->animator->target = qMax(0, center - 2); +} + +/*! Shows next slide using animation effect. */ +void QxtFlowView::showNext() +{ + int step = d->animator->step; + int center = d->state->centerIndex; + + if (step < 0) + d->animator->start(center); + + if (step == 0) + if (center < d->state->slideImages.count() - 1) + d->animator->start(center + 1); + + if (step > 0) + d->animator->target = qMin(center + 2, d->state->slideImages.count() - 1); +} + +/*! Go to specified slide at \a index using animation effect. */ +void QxtFlowView::showSlide(QModelIndex index) +{ + int r = d->modelmap.indexOf(index); + if (r < 0) + return; + + d->showSlide(r); +} + +/*! \reimp */ +void QxtFlowView::keyPressEvent(QKeyEvent* event) +{ + if (event->key() == Qt::Key_Left) + { + if (event->modifiers() == Qt::ControlModifier) + d->showSlide(currentIndex().row() - 10); + else + showPrevious(); + event->accept(); + return; + } + + if (event->key() == Qt::Key_Right) + { + if (event->modifiers() == Qt::ControlModifier) + d->showSlide(currentIndex().row() + 10); + else + showNext(); + event->accept(); + return; + } + + event->ignore(); +} + +/*! \reimp */ +void QxtFlowView::mousePressEvent(QMouseEvent* event) +{ + d->lastgrabpos = event->pos(); +} + +/*! \reimp */ +void QxtFlowView::mouseMoveEvent(QMouseEvent * event) +{ + int i = (event->pos() - d->lastgrabpos).x() / (d->state->slideWidth / 4); + if (i > 0) + { + showPrevious(); + d->lastgrabpos = event->pos(); + } + if (i < 0) + { + showNext(); + d->lastgrabpos = event->pos(); + } + +} + +/*! \reimp */ +void QxtFlowView::mouseReleaseEvent(QMouseEvent* event) +{ + Q_UNUSED(event); + +} + +/*! \reimp */ +void QxtFlowView::paintEvent(QPaintEvent* event) +{ + Q_UNUSED(event); + d->renderer->paint(); +} + +/*! \reimp */ +void QxtFlowView::resizeEvent(QResizeEvent* event) +{ + triggerRender(); + QWidget::resizeEvent(event); +} + +/*! \reimp */ +void QxtFlowView::wheelEvent(QWheelEvent * event) +{ + + if (event->orientation() == Qt::Horizontal) + { + event->ignore(); + } + else + { + int numSteps = -((event->delta() / 8) / 15); + + + + if (numSteps > 0) + { + for (int i = 0;i < numSteps;i++) + { + showNext(); + } + } + else + { + for (int i = numSteps;i < 0;i++) + { + showPrevious(); + } + } + event->accept(); + } + + +} + +/*! \internal */ +void QxtFlowView::updateAnimation() +{ + int old_center = d->state->centerIndex; + d->animator->update(); + triggerRender(); + if (d->state->centerIndex != old_center) + { + d->currentcenter = d->modelmap.at(d->state->centerIndex); + emit currentIndexChanged(d->currentcenter); + } +} + + + + + + + + + +void QxtFlowViewPrivate::columnsAboutToBeInserted(const QModelIndex & parent, int start, int end) +{ + Q_UNUSED(parent); + Q_UNUSED(start); + Q_UNUSED(end); + +} + +void QxtFlowViewPrivate::columnsAboutToBeRemoved(const QModelIndex & parent, int start, int end) +{ + Q_UNUSED(parent); + Q_UNUSED(start); + Q_UNUSED(end); + +} + +void QxtFlowViewPrivate::columnsInserted(const QModelIndex & parent, int start, int end) +{ + Q_UNUSED(parent); + Q_UNUSED(start); + Q_UNUSED(end); + +} + +void QxtFlowViewPrivate::columnsRemoved(const QModelIndex & parent, int start, int end) +{ + Q_UNUSED(parent); + Q_UNUSED(start); + Q_UNUSED(end); +} + +void QxtFlowViewPrivate::dataChanged(const QModelIndex & topLeft, const QModelIndex & bottomRight) +{ + Q_UNUSED(topLeft); + Q_UNUSED(bottomRight); + + if (topLeft.parent() != rootindex) + return; + + if (bottomRight.parent() != rootindex) + return; + + + int start = topLeft.row(); + int end = bottomRight.row(); + + for (int i = start;i <= end;i++) + replaceSlide(i, qvariant_cast(model->data(model->index(i, piccolumn, rootindex), picrole))); +} + +void QxtFlowViewPrivate::headerDataChanged(Qt::Orientation orientation, int first, int last) +{ + Q_UNUSED(orientation); + Q_UNUSED(first); + Q_UNUSED(last); + + + + + +} + +void QxtFlowViewPrivate::layoutAboutToBeChanged() +{ + +} + +void QxtFlowViewPrivate::layoutChanged() +{ + reset(); + setCurrentIndex(currentcenter); +} + +void QxtFlowViewPrivate::modelAboutToBeReset() +{ +} + +void QxtFlowViewPrivate::modelReset() +{ + reset(); +} + +void QxtFlowViewPrivate::rowsAboutToBeInserted(const QModelIndex & parent, int start, int end) +{ + Q_UNUSED(parent); + Q_UNUSED(start); + Q_UNUSED(end); +} + +void QxtFlowViewPrivate::rowsAboutToBeRemoved(const QModelIndex & parent, int start, int end) +{ + Q_UNUSED(parent); + Q_UNUSED(start); + Q_UNUSED(end); +} + +void QxtFlowViewPrivate::rowsInserted(const QModelIndex & parent, int start, int end) +{ + if (rootindex != parent) + return; + for (int i = start;i <= end;i++) + { + QModelIndex idx = model->index(i, piccolumn, rootindex); + insertSlide(i, qvariant_cast(model->data(idx, picrole))); + modelmap.insert(i, idx); + } +} + +void QxtFlowViewPrivate::rowsRemoved(const QModelIndex & parent, int start, int end) +{ + if (rootindex != parent) + return; + for (int i = start;i <= end;i++) + { + removeSlide(i); + modelmap.removeAt(i); + } + +} + +void QxtFlowViewPrivate::setModel(QAbstractItemModel * m) +{ + + + if (model) + { + + disconnect(this->model, SIGNAL(columnsAboutToBeInserted(const QModelIndex & , int , int)), + this, SLOT(columnsAboutToBeInserted(const QModelIndex & , int , int))); + disconnect(this->model, SIGNAL(columnsAboutToBeRemoved(const QModelIndex & , int , int)), + this, SLOT(columnsAboutToBeRemoved(const QModelIndex & , int , int))); + disconnect(this->model, SIGNAL(columnsInserted(const QModelIndex & , int , int)), + this, SLOT(columnsInserted(const QModelIndex & , int , int))); + disconnect(this->model, SIGNAL(columnsRemoved(const QModelIndex & , int , int)), + this, SLOT(columnsRemoved(const QModelIndex & , int , int))); + disconnect(this->model, SIGNAL(dataChanged(const QModelIndex & , const QModelIndex &)), + this, SLOT(dataChanged(const QModelIndex & , const QModelIndex &))); + disconnect(this->model, SIGNAL(headerDataChanged(Qt::Orientation , int , int)), + this, SLOT(headerDataChanged(Qt::Orientation , int , int))); + disconnect(this->model, SIGNAL(layoutAboutToBeChanged()), + this, SLOT(layoutAboutToBeChanged())); + disconnect(this->model, SIGNAL(layoutChanged()), + this, SLOT(layoutChanged())); + disconnect(this->model, SIGNAL(modelAboutToBeReset()), + this, SLOT(modelAboutToBeReset())); + disconnect(this->model, SIGNAL(modelReset()), + this, SLOT(modelReset())); + disconnect(this->model, SIGNAL(rowsAboutToBeInserted(const QModelIndex & , int , int)), + this, SLOT(rowsAboutToBeInserted(const QModelIndex & , int , int))); + disconnect(this->model, SIGNAL(rowsAboutToBeRemoved(const QModelIndex & , int , int)), + this, SLOT(rowsAboutToBeRemoved(const QModelIndex & , int , int))); + disconnect(this->model, SIGNAL(rowsInserted(const QModelIndex & , int , int)), + this, SLOT(rowsInserted(const QModelIndex & , int , int))); + disconnect(this->model, SIGNAL(rowsRemoved(const QModelIndex & , int , int)), + this, SLOT(rowsRemoved(const QModelIndex & , int , int))); + } + model = m; + if (model) + { + rootindex = model->parent(QModelIndex()); + + connect(this->model, SIGNAL(columnsAboutToBeInserted(const QModelIndex & , int , int)), + this, SLOT(columnsAboutToBeInserted(const QModelIndex & , int , int))); + connect(this->model, SIGNAL(columnsAboutToBeRemoved(const QModelIndex & , int , int)), + this, SLOT(columnsAboutToBeRemoved(const QModelIndex & , int , int))); + connect(this->model, SIGNAL(columnsInserted(const QModelIndex & , int , int)), + this, SLOT(columnsInserted(const QModelIndex & , int , int))); + connect(this->model, SIGNAL(columnsRemoved(const QModelIndex & , int , int)), + this, SLOT(columnsRemoved(const QModelIndex & , int , int))); + connect(this->model, SIGNAL(dataChanged(const QModelIndex & , const QModelIndex &)), + this, SLOT(dataChanged(const QModelIndex & , const QModelIndex &))); + connect(this->model, SIGNAL(headerDataChanged(Qt::Orientation , int , int)), + this, SLOT(headerDataChanged(Qt::Orientation , int , int))); + connect(this->model, SIGNAL(layoutAboutToBeChanged()), + this, SLOT(layoutAboutToBeChanged())); + connect(this->model, SIGNAL(layoutChanged()), + this, SLOT(layoutChanged())); + connect(this->model, SIGNAL(modelAboutToBeReset()), + this, SLOT(modelAboutToBeReset())); + connect(this->model, SIGNAL(modelReset()), + this, SLOT(modelReset())); + connect(this->model, SIGNAL(rowsAboutToBeInserted(const QModelIndex & , int , int)), + this, SLOT(rowsAboutToBeInserted(const QModelIndex & , int , int))); + connect(this->model, SIGNAL(rowsAboutToBeRemoved(const QModelIndex & , int , int)), + this, SLOT(rowsAboutToBeRemoved(const QModelIndex & , int , int))); + connect(this->model, SIGNAL(rowsInserted(const QModelIndex & , int , int)), + this, SLOT(rowsInserted(const QModelIndex & , int , int))); + connect(this->model, SIGNAL(rowsRemoved(const QModelIndex & , int , int)), + this, SLOT(rowsRemoved(const QModelIndex & , int , int))); + } + + reset(); +} + + +void QxtFlowViewPrivate::clear() +{ + int c = state->slideImages.count(); + for (int i = 0; i < c; i++) + delete state->slideImages[i]; + state->slideImages.resize(0); + + state->reset(); + modelmap.clear(); + triggerRender(); +} + + +void QxtFlowViewPrivate::triggerRender() +{ + triggerTimer.setSingleShot(true); + triggerTimer.start(0); +} + + + +void QxtFlowViewPrivate::insertSlide(int index, const QImage& image) +{ + state->slideImages.insert(index, new QImage(image)); + triggerRender(); +} + +void QxtFlowViewPrivate::replaceSlide(int index, const QImage& image) +{ + Q_ASSERT((index >= 0) && (index < state->slideImages.count())); + + QImage* i = image.isNull() ? 0 : new QImage(image); + delete state->slideImages[index]; + state->slideImages[index] = i; + triggerRender(); +} + +void QxtFlowViewPrivate::removeSlide(int index) +{ + delete state->slideImages[index]; + state->slideImages.remove(index); + triggerRender(); +} + + +void QxtFlowViewPrivate::showSlide(int index) +{ + if (index == state->centerSlide.slideIndex) + return; + animator->start(index); +} + + + +void QxtFlowViewPrivate::reset() +{ + clear(); + if (model) + { + for (int i = 0;i < model->rowCount(rootindex);i++) + { + QModelIndex idx = model->index(i, piccolumn, rootindex); + insertSlide(i, qvariant_cast(model->data(idx, picrole))); + modelmap.insert(i, idx); + } + if(modelmap.count()) + currentcenter=modelmap.at(0); + else + currentcenter=QModelIndex(); + } + triggerRender(); +} + + + +void QxtFlowViewPrivate::setCurrentIndex(QModelIndex index) +{ + if (model->parent(index) != rootindex) + return; + + int r = modelmap.indexOf(index); + if (r < 0) + return; + + state->centerIndex = r; + state->reset(); + animator->stop(r); + triggerRender(); +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview.h index 49e5d8425..7960b05d5 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview.h @@ -1,150 +1,150 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ** - ** This is a derived work of PictureFlow (http://pictureflow.googlecode.com) - ** The original code was distributed under the following terms: - ** - ** Copyright (C) 2008 Ariya Hidayat (ariya@kde.org) - ** Copyright (C) 2007 Ariya Hidayat (ariya@kde.org) - ** - ** Permission is hereby granted, free of charge, to any person obtaining a copy - ** of this software and associated documentation files (the "Software"), to deal - ** in the Software without restriction, including without limitation the rights - ** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - ** copies of the Software, and to permit persons to whom the Software is - ** furnished to do so, subject to the following conditions: - ** - ** The above copyright notice and this permission notice shall be included in - ** all copies or substantial portions of the Software. - ** - ** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - ** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - ** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - ** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - ** LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - ** OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - ** THE SOFTWARE. - ****************************************************************************/ - -#ifndef QXT_FLOWVIEW_H -#define QXT_FLOWVIEW_H - -#include -#include -#include "qxtglobal.h" - - -class QxtFlowViewPrivate; -class QXT_GUI_EXPORT QxtFlowView : public QWidget -{ - Q_OBJECT - - Q_PROPERTY(QColor backgroundColor READ backgroundColor WRITE setBackgroundColor) - Q_PROPERTY(QSize slideSize READ slideSize WRITE setSlideSize) - Q_PROPERTY(QModelIndex currentIndex READ currentIndex WRITE setCurrentIndex) - Q_PROPERTY(int pictureRole READ pictureRole WRITE setPictureRole) - Q_PROPERTY(int pictureColumn READ pictureColumn WRITE setPictureColumn) - Q_PROPERTY(QModelIndex rootIndex READ rootIndex WRITE setRootIndex) - Q_PROPERTY(ReflectionEffect reflectionEffect READ reflectionEffect WRITE setReflectionEffect) - Q_ENUMS(ReflectionEffect) - -#if 0 - Q_PROPERTY(int textRole READ textRole WRITE setTextRole) - Q_PROPERTY(int textColumn READ textColumn WRITE setTextColumn) -#endif - - -public: - - enum ReflectionEffect - { - NoReflection, - PlainReflection, - BlurredReflection - }; - - QxtFlowView(QWidget* parent = 0); - ~QxtFlowView(); - - void setModel(QAbstractItemModel * model); - QAbstractItemModel * model(); - - QColor backgroundColor() const; - void setBackgroundColor(const QColor& c); - - QSize slideSize() const; - void setSlideSize(QSize size); - - QModelIndex currentIndex() const; - - QModelIndex rootIndex() const; - void setRootIndex(QModelIndex index); - - ReflectionEffect reflectionEffect() const; - void setReflectionEffect(ReflectionEffect effect); - - int pictureRole(); - void setPictureRole(int); - - int pictureColumn(); - void setPictureColumn(int); - -#if 0 - int textRole(); - void setTextRole(int); - int textColumn(); - void setTextColumn(int); -#endif - -public Q_SLOTS: - void setCurrentIndex(QModelIndex index); - - void showPrevious(); - void showNext(); - - void showSlide(QModelIndex index); - - void render(); - void triggerRender(); - -Q_SIGNALS: - void currentIndexChanged(QModelIndex index); - -protected: - virtual void paintEvent(QPaintEvent *event); - virtual void keyPressEvent(QKeyEvent* event); - virtual void mousePressEvent(QMouseEvent* event); - virtual void mouseMoveEvent(QMouseEvent * event); - virtual void mouseReleaseEvent(QMouseEvent* event); - virtual void resizeEvent(QResizeEvent* event); - virtual void wheelEvent(QWheelEvent * event); - -private Q_SLOTS: - void updateAnimation(); - -private: - QxtFlowViewPrivate* d; -}; - -#endif // PICTUREFLOW_H +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ** + ** This is a derived work of PictureFlow (http://pictureflow.googlecode.com) + ** The original code was distributed under the following terms: + ** + ** Copyright (C) 2008 Ariya Hidayat (ariya@kde.org) + ** Copyright (C) 2007 Ariya Hidayat (ariya@kde.org) + ** + ** Permission is hereby granted, free of charge, to any person obtaining a copy + ** of this software and associated documentation files (the "Software"), to deal + ** in the Software without restriction, including without limitation the rights + ** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + ** copies of the Software, and to permit persons to whom the Software is + ** furnished to do so, subject to the following conditions: + ** + ** The above copyright notice and this permission notice shall be included in + ** all copies or substantial portions of the Software. + ** + ** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + ** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + ** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + ** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + ** LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + ** OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + ** THE SOFTWARE. + ****************************************************************************/ + +#ifndef QXT_FLOWVIEW_H +#define QXT_FLOWVIEW_H + +#include +#include +#include "qxtglobal.h" + + +class QxtFlowViewPrivate; +class QXT_GUI_EXPORT QxtFlowView : public QWidget +{ + Q_OBJECT + + Q_PROPERTY(QColor backgroundColor READ backgroundColor WRITE setBackgroundColor) + Q_PROPERTY(QSize slideSize READ slideSize WRITE setSlideSize) + Q_PROPERTY(QModelIndex currentIndex READ currentIndex WRITE setCurrentIndex) + Q_PROPERTY(int pictureRole READ pictureRole WRITE setPictureRole) + Q_PROPERTY(int pictureColumn READ pictureColumn WRITE setPictureColumn) + Q_PROPERTY(QModelIndex rootIndex READ rootIndex WRITE setRootIndex) + Q_PROPERTY(ReflectionEffect reflectionEffect READ reflectionEffect WRITE setReflectionEffect) + Q_ENUMS(ReflectionEffect) + +#if 0 + Q_PROPERTY(int textRole READ textRole WRITE setTextRole) + Q_PROPERTY(int textColumn READ textColumn WRITE setTextColumn) +#endif + + +public: + + enum ReflectionEffect + { + NoReflection, + PlainReflection, + BlurredReflection + }; + + QxtFlowView(QWidget* parent = 0); + ~QxtFlowView(); + + void setModel(QAbstractItemModel * model); + QAbstractItemModel * model(); + + QColor backgroundColor() const; + void setBackgroundColor(const QColor& c); + + QSize slideSize() const; + void setSlideSize(QSize size); + + QModelIndex currentIndex() const; + + QModelIndex rootIndex() const; + void setRootIndex(QModelIndex index); + + ReflectionEffect reflectionEffect() const; + void setReflectionEffect(ReflectionEffect effect); + + int pictureRole(); + void setPictureRole(int); + + int pictureColumn(); + void setPictureColumn(int); + +#if 0 + int textRole(); + void setTextRole(int); + int textColumn(); + void setTextColumn(int); +#endif + +public Q_SLOTS: + void setCurrentIndex(QModelIndex index); + + void showPrevious(); + void showNext(); + + void showSlide(QModelIndex index); + + void render(); + void triggerRender(); + +Q_SIGNALS: + void currentIndexChanged(QModelIndex index); + +protected: + virtual void paintEvent(QPaintEvent *event); + virtual void keyPressEvent(QKeyEvent* event); + virtual void mousePressEvent(QMouseEvent* event); + virtual void mouseMoveEvent(QMouseEvent * event); + virtual void mouseReleaseEvent(QMouseEvent* event); + virtual void resizeEvent(QResizeEvent* event); + virtual void wheelEvent(QWheelEvent * event); + +private Q_SLOTS: + void updateAnimation(); + +private: + QxtFlowViewPrivate* d; +}; + +#endif // PICTUREFLOW_H diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview_p.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview_p.cpp index c1ca3361d..ee68a664d 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview_p.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview_p.cpp @@ -1,714 +1,714 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ** - ** This is a derived work of QxtFlowView (http://pictureflow.googlecode.com) - ** The original code was distributed under the following terms: - ** - ** Copyright (C) 2008 Ariya Hidayat (ariya@kde.org) - ** Copyright (C) 2007 Ariya Hidayat (ariya@kde.org) - ** - ** Permission is hereby granted, free of charge, to any person obtaining a copy - ** of this software and associated documentation files (the "Software"), to deal - ** in the Software without restriction, including without limitation the rights - ** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - ** copies of the Software, and to permit persons to whom the Software is - ** furnished to do so, subject to the following conditions: - ** - ** The above copyright notice and this permission notice shall be included in - ** all copies or substantial portions of the Software. - ** - ** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - ** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - ** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - ** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - ** LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - ** OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - ** THE SOFTWARE. - ****************************************************************************/ - -#include "qxtflowview_p.h" - - - - -// ------------- QxtFlowViewState --------------------------------------- - -QxtFlowViewState::QxtFlowViewState(): - backgroundColor(0), slideWidth(150), slideHeight(200), - reflectionEffect(QxtFlowView::BlurredReflection), centerIndex(0) -{ -} - -QxtFlowViewState::~QxtFlowViewState() -{ - for (int i = 0; i < (int)slideImages.count(); i++) - delete slideImages[i]; -} - -// readjust the settings, call this when slide dimension is changed -void QxtFlowViewState::reposition() -{ - angle = 70 * IANGLE_MAX / 360; // approx. 70 degrees tilted - - offsetX = slideWidth / 2 * (PFREAL_ONE - fcos(angle)); - offsetY = slideWidth / 2 * fsin(angle); - offsetX += slideWidth * PFREAL_ONE; - offsetY += slideWidth * PFREAL_ONE / 4; - spacing = 40; -} - -// adjust slides so that they are in "steady state" position -void QxtFlowViewState::reset() -{ - centerSlide.angle = 0; - centerSlide.cx = 0; - centerSlide.cy = 0; - centerSlide.slideIndex = centerIndex; - centerSlide.blend = 256; - - leftSlides.resize(6); - for (int i = 0; i < (int)leftSlides.count(); i++) - { - SlideInfo& si = leftSlides[i]; - si.angle = angle; - si.cx = -(offsetX + spacing * i * PFREAL_ONE); - si.cy = offsetY; - si.slideIndex = centerIndex - 1 - i; - si.blend = 256; - if (i == (int)leftSlides.count() - 2) - si.blend = 128; - if (i == (int)leftSlides.count() - 1) - si.blend = 0; - } - - rightSlides.resize(6); - for (int i = 0; i < (int)rightSlides.count(); i++) - { - SlideInfo& si = rightSlides[i]; - si.angle = -angle; - si.cx = offsetX + spacing * i * PFREAL_ONE; - si.cy = offsetY; - si.slideIndex = centerIndex + 1 + i; - si.blend = 256; - if (i == (int)rightSlides.count() - 2) - si.blend = 128; - if (i == (int)rightSlides.count() - 1) - si.blend = 0; - } -} - -// ------------- QxtFlowViewAnimator --------------------------------------- - -QxtFlowViewAnimator::QxtFlowViewAnimator(): - state(0), target(0), step(0), frame(0) -{ -} - -void QxtFlowViewAnimator::start(int slide) -{ - target = slide; - if (!animateTimer.isActive() && state) - { - step = (target < state->centerSlide.slideIndex) ? -1 : 1; - animateTimer.start(30); - } -} - -void QxtFlowViewAnimator::stop(int slide) -{ - step = 0; - target = slide; - frame = slide << 16; - animateTimer.stop(); -} - -void QxtFlowViewAnimator::update() -{ - if (!animateTimer.isActive()) - return; - if (step == 0) - return; - if (!state) - return; - - int speed = 16384 / 4; - -#if 1 - // deaccelerate when approaching the target - const int max = 2 * 65536; - - int fi = frame; - fi -= (target << 16); - if (fi < 0) - fi = -fi; - fi = qMin(fi, max); - - int ia = IANGLE_MAX * (fi - max / 2) / (max * 2); - speed = 512 + 16384 * (PFREAL_ONE + fsin(ia)) / PFREAL_ONE; -#endif - - frame += speed * step; - - int index = frame >> 16; - int pos = frame & 0xffff; - int neg = 65536 - pos; - int tick = (step < 0) ? neg : pos; - PFreal ftick = (tick * PFREAL_ONE) >> 16; - - if (step < 0) - index++; - - if (state->centerIndex != index) - { - state->centerIndex = index; - frame = index << 16; - state->centerSlide.slideIndex = state->centerIndex; - for (int i = 0; i < (int)state->leftSlides.count(); i++) - state->leftSlides[i].slideIndex = state->centerIndex - 1 - i; - for (int i = 0; i < (int)state->rightSlides.count(); i++) - state->rightSlides[i].slideIndex = state->centerIndex + 1 + i; - } - - state->centerSlide.angle = (step * tick * state->angle) >> 16; - state->centerSlide.cx = -step * fmul(state->offsetX, ftick); - state->centerSlide.cy = fmul(state->offsetY, ftick); - - if (state->centerIndex == target) - { - stop(target); - state->reset(); - return; - } - - for (int i = 0; i < (int)state->leftSlides.count(); i++) - { - SlideInfo& si = state->leftSlides[i]; - si.angle = state->angle; - si.cx = -(state->offsetX + state->spacing * i * PFREAL_ONE + step * state->spacing * ftick); - si.cy = state->offsetY; - } - - for (int i = 0; i < (int)state->rightSlides.count(); i++) - { - SlideInfo& si = state->rightSlides[i]; - si.angle = -state->angle; - si.cx = state->offsetX + state->spacing * i * PFREAL_ONE - step * state->spacing * ftick; - si.cy = state->offsetY; - } - - if (step > 0) - { - PFreal ftick = (neg * PFREAL_ONE) >> 16; - state->rightSlides[0].angle = -(neg * state->angle) >> 16; - state->rightSlides[0].cx = fmul(state->offsetX, ftick); - state->rightSlides[0].cy = fmul(state->offsetY, ftick); - } - else - { - PFreal ftick = (pos * PFREAL_ONE) >> 16; - state->leftSlides[0].angle = (pos * state->angle) >> 16; - state->leftSlides[0].cx = -fmul(state->offsetX, ftick); - state->leftSlides[0].cy = fmul(state->offsetY, ftick); - } - - // must change direction ? - if (target < index) if (step > 0) - step = -1; - if (target > index) if (step < 0) - step = 1; - - // the first and last slide must fade in/fade out - int nleft = state->leftSlides.count(); - int nright = state->rightSlides.count(); - int fade = pos / 256; - - for (int index = 0; index < nleft; index++) - { - int blend = 256; - if (index == nleft - 1) - blend = (step > 0) ? 0 : 128 - fade / 2; - if (index == nleft - 2) - blend = (step > 0) ? 128 - fade / 2 : 256 - fade / 2; - if (index == nleft - 3) - blend = (step > 0) ? 256 - fade / 2 : 256; - state->leftSlides[index].blend = blend; - } - for (int index = 0; index < nright; index++) - { - int blend = (index < nright - 2) ? 256 : 128; - if (index == nright - 1) - blend = (step > 0) ? fade / 2 : 0; - if (index == nright - 2) - blend = (step > 0) ? 128 + fade / 2 : fade / 2; - if (index == nright - 3) - blend = (step > 0) ? 256 : 128 + fade / 2; - state->rightSlides[index].blend = blend; - } - -} - -// ------------- QxtFlowViewSoftwareRenderer --------------------------------------- - -QxtFlowViewSoftwareRenderer::QxtFlowViewSoftwareRenderer(): - QxtFlowViewAbstractRenderer(), size(0, 0), bgcolor(0), effect(-1), blankSurface(0) -{ -} - -QxtFlowViewSoftwareRenderer::~QxtFlowViewSoftwareRenderer() -{ - surfaceCache.clear(); - buffer = QImage(); - delete blankSurface; -} - -void QxtFlowViewSoftwareRenderer::paint() -{ - if (!widget) - return; - - if (widget->size() != size) - init(); - - if (state->backgroundColor != bgcolor) - { - bgcolor = state->backgroundColor; - surfaceCache.clear(); - } - - if ((int)(state->reflectionEffect) != effect) - { - effect = (int)state->reflectionEffect; - surfaceCache.clear(); - } - - if (dirty) - render(); - - QPainter painter(widget); - painter.drawImage(QPoint(0, 0), buffer); -} - -void QxtFlowViewSoftwareRenderer::init() -{ - if (!widget) - return; - - surfaceCache.clear(); - blankSurface = 0; - - size = widget->size(); - int ww = size.width(); - int wh = size.height(); - int w = (ww + 1) / 2; - int h = (wh + 1) / 2; - -#ifdef PICTUREFLOW_QT4 - buffer = QImage(ww, wh, QImage::Format_RGB32); -#endif -#if defined(PICTUREFLOW_QT3) || defined(PICTUREFLOW_QT2) - buffer.create(ww, wh, 32); -#endif - buffer.fill(bgcolor); - - rays.resize(w*2); - for (int i = 0; i < w; i++) - { - PFreal gg = ((PFREAL_ONE >> 1) + i * PFREAL_ONE) / (2 * h); - rays[w-i-1] = -gg; - rays[w+i] = gg; - } - - dirty = true; -} - -// TODO: optimize this with lookup tables -static QRgb blendColor(QRgb c1, QRgb c2, int blend) -{ - int r = qRed(c1) * blend / 256 + qRed(c2) * (256 - blend) / 256; - int g = qGreen(c1) * blend / 256 + qGreen(c2) * (256 - blend) / 256; - int b = qBlue(c1) * blend / 256 + qBlue(c2) * (256 - blend) / 256; - return qRgb(r, g, b); -} - - -static QImage* prepareSurface(const QImage* slideImage, int w, int h, QRgb bgcolor, - QxtFlowView::ReflectionEffect reflectionEffect) -{ -#ifdef PICTUREFLOW_QT4 - Qt::TransformationMode mode = Qt::SmoothTransformation; - QImage img = slideImage->scaled(w, h, Qt::IgnoreAspectRatio, mode); -#endif -#if defined(PICTUREFLOW_QT3) || defined(PICTUREFLOW_QT2) - QImage img = slideImage->smoothScale(w, h); -#endif - - // slightly larger, to accommodate for the reflection - int hs = h * 2; - int hofs = h / 3; - - // offscreen buffer: black is sweet -#ifdef PICTUREFLOW_QT4 - QImage* result = new QImage(hs, w, QImage::Format_RGB32); -#endif -#if defined(PICTUREFLOW_QT3) || defined(PICTUREFLOW_QT2) - QImage* result = new QImage; - result->create(hs, w, 32); -#endif - result->fill(bgcolor); - - // transpose the image, this is to speed-up the rendering - // because we process one column at a time - // (and much better and faster to work row-wise, i.e in one scanline) - for (int x = 0; x < w; x++) - for (int y = 0; y < h; y++) - result->setPixel(hofs + y, x, img.pixel(x, y)); - - if (reflectionEffect != QxtFlowView::NoReflection) - { - // create the reflection - int ht = hs - h - hofs; - int hte = ht; - for (int x = 0; x < w; x++) - for (int y = 0; y < ht; y++) - { - QRgb color = img.pixel(x, img.height() - y - 1); - result->setPixel(h + hofs + y, x, blendColor(color, bgcolor, 128*(hte - y) / hte)); - } - - if (reflectionEffect == QxtFlowView::BlurredReflection) - { - // blur the reflection everything first - // Based on exponential blur algorithm by Jani Huhtanen - QRect rect(hs / 2, 0, hs / 2, w); - rect &= result->rect(); - - int r1 = rect.top(); - int r2 = rect.bottom(); - int c1 = rect.left(); - int c2 = rect.right(); - - int bpl = result->bytesPerLine(); - int rgba[4]; - unsigned char* p; - - // how many times blur is applied? - // for low-end system, limit this to only 1 loop - for (int loop = 0; loop < 2; loop++) - { - for (int col = c1; col <= c2; col++) - { - p = result->scanLine(r1) + col * 4; - for (int i = 0; i < 3; i++) - rgba[i] = p[i] << 4; - - p += bpl; - for (int j = r1; j < r2; j++, p += bpl) - for (int i = 0; i < 3; i++) - p[i] = (rgba[i] += (((p[i] << 4) - rgba[i])) >> 1) >> 4; - } - - for (int row = r1; row <= r2; row++) - { - p = result->scanLine(row) + c1 * 4; - for (int i = 0; i < 3; i++) - rgba[i] = p[i] << 4; - - p += 4; - for (int j = c1; j < c2; j++, p += 4) - for (int i = 0; i < 3; i++) - p[i] = (rgba[i] += (((p[i] << 4) - rgba[i])) >> 1) >> 4; - } - - for (int col = c1; col <= c2; col++) - { - p = result->scanLine(r2) + col * 4; - for (int i = 0; i < 3; i++) - rgba[i] = p[i] << 4; - - p -= bpl; - for (int j = r1; j < r2; j++, p -= bpl) - for (int i = 0; i < 3; i++) - p[i] = (rgba[i] += (((p[i] << 4) - rgba[i])) >> 1) >> 4; - } - - for (int row = r1; row <= r2; row++) - { - p = result->scanLine(row) + c2 * 4; - for (int i = 0; i < 3; i++) - rgba[i] = p[i] << 4; - - p -= 4; - for (int j = c1; j < c2; j++, p -= 4) - for (int i = 0; i < 3; i++) - p[i] = (rgba[i] += (((p[i] << 4) - rgba[i])) >> 1) >> 4; - } - } - - // overdraw to leave only the reflection blurred (but not the actual image) - for (int x = 0; x < w; x++) - for (int y = 0; y < h; y++) - result->setPixel(hofs + y, x, img.pixel(x, y)); - } - } - - return result; -} - -QImage* QxtFlowViewSoftwareRenderer::surface(int slideIndex) -{ - if (!state) - return 0; - if (slideIndex < 0) - return 0; - if (slideIndex >= (int)state->slideImages.count()) - return 0; - -#ifdef PICTUREFLOW_QT4 - int key = slideIndex; -#endif -#if defined(PICTUREFLOW_QT3) || defined(PICTUREFLOW_QT2) - QString key = QString::number(slideIndex); -#endif - - QImage* img = state->slideImages.at(slideIndex); - bool empty = img ? img->isNull() : true; - if (empty) - { - surfaceCache.remove(key); - imageHash.remove(slideIndex); - if (!blankSurface) - { - int sw = state->slideWidth; - int sh = state->slideHeight; - -#ifdef PICTUREFLOW_QT4 - QImage img = QImage(sw, sh, QImage::Format_RGB32); - - QPainter painter(&img); - QPoint p1(sw*4 / 10, 0); - QPoint p2(sw*6 / 10, sh); - QLinearGradient linearGrad(p1, p2); - linearGrad.setColorAt(0, Qt::black); - linearGrad.setColorAt(1, Qt::white); - painter.setBrush(linearGrad); - painter.fillRect(0, 0, sw, sh, QBrush(linearGrad)); - - painter.setPen(QPen(QColor(64, 64, 64), 4)); - painter.setBrush(QBrush()); - painter.drawRect(2, 2, sw - 3, sh - 3); - painter.end(); -#endif -#if defined(PICTUREFLOW_QT3) || defined(PICTUREFLOW_QT2) - QPixmap pixmap(sw, sh, 32); - QPainter painter(&pixmap); - painter.fillRect(pixmap.rect(), QColor(192, 192, 192)); - painter.fillRect(5, 5, sw - 10, sh - 10, QColor(64, 64, 64)); - painter.end(); - QImage img = pixmap.convertToImage(); -#endif - - blankSurface = prepareSurface(&img, sw, sh, bgcolor, state->reflectionEffect); - } - return blankSurface; - } - -#ifdef PICTUREFLOW_QT4 - bool exist = imageHash.contains(slideIndex); - if (exist) - if (img == imageHash.find(slideIndex).value()) -#endif -#ifdef PICTUREFLOW_QT3 - bool exist = imageHash.find(slideIndex) != imageHash.end(); - if (exist) - if (img == imageHash.find(slideIndex).data()) -#endif -#ifdef PICTUREFLOW_QT2 - if (img == imageHash[slideIndex]) -#endif - if (surfaceCache.contains(key)) - return surfaceCache[key]; - - QImage* sr = prepareSurface(img, state->slideWidth, state->slideHeight, bgcolor, state->reflectionEffect); - surfaceCache.insert(key, sr); - imageHash.insert(slideIndex, img); - - return sr; -} - -// Renders a slide to offscreen buffer. Returns a rect of the rendered area. -// col1 and col2 limit the column for rendering. -QRect QxtFlowViewSoftwareRenderer::renderSlide(const SlideInfo &slide, int col1, int col2) -{ - int blend = slide.blend; - if (!blend) - return QRect(); - - QImage* src = surface(slide.slideIndex); - if (!src) - return QRect(); - - QRect rect(0, 0, 0, 0); - - int sw = src->height(); - int sh = src->width(); - int h = buffer.height(); - int w = buffer.width(); - - if (col1 > col2) - { - int c = col2; - col2 = col1; - col1 = c; - } - - col1 = (col1 >= 0) ? col1 : 0; - col2 = (col2 >= 0) ? col2 : w - 1; - col1 = qMin(col1, w - 1); - col2 = qMin(col2, w - 1); - - int zoom = 100; - int distance = h * 100 / zoom; - PFreal sdx = fcos(slide.angle); - PFreal sdy = fsin(slide.angle); - PFreal xs = slide.cx - state->slideWidth * sdx / 2; - PFreal ys = slide.cy - state->slideWidth * sdy / 2; - PFreal dist = distance * PFREAL_ONE; - - int xi = qMax((PFreal)0, ((w * PFREAL_ONE / 2) + fdiv(xs * h, dist + ys)) >> PFREAL_SHIFT); - if (xi >= w) - return rect; - - bool flag = false; - rect.setLeft(xi); - for (int x = qMax(xi, col1); x <= col2; x++) - { - PFreal hity = 0; - PFreal fk = rays[x]; - if (sdy) - { - fk = fk - fdiv(sdx, sdy); - hity = -fdiv((rays[x] * distance - slide.cx + slide.cy * sdx / sdy), fk); - } - - dist = distance * PFREAL_ONE + hity; - if (dist < 0) - continue; - - PFreal hitx = fmul(dist, rays[x]); - PFreal hitdist = fdiv(hitx - slide.cx, sdx); - - int column = sw / 2 + (hitdist >> PFREAL_SHIFT); - if (column >= sw) - break; - if (column < 0) - continue; - - rect.setRight(x); - if (!flag) - rect.setLeft(x); - flag = true; - - int y1 = h / 2; - int y2 = y1 + 1; - QRgb* pixel1 = (QRgb*)(buffer.scanLine(y1)) + x; - QRgb* pixel2 = (QRgb*)(buffer.scanLine(y2)) + x; - QRgb pixelstep = pixel2 - pixel1; - - int center = (sh / 2); - int dy = dist / h; - int p1 = center * PFREAL_ONE - dy / 2; - int p2 = center * PFREAL_ONE + dy / 2; - - const QRgb *ptr = (const QRgb*)(src->scanLine(column)); - if (blend == 256) - while ((y1 >= 0) && (y2 < h) && (p1 >= 0)) - { - *pixel1 = ptr[p1 >> PFREAL_SHIFT]; - *pixel2 = ptr[p2 >> PFREAL_SHIFT]; - p1 -= dy; - p2 += dy; - y1--; - y2++; - pixel1 -= pixelstep; - pixel2 += pixelstep; - } - else - while ((y1 >= 0) && (y2 < h) && (p1 >= 0)) - { - QRgb c1 = ptr[p1 >> PFREAL_SHIFT]; - QRgb c2 = ptr[p2 >> PFREAL_SHIFT]; - *pixel1 = blendColor(c1, bgcolor, blend); - *pixel2 = blendColor(c2, bgcolor, blend); - p1 -= dy; - p2 += dy; - y1--; - y2++; - pixel1 -= pixelstep; - pixel2 += pixelstep; - } - } - - rect.setTop(0); - rect.setBottom(h - 1); - return rect; -} - -void QxtFlowViewSoftwareRenderer::renderSlides() -{ - int nleft = state->leftSlides.count(); - int nright = state->rightSlides.count(); - - QRect r = renderSlide(state->centerSlide); - int c1 = r.left(); - int c2 = r.right(); - - for (int index = 0; index < nleft; index++) - { - QRect rs = renderSlide(state->leftSlides[index], 0, c1 - 1); - if (!rs.isEmpty()) - c1 = rs.left(); - } - for (int index = 0; index < nright; index++) - { - QRect rs = renderSlide(state->rightSlides[index], c2 + 1, buffer.width()); - if (!rs.isEmpty()) - c2 = rs.right(); - } -} - -// Render the slides. Updates only the offscreen buffer. -void QxtFlowViewSoftwareRenderer::render() -{ - buffer.fill(state->backgroundColor); - renderSlides(); - dirty = false; -} - - - - - - - - +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ** + ** This is a derived work of QxtFlowView (http://pictureflow.googlecode.com) + ** The original code was distributed under the following terms: + ** + ** Copyright (C) 2008 Ariya Hidayat (ariya@kde.org) + ** Copyright (C) 2007 Ariya Hidayat (ariya@kde.org) + ** + ** Permission is hereby granted, free of charge, to any person obtaining a copy + ** of this software and associated documentation files (the "Software"), to deal + ** in the Software without restriction, including without limitation the rights + ** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + ** copies of the Software, and to permit persons to whom the Software is + ** furnished to do so, subject to the following conditions: + ** + ** The above copyright notice and this permission notice shall be included in + ** all copies or substantial portions of the Software. + ** + ** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + ** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + ** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + ** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + ** LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + ** OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + ** THE SOFTWARE. + ****************************************************************************/ + +#include "qxtflowview_p.h" + + + + +// ------------- QxtFlowViewState --------------------------------------- + +QxtFlowViewState::QxtFlowViewState(): + backgroundColor(0), slideWidth(150), slideHeight(200), + reflectionEffect(QxtFlowView::BlurredReflection), centerIndex(0) +{ +} + +QxtFlowViewState::~QxtFlowViewState() +{ + for (int i = 0; i < (int)slideImages.count(); i++) + delete slideImages[i]; +} + +// readjust the settings, call this when slide dimension is changed +void QxtFlowViewState::reposition() +{ + angle = 70 * IANGLE_MAX / 360; // approx. 70 degrees tilted + + offsetX = slideWidth / 2 * (PFREAL_ONE - fcos(angle)); + offsetY = slideWidth / 2 * fsin(angle); + offsetX += slideWidth * PFREAL_ONE; + offsetY += slideWidth * PFREAL_ONE / 4; + spacing = 40; +} + +// adjust slides so that they are in "steady state" position +void QxtFlowViewState::reset() +{ + centerSlide.angle = 0; + centerSlide.cx = 0; + centerSlide.cy = 0; + centerSlide.slideIndex = centerIndex; + centerSlide.blend = 256; + + leftSlides.resize(6); + for (int i = 0; i < (int)leftSlides.count(); i++) + { + SlideInfo& si = leftSlides[i]; + si.angle = angle; + si.cx = -(offsetX + spacing * i * PFREAL_ONE); + si.cy = offsetY; + si.slideIndex = centerIndex - 1 - i; + si.blend = 256; + if (i == (int)leftSlides.count() - 2) + si.blend = 128; + if (i == (int)leftSlides.count() - 1) + si.blend = 0; + } + + rightSlides.resize(6); + for (int i = 0; i < (int)rightSlides.count(); i++) + { + SlideInfo& si = rightSlides[i]; + si.angle = -angle; + si.cx = offsetX + spacing * i * PFREAL_ONE; + si.cy = offsetY; + si.slideIndex = centerIndex + 1 + i; + si.blend = 256; + if (i == (int)rightSlides.count() - 2) + si.blend = 128; + if (i == (int)rightSlides.count() - 1) + si.blend = 0; + } +} + +// ------------- QxtFlowViewAnimator --------------------------------------- + +QxtFlowViewAnimator::QxtFlowViewAnimator(): + state(0), target(0), step(0), frame(0) +{ +} + +void QxtFlowViewAnimator::start(int slide) +{ + target = slide; + if (!animateTimer.isActive() && state) + { + step = (target < state->centerSlide.slideIndex) ? -1 : 1; + animateTimer.start(30); + } +} + +void QxtFlowViewAnimator::stop(int slide) +{ + step = 0; + target = slide; + frame = slide << 16; + animateTimer.stop(); +} + +void QxtFlowViewAnimator::update() +{ + if (!animateTimer.isActive()) + return; + if (step == 0) + return; + if (!state) + return; + + int speed = 16384 / 4; + +#if 1 + // deaccelerate when approaching the target + const int max = 2 * 65536; + + int fi = frame; + fi -= (target << 16); + if (fi < 0) + fi = -fi; + fi = qMin(fi, max); + + int ia = IANGLE_MAX * (fi - max / 2) / (max * 2); + speed = 512 + 16384 * (PFREAL_ONE + fsin(ia)) / PFREAL_ONE; +#endif + + frame += speed * step; + + int index = frame >> 16; + int pos = frame & 0xffff; + int neg = 65536 - pos; + int tick = (step < 0) ? neg : pos; + PFreal ftick = (tick * PFREAL_ONE) >> 16; + + if (step < 0) + index++; + + if (state->centerIndex != index) + { + state->centerIndex = index; + frame = index << 16; + state->centerSlide.slideIndex = state->centerIndex; + for (int i = 0; i < (int)state->leftSlides.count(); i++) + state->leftSlides[i].slideIndex = state->centerIndex - 1 - i; + for (int i = 0; i < (int)state->rightSlides.count(); i++) + state->rightSlides[i].slideIndex = state->centerIndex + 1 + i; + } + + state->centerSlide.angle = (step * tick * state->angle) >> 16; + state->centerSlide.cx = -step * fmul(state->offsetX, ftick); + state->centerSlide.cy = fmul(state->offsetY, ftick); + + if (state->centerIndex == target) + { + stop(target); + state->reset(); + return; + } + + for (int i = 0; i < (int)state->leftSlides.count(); i++) + { + SlideInfo& si = state->leftSlides[i]; + si.angle = state->angle; + si.cx = -(state->offsetX + state->spacing * i * PFREAL_ONE + step * state->spacing * ftick); + si.cy = state->offsetY; + } + + for (int i = 0; i < (int)state->rightSlides.count(); i++) + { + SlideInfo& si = state->rightSlides[i]; + si.angle = -state->angle; + si.cx = state->offsetX + state->spacing * i * PFREAL_ONE - step * state->spacing * ftick; + si.cy = state->offsetY; + } + + if (step > 0) + { + PFreal ftick = (neg * PFREAL_ONE) >> 16; + state->rightSlides[0].angle = -(neg * state->angle) >> 16; + state->rightSlides[0].cx = fmul(state->offsetX, ftick); + state->rightSlides[0].cy = fmul(state->offsetY, ftick); + } + else + { + PFreal ftick = (pos * PFREAL_ONE) >> 16; + state->leftSlides[0].angle = (pos * state->angle) >> 16; + state->leftSlides[0].cx = -fmul(state->offsetX, ftick); + state->leftSlides[0].cy = fmul(state->offsetY, ftick); + } + + // must change direction ? + if (target < index) if (step > 0) + step = -1; + if (target > index) if (step < 0) + step = 1; + + // the first and last slide must fade in/fade out + int nleft = state->leftSlides.count(); + int nright = state->rightSlides.count(); + int fade = pos / 256; + + for (int index = 0; index < nleft; index++) + { + int blend = 256; + if (index == nleft - 1) + blend = (step > 0) ? 0 : 128 - fade / 2; + if (index == nleft - 2) + blend = (step > 0) ? 128 - fade / 2 : 256 - fade / 2; + if (index == nleft - 3) + blend = (step > 0) ? 256 - fade / 2 : 256; + state->leftSlides[index].blend = blend; + } + for (int index = 0; index < nright; index++) + { + int blend = (index < nright - 2) ? 256 : 128; + if (index == nright - 1) + blend = (step > 0) ? fade / 2 : 0; + if (index == nright - 2) + blend = (step > 0) ? 128 + fade / 2 : fade / 2; + if (index == nright - 3) + blend = (step > 0) ? 256 : 128 + fade / 2; + state->rightSlides[index].blend = blend; + } + +} + +// ------------- QxtFlowViewSoftwareRenderer --------------------------------------- + +QxtFlowViewSoftwareRenderer::QxtFlowViewSoftwareRenderer(): + QxtFlowViewAbstractRenderer(), size(0, 0), bgcolor(0), effect(-1), blankSurface(0) +{ +} + +QxtFlowViewSoftwareRenderer::~QxtFlowViewSoftwareRenderer() +{ + surfaceCache.clear(); + buffer = QImage(); + delete blankSurface; +} + +void QxtFlowViewSoftwareRenderer::paint() +{ + if (!widget) + return; + + if (widget->size() != size) + init(); + + if (state->backgroundColor != bgcolor) + { + bgcolor = state->backgroundColor; + surfaceCache.clear(); + } + + if ((int)(state->reflectionEffect) != effect) + { + effect = (int)state->reflectionEffect; + surfaceCache.clear(); + } + + if (dirty) + render(); + + QPainter painter(widget); + painter.drawImage(QPoint(0, 0), buffer); +} + +void QxtFlowViewSoftwareRenderer::init() +{ + if (!widget) + return; + + surfaceCache.clear(); + blankSurface = 0; + + size = widget->size(); + int ww = size.width(); + int wh = size.height(); + int w = (ww + 1) / 2; + int h = (wh + 1) / 2; + +#ifdef PICTUREFLOW_QT4 + buffer = QImage(ww, wh, QImage::Format_RGB32); +#endif +#if defined(PICTUREFLOW_QT3) || defined(PICTUREFLOW_QT2) + buffer.create(ww, wh, 32); +#endif + buffer.fill(bgcolor); + + rays.resize(w*2); + for (int i = 0; i < w; i++) + { + PFreal gg = ((PFREAL_ONE >> 1) + i * PFREAL_ONE) / (2 * h); + rays[w-i-1] = -gg; + rays[w+i] = gg; + } + + dirty = true; +} + +// TODO: optimize this with lookup tables +static QRgb blendColor(QRgb c1, QRgb c2, int blend) +{ + int r = qRed(c1) * blend / 256 + qRed(c2) * (256 - blend) / 256; + int g = qGreen(c1) * blend / 256 + qGreen(c2) * (256 - blend) / 256; + int b = qBlue(c1) * blend / 256 + qBlue(c2) * (256 - blend) / 256; + return qRgb(r, g, b); +} + + +static QImage* prepareSurface(const QImage* slideImage, int w, int h, QRgb bgcolor, + QxtFlowView::ReflectionEffect reflectionEffect) +{ +#ifdef PICTUREFLOW_QT4 + Qt::TransformationMode mode = Qt::SmoothTransformation; + QImage img = slideImage->scaled(w, h, Qt::IgnoreAspectRatio, mode); +#endif +#if defined(PICTUREFLOW_QT3) || defined(PICTUREFLOW_QT2) + QImage img = slideImage->smoothScale(w, h); +#endif + + // slightly larger, to accommodate for the reflection + int hs = h * 2; + int hofs = h / 3; + + // offscreen buffer: black is sweet +#ifdef PICTUREFLOW_QT4 + QImage* result = new QImage(hs, w, QImage::Format_RGB32); +#endif +#if defined(PICTUREFLOW_QT3) || defined(PICTUREFLOW_QT2) + QImage* result = new QImage; + result->create(hs, w, 32); +#endif + result->fill(bgcolor); + + // transpose the image, this is to speed-up the rendering + // because we process one column at a time + // (and much better and faster to work row-wise, i.e in one scanline) + for (int x = 0; x < w; x++) + for (int y = 0; y < h; y++) + result->setPixel(hofs + y, x, img.pixel(x, y)); + + if (reflectionEffect != QxtFlowView::NoReflection) + { + // create the reflection + int ht = hs - h - hofs; + int hte = ht; + for (int x = 0; x < w; x++) + for (int y = 0; y < ht; y++) + { + QRgb color = img.pixel(x, img.height() - y - 1); + result->setPixel(h + hofs + y, x, blendColor(color, bgcolor, 128*(hte - y) / hte)); + } + + if (reflectionEffect == QxtFlowView::BlurredReflection) + { + // blur the reflection everything first + // Based on exponential blur algorithm by Jani Huhtanen + QRect rect(hs / 2, 0, hs / 2, w); + rect &= result->rect(); + + int r1 = rect.top(); + int r2 = rect.bottom(); + int c1 = rect.left(); + int c2 = rect.right(); + + int bpl = result->bytesPerLine(); + int rgba[4]; + unsigned char* p; + + // how many times blur is applied? + // for low-end system, limit this to only 1 loop + for (int loop = 0; loop < 2; loop++) + { + for (int col = c1; col <= c2; col++) + { + p = result->scanLine(r1) + col * 4; + for (int i = 0; i < 3; i++) + rgba[i] = p[i] << 4; + + p += bpl; + for (int j = r1; j < r2; j++, p += bpl) + for (int i = 0; i < 3; i++) + p[i] = (rgba[i] += (((p[i] << 4) - rgba[i])) >> 1) >> 4; + } + + for (int row = r1; row <= r2; row++) + { + p = result->scanLine(row) + c1 * 4; + for (int i = 0; i < 3; i++) + rgba[i] = p[i] << 4; + + p += 4; + for (int j = c1; j < c2; j++, p += 4) + for (int i = 0; i < 3; i++) + p[i] = (rgba[i] += (((p[i] << 4) - rgba[i])) >> 1) >> 4; + } + + for (int col = c1; col <= c2; col++) + { + p = result->scanLine(r2) + col * 4; + for (int i = 0; i < 3; i++) + rgba[i] = p[i] << 4; + + p -= bpl; + for (int j = r1; j < r2; j++, p -= bpl) + for (int i = 0; i < 3; i++) + p[i] = (rgba[i] += (((p[i] << 4) - rgba[i])) >> 1) >> 4; + } + + for (int row = r1; row <= r2; row++) + { + p = result->scanLine(row) + c2 * 4; + for (int i = 0; i < 3; i++) + rgba[i] = p[i] << 4; + + p -= 4; + for (int j = c1; j < c2; j++, p -= 4) + for (int i = 0; i < 3; i++) + p[i] = (rgba[i] += (((p[i] << 4) - rgba[i])) >> 1) >> 4; + } + } + + // overdraw to leave only the reflection blurred (but not the actual image) + for (int x = 0; x < w; x++) + for (int y = 0; y < h; y++) + result->setPixel(hofs + y, x, img.pixel(x, y)); + } + } + + return result; +} + +QImage* QxtFlowViewSoftwareRenderer::surface(int slideIndex) +{ + if (!state) + return 0; + if (slideIndex < 0) + return 0; + if (slideIndex >= (int)state->slideImages.count()) + return 0; + +#ifdef PICTUREFLOW_QT4 + int key = slideIndex; +#endif +#if defined(PICTUREFLOW_QT3) || defined(PICTUREFLOW_QT2) + QString key = QString::number(slideIndex); +#endif + + QImage* img = state->slideImages.at(slideIndex); + bool empty = img ? img->isNull() : true; + if (empty) + { + surfaceCache.remove(key); + imageHash.remove(slideIndex); + if (!blankSurface) + { + int sw = state->slideWidth; + int sh = state->slideHeight; + +#ifdef PICTUREFLOW_QT4 + QImage img = QImage(sw, sh, QImage::Format_RGB32); + + QPainter painter(&img); + QPoint p1(sw*4 / 10, 0); + QPoint p2(sw*6 / 10, sh); + QLinearGradient linearGrad(p1, p2); + linearGrad.setColorAt(0, Qt::black); + linearGrad.setColorAt(1, Qt::white); + painter.setBrush(linearGrad); + painter.fillRect(0, 0, sw, sh, QBrush(linearGrad)); + + painter.setPen(QPen(QColor(64, 64, 64), 4)); + painter.setBrush(QBrush()); + painter.drawRect(2, 2, sw - 3, sh - 3); + painter.end(); +#endif +#if defined(PICTUREFLOW_QT3) || defined(PICTUREFLOW_QT2) + QPixmap pixmap(sw, sh, 32); + QPainter painter(&pixmap); + painter.fillRect(pixmap.rect(), QColor(192, 192, 192)); + painter.fillRect(5, 5, sw - 10, sh - 10, QColor(64, 64, 64)); + painter.end(); + QImage img = pixmap.convertToImage(); +#endif + + blankSurface = prepareSurface(&img, sw, sh, bgcolor, state->reflectionEffect); + } + return blankSurface; + } + +#ifdef PICTUREFLOW_QT4 + bool exist = imageHash.contains(slideIndex); + if (exist) + if (img == imageHash.find(slideIndex).value()) +#endif +#ifdef PICTUREFLOW_QT3 + bool exist = imageHash.find(slideIndex) != imageHash.end(); + if (exist) + if (img == imageHash.find(slideIndex).data()) +#endif +#ifdef PICTUREFLOW_QT2 + if (img == imageHash[slideIndex]) +#endif + if (surfaceCache.contains(key)) + return surfaceCache[key]; + + QImage* sr = prepareSurface(img, state->slideWidth, state->slideHeight, bgcolor, state->reflectionEffect); + surfaceCache.insert(key, sr); + imageHash.insert(slideIndex, img); + + return sr; +} + +// Renders a slide to offscreen buffer. Returns a rect of the rendered area. +// col1 and col2 limit the column for rendering. +QRect QxtFlowViewSoftwareRenderer::renderSlide(const SlideInfo &slide, int col1, int col2) +{ + int blend = slide.blend; + if (!blend) + return QRect(); + + QImage* src = surface(slide.slideIndex); + if (!src) + return QRect(); + + QRect rect(0, 0, 0, 0); + + int sw = src->height(); + int sh = src->width(); + int h = buffer.height(); + int w = buffer.width(); + + if (col1 > col2) + { + int c = col2; + col2 = col1; + col1 = c; + } + + col1 = (col1 >= 0) ? col1 : 0; + col2 = (col2 >= 0) ? col2 : w - 1; + col1 = qMin(col1, w - 1); + col2 = qMin(col2, w - 1); + + int zoom = 100; + int distance = h * 100 / zoom; + PFreal sdx = fcos(slide.angle); + PFreal sdy = fsin(slide.angle); + PFreal xs = slide.cx - state->slideWidth * sdx / 2; + PFreal ys = slide.cy - state->slideWidth * sdy / 2; + PFreal dist = distance * PFREAL_ONE; + + int xi = qMax((PFreal)0, ((w * PFREAL_ONE / 2) + fdiv(xs * h, dist + ys)) >> PFREAL_SHIFT); + if (xi >= w) + return rect; + + bool flag = false; + rect.setLeft(xi); + for (int x = qMax(xi, col1); x <= col2; x++) + { + PFreal hity = 0; + PFreal fk = rays[x]; + if (sdy) + { + fk = fk - fdiv(sdx, sdy); + hity = -fdiv((rays[x] * distance - slide.cx + slide.cy * sdx / sdy), fk); + } + + dist = distance * PFREAL_ONE + hity; + if (dist < 0) + continue; + + PFreal hitx = fmul(dist, rays[x]); + PFreal hitdist = fdiv(hitx - slide.cx, sdx); + + int column = sw / 2 + (hitdist >> PFREAL_SHIFT); + if (column >= sw) + break; + if (column < 0) + continue; + + rect.setRight(x); + if (!flag) + rect.setLeft(x); + flag = true; + + int y1 = h / 2; + int y2 = y1 + 1; + QRgb* pixel1 = (QRgb*)(buffer.scanLine(y1)) + x; + QRgb* pixel2 = (QRgb*)(buffer.scanLine(y2)) + x; + QRgb pixelstep = pixel2 - pixel1; + + int center = (sh / 2); + int dy = dist / h; + int p1 = center * PFREAL_ONE - dy / 2; + int p2 = center * PFREAL_ONE + dy / 2; + + const QRgb *ptr = (const QRgb*)(src->scanLine(column)); + if (blend == 256) + while ((y1 >= 0) && (y2 < h) && (p1 >= 0)) + { + *pixel1 = ptr[p1 >> PFREAL_SHIFT]; + *pixel2 = ptr[p2 >> PFREAL_SHIFT]; + p1 -= dy; + p2 += dy; + y1--; + y2++; + pixel1 -= pixelstep; + pixel2 += pixelstep; + } + else + while ((y1 >= 0) && (y2 < h) && (p1 >= 0)) + { + QRgb c1 = ptr[p1 >> PFREAL_SHIFT]; + QRgb c2 = ptr[p2 >> PFREAL_SHIFT]; + *pixel1 = blendColor(c1, bgcolor, blend); + *pixel2 = blendColor(c2, bgcolor, blend); + p1 -= dy; + p2 += dy; + y1--; + y2++; + pixel1 -= pixelstep; + pixel2 += pixelstep; + } + } + + rect.setTop(0); + rect.setBottom(h - 1); + return rect; +} + +void QxtFlowViewSoftwareRenderer::renderSlides() +{ + int nleft = state->leftSlides.count(); + int nright = state->rightSlides.count(); + + QRect r = renderSlide(state->centerSlide); + int c1 = r.left(); + int c2 = r.right(); + + for (int index = 0; index < nleft; index++) + { + QRect rs = renderSlide(state->leftSlides[index], 0, c1 - 1); + if (!rs.isEmpty()) + c1 = rs.left(); + } + for (int index = 0; index < nright; index++) + { + QRect rs = renderSlide(state->rightSlides[index], c2 + 1, buffer.width()); + if (!rs.isEmpty()) + c2 = rs.right(); + } +} + +// Render the slides. Updates only the offscreen buffer. +void QxtFlowViewSoftwareRenderer::render() +{ + buffer.fill(state->backgroundColor); + renderSlides(); + dirty = false; +} + + + + + + + + diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview_p.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview_p.h index fcae5c3d1..f3f9beeda 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview_p.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtflowview_p.h @@ -1,298 +1,298 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ** - ** This is a derived work of PictureFlow (http://pictureflow.googlecode.com) - ** The original code was distributed under the following terms: - ** - ** Copyright (C) 2008 Ariya Hidayat (ariya@kde.org) - ** Copyright (C) 2007 Ariya Hidayat (ariya@kde.org) - ** - ** Permission is hereby granted, free of charge, to any person obtaining a copy - ** of this software and associated documentation files (the "Software"), to deal - ** in the Software without restriction, including without limitation the rights - ** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - ** copies of the Software, and to permit persons to whom the Software is - ** furnished to do so, subject to the following conditions: - ** - ** The above copyright notice and this permission notice shall be included in - ** all copies or substantial portions of the Software. - ** - ** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - ** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - ** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - ** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - ** LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - ** OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - ** THE SOFTWARE. - ****************************************************************************/ - -#ifndef QXTFLOWVIEW_P_H_INCLUDED -#define QXTFLOWVIEW_P_H_INCLUDED - - -#include "qxtflowview.h" - -#define PICTUREFLOW_QT4 - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// for fixed-point arithmetic, we need minimum 32-bit long -// long long (64-bit) might be useful for multiplication and division -typedef long PFreal; -#define PFREAL_SHIFT 10 -#define PFREAL_ONE (1 << PFREAL_SHIFT) - -#define IANGLE_MAX 1024 -#define IANGLE_MASK 1023 - -inline PFreal fmul(PFreal a, PFreal b) -{ - return ((long long)(a))*((long long)(b)) >> PFREAL_SHIFT; -} - -inline PFreal fdiv(PFreal num, PFreal den) -{ - long long p = (long long)(num) << (PFREAL_SHIFT * 2); - long long q = p / (long long)den; - long long r = q >> PFREAL_SHIFT; - - return r; -} - -inline PFreal fsin(int iangle) -{ - // warning: regenerate the table if IANGLE_MAX and PFREAL_SHIFT are changed! - static const PFreal tab[] = - { - 3, 103, 202, 300, 394, 485, 571, 652, - 726, 793, 853, 904, 947, 980, 1004, 1019, - 1023, 1018, 1003, 978, 944, 901, 849, 789, - 721, 647, 566, 479, 388, 294, 196, 97, - -4, -104, -203, -301, -395, -486, -572, -653, - -727, -794, -854, -905, -948, -981, -1005, -1020, - -1024, -1019, -1004, -979, -945, -902, -850, -790, - -722, -648, -567, -480, -389, -295, -197, -98, - 3 - }; - - while (iangle < 0) - iangle += IANGLE_MAX; - iangle &= IANGLE_MASK; - - int i = (iangle >> 4); - PFreal p = tab[i]; - PFreal q = tab[(i+1)]; - PFreal g = (q - p); - return p + g * (iangle - i*16) / 16; -} - -inline PFreal fcos(int iangle) -{ - return fsin(iangle + (IANGLE_MAX >> 2)); -} - -/* ---------------------------------------------------------- - -QxtFlowViewState stores the state of all slides, i.e. all the necessary -information to be able to render them. - -QxtFlowViewAnimator is responsible to move the slides during the -transition between slides, to achieve the effect similar to Cover Flow, -by changing the state. - -QxtFlowViewSoftwareRenderer (or QxtFlowViewOpenGLRenderer) is -the actual 3-d renderer. It should render all slides given the state -(an instance of QxtFlowViewState). - -Instances of all the above three classes are stored in -QxtFlowViewPrivate. - -------------------------------------------------------- */ - -struct SlideInfo -{ - int slideIndex; - int angle; - PFreal cx; - PFreal cy; - int blend; -}; - -class QxtFlowViewState -{ -public: - QxtFlowViewState(); - ~QxtFlowViewState(); - - void reposition(); - void reset(); - - QRgb backgroundColor; - int slideWidth; - int slideHeight; - QxtFlowView::ReflectionEffect reflectionEffect; - QVector slideImages; - - int angle; - int spacing; - PFreal offsetX; - PFreal offsetY; - - SlideInfo centerSlide; - QVector leftSlides; - QVector rightSlides; - int centerIndex; -}; - -class QxtFlowViewAnimator -{ -public: - QxtFlowViewAnimator(); - QxtFlowViewState* state; - - void start(int slide); - void stop(int slide); - void update(); - - int target; - int step; - int frame; - QTimer animateTimer; -}; - -class QxtFlowViewAbstractRenderer -{ -public: - QxtFlowViewAbstractRenderer(): state(0), dirty(false), widget(0) {} - virtual ~QxtFlowViewAbstractRenderer() {} - - QxtFlowViewState* state; - bool dirty; - QWidget* widget; - - virtual void init() = 0; - virtual void paint() = 0; -}; - -class QxtFlowViewSoftwareRenderer: public QxtFlowViewAbstractRenderer -{ -public: - QxtFlowViewSoftwareRenderer(); - ~QxtFlowViewSoftwareRenderer(); - - virtual void init(); - virtual void paint(); - -private: - QSize size; - QRgb bgcolor; - int effect; - QImage buffer; - QVector rays; - QImage* blankSurface; -#ifdef PICTUREFLOW_QT4 - QCache surfaceCache; - QHash imageHash; -#endif -#ifdef PICTUREFLOW_QT3 - QCache surfaceCache; - QMap imageHash; -#endif -#ifdef PICTUREFLOW_QT2 - QCache surfaceCache; - QIntDict imageHash; -#endif - - void render(); - void renderSlides(); - QRect renderSlide(const SlideInfo &slide, int col1 = -1, int col2 = -1); - QImage* surface(int slideIndex); -}; - - - -// ----------------------------------------- - -class QxtFlowViewPrivate : public QObject -{ - Q_OBJECT -public: - QxtFlowViewState* state; - QxtFlowViewAnimator* animator; - QxtFlowViewAbstractRenderer* renderer; - QTimer triggerTimer; - QAbstractItemModel * model; - void setModel(QAbstractItemModel * model); - void clear(); - void triggerRender(); - void insertSlide(int index, const QImage& image); - void replaceSlide(int index, const QImage& image); - void removeSlide(int index); - void setCurrentIndex(QModelIndex index); - void showSlide(int index); - - int picrole; - int textrole; - int piccolumn; - int textcolumn; - - void reset(); - - QList modelmap; - QPersistentModelIndex currentcenter; - - QPoint lastgrabpos; - QModelIndex rootindex; - -public Q_SLOTS: - void columnsAboutToBeInserted(const QModelIndex & parent, int start, int end); - void columnsAboutToBeRemoved(const QModelIndex & parent, int start, int end); - void columnsInserted(const QModelIndex & parent, int start, int end); - void columnsRemoved(const QModelIndex & parent, int start, int end); - void dataChanged(const QModelIndex & topLeft, const QModelIndex & bottomRight); - void headerDataChanged(Qt::Orientation orientation, int first, int last); - void layoutAboutToBeChanged(); - void layoutChanged(); - void modelAboutToBeReset(); - void modelReset(); - void rowsAboutToBeInserted(const QModelIndex & parent, int start, int end); - void rowsAboutToBeRemoved(const QModelIndex & parent, int start, int end); - void rowsInserted(const QModelIndex & parent, int start, int end); - void rowsRemoved(const QModelIndex & parent, int start, int end); -}; - - -#endif // QXTFLOWVIEW_P_H_INCLUDED +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ** + ** This is a derived work of PictureFlow (http://pictureflow.googlecode.com) + ** The original code was distributed under the following terms: + ** + ** Copyright (C) 2008 Ariya Hidayat (ariya@kde.org) + ** Copyright (C) 2007 Ariya Hidayat (ariya@kde.org) + ** + ** Permission is hereby granted, free of charge, to any person obtaining a copy + ** of this software and associated documentation files (the "Software"), to deal + ** in the Software without restriction, including without limitation the rights + ** to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + ** copies of the Software, and to permit persons to whom the Software is + ** furnished to do so, subject to the following conditions: + ** + ** The above copyright notice and this permission notice shall be included in + ** all copies or substantial portions of the Software. + ** + ** THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + ** IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + ** FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + ** AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + ** LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + ** OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + ** THE SOFTWARE. + ****************************************************************************/ + +#ifndef QXTFLOWVIEW_P_H_INCLUDED +#define QXTFLOWVIEW_P_H_INCLUDED + + +#include "qxtflowview.h" + +#define PICTUREFLOW_QT4 + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// for fixed-point arithmetic, we need minimum 32-bit long +// long long (64-bit) might be useful for multiplication and division +typedef long PFreal; +#define PFREAL_SHIFT 10 +#define PFREAL_ONE (1 << PFREAL_SHIFT) + +#define IANGLE_MAX 1024 +#define IANGLE_MASK 1023 + +inline PFreal fmul(PFreal a, PFreal b) +{ + return ((long long)(a))*((long long)(b)) >> PFREAL_SHIFT; +} + +inline PFreal fdiv(PFreal num, PFreal den) +{ + long long p = (long long)(num) << (PFREAL_SHIFT * 2); + long long q = p / (long long)den; + long long r = q >> PFREAL_SHIFT; + + return r; +} + +inline PFreal fsin(int iangle) +{ + // warning: regenerate the table if IANGLE_MAX and PFREAL_SHIFT are changed! + static const PFreal tab[] = + { + 3, 103, 202, 300, 394, 485, 571, 652, + 726, 793, 853, 904, 947, 980, 1004, 1019, + 1023, 1018, 1003, 978, 944, 901, 849, 789, + 721, 647, 566, 479, 388, 294, 196, 97, + -4, -104, -203, -301, -395, -486, -572, -653, + -727, -794, -854, -905, -948, -981, -1005, -1020, + -1024, -1019, -1004, -979, -945, -902, -850, -790, + -722, -648, -567, -480, -389, -295, -197, -98, + 3 + }; + + while (iangle < 0) + iangle += IANGLE_MAX; + iangle &= IANGLE_MASK; + + int i = (iangle >> 4); + PFreal p = tab[i]; + PFreal q = tab[(i+1)]; + PFreal g = (q - p); + return p + g * (iangle - i*16) / 16; +} + +inline PFreal fcos(int iangle) +{ + return fsin(iangle + (IANGLE_MAX >> 2)); +} + +/* ---------------------------------------------------------- + +QxtFlowViewState stores the state of all slides, i.e. all the necessary +information to be able to render them. + +QxtFlowViewAnimator is responsible to move the slides during the +transition between slides, to achieve the effect similar to Cover Flow, +by changing the state. + +QxtFlowViewSoftwareRenderer (or QxtFlowViewOpenGLRenderer) is +the actual 3-d renderer. It should render all slides given the state +(an instance of QxtFlowViewState). + +Instances of all the above three classes are stored in +QxtFlowViewPrivate. + +------------------------------------------------------- */ + +struct SlideInfo +{ + int slideIndex; + int angle; + PFreal cx; + PFreal cy; + int blend; +}; + +class QxtFlowViewState +{ +public: + QxtFlowViewState(); + ~QxtFlowViewState(); + + void reposition(); + void reset(); + + QRgb backgroundColor; + int slideWidth; + int slideHeight; + QxtFlowView::ReflectionEffect reflectionEffect; + QVector slideImages; + + int angle; + int spacing; + PFreal offsetX; + PFreal offsetY; + + SlideInfo centerSlide; + QVector leftSlides; + QVector rightSlides; + int centerIndex; +}; + +class QxtFlowViewAnimator +{ +public: + QxtFlowViewAnimator(); + QxtFlowViewState* state; + + void start(int slide); + void stop(int slide); + void update(); + + int target; + int step; + int frame; + QTimer animateTimer; +}; + +class QxtFlowViewAbstractRenderer +{ +public: + QxtFlowViewAbstractRenderer(): state(0), dirty(false), widget(0) {} + virtual ~QxtFlowViewAbstractRenderer() {} + + QxtFlowViewState* state; + bool dirty; + QWidget* widget; + + virtual void init() = 0; + virtual void paint() = 0; +}; + +class QxtFlowViewSoftwareRenderer: public QxtFlowViewAbstractRenderer +{ +public: + QxtFlowViewSoftwareRenderer(); + ~QxtFlowViewSoftwareRenderer(); + + virtual void init(); + virtual void paint(); + +private: + QSize size; + QRgb bgcolor; + int effect; + QImage buffer; + QVector rays; + QImage* blankSurface; +#ifdef PICTUREFLOW_QT4 + QCache surfaceCache; + QHash imageHash; +#endif +#ifdef PICTUREFLOW_QT3 + QCache surfaceCache; + QMap imageHash; +#endif +#ifdef PICTUREFLOW_QT2 + QCache surfaceCache; + QIntDict imageHash; +#endif + + void render(); + void renderSlides(); + QRect renderSlide(const SlideInfo &slide, int col1 = -1, int col2 = -1); + QImage* surface(int slideIndex); +}; + + + +// ----------------------------------------- + +class QxtFlowViewPrivate : public QObject +{ + Q_OBJECT +public: + QxtFlowViewState* state; + QxtFlowViewAnimator* animator; + QxtFlowViewAbstractRenderer* renderer; + QTimer triggerTimer; + QAbstractItemModel * model; + void setModel(QAbstractItemModel * model); + void clear(); + void triggerRender(); + void insertSlide(int index, const QImage& image); + void replaceSlide(int index, const QImage& image); + void removeSlide(int index); + void setCurrentIndex(QModelIndex index); + void showSlide(int index); + + int picrole; + int textrole; + int piccolumn; + int textcolumn; + + void reset(); + + QList modelmap; + QPersistentModelIndex currentcenter; + + QPoint lastgrabpos; + QModelIndex rootindex; + +public Q_SLOTS: + void columnsAboutToBeInserted(const QModelIndex & parent, int start, int end); + void columnsAboutToBeRemoved(const QModelIndex & parent, int start, int end); + void columnsInserted(const QModelIndex & parent, int start, int end); + void columnsRemoved(const QModelIndex & parent, int start, int end); + void dataChanged(const QModelIndex & topLeft, const QModelIndex & bottomRight); + void headerDataChanged(Qt::Orientation orientation, int first, int last); + void layoutAboutToBeChanged(); + void layoutChanged(); + void modelAboutToBeReset(); + void modelReset(); + void rowsAboutToBeInserted(const QModelIndex & parent, int start, int end); + void rowsAboutToBeRemoved(const QModelIndex & parent, int start, int end); + void rowsInserted(const QModelIndex & parent, int start, int end); + void rowsRemoved(const QModelIndex & parent, int start, int end); +}; + + +#endif // QXTFLOWVIEW_P_H_INCLUDED diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut.cpp index 310e71b1f..ef378f965 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut.cpp @@ -1,191 +1,191 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include "qxtglobalshortcut.h" -#include "qxtglobalshortcut_p.h" -#include -#include - -bool QxtGlobalShortcutPrivate::error = false; -int QxtGlobalShortcutPrivate::ref = 0; -QAbstractEventDispatcher::EventFilter QxtGlobalShortcutPrivate::prevEventFilter = 0; -QHash, QxtGlobalShortcut*> QxtGlobalShortcutPrivate::shortcuts; - -QxtGlobalShortcutPrivate::QxtGlobalShortcutPrivate() : enabled(true), key(Qt::Key(0)), mods(Qt::NoModifier) -{ - if (!ref++) - prevEventFilter = QAbstractEventDispatcher::instance()->setEventFilter(eventFilter); -} - -QxtGlobalShortcutPrivate::~QxtGlobalShortcutPrivate() -{ - if (!--ref) - QAbstractEventDispatcher::instance()->setEventFilter(prevEventFilter); -} - -bool QxtGlobalShortcutPrivate::setShortcut(const QKeySequence& shortcut) -{ - Qt::KeyboardModifiers allMods = Qt::ShiftModifier | Qt::ControlModifier | Qt::AltModifier | Qt::MetaModifier; - key = shortcut.isEmpty() ? Qt::Key(0) : Qt::Key((shortcut[0] ^ allMods) & shortcut[0]); - mods = shortcut.isEmpty() ? Qt::KeyboardModifiers(0) : Qt::KeyboardModifiers(shortcut[0] & allMods); - const quint32 nativeKey = nativeKeycode(key); - const quint32 nativeMods = nativeModifiers(mods); - const bool res = registerShortcut(nativeKey, nativeMods); - shortcuts.insert(qMakePair(nativeKey, nativeMods), &qxt_p()); - if (!res) - qWarning() << "QxtGlobalShortcut failed to register:" << QKeySequence(key + mods).toString(); - return res; -} - -bool QxtGlobalShortcutPrivate::unsetShortcut() -{ - const quint32 nativeKey = nativeKeycode(key); - const quint32 nativeMods = nativeModifiers(mods); - const bool res = unregisterShortcut(nativeKey, nativeMods); - shortcuts.remove(qMakePair(nativeKey, nativeMods)); - if (!res) - qWarning() << "QxtGlobalShortcut failed to unregister:" << QKeySequence(key + mods).toString(); - key = Qt::Key(0); - mods = Qt::KeyboardModifiers(0); - return res; -} - -void QxtGlobalShortcutPrivate::activateShortcut(quint32 nativeKey, quint32 nativeMods) -{ - QxtGlobalShortcut* shortcut = shortcuts.value(qMakePair(nativeKey, nativeMods)); - if (shortcut && shortcut->isEnabled()) - emit shortcut->activated(); -} - -/*! - \class QxtGlobalShortcut - \inmodule QxtGui - \brief The QxtGlobalShortcut class provides a global shortcut aka "hotkey". - - A global shortcut triggers even if the application is not active. This - makes it easy to implement applications that react to certain shortcuts - still if some other application is active or if the application is for - example minimized to the system tray. - - Example usage: - \code - QxtGlobalShortcut* shortcut = new QxtGlobalShortcut(window); - connect(shortcut, SIGNAL(activated()), window, SLOT(toggleVisibility())); - shortcut->setShortcut(QKeySequence("Ctrl+Shift+F12")); - \endcode - - \bold {Note:} Since Qxt 0.6 QxtGlobalShortcut no more requires QxtApplication. - */ - -/*! - \fn QxtGlobalShortcut::activated() - - This signal is emitted when the user types the shortcut's key sequence. - - \sa shortcut - */ - -/*! - Constructs a new QxtGlobalShortcut with \a parent. - */ -QxtGlobalShortcut::QxtGlobalShortcut(QObject* parent) - : QObject(parent) -{ - QXT_INIT_PRIVATE(QxtGlobalShortcut); -} - -/*! - Constructs a new QxtGlobalShortcut with \a shortcut and \a parent. - */ -QxtGlobalShortcut::QxtGlobalShortcut(const QKeySequence& shortcut, QObject* parent) - : QObject(parent) -{ - QXT_INIT_PRIVATE(QxtGlobalShortcut); - setShortcut(shortcut); -} - -/*! - Destructs the QxtGlobalShortcut. - */ -QxtGlobalShortcut::~QxtGlobalShortcut() -{ - if (qxt_d().key != 0) - qxt_d().unsetShortcut(); -} - -/*! - \property QxtGlobalShortcut::shortcut - \brief the shortcut key sequence - - \bold {Note:} Notice that corresponding key press and release events are not - delivered for registered global shortcuts even if they are disabled. - Also, comma separated key sequences are not supported. - Only the first part is used: - - \code - qxtShortcut->setShortcut(QKeySequence("Ctrl+Alt+A,Ctrl+Alt+B")); - Q_ASSERT(qxtShortcut->shortcut() == QKeySequence("Ctrl+Alt+A")); - \endcode - */ -QKeySequence QxtGlobalShortcut::shortcut() const -{ - return QKeySequence(qxt_d().key | qxt_d().mods); -} - -bool QxtGlobalShortcut::setShortcut(const QKeySequence& shortcut) -{ - if (qxt_d().key != 0) - qxt_d().unsetShortcut(); - return qxt_d().setShortcut(shortcut); -} - -/*! - \property QxtGlobalShortcut::enabled - \brief whether the shortcut is enabled - - A disabled shortcut does not get activated. - - The default value is \c true. - - \sa setDisabled() - */ -bool QxtGlobalShortcut::isEnabled() const -{ - return qxt_d().enabled; -} - -void QxtGlobalShortcut::setEnabled(bool enabled) -{ - qxt_d().enabled = enabled; -} - -/*! - Sets the shortcut \a disabled. - - \sa enabled - */ -void QxtGlobalShortcut::setDisabled(bool disabled) -{ - qxt_d().enabled = !disabled; -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include "qxtglobalshortcut.h" +#include "qxtglobalshortcut_p.h" +#include +#include + +bool QxtGlobalShortcutPrivate::error = false; +int QxtGlobalShortcutPrivate::ref = 0; +QAbstractEventDispatcher::EventFilter QxtGlobalShortcutPrivate::prevEventFilter = 0; +QHash, QxtGlobalShortcut*> QxtGlobalShortcutPrivate::shortcuts; + +QxtGlobalShortcutPrivate::QxtGlobalShortcutPrivate() : enabled(true), key(Qt::Key(0)), mods(Qt::NoModifier) +{ + if (!ref++) + prevEventFilter = QAbstractEventDispatcher::instance()->setEventFilter(eventFilter); +} + +QxtGlobalShortcutPrivate::~QxtGlobalShortcutPrivate() +{ + if (!--ref) + QAbstractEventDispatcher::instance()->setEventFilter(prevEventFilter); +} + +bool QxtGlobalShortcutPrivate::setShortcut(const QKeySequence& shortcut) +{ + Qt::KeyboardModifiers allMods = Qt::ShiftModifier | Qt::ControlModifier | Qt::AltModifier | Qt::MetaModifier; + key = shortcut.isEmpty() ? Qt::Key(0) : Qt::Key((shortcut[0] ^ allMods) & shortcut[0]); + mods = shortcut.isEmpty() ? Qt::KeyboardModifiers(0) : Qt::KeyboardModifiers(shortcut[0] & allMods); + const quint32 nativeKey = nativeKeycode(key); + const quint32 nativeMods = nativeModifiers(mods); + const bool res = registerShortcut(nativeKey, nativeMods); + shortcuts.insert(qMakePair(nativeKey, nativeMods), &qxt_p()); + if (!res) + qWarning() << "QxtGlobalShortcut failed to register:" << QKeySequence(key + mods).toString(); + return res; +} + +bool QxtGlobalShortcutPrivate::unsetShortcut() +{ + const quint32 nativeKey = nativeKeycode(key); + const quint32 nativeMods = nativeModifiers(mods); + const bool res = unregisterShortcut(nativeKey, nativeMods); + shortcuts.remove(qMakePair(nativeKey, nativeMods)); + if (!res) + qWarning() << "QxtGlobalShortcut failed to unregister:" << QKeySequence(key + mods).toString(); + key = Qt::Key(0); + mods = Qt::KeyboardModifiers(0); + return res; +} + +void QxtGlobalShortcutPrivate::activateShortcut(quint32 nativeKey, quint32 nativeMods) +{ + QxtGlobalShortcut* shortcut = shortcuts.value(qMakePair(nativeKey, nativeMods)); + if (shortcut && shortcut->isEnabled()) + emit shortcut->activated(); +} + +/*! + \class QxtGlobalShortcut + \inmodule QxtGui + \brief The QxtGlobalShortcut class provides a global shortcut aka "hotkey". + + A global shortcut triggers even if the application is not active. This + makes it easy to implement applications that react to certain shortcuts + still if some other application is active or if the application is for + example minimized to the system tray. + + Example usage: + \code + QxtGlobalShortcut* shortcut = new QxtGlobalShortcut(window); + connect(shortcut, SIGNAL(activated()), window, SLOT(toggleVisibility())); + shortcut->setShortcut(QKeySequence("Ctrl+Shift+F12")); + \endcode + + \bold {Note:} Since Qxt 0.6 QxtGlobalShortcut no more requires QxtApplication. + */ + +/*! + \fn QxtGlobalShortcut::activated() + + This signal is emitted when the user types the shortcut's key sequence. + + \sa shortcut + */ + +/*! + Constructs a new QxtGlobalShortcut with \a parent. + */ +QxtGlobalShortcut::QxtGlobalShortcut(QObject* parent) + : QObject(parent) +{ + QXT_INIT_PRIVATE(QxtGlobalShortcut); +} + +/*! + Constructs a new QxtGlobalShortcut with \a shortcut and \a parent. + */ +QxtGlobalShortcut::QxtGlobalShortcut(const QKeySequence& shortcut, QObject* parent) + : QObject(parent) +{ + QXT_INIT_PRIVATE(QxtGlobalShortcut); + setShortcut(shortcut); +} + +/*! + Destructs the QxtGlobalShortcut. + */ +QxtGlobalShortcut::~QxtGlobalShortcut() +{ + if (qxt_d().key != 0) + qxt_d().unsetShortcut(); +} + +/*! + \property QxtGlobalShortcut::shortcut + \brief the shortcut key sequence + + \bold {Note:} Notice that corresponding key press and release events are not + delivered for registered global shortcuts even if they are disabled. + Also, comma separated key sequences are not supported. + Only the first part is used: + + \code + qxtShortcut->setShortcut(QKeySequence("Ctrl+Alt+A,Ctrl+Alt+B")); + Q_ASSERT(qxtShortcut->shortcut() == QKeySequence("Ctrl+Alt+A")); + \endcode + */ +QKeySequence QxtGlobalShortcut::shortcut() const +{ + return QKeySequence(qxt_d().key | qxt_d().mods); +} + +bool QxtGlobalShortcut::setShortcut(const QKeySequence& shortcut) +{ + if (qxt_d().key != 0) + qxt_d().unsetShortcut(); + return qxt_d().setShortcut(shortcut); +} + +/*! + \property QxtGlobalShortcut::enabled + \brief whether the shortcut is enabled + + A disabled shortcut does not get activated. + + The default value is \c true. + + \sa setDisabled() + */ +bool QxtGlobalShortcut::isEnabled() const +{ + return qxt_d().enabled; +} + +void QxtGlobalShortcut::setEnabled(bool enabled) +{ + qxt_d().enabled = enabled; +} + +/*! + Sets the shortcut \a disabled. + + \sa enabled + */ +void QxtGlobalShortcut::setDisabled(bool disabled) +{ + qxt_d().enabled = !disabled; +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut.h index f22536a75..a97ba2ddb 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut.h @@ -1,58 +1,58 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#ifndef QXTGLOBALSHORTCUT_H -#define QXTGLOBALSHORTCUT_H - -#include "qxtglobal.h" -#include -#include -class QxtGlobalShortcutPrivate; - -class QXT_GUI_EXPORT QxtGlobalShortcut : public QObject -{ - Q_OBJECT - QXT_DECLARE_PRIVATE(QxtGlobalShortcut) - Q_PROPERTY(bool enabled READ isEnabled WRITE setEnabled) - Q_PROPERTY(QKeySequence shortcut READ shortcut WRITE setShortcut) - -public: - explicit QxtGlobalShortcut(QObject* parent = 0); - explicit QxtGlobalShortcut(const QKeySequence& shortcut, QObject* parent = 0); - virtual ~QxtGlobalShortcut(); - - QKeySequence shortcut() const; - bool setShortcut(const QKeySequence& shortcut); - - bool isEnabled() const; - -public Q_SLOTS: - void setEnabled(bool enabled = true); - void setDisabled(bool disabled = true); - -Q_SIGNALS: - void activated(); -}; - -#endif // QXTGLOBALSHORTCUT_H +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#ifndef QXTGLOBALSHORTCUT_H +#define QXTGLOBALSHORTCUT_H + +#include "qxtglobal.h" +#include +#include +class QxtGlobalShortcutPrivate; + +class QXT_GUI_EXPORT QxtGlobalShortcut : public QObject +{ + Q_OBJECT + QXT_DECLARE_PRIVATE(QxtGlobalShortcut) + Q_PROPERTY(bool enabled READ isEnabled WRITE setEnabled) + Q_PROPERTY(QKeySequence shortcut READ shortcut WRITE setShortcut) + +public: + explicit QxtGlobalShortcut(QObject* parent = 0); + explicit QxtGlobalShortcut(const QKeySequence& shortcut, QObject* parent = 0); + virtual ~QxtGlobalShortcut(); + + QKeySequence shortcut() const; + bool setShortcut(const QKeySequence& shortcut); + + bool isEnabled() const; + +public Q_SLOTS: + void setEnabled(bool enabled = true); + void setDisabled(bool disabled = true); + +Q_SIGNALS: + void activated(); +}; + +#endif // QXTGLOBALSHORTCUT_H diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_mac.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_mac.cpp index 829cae232..0bcea7f36 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_mac.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_mac.cpp @@ -1,207 +1,207 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include -#include "qxtglobalshortcut_p.h" -#include -#include -#include -#include - -typedef QPair Identifier; -static QMap keyRefs; -static QHash keyIDs; -static quint32 hotKeySerial = 0; -static bool qxt_mac_handler_installed = false; - -OSStatus qxt_mac_handle_hot_key(EventHandlerCallRef nextHandler, EventRef event, void* data) -{ - // pass event to the app event filter - Q_UNUSED(data); - qApp->macEventFilter(nextHandler, event); - return noErr; -} - -bool QxtGlobalShortcutPrivate::eventFilter(void* message) -//bool QxtGlobalShortcutPrivate::macEventFilter(EventHandlerCallRef caller, EventRef event) -{ - EventRef event = (EventRef) message; - if (GetEventClass(event) == kEventClassKeyboard && GetEventKind(event) == kEventHotKeyPressed) - { - EventHotKeyID keyID; - GetEventParameter(event, kEventParamDirectObject, typeEventHotKeyID, NULL, sizeof(keyID), NULL, &keyID); - Identifier id = keyIDs.key(keyID.id); - activateShortcut(id.second, id.first); - } - return false; -} - -quint32 QxtGlobalShortcutPrivate::nativeModifiers(Qt::KeyboardModifiers modifiers) -{ - quint32 native = 0; - if (modifiers & Qt::ShiftModifier) - native |= shiftKeyBit; - if (modifiers & Qt::ControlModifier) - native |= cmdKey; - if (modifiers & Qt::AltModifier) - native |= optionKey; - if (modifiers & Qt::MetaModifier) - native |= controlKey; - if (modifiers & Qt::KeypadModifier) - native |= kEventKeyModifierNumLockMask; - return native; -} - -quint32 QxtGlobalShortcutPrivate::nativeKeycode(Qt::Key key) -{ - UTF16Char ch; - // Constants found in NSEvent.h from AppKit.framework - if (key == Qt::Key_Up) ch = 0xF700; - else if (key == Qt::Key_Down) ch = 0xF701; - else if (key == Qt::Key_Left) ch = 0xF702; - else if (key == Qt::Key_Right) ch = 0xF703; - else if (key >= Qt::Key_F1 && key <= Qt::Key_F35) - ch = key - Qt::Key_F1 + 0xF704; - else if (key == Qt::Key_Insert) ch = 0xF727; - else if (key == Qt::Key_Delete) ch = 0xF728; - else if (key == Qt::Key_Home) ch = 0xF729; - else if (key == Qt::Key_End) ch = 0xF72B; - else if (key == Qt::Key_PageUp) ch = 0xF72C; - else if (key == Qt::Key_PageDown) ch = 0xF72D; - else if (key == Qt::Key_Print) ch = 0xF72E; - else if (key == Qt::Key_ScrollLock) ch = 0xF72F; - else if (key == Qt::Key_Pause) ch = 0xF730; - else if (key == Qt::Key_SysReq) ch = 0xF731; - else if (key == Qt::Key_Stop) ch = 0xF734; - else if (key == Qt::Key_Menu) ch = 0xF735; - else if (key == Qt::Key_Select) ch = 0xF741; - else if (key == Qt::Key_Execute) ch = 0xF742; - else if (key == Qt::Key_Help) ch = 0xF746; - else if (key == Qt::Key_Mode_switch) ch = 0xF747; - else if (key == Qt::Key_Escape) ch = 27; - else if (key == Qt::Key_Return) ch = 13; - else if (key == Qt::Key_Enter) ch = 3; - else if (key == Qt::Key_Tab) ch = 9; - else ch = key; - - KeyboardLayoutRef layout; - KeyboardLayoutKind layoutKind; - KLGetCurrentKeyboardLayout(&layout); - KLGetKeyboardLayoutProperty(layout, kKLKind, const_cast(reinterpret_cast(&layoutKind))); - - if (layoutKind == kKLKCHRKind) - { // no Unicode available - if (ch > 255) return 0; - - char* data; - KLGetKeyboardLayoutProperty(layout, kKLKCHRData, const_cast(reinterpret_cast(&data))); - int ct = *reinterpret_cast(data + 258); - for (int i = 0; i < ct; i++) - { - char* keyTable = data + 260 + 128 * i; - for (int j = 0; j < 128; j++) - { - if (keyTable[j] == ch) return j; - } - } - - return 0; - } - - char* data; - KLGetKeyboardLayoutProperty(layout, kKLuchrData, const_cast(reinterpret_cast(&data))); - UCKeyboardLayout* header = reinterpret_cast(data); - UCKeyboardTypeHeader* table = header->keyboardTypeList; - - for (quint32 i=0; i < header->keyboardTypeCount; i++) - { - UCKeyStateRecordsIndex* stateRec = 0; - if (table[i].keyStateRecordsIndexOffset != 0) - { - stateRec = reinterpret_cast(data + table[i].keyStateRecordsIndexOffset); - if (stateRec->keyStateRecordsIndexFormat != kUCKeyStateRecordsIndexFormat) stateRec = 0; - } - - UCKeyToCharTableIndex* charTable = reinterpret_cast(data + table[i].keyToCharTableIndexOffset); - if (charTable->keyToCharTableIndexFormat != kUCKeyToCharTableIndexFormat) continue; - - for (quint32 j=0; j < charTable->keyToCharTableCount; j++) - { - UCKeyOutput* keyToChar = reinterpret_cast(data + charTable->keyToCharTableOffsets[j]); - for (quint32 k=0; k < charTable->keyToCharTableSize; k++) - { - if (keyToChar[k] & kUCKeyOutputTestForIndexMask) - { - long idx = keyToChar[k] & kUCKeyOutputGetIndexMask; - if (stateRec && idx < stateRec->keyStateRecordCount) - { - UCKeyStateRecord* rec = reinterpret_cast(data + stateRec->keyStateRecordOffsets[idx]); - if (rec->stateZeroCharData == ch) return k; - } - } - else if (!(keyToChar[k] & kUCKeyOutputSequenceIndexMask) && keyToChar[k] < 0xFFFE) - { - if (keyToChar[k] == ch) return k; - } - } // for k - } // for j - } // for i - - return 0; -} - -bool QxtGlobalShortcutPrivate::registerShortcut(quint32 nativeKey, quint32 nativeMods) -{ - if (!qxt_mac_handler_installed) - { - EventTypeSpec t; - t.eventClass = kEventClassKeyboard; - t.eventKind = kEventHotKeyPressed; - InstallApplicationEventHandler(&qxt_mac_handle_hot_key, 1, &t, NULL, NULL); - } - - EventHotKeyID keyID; - keyID.signature = 'cute'; - keyID.id = ++hotKeySerial; - - EventHotKeyRef ref = 0; - bool rv = !RegisterEventHotKey(nativeKey, nativeMods, keyID, GetApplicationEventTarget(), 0, &ref); - if (rv) - { - keyIDs.insert(Identifier(nativeMods, nativeKey), keyID.id); - keyRefs.insert(keyID.id, ref); - } - qDebug() << ref; - return rv; -} - -bool QxtGlobalShortcutPrivate::unregisterShortcut(quint32 nativeKey, quint32 nativeMods) -{ - Identifier id(nativeMods, nativeKey); - if (!keyIDs.contains(id)) return false; - - EventHotKeyRef ref = keyRefs.take(keyIDs[id]); - keyIDs.remove(id); - return !UnregisterEventHotKey(ref); -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include +#include "qxtglobalshortcut_p.h" +#include +#include +#include +#include + +typedef QPair Identifier; +static QMap keyRefs; +static QHash keyIDs; +static quint32 hotKeySerial = 0; +static bool qxt_mac_handler_installed = false; + +OSStatus qxt_mac_handle_hot_key(EventHandlerCallRef nextHandler, EventRef event, void* data) +{ + // pass event to the app event filter + Q_UNUSED(data); + qApp->macEventFilter(nextHandler, event); + return noErr; +} + +bool QxtGlobalShortcutPrivate::eventFilter(void* message) +//bool QxtGlobalShortcutPrivate::macEventFilter(EventHandlerCallRef caller, EventRef event) +{ + EventRef event = (EventRef) message; + if (GetEventClass(event) == kEventClassKeyboard && GetEventKind(event) == kEventHotKeyPressed) + { + EventHotKeyID keyID; + GetEventParameter(event, kEventParamDirectObject, typeEventHotKeyID, NULL, sizeof(keyID), NULL, &keyID); + Identifier id = keyIDs.key(keyID.id); + activateShortcut(id.second, id.first); + } + return false; +} + +quint32 QxtGlobalShortcutPrivate::nativeModifiers(Qt::KeyboardModifiers modifiers) +{ + quint32 native = 0; + if (modifiers & Qt::ShiftModifier) + native |= shiftKeyBit; + if (modifiers & Qt::ControlModifier) + native |= cmdKey; + if (modifiers & Qt::AltModifier) + native |= optionKey; + if (modifiers & Qt::MetaModifier) + native |= controlKey; + if (modifiers & Qt::KeypadModifier) + native |= kEventKeyModifierNumLockMask; + return native; +} + +quint32 QxtGlobalShortcutPrivate::nativeKeycode(Qt::Key key) +{ + UTF16Char ch; + // Constants found in NSEvent.h from AppKit.framework + if (key == Qt::Key_Up) ch = 0xF700; + else if (key == Qt::Key_Down) ch = 0xF701; + else if (key == Qt::Key_Left) ch = 0xF702; + else if (key == Qt::Key_Right) ch = 0xF703; + else if (key >= Qt::Key_F1 && key <= Qt::Key_F35) + ch = key - Qt::Key_F1 + 0xF704; + else if (key == Qt::Key_Insert) ch = 0xF727; + else if (key == Qt::Key_Delete) ch = 0xF728; + else if (key == Qt::Key_Home) ch = 0xF729; + else if (key == Qt::Key_End) ch = 0xF72B; + else if (key == Qt::Key_PageUp) ch = 0xF72C; + else if (key == Qt::Key_PageDown) ch = 0xF72D; + else if (key == Qt::Key_Print) ch = 0xF72E; + else if (key == Qt::Key_ScrollLock) ch = 0xF72F; + else if (key == Qt::Key_Pause) ch = 0xF730; + else if (key == Qt::Key_SysReq) ch = 0xF731; + else if (key == Qt::Key_Stop) ch = 0xF734; + else if (key == Qt::Key_Menu) ch = 0xF735; + else if (key == Qt::Key_Select) ch = 0xF741; + else if (key == Qt::Key_Execute) ch = 0xF742; + else if (key == Qt::Key_Help) ch = 0xF746; + else if (key == Qt::Key_Mode_switch) ch = 0xF747; + else if (key == Qt::Key_Escape) ch = 27; + else if (key == Qt::Key_Return) ch = 13; + else if (key == Qt::Key_Enter) ch = 3; + else if (key == Qt::Key_Tab) ch = 9; + else ch = key; + + KeyboardLayoutRef layout; + KeyboardLayoutKind layoutKind; + KLGetCurrentKeyboardLayout(&layout); + KLGetKeyboardLayoutProperty(layout, kKLKind, const_cast(reinterpret_cast(&layoutKind))); + + if (layoutKind == kKLKCHRKind) + { // no Unicode available + if (ch > 255) return 0; + + char* data; + KLGetKeyboardLayoutProperty(layout, kKLKCHRData, const_cast(reinterpret_cast(&data))); + int ct = *reinterpret_cast(data + 258); + for (int i = 0; i < ct; i++) + { + char* keyTable = data + 260 + 128 * i; + for (int j = 0; j < 128; j++) + { + if (keyTable[j] == ch) return j; + } + } + + return 0; + } + + char* data; + KLGetKeyboardLayoutProperty(layout, kKLuchrData, const_cast(reinterpret_cast(&data))); + UCKeyboardLayout* header = reinterpret_cast(data); + UCKeyboardTypeHeader* table = header->keyboardTypeList; + + for (quint32 i=0; i < header->keyboardTypeCount; i++) + { + UCKeyStateRecordsIndex* stateRec = 0; + if (table[i].keyStateRecordsIndexOffset != 0) + { + stateRec = reinterpret_cast(data + table[i].keyStateRecordsIndexOffset); + if (stateRec->keyStateRecordsIndexFormat != kUCKeyStateRecordsIndexFormat) stateRec = 0; + } + + UCKeyToCharTableIndex* charTable = reinterpret_cast(data + table[i].keyToCharTableIndexOffset); + if (charTable->keyToCharTableIndexFormat != kUCKeyToCharTableIndexFormat) continue; + + for (quint32 j=0; j < charTable->keyToCharTableCount; j++) + { + UCKeyOutput* keyToChar = reinterpret_cast(data + charTable->keyToCharTableOffsets[j]); + for (quint32 k=0; k < charTable->keyToCharTableSize; k++) + { + if (keyToChar[k] & kUCKeyOutputTestForIndexMask) + { + long idx = keyToChar[k] & kUCKeyOutputGetIndexMask; + if (stateRec && idx < stateRec->keyStateRecordCount) + { + UCKeyStateRecord* rec = reinterpret_cast(data + stateRec->keyStateRecordOffsets[idx]); + if (rec->stateZeroCharData == ch) return k; + } + } + else if (!(keyToChar[k] & kUCKeyOutputSequenceIndexMask) && keyToChar[k] < 0xFFFE) + { + if (keyToChar[k] == ch) return k; + } + } // for k + } // for j + } // for i + + return 0; +} + +bool QxtGlobalShortcutPrivate::registerShortcut(quint32 nativeKey, quint32 nativeMods) +{ + if (!qxt_mac_handler_installed) + { + EventTypeSpec t; + t.eventClass = kEventClassKeyboard; + t.eventKind = kEventHotKeyPressed; + InstallApplicationEventHandler(&qxt_mac_handle_hot_key, 1, &t, NULL, NULL); + } + + EventHotKeyID keyID; + keyID.signature = 'cute'; + keyID.id = ++hotKeySerial; + + EventHotKeyRef ref = 0; + bool rv = !RegisterEventHotKey(nativeKey, nativeMods, keyID, GetApplicationEventTarget(), 0, &ref); + if (rv) + { + keyIDs.insert(Identifier(nativeMods, nativeKey), keyID.id); + keyRefs.insert(keyID.id, ref); + } + qDebug() << ref; + return rv; +} + +bool QxtGlobalShortcutPrivate::unregisterShortcut(quint32 nativeKey, quint32 nativeMods) +{ + Identifier id(nativeMods, nativeKey); + if (!keyIDs.contains(id)) return false; + + EventHotKeyRef ref = keyRefs.take(keyIDs[id]); + keyIDs.remove(id); + return !UnregisterEventHotKey(ref); +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_p.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_p.h index 4f627cc3f..4570396fe 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_p.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_p.h @@ -1,63 +1,63 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#ifndef QXTGLOBALSHORTCUT_P_H -#define QXTGLOBALSHORTCUT_P_H - -#include "qxtglobalshortcut.h" -#include -#include -#include - -class QxtGlobalShortcutPrivate : public QxtPrivate -{ -public: - QXT_DECLARE_PUBLIC(QxtGlobalShortcut) - QxtGlobalShortcutPrivate(); - ~QxtGlobalShortcutPrivate(); - - bool enabled; - Qt::Key key; - Qt::KeyboardModifiers mods; - - bool setShortcut(const QKeySequence& shortcut); - bool unsetShortcut(); - - static bool error; - static int ref; - static QAbstractEventDispatcher::EventFilter prevEventFilter; - static bool eventFilter(void* message); - -private: - static quint32 nativeKeycode(Qt::Key keycode); - static quint32 nativeModifiers(Qt::KeyboardModifiers modifiers); - - static bool registerShortcut(quint32 nativeKey, quint32 nativeMods); - static bool unregisterShortcut(quint32 nativeKey, quint32 nativeMods); - static void activateShortcut(quint32 nativeKey, quint32 nativeMods); - - static QHash, QxtGlobalShortcut*> shortcuts; -}; - -#endif // QXTGLOBALSHORTCUT_P_H +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#ifndef QXTGLOBALSHORTCUT_P_H +#define QXTGLOBALSHORTCUT_P_H + +#include "qxtglobalshortcut.h" +#include +#include +#include + +class QxtGlobalShortcutPrivate : public QxtPrivate +{ +public: + QXT_DECLARE_PUBLIC(QxtGlobalShortcut) + QxtGlobalShortcutPrivate(); + ~QxtGlobalShortcutPrivate(); + + bool enabled; + Qt::Key key; + Qt::KeyboardModifiers mods; + + bool setShortcut(const QKeySequence& shortcut); + bool unsetShortcut(); + + static bool error; + static int ref; + static QAbstractEventDispatcher::EventFilter prevEventFilter; + static bool eventFilter(void* message); + +private: + static quint32 nativeKeycode(Qt::Key keycode); + static quint32 nativeModifiers(Qt::KeyboardModifiers modifiers); + + static bool registerShortcut(quint32 nativeKey, quint32 nativeMods); + static bool unregisterShortcut(quint32 nativeKey, quint32 nativeMods); + static void activateShortcut(quint32 nativeKey, quint32 nativeMods); + + static QHash, QxtGlobalShortcut*> shortcuts; +}; + +#endif // QXTGLOBALSHORTCUT_P_H diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_win.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_win.cpp index 8f504e278..40999893d 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_win.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_win.cpp @@ -1,214 +1,214 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include "qxtglobalshortcut_p.h" -#include - -bool QxtGlobalShortcutPrivate::eventFilter(void* message) -{ - MSG* msg = static_cast(message); - if (msg->message == WM_HOTKEY) - { - const quint32 keycode = HIWORD(msg->lParam); - const quint32 modifiers = LOWORD(msg->lParam); - activateShortcut(keycode, modifiers); - } - return false; -} - -quint32 QxtGlobalShortcutPrivate::nativeModifiers(Qt::KeyboardModifiers modifiers) -{ - // MOD_ALT, MOD_CONTROL, (MOD_KEYUP), MOD_SHIFT, MOD_WIN - quint32 native = 0; - if (modifiers & Qt::ShiftModifier) - native |= MOD_SHIFT; - if (modifiers & Qt::ControlModifier) - native |= MOD_CONTROL; - if (modifiers & Qt::AltModifier) - native |= MOD_ALT; - if (modifiers & Qt::MetaModifier) - native |= MOD_WIN; - // TODO: resolve these? - //if (modifiers & Qt::KeypadModifier) - //if (modifiers & Qt::GroupSwitchModifier) - return native; -} - -quint32 QxtGlobalShortcutPrivate::nativeKeycode(Qt::Key key) -{ - switch (key) - { - case Qt::Key_Escape: - return VK_ESCAPE; - case Qt::Key_Tab: - case Qt::Key_Backtab: - return VK_TAB; - case Qt::Key_Backspace: - return VK_BACK; - case Qt::Key_Return: - case Qt::Key_Enter: - return VK_RETURN; - case Qt::Key_Insert: - return VK_INSERT; - case Qt::Key_Delete: - return VK_DELETE; - case Qt::Key_Pause: - return VK_PAUSE; - case Qt::Key_Print: - return VK_PRINT; - case Qt::Key_Clear: - return VK_CLEAR; - case Qt::Key_Home: - return VK_HOME; - case Qt::Key_End: - return VK_END; - case Qt::Key_Left: - return VK_LEFT; - case Qt::Key_Up: - return VK_UP; - case Qt::Key_Right: - return VK_RIGHT; - case Qt::Key_Down: - return VK_DOWN; - case Qt::Key_PageUp: - return VK_PRIOR; - case Qt::Key_PageDown: - return VK_NEXT; - case Qt::Key_F1: - return VK_F1; - case Qt::Key_F2: - return VK_F2; - case Qt::Key_F3: - return VK_F3; - case Qt::Key_F4: - return VK_F4; - case Qt::Key_F5: - return VK_F5; - case Qt::Key_F6: - return VK_F6; - case Qt::Key_F7: - return VK_F7; - case Qt::Key_F8: - return VK_F8; - case Qt::Key_F9: - return VK_F9; - case Qt::Key_F10: - return VK_F10; - case Qt::Key_F11: - return VK_F11; - case Qt::Key_F12: - return VK_F12; - case Qt::Key_F13: - return VK_F13; - case Qt::Key_F14: - return VK_F14; - case Qt::Key_F15: - return VK_F15; - case Qt::Key_F16: - return VK_F16; - case Qt::Key_F17: - return VK_F17; - case Qt::Key_F18: - return VK_F18; - case Qt::Key_F19: - return VK_F19; - case Qt::Key_F20: - return VK_F20; - case Qt::Key_F21: - return VK_F21; - case Qt::Key_F22: - return VK_F22; - case Qt::Key_F23: - return VK_F23; - case Qt::Key_F24: - return VK_F24; - case Qt::Key_Space: - return VK_SPACE; - case Qt::Key_Asterisk: - return VK_MULTIPLY; - case Qt::Key_Plus: - return VK_ADD; - case Qt::Key_Comma: - return VK_SEPARATOR; - case Qt::Key_Minus: - return VK_SUBTRACT; - case Qt::Key_Slash: - return VK_DIVIDE; - - // numbers - case Qt::Key_0: - case Qt::Key_1: - case Qt::Key_2: - case Qt::Key_3: - case Qt::Key_4: - case Qt::Key_5: - case Qt::Key_6: - case Qt::Key_7: - case Qt::Key_8: - case Qt::Key_9: - return key; - - // letters - case Qt::Key_A: - case Qt::Key_B: - case Qt::Key_C: - case Qt::Key_D: - case Qt::Key_E: - case Qt::Key_F: - case Qt::Key_G: - case Qt::Key_H: - case Qt::Key_I: - case Qt::Key_J: - case Qt::Key_K: - case Qt::Key_L: - case Qt::Key_M: - case Qt::Key_N: - case Qt::Key_O: - case Qt::Key_P: - case Qt::Key_Q: - case Qt::Key_R: - case Qt::Key_S: - case Qt::Key_T: - case Qt::Key_U: - case Qt::Key_V: - case Qt::Key_W: - case Qt::Key_X: - case Qt::Key_Y: - case Qt::Key_Z: - return key; - - default: - return 0; - } -} - -bool QxtGlobalShortcutPrivate::registerShortcut(quint32 nativeKey, quint32 nativeMods) -{ - return RegisterHotKey(0, nativeMods ^ nativeKey, nativeMods, nativeKey); -} - -bool QxtGlobalShortcutPrivate::unregisterShortcut(quint32 nativeKey, quint32 nativeMods) -{ - return UnregisterHotKey(0, nativeMods ^ nativeKey); -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include "qxtglobalshortcut_p.h" +#include + +bool QxtGlobalShortcutPrivate::eventFilter(void* message) +{ + MSG* msg = static_cast(message); + if (msg->message == WM_HOTKEY) + { + const quint32 keycode = HIWORD(msg->lParam); + const quint32 modifiers = LOWORD(msg->lParam); + activateShortcut(keycode, modifiers); + } + return false; +} + +quint32 QxtGlobalShortcutPrivate::nativeModifiers(Qt::KeyboardModifiers modifiers) +{ + // MOD_ALT, MOD_CONTROL, (MOD_KEYUP), MOD_SHIFT, MOD_WIN + quint32 native = 0; + if (modifiers & Qt::ShiftModifier) + native |= MOD_SHIFT; + if (modifiers & Qt::ControlModifier) + native |= MOD_CONTROL; + if (modifiers & Qt::AltModifier) + native |= MOD_ALT; + if (modifiers & Qt::MetaModifier) + native |= MOD_WIN; + // TODO: resolve these? + //if (modifiers & Qt::KeypadModifier) + //if (modifiers & Qt::GroupSwitchModifier) + return native; +} + +quint32 QxtGlobalShortcutPrivate::nativeKeycode(Qt::Key key) +{ + switch (key) + { + case Qt::Key_Escape: + return VK_ESCAPE; + case Qt::Key_Tab: + case Qt::Key_Backtab: + return VK_TAB; + case Qt::Key_Backspace: + return VK_BACK; + case Qt::Key_Return: + case Qt::Key_Enter: + return VK_RETURN; + case Qt::Key_Insert: + return VK_INSERT; + case Qt::Key_Delete: + return VK_DELETE; + case Qt::Key_Pause: + return VK_PAUSE; + case Qt::Key_Print: + return VK_PRINT; + case Qt::Key_Clear: + return VK_CLEAR; + case Qt::Key_Home: + return VK_HOME; + case Qt::Key_End: + return VK_END; + case Qt::Key_Left: + return VK_LEFT; + case Qt::Key_Up: + return VK_UP; + case Qt::Key_Right: + return VK_RIGHT; + case Qt::Key_Down: + return VK_DOWN; + case Qt::Key_PageUp: + return VK_PRIOR; + case Qt::Key_PageDown: + return VK_NEXT; + case Qt::Key_F1: + return VK_F1; + case Qt::Key_F2: + return VK_F2; + case Qt::Key_F3: + return VK_F3; + case Qt::Key_F4: + return VK_F4; + case Qt::Key_F5: + return VK_F5; + case Qt::Key_F6: + return VK_F6; + case Qt::Key_F7: + return VK_F7; + case Qt::Key_F8: + return VK_F8; + case Qt::Key_F9: + return VK_F9; + case Qt::Key_F10: + return VK_F10; + case Qt::Key_F11: + return VK_F11; + case Qt::Key_F12: + return VK_F12; + case Qt::Key_F13: + return VK_F13; + case Qt::Key_F14: + return VK_F14; + case Qt::Key_F15: + return VK_F15; + case Qt::Key_F16: + return VK_F16; + case Qt::Key_F17: + return VK_F17; + case Qt::Key_F18: + return VK_F18; + case Qt::Key_F19: + return VK_F19; + case Qt::Key_F20: + return VK_F20; + case Qt::Key_F21: + return VK_F21; + case Qt::Key_F22: + return VK_F22; + case Qt::Key_F23: + return VK_F23; + case Qt::Key_F24: + return VK_F24; + case Qt::Key_Space: + return VK_SPACE; + case Qt::Key_Asterisk: + return VK_MULTIPLY; + case Qt::Key_Plus: + return VK_ADD; + case Qt::Key_Comma: + return VK_SEPARATOR; + case Qt::Key_Minus: + return VK_SUBTRACT; + case Qt::Key_Slash: + return VK_DIVIDE; + + // numbers + case Qt::Key_0: + case Qt::Key_1: + case Qt::Key_2: + case Qt::Key_3: + case Qt::Key_4: + case Qt::Key_5: + case Qt::Key_6: + case Qt::Key_7: + case Qt::Key_8: + case Qt::Key_9: + return key; + + // letters + case Qt::Key_A: + case Qt::Key_B: + case Qt::Key_C: + case Qt::Key_D: + case Qt::Key_E: + case Qt::Key_F: + case Qt::Key_G: + case Qt::Key_H: + case Qt::Key_I: + case Qt::Key_J: + case Qt::Key_K: + case Qt::Key_L: + case Qt::Key_M: + case Qt::Key_N: + case Qt::Key_O: + case Qt::Key_P: + case Qt::Key_Q: + case Qt::Key_R: + case Qt::Key_S: + case Qt::Key_T: + case Qt::Key_U: + case Qt::Key_V: + case Qt::Key_W: + case Qt::Key_X: + case Qt::Key_Y: + case Qt::Key_Z: + return key; + + default: + return 0; + } +} + +bool QxtGlobalShortcutPrivate::registerShortcut(quint32 nativeKey, quint32 nativeMods) +{ + return RegisterHotKey(0, nativeMods ^ nativeKey, nativeMods, nativeKey); +} + +bool QxtGlobalShortcutPrivate::unregisterShortcut(quint32 nativeKey, quint32 nativeMods) +{ + return UnregisterHotKey(0, nativeMods ^ nativeKey); +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_x11.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_x11.cpp index 395a67a97..2b2e6b7b4 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_x11.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtglobalshortcut_x11.cpp @@ -1,115 +1,115 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include "qxtglobalshortcut_p.h" -#include -#include - -static int (*original_x_errhandler)(Display* display, XErrorEvent* event); - -static int qxt_x_errhandler(Display* display, XErrorEvent *event) -{ - Q_UNUSED(display); - switch (event->error_code) - { - case BadAccess: - case BadValue: - case BadWindow: - if (event->request_code == 33 /* X_GrabKey */ || - event->request_code == 34 /* X_UngrabKey */) - { - QxtGlobalShortcutPrivate::error = true; - //TODO: - //char errstr[256]; - //XGetErrorText(dpy, err->error_code, errstr, 256); - } - default: - return 0; - } -} - -bool QxtGlobalShortcutPrivate::eventFilter(void* message) -{ - XEvent* event = static_cast(message); - if (event->type == KeyPress) - { - XKeyEvent* key = (XKeyEvent*) event; - activateShortcut(key->keycode, - // Mod1Mask == Alt, Mod4Mask == Meta - key->state & (ShiftMask | ControlMask | Mod1Mask | Mod4Mask)); - } - return false; -} - -quint32 QxtGlobalShortcutPrivate::nativeModifiers(Qt::KeyboardModifiers modifiers) -{ - // ShiftMask, LockMask, ControlMask, Mod1Mask, Mod2Mask, Mod3Mask, Mod4Mask, and Mod5Mask - quint32 native = 0; - if (modifiers & Qt::ShiftModifier) - native |= ShiftMask; - if (modifiers & Qt::ControlModifier) - native |= ControlMask; - if (modifiers & Qt::AltModifier) - native |= Mod1Mask; - // TODO: resolve these? - //if (modifiers & Qt::MetaModifier) - //if (modifiers & Qt::KeypadModifier) - //if (modifiers & Qt::GroupSwitchModifier) - return native; -} - -quint32 QxtGlobalShortcutPrivate::nativeKeycode(Qt::Key key) -{ - Display* display = QX11Info::display(); - return XKeysymToKeycode(display, XStringToKeysym(QKeySequence(key).toString().toLatin1().data())); -} - -bool QxtGlobalShortcutPrivate::registerShortcut(quint32 nativeKey, quint32 nativeMods) -{ - Display* display = QX11Info::display(); - Window window = QX11Info::appRootWindow(); - Bool owner = True; - int pointer = GrabModeAsync; - int keyboard = GrabModeAsync; - error = false; - original_x_errhandler = XSetErrorHandler(qxt_x_errhandler); - XGrabKey(display, nativeKey, nativeMods, window, owner, pointer, keyboard); - XGrabKey(display, nativeKey, nativeMods | Mod2Mask, window, owner, pointer, keyboard); // allow numlock - XSync(display, False); - XSetErrorHandler(original_x_errhandler); - return !error; -} - -bool QxtGlobalShortcutPrivate::unregisterShortcut(quint32 nativeKey, quint32 nativeMods) -{ - Display* display = QX11Info::display(); - Window window = QX11Info::appRootWindow(); - error = false; - original_x_errhandler = XSetErrorHandler(qxt_x_errhandler); - XUngrabKey(display, nativeKey, nativeMods, window); - XUngrabKey(display, nativeKey, nativeMods | Mod2Mask, window); // allow numlock - XSync(display, False); - XSetErrorHandler(original_x_errhandler); - return !error; -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include "qxtglobalshortcut_p.h" +#include +#include + +static int (*original_x_errhandler)(Display* display, XErrorEvent* event); + +static int qxt_x_errhandler(Display* display, XErrorEvent *event) +{ + Q_UNUSED(display); + switch (event->error_code) + { + case BadAccess: + case BadValue: + case BadWindow: + if (event->request_code == 33 /* X_GrabKey */ || + event->request_code == 34 /* X_UngrabKey */) + { + QxtGlobalShortcutPrivate::error = true; + //TODO: + //char errstr[256]; + //XGetErrorText(dpy, err->error_code, errstr, 256); + } + default: + return 0; + } +} + +bool QxtGlobalShortcutPrivate::eventFilter(void* message) +{ + XEvent* event = static_cast(message); + if (event->type == KeyPress) + { + XKeyEvent* key = (XKeyEvent*) event; + activateShortcut(key->keycode, + // Mod1Mask == Alt, Mod4Mask == Meta + key->state & (ShiftMask | ControlMask | Mod1Mask | Mod4Mask)); + } + return false; +} + +quint32 QxtGlobalShortcutPrivate::nativeModifiers(Qt::KeyboardModifiers modifiers) +{ + // ShiftMask, LockMask, ControlMask, Mod1Mask, Mod2Mask, Mod3Mask, Mod4Mask, and Mod5Mask + quint32 native = 0; + if (modifiers & Qt::ShiftModifier) + native |= ShiftMask; + if (modifiers & Qt::ControlModifier) + native |= ControlMask; + if (modifiers & Qt::AltModifier) + native |= Mod1Mask; + // TODO: resolve these? + //if (modifiers & Qt::MetaModifier) + //if (modifiers & Qt::KeypadModifier) + //if (modifiers & Qt::GroupSwitchModifier) + return native; +} + +quint32 QxtGlobalShortcutPrivate::nativeKeycode(Qt::Key key) +{ + Display* display = QX11Info::display(); + return XKeysymToKeycode(display, XStringToKeysym(QKeySequence(key).toString().toLatin1().data())); +} + +bool QxtGlobalShortcutPrivate::registerShortcut(quint32 nativeKey, quint32 nativeMods) +{ + Display* display = QX11Info::display(); + Window window = QX11Info::appRootWindow(); + Bool owner = True; + int pointer = GrabModeAsync; + int keyboard = GrabModeAsync; + error = false; + original_x_errhandler = XSetErrorHandler(qxt_x_errhandler); + XGrabKey(display, nativeKey, nativeMods, window, owner, pointer, keyboard); + XGrabKey(display, nativeKey, nativeMods | Mod2Mask, window, owner, pointer, keyboard); // allow numlock + XSync(display, False); + XSetErrorHandler(original_x_errhandler); + return !error; +} + +bool QxtGlobalShortcutPrivate::unregisterShortcut(quint32 nativeKey, quint32 nativeMods) +{ + Display* display = QX11Info::display(); + Window window = QX11Info::appRootWindow(); + error = false; + original_x_errhandler = XSetErrorHandler(qxt_x_errhandler); + XUngrabKey(display, nativeKey, nativeMods, window); + XUngrabKey(display, nativeKey, nativeMods | Mod2Mask, window); // allow numlock + XSync(display, False); + XSetErrorHandler(original_x_errhandler); + return !error; +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit.cpp index 23f705733..50d555abf 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit.cpp @@ -1,186 +1,186 @@ -#include "qxtlookuplineedit.h" -#include "qxtlookuplineedit_p.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/*! - \class QxtLookupLineEdit QxtLookupLineEdit - \brief The QxtLookupLineEdit class is a QLineEdit to select from data provided by a QAbstractItemModel. - QxtLookupLineEdit uses QxtFilterDialog to make it easy for the user, - to select data from a large dataset. - \code - QSqlQueryModel *model = new QSqlQueryModel(parent); - model->setQuery("Select employeeNr,name,forename,hometown,phone from employees;",dbConnection); - QxtLookupLineEdit* edit = new QxtLookupLineEdit(parent); - edit->setSourceModel(model); - //we want to search by name not by nr so use the name column - edit->setLookupColumn(1); - //we need the employeeNr in the lineEdit , so choose col 0 as dataColumn - edit->setDataColumn(0); - //we want to seek the Display Role - edit->setLookupRole(Qt::DisplayRole); - //if the user presses * in the lineEdit open the popup - edit->setPopupTrigger(QKeySequence("*")); - \endcode - */ - - -QxtLookupLineEditPrivate::QxtLookupLineEditPrivate() -{ -} - -QxtLookupLineEdit::QxtLookupLineEdit(QWidget *parent) - : QLineEdit(parent) -{ - QXT_INIT_PRIVATE(QxtLookupLineEdit); - qxt_d().m_dataColumn = qxt_d().m_lookupColumn = 0; - qxt_d().m_lookupRole = Qt::DisplayRole; - qxt_d().m_sourceModel = 0; -} - -QxtLookupLineEdit::~QxtLookupLineEdit() -{ - -} - -/*! - \brief returns the sourceModel - \sa setSourceModel(QAbstractItemModel *model) - */ -QAbstractItemModel *QxtLookupLineEdit::sourceModel() const -{ - return qxt_d().m_sourceModel; -} -/*! - \brief returns the column the lineEdit is looking - \sa setLookupColumn(const int column) - */ -int QxtLookupLineEdit::lookupColumn () const -{ - return qxt_d().m_lookupColumn; -} -/*! - \brief returns the role the lineEdit is looking - \sa setLookupRole(const int role) - */ -int QxtLookupLineEdit::lookupRole () const -{ - return qxt_d().m_lookupRole; -} -/*! - \brief returns the trigger that opens the popup - \sa setPopupTrigger (const QKeySequence &trigger) - */ -QKeySequence QxtLookupLineEdit::popupTrigger () const -{ - return qxt_d().m_trigger; -} - -/*! - \brief sets the sourceModel used in the popup dialog - */ -void QxtLookupLineEdit::setSourceModel(QAbstractItemModel *model) -{ - qxt_d().m_sourceModel = model; -} -/*! - \brief sets the column wherethe popup dialog searches - */ -void QxtLookupLineEdit::setLookupColumn (const int column) -{ - qxt_d().m_lookupColumn = (column); -} -/*! - \brief sets the model role the popup should use - */ -void QxtLookupLineEdit::setLookupRole (const int role) -{ - qxt_d().m_lookupRole = (role); -} -/*! - \brief Sets the popup trigger that makes QxtLookupLineEdit open the popup dialog - */ -void QxtLookupLineEdit::setPopupTrigger (const QKeySequence &trigger) -{ - qxt_d().m_trigger = trigger; -} - -void QxtLookupLineEdit::showPopup () -{ - /*open wildcard dialog*/ - if(!sourceModel()) - return; - - QString tempText = text(); - if(hasSelectedText()){ - QString selected = selectedText(); - tempText.replace(selected,""); - } - - QModelIndex currIndex = QxtFilterDialog::getIndex(this,qxt_d().m_sourceModel,qxt_d().m_lookupColumn,qxt_d().m_lookupRole,tempText); - if(currIndex.isValid()){ - QModelIndex dataIndex = sourceModel()->index(currIndex.row(),dataColumn()); - if(dataIndex.isValid()) - { - setText(dataIndex.data(lookupRole()).toString()); - emit selected(); - this->nextInFocusChain()->setFocus(); - } - } - -#if 0 - - QPoint pos = this->geometry().topLeft(); - if(qobject_cast(this->parent())) - pos = qobject_cast(this->parent())->mapToGlobal(pos); - - qxt_d().filterView->setGeometry(QRect(pos,QSize(400,300))); - qxt_d().filterView->setFilterText(text()); - int ret = qxt_d().filterView->exec(); - - if(ret == QDialog::Accepted) - { - QModelIndex currIndex = qxt_d().filterView->selectedIndex(); - QModelIndex dataIndex = sourceModel()->index(currIndex.row(),dataColumn()); - if(dataIndex.isValid()) - { - setText(dataIndex.data(lookupRole()).toString()); - this->nextInFocusChain()->setFocus(); - } - } -#endif -} - -void QxtLookupLineEdit::keyPressEvent ( QKeyEvent * event ) -{ - QKeySequence currSeq = QKeySequence(event->key() | event->modifiers()); - if(currSeq.matches(qxt_d().m_trigger)) - showPopup (); - else - QLineEdit::keyPressEvent(event); -} - -/*! - \brief set the model column index QxtLookupLineEdit will use to get data from the model - after the user has chosen the dataset in the popup - */ -void QxtLookupLineEdit::setDataColumn (const int column) -{ - qxt_d().m_dataColumn = column; -} -/*! - \brief returns the model column index QxtLookupLineEdit will use to get data from the model - after the user has chosen the dataset in the popup - */ -int QxtLookupLineEdit::dataColumn ( ) const -{ - return qxt_d().m_dataColumn; -} +#include "qxtlookuplineedit.h" +#include "qxtlookuplineedit_p.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/*! + \class QxtLookupLineEdit QxtLookupLineEdit + \brief The QxtLookupLineEdit class is a QLineEdit to select from data provided by a QAbstractItemModel. + QxtLookupLineEdit uses QxtFilterDialog to make it easy for the user, + to select data from a large dataset. + \code + QSqlQueryModel *model = new QSqlQueryModel(parent); + model->setQuery("Select employeeNr,name,forename,hometown,phone from employees;",dbConnection); + QxtLookupLineEdit* edit = new QxtLookupLineEdit(parent); + edit->setSourceModel(model); + //we want to search by name not by nr so use the name column + edit->setLookupColumn(1); + //we need the employeeNr in the lineEdit , so choose col 0 as dataColumn + edit->setDataColumn(0); + //we want to seek the Display Role + edit->setLookupRole(Qt::DisplayRole); + //if the user presses * in the lineEdit open the popup + edit->setPopupTrigger(QKeySequence("*")); + \endcode + */ + + +QxtLookupLineEditPrivate::QxtLookupLineEditPrivate() +{ +} + +QxtLookupLineEdit::QxtLookupLineEdit(QWidget *parent) + : QLineEdit(parent) +{ + QXT_INIT_PRIVATE(QxtLookupLineEdit); + qxt_d().m_dataColumn = qxt_d().m_lookupColumn = 0; + qxt_d().m_lookupRole = Qt::DisplayRole; + qxt_d().m_sourceModel = 0; +} + +QxtLookupLineEdit::~QxtLookupLineEdit() +{ + +} + +/*! + \brief returns the sourceModel + \sa setSourceModel(QAbstractItemModel *model) + */ +QAbstractItemModel *QxtLookupLineEdit::sourceModel() const +{ + return qxt_d().m_sourceModel; +} +/*! + \brief returns the column the lineEdit is looking + \sa setLookupColumn(const int column) + */ +int QxtLookupLineEdit::lookupColumn () const +{ + return qxt_d().m_lookupColumn; +} +/*! + \brief returns the role the lineEdit is looking + \sa setLookupRole(const int role) + */ +int QxtLookupLineEdit::lookupRole () const +{ + return qxt_d().m_lookupRole; +} +/*! + \brief returns the trigger that opens the popup + \sa setPopupTrigger (const QKeySequence &trigger) + */ +QKeySequence QxtLookupLineEdit::popupTrigger () const +{ + return qxt_d().m_trigger; +} + +/*! + \brief sets the sourceModel used in the popup dialog + */ +void QxtLookupLineEdit::setSourceModel(QAbstractItemModel *model) +{ + qxt_d().m_sourceModel = model; +} +/*! + \brief sets the column wherethe popup dialog searches + */ +void QxtLookupLineEdit::setLookupColumn (const int column) +{ + qxt_d().m_lookupColumn = (column); +} +/*! + \brief sets the model role the popup should use + */ +void QxtLookupLineEdit::setLookupRole (const int role) +{ + qxt_d().m_lookupRole = (role); +} +/*! + \brief Sets the popup trigger that makes QxtLookupLineEdit open the popup dialog + */ +void QxtLookupLineEdit::setPopupTrigger (const QKeySequence &trigger) +{ + qxt_d().m_trigger = trigger; +} + +void QxtLookupLineEdit::showPopup () +{ + /*open wildcard dialog*/ + if(!sourceModel()) + return; + + QString tempText = text(); + if(hasSelectedText()){ + QString selected = selectedText(); + tempText.replace(selected,""); + } + + QModelIndex currIndex = QxtFilterDialog::getIndex(this,qxt_d().m_sourceModel,qxt_d().m_lookupColumn,qxt_d().m_lookupRole,tempText); + if(currIndex.isValid()){ + QModelIndex dataIndex = sourceModel()->index(currIndex.row(),dataColumn()); + if(dataIndex.isValid()) + { + setText(dataIndex.data(lookupRole()).toString()); + emit selected(); + this->nextInFocusChain()->setFocus(); + } + } + +#if 0 + + QPoint pos = this->geometry().topLeft(); + if(qobject_cast(this->parent())) + pos = qobject_cast(this->parent())->mapToGlobal(pos); + + qxt_d().filterView->setGeometry(QRect(pos,QSize(400,300))); + qxt_d().filterView->setFilterText(text()); + int ret = qxt_d().filterView->exec(); + + if(ret == QDialog::Accepted) + { + QModelIndex currIndex = qxt_d().filterView->selectedIndex(); + QModelIndex dataIndex = sourceModel()->index(currIndex.row(),dataColumn()); + if(dataIndex.isValid()) + { + setText(dataIndex.data(lookupRole()).toString()); + this->nextInFocusChain()->setFocus(); + } + } +#endif +} + +void QxtLookupLineEdit::keyPressEvent ( QKeyEvent * event ) +{ + QKeySequence currSeq = QKeySequence(event->key() | event->modifiers()); + if(currSeq.matches(qxt_d().m_trigger)) + showPopup (); + else + QLineEdit::keyPressEvent(event); +} + +/*! + \brief set the model column index QxtLookupLineEdit will use to get data from the model + after the user has chosen the dataset in the popup + */ +void QxtLookupLineEdit::setDataColumn (const int column) +{ + qxt_d().m_dataColumn = column; +} +/*! + \brief returns the model column index QxtLookupLineEdit will use to get data from the model + after the user has chosen the dataset in the popup + */ +int QxtLookupLineEdit::dataColumn ( ) const +{ + return qxt_d().m_dataColumn; +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit.h index ba698424c..7db1331d5 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit.h @@ -1,48 +1,48 @@ -#ifndef QXTLOOKUPLINEEDIT_H_INCLUDED -#define QXTLOOKUPLINEEDIT_H_INCLUDED - -#include -#include -#include -#include "qxtglobal.h" - -class QxtLookupLineEditPrivate; -class QAbstractItemModel; -class QKeyEvent; - -class QXT_GUI_EXPORT QxtLookupLineEdit : public QLineEdit -{ - Q_OBJECT - -public: - QxtLookupLineEdit(QWidget *parent = 0); - ~QxtLookupLineEdit(); - - void setSourceModel (QAbstractItemModel *model); - void setLookupColumn (const int column); - void setDataColumn (const int column); - void setLookupRole (const int role); - void setPopupTrigger (const QKeySequence &trigger); - - QAbstractItemModel *sourceModel() const; - int lookupColumn ( ) const; - int dataColumn ( ) const; - int lookupRole ( ) const; - QKeySequence popupTrigger () const; - -protected: - virtual void keyPressEvent ( QKeyEvent * event ); - -protected slots: - virtual void showPopup(); - -signals: - void selected (); - - -private: - QXT_DECLARE_PRIVATE(QxtLookupLineEdit); - -}; - -#endif // QXTLOOKUPLINEEDIT_H_INCLUDED +#ifndef QXTLOOKUPLINEEDIT_H_INCLUDED +#define QXTLOOKUPLINEEDIT_H_INCLUDED + +#include +#include +#include +#include "qxtglobal.h" + +class QxtLookupLineEditPrivate; +class QAbstractItemModel; +class QKeyEvent; + +class QXT_GUI_EXPORT QxtLookupLineEdit : public QLineEdit +{ + Q_OBJECT + +public: + QxtLookupLineEdit(QWidget *parent = 0); + ~QxtLookupLineEdit(); + + void setSourceModel (QAbstractItemModel *model); + void setLookupColumn (const int column); + void setDataColumn (const int column); + void setLookupRole (const int role); + void setPopupTrigger (const QKeySequence &trigger); + + QAbstractItemModel *sourceModel() const; + int lookupColumn ( ) const; + int dataColumn ( ) const; + int lookupRole ( ) const; + QKeySequence popupTrigger () const; + +protected: + virtual void keyPressEvent ( QKeyEvent * event ); + +protected slots: + virtual void showPopup(); + +signals: + void selected (); + + +private: + QXT_DECLARE_PRIVATE(QxtLookupLineEdit); + +}; + +#endif // QXTLOOKUPLINEEDIT_H_INCLUDED diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit_p.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit_p.h index d5f0c97e9..4223f62e9 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit_p.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtlookuplineedit_p.h @@ -1,28 +1,28 @@ -#ifndef QXTLOOKUPLINEEDIT_P_H_INCLUDED -#define QXTLOOKUPLINEEDIT_P_H_INCLUDED - -#include "qxtpimpl.h" -#include "qxtfilterdialog.h" -#include -#include -#include -#include - -class QxtLookupLineEdit; -class QAbstractItemModel; - -class QxtLookupLineEditPrivate : public QxtPrivate -{ - public: - QxtLookupLineEditPrivate(); - QXT_DECLARE_PUBLIC(QxtLookupLineEdit); - - int m_dataColumn; - int m_lookupColumn; - int m_lookupRole; - QAbstractItemModel* m_sourceModel; - QKeySequence m_trigger; - -}; - -#endif //QXTLOOKUPLINEEDIT_P_H_INCLUDED +#ifndef QXTLOOKUPLINEEDIT_P_H_INCLUDED +#define QXTLOOKUPLINEEDIT_P_H_INCLUDED + +#include "qxtpimpl.h" +#include "qxtfilterdialog.h" +#include +#include +#include +#include + +class QxtLookupLineEdit; +class QAbstractItemModel; + +class QxtLookupLineEditPrivate : public QxtPrivate +{ + public: + QxtLookupLineEditPrivate(); + QXT_DECLARE_PUBLIC(QxtLookupLineEdit); + + int m_dataColumn; + int m_lookupColumn; + int m_lookupRole; + QAbstractItemModel* m_sourceModel; + QKeySequence m_trigger; + +}; + +#endif //QXTLOOKUPLINEEDIT_P_H_INCLUDED diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtnativeeventfilter.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtnativeeventfilter.h index bc8008aaf..5b8d3a487 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtnativeeventfilter.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtnativeeventfilter.h @@ -1,58 +1,58 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#ifndef QXTNATIVEEVENTFILTER_H -#define QXTNATIVEEVENTFILTER_H - -#include "qxtapplication.h" - -class QxtNativeEventFilter -{ -public: - virtual ~QxtNativeEventFilter() - { - qxtApp->removeNativeEventFilter(this); - } - -#if defined(Q_WS_X11) || defined(QXT_DOXYGEN_RUN) - virtual bool x11EventFilter(XEvent*) - { - return false; - } -#endif // Q_WS_X11 -#if defined(Q_WS_WIN) || defined(QXT_DOXYGEN_RUN) - virtual bool winEventFilter(MSG*, long*) - { - return false; - } -#endif // Q_WS_WIN -#if defined(Q_WS_MAC) || defined(QXT_DOXYGEN_RUN) - virtual bool macEventFilter(EventHandlerCallRef, EventRef) - { - return false; - } -#endif // Q_WS_MAC -}; - -#endif // QXTNATIVEEVENTFILTER_H +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#ifndef QXTNATIVEEVENTFILTER_H +#define QXTNATIVEEVENTFILTER_H + +#include "qxtapplication.h" + +class QxtNativeEventFilter +{ +public: + virtual ~QxtNativeEventFilter() + { + qxtApp->removeNativeEventFilter(this); + } + +#if defined(Q_WS_X11) || defined(QXT_DOXYGEN_RUN) + virtual bool x11EventFilter(XEvent*) + { + return false; + } +#endif // Q_WS_X11 +#if defined(Q_WS_WIN) || defined(QXT_DOXYGEN_RUN) + virtual bool winEventFilter(MSG*, long*) + { + return false; + } +#endif // Q_WS_WIN +#if defined(Q_WS_MAC) || defined(QXT_DOXYGEN_RUN) + virtual bool macEventFilter(EventHandlerCallRef, EventRef) + { + return false; + } +#endif // Q_WS_MAC +}; + +#endif // QXTNATIVEEVENTFILTER_H diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtproxystyle.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtproxystyle.cpp index 28949867c..85e9d3a94 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtproxystyle.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtproxystyle.cpp @@ -273,11 +273,11 @@ void QxtProxyStyle::unpolish(QApplication* app) */ QIcon QxtProxyStyle::standardIconImplementation(StandardPixmap standardIcon, const QStyleOption* option, const QWidget* widget) const { - QIcon result; - QMetaObject::invokeMethod(style, "standardIconImplementation", Qt::DirectConnection, - Q_RETURN_ARG(QIcon, result), - Q_ARG(StandardPixmap, standardIcon), - Q_ARG(const QStyleOption*, option), - Q_ARG(const QWidget*, widget)); - return result; + QIcon result; + QMetaObject::invokeMethod(style, "standardIconImplementation", Qt::DirectConnection, + Q_RETURN_ARG(QIcon, result), + Q_ARG(StandardPixmap, standardIcon), + Q_ARG(const QStyleOption*, option), + Q_ARG(const QWidget*, widget)); + return result; } diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleheaderwidget.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleheaderwidget.cpp index 1e8229e4e..a7c885025 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleheaderwidget.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleheaderwidget.cpp @@ -1,89 +1,89 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include "qxtscheduleheaderwidget.h" -#include "qxtscheduleview.h" -#include "qxtscheduleviewheadermodel_p.h" - -#include -#include -#include -#include - - -/*! - * @internal the QxtAgendaHeaderWidget operates on a internal model , that uses the QxtScheduleView as DataSource - * - */ - -QxtScheduleHeaderWidget::QxtScheduleHeaderWidget(Qt::Orientation orientation , QxtScheduleView *parent) : QHeaderView(orientation, parent) -{ - QxtScheduleViewHeaderModel *model = new QxtScheduleViewHeaderModel(this); - setModel(model); - - if (parent) - { - model->setDataSource(parent); - } -} - -void QxtScheduleHeaderWidget::paintSection(QPainter * painter, const QRect & rect, int logicalIndex) const -{ - if (model()) - { - switch (orientation()) - { - case Qt::Horizontal: - { - QHeaderView::paintSection(painter, rect, logicalIndex); - } - break; - case Qt::Vertical: - { - QTime time = model()->headerData(logicalIndex, Qt::Vertical, Qt::DisplayRole).toTime(); - if (time.isValid()) - { - QRect temp = rect; - temp.adjust(1, 1, -1, -1); - - painter->fillRect(rect, this->palette().background()); - - if (time.minute() == 0) - { - painter->drawLine(temp.topLeft() + QPoint(temp.width() / 3, 0), temp.topRight()); - painter->drawText(temp, Qt::AlignTop | Qt::AlignRight, time.toString("hh:mm")); - } - } - } - break; - default: - Q_ASSERT(false); //this will never happen... normally - } - } -} - -void QxtScheduleHeaderWidget::setModel(QxtScheduleViewHeaderModel *model) -{ - QHeaderView::setModel(model); -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include "qxtscheduleheaderwidget.h" +#include "qxtscheduleview.h" +#include "qxtscheduleviewheadermodel_p.h" + +#include +#include +#include +#include + + +/*! + * @internal the QxtAgendaHeaderWidget operates on a internal model , that uses the QxtScheduleView as DataSource + * + */ + +QxtScheduleHeaderWidget::QxtScheduleHeaderWidget(Qt::Orientation orientation , QxtScheduleView *parent) : QHeaderView(orientation, parent) +{ + QxtScheduleViewHeaderModel *model = new QxtScheduleViewHeaderModel(this); + setModel(model); + + if (parent) + { + model->setDataSource(parent); + } +} + +void QxtScheduleHeaderWidget::paintSection(QPainter * painter, const QRect & rect, int logicalIndex) const +{ + if (model()) + { + switch (orientation()) + { + case Qt::Horizontal: + { + QHeaderView::paintSection(painter, rect, logicalIndex); + } + break; + case Qt::Vertical: + { + QTime time = model()->headerData(logicalIndex, Qt::Vertical, Qt::DisplayRole).toTime(); + if (time.isValid()) + { + QRect temp = rect; + temp.adjust(1, 1, -1, -1); + + painter->fillRect(rect, this->palette().background()); + + if (time.minute() == 0) + { + painter->drawLine(temp.topLeft() + QPoint(temp.width() / 3, 0), temp.topRight()); + painter->drawText(temp, Qt::AlignTop | Qt::AlignRight, time.toString("hh:mm")); + } + } + } + break; + default: + Q_ASSERT(false); //this will never happen... normally + } + } +} + +void QxtScheduleHeaderWidget::setModel(QxtScheduleViewHeaderModel *model) +{ + QHeaderView::setModel(model); +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleheaderwidget.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleheaderwidget.h index ea17fe811..6eaa2a338 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleheaderwidget.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleheaderwidget.h @@ -1,49 +1,49 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#ifndef QXTSCHEDULEHEADERWIDGET_H_INCLUDED -#define QXTSCHEDULEHEADERWIDGET_H_INCLUDED - -#include -#include "qxtglobal.h" - -class QxtScheduleView; -class QxtScheduleViewHeaderModel; - -class QXT_GUI_EXPORT QxtScheduleHeaderWidget : public QHeaderView -{ - Q_OBJECT - -public: - explicit QxtScheduleHeaderWidget(Qt::Orientation orientation, QxtScheduleView *parent = 0); - -protected: - virtual void paintSection(QPainter * painter, const QRect & rect, int logicalIndex) const; - -private: - virtual void setModel(QxtScheduleViewHeaderModel *model); -}; - -#endif // QXTSCHEDULEHEADERWIDGET_H_INCLUDED - +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#ifndef QXTSCHEDULEHEADERWIDGET_H_INCLUDED +#define QXTSCHEDULEHEADERWIDGET_H_INCLUDED + +#include +#include "qxtglobal.h" + +class QxtScheduleView; +class QxtScheduleViewHeaderModel; + +class QXT_GUI_EXPORT QxtScheduleHeaderWidget : public QHeaderView +{ + Q_OBJECT + +public: + explicit QxtScheduleHeaderWidget(Qt::Orientation orientation, QxtScheduleView *parent = 0); + +protected: + virtual void paintSection(QPainter * painter, const QRect & rect, int logicalIndex) const; + +private: + virtual void setModel(QxtScheduleViewHeaderModel *model); +}; + +#endif // QXTSCHEDULEHEADERWIDGET_H_INCLUDED + diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleitemdelegate.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleitemdelegate.cpp index d46aa0f85..62c3842e6 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleitemdelegate.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleitemdelegate.cpp @@ -1,282 +1,282 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include "qxtscheduleitemdelegate.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "qxtnamespace.h" - -QxtScheduleItemDelegate::QxtScheduleItemDelegate(QObject *parent) - : QAbstractItemDelegate(parent) -{ -} - - -QxtScheduleItemDelegate::~QxtScheduleItemDelegate() -{ -} - - -/*! - * reimplemented for item painting - * You should not reimplement this to change the item painting, use paintItemBody, paintItemHeader and paintSubItem instead - * because this function uses caches to speed up painting. If you want to change the item shape only you could also reimplement - * the createPainterPath function. - * \note the parameter option hast to be of type QxtStyleOptionScheduleViewItem or the delegate will not paint something - * \sa paintItemBody(), paintItemHeader(), paintSubItem() - */ -void QxtScheduleItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const -{ - - const QxtStyleOptionScheduleViewItem *agendaOption = qstyleoption_cast(&option); - if (!agendaOption) - return; - - QStringList rowsData = index.data(Qt::EditRole).toStringList(); - - QRect currRect; - - painter->save(); - - if (agendaOption->itemPaintCache->size() != agendaOption->itemGeometries.size()) - (*agendaOption->itemPaintCache) = QVector(agendaOption->itemGeometries.size(), QPixmap()); - - int lastPart = agendaOption->itemGeometries.size() - 1; - int paintedSubItems = 0; - - for (int iLoop = 0; iLoop < agendaOption->itemGeometries.size();iLoop++) - { - if ((*agendaOption->itemPaintCache)[iLoop].width() != agendaOption->itemGeometries[iLoop].width() - || (*agendaOption->itemPaintCache)[iLoop].height() != agendaOption->itemGeometries[iLoop].height()) - { - //If we enter this codepath we have to rebuild the pixmap cache - //so first we create a empty pixmap - (*agendaOption->itemPaintCache)[iLoop] = QPixmap(agendaOption->itemGeometries[iLoop].size()); - (*agendaOption->itemPaintCache)[iLoop].fill(Qt::transparent); - - QPainter cachePainter(&(*agendaOption->itemPaintCache)[iLoop]); - QRect rect = QRect(QPoint(0, 0), agendaOption->itemGeometries[iLoop].size()); - - //what kind of itempart do we need to paint? - ItemPart part = iLoop == 0 ? Top : (iLoop == lastPart ? Bottom : Middle); - - //if the item has only one part - if (lastPart == 0) - part = Single; - - //paint the item body - cachePainter.save(); - paintItemBody(&cachePainter, rect, *agendaOption, part, index); - cachePainter.restore(); - - int remainingHeight = rect.height(); - - //paint item header - if (iLoop == 0 && agendaOption->itemHeaderHeight > 0 && agendaOption->itemHeaderHeight < remainingHeight) - { - QRect headerRect(0, 0, rect.width(), agendaOption->itemHeaderHeight); - paintItemHeader(&cachePainter, headerRect, *agendaOption, index); - remainingHeight -= agendaOption->itemHeaderHeight; - } - - //paint subitems if there are any - int subItems = index.model()->rowCount(index); - for (int items = paintedSubItems; items < subItems; items++) - { - QModelIndex currSubItem = index.model()->index(items, 0, index); - QSize size = sizeHint(option, currSubItem); - - if (currSubItem.isValid()){ - paintSubItem(&cachePainter, QRect(), *agendaOption, currSubItem); - } - - paintedSubItems++; - } - - cachePainter.end(); - - } - currRect = agendaOption->itemGeometries[iLoop]; - currRect.translate(agendaOption->translate); - painter->drawPixmap(currRect, (*agendaOption->itemPaintCache)[iLoop]); - } - painter->restore(); -} - -/*! - * \brief paints the items body reimplement this to paint a custom body - * \a QPainter *painter the initialized painter - * \a const QRect rect the ItemPart rect - * \a const QxtStyleOptionScheduleViewItem & option - * \a const ItemPart part this indicates what part of the item gets painted, remember items can be splitted in parts - * \a const QModelIndex &index the items model index - */ -void QxtScheduleItemDelegate::paintItemBody(QPainter *painter, const QRect rect , const QxtStyleOptionScheduleViewItem & option , const ItemPart part, const QModelIndex & index) const -{ - int iCurrRoundTop, iCurrRoundBottom; - iCurrRoundTop = iCurrRoundBottom = 0; - - QColor fillColor = index.data(Qt::BackgroundRole).value(); - fillColor.setAlpha(120); - QColor outLineColor = index.data(Qt::ForegroundRole).value(); - - painter->setFont(option.font); - painter->setRenderHint(QPainter::Antialiasing); - - if (part == Top || part == Single) - iCurrRoundTop = option.roundCornersRadius; - if (part == Bottom || part == Single) - iCurrRoundBottom = option.roundCornersRadius; - - QPainterPath cachePath; - QRect cacheRect = QRect(QPoint(1, 1), rect.size() - QSize(1, 1)); - - painter->setBrush(fillColor); - painter->setPen(outLineColor); - - createPainterPath(cachePath, cacheRect, iCurrRoundTop, iCurrRoundBottom); - painter->drawPath(cachePath); -} - -/*! - * \brief paints the items header reimplement this to paint a custom header - * \a QPainter *painter the initialized painter - * \a const QRect rect the header rect - * \a const QxtStyleOptionScheduleViewItem & option - * \a const QModelIndex &index the items model index - */ -void QxtScheduleItemDelegate::paintItemHeader(QPainter *painter, const QRect rect , const QxtStyleOptionScheduleViewItem & option, const QModelIndex &index) const -{ - bool converted = false; - int startUnixTime = index.data(Qxt::ItemStartTimeRole).toInt(&converted); - if (!converted) - return; - - int duration = index.data(Qxt::ItemDurationRole).toInt(&converted); - if (!converted) - return; - - QDateTime startTime = QDateTime::fromTime_t(startUnixTime); - QDateTime endTime = QDateTime::fromTime_t(startUnixTime + duration); - - if (!startTime.isValid() || !endTime.isValid()) - return; - - QFont font; - QVariant vfont = index.data(Qt::FontRole); - - if (vfont.isValid()) - font = vfont.value(); - else - font = option.font; - - QString text = startTime.toString("hh:mm") + ' ' + endTime.toString("hh:mm"); - QFontMetrics metr(font); - text = metr.elidedText(text, Qt::ElideRight, rect.width()); - painter->drawText(rect, Qt::AlignCenter, text); -} - -/*! - * \brief paints a subitem, if you want custom subitem painting reimplement this member function - * \a QPainter *painter the initialized painter - * \a const QRect rect the subitem rect - * \a const QxtStyleOptionScheduleViewItem & option - * \a const QModelIndex &index the items model index - */ -void QxtScheduleItemDelegate::paintSubItem(QPainter * /*painter*/, const QRect /*rect*/, const QxtStyleOptionScheduleViewItem & /*option*/, const QModelIndex & /*index*/) const -{ - -} - -/*! - * \brief returns the sizeHint for subitems. - */ -QSize QxtScheduleItemDelegate::sizeHint(const QStyleOptionViewItem & option, const QModelIndex & index) const -{ - //we return the size only for subitems and only the height - - if (index.parent().isValid()) - { - QSize size = index.data(Qt::SizeHintRole).toSize(); - - if (!size.isValid()) - { - QFont font; - QVariant vfont = index.data(Qt::FontRole); - - if (vfont.isValid()) - font = vfont.value(); - else - font = option.font; - - int height = 0; - QFontMetrics metr(font); - height = metr.height() + 2; - - return QSize(0, height); - } - } - return QSize(); -} - -void QxtScheduleItemDelegate::createPainterPath(QPainterPath & emptyPath, const QRect & fullItemRect, const int iRoundTop, const int iRoundBottom) const -{ - emptyPath = QPainterPath(); - bool bRoundTop = iRoundTop > 0; - bool bRountBottom = iRoundBottom > 0; - - if (bRoundTop) - { - emptyPath.moveTo(fullItemRect.topLeft() + QPoint(0, iRoundTop)); - emptyPath.quadTo(fullItemRect.topLeft(), fullItemRect.topLeft() + QPoint(iRoundTop, 0)); - } - else - emptyPath.moveTo(fullItemRect.topLeft()); - - emptyPath.lineTo(fullItemRect.topRight() - QPoint(iRoundTop, 0)); - - if (bRoundTop) - emptyPath.quadTo(fullItemRect.topRight(), fullItemRect.topRight() + QPoint(0, iRoundTop)); - - emptyPath.lineTo(fullItemRect.bottomRight() - QPoint(0, iRoundBottom)); - - if (bRountBottom) - emptyPath.quadTo(fullItemRect.bottomRight(), fullItemRect.bottomRight() - QPoint(iRoundBottom, 0)); - - emptyPath.lineTo(fullItemRect.bottomLeft() + QPoint(iRoundBottom, 0)); - - if (bRountBottom) - emptyPath.quadTo(fullItemRect.bottomLeft(), fullItemRect.bottomLeft() - QPoint(0, iRoundBottom)); - - emptyPath.closeSubpath(); -} - - +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include "qxtscheduleitemdelegate.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "qxtnamespace.h" + +QxtScheduleItemDelegate::QxtScheduleItemDelegate(QObject *parent) + : QAbstractItemDelegate(parent) +{ +} + + +QxtScheduleItemDelegate::~QxtScheduleItemDelegate() +{ +} + + +/*! + * reimplemented for item painting + * You should not reimplement this to change the item painting, use paintItemBody, paintItemHeader and paintSubItem instead + * because this function uses caches to speed up painting. If you want to change the item shape only you could also reimplement + * the createPainterPath function. + * \note the parameter option hast to be of type QxtStyleOptionScheduleViewItem or the delegate will not paint something + * \sa paintItemBody(), paintItemHeader(), paintSubItem() + */ +void QxtScheduleItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const +{ + + const QxtStyleOptionScheduleViewItem *agendaOption = qstyleoption_cast(&option); + if (!agendaOption) + return; + + QStringList rowsData = index.data(Qt::EditRole).toStringList(); + + QRect currRect; + + painter->save(); + + if (agendaOption->itemPaintCache->size() != agendaOption->itemGeometries.size()) + (*agendaOption->itemPaintCache) = QVector(agendaOption->itemGeometries.size(), QPixmap()); + + int lastPart = agendaOption->itemGeometries.size() - 1; + int paintedSubItems = 0; + + for (int iLoop = 0; iLoop < agendaOption->itemGeometries.size();iLoop++) + { + if ((*agendaOption->itemPaintCache)[iLoop].width() != agendaOption->itemGeometries[iLoop].width() + || (*agendaOption->itemPaintCache)[iLoop].height() != agendaOption->itemGeometries[iLoop].height()) + { + //If we enter this codepath we have to rebuild the pixmap cache + //so first we create a empty pixmap + (*agendaOption->itemPaintCache)[iLoop] = QPixmap(agendaOption->itemGeometries[iLoop].size()); + (*agendaOption->itemPaintCache)[iLoop].fill(Qt::transparent); + + QPainter cachePainter(&(*agendaOption->itemPaintCache)[iLoop]); + QRect rect = QRect(QPoint(0, 0), agendaOption->itemGeometries[iLoop].size()); + + //what kind of itempart do we need to paint? + ItemPart part = iLoop == 0 ? Top : (iLoop == lastPart ? Bottom : Middle); + + //if the item has only one part + if (lastPart == 0) + part = Single; + + //paint the item body + cachePainter.save(); + paintItemBody(&cachePainter, rect, *agendaOption, part, index); + cachePainter.restore(); + + int remainingHeight = rect.height(); + + //paint item header + if (iLoop == 0 && agendaOption->itemHeaderHeight > 0 && agendaOption->itemHeaderHeight < remainingHeight) + { + QRect headerRect(0, 0, rect.width(), agendaOption->itemHeaderHeight); + paintItemHeader(&cachePainter, headerRect, *agendaOption, index); + remainingHeight -= agendaOption->itemHeaderHeight; + } + + //paint subitems if there are any + int subItems = index.model()->rowCount(index); + for (int items = paintedSubItems; items < subItems; items++) + { + QModelIndex currSubItem = index.model()->index(items, 0, index); + QSize size = sizeHint(option, currSubItem); + + if (currSubItem.isValid()){ + paintSubItem(&cachePainter, QRect(), *agendaOption, currSubItem); + } + + paintedSubItems++; + } + + cachePainter.end(); + + } + currRect = agendaOption->itemGeometries[iLoop]; + currRect.translate(agendaOption->translate); + painter->drawPixmap(currRect, (*agendaOption->itemPaintCache)[iLoop]); + } + painter->restore(); +} + +/*! + * \brief paints the items body reimplement this to paint a custom body + * \a QPainter *painter the initialized painter + * \a const QRect rect the ItemPart rect + * \a const QxtStyleOptionScheduleViewItem & option + * \a const ItemPart part this indicates what part of the item gets painted, remember items can be splitted in parts + * \a const QModelIndex &index the items model index + */ +void QxtScheduleItemDelegate::paintItemBody(QPainter *painter, const QRect rect , const QxtStyleOptionScheduleViewItem & option , const ItemPart part, const QModelIndex & index) const +{ + int iCurrRoundTop, iCurrRoundBottom; + iCurrRoundTop = iCurrRoundBottom = 0; + + QColor fillColor = index.data(Qt::BackgroundRole).value(); + fillColor.setAlpha(120); + QColor outLineColor = index.data(Qt::ForegroundRole).value(); + + painter->setFont(option.font); + painter->setRenderHint(QPainter::Antialiasing); + + if (part == Top || part == Single) + iCurrRoundTop = option.roundCornersRadius; + if (part == Bottom || part == Single) + iCurrRoundBottom = option.roundCornersRadius; + + QPainterPath cachePath; + QRect cacheRect = QRect(QPoint(1, 1), rect.size() - QSize(1, 1)); + + painter->setBrush(fillColor); + painter->setPen(outLineColor); + + createPainterPath(cachePath, cacheRect, iCurrRoundTop, iCurrRoundBottom); + painter->drawPath(cachePath); +} + +/*! + * \brief paints the items header reimplement this to paint a custom header + * \a QPainter *painter the initialized painter + * \a const QRect rect the header rect + * \a const QxtStyleOptionScheduleViewItem & option + * \a const QModelIndex &index the items model index + */ +void QxtScheduleItemDelegate::paintItemHeader(QPainter *painter, const QRect rect , const QxtStyleOptionScheduleViewItem & option, const QModelIndex &index) const +{ + bool converted = false; + int startUnixTime = index.data(Qxt::ItemStartTimeRole).toInt(&converted); + if (!converted) + return; + + int duration = index.data(Qxt::ItemDurationRole).toInt(&converted); + if (!converted) + return; + + QDateTime startTime = QDateTime::fromTime_t(startUnixTime); + QDateTime endTime = QDateTime::fromTime_t(startUnixTime + duration); + + if (!startTime.isValid() || !endTime.isValid()) + return; + + QFont font; + QVariant vfont = index.data(Qt::FontRole); + + if (vfont.isValid()) + font = vfont.value(); + else + font = option.font; + + QString text = startTime.toString("hh:mm") + ' ' + endTime.toString("hh:mm"); + QFontMetrics metr(font); + text = metr.elidedText(text, Qt::ElideRight, rect.width()); + painter->drawText(rect, Qt::AlignCenter, text); +} + +/*! + * \brief paints a subitem, if you want custom subitem painting reimplement this member function + * \a QPainter *painter the initialized painter + * \a const QRect rect the subitem rect + * \a const QxtStyleOptionScheduleViewItem & option + * \a const QModelIndex &index the items model index + */ +void QxtScheduleItemDelegate::paintSubItem(QPainter * /*painter*/, const QRect /*rect*/, const QxtStyleOptionScheduleViewItem & /*option*/, const QModelIndex & /*index*/) const +{ + +} + +/*! + * \brief returns the sizeHint for subitems. + */ +QSize QxtScheduleItemDelegate::sizeHint(const QStyleOptionViewItem & option, const QModelIndex & index) const +{ + //we return the size only for subitems and only the height + + if (index.parent().isValid()) + { + QSize size = index.data(Qt::SizeHintRole).toSize(); + + if (!size.isValid()) + { + QFont font; + QVariant vfont = index.data(Qt::FontRole); + + if (vfont.isValid()) + font = vfont.value(); + else + font = option.font; + + int height = 0; + QFontMetrics metr(font); + height = metr.height() + 2; + + return QSize(0, height); + } + } + return QSize(); +} + +void QxtScheduleItemDelegate::createPainterPath(QPainterPath & emptyPath, const QRect & fullItemRect, const int iRoundTop, const int iRoundBottom) const +{ + emptyPath = QPainterPath(); + bool bRoundTop = iRoundTop > 0; + bool bRountBottom = iRoundBottom > 0; + + if (bRoundTop) + { + emptyPath.moveTo(fullItemRect.topLeft() + QPoint(0, iRoundTop)); + emptyPath.quadTo(fullItemRect.topLeft(), fullItemRect.topLeft() + QPoint(iRoundTop, 0)); + } + else + emptyPath.moveTo(fullItemRect.topLeft()); + + emptyPath.lineTo(fullItemRect.topRight() - QPoint(iRoundTop, 0)); + + if (bRoundTop) + emptyPath.quadTo(fullItemRect.topRight(), fullItemRect.topRight() + QPoint(0, iRoundTop)); + + emptyPath.lineTo(fullItemRect.bottomRight() - QPoint(0, iRoundBottom)); + + if (bRountBottom) + emptyPath.quadTo(fullItemRect.bottomRight(), fullItemRect.bottomRight() - QPoint(iRoundBottom, 0)); + + emptyPath.lineTo(fullItemRect.bottomLeft() + QPoint(iRoundBottom, 0)); + + if (bRountBottom) + emptyPath.quadTo(fullItemRect.bottomLeft(), fullItemRect.bottomLeft() - QPoint(0, iRoundBottom)); + + emptyPath.closeSubpath(); +} + + diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleitemdelegate.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleitemdelegate.h index 65b5b13df..298459933 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleitemdelegate.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleitemdelegate.h @@ -1,65 +1,65 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#ifndef QXTSCHEDULEITEMDELEGATE_H_INCLUDED -#define QXTSCHEDULEITEMDELEGATE_H_INCLUDED - -#include -#include -#include "qxtstyleoptionscheduleviewitem.h" -#include "qxtglobal.h" - -QT_FORWARD_DECLARE_CLASS(QPainter) - -/*! - @author Benjamin Zeller -*/ -class QXT_GUI_EXPORT QxtScheduleItemDelegate : public QAbstractItemDelegate -{ - Q_OBJECT -public: - - enum ItemPart - { - Top, - Middle, - Bottom, - Single - - }; - - QxtScheduleItemDelegate(QObject *parent = 0); - ~QxtScheduleItemDelegate(); - - virtual void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const; - virtual void paintItemBody(QPainter *painter, const QRect rect , const QxtStyleOptionScheduleViewItem & option , const ItemPart part, const QModelIndex & index) const; - virtual void paintItemHeader(QPainter *painter, const QRect rect , const QxtStyleOptionScheduleViewItem & option , const QModelIndex & index) const; - virtual void paintSubItem(QPainter *painter, const QRect rect , const QxtStyleOptionScheduleViewItem & option , const QModelIndex & index) const; - virtual QSize sizeHint(const QStyleOptionViewItem & option , const QModelIndex & index) const; - virtual void createPainterPath(QPainterPath &emptyPath, const QRect &fullItemRect , const int iRoundTop, const int iRoundBottom) const; - - -}; - -#endif // QXTSCHEDULEITEMDELEGATE_H_INCLUDED +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#ifndef QXTSCHEDULEITEMDELEGATE_H_INCLUDED +#define QXTSCHEDULEITEMDELEGATE_H_INCLUDED + +#include +#include +#include "qxtstyleoptionscheduleviewitem.h" +#include "qxtglobal.h" + +QT_FORWARD_DECLARE_CLASS(QPainter) + +/*! + @author Benjamin Zeller +*/ +class QXT_GUI_EXPORT QxtScheduleItemDelegate : public QAbstractItemDelegate +{ + Q_OBJECT +public: + + enum ItemPart + { + Top, + Middle, + Bottom, + Single + + }; + + QxtScheduleItemDelegate(QObject *parent = 0); + ~QxtScheduleItemDelegate(); + + virtual void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const; + virtual void paintItemBody(QPainter *painter, const QRect rect , const QxtStyleOptionScheduleViewItem & option , const ItemPart part, const QModelIndex & index) const; + virtual void paintItemHeader(QPainter *painter, const QRect rect , const QxtStyleOptionScheduleViewItem & option , const QModelIndex & index) const; + virtual void paintSubItem(QPainter *painter, const QRect rect , const QxtStyleOptionScheduleViewItem & option , const QModelIndex & index) const; + virtual QSize sizeHint(const QStyleOptionViewItem & option , const QModelIndex & index) const; + virtual void createPainterPath(QPainterPath &emptyPath, const QRect &fullItemRect , const int iRoundTop, const int iRoundBottom) const; + + +}; + +#endif // QXTSCHEDULEITEMDELEGATE_H_INCLUDED diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview.cpp index ddee54c45..0b5d13ce6 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview.cpp @@ -1,947 +1,947 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ - -#include "qxtscheduleview.h" -#include "qxtscheduleview_p.h" -#include "qxtscheduleheaderwidget.h" -#include "qxtscheduleviewheadermodel_p.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -/*! - \class QxtScheduleView QxtScheduleView - \inmodule QxtGui - \brief The QxtScheduleView class provides an iCal like view to plan events - - QxtScheduleView is a item based View,inspired by iCal, that makes it possible to visualize event planning. - - \raw HTML - It's time based and can show the events in different modes: -
    -
  • DayMode : Every column in the view shows one day
  • -
  • HourMode : Every column in the view shows one hour
  • -
  • MinuteMode : Every column in the view shows one minute
  • -
- In addition you can adjust how much time every cell represents in the view. The default value is 900 seconds - or 15 minutes and DayMode. - \endraw - - - \image qxtscheduleview.png QxtScheduleView - -*/ - -QxtScheduleView::QxtScheduleView(QWidget *parent) - : QAbstractScrollArea(parent) -{ - QXT_INIT_PRIVATE(QxtScheduleView); - - /*standart values are 15 minutes per cell and 69 rows == 1 Day*/ - qxt_d().m_currentZoomDepth = 15 * 60; - qxt_d().m_currentViewMode = DayView; - qxt_d().m_startUnixTime = QDateTime(QDate::currentDate(),QTime(0, 0, 0)).toTime_t(); - qxt_d().m_endUnixTime = QDateTime(QDate::currentDate().addDays(6),QTime(23, 59, 59)).toTime_t(); - qxt_d().delegate = qxt_d().defaultDelegate = new QxtScheduleItemDelegate(this); - -#if 0 - qxt_d().m_vHeader = new QxtScheduleHeaderWidget(Qt::Vertical, this); - connect(qxt_d().m_vHeader, SIGNAL(geometriesChanged()), this, SLOT(updateGeometries())); - qxt_d().m_vHeader->hide(); - - qxt_d().m_hHeader = new QxtScheduleHeaderWidget(Qt::Horizontal, this); - connect(qxt_d().m_hHeader, SIGNAL(geometriesChanged()), this, SLOT(updateGeometries())); - qxt_d().m_hHeader->hide(); -#else - //init will take care of initializing headers - qxt_d().m_vHeader = 0; - qxt_d().m_hHeader = 0; -#endif - -} - -/*! - * returns the vertial header - *\note can be NULL if the view has not called init() already (FIXME) - */ -QHeaderView* QxtScheduleView::verticalHeader ( ) const -{ - return qxt_d().m_vHeader; -} - -/** - * returns the horizontal header - *\note can be NULL if the view has not called init() already (FIXME) - */ -QHeaderView* QxtScheduleView::horizontalHeader ( ) const -{ - return qxt_d().m_hHeader; -} - -/** - * sets the model for QxtScheduleView - * - * \a model - */ -void QxtScheduleView::setModel(QAbstractItemModel *model) -{ - if (qxt_d().m_Model) - { - /*delete all cached items*/ - qDeleteAll(qxt_d().m_Items.begin(), qxt_d().m_Items.end()); - qxt_d().m_Items.clear(); - - /*disconnect all signals*/ - disconnect(qxt_d().m_Model, SIGNAL(dataChanged(const QModelIndex &, const QModelIndex &)), this, SLOT(dataChanged(const QModelIndex &, const QModelIndex &))); - disconnect(qxt_d().m_Model, SIGNAL(rowsAboutToBeInserted(const QModelIndex &, int, int)), this, SLOT(rowsAboutToBeInserted(const QModelIndex &, int , int))); - disconnect(qxt_d().m_Model, SIGNAL(rowsInserted(const QModelIndex &, int, int)), this, SLOT(rowsInserted(const QModelIndex &, int , int))); - disconnect(qxt_d().m_Model, SIGNAL(rowsAboutToBeRemoved(const QModelIndex &, int, int)), this, SLOT(rowsAboutToBeRemoved(const QModelIndex &, int , int))); - disconnect(qxt_d().m_Model, SIGNAL(rowsRemoved(const QModelIndex &, int, int)), this, SLOT(rowsRemoved(const QModelIndex &, int , int))); - - /*don't delete the model maybe someone else will use it*/ - qxt_d().m_Model = 0; - } - - if (model != 0) - { - /*initialize the new model*/ - qxt_d().m_Model = model; - connect(model, SIGNAL(dataChanged(const QModelIndex &, const QModelIndex &)), this, SLOT(dataChanged(const QModelIndex &, const QModelIndex &))); - connect(model, SIGNAL(rowsAboutToBeInserted(const QModelIndex &, int, int)), this, SLOT(rowsAboutToBeInserted(const QModelIndex &, int , int))); - connect(model, SIGNAL(rowsInserted(const QModelIndex &, int, int)), this, SLOT(rowsInserted(const QModelIndex &, int , int))); - connect(model, SIGNAL(rowsAboutToBeRemoved(const QModelIndex &, int, int)), this, SLOT(rowsAboutToBeRemoved(const QModelIndex &, int , int))); - connect(model, SIGNAL(rowsRemoved(const QModelIndex &, int, int)), this, SLOT(rowsRemoved(const QModelIndex &, int , int))); - } - qxt_d().init(); -} - -QAbstractItemModel * QxtScheduleView::model() const -{ - return qxt_d().m_Model; -} - -/*! - * changes the current ViewMode - * The QxtScheduleView supports some different viewmodes. A viewmode defines how much time a column holds. - * It is also possible to define custom viewmodes. To do that you have to set the currentView mode to Custom and - * reimplement timePerColumn - * - * \a QxtScheduleView::ViewMode mode the new ViewMode - * - * \sa timePerColumn() - * \sa viewMode() - */ -void QxtScheduleView::setViewMode(const QxtScheduleView::ViewMode mode) -{ - qxt_d().m_currentViewMode = mode; - - //this will calculate the correct alignment - //\BUG this may not work because the currentZoomDepth may not fit into the new viewMode - setCurrentZoomDepth(qxt_d().m_currentZoomDepth); -} - -/*! - *\\esc returns the current used delegate - */ -QxtScheduleItemDelegate* QxtScheduleView::delegate () const -{ - return qxt_d().delegate; -} - -/*! - *Sets the item delegate for this view and its model to delegate. This is useful if you want complete control over the editing and display of items. -*Any existing delegate will be removed, but not deleted. QxtScheduleView does not take ownership of delegate. -*Passing a 0 pointer will restore the view to use the default delegate. -*\Warning You should not share the same instance of a delegate between views. Doing so can cause incorrect or unintuitive behavior. - */ -void QxtScheduleView::setItemDelegate (QxtScheduleItemDelegate * delegate) -{ - if(!delegate) - qxt_d().delegate = qxt_d().defaultDelegate; - else - qxt_d().delegate = delegate; - - //the delegate changed repaint everything - viewport()->update(); -} - -/*! - * returns the current ViewMode - * - * Returns QxtScheduleView::ViewMode - * \sa setViewMode() - */ -QxtScheduleView::ViewMode QxtScheduleView::viewMode() const -{ - return (ViewMode)qxt_d().m_currentViewMode; -} - -/*! - * changes the current Zoom step width - * Changes the current Zoom step width. Zooming in QxtScheduleView means to change the amount - * of time one cell holds. For example 5 Minutes. The zoom step width defines how many time - * is added / removed from the cell when zooming the view. - * - * \a int zoomWidth the new zoom step width - * \a Qxt::Timeunit unit the unit of the new step width (Minutes , Seconds , Hours) - * - * \sa zoomIn() zoomOut() setCurrentZoomDepth() - */ -void QxtScheduleView::setZoomStepWidth(const int zoomWidth , const Qxt::Timeunit unit) -{ - switch (unit) - { - case Qxt::Second: - { - qxt_d().m_zoomStepWidth = zoomWidth; - } - break; - case Qxt::Minute: - { - qxt_d().m_zoomStepWidth = zoomWidth * 60; - } - break; - case Qxt::Hour: - { - qxt_d().m_zoomStepWidth = zoomWidth * 60 * 60; - } - break; - default: - qWarning() << "This Timeunit is not implemented yet you can use Second,Minute,Hour using standart 15 minutes"; - qxt_d().m_zoomStepWidth = 900; - break; - } -} - -/*! - * changes the current zoom depth - * The current zoom depth in QxtScheduleView defines how many time one cell holds in the view. - * If the new depth does not fit in the view the next possible value is used. If no possible value can be found - * nothing changes. - * Normally this is used only to initialize the view, later you want to use zoomIn and zoomOut - * - * \a int depth - * \a Qxt::Timeunit unit - * - * \sa zoomIn() zoomOut() setCurrentZoomDepth() - */ -void QxtScheduleView::setCurrentZoomDepth(const int depth , const Qxt::Timeunit unit) -{ - int newZoomDepth = 900; - - //a zoom depth of 0 is invalid - if (depth == 0) - return; - - switch (unit) - { - case Qxt::Second: - { - newZoomDepth = depth; - } - break; - case Qxt::Minute: - { - newZoomDepth = depth * 60; - } - break; - case Qxt::Hour: - { - newZoomDepth = depth * 60 * 60; - } - break; - default: - qWarning() << "This Timeunit is not implemented yet you can use Second,Minute,Hour using standart 15 minutes"; - break; - } - - //now we have to align the currentZoomDepth to the viewMode - int timePerCol = timePerColumn(); - - newZoomDepth = newZoomDepth > timePerCol ? timePerCol : newZoomDepth; - newZoomDepth = newZoomDepth <= 0 ? 1 : newZoomDepth; - - while (timePerCol % newZoomDepth) - { - if (depth > qxt_d().m_currentZoomDepth) - { - newZoomDepth++; - if (newZoomDepth >= timePerCol) - return; - } - - else - { - newZoomDepth--; - if (newZoomDepth <= 1) - return; - } - } - - qDebug() << "Zoomed, old zoom depth: " << qxt_d().m_currentZoomDepth << " new zoom depth: " << newZoomDepth; - - qxt_d().m_currentZoomDepth = newZoomDepth; - emit this->newZoomDepth(newZoomDepth); - - /*reinit the view*/ - if (model()) - { - updateGeometries(); - qxt_d().reloadItemsFromModel(); - } -} - -/*! - * returns the current zoom depth - */ -int QxtScheduleView::currentZoomDepth(const Qxt::Timeunit unit) -{ - switch (unit) - { - case Qxt::Second: - { - return qxt_d().m_currentZoomDepth; - } - break; - case Qxt::Minute: - { - return qxt_d().m_currentZoomDepth / 60; - } - break; - case Qxt::Hour: - { - return qxt_d().m_currentZoomDepth / 60 / 60; - } - break; - default: - qWarning() << "This Timeunit is not implemented yet you can use Second,Minute,Hour returning seconds"; - return qxt_d().m_currentZoomDepth; - break; - } -} - -/*! - * zooms one step in - * - * \sa zoomOut() setCurrentZoomDepth() setZoomStepWidth() - */ -void QxtScheduleView::zoomIn() -{ - setCurrentZoomDepth(qxt_d().m_currentZoomDepth - qxt_d().m_zoomStepWidth); -} - -/*! - * zooms one step out - * - * \sa zoomIn() setCurrentZoomDepth() setZoomStepWidth() - */ -void QxtScheduleView::zoomOut() -{ - setCurrentZoomDepth(qxt_d().m_currentZoomDepth + qxt_d().m_zoomStepWidth); -} - -void QxtScheduleView::paintEvent(QPaintEvent * /*event*/) -{ - if (model()) - { - /*paint the grid*/ - - int iNumRows = qxt_d().m_vHeader->count(); - qDebug() << "Painting rows " << iNumRows; - - int xRowEnd = qxt_d().m_hHeader->sectionViewportPosition(qxt_d().m_hHeader->count() - 1) + qxt_d().m_hHeader->sectionSize(qxt_d().m_hHeader->count() - 1); - QPainter painter(viewport()); - - - painter.save(); - painter.setPen(QColor(220, 220, 220)); - - bool thinLine; - thinLine = false; - for (int iLoop = 0; iLoop < iNumRows; iLoop += 2) - { - painter.drawLine(0 , qxt_d().m_vHeader->sectionViewportPosition(iLoop), xRowEnd, qxt_d().m_vHeader->sectionViewportPosition(iLoop)); - } - - int iNumCols = qxt_d().m_hHeader->count(); - int iYColEnd = qxt_d().m_vHeader->sectionViewportPosition(qxt_d().m_vHeader->count() - 1) + qxt_d().m_vHeader->sectionSize(qxt_d().m_vHeader->count() - 1); - - for (int iLoop = 0; iLoop < iNumCols ; iLoop++) - { - painter.drawLine(qxt_d().m_hHeader->sectionViewportPosition(iLoop), 0, qxt_d().m_hHeader->sectionViewportPosition(iLoop), iYColEnd); - } - - painter.restore(); - - QListIterator itemIterator(qxt_d().m_Items); - while (itemIterator.hasNext()) - { - QxtScheduleInternalItem * currItem = itemIterator.next(); - QxtStyleOptionScheduleViewItem style; - - //\BUG use the correct section here or find a way to forbit section resizing - style.roundCornersRadius = qxt_d().m_vHeader->sectionSize(1) / 2; - style.itemHeaderHeight = qxt_d().m_vHeader->sectionSize(1); - style.maxSubItemHeight = qxt_d().m_vHeader->sectionSize(1); - - if (currItem->isDirty) - currItem->m_cachedParts.clear(); - - style.itemGeometries = currItem->m_geometries; - style.itemPaintCache = &currItem->m_cachedParts; - style.translate = QPoint(-qxt_d().m_hHeader->offset(), -qxt_d().m_vHeader->offset()); - painter.save(); - qxt_d().delegate->paint(&painter, style, currItem->modelIndex()); - painter.restore(); - currItem->setDirty(false); - } - - painter.end(); - } -} - -void QxtScheduleView::updateGeometries() -{ - //check if we are already initialized - if(!qxt_d().m_Model || !qxt_d().m_vHeader || !qxt_d().m_hHeader) - return; - - this->setViewportMargins(qxt_d().m_vHeader->sizeHint().width() + 1, qxt_d().m_hHeader->sizeHint().height() + 1, 0, 0); - - - verticalScrollBar()->setRange(0, qxt_d().m_vHeader->count()*qxt_d().m_vHeader->defaultSectionSize() - viewport()->height()); - verticalScrollBar()->setSingleStep(qxt_d().m_vHeader->defaultSectionSize()); - verticalScrollBar()->setPageStep(qxt_d().m_vHeader->defaultSectionSize()); - - int left = 2; - int top = qxt_d().m_hHeader->sizeHint().height() + 2; - int width = qxt_d().m_vHeader->sizeHint().width(); - int height = viewport()->height(); - qxt_d().m_vHeader->setGeometry(left, top, width, height); - - left = left + width; - top = 1; - width = viewport()->width(); - height = qxt_d().m_hHeader->sizeHint().height(); - - qxt_d().m_hHeader->setGeometry(left, top, width, height); - qxt_d().m_hHeader->setDefaultSectionSize(viewport()->width() / 5); - - for (int iLoop = 0; iLoop < qxt_d().m_hHeader->count(); iLoop++) - qxt_d().m_hHeader->resizeSection(iLoop, viewport()->width() / 5); - qxt_d().m_hHeader->setResizeMode(QHeaderView::Fixed); - - - horizontalScrollBar()->setRange(0, (qxt_d().m_hHeader->count() * qxt_d().m_hHeader->defaultSectionSize() - viewport()->width())); - horizontalScrollBar()->setSingleStep(qxt_d().m_hHeader->defaultSectionSize()); - horizontalScrollBar()->setPageStep(qxt_d().m_hHeader->defaultSectionSize()); - - - qxt_d().m_vHeader->show(); - qxt_d().m_hHeader->show(); - qxt_d().handleItemConcurrency(0, this->rows() * this->cols() - 1); - viewport()->update(); -} - -void QxtScheduleView::scrollContentsBy(int dx, int dy) -{ - qxt_d().m_vHeader->setOffset(qxt_d().m_vHeader->offset() - dy); - qxt_d().m_hHeader->setOffset(qxt_d().m_hHeader->offset() - dx); - QAbstractScrollArea::scrollContentsBy(dx, dy); -} - -void QxtScheduleView::mouseMoveEvent(QMouseEvent * e) -{ - if (qxt_d().m_selectedItem) - { - int currentMousePosTableOffset = qxt_d().pointToOffset((e->pos())); - - if (currentMousePosTableOffset != qxt_d().m_lastMousePosOffset) - { - if (currentMousePosTableOffset >= 0) - { - /*i cannot use the model data here because all changes are committed to the model only when the move ends*/ - int startTableOffset = qxt_d().m_selectedItem->visualStartTableOffset(); - int endTableOffset = -1; - - /*i simply use the shape to check if we have a move or a resize. Because we enter this codepath the shape gets not changed*/ - if (this->viewport()->cursor().shape() == Qt::SizeVerCursor) - { - QVector geo = qxt_d().m_selectedItem->geometry(); - QRect rect = geo[geo.size()-1]; - endTableOffset = currentMousePosTableOffset; - } - else - { - /*well the duration is the same for a move*/ - //qint32 difference = qxt_d().rowsTo(qxt_d().m_lastMousePosIndex,currentMousePos); // tableCellToUnixTime(currentMousePos) - tableCellToUnixTime(this->m_lastMousePosIndex); - int difference = currentMousePosTableOffset - qxt_d().m_lastMousePosOffset; - //qDebug()<<"Difference Rows: "<rows() - 1; - } - if (startTableOffset >= 0 && endTableOffset >= startTableOffset && endTableOffset < (rows()*cols())) - { - QVector< QRect > newGeometry = qxt_d().calculateRangeGeometries(startTableOffset, endTableOffset); - - int oldStartOffset = qxt_d().m_selectedItem->visualStartTableOffset(); - int newStartOffset = qxt_d().m_selectedItem->visualEndTableOffset(); - - qxt_d().m_selectedItem->setGeometry(newGeometry); - qxt_d().m_selectedItem->setDirty(); - qxt_d().m_lastMousePosOffset = currentMousePosTableOffset; -#if 1 - if (newGeometry.size() > 0) - { - int start = qxt_d().m_selectedItem->visualStartTableOffset(); - int end = qxt_d().m_selectedItem->visualEndTableOffset(); - qxt_d().handleItemConcurrency(oldStartOffset, newStartOffset); - qxt_d().handleItemConcurrency(start, end); - } -#endif - - } - } - } - return; - } - else - { - /*change the cursor to show the resize arrow*/ - QPoint translatedPos = mapFromViewport(e->pos()); - QxtScheduleInternalItem * it = qxt_d().internalItemAt(translatedPos); - if (it) - { - QVector geo = it->geometry(); - QRect rect = geo[geo.size()-1]; - if (rect.contains(translatedPos) && (translatedPos.y() >= rect.bottom() - 5 && translatedPos.y() <= rect.bottom())) - { - this->viewport()->setCursor(Qt::SizeVerCursor); - return; - } - } - - if (this->viewport()->cursor().shape() != Qt::ArrowCursor) - this->viewport()->setCursor(Qt::ArrowCursor); - } -} - -void QxtScheduleView::mouseDoubleClickEvent ( QMouseEvent * e ) -{ - qxt_d().m_currentItem = qxt_d().internalItemAt(mapFromViewport(e->pos())); - if (qxt_d().m_currentItem) - { - emit indexDoubleClicked(qxt_d().m_currentItem->modelIndex()); - } -} - -void QxtScheduleView::mousePressEvent(QMouseEvent * e) -{ - qxt_d().m_currentItem = qxt_d().internalItemAt(mapFromViewport(e->pos())); - - if (qxt_d().m_currentItem) - { - emit indexSelected(qxt_d().m_currentItem->modelIndex()); - } - else - emit indexSelected(QModelIndex()); - - if (e->button() == Qt::RightButton) - { - if (qxt_d().m_currentItem) - emit contextMenuRequested(qxt_d().m_currentItem->modelIndex()); - } - else - { - qxt_d().m_lastMousePosOffset = qxt_d().pointToOffset(e->pos()); - if (qxt_d().m_lastMousePosOffset >= 0) - { - qxt_d().m_selectedItem = qxt_d().m_currentItem; - - - if (qxt_d().m_selectedItem) - { - qDebug() << "Selected Item:" << qxt_d().m_selectedItem->m_iModelRow; - raiseItem(qxt_d().m_selectedItem->modelIndex()); - qxt_d().m_selectedItem->startMove(); - qxt_d().scrollTimer.start(100); - } - else - qxt_d().m_lastMousePosOffset = -1; - } - } - - -} - -void QxtScheduleView::mouseReleaseEvent(QMouseEvent * /*e*/) -{ - qxt_d().scrollTimer.stop(); - if (qxt_d().m_selectedItem) - { - int oldStartTableOffset = qxt_d().m_selectedItem->startTableOffset(); - int oldEndTableOffset = oldStartTableOffset + qxt_d().m_selectedItem->rows() - 1 ; - - - QVector geo = qxt_d().m_selectedItem->geometry(); - QRect rect = geo[geo.size()-1]; - - int newStartTableOffset = qxt_d().m_selectedItem->visualStartTableOffset(); - int newEndTableOffset = qxt_d().m_selectedItem->visualEndTableOffset(); - - qxt_d().m_selectedItem->stopMove(); - - QVariant newStartUnixTime; - QVariant newDuration; - - newStartUnixTime = qxt_d().offsetToUnixTime(newStartTableOffset); - model()->setData(qxt_d().m_selectedItem->modelIndex(), newStartUnixTime, Qxt::ItemStartTimeRole); - newDuration = qxt_d().offsetToUnixTime(newEndTableOffset, true) - newStartUnixTime.toInt(); - model()->setData(qxt_d().m_selectedItem->modelIndex(), newDuration, Qxt::ItemDurationRole); - - qxt_d().m_selectedItem = NULL; - qxt_d().m_lastMousePosOffset = -1; - - /*only call for the old geometry the dataChanged slot will call it for the new position*/ - qxt_d().handleItemConcurrency(oldStartTableOffset, oldEndTableOffset); - //qxt_d().handleItemConcurrency(newStartIndex,newEndIndex); - - //viewport()->update(); - - } -} - -void QxtScheduleView::wheelEvent(QWheelEvent * e) -{ - /*time scrolling when pressing ctrl while using the mouse wheel*/ - if (e->modifiers() & Qt::ControlModifier) - { - if (e->delta() < 0) - zoomOut(); - else - zoomIn(); - - } - else - QAbstractScrollArea::wheelEvent(e); -} - -/*! - * returns the current row count of the view - */ -int QxtScheduleView::rows() const -{ - if (!model()) - return 0; - - int timePerCol = timePerColumn(); - - Q_ASSERT(timePerCol % qxt_d().m_currentZoomDepth == 0); - int iNeededRows = timePerCol / qxt_d().m_currentZoomDepth; - - return iNeededRows; - -} - -/*! - * returns the current column count of the view - */ -int QxtScheduleView::cols() const -{ - if (!model()) - return 0; - - int cols = 0; - int timeToShow = qxt_d().m_endUnixTime - qxt_d().m_startUnixTime + 1 ; - int timePerCol = timePerColumn(); - - Q_ASSERT(timeToShow % timePerCol == 0); - cols = (timeToShow / timePerCol); - - return cols; -} - -/*! - * reimplement this to support custom view modes - *Returns the time per column in seconds - */ -int QxtScheduleView::timePerColumn() const -{ - int timePerColumn = 0; - - switch (qxt_d().m_currentViewMode) - { - case DayView: - timePerColumn = 24 * 60 * 60; - break; - case HourView: - timePerColumn = 60 * 60; - break; - case MinuteView: - timePerColumn = 60; - break; - default: - Q_ASSERT(false); - } - - return timePerColumn; -} - -/*! - * reimplement this to support custom view modes - * This function has to adjust the given start and end time to the current view mode: - * For example, the DayMode always adjust to time 0:00:00am for startTime and 11:59:59pm for endTime - */ -void QxtScheduleView::adjustRangeToViewMode(QDateTime *startTime, QDateTime *endTime) const -{ - switch (qxt_d().m_currentViewMode) - { - case DayView: - startTime->setTime(QTime(0, 0)); - endTime ->setTime(QTime(23, 59, 59)); - break; - case HourView: - startTime->setTime(QTime(startTime->time().hour(), 0)); - endTime ->setTime(QTime(endTime->time().hour(), 59, 59)); - break; - case MinuteView: - startTime->setTime(QTime(startTime->time().hour(), startTime->time().minute(), 0)); - endTime ->setTime(QTime(endTime->time().hour(), endTime->time().minute(), 59)); - break; - default: - Q_ASSERT(false); - } -} - -QPoint QxtScheduleView::mapFromViewport(const QPoint & point) const -{ - return point + QPoint(qxt_d().m_hHeader->offset(), qxt_d().m_vHeader->offset()); -} - -QPoint QxtScheduleView::mapToViewport(const QPoint & point) const -{ - return point - QPoint(qxt_d().m_hHeader->offset(), qxt_d().m_vHeader->offset()); -} - -/*! - * raises the item belonging to index - */ -void QxtScheduleView::raiseItem(const QModelIndex &index) -{ - QxtScheduleInternalItem *item = qxt_d().itemForModelIndex(index); - if (item) - { - int iItemIndex = -1; - if ((iItemIndex = qxt_d().m_Items.indexOf(item)) >= 0) - { - qxt_d().m_Items.takeAt(iItemIndex); - qxt_d().m_Items.append(item); - viewport()->update(); - } - } -} - -void QxtScheduleView::dataChanged(const QModelIndex & topLeft, const QModelIndex & bottomRight) -{ - for (int iLoop = topLeft.row(); iLoop <= bottomRight.row();iLoop++) - { - QModelIndex index = model()->index(iLoop, 0); - QxtScheduleInternalItem * item = qxt_d().itemForModelIndex(index); - if (item) - { - int startOffset = item->startTableOffset(); - int endIndex = item->startTableOffset() + item->rows() - 1; - - if (item->m_geometries.count() > 0) - { - int oldStartOffset = qxt_d().pointToOffset(mapToViewport(item->m_geometries[0].topLeft())); - int oldEndOffset = qxt_d().pointToOffset(mapToViewport(item->m_geometries[item->m_geometries.size()-1].bottomRight())); - qxt_d().handleItemConcurrency(oldStartOffset, oldEndOffset); - } - - /*that maybe will set a empty geometry thats okay because the item maybe out of bounds of the view */ - item->setGeometry(qxt_d().calculateRangeGeometries(startOffset, endIndex)); - /*force item cache update even if the geometry is the same*/ - item->setDirty(); - - qxt_d().handleItemConcurrency(startOffset, endIndex); - - - viewport()->update(); - } - } -} - -/*! - * triggers the view to relayout the items that are concurrent to index - */ -void QxtScheduleView::handleItemConcurrency(const QModelIndex &index) -{ - QxtScheduleInternalItem *item = qxt_d().itemForModelIndex(index); - if (item) - qxt_d().handleItemConcurrency(item); -} - - -void QxtScheduleView::resizeEvent(QResizeEvent * /* e*/) -{ - updateGeometries(); -} - - -void QxtScheduleView::rowsRemoved(const QModelIndex & parent, int start, int end) -{ - /*! - *\FIXME write correct code here - */ - return qxt_d().reloadItemsFromModel(); - /*for now we care only about toplevel items*/ - if (!parent.isValid()) - { - for (int iLoop = 0; iLoop < qxt_d().m_Items.count();iLoop++) - { - QxtScheduleInternalItem *item = qxt_d().m_Items.at(iLoop); - if (item) - { - if (item->m_iModelRow >= start && item->m_iModelRow <= end) - { - qxt_d().m_Items.takeAt(iLoop); - if (item == qxt_d().m_currentItem) - { - qxt_d().m_currentItem = 0; - emit indexSelected(QModelIndex()); - } - delete item; - continue; - } - if (item->m_iModelRow > end) - { - int iDifference = end - start + 1; - item->m_iModelRow -= iDifference; - } - } - } - } -} - -void QxtScheduleView::rowsInserted(const QModelIndex & parent, int start, int end) -{ - /*for now we care only about toplevel items*/ - if (!parent.isValid()) - { - for (int iLoop = start; iLoop <= end;iLoop++) - { - /*now create the items*/ - QxtScheduleInternalItem *currentItem = new QxtScheduleInternalItem(this, model()->index(iLoop, 0)); - qxt_d().m_Items.append(currentItem); - connect(currentItem, SIGNAL(geometryChanged(QxtScheduleInternalItem*, QVector)), &qxt_d(), SLOT(itemGeometryChanged(QxtScheduleInternalItem * , QVector< QRect >))); - qxt_d().handleItemConcurrency(currentItem); - } - } - - viewport()->update(); -} - -void QxtScheduleView::rowsAboutToBeRemoved(const QModelIndex & parent, int start, int end) -{ - Q_UNUSED(parent); - Q_UNUSED(start); - Q_UNUSED(end); - /*for now we care only about toplevel items*/ - return; -} - -void QxtScheduleView::rowsAboutToBeInserted(const QModelIndex & parent, int start, int end) -{ - /*for now we care only about toplevel items*/ - if (!parent.isValid()) - { - int iDifference = end - start; - for (int iLoop = 0; iLoop < qxt_d().m_Items.count();iLoop++) - { - QxtScheduleInternalItem * item = qxt_d().m_Items[iLoop]; - if (item) - if (item->m_iModelRow >= start && item->m_iModelRow < model()->rowCount()) - item->m_iModelRow += iDifference + 1; - } - } -} - -/*! - * returns the current selected index - */ -QModelIndex QxtScheduleView::currentIndex() -{ - QModelIndex currIndex; - if (qxt_d().m_currentItem) - currIndex = qxt_d().m_currentItem->modelIndex(); - return currIndex; - -} - -/*! - * sets the timerange - * This function will set a Timerange from fromDate 00:00am to toDate 23:59pm - */ -void QxtScheduleView::setDateRange(const QDate & fromDate, const QDate & toDate) -{ - Q_UNUSED(fromDate); - Q_UNUSED(toDate); - - QDateTime startTime = QDateTime(fromDate, QTime(0, 0, 0)); - QDateTime endTime = QDateTime(toDate, QTime(23, 59, 59)); - setTimeRange(startTime, endTime); -} - -/*! - * sets the timerange - * This function will set the passed timerange, but may adjust it to the current viewmode. - * e.g You cannot start at 1:30am in a DayMode, this gets adjusted to 00:00am - */ -void QxtScheduleView::setTimeRange(const QDateTime & fromDateTime, const QDateTime & toDateTime) -{ - QDateTime startTime = fromDateTime; - QDateTime endTime = toDateTime; - - //adjust the timeranges to fit in the view - adjustRangeToViewMode(&startTime, &endTime); - qxt_d().m_startUnixTime = startTime.toTime_t(); - qxt_d().m_endUnixTime = endTime.toTime_t(); -} - - - - +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ + +#include "qxtscheduleview.h" +#include "qxtscheduleview_p.h" +#include "qxtscheduleheaderwidget.h" +#include "qxtscheduleviewheadermodel_p.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +/*! + \class QxtScheduleView QxtScheduleView + \inmodule QxtGui + \brief The QxtScheduleView class provides an iCal like view to plan events + + QxtScheduleView is a item based View,inspired by iCal, that makes it possible to visualize event planning. + + \raw HTML + It's time based and can show the events in different modes: +
    +
  • DayMode : Every column in the view shows one day
  • +
  • HourMode : Every column in the view shows one hour
  • +
  • MinuteMode : Every column in the view shows one minute
  • +
+ In addition you can adjust how much time every cell represents in the view. The default value is 900 seconds + or 15 minutes and DayMode. + \endraw + + + \image qxtscheduleview.png QxtScheduleView + +*/ + +QxtScheduleView::QxtScheduleView(QWidget *parent) + : QAbstractScrollArea(parent) +{ + QXT_INIT_PRIVATE(QxtScheduleView); + + /*standart values are 15 minutes per cell and 69 rows == 1 Day*/ + qxt_d().m_currentZoomDepth = 15 * 60; + qxt_d().m_currentViewMode = DayView; + qxt_d().m_startUnixTime = QDateTime(QDate::currentDate(),QTime(0, 0, 0)).toTime_t(); + qxt_d().m_endUnixTime = QDateTime(QDate::currentDate().addDays(6),QTime(23, 59, 59)).toTime_t(); + qxt_d().delegate = qxt_d().defaultDelegate = new QxtScheduleItemDelegate(this); + +#if 0 + qxt_d().m_vHeader = new QxtScheduleHeaderWidget(Qt::Vertical, this); + connect(qxt_d().m_vHeader, SIGNAL(geometriesChanged()), this, SLOT(updateGeometries())); + qxt_d().m_vHeader->hide(); + + qxt_d().m_hHeader = new QxtScheduleHeaderWidget(Qt::Horizontal, this); + connect(qxt_d().m_hHeader, SIGNAL(geometriesChanged()), this, SLOT(updateGeometries())); + qxt_d().m_hHeader->hide(); +#else + //init will take care of initializing headers + qxt_d().m_vHeader = 0; + qxt_d().m_hHeader = 0; +#endif + +} + +/*! + * returns the vertial header + *\note can be NULL if the view has not called init() already (FIXME) + */ +QHeaderView* QxtScheduleView::verticalHeader ( ) const +{ + return qxt_d().m_vHeader; +} + +/** + * returns the horizontal header + *\note can be NULL if the view has not called init() already (FIXME) + */ +QHeaderView* QxtScheduleView::horizontalHeader ( ) const +{ + return qxt_d().m_hHeader; +} + +/** + * sets the model for QxtScheduleView + * + * \a model + */ +void QxtScheduleView::setModel(QAbstractItemModel *model) +{ + if (qxt_d().m_Model) + { + /*delete all cached items*/ + qDeleteAll(qxt_d().m_Items.begin(), qxt_d().m_Items.end()); + qxt_d().m_Items.clear(); + + /*disconnect all signals*/ + disconnect(qxt_d().m_Model, SIGNAL(dataChanged(const QModelIndex &, const QModelIndex &)), this, SLOT(dataChanged(const QModelIndex &, const QModelIndex &))); + disconnect(qxt_d().m_Model, SIGNAL(rowsAboutToBeInserted(const QModelIndex &, int, int)), this, SLOT(rowsAboutToBeInserted(const QModelIndex &, int , int))); + disconnect(qxt_d().m_Model, SIGNAL(rowsInserted(const QModelIndex &, int, int)), this, SLOT(rowsInserted(const QModelIndex &, int , int))); + disconnect(qxt_d().m_Model, SIGNAL(rowsAboutToBeRemoved(const QModelIndex &, int, int)), this, SLOT(rowsAboutToBeRemoved(const QModelIndex &, int , int))); + disconnect(qxt_d().m_Model, SIGNAL(rowsRemoved(const QModelIndex &, int, int)), this, SLOT(rowsRemoved(const QModelIndex &, int , int))); + + /*don't delete the model maybe someone else will use it*/ + qxt_d().m_Model = 0; + } + + if (model != 0) + { + /*initialize the new model*/ + qxt_d().m_Model = model; + connect(model, SIGNAL(dataChanged(const QModelIndex &, const QModelIndex &)), this, SLOT(dataChanged(const QModelIndex &, const QModelIndex &))); + connect(model, SIGNAL(rowsAboutToBeInserted(const QModelIndex &, int, int)), this, SLOT(rowsAboutToBeInserted(const QModelIndex &, int , int))); + connect(model, SIGNAL(rowsInserted(const QModelIndex &, int, int)), this, SLOT(rowsInserted(const QModelIndex &, int , int))); + connect(model, SIGNAL(rowsAboutToBeRemoved(const QModelIndex &, int, int)), this, SLOT(rowsAboutToBeRemoved(const QModelIndex &, int , int))); + connect(model, SIGNAL(rowsRemoved(const QModelIndex &, int, int)), this, SLOT(rowsRemoved(const QModelIndex &, int , int))); + } + qxt_d().init(); +} + +QAbstractItemModel * QxtScheduleView::model() const +{ + return qxt_d().m_Model; +} + +/*! + * changes the current ViewMode + * The QxtScheduleView supports some different viewmodes. A viewmode defines how much time a column holds. + * It is also possible to define custom viewmodes. To do that you have to set the currentView mode to Custom and + * reimplement timePerColumn + * + * \a QxtScheduleView::ViewMode mode the new ViewMode + * + * \sa timePerColumn() + * \sa viewMode() + */ +void QxtScheduleView::setViewMode(const QxtScheduleView::ViewMode mode) +{ + qxt_d().m_currentViewMode = mode; + + //this will calculate the correct alignment + //\BUG this may not work because the currentZoomDepth may not fit into the new viewMode + setCurrentZoomDepth(qxt_d().m_currentZoomDepth); +} + +/*! + *\\esc returns the current used delegate + */ +QxtScheduleItemDelegate* QxtScheduleView::delegate () const +{ + return qxt_d().delegate; +} + +/*! + *Sets the item delegate for this view and its model to delegate. This is useful if you want complete control over the editing and display of items. +*Any existing delegate will be removed, but not deleted. QxtScheduleView does not take ownership of delegate. +*Passing a 0 pointer will restore the view to use the default delegate. +*\Warning You should not share the same instance of a delegate between views. Doing so can cause incorrect or unintuitive behavior. + */ +void QxtScheduleView::setItemDelegate (QxtScheduleItemDelegate * delegate) +{ + if(!delegate) + qxt_d().delegate = qxt_d().defaultDelegate; + else + qxt_d().delegate = delegate; + + //the delegate changed repaint everything + viewport()->update(); +} + +/*! + * returns the current ViewMode + * + * Returns QxtScheduleView::ViewMode + * \sa setViewMode() + */ +QxtScheduleView::ViewMode QxtScheduleView::viewMode() const +{ + return (ViewMode)qxt_d().m_currentViewMode; +} + +/*! + * changes the current Zoom step width + * Changes the current Zoom step width. Zooming in QxtScheduleView means to change the amount + * of time one cell holds. For example 5 Minutes. The zoom step width defines how many time + * is added / removed from the cell when zooming the view. + * + * \a int zoomWidth the new zoom step width + * \a Qxt::Timeunit unit the unit of the new step width (Minutes , Seconds , Hours) + * + * \sa zoomIn() zoomOut() setCurrentZoomDepth() + */ +void QxtScheduleView::setZoomStepWidth(const int zoomWidth , const Qxt::Timeunit unit) +{ + switch (unit) + { + case Qxt::Second: + { + qxt_d().m_zoomStepWidth = zoomWidth; + } + break; + case Qxt::Minute: + { + qxt_d().m_zoomStepWidth = zoomWidth * 60; + } + break; + case Qxt::Hour: + { + qxt_d().m_zoomStepWidth = zoomWidth * 60 * 60; + } + break; + default: + qWarning() << "This Timeunit is not implemented yet you can use Second,Minute,Hour using standart 15 minutes"; + qxt_d().m_zoomStepWidth = 900; + break; + } +} + +/*! + * changes the current zoom depth + * The current zoom depth in QxtScheduleView defines how many time one cell holds in the view. + * If the new depth does not fit in the view the next possible value is used. If no possible value can be found + * nothing changes. + * Normally this is used only to initialize the view, later you want to use zoomIn and zoomOut + * + * \a int depth + * \a Qxt::Timeunit unit + * + * \sa zoomIn() zoomOut() setCurrentZoomDepth() + */ +void QxtScheduleView::setCurrentZoomDepth(const int depth , const Qxt::Timeunit unit) +{ + int newZoomDepth = 900; + + //a zoom depth of 0 is invalid + if (depth == 0) + return; + + switch (unit) + { + case Qxt::Second: + { + newZoomDepth = depth; + } + break; + case Qxt::Minute: + { + newZoomDepth = depth * 60; + } + break; + case Qxt::Hour: + { + newZoomDepth = depth * 60 * 60; + } + break; + default: + qWarning() << "This Timeunit is not implemented yet you can use Second,Minute,Hour using standart 15 minutes"; + break; + } + + //now we have to align the currentZoomDepth to the viewMode + int timePerCol = timePerColumn(); + + newZoomDepth = newZoomDepth > timePerCol ? timePerCol : newZoomDepth; + newZoomDepth = newZoomDepth <= 0 ? 1 : newZoomDepth; + + while (timePerCol % newZoomDepth) + { + if (depth > qxt_d().m_currentZoomDepth) + { + newZoomDepth++; + if (newZoomDepth >= timePerCol) + return; + } + + else + { + newZoomDepth--; + if (newZoomDepth <= 1) + return; + } + } + + qDebug() << "Zoomed, old zoom depth: " << qxt_d().m_currentZoomDepth << " new zoom depth: " << newZoomDepth; + + qxt_d().m_currentZoomDepth = newZoomDepth; + emit this->newZoomDepth(newZoomDepth); + + /*reinit the view*/ + if (model()) + { + updateGeometries(); + qxt_d().reloadItemsFromModel(); + } +} + +/*! + * returns the current zoom depth + */ +int QxtScheduleView::currentZoomDepth(const Qxt::Timeunit unit) +{ + switch (unit) + { + case Qxt::Second: + { + return qxt_d().m_currentZoomDepth; + } + break; + case Qxt::Minute: + { + return qxt_d().m_currentZoomDepth / 60; + } + break; + case Qxt::Hour: + { + return qxt_d().m_currentZoomDepth / 60 / 60; + } + break; + default: + qWarning() << "This Timeunit is not implemented yet you can use Second,Minute,Hour returning seconds"; + return qxt_d().m_currentZoomDepth; + break; + } +} + +/*! + * zooms one step in + * + * \sa zoomOut() setCurrentZoomDepth() setZoomStepWidth() + */ +void QxtScheduleView::zoomIn() +{ + setCurrentZoomDepth(qxt_d().m_currentZoomDepth - qxt_d().m_zoomStepWidth); +} + +/*! + * zooms one step out + * + * \sa zoomIn() setCurrentZoomDepth() setZoomStepWidth() + */ +void QxtScheduleView::zoomOut() +{ + setCurrentZoomDepth(qxt_d().m_currentZoomDepth + qxt_d().m_zoomStepWidth); +} + +void QxtScheduleView::paintEvent(QPaintEvent * /*event*/) +{ + if (model()) + { + /*paint the grid*/ + + int iNumRows = qxt_d().m_vHeader->count(); + qDebug() << "Painting rows " << iNumRows; + + int xRowEnd = qxt_d().m_hHeader->sectionViewportPosition(qxt_d().m_hHeader->count() - 1) + qxt_d().m_hHeader->sectionSize(qxt_d().m_hHeader->count() - 1); + QPainter painter(viewport()); + + + painter.save(); + painter.setPen(QColor(220, 220, 220)); + + bool thinLine; + thinLine = false; + for (int iLoop = 0; iLoop < iNumRows; iLoop += 2) + { + painter.drawLine(0 , qxt_d().m_vHeader->sectionViewportPosition(iLoop), xRowEnd, qxt_d().m_vHeader->sectionViewportPosition(iLoop)); + } + + int iNumCols = qxt_d().m_hHeader->count(); + int iYColEnd = qxt_d().m_vHeader->sectionViewportPosition(qxt_d().m_vHeader->count() - 1) + qxt_d().m_vHeader->sectionSize(qxt_d().m_vHeader->count() - 1); + + for (int iLoop = 0; iLoop < iNumCols ; iLoop++) + { + painter.drawLine(qxt_d().m_hHeader->sectionViewportPosition(iLoop), 0, qxt_d().m_hHeader->sectionViewportPosition(iLoop), iYColEnd); + } + + painter.restore(); + + QListIterator itemIterator(qxt_d().m_Items); + while (itemIterator.hasNext()) + { + QxtScheduleInternalItem * currItem = itemIterator.next(); + QxtStyleOptionScheduleViewItem style; + + //\BUG use the correct section here or find a way to forbit section resizing + style.roundCornersRadius = qxt_d().m_vHeader->sectionSize(1) / 2; + style.itemHeaderHeight = qxt_d().m_vHeader->sectionSize(1); + style.maxSubItemHeight = qxt_d().m_vHeader->sectionSize(1); + + if (currItem->isDirty) + currItem->m_cachedParts.clear(); + + style.itemGeometries = currItem->m_geometries; + style.itemPaintCache = &currItem->m_cachedParts; + style.translate = QPoint(-qxt_d().m_hHeader->offset(), -qxt_d().m_vHeader->offset()); + painter.save(); + qxt_d().delegate->paint(&painter, style, currItem->modelIndex()); + painter.restore(); + currItem->setDirty(false); + } + + painter.end(); + } +} + +void QxtScheduleView::updateGeometries() +{ + //check if we are already initialized + if(!qxt_d().m_Model || !qxt_d().m_vHeader || !qxt_d().m_hHeader) + return; + + this->setViewportMargins(qxt_d().m_vHeader->sizeHint().width() + 1, qxt_d().m_hHeader->sizeHint().height() + 1, 0, 0); + + + verticalScrollBar()->setRange(0, qxt_d().m_vHeader->count()*qxt_d().m_vHeader->defaultSectionSize() - viewport()->height()); + verticalScrollBar()->setSingleStep(qxt_d().m_vHeader->defaultSectionSize()); + verticalScrollBar()->setPageStep(qxt_d().m_vHeader->defaultSectionSize()); + + int left = 2; + int top = qxt_d().m_hHeader->sizeHint().height() + 2; + int width = qxt_d().m_vHeader->sizeHint().width(); + int height = viewport()->height(); + qxt_d().m_vHeader->setGeometry(left, top, width, height); + + left = left + width; + top = 1; + width = viewport()->width(); + height = qxt_d().m_hHeader->sizeHint().height(); + + qxt_d().m_hHeader->setGeometry(left, top, width, height); + qxt_d().m_hHeader->setDefaultSectionSize(viewport()->width() / 5); + + for (int iLoop = 0; iLoop < qxt_d().m_hHeader->count(); iLoop++) + qxt_d().m_hHeader->resizeSection(iLoop, viewport()->width() / 5); + qxt_d().m_hHeader->setResizeMode(QHeaderView::Fixed); + + + horizontalScrollBar()->setRange(0, (qxt_d().m_hHeader->count() * qxt_d().m_hHeader->defaultSectionSize() - viewport()->width())); + horizontalScrollBar()->setSingleStep(qxt_d().m_hHeader->defaultSectionSize()); + horizontalScrollBar()->setPageStep(qxt_d().m_hHeader->defaultSectionSize()); + + + qxt_d().m_vHeader->show(); + qxt_d().m_hHeader->show(); + qxt_d().handleItemConcurrency(0, this->rows() * this->cols() - 1); + viewport()->update(); +} + +void QxtScheduleView::scrollContentsBy(int dx, int dy) +{ + qxt_d().m_vHeader->setOffset(qxt_d().m_vHeader->offset() - dy); + qxt_d().m_hHeader->setOffset(qxt_d().m_hHeader->offset() - dx); + QAbstractScrollArea::scrollContentsBy(dx, dy); +} + +void QxtScheduleView::mouseMoveEvent(QMouseEvent * e) +{ + if (qxt_d().m_selectedItem) + { + int currentMousePosTableOffset = qxt_d().pointToOffset((e->pos())); + + if (currentMousePosTableOffset != qxt_d().m_lastMousePosOffset) + { + if (currentMousePosTableOffset >= 0) + { + /*i cannot use the model data here because all changes are committed to the model only when the move ends*/ + int startTableOffset = qxt_d().m_selectedItem->visualStartTableOffset(); + int endTableOffset = -1; + + /*i simply use the shape to check if we have a move or a resize. Because we enter this codepath the shape gets not changed*/ + if (this->viewport()->cursor().shape() == Qt::SizeVerCursor) + { + QVector geo = qxt_d().m_selectedItem->geometry(); + QRect rect = geo[geo.size()-1]; + endTableOffset = currentMousePosTableOffset; + } + else + { + /*well the duration is the same for a move*/ + //qint32 difference = qxt_d().rowsTo(qxt_d().m_lastMousePosIndex,currentMousePos); // tableCellToUnixTime(currentMousePos) - tableCellToUnixTime(this->m_lastMousePosIndex); + int difference = currentMousePosTableOffset - qxt_d().m_lastMousePosOffset; + //qDebug()<<"Difference Rows: "<rows() - 1; + } + if (startTableOffset >= 0 && endTableOffset >= startTableOffset && endTableOffset < (rows()*cols())) + { + QVector< QRect > newGeometry = qxt_d().calculateRangeGeometries(startTableOffset, endTableOffset); + + int oldStartOffset = qxt_d().m_selectedItem->visualStartTableOffset(); + int newStartOffset = qxt_d().m_selectedItem->visualEndTableOffset(); + + qxt_d().m_selectedItem->setGeometry(newGeometry); + qxt_d().m_selectedItem->setDirty(); + qxt_d().m_lastMousePosOffset = currentMousePosTableOffset; +#if 1 + if (newGeometry.size() > 0) + { + int start = qxt_d().m_selectedItem->visualStartTableOffset(); + int end = qxt_d().m_selectedItem->visualEndTableOffset(); + qxt_d().handleItemConcurrency(oldStartOffset, newStartOffset); + qxt_d().handleItemConcurrency(start, end); + } +#endif + + } + } + } + return; + } + else + { + /*change the cursor to show the resize arrow*/ + QPoint translatedPos = mapFromViewport(e->pos()); + QxtScheduleInternalItem * it = qxt_d().internalItemAt(translatedPos); + if (it) + { + QVector geo = it->geometry(); + QRect rect = geo[geo.size()-1]; + if (rect.contains(translatedPos) && (translatedPos.y() >= rect.bottom() - 5 && translatedPos.y() <= rect.bottom())) + { + this->viewport()->setCursor(Qt::SizeVerCursor); + return; + } + } + + if (this->viewport()->cursor().shape() != Qt::ArrowCursor) + this->viewport()->setCursor(Qt::ArrowCursor); + } +} + +void QxtScheduleView::mouseDoubleClickEvent ( QMouseEvent * e ) +{ + qxt_d().m_currentItem = qxt_d().internalItemAt(mapFromViewport(e->pos())); + if (qxt_d().m_currentItem) + { + emit indexDoubleClicked(qxt_d().m_currentItem->modelIndex()); + } +} + +void QxtScheduleView::mousePressEvent(QMouseEvent * e) +{ + qxt_d().m_currentItem = qxt_d().internalItemAt(mapFromViewport(e->pos())); + + if (qxt_d().m_currentItem) + { + emit indexSelected(qxt_d().m_currentItem->modelIndex()); + } + else + emit indexSelected(QModelIndex()); + + if (e->button() == Qt::RightButton) + { + if (qxt_d().m_currentItem) + emit contextMenuRequested(qxt_d().m_currentItem->modelIndex()); + } + else + { + qxt_d().m_lastMousePosOffset = qxt_d().pointToOffset(e->pos()); + if (qxt_d().m_lastMousePosOffset >= 0) + { + qxt_d().m_selectedItem = qxt_d().m_currentItem; + + + if (qxt_d().m_selectedItem) + { + qDebug() << "Selected Item:" << qxt_d().m_selectedItem->m_iModelRow; + raiseItem(qxt_d().m_selectedItem->modelIndex()); + qxt_d().m_selectedItem->startMove(); + qxt_d().scrollTimer.start(100); + } + else + qxt_d().m_lastMousePosOffset = -1; + } + } + + +} + +void QxtScheduleView::mouseReleaseEvent(QMouseEvent * /*e*/) +{ + qxt_d().scrollTimer.stop(); + if (qxt_d().m_selectedItem) + { + int oldStartTableOffset = qxt_d().m_selectedItem->startTableOffset(); + int oldEndTableOffset = oldStartTableOffset + qxt_d().m_selectedItem->rows() - 1 ; + + + QVector geo = qxt_d().m_selectedItem->geometry(); + QRect rect = geo[geo.size()-1]; + + int newStartTableOffset = qxt_d().m_selectedItem->visualStartTableOffset(); + int newEndTableOffset = qxt_d().m_selectedItem->visualEndTableOffset(); + + qxt_d().m_selectedItem->stopMove(); + + QVariant newStartUnixTime; + QVariant newDuration; + + newStartUnixTime = qxt_d().offsetToUnixTime(newStartTableOffset); + model()->setData(qxt_d().m_selectedItem->modelIndex(), newStartUnixTime, Qxt::ItemStartTimeRole); + newDuration = qxt_d().offsetToUnixTime(newEndTableOffset, true) - newStartUnixTime.toInt(); + model()->setData(qxt_d().m_selectedItem->modelIndex(), newDuration, Qxt::ItemDurationRole); + + qxt_d().m_selectedItem = NULL; + qxt_d().m_lastMousePosOffset = -1; + + /*only call for the old geometry the dataChanged slot will call it for the new position*/ + qxt_d().handleItemConcurrency(oldStartTableOffset, oldEndTableOffset); + //qxt_d().handleItemConcurrency(newStartIndex,newEndIndex); + + //viewport()->update(); + + } +} + +void QxtScheduleView::wheelEvent(QWheelEvent * e) +{ + /*time scrolling when pressing ctrl while using the mouse wheel*/ + if (e->modifiers() & Qt::ControlModifier) + { + if (e->delta() < 0) + zoomOut(); + else + zoomIn(); + + } + else + QAbstractScrollArea::wheelEvent(e); +} + +/*! + * returns the current row count of the view + */ +int QxtScheduleView::rows() const +{ + if (!model()) + return 0; + + int timePerCol = timePerColumn(); + + Q_ASSERT(timePerCol % qxt_d().m_currentZoomDepth == 0); + int iNeededRows = timePerCol / qxt_d().m_currentZoomDepth; + + return iNeededRows; + +} + +/*! + * returns the current column count of the view + */ +int QxtScheduleView::cols() const +{ + if (!model()) + return 0; + + int cols = 0; + int timeToShow = qxt_d().m_endUnixTime - qxt_d().m_startUnixTime + 1 ; + int timePerCol = timePerColumn(); + + Q_ASSERT(timeToShow % timePerCol == 0); + cols = (timeToShow / timePerCol); + + return cols; +} + +/*! + * reimplement this to support custom view modes + *Returns the time per column in seconds + */ +int QxtScheduleView::timePerColumn() const +{ + int timePerColumn = 0; + + switch (qxt_d().m_currentViewMode) + { + case DayView: + timePerColumn = 24 * 60 * 60; + break; + case HourView: + timePerColumn = 60 * 60; + break; + case MinuteView: + timePerColumn = 60; + break; + default: + Q_ASSERT(false); + } + + return timePerColumn; +} + +/*! + * reimplement this to support custom view modes + * This function has to adjust the given start and end time to the current view mode: + * For example, the DayMode always adjust to time 0:00:00am for startTime and 11:59:59pm for endTime + */ +void QxtScheduleView::adjustRangeToViewMode(QDateTime *startTime, QDateTime *endTime) const +{ + switch (qxt_d().m_currentViewMode) + { + case DayView: + startTime->setTime(QTime(0, 0)); + endTime ->setTime(QTime(23, 59, 59)); + break; + case HourView: + startTime->setTime(QTime(startTime->time().hour(), 0)); + endTime ->setTime(QTime(endTime->time().hour(), 59, 59)); + break; + case MinuteView: + startTime->setTime(QTime(startTime->time().hour(), startTime->time().minute(), 0)); + endTime ->setTime(QTime(endTime->time().hour(), endTime->time().minute(), 59)); + break; + default: + Q_ASSERT(false); + } +} + +QPoint QxtScheduleView::mapFromViewport(const QPoint & point) const +{ + return point + QPoint(qxt_d().m_hHeader->offset(), qxt_d().m_vHeader->offset()); +} + +QPoint QxtScheduleView::mapToViewport(const QPoint & point) const +{ + return point - QPoint(qxt_d().m_hHeader->offset(), qxt_d().m_vHeader->offset()); +} + +/*! + * raises the item belonging to index + */ +void QxtScheduleView::raiseItem(const QModelIndex &index) +{ + QxtScheduleInternalItem *item = qxt_d().itemForModelIndex(index); + if (item) + { + int iItemIndex = -1; + if ((iItemIndex = qxt_d().m_Items.indexOf(item)) >= 0) + { + qxt_d().m_Items.takeAt(iItemIndex); + qxt_d().m_Items.append(item); + viewport()->update(); + } + } +} + +void QxtScheduleView::dataChanged(const QModelIndex & topLeft, const QModelIndex & bottomRight) +{ + for (int iLoop = topLeft.row(); iLoop <= bottomRight.row();iLoop++) + { + QModelIndex index = model()->index(iLoop, 0); + QxtScheduleInternalItem * item = qxt_d().itemForModelIndex(index); + if (item) + { + int startOffset = item->startTableOffset(); + int endIndex = item->startTableOffset() + item->rows() - 1; + + if (item->m_geometries.count() > 0) + { + int oldStartOffset = qxt_d().pointToOffset(mapToViewport(item->m_geometries[0].topLeft())); + int oldEndOffset = qxt_d().pointToOffset(mapToViewport(item->m_geometries[item->m_geometries.size()-1].bottomRight())); + qxt_d().handleItemConcurrency(oldStartOffset, oldEndOffset); + } + + /*that maybe will set a empty geometry thats okay because the item maybe out of bounds of the view */ + item->setGeometry(qxt_d().calculateRangeGeometries(startOffset, endIndex)); + /*force item cache update even if the geometry is the same*/ + item->setDirty(); + + qxt_d().handleItemConcurrency(startOffset, endIndex); + + + viewport()->update(); + } + } +} + +/*! + * triggers the view to relayout the items that are concurrent to index + */ +void QxtScheduleView::handleItemConcurrency(const QModelIndex &index) +{ + QxtScheduleInternalItem *item = qxt_d().itemForModelIndex(index); + if (item) + qxt_d().handleItemConcurrency(item); +} + + +void QxtScheduleView::resizeEvent(QResizeEvent * /* e*/) +{ + updateGeometries(); +} + + +void QxtScheduleView::rowsRemoved(const QModelIndex & parent, int start, int end) +{ + /*! + *\FIXME write correct code here + */ + return qxt_d().reloadItemsFromModel(); + /*for now we care only about toplevel items*/ + if (!parent.isValid()) + { + for (int iLoop = 0; iLoop < qxt_d().m_Items.count();iLoop++) + { + QxtScheduleInternalItem *item = qxt_d().m_Items.at(iLoop); + if (item) + { + if (item->m_iModelRow >= start && item->m_iModelRow <= end) + { + qxt_d().m_Items.takeAt(iLoop); + if (item == qxt_d().m_currentItem) + { + qxt_d().m_currentItem = 0; + emit indexSelected(QModelIndex()); + } + delete item; + continue; + } + if (item->m_iModelRow > end) + { + int iDifference = end - start + 1; + item->m_iModelRow -= iDifference; + } + } + } + } +} + +void QxtScheduleView::rowsInserted(const QModelIndex & parent, int start, int end) +{ + /*for now we care only about toplevel items*/ + if (!parent.isValid()) + { + for (int iLoop = start; iLoop <= end;iLoop++) + { + /*now create the items*/ + QxtScheduleInternalItem *currentItem = new QxtScheduleInternalItem(this, model()->index(iLoop, 0)); + qxt_d().m_Items.append(currentItem); + connect(currentItem, SIGNAL(geometryChanged(QxtScheduleInternalItem*, QVector)), &qxt_d(), SLOT(itemGeometryChanged(QxtScheduleInternalItem * , QVector< QRect >))); + qxt_d().handleItemConcurrency(currentItem); + } + } + + viewport()->update(); +} + +void QxtScheduleView::rowsAboutToBeRemoved(const QModelIndex & parent, int start, int end) +{ + Q_UNUSED(parent); + Q_UNUSED(start); + Q_UNUSED(end); + /*for now we care only about toplevel items*/ + return; +} + +void QxtScheduleView::rowsAboutToBeInserted(const QModelIndex & parent, int start, int end) +{ + /*for now we care only about toplevel items*/ + if (!parent.isValid()) + { + int iDifference = end - start; + for (int iLoop = 0; iLoop < qxt_d().m_Items.count();iLoop++) + { + QxtScheduleInternalItem * item = qxt_d().m_Items[iLoop]; + if (item) + if (item->m_iModelRow >= start && item->m_iModelRow < model()->rowCount()) + item->m_iModelRow += iDifference + 1; + } + } +} + +/*! + * returns the current selected index + */ +QModelIndex QxtScheduleView::currentIndex() +{ + QModelIndex currIndex; + if (qxt_d().m_currentItem) + currIndex = qxt_d().m_currentItem->modelIndex(); + return currIndex; + +} + +/*! + * sets the timerange + * This function will set a Timerange from fromDate 00:00am to toDate 23:59pm + */ +void QxtScheduleView::setDateRange(const QDate & fromDate, const QDate & toDate) +{ + Q_UNUSED(fromDate); + Q_UNUSED(toDate); + + QDateTime startTime = QDateTime(fromDate, QTime(0, 0, 0)); + QDateTime endTime = QDateTime(toDate, QTime(23, 59, 59)); + setTimeRange(startTime, endTime); +} + +/*! + * sets the timerange + * This function will set the passed timerange, but may adjust it to the current viewmode. + * e.g You cannot start at 1:30am in a DayMode, this gets adjusted to 00:00am + */ +void QxtScheduleView::setTimeRange(const QDateTime & fromDateTime, const QDateTime & toDateTime) +{ + QDateTime startTime = fromDateTime; + QDateTime endTime = toDateTime; + + //adjust the timeranges to fit in the view + adjustRangeToViewMode(&startTime, &endTime); + qxt_d().m_startUnixTime = startTime.toTime_t(); + qxt_d().m_endUnixTime = endTime.toTime_t(); +} + + + + diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview.h index b9ef79fd0..50cb353c1 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview.h @@ -1,136 +1,136 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#ifndef QXTSCHEDULEVIEW_H_INCLUDED -#define QXTSCHEDULEVIEW_H_INCLUDED - -#include -#include -#include -#include -#include -#include - -#include "qxtglobal.h" -#include "qxtnamespace.h" - -QT_FORWARD_DECLARE_CLASS(QAbstractItemModel) -class QxtScheduleItemDelegate; -class QxtScheduleViewPrivate; -class QxtScheduleInternalItem; - -#if 0 -enum -{ - TIMERANGEPERCOL = 86400, - TIMESTEP = 900 -}; -#endif - - -class QXT_GUI_EXPORT QxtScheduleView : public QAbstractScrollArea -{ - Q_OBJECT - - QXT_DECLARE_PRIVATE(QxtScheduleView) - friend class QxtScheduleInternalItem; - friend class QxtScheduleViewHeaderModel; - -public: - - enum ViewMode - { - MinuteView, - HourView, - DayView, - CustomView - }; - - QxtScheduleView(QWidget *parent = 0); - - void setModel(QAbstractItemModel *model); - QAbstractItemModel* model() const; - - void setViewMode(const QxtScheduleView::ViewMode mode); - QxtScheduleView::ViewMode viewMode() const; - - QHeaderView* verticalHeader ( ) const; - QHeaderView* horizontalHeader ( ) const; - - void setDateRange(const QDate & fromDate , const QDate & toDate); - void setTimeRange(const QDateTime &fromDateTime , const QDateTime &toTime); - - QxtScheduleItemDelegate* delegate () const; - void setItemDelegate (QxtScheduleItemDelegate * delegate); - - void setZoomStepWidth(const int zoomWidth , const Qxt::Timeunit unit = Qxt::Second); - void setCurrentZoomDepth(const int depth , const Qxt::Timeunit unit = Qxt::Second); - int currentZoomDepth(const Qxt::Timeunit unit = Qxt::Second); - - QPoint mapFromViewport(const QPoint& point) const; - QPoint mapToViewport(const QPoint& point) const; - - QModelIndex indexAt(const QPoint &pt); - void raiseItem(const QModelIndex &index); - void handleItemConcurrency(const QModelIndex &index); - QModelIndex currentIndex(); - int rows() const; - int cols() const; - -Q_SIGNALS: - void itemMoved(int rows, int cols, QModelIndex index); - void indexSelected(QModelIndex index); - void indexDoubleClicked(QModelIndex index); - void contextMenuRequested(QModelIndex index); - void newZoomDepth(const int newDepthInSeconds); - void viewModeChanged(const int newViewMode); - - -protected: - virtual int timePerColumn() const; - virtual void adjustRangeToViewMode(QDateTime *startTime, QDateTime *endTime) const; - - virtual void scrollContentsBy(int dx, int dy); - virtual void paintEvent(QPaintEvent *e); - virtual void mouseMoveEvent(QMouseEvent * e); - virtual void mousePressEvent(QMouseEvent * e); - virtual void mouseReleaseEvent(QMouseEvent * e); - virtual void mouseDoubleClickEvent ( QMouseEvent * e ); - virtual void resizeEvent(QResizeEvent * e); - virtual void wheelEvent(QWheelEvent * e); - -public Q_SLOTS: - void dataChanged(const QModelIndex & topLeft, const QModelIndex & bottomRight); - void updateGeometries(); - void zoomIn(); - void zoomOut(); - -protected Q_SLOTS: - virtual void rowsAboutToBeRemoved(const QModelIndex & parent, int start, int end); - virtual void rowsAboutToBeInserted(const QModelIndex & parent, int start, int end); - virtual void rowsRemoved(const QModelIndex & parent, int start, int end); - virtual void rowsInserted(const QModelIndex & parent, int start, int end); -}; - -#endif //QXTSCHEDULEVIEW_H_INCLUDED +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#ifndef QXTSCHEDULEVIEW_H_INCLUDED +#define QXTSCHEDULEVIEW_H_INCLUDED + +#include +#include +#include +#include +#include +#include + +#include "qxtglobal.h" +#include "qxtnamespace.h" + +QT_FORWARD_DECLARE_CLASS(QAbstractItemModel) +class QxtScheduleItemDelegate; +class QxtScheduleViewPrivate; +class QxtScheduleInternalItem; + +#if 0 +enum +{ + TIMERANGEPERCOL = 86400, + TIMESTEP = 900 +}; +#endif + + +class QXT_GUI_EXPORT QxtScheduleView : public QAbstractScrollArea +{ + Q_OBJECT + + QXT_DECLARE_PRIVATE(QxtScheduleView) + friend class QxtScheduleInternalItem; + friend class QxtScheduleViewHeaderModel; + +public: + + enum ViewMode + { + MinuteView, + HourView, + DayView, + CustomView + }; + + QxtScheduleView(QWidget *parent = 0); + + void setModel(QAbstractItemModel *model); + QAbstractItemModel* model() const; + + void setViewMode(const QxtScheduleView::ViewMode mode); + QxtScheduleView::ViewMode viewMode() const; + + QHeaderView* verticalHeader ( ) const; + QHeaderView* horizontalHeader ( ) const; + + void setDateRange(const QDate & fromDate , const QDate & toDate); + void setTimeRange(const QDateTime &fromDateTime , const QDateTime &toTime); + + QxtScheduleItemDelegate* delegate () const; + void setItemDelegate (QxtScheduleItemDelegate * delegate); + + void setZoomStepWidth(const int zoomWidth , const Qxt::Timeunit unit = Qxt::Second); + void setCurrentZoomDepth(const int depth , const Qxt::Timeunit unit = Qxt::Second); + int currentZoomDepth(const Qxt::Timeunit unit = Qxt::Second); + + QPoint mapFromViewport(const QPoint& point) const; + QPoint mapToViewport(const QPoint& point) const; + + QModelIndex indexAt(const QPoint &pt); + void raiseItem(const QModelIndex &index); + void handleItemConcurrency(const QModelIndex &index); + QModelIndex currentIndex(); + int rows() const; + int cols() const; + +Q_SIGNALS: + void itemMoved(int rows, int cols, QModelIndex index); + void indexSelected(QModelIndex index); + void indexDoubleClicked(QModelIndex index); + void contextMenuRequested(QModelIndex index); + void newZoomDepth(const int newDepthInSeconds); + void viewModeChanged(const int newViewMode); + + +protected: + virtual int timePerColumn() const; + virtual void adjustRangeToViewMode(QDateTime *startTime, QDateTime *endTime) const; + + virtual void scrollContentsBy(int dx, int dy); + virtual void paintEvent(QPaintEvent *e); + virtual void mouseMoveEvent(QMouseEvent * e); + virtual void mousePressEvent(QMouseEvent * e); + virtual void mouseReleaseEvent(QMouseEvent * e); + virtual void mouseDoubleClickEvent ( QMouseEvent * e ); + virtual void resizeEvent(QResizeEvent * e); + virtual void wheelEvent(QWheelEvent * e); + +public Q_SLOTS: + void dataChanged(const QModelIndex & topLeft, const QModelIndex & bottomRight); + void updateGeometries(); + void zoomIn(); + void zoomOut(); + +protected Q_SLOTS: + virtual void rowsAboutToBeRemoved(const QModelIndex & parent, int start, int end); + virtual void rowsAboutToBeInserted(const QModelIndex & parent, int start, int end); + virtual void rowsRemoved(const QModelIndex & parent, int start, int end); + virtual void rowsInserted(const QModelIndex & parent, int start, int end); +}; + +#endif //QXTSCHEDULEVIEW_H_INCLUDED diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview_p.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview_p.cpp index d7d12c5a4..3478744d7 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview_p.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview_p.cpp @@ -1,762 +1,762 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ - -#include "qxtscheduleview_p.h" -#include "qxtscheduleview.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "qxtscheduleheaderwidget.h" - -/*-------------------------------------start private functions-------------------------------------------------------*/ - -int QxtScheduleViewPrivate::offsetToVisualColumn(const int iOffset) const -{ - if (iOffset >= 0) - return iOffset / qxt_p().rows(); - return -1; -} - -int QxtScheduleViewPrivate::visualIndexToOffset(const int iRow, const int iCol) const -{ - return (iCol* qxt_p().rows()) + iRow; -} - -int QxtScheduleViewPrivate::offsetToVisualRow(const int iOffset) const -{ - if (iOffset >= 0 && qxt_p().model()) - return iOffset % qxt_p().rows(); - return -1; -} - -QVector< QRect > QxtScheduleViewPrivate::calculateRangeGeometries(const int iStartOffset, const int iEndOffset) const -{ - QVector rects; - - if (iStartOffset < 0 || iEndOffset < 0) - return rects; - - if (iEndOffset < iStartOffset) - return rects; - - int iCurrentStartOffset = iStartOffset; - int iCurrentEndOffset; - - do - { - if (offsetToVisualColumn(iCurrentStartOffset) == offsetToVisualColumn(iEndOffset)) - iCurrentEndOffset = iEndOffset; - else - iCurrentEndOffset = visualIndexToOffset(m_vHeader->count() - 1, offsetToVisualColumn(iCurrentStartOffset)); - - qint32 iLeft = m_hHeader->sectionPosition(offsetToVisualColumn(iCurrentStartOffset)); - qint32 iTop = m_vHeader->sectionPosition(offsetToVisualRow(iCurrentStartOffset)); - qint32 iBottom = m_vHeader->sectionPosition(offsetToVisualRow(iCurrentEndOffset)) + m_vHeader->sectionSize(offsetToVisualRow(iCurrentEndOffset)); - qint32 iRight = m_hHeader->sectionPosition(offsetToVisualColumn(iCurrentEndOffset)) + m_hHeader->sectionSize(offsetToVisualColumn(iCurrentEndOffset)); - rects.append(QRect(iLeft + 1, iTop + 1, iRight - iLeft - 1, iBottom - iTop - 1)); - - iCurrentStartOffset = visualIndexToOffset(0, offsetToVisualColumn(iCurrentEndOffset) + 1); - - } - while (iCurrentEndOffset < iEndOffset); - - return rects; - -} - -int QxtScheduleViewPrivate::pointToOffset(const QPoint & point) -{ - int iRow = m_vHeader->visualIndexAt(point.y()); - int iCol = m_hHeader->visualIndexAt(point.x()); - return visualIndexToOffset(iRow, iCol); -} - - - -QxtScheduleInternalItem * QxtScheduleViewPrivate::internalItemAt(const QPoint & pt) -{ - QListIteratoriterator(m_Items); - QxtScheduleInternalItem *currentItem; - iterator.toBack(); - while (iterator.hasPrevious()) - { - currentItem = iterator.previous(); - if (currentItem->contains(pt)) - return currentItem; - } - return 0; -} - - -void QxtScheduleViewPrivate::reloadItemsFromModel() -{ - qDeleteAll(m_Items.begin(), m_Items.end()); - m_Items.clear(); - m_selectedItem = NULL; - - int iNumItems = qxt_p().model()->rowCount(); - //delete all old stuff here - QxtScheduleInternalItem *currentItem; - for (int iLoop = 0; iLoop < iNumItems; iLoop++) - { - currentItem = new QxtScheduleInternalItem(&qxt_p(), qxt_p().model()->index(iLoop, 0)); - m_Items.append(currentItem); - connect(currentItem, SIGNAL(geometryChanged(QxtScheduleInternalItem*, QVector)), this, SLOT(itemGeometryChanged(QxtScheduleInternalItem * , QVector< QRect >))); - } - - handleItemConcurrency(0, (qxt_p().rows()*qxt_p().cols()) - 1); -} - -void QxtScheduleViewPrivate::init() -{ - if (qxt_p().model()) - { - qxt_p().viewport()->setMouseTracking(true); - - if (!m_vHeader) - { - m_vHeader = new QxtScheduleHeaderWidget(Qt::Vertical, &qxt_p()); - connect(m_vHeader, SIGNAL(geometriesChanged()), &qxt_p(), SLOT(updateGeometries())); - } - m_vHeader->show(); - - if (!m_hHeader) - { - m_hHeader = new QxtScheduleHeaderWidget(Qt::Horizontal, &qxt_p()); - connect(m_hHeader, SIGNAL(geometriesChanged()), &qxt_p(), SLOT(updateGeometries())); - } - m_hHeader->show(); - - /*here we also initialize the items*/ - m_vHeader->setDefaultSectionSize(20); - m_vHeader->setResizeMode(QHeaderView::Fixed); - reloadItemsFromModel(); - } - qxt_p().updateGeometries(); -} - -/*! - * @desc collects groups of concurrent items in the offset range - */ -QList< QLinkedList > QxtScheduleViewPrivate::findConcurrentItems(const int from, const int to) const -{ - QList< QLinkedList > allConcurrentItems; - - QList allItemsSorted = m_Items; - - if(m_Items.size() == 0) - return allConcurrentItems; - - qSort(allItemsSorted.begin(), allItemsSorted.end(), qxtScheduleItemLessThan); - - int startItem = 0; - int endItem = allItemsSorted.size() - 1; - - //find the startitem that interferes with our range - for (int i = 0; i < allItemsSorted.size(); i++) - { - if (i > 0) - { - if (!(allItemsSorted.at(i - 1)->visualEndTableOffset() >= allItemsSorted.at(i)->visualStartTableOffset() - && allItemsSorted.at(i - 1)->visualStartTableOffset() <= allItemsSorted.at(i)->visualEndTableOffset())) - startItem = i; - } - - if (allItemsSorted.at(i)->visualEndTableOffset() >= from && allItemsSorted.at(i)->visualStartTableOffset() <= to) - break; - } - - //find the last item that interferes with our range - for (int i = allItemsSorted.size() - 1; i >= 0 ; i--) - { - if (i < allItemsSorted.size() - 1) - { - if (!(allItemsSorted.at(i + 1)->visualEndTableOffset() >= allItemsSorted.at(i)->visualStartTableOffset() - && allItemsSorted.at(i + 1)->visualStartTableOffset() <= allItemsSorted.at(i)->visualEndTableOffset())) - endItem = i; - } - - if (allItemsSorted.at(i)->visualEndTableOffset() >= from && allItemsSorted.at(i)->visualStartTableOffset() <= to) - break; - } - - int startOffset = allItemsSorted.at(startItem)->visualStartTableOffset(); - int endOffset = allItemsSorted.at(endItem)->visualEndTableOffset(); - - /*now we have to populate a list with all items that interfere with our range */ - QLinkedList concurrentItems; - for (int iAllItemLoop = startItem; iAllItemLoop <= endItem; iAllItemLoop++) - { - int tempStartOffset = allItemsSorted.at(iAllItemLoop)->visualStartTableOffset(); - int tempEndOffset = allItemsSorted.at(iAllItemLoop)->visualEndTableOffset(); - - if (tempEndOffset >= startOffset && tempStartOffset <= endOffset) - { - - if (concurrentItems.size() >= 1) - { - bool bAppend = false; - /*check all items in the list if the current items interfers although the items are ordered by startIndex - *we can loose some of them if the endTime of the last Item is before the endTime of the pre last item - */ - - for (QLinkedList::iterator it = concurrentItems.begin(); it != concurrentItems.end(); ++it) - { - int lastStartOffset = (*it)->visualStartTableOffset(); - int lastEndOffset = (*it)->visualEndTableOffset(); - - if (tempEndOffset >= lastStartOffset && tempStartOffset <= lastEndOffset) - { - bAppend = true; - break; - } - } - - if (bAppend) - { - concurrentItems.append(allItemsSorted.at(iAllItemLoop)); - } - else - { - allConcurrentItems.append(concurrentItems); - concurrentItems.clear(); - concurrentItems.append(allItemsSorted.at(iAllItemLoop)); - } - } - else - concurrentItems.append(allItemsSorted.at(iAllItemLoop)); - - if (tempStartOffset < startOffset) - startOffset = tempStartOffset; - - if (tempEndOffset > endOffset) - endOffset = tempEndOffset; - } - } - if (concurrentItems.size() > 0) - allConcurrentItems.append(concurrentItems); - - return allConcurrentItems; -} - -void QxtScheduleViewPrivate::handleItemConcurrency(const int from, const int to) -{ - /*collect all items that interfere only in that range*/ - if (from < 0 || to < 0 || m_Items.size() == 0){ - //do a update or we may have artifacts - qxt_p().viewport()->update(); - return; - } - - qDebug() << "handleItemConcurrency"; - - if (handlesConcurrency) - return; - - handlesConcurrency = true; - - QList< QLinkedList > allConcurrentItems = findConcurrentItems(from, to); - - /*thx to ahigerd for suggesting that algorithm*/ - //[16:24] Start with the first event. Put it in a list. - //[16:25] Iterate until you find an event that doesn't overlap with the first event. Put it in the list. Repeat until you've reached the last event. - //[16:25] This fills the left column optimally. - //[16:25] Repeat the algorithm for the second column, etc., until there aren't any events left that don't have a column. - //[16:27] This algorithm is O(n*m), where n is the number of events and m is the maximum number of overlapping events. - - QList< QList< QxtScheduleInternalItem *> >virtualTable; - - for (int iListLoop = 0; iListLoop < allConcurrentItems.size(); iListLoop++) - { - QLinkedList & currentItems = allConcurrentItems[iListLoop]; - QList< QxtScheduleInternalItem * > currentColumn; - - qDebug() << "handle overlapping for " << currentItems.size() << " Items"; - - virtualTable.clear(); - - //we iterate over the currect collection and remove every item that can be placed in the current column - //when the collection is empty we are done - while (currentItems.size()) - { - QMutableLinkedListIterator< QxtScheduleInternalItem * > iter(currentItems); - - while (iter.hasNext()) - { - iter.next(); - //initialize the current column - if (currentColumn.isEmpty() || currentColumn[currentColumn.size()-1]->visualEndTableOffset() < iter.value()->visualStartTableOffset()) - { - currentColumn.append(iter.value()); - iter.remove(); - continue; - } - } - - if (!currentColumn.isEmpty()) - { - virtualTable.append(currentColumn); - currentColumn.clear(); - } - } - - qDebug() << "Found columns" << virtualTable.size(); - - //this code part resizes the item geometries - for (int col = 0; col < virtualTable.size(); col++) - { - for (int item = 0; item < virtualTable.at(col).size() ; item++) - { - int startVisualCol = offsetToVisualColumn(virtualTable[col][item]->visualStartTableOffset()); - QVector geo = virtualTable[col][item]->geometry(); - - for (int rect = 0; rect < geo.size(); rect++) - { - int sectionStart = m_hHeader->sectionPosition(startVisualCol); - int fullWidth = m_hHeader->sectionSize(startVisualCol); - int oneItemWidth = fullWidth / virtualTable.size(); - int itemWidth = oneItemWidth; - int itemXStart = (col * oneItemWidth) + sectionStart; - int overlap = oneItemWidth / 10; - int adjustX1 = 0; - int adjustX2 = 0; - - //this is very expensive.I try to check if my item can span over more than one col - int possibleCols = 1; - bool foundCollision; - - for (int tmpCol = col + 1; tmpCol < virtualTable.size(); tmpCol++) - { - foundCollision = false; - for (int tmpItem = 0; tmpItem < virtualTable.at(tmpCol).size() ; tmpItem++) - { - if ((virtualTable[tmpCol][tmpItem]->visualEndTableOffset() >= virtualTable[col][item]->visualStartTableOffset() - && virtualTable[tmpCol][tmpItem]->visualStartTableOffset() <= virtualTable[col][item]->visualEndTableOffset())) - { - foundCollision = true; - break; - } - } - - if (!foundCollision) - possibleCols++; - else - break; - } - //now lets adjust the size to get a nice overlapping of items - if (virtualTable.size() > 1) - { - if (col == 0) - adjustX2 = overlap; - else if (col == virtualTable.size() - 1) - { - adjustX1 = -overlap; - adjustX2 = overlap; - } - else - { - if (col + possibleCols == virtualTable.size()) - adjustX2 = overlap; - else - adjustX2 = overlap * 2; - - adjustX1 = -overlap; - } - } - - // possibleCols = 1; - itemWidth = oneItemWidth * possibleCols; - - qDebug() << "orginial rect" << geo[rect]; - geo[rect].setLeft(itemXStart + adjustX1); - geo[rect].setWidth(itemWidth + adjustX2); - qDebug() << "new rect" << geo[rect]; - - - startVisualCol++; - } - virtualTable[col][item]->setGeometry(geo); - } - } - } - handlesConcurrency = false; - qxt_p().viewport()->update(); -} - -QxtScheduleViewPrivate::QxtScheduleViewPrivate() -{ - m_Cols = 0; - m_vHeader = 0; - m_hHeader = 0; - m_Model = 0; - m_selectedItem = 0; - handlesConcurrency = false; - delegate = 0; - m_zoomStepWidth = 0; - - connect(&scrollTimer, SIGNAL(timeout()), this, SLOT(scrollTimerTimeout())); -} - -void QxtScheduleViewPrivate::itemGeometryChanged(QxtScheduleInternalItem * item, QVector< QRect > oldGeometry) -{ - QRegion oldRegion; - - if (item->geometry() == oldGeometry) - return; - - QVectorIterator iter(oldGeometry); - QRect currRect; - while (iter.hasNext()) - { - currRect = iter.next(); - currRect.adjust(-1, -1, 2, 2); - oldRegion += currRect; - } - //viewport()->update(oldRegion); - - - QRegion newRegion; - QVectorIterator newIter(item->geometry()); - while (newIter.hasNext()) - { - currRect = newIter.next(); - currRect.adjust(-1, -1, 2, 2); - newRegion += currRect; - } - //viewport()->update(newRegion); - qxt_p().viewport()->update(); -} - -int QxtScheduleViewPrivate::unixTimeToOffset(const uint constUnixTime, bool indexEndTime) const -{ - uint unixTime = constUnixTime; - if (unixTime >= m_startUnixTime && unixTime <= m_endUnixTime) - { - if (indexEndTime) - { - unixTime -= m_currentZoomDepth; - } - qint32 rows = qxt_p().rows(); - qint32 iOffset = unixTime - m_startUnixTime; - - //round to the closest boundaries - iOffset = qRound((qreal)iOffset / (qreal)m_currentZoomDepth); - - qint32 iCol = iOffset / rows; - qint32 iRow = iOffset % rows; - return visualIndexToOffset(iRow, iCol); - } - //virtual void handleItemOverlapping(QxtScheduleInternalItem *item); - return -1; -} - -void QxtScheduleViewPrivate::scrollTimerTimeout() -{ - QPoint globalPos = QCursor::pos(); - QPoint viewportPos = qxt_p().viewport()->mapFromGlobal(globalPos); - - int iScrollVertical = this->m_vHeader->defaultSectionSize(); - int iScrollHorizontal = this->m_hHeader->defaultSectionSize(); - - if (viewportPos.y() <= iScrollVertical) - { - int iCurrPos = qxt_p().verticalScrollBar()->value(); - if (iCurrPos > qxt_p().verticalScrollBar()->minimum() + iScrollVertical) - { - qxt_p().verticalScrollBar()->setValue(iCurrPos - iScrollVertical); - } - else - qxt_p().verticalScrollBar()->setValue(qxt_p().verticalScrollBar()->minimum()); - - } - else if (viewportPos.y() >= qxt_p().viewport()->height() - iScrollVertical) - { - int iCurrPos = qxt_p().verticalScrollBar()->value(); - if (iCurrPos < qxt_p().verticalScrollBar()->maximum() - iScrollVertical) - { - qxt_p().verticalScrollBar()->setValue(iCurrPos + iScrollVertical); - } - else - qxt_p().verticalScrollBar()->setValue(qxt_p().verticalScrollBar()->maximum()); - } - - if (viewportPos.x() <= iScrollHorizontal / 2) - { - int iCurrPos = qxt_p().horizontalScrollBar()->value(); - if (iCurrPos > qxt_p().horizontalScrollBar()->minimum() + iScrollHorizontal) - { - qxt_p().horizontalScrollBar()->setValue(iCurrPos - iScrollHorizontal); - } - else - qxt_p().horizontalScrollBar()->setValue(qxt_p().horizontalScrollBar()->minimum()); - - } - else if (viewportPos.x() >= qxt_p().viewport()->width() - (iScrollHorizontal / 2)) - { - int iCurrPos = qxt_p().horizontalScrollBar()->value(); - if (iCurrPos < qxt_p().horizontalScrollBar()->maximum() - iScrollHorizontal) - { - qxt_p().horizontalScrollBar()->setValue(iCurrPos + iScrollHorizontal); - } - else - qxt_p().horizontalScrollBar()->setValue(qxt_p().horizontalScrollBar()->maximum()); - } - -} - -int QxtScheduleViewPrivate::offsetToUnixTime(const int offset, bool indexEndTime) const -{ - qint32 rows = qxt_p().rows(); - uint unixTime = (offsetToVisualRow(offset) + (offsetToVisualColumn(offset) * rows)) * m_currentZoomDepth; - unixTime += m_startUnixTime; - - if (indexEndTime) - { - unixTime += m_currentZoomDepth; - } - - if (unixTime >= m_startUnixTime && unixTime <= m_endUnixTime + 1) - return unixTime; - return -1; -} - - -QxtScheduleInternalItem::QxtScheduleInternalItem(QxtScheduleView *parent, QModelIndex index, QVector geometries) - : QObject(parent), m_iModelRow(index.row()), m_geometries(geometries) -{ - m_moving = false; - if (parent) - { - if (index.isValid()) - { - if (m_geometries.empty()) - { - int startOffset = this->startTableOffset(); - int endOffset = startOffset + this->rows() - 1; - m_geometries = parent->qxt_d().calculateRangeGeometries(startOffset, endOffset); - } - } - } -} - -QxtScheduleView * QxtScheduleInternalItem::parentView() const -{ - return qobject_cast(parent()); -} - -/*! - * @desc returns the currently VISUAL offset (changes when a item moves) - */ -int QxtScheduleInternalItem::visualStartTableOffset() const -{ - if (m_geometries.size() == 0 || !parentView()) - return -1; - - //are we in a move? - if (!m_moving) - return startTableOffset(); - - int offset = parentView()->qxt_d().pointToOffset(parentView()->mapToViewport((this->geometry()[0].topLeft()))); - return offset; -} - -/*! - * @desc returns the currently VISUAL offset (changes when a item moves) - */ -int QxtScheduleInternalItem::visualEndTableOffset() const -{ - if (m_geometries.size() == 0 || !parentView()) - return -1; - - //are we in a move? - if (!m_moving) - return endTableOffset(); - - QRect rect = m_geometries[m_geometries.size()-1]; - int endTableOffset = parentView()->qxt_d().pointToOffset(parentView()->mapToViewport(rect.bottomRight())); - return endTableOffset; -} - -bool QxtScheduleInternalItem::setData(QVariant data, int role) -{ - if (parentView() && parentView()->model()) - { - return parentView()->model()->setData(modelIndex(), data, role); - } - return false; -} - -QVariant QxtScheduleInternalItem::data(int role) const -{ - if (modelIndex().isValid()) - return modelIndex().data(role); - return QVariant(); -} - -int QxtScheduleInternalItem::startTableOffset() const -{ - if (parentView() && parentView()->model()) - { - int startTime = data(Qxt::ItemStartTimeRole).toInt(); - int zoomDepth = parentView()->currentZoomDepth(Qxt::Second); - - qint32 offset = startTime - parentView()->qxt_d().m_startUnixTime; - - //the start of the current item does not fit in the view - //so we have to align it to the nearest boundaries - if (offset % zoomDepth) - { - int lower = offset / zoomDepth * zoomDepth; - int upper = lower + zoomDepth; - - offset = (offset - lower >= upper - offset ? upper : lower); - - return parentView()->qxt_d().unixTimeToOffset(offset + parentView()->qxt_d().m_startUnixTime); - } - - return parentView()->qxt_d().unixTimeToOffset(startTime); - } - return -1; -} - -int QxtScheduleInternalItem::endTableOffset() const -{ - return startTableOffset() + rows() - 1; -} - -void QxtScheduleInternalItem::setStartTableOffset(int iOffset) -{ - if (parentView() && parentView()->model()) - { - setData(parentView()->qxt_d().offsetToUnixTime(iOffset), Qxt::ItemStartTimeRole); - } -} - -void QxtScheduleInternalItem::setRowsUsed(int rows) -{ - if (parentView() && parentView()->model()) - { - int seconds = rows * parentView()->currentZoomDepth(Qxt::Second); - setData(seconds, Qxt::ItemDurationRole); - } -} - -int QxtScheduleInternalItem::rows() const -{ - if (parentView() && parentView()->model()) - { - int iNumSecs = data(Qxt::ItemDurationRole).toInt(); - int zoomDepth = parentView()->currentZoomDepth(Qxt::Second); - - //the length of the current item does not fit in the view - //so we have to align it to the nearest boundaries - if (iNumSecs % zoomDepth) - { - int lower = iNumSecs / zoomDepth * zoomDepth; - int upper = lower + zoomDepth; - - return (iNumSecs - lower >= upper - iNumSecs ? (upper / zoomDepth) : (lower / zoomDepth)); - - } - return (iNumSecs / zoomDepth); - } - return -1; -} - -bool qxtScheduleItemLessThan(const QxtScheduleInternalItem * item1, const QxtScheduleInternalItem * item2) -{ - if (item1->visualStartTableOffset() < item2->visualStartTableOffset()) - return true; - if (item1->visualStartTableOffset() == item2->visualStartTableOffset() && item1->modelIndex().row() < item2->modelIndex().row()) - return true; - return false; -} - -bool QxtScheduleInternalItem::contains(const QPoint & pt) -{ - QVectorIterator iterator(this->m_geometries); - while (iterator.hasNext()) - { - if (iterator.next().contains(pt)) - return true; - } - return false; -} - -void QxtScheduleInternalItem::setGeometry(const QVector< QRect > geo) -{ - if (!this->parent()) - return; - - QVector oldGeo = this->m_geometries; - this->m_geometries.clear(); - this->m_geometries = geo; - emit geometryChanged(this, oldGeo); -} - -QVector< QRect > QxtScheduleInternalItem::geometry() const -{ - return this->m_geometries; -} - -void QxtScheduleInternalItem::startMove() -{ - //save old geometry before we start to move - this->m_SavedGeometries = this->m_geometries; - m_moving = true; -} - -void QxtScheduleInternalItem::resetMove() -{ - this->setGeometry(this->m_SavedGeometries); - this->m_SavedGeometries.clear(); - m_moving = false; -} - -void QxtScheduleInternalItem::stopMove() -{ - this->m_SavedGeometries.clear(); - m_moving = false; -} - -QModelIndex QxtScheduleInternalItem::modelIndex() const -{ - QModelIndex indx; - if (parentView() && parentView()->model()) - { - indx = parentView()->model()->index(this->m_iModelRow, 0); - } - return indx; -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ + +#include "qxtscheduleview_p.h" +#include "qxtscheduleview.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "qxtscheduleheaderwidget.h" + +/*-------------------------------------start private functions-------------------------------------------------------*/ + +int QxtScheduleViewPrivate::offsetToVisualColumn(const int iOffset) const +{ + if (iOffset >= 0) + return iOffset / qxt_p().rows(); + return -1; +} + +int QxtScheduleViewPrivate::visualIndexToOffset(const int iRow, const int iCol) const +{ + return (iCol* qxt_p().rows()) + iRow; +} + +int QxtScheduleViewPrivate::offsetToVisualRow(const int iOffset) const +{ + if (iOffset >= 0 && qxt_p().model()) + return iOffset % qxt_p().rows(); + return -1; +} + +QVector< QRect > QxtScheduleViewPrivate::calculateRangeGeometries(const int iStartOffset, const int iEndOffset) const +{ + QVector rects; + + if (iStartOffset < 0 || iEndOffset < 0) + return rects; + + if (iEndOffset < iStartOffset) + return rects; + + int iCurrentStartOffset = iStartOffset; + int iCurrentEndOffset; + + do + { + if (offsetToVisualColumn(iCurrentStartOffset) == offsetToVisualColumn(iEndOffset)) + iCurrentEndOffset = iEndOffset; + else + iCurrentEndOffset = visualIndexToOffset(m_vHeader->count() - 1, offsetToVisualColumn(iCurrentStartOffset)); + + qint32 iLeft = m_hHeader->sectionPosition(offsetToVisualColumn(iCurrentStartOffset)); + qint32 iTop = m_vHeader->sectionPosition(offsetToVisualRow(iCurrentStartOffset)); + qint32 iBottom = m_vHeader->sectionPosition(offsetToVisualRow(iCurrentEndOffset)) + m_vHeader->sectionSize(offsetToVisualRow(iCurrentEndOffset)); + qint32 iRight = m_hHeader->sectionPosition(offsetToVisualColumn(iCurrentEndOffset)) + m_hHeader->sectionSize(offsetToVisualColumn(iCurrentEndOffset)); + rects.append(QRect(iLeft + 1, iTop + 1, iRight - iLeft - 1, iBottom - iTop - 1)); + + iCurrentStartOffset = visualIndexToOffset(0, offsetToVisualColumn(iCurrentEndOffset) + 1); + + } + while (iCurrentEndOffset < iEndOffset); + + return rects; + +} + +int QxtScheduleViewPrivate::pointToOffset(const QPoint & point) +{ + int iRow = m_vHeader->visualIndexAt(point.y()); + int iCol = m_hHeader->visualIndexAt(point.x()); + return visualIndexToOffset(iRow, iCol); +} + + + +QxtScheduleInternalItem * QxtScheduleViewPrivate::internalItemAt(const QPoint & pt) +{ + QListIteratoriterator(m_Items); + QxtScheduleInternalItem *currentItem; + iterator.toBack(); + while (iterator.hasPrevious()) + { + currentItem = iterator.previous(); + if (currentItem->contains(pt)) + return currentItem; + } + return 0; +} + + +void QxtScheduleViewPrivate::reloadItemsFromModel() +{ + qDeleteAll(m_Items.begin(), m_Items.end()); + m_Items.clear(); + m_selectedItem = NULL; + + int iNumItems = qxt_p().model()->rowCount(); + //delete all old stuff here + QxtScheduleInternalItem *currentItem; + for (int iLoop = 0; iLoop < iNumItems; iLoop++) + { + currentItem = new QxtScheduleInternalItem(&qxt_p(), qxt_p().model()->index(iLoop, 0)); + m_Items.append(currentItem); + connect(currentItem, SIGNAL(geometryChanged(QxtScheduleInternalItem*, QVector)), this, SLOT(itemGeometryChanged(QxtScheduleInternalItem * , QVector< QRect >))); + } + + handleItemConcurrency(0, (qxt_p().rows()*qxt_p().cols()) - 1); +} + +void QxtScheduleViewPrivate::init() +{ + if (qxt_p().model()) + { + qxt_p().viewport()->setMouseTracking(true); + + if (!m_vHeader) + { + m_vHeader = new QxtScheduleHeaderWidget(Qt::Vertical, &qxt_p()); + connect(m_vHeader, SIGNAL(geometriesChanged()), &qxt_p(), SLOT(updateGeometries())); + } + m_vHeader->show(); + + if (!m_hHeader) + { + m_hHeader = new QxtScheduleHeaderWidget(Qt::Horizontal, &qxt_p()); + connect(m_hHeader, SIGNAL(geometriesChanged()), &qxt_p(), SLOT(updateGeometries())); + } + m_hHeader->show(); + + /*here we also initialize the items*/ + m_vHeader->setDefaultSectionSize(20); + m_vHeader->setResizeMode(QHeaderView::Fixed); + reloadItemsFromModel(); + } + qxt_p().updateGeometries(); +} + +/*! + * @desc collects groups of concurrent items in the offset range + */ +QList< QLinkedList > QxtScheduleViewPrivate::findConcurrentItems(const int from, const int to) const +{ + QList< QLinkedList > allConcurrentItems; + + QList allItemsSorted = m_Items; + + if(m_Items.size() == 0) + return allConcurrentItems; + + qSort(allItemsSorted.begin(), allItemsSorted.end(), qxtScheduleItemLessThan); + + int startItem = 0; + int endItem = allItemsSorted.size() - 1; + + //find the startitem that interferes with our range + for (int i = 0; i < allItemsSorted.size(); i++) + { + if (i > 0) + { + if (!(allItemsSorted.at(i - 1)->visualEndTableOffset() >= allItemsSorted.at(i)->visualStartTableOffset() + && allItemsSorted.at(i - 1)->visualStartTableOffset() <= allItemsSorted.at(i)->visualEndTableOffset())) + startItem = i; + } + + if (allItemsSorted.at(i)->visualEndTableOffset() >= from && allItemsSorted.at(i)->visualStartTableOffset() <= to) + break; + } + + //find the last item that interferes with our range + for (int i = allItemsSorted.size() - 1; i >= 0 ; i--) + { + if (i < allItemsSorted.size() - 1) + { + if (!(allItemsSorted.at(i + 1)->visualEndTableOffset() >= allItemsSorted.at(i)->visualStartTableOffset() + && allItemsSorted.at(i + 1)->visualStartTableOffset() <= allItemsSorted.at(i)->visualEndTableOffset())) + endItem = i; + } + + if (allItemsSorted.at(i)->visualEndTableOffset() >= from && allItemsSorted.at(i)->visualStartTableOffset() <= to) + break; + } + + int startOffset = allItemsSorted.at(startItem)->visualStartTableOffset(); + int endOffset = allItemsSorted.at(endItem)->visualEndTableOffset(); + + /*now we have to populate a list with all items that interfere with our range */ + QLinkedList concurrentItems; + for (int iAllItemLoop = startItem; iAllItemLoop <= endItem; iAllItemLoop++) + { + int tempStartOffset = allItemsSorted.at(iAllItemLoop)->visualStartTableOffset(); + int tempEndOffset = allItemsSorted.at(iAllItemLoop)->visualEndTableOffset(); + + if (tempEndOffset >= startOffset && tempStartOffset <= endOffset) + { + + if (concurrentItems.size() >= 1) + { + bool bAppend = false; + /*check all items in the list if the current items interfers although the items are ordered by startIndex + *we can loose some of them if the endTime of the last Item is before the endTime of the pre last item + */ + + for (QLinkedList::iterator it = concurrentItems.begin(); it != concurrentItems.end(); ++it) + { + int lastStartOffset = (*it)->visualStartTableOffset(); + int lastEndOffset = (*it)->visualEndTableOffset(); + + if (tempEndOffset >= lastStartOffset && tempStartOffset <= lastEndOffset) + { + bAppend = true; + break; + } + } + + if (bAppend) + { + concurrentItems.append(allItemsSorted.at(iAllItemLoop)); + } + else + { + allConcurrentItems.append(concurrentItems); + concurrentItems.clear(); + concurrentItems.append(allItemsSorted.at(iAllItemLoop)); + } + } + else + concurrentItems.append(allItemsSorted.at(iAllItemLoop)); + + if (tempStartOffset < startOffset) + startOffset = tempStartOffset; + + if (tempEndOffset > endOffset) + endOffset = tempEndOffset; + } + } + if (concurrentItems.size() > 0) + allConcurrentItems.append(concurrentItems); + + return allConcurrentItems; +} + +void QxtScheduleViewPrivate::handleItemConcurrency(const int from, const int to) +{ + /*collect all items that interfere only in that range*/ + if (from < 0 || to < 0 || m_Items.size() == 0){ + //do a update or we may have artifacts + qxt_p().viewport()->update(); + return; + } + + qDebug() << "handleItemConcurrency"; + + if (handlesConcurrency) + return; + + handlesConcurrency = true; + + QList< QLinkedList > allConcurrentItems = findConcurrentItems(from, to); + + /*thx to ahigerd for suggesting that algorithm*/ + //[16:24] Start with the first event. Put it in a list. + //[16:25] Iterate until you find an event that doesn't overlap with the first event. Put it in the list. Repeat until you've reached the last event. + //[16:25] This fills the left column optimally. + //[16:25] Repeat the algorithm for the second column, etc., until there aren't any events left that don't have a column. + //[16:27] This algorithm is O(n*m), where n is the number of events and m is the maximum number of overlapping events. + + QList< QList< QxtScheduleInternalItem *> >virtualTable; + + for (int iListLoop = 0; iListLoop < allConcurrentItems.size(); iListLoop++) + { + QLinkedList & currentItems = allConcurrentItems[iListLoop]; + QList< QxtScheduleInternalItem * > currentColumn; + + qDebug() << "handle overlapping for " << currentItems.size() << " Items"; + + virtualTable.clear(); + + //we iterate over the currect collection and remove every item that can be placed in the current column + //when the collection is empty we are done + while (currentItems.size()) + { + QMutableLinkedListIterator< QxtScheduleInternalItem * > iter(currentItems); + + while (iter.hasNext()) + { + iter.next(); + //initialize the current column + if (currentColumn.isEmpty() || currentColumn[currentColumn.size()-1]->visualEndTableOffset() < iter.value()->visualStartTableOffset()) + { + currentColumn.append(iter.value()); + iter.remove(); + continue; + } + } + + if (!currentColumn.isEmpty()) + { + virtualTable.append(currentColumn); + currentColumn.clear(); + } + } + + qDebug() << "Found columns" << virtualTable.size(); + + //this code part resizes the item geometries + for (int col = 0; col < virtualTable.size(); col++) + { + for (int item = 0; item < virtualTable.at(col).size() ; item++) + { + int startVisualCol = offsetToVisualColumn(virtualTable[col][item]->visualStartTableOffset()); + QVector geo = virtualTable[col][item]->geometry(); + + for (int rect = 0; rect < geo.size(); rect++) + { + int sectionStart = m_hHeader->sectionPosition(startVisualCol); + int fullWidth = m_hHeader->sectionSize(startVisualCol); + int oneItemWidth = fullWidth / virtualTable.size(); + int itemWidth = oneItemWidth; + int itemXStart = (col * oneItemWidth) + sectionStart; + int overlap = oneItemWidth / 10; + int adjustX1 = 0; + int adjustX2 = 0; + + //this is very expensive.I try to check if my item can span over more than one col + int possibleCols = 1; + bool foundCollision; + + for (int tmpCol = col + 1; tmpCol < virtualTable.size(); tmpCol++) + { + foundCollision = false; + for (int tmpItem = 0; tmpItem < virtualTable.at(tmpCol).size() ; tmpItem++) + { + if ((virtualTable[tmpCol][tmpItem]->visualEndTableOffset() >= virtualTable[col][item]->visualStartTableOffset() + && virtualTable[tmpCol][tmpItem]->visualStartTableOffset() <= virtualTable[col][item]->visualEndTableOffset())) + { + foundCollision = true; + break; + } + } + + if (!foundCollision) + possibleCols++; + else + break; + } + //now lets adjust the size to get a nice overlapping of items + if (virtualTable.size() > 1) + { + if (col == 0) + adjustX2 = overlap; + else if (col == virtualTable.size() - 1) + { + adjustX1 = -overlap; + adjustX2 = overlap; + } + else + { + if (col + possibleCols == virtualTable.size()) + adjustX2 = overlap; + else + adjustX2 = overlap * 2; + + adjustX1 = -overlap; + } + } + + // possibleCols = 1; + itemWidth = oneItemWidth * possibleCols; + + qDebug() << "orginial rect" << geo[rect]; + geo[rect].setLeft(itemXStart + adjustX1); + geo[rect].setWidth(itemWidth + adjustX2); + qDebug() << "new rect" << geo[rect]; + + + startVisualCol++; + } + virtualTable[col][item]->setGeometry(geo); + } + } + } + handlesConcurrency = false; + qxt_p().viewport()->update(); +} + +QxtScheduleViewPrivate::QxtScheduleViewPrivate() +{ + m_Cols = 0; + m_vHeader = 0; + m_hHeader = 0; + m_Model = 0; + m_selectedItem = 0; + handlesConcurrency = false; + delegate = 0; + m_zoomStepWidth = 0; + + connect(&scrollTimer, SIGNAL(timeout()), this, SLOT(scrollTimerTimeout())); +} + +void QxtScheduleViewPrivate::itemGeometryChanged(QxtScheduleInternalItem * item, QVector< QRect > oldGeometry) +{ + QRegion oldRegion; + + if (item->geometry() == oldGeometry) + return; + + QVectorIterator iter(oldGeometry); + QRect currRect; + while (iter.hasNext()) + { + currRect = iter.next(); + currRect.adjust(-1, -1, 2, 2); + oldRegion += currRect; + } + //viewport()->update(oldRegion); + + + QRegion newRegion; + QVectorIterator newIter(item->geometry()); + while (newIter.hasNext()) + { + currRect = newIter.next(); + currRect.adjust(-1, -1, 2, 2); + newRegion += currRect; + } + //viewport()->update(newRegion); + qxt_p().viewport()->update(); +} + +int QxtScheduleViewPrivate::unixTimeToOffset(const uint constUnixTime, bool indexEndTime) const +{ + uint unixTime = constUnixTime; + if (unixTime >= m_startUnixTime && unixTime <= m_endUnixTime) + { + if (indexEndTime) + { + unixTime -= m_currentZoomDepth; + } + qint32 rows = qxt_p().rows(); + qint32 iOffset = unixTime - m_startUnixTime; + + //round to the closest boundaries + iOffset = qRound((qreal)iOffset / (qreal)m_currentZoomDepth); + + qint32 iCol = iOffset / rows; + qint32 iRow = iOffset % rows; + return visualIndexToOffset(iRow, iCol); + } + //virtual void handleItemOverlapping(QxtScheduleInternalItem *item); + return -1; +} + +void QxtScheduleViewPrivate::scrollTimerTimeout() +{ + QPoint globalPos = QCursor::pos(); + QPoint viewportPos = qxt_p().viewport()->mapFromGlobal(globalPos); + + int iScrollVertical = this->m_vHeader->defaultSectionSize(); + int iScrollHorizontal = this->m_hHeader->defaultSectionSize(); + + if (viewportPos.y() <= iScrollVertical) + { + int iCurrPos = qxt_p().verticalScrollBar()->value(); + if (iCurrPos > qxt_p().verticalScrollBar()->minimum() + iScrollVertical) + { + qxt_p().verticalScrollBar()->setValue(iCurrPos - iScrollVertical); + } + else + qxt_p().verticalScrollBar()->setValue(qxt_p().verticalScrollBar()->minimum()); + + } + else if (viewportPos.y() >= qxt_p().viewport()->height() - iScrollVertical) + { + int iCurrPos = qxt_p().verticalScrollBar()->value(); + if (iCurrPos < qxt_p().verticalScrollBar()->maximum() - iScrollVertical) + { + qxt_p().verticalScrollBar()->setValue(iCurrPos + iScrollVertical); + } + else + qxt_p().verticalScrollBar()->setValue(qxt_p().verticalScrollBar()->maximum()); + } + + if (viewportPos.x() <= iScrollHorizontal / 2) + { + int iCurrPos = qxt_p().horizontalScrollBar()->value(); + if (iCurrPos > qxt_p().horizontalScrollBar()->minimum() + iScrollHorizontal) + { + qxt_p().horizontalScrollBar()->setValue(iCurrPos - iScrollHorizontal); + } + else + qxt_p().horizontalScrollBar()->setValue(qxt_p().horizontalScrollBar()->minimum()); + + } + else if (viewportPos.x() >= qxt_p().viewport()->width() - (iScrollHorizontal / 2)) + { + int iCurrPos = qxt_p().horizontalScrollBar()->value(); + if (iCurrPos < qxt_p().horizontalScrollBar()->maximum() - iScrollHorizontal) + { + qxt_p().horizontalScrollBar()->setValue(iCurrPos + iScrollHorizontal); + } + else + qxt_p().horizontalScrollBar()->setValue(qxt_p().horizontalScrollBar()->maximum()); + } + +} + +int QxtScheduleViewPrivate::offsetToUnixTime(const int offset, bool indexEndTime) const +{ + qint32 rows = qxt_p().rows(); + uint unixTime = (offsetToVisualRow(offset) + (offsetToVisualColumn(offset) * rows)) * m_currentZoomDepth; + unixTime += m_startUnixTime; + + if (indexEndTime) + { + unixTime += m_currentZoomDepth; + } + + if (unixTime >= m_startUnixTime && unixTime <= m_endUnixTime + 1) + return unixTime; + return -1; +} + + +QxtScheduleInternalItem::QxtScheduleInternalItem(QxtScheduleView *parent, QModelIndex index, QVector geometries) + : QObject(parent), m_iModelRow(index.row()), m_geometries(geometries) +{ + m_moving = false; + if (parent) + { + if (index.isValid()) + { + if (m_geometries.empty()) + { + int startOffset = this->startTableOffset(); + int endOffset = startOffset + this->rows() - 1; + m_geometries = parent->qxt_d().calculateRangeGeometries(startOffset, endOffset); + } + } + } +} + +QxtScheduleView * QxtScheduleInternalItem::parentView() const +{ + return qobject_cast(parent()); +} + +/*! + * @desc returns the currently VISUAL offset (changes when a item moves) + */ +int QxtScheduleInternalItem::visualStartTableOffset() const +{ + if (m_geometries.size() == 0 || !parentView()) + return -1; + + //are we in a move? + if (!m_moving) + return startTableOffset(); + + int offset = parentView()->qxt_d().pointToOffset(parentView()->mapToViewport((this->geometry()[0].topLeft()))); + return offset; +} + +/*! + * @desc returns the currently VISUAL offset (changes when a item moves) + */ +int QxtScheduleInternalItem::visualEndTableOffset() const +{ + if (m_geometries.size() == 0 || !parentView()) + return -1; + + //are we in a move? + if (!m_moving) + return endTableOffset(); + + QRect rect = m_geometries[m_geometries.size()-1]; + int endTableOffset = parentView()->qxt_d().pointToOffset(parentView()->mapToViewport(rect.bottomRight())); + return endTableOffset; +} + +bool QxtScheduleInternalItem::setData(QVariant data, int role) +{ + if (parentView() && parentView()->model()) + { + return parentView()->model()->setData(modelIndex(), data, role); + } + return false; +} + +QVariant QxtScheduleInternalItem::data(int role) const +{ + if (modelIndex().isValid()) + return modelIndex().data(role); + return QVariant(); +} + +int QxtScheduleInternalItem::startTableOffset() const +{ + if (parentView() && parentView()->model()) + { + int startTime = data(Qxt::ItemStartTimeRole).toInt(); + int zoomDepth = parentView()->currentZoomDepth(Qxt::Second); + + qint32 offset = startTime - parentView()->qxt_d().m_startUnixTime; + + //the start of the current item does not fit in the view + //so we have to align it to the nearest boundaries + if (offset % zoomDepth) + { + int lower = offset / zoomDepth * zoomDepth; + int upper = lower + zoomDepth; + + offset = (offset - lower >= upper - offset ? upper : lower); + + return parentView()->qxt_d().unixTimeToOffset(offset + parentView()->qxt_d().m_startUnixTime); + } + + return parentView()->qxt_d().unixTimeToOffset(startTime); + } + return -1; +} + +int QxtScheduleInternalItem::endTableOffset() const +{ + return startTableOffset() + rows() - 1; +} + +void QxtScheduleInternalItem::setStartTableOffset(int iOffset) +{ + if (parentView() && parentView()->model()) + { + setData(parentView()->qxt_d().offsetToUnixTime(iOffset), Qxt::ItemStartTimeRole); + } +} + +void QxtScheduleInternalItem::setRowsUsed(int rows) +{ + if (parentView() && parentView()->model()) + { + int seconds = rows * parentView()->currentZoomDepth(Qxt::Second); + setData(seconds, Qxt::ItemDurationRole); + } +} + +int QxtScheduleInternalItem::rows() const +{ + if (parentView() && parentView()->model()) + { + int iNumSecs = data(Qxt::ItemDurationRole).toInt(); + int zoomDepth = parentView()->currentZoomDepth(Qxt::Second); + + //the length of the current item does not fit in the view + //so we have to align it to the nearest boundaries + if (iNumSecs % zoomDepth) + { + int lower = iNumSecs / zoomDepth * zoomDepth; + int upper = lower + zoomDepth; + + return (iNumSecs - lower >= upper - iNumSecs ? (upper / zoomDepth) : (lower / zoomDepth)); + + } + return (iNumSecs / zoomDepth); + } + return -1; +} + +bool qxtScheduleItemLessThan(const QxtScheduleInternalItem * item1, const QxtScheduleInternalItem * item2) +{ + if (item1->visualStartTableOffset() < item2->visualStartTableOffset()) + return true; + if (item1->visualStartTableOffset() == item2->visualStartTableOffset() && item1->modelIndex().row() < item2->modelIndex().row()) + return true; + return false; +} + +bool QxtScheduleInternalItem::contains(const QPoint & pt) +{ + QVectorIterator iterator(this->m_geometries); + while (iterator.hasNext()) + { + if (iterator.next().contains(pt)) + return true; + } + return false; +} + +void QxtScheduleInternalItem::setGeometry(const QVector< QRect > geo) +{ + if (!this->parent()) + return; + + QVector oldGeo = this->m_geometries; + this->m_geometries.clear(); + this->m_geometries = geo; + emit geometryChanged(this, oldGeo); +} + +QVector< QRect > QxtScheduleInternalItem::geometry() const +{ + return this->m_geometries; +} + +void QxtScheduleInternalItem::startMove() +{ + //save old geometry before we start to move + this->m_SavedGeometries = this->m_geometries; + m_moving = true; +} + +void QxtScheduleInternalItem::resetMove() +{ + this->setGeometry(this->m_SavedGeometries); + this->m_SavedGeometries.clear(); + m_moving = false; +} + +void QxtScheduleInternalItem::stopMove() +{ + this->m_SavedGeometries.clear(); + m_moving = false; +} + +QModelIndex QxtScheduleInternalItem::modelIndex() const +{ + QModelIndex indx; + if (parentView() && parentView()->model()) + { + indx = parentView()->model()->index(this->m_iModelRow, 0); + } + return indx; +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview_p.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview_p.h index 994fb2c27..423c0f6ff 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview_p.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleview_p.h @@ -1,183 +1,183 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ - -#ifndef QXTSCHEDULEVIEW_P_INCLUDED -#define QXTSCHEDULEVIEW_P_INCLUDED - -// -// W A R N I N G -// ------------- -// -// This file is not part of the Qxt API. It exists for the convenience -// of other Qxt classes. This header file may change from version to -// version without notice, or even be removed. -// -// We mean it. -// - - -#include -#include -#include -#include -#include -#include -#include -#include "qxtnamespace.h" -#include "qxtscheduleitemdelegate.h" - -class QxtScheduleView; -class QxtScheduleHeaderWidget; - -class QxtScheduleInternalItem : public QObject -{ - Q_OBJECT - friend class QxtScheduleView; - -public: - - QxtScheduleInternalItem(QxtScheduleView *parent , QModelIndex index , QVector geometries = QVector()); - - bool setData(QVariant data , int role); - QVariant data(int role) const; - - int visualStartTableOffset() const; - int visualEndTableOffset() const; - - int startTableOffset() const; - int endTableOffset() const; - void setStartTableOffset(int iOffset); - - int rows() const; - void setRowsUsed(int rows); - QxtScheduleView* parentView() const; - - void startMove(); - void resetMove(); - void stopMove(); - - bool contains(const QPoint &pt); - void setGeometry(const QVector geo); - QModelIndex modelIndex() const; - void setDirty(bool state = true) - { - isDirty = state; - } - - QVector geometry() const; - -Q_SIGNALS: - void geometryChanged(QxtScheduleInternalItem * item , QVector oldGeometry); - -public: - bool m_moving; - bool isDirty; - int m_iModelRow; - QVector m_geometries; - QVector m_SavedGeometries; - QVector m_cachedParts; -}; - -class QxtScheduleViewPrivate : public QObject, public QxtPrivate -{ - Q_OBJECT -public: - - QXT_DECLARE_PUBLIC(QxtScheduleView) - QxtScheduleViewPrivate(); - - - int offsetToVisualColumn(const int iOffset) const; - int offsetToVisualRow(const int iOffset) const; - int visualIndexToOffset(const int iRow, const int iCol) const; - int unixTimeToOffset(const uint constUnixTime, bool indexEndTime = false) const; - int offsetToUnixTime(const int offset, bool indexEndTime = false) const; - QVector< QRect > calculateRangeGeometries(const int iStartOffset, const int iEndOffset) const; - int pointToOffset(const QPoint & point); - void handleItemConcurrency(const int from, const int to); - QList< QLinkedList >findConcurrentItems(const int from, const int to) const; - - - QxtScheduleInternalItem *internalItemAt(const QPoint &pt); - QxtScheduleInternalItem *internalItemAtModelIndex(const QModelIndex &index); - - - void init(); - void reloadItemsFromModel(); - - QxtScheduleInternalItem * itemForModelIndex(const QModelIndex &index)const - { - for (int iLoop = 0; iLoop < m_Items.size(); iLoop++) - { - if (m_Items.at(iLoop)->modelIndex() == index) - return m_Items.at(iLoop); - } - return 0; - } - - void handleItemConcurrency(QxtScheduleInternalItem *item) - { - if (item) - { - int startOffset = item->startTableOffset(); - int endOffset = startOffset + item->rows() - 1 ; - handleItemConcurrency(startOffset, endOffset); - } - } - - QxtScheduleInternalItem *m_currentItem; - QxtScheduleInternalItem *m_selectedItem; - - int m_lastMousePosOffset; - int m_currentZoomDepth; - int m_zoomStepWidth; - int m_currentViewMode; - uint m_startUnixTime; - uint m_endUnixTime; - - QList m_Items ; - QList m_InactiveItems; /*used for items that are not in the range of our view but we need to look if they get updates*/ - - QTimer scrollTimer; - - QxtScheduleHeaderWidget *m_vHeader; - QxtScheduleHeaderWidget *m_hHeader; - - int m_Cols; - - QAbstractItemModel *m_Model; - bool handlesConcurrency; - QxtScheduleItemDelegate *delegate; - QxtScheduleItemDelegate *defaultDelegate; - -public Q_SLOTS: - void itemGeometryChanged(QxtScheduleInternalItem * item, QVector oldGeometry); - void scrollTimerTimeout(); - -}; - -bool qxtScheduleItemLessThan(const QxtScheduleInternalItem * item1, const QxtScheduleInternalItem * item2); - -#endif +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ + +#ifndef QXTSCHEDULEVIEW_P_INCLUDED +#define QXTSCHEDULEVIEW_P_INCLUDED + +// +// W A R N I N G +// ------------- +// +// This file is not part of the Qxt API. It exists for the convenience +// of other Qxt classes. This header file may change from version to +// version without notice, or even be removed. +// +// We mean it. +// + + +#include +#include +#include +#include +#include +#include +#include +#include "qxtnamespace.h" +#include "qxtscheduleitemdelegate.h" + +class QxtScheduleView; +class QxtScheduleHeaderWidget; + +class QxtScheduleInternalItem : public QObject +{ + Q_OBJECT + friend class QxtScheduleView; + +public: + + QxtScheduleInternalItem(QxtScheduleView *parent , QModelIndex index , QVector geometries = QVector()); + + bool setData(QVariant data , int role); + QVariant data(int role) const; + + int visualStartTableOffset() const; + int visualEndTableOffset() const; + + int startTableOffset() const; + int endTableOffset() const; + void setStartTableOffset(int iOffset); + + int rows() const; + void setRowsUsed(int rows); + QxtScheduleView* parentView() const; + + void startMove(); + void resetMove(); + void stopMove(); + + bool contains(const QPoint &pt); + void setGeometry(const QVector geo); + QModelIndex modelIndex() const; + void setDirty(bool state = true) + { + isDirty = state; + } + + QVector geometry() const; + +Q_SIGNALS: + void geometryChanged(QxtScheduleInternalItem * item , QVector oldGeometry); + +public: + bool m_moving; + bool isDirty; + int m_iModelRow; + QVector m_geometries; + QVector m_SavedGeometries; + QVector m_cachedParts; +}; + +class QxtScheduleViewPrivate : public QObject, public QxtPrivate +{ + Q_OBJECT +public: + + QXT_DECLARE_PUBLIC(QxtScheduleView) + QxtScheduleViewPrivate(); + + + int offsetToVisualColumn(const int iOffset) const; + int offsetToVisualRow(const int iOffset) const; + int visualIndexToOffset(const int iRow, const int iCol) const; + int unixTimeToOffset(const uint constUnixTime, bool indexEndTime = false) const; + int offsetToUnixTime(const int offset, bool indexEndTime = false) const; + QVector< QRect > calculateRangeGeometries(const int iStartOffset, const int iEndOffset) const; + int pointToOffset(const QPoint & point); + void handleItemConcurrency(const int from, const int to); + QList< QLinkedList >findConcurrentItems(const int from, const int to) const; + + + QxtScheduleInternalItem *internalItemAt(const QPoint &pt); + QxtScheduleInternalItem *internalItemAtModelIndex(const QModelIndex &index); + + + void init(); + void reloadItemsFromModel(); + + QxtScheduleInternalItem * itemForModelIndex(const QModelIndex &index)const + { + for (int iLoop = 0; iLoop < m_Items.size(); iLoop++) + { + if (m_Items.at(iLoop)->modelIndex() == index) + return m_Items.at(iLoop); + } + return 0; + } + + void handleItemConcurrency(QxtScheduleInternalItem *item) + { + if (item) + { + int startOffset = item->startTableOffset(); + int endOffset = startOffset + item->rows() - 1 ; + handleItemConcurrency(startOffset, endOffset); + } + } + + QxtScheduleInternalItem *m_currentItem; + QxtScheduleInternalItem *m_selectedItem; + + int m_lastMousePosOffset; + int m_currentZoomDepth; + int m_zoomStepWidth; + int m_currentViewMode; + uint m_startUnixTime; + uint m_endUnixTime; + + QList m_Items ; + QList m_InactiveItems; /*used for items that are not in the range of our view but we need to look if they get updates*/ + + QTimer scrollTimer; + + QxtScheduleHeaderWidget *m_vHeader; + QxtScheduleHeaderWidget *m_hHeader; + + int m_Cols; + + QAbstractItemModel *m_Model; + bool handlesConcurrency; + QxtScheduleItemDelegate *delegate; + QxtScheduleItemDelegate *defaultDelegate; + +public Q_SLOTS: + void itemGeometryChanged(QxtScheduleInternalItem * item, QVector oldGeometry); + void scrollTimerTimeout(); + +}; + +bool qxtScheduleItemLessThan(const QxtScheduleInternalItem * item1, const QxtScheduleInternalItem * item2); + +#endif diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleviewheadermodel_p.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleviewheadermodel_p.cpp index 874502e5d..ba2966248 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleviewheadermodel_p.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleviewheadermodel_p.cpp @@ -1,211 +1,211 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ - -#include "qxtscheduleviewheadermodel_p.h" -#include "qxtscheduleview.h" -#include "qxtscheduleview_p.h" -#include -#include - -QxtScheduleViewHeaderModel::QxtScheduleViewHeaderModel(QObject *parent) : QAbstractTableModel(parent) - , m_rowCountBuffer(0) - , m_colCountBuffer(0) -{ - -} - -void QxtScheduleViewHeaderModel::newZoomDepth(const int zoomDepth) -{ - Q_UNUSED(zoomDepth); - - if (this->m_dataSource) - { - /* - qDebug()<<"old rows "<rows(); - beginRemoveRows(QModelIndex(),0,m_rowCountBuffer); - m_rowCountBuffer = 0; - endRemoveRows(); - - beginInsertRows(QModelIndex(),0,m_dataSource->rows()); - m_rowCountBuffer = m_dataSource->rows(); - endInsertRows(); - */ - m_rowCountBuffer = m_dataSource->rows(); - reset(); - - } -} - -void QxtScheduleViewHeaderModel::viewModeChanged(const int viewMode) -{ - Q_UNUSED(viewMode); - - if (this->m_dataSource) - { - beginRemoveRows(QModelIndex(), 0, m_rowCountBuffer); - m_rowCountBuffer = 0; - endRemoveRows(); - - beginInsertRows(QModelIndex(), 0, m_dataSource->rows()); - m_rowCountBuffer = m_dataSource->rows(); - endInsertRows(); - - beginRemoveColumns(QModelIndex(), 0, m_colCountBuffer); - m_colCountBuffer = 0; - endRemoveColumns(); - - beginInsertColumns(QModelIndex(), 0, m_dataSource->cols()); - m_colCountBuffer = m_dataSource->cols(); - endInsertColumns(); - } -} - -void QxtScheduleViewHeaderModel::setDataSource(QxtScheduleView *dataSource) -{ - if (this->m_dataSource) - { - disconnect(m_dataSource, SIGNAL(newZoomDepth(const int)), this, SLOT(newZoomDepth(const int))); - disconnect(m_dataSource, SIGNAL(viewModeChanged(const int)), this, SLOT(viewModeChanged(const int))); - - emit beginRemoveRows(QModelIndex(), 0, m_rowCountBuffer); - m_rowCountBuffer = 0; - emit endRemoveRows(); - - emit beginRemoveColumns(QModelIndex(), 0, m_colCountBuffer); - m_colCountBuffer = 0; - emit endRemoveColumns(); - } - - if (dataSource) - { - connect(dataSource, SIGNAL(newZoomDepth(const int)), this, SLOT(newZoomDepth(const int))); - connect(dataSource, SIGNAL(viewModeChanged(const int)), this, SLOT(viewModeChanged(const int))); - - emit beginInsertRows(QModelIndex(), 0, dataSource->rows()); - m_rowCountBuffer = dataSource->rows(); - emit endInsertRows(); - - emit beginInsertColumns(QModelIndex(), 0, dataSource->cols()); - m_colCountBuffer = dataSource->cols(); - emit endInsertColumns(); - } - - m_dataSource = dataSource; -} - -QModelIndex QxtScheduleViewHeaderModel::parent(const QModelIndex & index) const -{ - Q_UNUSED(index); - return QModelIndex(); -} - -int QxtScheduleViewHeaderModel::rowCount(const QModelIndex & parent) const -{ - if (!parent.isValid()) - { - if (this->m_dataSource) - return m_dataSource->rows(); - } - return 0; -} - -int QxtScheduleViewHeaderModel::columnCount(const QModelIndex & parent) const -{ - if (!parent.isValid()) - { - if (this->m_dataSource) - return m_dataSource->cols(); - } - return 0; -} - -QVariant QxtScheduleViewHeaderModel::data(const QModelIndex & index, int role) const -{ - Q_UNUSED(index); - Q_UNUSED(role); - return QVariant(); -} - -bool QxtScheduleViewHeaderModel::setData(const QModelIndex & index, const QVariant & value, int role) -{ - Q_UNUSED(index); - Q_UNUSED(value); - Q_UNUSED(role); - return false; -} - -bool QxtScheduleViewHeaderModel::insertRow(int row, const QModelIndex & parent) -{ - Q_UNUSED(row); - Q_UNUSED(parent); - return false; -} - -QVariant QxtScheduleViewHeaderModel::headerData(int section, Qt::Orientation orientation, int role) const -{ - if (!m_dataSource) - return QVariant(); -#if 0 - if (role == Qt::SizeHintRole) - { - if (this->viewModel) - { - return viewModel->headerData(section, orientation, role); - } - } -#endif - - if (role == Qt::DisplayRole || role == Qt::EditRole) - { - if (Qt::Horizontal == orientation) - { - int iTableOffset = m_dataSource->qxt_d().visualIndexToOffset(0, section); - QDateTime startTime = QDateTime::fromTime_t(m_dataSource->qxt_d().offsetToUnixTime(iTableOffset)); - return QVariant(startTime.date().toString()); - } - else - { - int iTableOffset = m_dataSource->qxt_d().visualIndexToOffset(section, 0); - QTime time = QDateTime::fromTime_t(m_dataSource->qxt_d().offsetToUnixTime(iTableOffset)).time(); - return QVariant(time.toString()); - } - } - - return QVariant(); -} - -Qt::ItemFlags QxtScheduleViewHeaderModel::flags(const QModelIndex & index) const -{ - Q_UNUSED(index); - return Qt::ItemIsEnabled; -} - -bool QxtScheduleViewHeaderModel::hasChildren(const QModelIndex & parent) const -{ - Q_UNUSED(parent); - return false; -} - - +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ + +#include "qxtscheduleviewheadermodel_p.h" +#include "qxtscheduleview.h" +#include "qxtscheduleview_p.h" +#include +#include + +QxtScheduleViewHeaderModel::QxtScheduleViewHeaderModel(QObject *parent) : QAbstractTableModel(parent) + , m_rowCountBuffer(0) + , m_colCountBuffer(0) +{ + +} + +void QxtScheduleViewHeaderModel::newZoomDepth(const int zoomDepth) +{ + Q_UNUSED(zoomDepth); + + if (this->m_dataSource) + { + /* + qDebug()<<"old rows "<rows(); + beginRemoveRows(QModelIndex(),0,m_rowCountBuffer); + m_rowCountBuffer = 0; + endRemoveRows(); + + beginInsertRows(QModelIndex(),0,m_dataSource->rows()); + m_rowCountBuffer = m_dataSource->rows(); + endInsertRows(); + */ + m_rowCountBuffer = m_dataSource->rows(); + reset(); + + } +} + +void QxtScheduleViewHeaderModel::viewModeChanged(const int viewMode) +{ + Q_UNUSED(viewMode); + + if (this->m_dataSource) + { + beginRemoveRows(QModelIndex(), 0, m_rowCountBuffer); + m_rowCountBuffer = 0; + endRemoveRows(); + + beginInsertRows(QModelIndex(), 0, m_dataSource->rows()); + m_rowCountBuffer = m_dataSource->rows(); + endInsertRows(); + + beginRemoveColumns(QModelIndex(), 0, m_colCountBuffer); + m_colCountBuffer = 0; + endRemoveColumns(); + + beginInsertColumns(QModelIndex(), 0, m_dataSource->cols()); + m_colCountBuffer = m_dataSource->cols(); + endInsertColumns(); + } +} + +void QxtScheduleViewHeaderModel::setDataSource(QxtScheduleView *dataSource) +{ + if (this->m_dataSource) + { + disconnect(m_dataSource, SIGNAL(newZoomDepth(const int)), this, SLOT(newZoomDepth(const int))); + disconnect(m_dataSource, SIGNAL(viewModeChanged(const int)), this, SLOT(viewModeChanged(const int))); + + emit beginRemoveRows(QModelIndex(), 0, m_rowCountBuffer); + m_rowCountBuffer = 0; + emit endRemoveRows(); + + emit beginRemoveColumns(QModelIndex(), 0, m_colCountBuffer); + m_colCountBuffer = 0; + emit endRemoveColumns(); + } + + if (dataSource) + { + connect(dataSource, SIGNAL(newZoomDepth(const int)), this, SLOT(newZoomDepth(const int))); + connect(dataSource, SIGNAL(viewModeChanged(const int)), this, SLOT(viewModeChanged(const int))); + + emit beginInsertRows(QModelIndex(), 0, dataSource->rows()); + m_rowCountBuffer = dataSource->rows(); + emit endInsertRows(); + + emit beginInsertColumns(QModelIndex(), 0, dataSource->cols()); + m_colCountBuffer = dataSource->cols(); + emit endInsertColumns(); + } + + m_dataSource = dataSource; +} + +QModelIndex QxtScheduleViewHeaderModel::parent(const QModelIndex & index) const +{ + Q_UNUSED(index); + return QModelIndex(); +} + +int QxtScheduleViewHeaderModel::rowCount(const QModelIndex & parent) const +{ + if (!parent.isValid()) + { + if (this->m_dataSource) + return m_dataSource->rows(); + } + return 0; +} + +int QxtScheduleViewHeaderModel::columnCount(const QModelIndex & parent) const +{ + if (!parent.isValid()) + { + if (this->m_dataSource) + return m_dataSource->cols(); + } + return 0; +} + +QVariant QxtScheduleViewHeaderModel::data(const QModelIndex & index, int role) const +{ + Q_UNUSED(index); + Q_UNUSED(role); + return QVariant(); +} + +bool QxtScheduleViewHeaderModel::setData(const QModelIndex & index, const QVariant & value, int role) +{ + Q_UNUSED(index); + Q_UNUSED(value); + Q_UNUSED(role); + return false; +} + +bool QxtScheduleViewHeaderModel::insertRow(int row, const QModelIndex & parent) +{ + Q_UNUSED(row); + Q_UNUSED(parent); + return false; +} + +QVariant QxtScheduleViewHeaderModel::headerData(int section, Qt::Orientation orientation, int role) const +{ + if (!m_dataSource) + return QVariant(); +#if 0 + if (role == Qt::SizeHintRole) + { + if (this->viewModel) + { + return viewModel->headerData(section, orientation, role); + } + } +#endif + + if (role == Qt::DisplayRole || role == Qt::EditRole) + { + if (Qt::Horizontal == orientation) + { + int iTableOffset = m_dataSource->qxt_d().visualIndexToOffset(0, section); + QDateTime startTime = QDateTime::fromTime_t(m_dataSource->qxt_d().offsetToUnixTime(iTableOffset)); + return QVariant(startTime.date().toString()); + } + else + { + int iTableOffset = m_dataSource->qxt_d().visualIndexToOffset(section, 0); + QTime time = QDateTime::fromTime_t(m_dataSource->qxt_d().offsetToUnixTime(iTableOffset)).time(); + return QVariant(time.toString()); + } + } + + return QVariant(); +} + +Qt::ItemFlags QxtScheduleViewHeaderModel::flags(const QModelIndex & index) const +{ + Q_UNUSED(index); + return Qt::ItemIsEnabled; +} + +bool QxtScheduleViewHeaderModel::hasChildren(const QModelIndex & parent) const +{ + Q_UNUSED(parent); + return false; +} + + diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleviewheadermodel_p.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleviewheadermodel_p.h index 5ed1a7f10..69a97dd26 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleviewheadermodel_p.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtscheduleviewheadermodel_p.h @@ -1,81 +1,81 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ - -// -// W A R N I N G -// ------------- -// -// This file is not part of the Qxt API. It exists for the convenience -// of other Qxt classes. This header file may change from version to -// version without notice, or even be removed. -// -// We mean it. -// - - -#ifndef QXTSCHEDULEVIEWHEADERMODEL_P_H_INCLUDED -#define QXTSCHEDULEVIEWHEADERMODEL_P_H_INCLUDED - -#include -#include -#include - -/*! - *@author Benjamin Zeller - *@desc This Model is used to tell the Header how many rows and columns the view has - */ - -class QxtScheduleView; - -class QxtScheduleViewHeaderModel : public QAbstractTableModel -{ - Q_OBJECT - -public: - QxtScheduleViewHeaderModel(QObject *parent = 0); - - void setDataSource(QxtScheduleView *dataSource); - - virtual QModelIndex parent(const QModelIndex & index) const; - virtual int rowCount(const QModelIndex & parent = QModelIndex()) const; - virtual int columnCount(const QModelIndex & parent = QModelIndex()) const; - virtual QVariant data(const QModelIndex & index, int role = Qt::DisplayRole) const; - virtual bool setData(const QModelIndex & index, const QVariant & value, int role = Qt::EditRole); - virtual bool insertRow(int row, const QModelIndex & parent = QModelIndex()); - virtual QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const; - virtual Qt::ItemFlags flags(const QModelIndex &index) const; - virtual bool hasChildren(const QModelIndex & parent = QModelIndex()) const; - -public Q_SLOTS: - void newZoomDepth(const int zoomDepth); - void viewModeChanged(const int viewMode); - -private: - QPointer m_dataSource; - int m_rowCountBuffer; - int m_colCountBuffer; -}; - -#endif // SPLITVIEWHEADERMODEL_H +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ + +// +// W A R N I N G +// ------------- +// +// This file is not part of the Qxt API. It exists for the convenience +// of other Qxt classes. This header file may change from version to +// version without notice, or even be removed. +// +// We mean it. +// + + +#ifndef QXTSCHEDULEVIEWHEADERMODEL_P_H_INCLUDED +#define QXTSCHEDULEVIEWHEADERMODEL_P_H_INCLUDED + +#include +#include +#include + +/*! + *@author Benjamin Zeller + *@desc This Model is used to tell the Header how many rows and columns the view has + */ + +class QxtScheduleView; + +class QxtScheduleViewHeaderModel : public QAbstractTableModel +{ + Q_OBJECT + +public: + QxtScheduleViewHeaderModel(QObject *parent = 0); + + void setDataSource(QxtScheduleView *dataSource); + + virtual QModelIndex parent(const QModelIndex & index) const; + virtual int rowCount(const QModelIndex & parent = QModelIndex()) const; + virtual int columnCount(const QModelIndex & parent = QModelIndex()) const; + virtual QVariant data(const QModelIndex & index, int role = Qt::DisplayRole) const; + virtual bool setData(const QModelIndex & index, const QVariant & value, int role = Qt::EditRole); + virtual bool insertRow(int row, const QModelIndex & parent = QModelIndex()); + virtual QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const; + virtual Qt::ItemFlags flags(const QModelIndex &index) const; + virtual bool hasChildren(const QModelIndex & parent = QModelIndex()) const; + +public Q_SLOTS: + void newZoomDepth(const int zoomDepth); + void viewModeChanged(const int viewMode); + +private: + QPointer m_dataSource; + int m_rowCountBuffer; + int m_colCountBuffer; +}; + +#endif // SPLITVIEWHEADERMODEL_H diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtsortfilterproxymodel.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtsortfilterproxymodel.cpp index 36b0e8a95..cfa5a6b89 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtsortfilterproxymodel.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtsortfilterproxymodel.cpp @@ -1,298 +1,298 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ - -#include "qxtsortfilterproxymodel.h" -#include - -class QxtModelFilterPrivate -{ - public: - QxtModelFilterPrivate (const QVariant &value = QVariant(), const int role = Qt::DisplayRole, const Qt::MatchFlags flags = Qt::MatchContains); - bool acceptsValue ( const QVariant & value ); - QVariant m_value; - int m_role; - Qt::MatchFlags m_flags; -}; - -class QxtSortFilterProxyModelPrivate : public QxtPrivate -{ - public: - QMap filters; - bool m_declaringFilter; -}; - -QxtModelFilterPrivate::QxtModelFilterPrivate(const QVariant &value, const int role, const Qt::MatchFlags flags) - :m_value(value),m_role(role),m_flags(flags) -{ - -} - -bool QxtModelFilterPrivate::acceptsValue ( const QVariant & value ) -{ - uint matchType = m_flags & 0x0F; - //if we have no value we accept everything - if(!m_value.isValid() || !value.isValid()) - return true; - - // QVariant based matching - if (matchType == Qt::MatchExactly ){ - if(m_value == value) - return true; - } - // QString based matching - else { - Qt::CaseSensitivity cs = m_flags & Qt::MatchCaseSensitive ? Qt::CaseSensitive : Qt::CaseInsensitive; - QString filterText = m_value.toString(); - QString modelText = value.toString(); - switch (matchType){ - case Qt::MatchRegExp: - if (QRegExp(filterText, cs).exactMatch(modelText)) - return true; - break; - case Qt::MatchWildcard: - if (QRegExp(filterText, cs, QRegExp::Wildcard).exactMatch(modelText)) - return true; - break; - case Qt::MatchStartsWith: - if (modelText.startsWith(filterText, cs)) - return true; - break; - case Qt::MatchEndsWith: - if (modelText.endsWith(filterText, cs)) - return true; - break; - case Qt::MatchFixedString: - if (modelText.compare(filterText, cs) == 0) - return true; - break; - default: - case Qt::MatchContains: - if (modelText.contains(filterText, cs)) - return true; - } - } - return false; -} - -/*! - \class QxtSortFilterProxyModel - \inmodule QxtGui - \brief The QxtSortFilterProxyModel class is a multi column filter model. - - The QxtSortFilterProxyModel makes it possible to filter over multiple columns. - - \code - QxtSortFilterProxyModel * filterModel = new QxtSortFilterProxyModel(parent); - filterModel->setSourceModel(sourceModel); - filterModel->beginDeclareFilter(); - filterModel->setFilter(1,QVariant("SomeStringValue"),Qt::DisplayRole,Qt::MatchExactly); - //remove some old filter - filterModel->removeFilter(2); - filterModel->setFilter(5,QVariant(1234),Qt::DisplayRole,Qt::MatchExactly); - filterModel->endDeclateFilter(); - \endcode - - Now the model will filter column 1 and 5, to be accepted by the filtermodel a row needs to pass all filters -*/ - -/*! - Constructs a new QxtSortFilterProxyModel with \a parent. - */ -QxtSortFilterProxyModel::QxtSortFilterProxyModel ( QObject *parent) : QSortFilterProxyModel(parent) -{ - QXT_INIT_PRIVATE(QxtSortFilterProxyModel); - qxt_d().m_declaringFilter = false; -} - - -/*! - \brief tells the model you want to declare a new filter - - If you have a lot of data in your model it can be slow to declare more than one filter, - because the model will always rebuild itself. If you call this member before setting the - new filters the model will invalidate its contents not before you call - - \sa endDeclareFilter() - */ -void QxtSortFilterProxyModel::beginDeclareFilter ( ) -{ - qxt_d().m_declaringFilter = true; -} - -/*! - \brief stops the filter declaration and invalidates the filter - - \sa beginDeclareFilter() - */ -void QxtSortFilterProxyModel::endDeclareFilter ( ) -{ - if(qxt_d().m_declaringFilter){ - qxt_d().m_declaringFilter = false; - invalidateFilter(); - } -} - -/*! - \reimp - */ -bool QxtSortFilterProxyModel::filterAcceptsRow ( int source_row, const QModelIndex &source_parent ) const -{ - QList filterColumns = qxt_d().filters.keys(); - foreach(int currCol,filterColumns){ - QxtModelFilterPrivate filter = qxt_d().filters[currCol]; - // if the column specified by the user is -1 - // that means all columns need to pass the filter to get into the result - if (currCol == -1) { - int column_count = sourceModel()->columnCount(source_parent); - for (int column = 0; column < column_count; ++column) { - QModelIndex source_index = sourceModel()->index(source_row, column, source_parent); - QVariant key = sourceModel()->data(source_index, filter.m_role); - if (!filter.acceptsValue(key)) - return false; - } - continue; - } - QModelIndex source_index = sourceModel()->index(source_row, currCol , source_parent); - if (!source_index.isValid()) // the column may not exist - continue; - QVariant key = sourceModel()->data(source_index, filter.m_role); - if(!filter.acceptsValue(key)) - return false; - } - return true; -} - -/*! - \brief Sets the filter with \a value, \a role and \a flags to the given \a column - */ -void QxtSortFilterProxyModel::setFilter ( const int column, const QVariant &value, const int role, Qt::MatchFlags flags ) -{ - if(qxt_d().filters.contains(column)) - qxt_d().filters[column] = QxtModelFilterPrivate(value,role,flags); - else - qxt_d().filters.insert(column,QxtModelFilterPrivate(value,role,flags)); - - if(!qxt_d().m_declaringFilter) - invalidateFilter(); -} - -/*! - \brief Removes the filter from the given \a column - */ -void QxtSortFilterProxyModel::removeFilter ( const int column ) -{ - if(qxt_d().filters.contains(column)){ - qxt_d().filters.remove(column); - - if(!qxt_d().m_declaringFilter) - invalidateFilter(); - } -} - -/*! - \brief Sets the filter \a value for the given \a column - */ -void QxtSortFilterProxyModel::setFilterValue ( const int column , const QVariant &value ) -{ - if(qxt_d().filters.contains(column)) - qxt_d().filters[column].m_value = value; - else - qxt_d().filters.insert(column,QxtModelFilterPrivate(value)); - - if(!qxt_d().m_declaringFilter) - invalidateFilter(); -} - -/*! - \brief Sets the filter \a role for the given \a column - */ -void QxtSortFilterProxyModel::setFilterRole ( const int column , const int role ) -{ - if(qxt_d().filters.contains(column)) - qxt_d().filters[column].m_role=role; - else - qxt_d().filters.insert(column,QxtModelFilterPrivate(QVariant(),role)); - - if(!qxt_d().m_declaringFilter) - invalidateFilter(); -} - -/*! - \brief Sets the filter \a flags for the given \a column - */ -void QxtSortFilterProxyModel::setFilterFlags ( const int column , const Qt::MatchFlags flags ) -{ - if(qxt_d().filters.contains(column)) - qxt_d().filters[column].m_flags = flags; - else - qxt_d().filters.insert(column,QxtModelFilterPrivate(QVariant(),Qt::DisplayRole,flags)); - - if(!qxt_d().m_declaringFilter) - invalidateFilter(); -} - -/*! - \brief Returns the filter value for the given \a column - - \bold {Note:} if the column is not filtered it will return a null variant - */ -QVariant QxtSortFilterProxyModel::filterValue ( const int column ) const -{ - if(qxt_d().filters.contains(column)) - return qxt_d().filters[column].m_value; - return QVariant(); -} - -/*! - \brief Returns the filter role for the given \a column - - \bold {Note:} if the column is not filtered it will return \c -1 -*/ -int QxtSortFilterProxyModel::filterRole ( const int column ) const -{ - if(qxt_d().filters.contains(column)) - return qxt_d().filters[column].m_role; - return -1; -} - -/*! - \brief returns the filter flags for the given \a column - - \bold {Note:} if the column is not filtered it will return the default value - */ -Qt::MatchFlags QxtSortFilterProxyModel::filterFlags ( const int column ) const -{ - if(qxt_d().filters.contains(column)) - return qxt_d().filters[column].m_flags; - return Qt::MatchContains; -} - -/*! - Returns true if the \a column is filtered - */ -bool QxtSortFilterProxyModel::isFiltered ( const int column ) -{ - return qxt_d().filters.contains(column); -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ + +#include "qxtsortfilterproxymodel.h" +#include + +class QxtModelFilterPrivate +{ + public: + QxtModelFilterPrivate (const QVariant &value = QVariant(), const int role = Qt::DisplayRole, const Qt::MatchFlags flags = Qt::MatchContains); + bool acceptsValue ( const QVariant & value ); + QVariant m_value; + int m_role; + Qt::MatchFlags m_flags; +}; + +class QxtSortFilterProxyModelPrivate : public QxtPrivate +{ + public: + QMap filters; + bool m_declaringFilter; +}; + +QxtModelFilterPrivate::QxtModelFilterPrivate(const QVariant &value, const int role, const Qt::MatchFlags flags) + :m_value(value),m_role(role),m_flags(flags) +{ + +} + +bool QxtModelFilterPrivate::acceptsValue ( const QVariant & value ) +{ + uint matchType = m_flags & 0x0F; + //if we have no value we accept everything + if(!m_value.isValid() || !value.isValid()) + return true; + + // QVariant based matching + if (matchType == Qt::MatchExactly ){ + if(m_value == value) + return true; + } + // QString based matching + else { + Qt::CaseSensitivity cs = m_flags & Qt::MatchCaseSensitive ? Qt::CaseSensitive : Qt::CaseInsensitive; + QString filterText = m_value.toString(); + QString modelText = value.toString(); + switch (matchType){ + case Qt::MatchRegExp: + if (QRegExp(filterText, cs).exactMatch(modelText)) + return true; + break; + case Qt::MatchWildcard: + if (QRegExp(filterText, cs, QRegExp::Wildcard).exactMatch(modelText)) + return true; + break; + case Qt::MatchStartsWith: + if (modelText.startsWith(filterText, cs)) + return true; + break; + case Qt::MatchEndsWith: + if (modelText.endsWith(filterText, cs)) + return true; + break; + case Qt::MatchFixedString: + if (modelText.compare(filterText, cs) == 0) + return true; + break; + default: + case Qt::MatchContains: + if (modelText.contains(filterText, cs)) + return true; + } + } + return false; +} + +/*! + \class QxtSortFilterProxyModel + \inmodule QxtGui + \brief The QxtSortFilterProxyModel class is a multi column filter model. + + The QxtSortFilterProxyModel makes it possible to filter over multiple columns. + + \code + QxtSortFilterProxyModel * filterModel = new QxtSortFilterProxyModel(parent); + filterModel->setSourceModel(sourceModel); + filterModel->beginDeclareFilter(); + filterModel->setFilter(1,QVariant("SomeStringValue"),Qt::DisplayRole,Qt::MatchExactly); + //remove some old filter + filterModel->removeFilter(2); + filterModel->setFilter(5,QVariant(1234),Qt::DisplayRole,Qt::MatchExactly); + filterModel->endDeclateFilter(); + \endcode + + Now the model will filter column 1 and 5, to be accepted by the filtermodel a row needs to pass all filters +*/ + +/*! + Constructs a new QxtSortFilterProxyModel with \a parent. + */ +QxtSortFilterProxyModel::QxtSortFilterProxyModel ( QObject *parent) : QSortFilterProxyModel(parent) +{ + QXT_INIT_PRIVATE(QxtSortFilterProxyModel); + qxt_d().m_declaringFilter = false; +} + + +/*! + \brief tells the model you want to declare a new filter + + If you have a lot of data in your model it can be slow to declare more than one filter, + because the model will always rebuild itself. If you call this member before setting the + new filters the model will invalidate its contents not before you call + + \sa endDeclareFilter() + */ +void QxtSortFilterProxyModel::beginDeclareFilter ( ) +{ + qxt_d().m_declaringFilter = true; +} + +/*! + \brief stops the filter declaration and invalidates the filter + + \sa beginDeclareFilter() + */ +void QxtSortFilterProxyModel::endDeclareFilter ( ) +{ + if(qxt_d().m_declaringFilter){ + qxt_d().m_declaringFilter = false; + invalidateFilter(); + } +} + +/*! + \reimp + */ +bool QxtSortFilterProxyModel::filterAcceptsRow ( int source_row, const QModelIndex &source_parent ) const +{ + QList filterColumns = qxt_d().filters.keys(); + foreach(int currCol,filterColumns){ + QxtModelFilterPrivate filter = qxt_d().filters[currCol]; + // if the column specified by the user is -1 + // that means all columns need to pass the filter to get into the result + if (currCol == -1) { + int column_count = sourceModel()->columnCount(source_parent); + for (int column = 0; column < column_count; ++column) { + QModelIndex source_index = sourceModel()->index(source_row, column, source_parent); + QVariant key = sourceModel()->data(source_index, filter.m_role); + if (!filter.acceptsValue(key)) + return false; + } + continue; + } + QModelIndex source_index = sourceModel()->index(source_row, currCol , source_parent); + if (!source_index.isValid()) // the column may not exist + continue; + QVariant key = sourceModel()->data(source_index, filter.m_role); + if(!filter.acceptsValue(key)) + return false; + } + return true; +} + +/*! + \brief Sets the filter with \a value, \a role and \a flags to the given \a column + */ +void QxtSortFilterProxyModel::setFilter ( const int column, const QVariant &value, const int role, Qt::MatchFlags flags ) +{ + if(qxt_d().filters.contains(column)) + qxt_d().filters[column] = QxtModelFilterPrivate(value,role,flags); + else + qxt_d().filters.insert(column,QxtModelFilterPrivate(value,role,flags)); + + if(!qxt_d().m_declaringFilter) + invalidateFilter(); +} + +/*! + \brief Removes the filter from the given \a column + */ +void QxtSortFilterProxyModel::removeFilter ( const int column ) +{ + if(qxt_d().filters.contains(column)){ + qxt_d().filters.remove(column); + + if(!qxt_d().m_declaringFilter) + invalidateFilter(); + } +} + +/*! + \brief Sets the filter \a value for the given \a column + */ +void QxtSortFilterProxyModel::setFilterValue ( const int column , const QVariant &value ) +{ + if(qxt_d().filters.contains(column)) + qxt_d().filters[column].m_value = value; + else + qxt_d().filters.insert(column,QxtModelFilterPrivate(value)); + + if(!qxt_d().m_declaringFilter) + invalidateFilter(); +} + +/*! + \brief Sets the filter \a role for the given \a column + */ +void QxtSortFilterProxyModel::setFilterRole ( const int column , const int role ) +{ + if(qxt_d().filters.contains(column)) + qxt_d().filters[column].m_role=role; + else + qxt_d().filters.insert(column,QxtModelFilterPrivate(QVariant(),role)); + + if(!qxt_d().m_declaringFilter) + invalidateFilter(); +} + +/*! + \brief Sets the filter \a flags for the given \a column + */ +void QxtSortFilterProxyModel::setFilterFlags ( const int column , const Qt::MatchFlags flags ) +{ + if(qxt_d().filters.contains(column)) + qxt_d().filters[column].m_flags = flags; + else + qxt_d().filters.insert(column,QxtModelFilterPrivate(QVariant(),Qt::DisplayRole,flags)); + + if(!qxt_d().m_declaringFilter) + invalidateFilter(); +} + +/*! + \brief Returns the filter value for the given \a column + + \bold {Note:} if the column is not filtered it will return a null variant + */ +QVariant QxtSortFilterProxyModel::filterValue ( const int column ) const +{ + if(qxt_d().filters.contains(column)) + return qxt_d().filters[column].m_value; + return QVariant(); +} + +/*! + \brief Returns the filter role for the given \a column + + \bold {Note:} if the column is not filtered it will return \c -1 +*/ +int QxtSortFilterProxyModel::filterRole ( const int column ) const +{ + if(qxt_d().filters.contains(column)) + return qxt_d().filters[column].m_role; + return -1; +} + +/*! + \brief returns the filter flags for the given \a column + + \bold {Note:} if the column is not filtered it will return the default value + */ +Qt::MatchFlags QxtSortFilterProxyModel::filterFlags ( const int column ) const +{ + if(qxt_d().filters.contains(column)) + return qxt_d().filters[column].m_flags; + return Qt::MatchContains; +} + +/*! + Returns true if the \a column is filtered + */ +bool QxtSortFilterProxyModel::isFiltered ( const int column ) +{ + return qxt_d().filters.contains(column); +} diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtsortfilterproxymodel.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtsortfilterproxymodel.h index d1448a1db..d3943112e 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtsortfilterproxymodel.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtsortfilterproxymodel.h @@ -1,65 +1,65 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#ifndef QXTSORTFILTERPROXYMODEL_H -#define QXTSORTFILTERPROXYMODEL_H - -#include -#include -#include -#include - -#include "qxtglobal.h" - -class QxtSortFilterProxyModelPrivate; - -class QXT_GUI_EXPORT QxtSortFilterProxyModel : public QSortFilterProxyModel -{ - Q_OBJECT - -public: - QxtSortFilterProxyModel( QObject *parent = 0 ); - - void beginDeclareFilter( ); - void endDeclareFilter( ); - void setFilter( const int column, const QVariant &value, const int role = Qt::DisplayRole, Qt::MatchFlags flags = Qt::MatchContains ); - void setFilterValue( const int column, const QVariant &value ); - void setFilterRole( const int column, const int role = Qt::DisplayRole ); - void setFilterFlags( const int column, const Qt::MatchFlags flags = Qt::MatchContains ); - void removeFilter( const int column ); - - QVariant filterValue( const int column ) const; - int filterRole( const int column ) const; - Qt::MatchFlags filterFlags( const int column ) const; - - bool isFiltered( const int column ); - -protected: - virtual bool filterAcceptsRow( int source_row, const QModelIndex &source_parent ) const; - -private: - QXT_DECLARE_PRIVATE(QxtSortFilterProxyModel) -}; - -#endif // QXTSORTFILTERPROXYMODEL_H +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#ifndef QXTSORTFILTERPROXYMODEL_H +#define QXTSORTFILTERPROXYMODEL_H + +#include +#include +#include +#include + +#include "qxtglobal.h" + +class QxtSortFilterProxyModelPrivate; + +class QXT_GUI_EXPORT QxtSortFilterProxyModel : public QSortFilterProxyModel +{ + Q_OBJECT + +public: + QxtSortFilterProxyModel( QObject *parent = 0 ); + + void beginDeclareFilter( ); + void endDeclareFilter( ); + void setFilter( const int column, const QVariant &value, const int role = Qt::DisplayRole, Qt::MatchFlags flags = Qt::MatchContains ); + void setFilterValue( const int column, const QVariant &value ); + void setFilterRole( const int column, const int role = Qt::DisplayRole ); + void setFilterFlags( const int column, const Qt::MatchFlags flags = Qt::MatchContains ); + void removeFilter( const int column ); + + QVariant filterValue( const int column ) const; + int filterRole( const int column ) const; + Qt::MatchFlags filterFlags( const int column ) const; + + bool isFiltered( const int column ); + +protected: + virtual bool filterAcceptsRow( int source_row, const QModelIndex &source_parent ) const; + +private: + QXT_DECLARE_PRIVATE(QxtSortFilterProxyModel) +}; + +#endif // QXTSORTFILTERPROXYMODEL_H diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtstyleoptionscheduleviewitem.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtstyleoptionscheduleviewitem.cpp index 872f0f43b..9c7d47e8c 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtstyleoptionscheduleviewitem.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtstyleoptionscheduleviewitem.cpp @@ -1,41 +1,41 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ - -#include "qxtstyleoptionscheduleviewitem.h" - -QxtStyleOptionScheduleViewItem::QxtStyleOptionScheduleViewItem() - : QStyleOptionViewItem() -{ - //make qstyleoption_cast work - version = Version; - type = Type; -} - - -QxtStyleOptionScheduleViewItem::~QxtStyleOptionScheduleViewItem() -{ -} - - +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ + +#include "qxtstyleoptionscheduleviewitem.h" + +QxtStyleOptionScheduleViewItem::QxtStyleOptionScheduleViewItem() + : QStyleOptionViewItem() +{ + //make qstyleoption_cast work + version = Version; + type = Type; +} + + +QxtStyleOptionScheduleViewItem::~QxtStyleOptionScheduleViewItem() +{ +} + + diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtstyleoptionscheduleviewitem.h b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtstyleoptionscheduleviewitem.h index 4f9b94151..fc5b1b91a 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtstyleoptionscheduleviewitem.h +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtstyleoptionscheduleviewitem.h @@ -1,56 +1,56 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#ifndef QXTSTYLEOPTIONSCHEDULEVIEWITEM_H -#define QXTSTYLEOPTIONSCHEDULEVIEWITEM_H - -#include -#include -#include -#include - - -/*! - @author Benjamin Zeller -*/ -class QxtStyleOptionScheduleViewItem : public QStyleOptionViewItem -{ -public: - QxtStyleOptionScheduleViewItem(); - ~QxtStyleOptionScheduleViewItem(); - - enum StyleOptionType { Type = QStyleOption::SO_CustomBase }; - enum StyleOptionVersion { Version = 1 }; - - - QVector itemGeometries; - mutable QVector *itemPaintCache; - QPoint translate; - int roundCornersRadius; - int itemHeaderHeight; - int maxSubItemHeight; - -}; - -#endif +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#ifndef QXTSTYLEOPTIONSCHEDULEVIEWITEM_H +#define QXTSTYLEOPTIONSCHEDULEVIEWITEM_H + +#include +#include +#include +#include + + +/*! + @author Benjamin Zeller +*/ +class QxtStyleOptionScheduleViewItem : public QStyleOptionViewItem +{ +public: + QxtStyleOptionScheduleViewItem(); + ~QxtStyleOptionScheduleViewItem(); + + enum StyleOptionType { Type = QStyleOption::SO_CustomBase }; + enum StyleOptionVersion { Version = 1 }; + + + QVector itemGeometries; + mutable QVector *itemPaintCache; + QPoint translate; + int roundCornersRadius; + int itemHeaderHeight; + int maxSubItemHeight; + +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtwindowsystem_x11.cpp b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtwindowsystem_x11.cpp index c57120ebe..fe08302ba 100644 --- a/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtwindowsystem_x11.cpp +++ b/ground/openpilotgcs/src/libs/libqxt/src/gui/qxtwindowsystem_x11.cpp @@ -1,182 +1,182 @@ -/**************************************************************************** - ** - ** Copyright (C) Qxt Foundation. Some rights reserved. - ** - ** This file is part of the QxtGui module of the Qxt library. - ** - ** This library is free software; you can redistribute it and/or modify it - ** under the terms of the Common Public License, version 1.0, as published - ** by IBM, and/or under the terms of the GNU Lesser General Public License, - ** version 2.1, as published by the Free Software Foundation. - ** - ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY - ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY - ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR - ** FITNESS FOR A PARTICULAR PURPOSE. - ** - ** You should have received a copy of the CPL and the LGPL along with this - ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files - ** included with the source distribution for more information. - ** If you did not receive a copy of the licenses, contact the Qxt Foundation. - ** - ** - ** - ****************************************************************************/ -#include "qxtwindowsystem.h" -#include -#include -#include - -static void qxt_getWindowProperty(Window wid, Atom prop, int maxlen, Window** data, int* count) -{ - Atom type = 0; - int format = 0; - unsigned long after = 0; - XGetWindowProperty(QX11Info::display(), wid, prop, 0, maxlen / 4, False, AnyPropertyType, - &type, &format, (unsigned long*) count, &after, (unsigned char**) data); -} - -static QRect qxt_getWindowRect(Window wid) -{ - QRect rect; - XWindowAttributes attr; - if (XGetWindowAttributes(QX11Info::display(), wid, &attr)) - { - rect = QRect(attr.x, attr.y, attr.width, attr.height); - } - return rect; -} - -WindowList QxtWindowSystem::windows() -{ - static Atom net_clients = 0; - if (!net_clients) - net_clients = XInternAtom(QX11Info::display(), "_NET_CLIENT_LIST_STACKING", True); - - int count = 0; - Window* list = 0; - qxt_getWindowProperty(QX11Info::appRootWindow(), net_clients, 1024 * sizeof(Window), &list, &count); - - WindowList res; - for (int i = 0; i < count; ++i) - res += list[i]; - XFree(list); - return res; -} - -WId QxtWindowSystem::activeWindow() -{ - Window focus; - int revert = 0; - Display* display = QX11Info::display(); - XGetInputFocus(display, &focus, &revert); - return focus; -} - -WId QxtWindowSystem::findWindow(const QString& title) -{ - Window result = 0; - WindowList list = windows(); - foreach(const Window &wid, list) - { - if (windowTitle(wid) == title) - { - result = wid; - break; - } - } - return result; -} - -WId QxtWindowSystem::windowAt(const QPoint& pos) -{ - Window result = 0; - WindowList list = windows(); - for (int i = list.size() - 1; i >= 0; --i) - { - WId wid = list.at(i); - if (windowGeometry(wid).contains(pos)) - { - result = wid; - break; - } - } - return result; -} - -QString QxtWindowSystem::windowTitle(WId window) -{ - QString name; - char* str = 0; - if (XFetchName(QX11Info::display(), window, &str)) - { - name = QString::fromLatin1(str); - } - XFree(str); - return name; -} - -QRect QxtWindowSystem::windowGeometry(WId window) -{ - QRect rect = qxt_getWindowRect(window); - - Window root = 0; - Window parent = 0; - Window* children = 0; - unsigned int count = 0; - Display* display = QX11Info::display(); - if (XQueryTree(display, window, &root, &parent, &children, &count)) - { - window = parent; // exclude decoration - XFree(children); - while (window != 0 && XQueryTree(display, window, &root, &parent, &children, &count)) - { - XWindowAttributes attr; - if (parent != 0 && XGetWindowAttributes(display, parent, &attr)) - rect.translate(QRect(attr.x, attr.y, attr.width, attr.height).topLeft()); - window = parent; - XFree(children); - } - } - return rect; -} - -typedef struct { - Window window; /* screen saver window - may not exist */ - int state; /* ScreenSaverOff, ScreenSaverOn, ScreenSaverDisabled*/ - int kind; /* ScreenSaverBlanked, ...Internal, ...External */ - unsigned long til_or_since; /* time til or since screen saver */ - unsigned long idle; /* total time since last user input */ - unsigned long eventMask; /* currently selected events for this client */ -} XScreenSaverInfo; - -typedef XScreenSaverInfo* (*XScreenSaverAllocInfo)(); -typedef Status (*XScreenSaverQueryInfo)(Display* display, Drawable* drawable, XScreenSaverInfo* info); - -static XScreenSaverAllocInfo _xScreenSaverAllocInfo = 0; -static XScreenSaverQueryInfo _xScreenSaverQueryInfo = 0; - -uint QxtWindowSystem::idleTime() -{ - static bool xssResolved = false; - if (!xssResolved) { - QLibrary xssLib(QLatin1String("Xss"), 1); - if (xssLib.load()) { - _xScreenSaverAllocInfo = (XScreenSaverAllocInfo) xssLib.resolve("XScreenSaverAllocInfo"); - _xScreenSaverQueryInfo = (XScreenSaverQueryInfo) xssLib.resolve("XScreenSaverQueryInfo"); - xssResolved = true; - } - } - - uint idle = 0; - if (xssResolved) - { - XScreenSaverInfo* info = _xScreenSaverAllocInfo(); - const int screen = QX11Info::appScreen(); - Qt::HANDLE rootWindow = QX11Info::appRootWindow(screen); - _xScreenSaverQueryInfo(QX11Info::display(), (Drawable*) rootWindow, info); - idle = info->idle; - XFree(info); - } - return idle; -} +/**************************************************************************** + ** + ** Copyright (C) Qxt Foundation. Some rights reserved. + ** + ** This file is part of the QxtGui module of the Qxt library. + ** + ** This library is free software; you can redistribute it and/or modify it + ** under the terms of the Common Public License, version 1.0, as published + ** by IBM, and/or under the terms of the GNU Lesser General Public License, + ** version 2.1, as published by the Free Software Foundation. + ** + ** This file is provided "AS IS", without WARRANTIES OR CONDITIONS OF ANY + ** KIND, EITHER EXPRESS OR IMPLIED INCLUDING, WITHOUT LIMITATION, ANY + ** WARRANTIES OR CONDITIONS OF TITLE, NON-INFRINGEMENT, MERCHANTABILITY OR + ** FITNESS FOR A PARTICULAR PURPOSE. + ** + ** You should have received a copy of the CPL and the LGPL along with this + ** file. See the LICENSE file and the cpl1.0.txt/lgpl-2.1.txt files + ** included with the source distribution for more information. + ** If you did not receive a copy of the licenses, contact the Qxt Foundation. + ** + ** + ** + ****************************************************************************/ +#include "qxtwindowsystem.h" +#include +#include +#include + +static void qxt_getWindowProperty(Window wid, Atom prop, int maxlen, Window** data, int* count) +{ + Atom type = 0; + int format = 0; + unsigned long after = 0; + XGetWindowProperty(QX11Info::display(), wid, prop, 0, maxlen / 4, False, AnyPropertyType, + &type, &format, (unsigned long*) count, &after, (unsigned char**) data); +} + +static QRect qxt_getWindowRect(Window wid) +{ + QRect rect; + XWindowAttributes attr; + if (XGetWindowAttributes(QX11Info::display(), wid, &attr)) + { + rect = QRect(attr.x, attr.y, attr.width, attr.height); + } + return rect; +} + +WindowList QxtWindowSystem::windows() +{ + static Atom net_clients = 0; + if (!net_clients) + net_clients = XInternAtom(QX11Info::display(), "_NET_CLIENT_LIST_STACKING", True); + + int count = 0; + Window* list = 0; + qxt_getWindowProperty(QX11Info::appRootWindow(), net_clients, 1024 * sizeof(Window), &list, &count); + + WindowList res; + for (int i = 0; i < count; ++i) + res += list[i]; + XFree(list); + return res; +} + +WId QxtWindowSystem::activeWindow() +{ + Window focus; + int revert = 0; + Display* display = QX11Info::display(); + XGetInputFocus(display, &focus, &revert); + return focus; +} + +WId QxtWindowSystem::findWindow(const QString& title) +{ + Window result = 0; + WindowList list = windows(); + foreach(const Window &wid, list) + { + if (windowTitle(wid) == title) + { + result = wid; + break; + } + } + return result; +} + +WId QxtWindowSystem::windowAt(const QPoint& pos) +{ + Window result = 0; + WindowList list = windows(); + for (int i = list.size() - 1; i >= 0; --i) + { + WId wid = list.at(i); + if (windowGeometry(wid).contains(pos)) + { + result = wid; + break; + } + } + return result; +} + +QString QxtWindowSystem::windowTitle(WId window) +{ + QString name; + char* str = 0; + if (XFetchName(QX11Info::display(), window, &str)) + { + name = QString::fromLatin1(str); + } + XFree(str); + return name; +} + +QRect QxtWindowSystem::windowGeometry(WId window) +{ + QRect rect = qxt_getWindowRect(window); + + Window root = 0; + Window parent = 0; + Window* children = 0; + unsigned int count = 0; + Display* display = QX11Info::display(); + if (XQueryTree(display, window, &root, &parent, &children, &count)) + { + window = parent; // exclude decoration + XFree(children); + while (window != 0 && XQueryTree(display, window, &root, &parent, &children, &count)) + { + XWindowAttributes attr; + if (parent != 0 && XGetWindowAttributes(display, parent, &attr)) + rect.translate(QRect(attr.x, attr.y, attr.width, attr.height).topLeft()); + window = parent; + XFree(children); + } + } + return rect; +} + +typedef struct { + Window window; /* screen saver window - may not exist */ + int state; /* ScreenSaverOff, ScreenSaverOn, ScreenSaverDisabled*/ + int kind; /* ScreenSaverBlanked, ...Internal, ...External */ + unsigned long til_or_since; /* time til or since screen saver */ + unsigned long idle; /* total time since last user input */ + unsigned long eventMask; /* currently selected events for this client */ +} XScreenSaverInfo; + +typedef XScreenSaverInfo* (*XScreenSaverAllocInfo)(); +typedef Status (*XScreenSaverQueryInfo)(Display* display, Drawable* drawable, XScreenSaverInfo* info); + +static XScreenSaverAllocInfo _xScreenSaverAllocInfo = 0; +static XScreenSaverQueryInfo _xScreenSaverQueryInfo = 0; + +uint QxtWindowSystem::idleTime() +{ + static bool xssResolved = false; + if (!xssResolved) { + QLibrary xssLib(QLatin1String("Xss"), 1); + if (xssLib.load()) { + _xScreenSaverAllocInfo = (XScreenSaverAllocInfo) xssLib.resolve("XScreenSaverAllocInfo"); + _xScreenSaverQueryInfo = (XScreenSaverQueryInfo) xssLib.resolve("XScreenSaverQueryInfo"); + xssResolved = true; + } + } + + uint idle = 0; + if (xssResolved) + { + XScreenSaverInfo* info = _xScreenSaverAllocInfo(); + const int screen = QX11Info::appScreen(); + Qt::HANDLE rootWindow = QX11Info::appRootWindow(screen); + _xScreenSaverQueryInfo(QX11Info::display(), (Drawable*) rootWindow, info); + idle = info->idle; + XFree(info); + } + return idle; +} diff --git a/ground/openpilotgcs/src/libs/libs.pro b/ground/openpilotgcs/src/libs/libs.pro index af3aaca8c..07227ff14 100644 --- a/ground/openpilotgcs/src/libs/libs.pro +++ b/ground/openpilotgcs/src/libs/libs.pro @@ -1,17 +1,17 @@ -TEMPLATE = subdirs -CONFIG += ordered - -SUBDIRS = \ - qscispinbox\ - qtconcurrent \ - aggregation \ - extensionsystem \ - utils \ - opmapcontrol \ - qwt \ - qextserialport \ - glc_lib\ - sdlgamepad \ - libqxt - -SUBDIRS += +TEMPLATE = subdirs +CONFIG += ordered + +SUBDIRS = \ + qscispinbox\ + qtconcurrent \ + aggregation \ + extensionsystem \ + utils \ + opmapcontrol \ + qwt \ + qextserialport \ + glc_lib\ + sdlgamepad \ + libqxt + +SUBDIRS += diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/common.pri b/ground/openpilotgcs/src/libs/opmapcontrol/src/common.pri index 6907c6f63..a7889f5e8 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/common.pri +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/common.pri @@ -1,10 +1,10 @@ -DESTDIR = ../build - -QT += network -QT += sql -CONFIG += staticlib -TEMPLATE = lib -UI_DIR = uics -MOC_DIR = mocs -OBJECTS_DIR = objs -INCLUDEPATH +=../../../../libs/ +DESTDIR = ../build + +QT += network +QT += sql +CONFIG += staticlib +TEMPLATE = lib +UI_DIR = uics +MOC_DIR = mocs +OBJECTS_DIR = objs +INCLUDEPATH +=../../../../libs/ diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/accessmode.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/accessmode.h index f81efa710..a2022e653 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/accessmode.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/accessmode.h @@ -1,86 +1,86 @@ -/** -****************************************************************************** -* -* @file accessmode.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef ACCESSMODE_H -#define ACCESSMODE_H - -#include "debugheader.h" -#include -#include -#include -#include -namespace core { - class AccessMode:public QObject - { - Q_OBJECT - Q_ENUMS(Types) - public: - enum Types - { - /// - /// access only server - /// - ServerOnly, - - /// - /// access first server and caches localy - /// - ServerAndCache, - - /// - /// access only cache - /// - CacheOnly - }; - static QString StrByType(Types const& value) - { - QMetaObject metaObject = AccessMode().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - QString s=metaEnum.valueToKey(value); - return s; - } - static Types TypeByStr(QString const& value) - { - QMetaObject metaObject = AccessMode().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - Types s=(Types)metaEnum.keyToValue(value.toLatin1()); - return s; - } - static QStringList TypesList() - { - QStringList ret; - QMetaObject metaObject = AccessMode().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - for(int x=0;x +#include +#include +#include +namespace core { + class AccessMode:public QObject + { + Q_OBJECT + Q_ENUMS(Types) + public: + enum Types + { + /// + /// access only server + /// + ServerOnly, + + /// + /// access first server and caches localy + /// + ServerAndCache, + + /// + /// access only cache + /// + CacheOnly + }; + static QString StrByType(Types const& value) + { + QMetaObject metaObject = AccessMode().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + QString s=metaEnum.valueToKey(value); + return s; + } + static Types TypeByStr(QString const& value) + { + QMetaObject metaObject = AccessMode().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + Types s=(Types)metaEnum.keyToValue(value.toLatin1()); + return s; + } + static QStringList TypesList() + { + QStringList ret; + QMetaObject metaObject = AccessMode().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + for(int x=0;x AllLayersOfType::GetAllLayersOfType(const MapType::Types &type) - { - QVector types; - { - switch(type) - { - case MapType::GoogleHybrid: - { - - types.append(MapType::GoogleSatellite); - types.append(MapType::GoogleLabels); - } - break; - - case MapType::GoogleHybridChina: - { - types.append(MapType::GoogleSatelliteChina); - types.append(MapType::GoogleLabelsChina); - } - break; - - case MapType::GoogleHybridKorea: - { - types.append(MapType::GoogleSatelliteKorea); - types.append(MapType::GoogleLabelsKorea); - } - break; - - case MapType::YahooHybrid: - { - types.append(MapType::YahooSatellite); - types.append(MapType::YahooLabels); - } - break; - - case MapType::ArcGIS_MapsLT_Map_Hybrid: - { - types.append(MapType::ArcGIS_MapsLT_OrtoFoto); - types.append(MapType::ArcGIS_MapsLT_Map_Labels); - } - break; - - default: - { - types.append(type); - } - break; - } - } - - return types; - - } -} +/** +****************************************************************************** +* +* @file alllayersoftype.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "alllayersoftype.h" + +namespace core { + AllLayersOfType::AllLayersOfType() + { + + } + QVector AllLayersOfType::GetAllLayersOfType(const MapType::Types &type) + { + QVector types; + { + switch(type) + { + case MapType::GoogleHybrid: + { + + types.append(MapType::GoogleSatellite); + types.append(MapType::GoogleLabels); + } + break; + + case MapType::GoogleHybridChina: + { + types.append(MapType::GoogleSatelliteChina); + types.append(MapType::GoogleLabelsChina); + } + break; + + case MapType::GoogleHybridKorea: + { + types.append(MapType::GoogleSatelliteKorea); + types.append(MapType::GoogleLabelsKorea); + } + break; + + case MapType::YahooHybrid: + { + types.append(MapType::YahooSatellite); + types.append(MapType::YahooLabels); + } + break; + + case MapType::ArcGIS_MapsLT_Map_Hybrid: + { + types.append(MapType::ArcGIS_MapsLT_OrtoFoto); + types.append(MapType::ArcGIS_MapsLT_Map_Labels); + } + break; + + default: + { + types.append(type); + } + break; + } + } + + return types; + + } +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.h index 3f351e83d..0c45bc7fe 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/alllayersoftype.h @@ -1,43 +1,43 @@ -/** -****************************************************************************** -* -* @file alllayersoftype.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef ALLLAYERSOFTYPE_H -#define ALLLAYERSOFTYPE_H - -#include "maptype.h" -#include -#include - -namespace core { - class AllLayersOfType - { - public: - AllLayersOfType(); - QVector GetAllLayersOfType(const MapType::Types &type); - }; - -} -#endif // ALLLAYERSOFTYPE_H +/** +****************************************************************************** +* +* @file alllayersoftype.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef ALLLAYERSOFTYPE_H +#define ALLLAYERSOFTYPE_H + +#include "maptype.h" +#include +#include + +namespace core { + class AllLayersOfType + { + public: + AllLayersOfType(); + QVector GetAllLayersOfType(const MapType::Types &type); + }; + +} +#endif // ALLLAYERSOFTYPE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.h index 8811d4ae7..3cbddf34f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cache.h @@ -1,62 +1,62 @@ -/** -****************************************************************************** -* -* @file cache.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef CACHE_H -#define CACHE_H - -#include "pureimagecache.h" -#include "debugheader.h" - -namespace core { - class Cache - { - public: - static Cache* Instance(); - - - PureImageCache ImageCache; - QString CacheLocation(); - void setCacheLocation(const QString& value); - void CacheGeocoder(const QString &urlEnd,const QString &content); - QString GetGeocoderFromCache(const QString &urlEnd); - void CachePlacemark(const QString &urlEnd,const QString &content); - QString GetPlacemarkFromCache(const QString &urlEnd); - void CacheRoute(const QString &urlEnd,const QString &content); - QString GetRouteFromCache(const QString &urlEnd); - - private: - Cache(); - Cache(Cache const&){} - Cache& operator=(Cache const&){ return *this; } - static Cache* m_pInstance; - QString cache; - QString routeCache; - QString geoCache; - QString placemarkCache; - }; - -} -#endif // CACHE_H +/** +****************************************************************************** +* +* @file cache.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef CACHE_H +#define CACHE_H + +#include "pureimagecache.h" +#include "debugheader.h" + +namespace core { + class Cache + { + public: + static Cache* Instance(); + + + PureImageCache ImageCache; + QString CacheLocation(); + void setCacheLocation(const QString& value); + void CacheGeocoder(const QString &urlEnd,const QString &content); + QString GetGeocoderFromCache(const QString &urlEnd); + void CachePlacemark(const QString &urlEnd,const QString &content); + QString GetPlacemarkFromCache(const QString &urlEnd); + void CacheRoute(const QString &urlEnd,const QString &content); + QString GetRouteFromCache(const QString &urlEnd); + + private: + Cache(); + Cache(Cache const&){} + Cache& operator=(Cache const&){ return *this; } + static Cache* m_pInstance; + QString cache; + QString routeCache; + QString geoCache; + QString placemarkCache; + }; + +} +#endif // CACHE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.cpp index 1d7d2b1cd..7d1f1d661 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.cpp @@ -1,79 +1,79 @@ -/** -****************************************************************************** -* -* @file cacheitemqueue.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "cacheitemqueue.h" - - -namespace core { - CacheItemQueue::CacheItemQueue(const MapType::Types &Type, const Point &Pos, const QByteArray &Img, const int &Zoom) - { - type=Type; - pos=Pos; - img=Img; - zoom=Zoom; - - } - - QByteArray CacheItemQueue::GetImg() - { - return img; - } - - MapType::Types CacheItemQueue::GetMapType() - { - return type; - } - Point CacheItemQueue::GetPosition() - { - return pos; - } - void CacheItemQueue::SetImg(const QByteArray &value) - { - img=value; - } - void CacheItemQueue::SetMapType(const MapType::Types &value) - { - type=value; - } - void CacheItemQueue::SetPosition(const Point &value) - { - pos=value; - } - - CacheItemQueue& CacheItemQueue::operator =(const CacheItemQueue &cSource) - { - img=cSource.img; - pos=cSource.pos; - type=cSource.type; - zoom=cSource.zoom; - return *this; - } - bool CacheItemQueue::operator ==(const CacheItemQueue &cSource) - { - bool b=(img==cSource.img)&& (pos==cSource.pos) && (type==cSource.type) && (zoom==cSource.zoom); - return b; - } -} +/** +****************************************************************************** +* +* @file cacheitemqueue.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "cacheitemqueue.h" + + +namespace core { + CacheItemQueue::CacheItemQueue(const MapType::Types &Type, const Point &Pos, const QByteArray &Img, const int &Zoom) + { + type=Type; + pos=Pos; + img=Img; + zoom=Zoom; + + } + + QByteArray CacheItemQueue::GetImg() + { + return img; + } + + MapType::Types CacheItemQueue::GetMapType() + { + return type; + } + Point CacheItemQueue::GetPosition() + { + return pos; + } + void CacheItemQueue::SetImg(const QByteArray &value) + { + img=value; + } + void CacheItemQueue::SetMapType(const MapType::Types &value) + { + type=value; + } + void CacheItemQueue::SetPosition(const Point &value) + { + pos=value; + } + + CacheItemQueue& CacheItemQueue::operator =(const CacheItemQueue &cSource) + { + img=cSource.img; + pos=cSource.pos; + type=cSource.type; + zoom=cSource.zoom; + return *this; + } + bool CacheItemQueue::operator ==(const CacheItemQueue &cSource) + { + bool b=(img==cSource.img)&& (pos==cSource.pos) && (type==cSource.type) && (zoom==cSource.zoom); + return b; + } +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.h index 89676624b..786fb5d5c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/cacheitemqueue.h @@ -1,69 +1,69 @@ -/** -****************************************************************************** -* -* @file cacheitemqueue.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef CACHEITEMQUEUE_H -#define CACHEITEMQUEUE_H - -#include "maptype.h" -#include "point.h" -#include - - - -namespace core { - class CacheItemQueue - { - public: - CacheItemQueue(const MapType::Types &Type,const core::Point &Pos,const QByteArray &Img,const int &Zoom); - CacheItemQueue(){}; - CacheItemQueue(const CacheItemQueue &cSource) - { - img=cSource.img; - pos=cSource.pos; - type=cSource.type; - zoom=cSource.zoom; - } - CacheItemQueue& operator= (const CacheItemQueue &cSource); - bool operator== (const CacheItemQueue &cSource); - void SetMapType(const MapType::Types &value); - void SetPosition(const core::Point &value); - void SetImg(const QByteArray &value); - MapType::Types GetMapType(); - core::Point GetPosition(); - QByteArray GetImg(); - int GetZoom(){return zoom;}; - void SetZoom(const int &value) {zoom=value;}; - private: - - - MapType::Types type; - core::Point pos; - QByteArray img; - int zoom; - }; - -} -#endif // CACHEITEMQUEUE_H +/** +****************************************************************************** +* +* @file cacheitemqueue.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef CACHEITEMQUEUE_H +#define CACHEITEMQUEUE_H + +#include "maptype.h" +#include "point.h" +#include + + + +namespace core { + class CacheItemQueue + { + public: + CacheItemQueue(const MapType::Types &Type,const core::Point &Pos,const QByteArray &Img,const int &Zoom); + CacheItemQueue(){}; + CacheItemQueue(const CacheItemQueue &cSource) + { + img=cSource.img; + pos=cSource.pos; + type=cSource.type; + zoom=cSource.zoom; + } + CacheItemQueue& operator= (const CacheItemQueue &cSource); + bool operator== (const CacheItemQueue &cSource); + void SetMapType(const MapType::Types &value); + void SetPosition(const core::Point &value); + void SetImg(const QByteArray &value); + MapType::Types GetMapType(); + core::Point GetPosition(); + QByteArray GetImg(); + int GetZoom(){return zoom;}; + void SetZoom(const int &value) {zoom=value;}; + private: + + + MapType::Types type; + core::Point pos; + QByteArray img; + int zoom; + }; + +} +#endif // CACHEITEMQUEUE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/core.pro b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/core.pro index 9c355e3ca..d606082a1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/core.pro +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/core.pro @@ -1,40 +1,40 @@ -include (../common.pri) - -SOURCES += opmaps.cpp \ - pureimagecache.cpp \ - pureimage.cpp \ - rawtile.cpp \ - memorycache.cpp \ - cache.cpp \ - languagetype.cpp \ - providerstrings.cpp \ - cacheitemqueue.cpp \ - tilecachequeue.cpp \ - alllayersoftype.cpp \ - urlfactory.cpp \ - placemark.cpp \ - point.cpp \ - size.cpp \ - kibertilecache.cpp \ - diagnostics.cpp -HEADERS += opmaps.h \ - size.h \ - maptype.h \ - pureimagecache.h \ - pureimage.h \ - rawtile.h \ - memorycache.h \ - cache.h \ - accessmode.h \ - languagetype.h \ - providerstrings.h \ - cacheitemqueue.h \ - tilecachequeue.h \ - alllayersoftype.h \ - urlfactory.h \ - geodecoderstatus.h \ - placemark.h \ - point.h \ - kibertilecache.h \ - debugheader.h \ - diagnostics.h +include (../common.pri) + +SOURCES += opmaps.cpp \ + pureimagecache.cpp \ + pureimage.cpp \ + rawtile.cpp \ + memorycache.cpp \ + cache.cpp \ + languagetype.cpp \ + providerstrings.cpp \ + cacheitemqueue.cpp \ + tilecachequeue.cpp \ + alllayersoftype.cpp \ + urlfactory.cpp \ + placemark.cpp \ + point.cpp \ + size.cpp \ + kibertilecache.cpp \ + diagnostics.cpp +HEADERS += opmaps.h \ + size.h \ + maptype.h \ + pureimagecache.h \ + pureimage.h \ + rawtile.h \ + memorycache.h \ + cache.h \ + accessmode.h \ + languagetype.h \ + providerstrings.h \ + cacheitemqueue.h \ + tilecachequeue.h \ + alllayersoftype.h \ + urlfactory.h \ + geodecoderstatus.h \ + placemark.h \ + point.h \ + kibertilecache.h \ + debugheader.h \ + diagnostics.h diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/debugheader.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/debugheader.h index 0e1f73195..9b410c9c2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/debugheader.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/debugheader.h @@ -1,13 +1,13 @@ -#ifndef DEBUGHEADER_H -#define DEBUGHEADER_H - -//#define DEBUG_MEMORY_CACHE -//#define DEBUG_CACHE -//#define DEBUG_GMAPS -//#define DEBUG_PUREIMAGECACHE -//#define DEBUG_TILECACHEQUEUE -//#define DEBUG_URLFACTORY -//#define DEBUG_MEMORY_CACHE -//#define DEBUG_GetGeocoderFromCache - -#endif // DEBUGHEADER_H +#ifndef DEBUGHEADER_H +#define DEBUGHEADER_H + +//#define DEBUG_MEMORY_CACHE +//#define DEBUG_CACHE +//#define DEBUG_GMAPS +//#define DEBUG_PUREIMAGECACHE +//#define DEBUG_TILECACHEQUEUE +//#define DEBUG_URLFACTORY +//#define DEBUG_MEMORY_CACHE +//#define DEBUG_GetGeocoderFromCache + +#endif // DEBUGHEADER_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.cpp index eb345a2c8..ea2242651 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.cpp @@ -1,31 +1,31 @@ -/** -****************************************************************************** -* -* @file diagnostics.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "diagnostics.h" - -diagnostics::diagnostics():networkerrors(0),emptytiles(0),timeouts(0),runningThreads(0),tilesFromMem(0),tilesFromNet(0),tilesFromDB(0) -{ -} +/** +****************************************************************************** +* +* @file diagnostics.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "diagnostics.h" + +diagnostics::diagnostics():networkerrors(0),emptytiles(0),timeouts(0),runningThreads(0),tilesFromMem(0),tilesFromNet(0),tilesFromDB(0) +{ +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.h index 07269b5fa..f9c503b97 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/diagnostics.h @@ -1,47 +1,47 @@ -/** -****************************************************************************** -* -* @file diagnostics.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef DIAGNOSTICS_H -#define DIAGNOSTICS_H -#include -struct diagnostics -{ - diagnostics(); - int networkerrors; - int emptytiles; - int timeouts; - int runningThreads; - int tilesFromMem; - int tilesFromNet; - int tilesFromDB; - QString toString() - { - return QString("Network errors:%1\nEmpty Tiles:%2\nTimeOuts:%3\nRunningThreads:%4\nTilesFromMem:%5\nTilesFromNet:%6\nTilesFromDB:%7").arg(networkerrors).arg(emptytiles).arg(timeouts).arg(runningThreads).arg(tilesFromMem).arg(tilesFromNet).arg(tilesFromDB); - ; - } -}; - -#endif // DIAGNOSTICS_H +/** +****************************************************************************** +* +* @file diagnostics.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef DIAGNOSTICS_H +#define DIAGNOSTICS_H +#include +struct diagnostics +{ + diagnostics(); + int networkerrors; + int emptytiles; + int timeouts; + int runningThreads; + int tilesFromMem; + int tilesFromNet; + int tilesFromDB; + QString toString() + { + return QString("Network errors:%1\nEmpty Tiles:%2\nTimeOuts:%3\nRunningThreads:%4\nTilesFromMem:%5\nTilesFromNet:%6\nTilesFromDB:%7").arg(networkerrors).arg(emptytiles).arg(timeouts).arg(runningThreads).arg(tilesFromMem).arg(tilesFromNet).arg(tilesFromDB); + ; + } +}; + +#endif // DIAGNOSTICS_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/geodecoderstatus.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/geodecoderstatus.h index 53e4b0c70..66fe1e56e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/geodecoderstatus.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/geodecoderstatus.h @@ -1,131 +1,131 @@ -/** -****************************************************************************** -* -* @file geodecoderstatus.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef GEODECODERSTATUS_H -#define GEODECODERSTATUS_H - -#include -#include -#include -#include -namespace core { - class GeoCoderStatusCode:public QObject - { - Q_OBJECT - Q_ENUMS(Types) - public: - enum Types - { - /// - /// unknow response - /// - Unknow = -1, - - /// - /// No errors occurred; the address was successfully parsed and its geocode has been returned. - /// - G_GEO_SUCCESS=200, - - /// - /// A directions request could not be successfully parsed. - /// For example, the request may have been rejected if it contained more than the maximum number of waypoints allowed. - /// - G_GEO_BAD_REQUEST=400, - - /// - /// A geocoding or directions request could not be successfully processed, yet the exact reason for the failure is not known. - /// - G_GEO_SERVER_ERROR=500, - - /// - /// The HTTP q parameter was either missing or had no value. - /// For geocoding requests, this means that an empty address was specified as input. For directions requests, this means that no query was specified in the input. - /// - G_GEO_MISSING_QUERY=601, - - /// - /// Synonym for G_GEO_MISSING_QUERY. - /// - G_GEO_MISSING_ADDRESS=601, - - /// - /// No corresponding geographic location could be found for the specified address. - /// This may be due to the fact that the address is relatively new, or it may be incorrect. - /// - G_GEO_UNKNOWN_ADDRESS=602, - - /// - /// The geocode for the given address or the route for the given directions query cannot be returned due to legal or contractual reasons. - /// - G_GEO_UNAVAILABLE_ADDRESS=603, - - /// - /// The GDirections object could not compute directions between the points mentioned in the query. - /// This is usually because there is no route available between the two points, or because we do not have data for routing in that region. - /// - G_GEO_UNKNOWN_DIRECTIONS=604, - - /// - /// The given key is either invalid or does not match the domain for which it was given. - /// - G_GEO_BAD_KEY=610, - - /// - /// The given key has gone over the requests limit in the 24 hour period or has submitted too many requests in too short a period of time. - /// If you're sending multiple requests in parallel or in a tight loop, use a timer or pause in your code to make sure you don't send the requests too quickly. - /// - G_GEO_TOO_MANY_QUERIES=620 - - }; - static QString StrByType(Types const& value) - { - QMetaObject metaObject = GeoCoderStatusCode().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - QString s=metaEnum.valueToKey(value); - return s; - } - static Types TypeByStr(QString const& value) - { - QMetaObject metaObject = GeoCoderStatusCode().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - Types s=(Types)metaEnum.keyToValue(value.toLatin1()); - return s; - } - static QStringList TypesList() - { - QStringList ret; - QMetaObject metaObject = GeoCoderStatusCode().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - for(int x=0;x +#include +#include +#include +namespace core { + class GeoCoderStatusCode:public QObject + { + Q_OBJECT + Q_ENUMS(Types) + public: + enum Types + { + /// + /// unknow response + /// + Unknow = -1, + + /// + /// No errors occurred; the address was successfully parsed and its geocode has been returned. + /// + G_GEO_SUCCESS=200, + + /// + /// A directions request could not be successfully parsed. + /// For example, the request may have been rejected if it contained more than the maximum number of waypoints allowed. + /// + G_GEO_BAD_REQUEST=400, + + /// + /// A geocoding or directions request could not be successfully processed, yet the exact reason for the failure is not known. + /// + G_GEO_SERVER_ERROR=500, + + /// + /// The HTTP q parameter was either missing or had no value. + /// For geocoding requests, this means that an empty address was specified as input. For directions requests, this means that no query was specified in the input. + /// + G_GEO_MISSING_QUERY=601, + + /// + /// Synonym for G_GEO_MISSING_QUERY. + /// + G_GEO_MISSING_ADDRESS=601, + + /// + /// No corresponding geographic location could be found for the specified address. + /// This may be due to the fact that the address is relatively new, or it may be incorrect. + /// + G_GEO_UNKNOWN_ADDRESS=602, + + /// + /// The geocode for the given address or the route for the given directions query cannot be returned due to legal or contractual reasons. + /// + G_GEO_UNAVAILABLE_ADDRESS=603, + + /// + /// The GDirections object could not compute directions between the points mentioned in the query. + /// This is usually because there is no route available between the two points, or because we do not have data for routing in that region. + /// + G_GEO_UNKNOWN_DIRECTIONS=604, + + /// + /// The given key is either invalid or does not match the domain for which it was given. + /// + G_GEO_BAD_KEY=610, + + /// + /// The given key has gone over the requests limit in the 24 hour period or has submitted too many requests in too short a period of time. + /// If you're sending multiple requests in parallel or in a tight loop, use a timer or pause in your code to make sure you don't send the requests too quickly. + /// + G_GEO_TOO_MANY_QUERIES=620 + + }; + static QString StrByType(Types const& value) + { + QMetaObject metaObject = GeoCoderStatusCode().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + QString s=metaEnum.valueToKey(value); + return s; + } + static Types TypeByStr(QString const& value) + { + QMetaObject metaObject = GeoCoderStatusCode().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + Types s=(Types)metaEnum.keyToValue(value.toLatin1()); + return s; + } + static QStringList TypesList() + { + QStringList ret; + QMetaObject metaObject = GeoCoderStatusCode().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + for(int x=0;xMemoryCacheCapacity()) - { - if(cachequeue.count()>0 && list.count()>0) - { -#ifdef DEBUG_MEMORY_CACHE - qDebug()<<"Cleaning Memory cache="<<" started with "<MemoryCacheCapacity()) + { + if(cachequeue.count()>0 && list.count()>0) + { +#ifdef DEBUG_MEMORY_CACHE + qDebug()<<"Cleaning Memory cache="<<" started with "< -#include -#include -#include -#include "debugheader.h" -namespace core { - class KiberTileCache - { - public: - KiberTileCache(); - - void setMemoryCacheCapacity(const int &value); - int MemoryCacheCapacity(); - double MemoryCacheSize(){return memoryCacheSize/1048576.0;} - void RemoveMemoryOverload(); - QReadWriteLock kiberCacheLock; - QHash cachequeue; - QQueue list; - long memoryCacheSize; - private: - int _MemoryCacheCapacity; - - }; - - - -} -#endif // KIBERTILECACHE_H +/** +****************************************************************************** +* +* @file kibertilecache.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef KIBERTILECACHE_H +#define KIBERTILECACHE_H + +#include "rawtile.h" +#include +#include +#include +#include +#include "debugheader.h" +namespace core { + class KiberTileCache + { + public: + KiberTileCache(); + + void setMemoryCacheCapacity(const int &value); + int MemoryCacheCapacity(); + double MemoryCacheSize(){return memoryCacheSize/1048576.0;} + void RemoveMemoryOverload(); + QReadWriteLock kiberCacheLock; + QHash cachequeue; + QQueue list; + long memoryCacheSize; + private: + int _MemoryCacheCapacity; + + }; + + + +} +#endif // KIBERTILECACHE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.cpp index 432719c71..52da98b80 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.cpp @@ -1,100 +1,100 @@ -/** -****************************************************************************** -* -* @file languagetype.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "languagetype.h" - - - -namespace core { - LanguageType::LanguageType() - { - list - <<"ar" - <<"bg" - <<"bn" - <<"ca" - <<"cs" - <<"da" - <<"de" - <<"el" - <<"en" - <<"en-AU" - <<"en-GB" - <<"es" - <<"eu" - <<"fi" - <<"fil" - <<"fr" - <<"gl" - <<"gu" - <<"hi" - <<"hr" - <<"hu" - <<"id" - <<"it" - <<"iw" - <<"ja" - <<"kn" - <<"ko" - <<"lt" - <<"lv" - <<"ml" - <<"mr" - <<"nl" - <<"nn" - <<"no" - <<"or" - <<"pl" - <<"pt" - <<"pt-BR" - <<"pt-PT" - <<"rm" - <<"ro" - <<"ru" - <<"sk" - <<"sl" - <<"sr" - <<"sv" - <<"ta" - <<"te" - <<"th" - <<"tr" - <<"uk" - <<"vi" - <<"zh-CN" - <<"zh-TW"; - - } - QString LanguageType::toShortString(Types type) - { - return list[type]; - } - LanguageType::~LanguageType() - { - list.clear(); - } - -} +/** +****************************************************************************** +* +* @file languagetype.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "languagetype.h" + + + +namespace core { + LanguageType::LanguageType() + { + list + <<"ar" + <<"bg" + <<"bn" + <<"ca" + <<"cs" + <<"da" + <<"de" + <<"el" + <<"en" + <<"en-AU" + <<"en-GB" + <<"es" + <<"eu" + <<"fi" + <<"fil" + <<"fr" + <<"gl" + <<"gu" + <<"hi" + <<"hr" + <<"hu" + <<"id" + <<"it" + <<"iw" + <<"ja" + <<"kn" + <<"ko" + <<"lt" + <<"lv" + <<"ml" + <<"mr" + <<"nl" + <<"nn" + <<"no" + <<"or" + <<"pl" + <<"pt" + <<"pt-BR" + <<"pt-PT" + <<"rm" + <<"ro" + <<"ru" + <<"sk" + <<"sl" + <<"sr" + <<"sv" + <<"ta" + <<"te" + <<"th" + <<"tr" + <<"uk" + <<"vi" + <<"zh-CN" + <<"zh-TW"; + + } + QString LanguageType::toShortString(Types type) + { + return list[type]; + } + LanguageType::~LanguageType() + { + list.clear(); + } + +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.h index 577a0a81a..17cfe3b67 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/languagetype.h @@ -1,133 +1,133 @@ -/** -****************************************************************************** -* -* @file languagetype.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef LANGUAGETYPE_H -#define LANGUAGETYPE_H - -#include -#include -#include -#include - - -namespace core { - class LanguageType:public QObject - { - Q_OBJECT - Q_ENUMS(Types) - public: - enum Types - { - Arabic, - Bulgarian, - Bengali, - Catalan, - Czech, - Danish, - German, - Greek, - English, - EnglishAustralian, - EnglishGreatBritain, - Spanish, - Basque, - Finnish, - Filipino, - French, - Galician, - Gujarati, - Hindi, - Croatian, - Hungarian, - Indonesian, - Italian, - Hebrew, - Japanese, - Kannada, - Korean, - Lithuanian, - Latvian, - Malayalam, - Marathi, - Dutch, - NorwegianNynorsk, - Norwegian, - Oriya, - Polish, - Portuguese, - PortugueseBrazil, - PortuguesePortugal, - Romansch, - Romanian, - Russian, - Slovak, - Slovenian, - Serbian, - Swedish, - Tamil, - Telugu, - Thai, - Turkish, - Ukrainian, - Vietnamese, - ChineseSimplified, - ChineseTraditional - }; - - static QString StrByType(Types const& value) - { - QMetaObject metaObject = LanguageType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - QString s=metaEnum.valueToKey(value); - return s; - } - static Types TypeByStr(QString const& value) - { - QMetaObject metaObject = LanguageType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - Types s=(Types)metaEnum.keyToValue(value.toLatin1()); - return s; - } - static QStringList TypesList() - { - QStringList ret; - QMetaObject metaObject = LanguageType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - for(int x=0;x +#include +#include +#include + + +namespace core { + class LanguageType:public QObject + { + Q_OBJECT + Q_ENUMS(Types) + public: + enum Types + { + Arabic, + Bulgarian, + Bengali, + Catalan, + Czech, + Danish, + German, + Greek, + English, + EnglishAustralian, + EnglishGreatBritain, + Spanish, + Basque, + Finnish, + Filipino, + French, + Galician, + Gujarati, + Hindi, + Croatian, + Hungarian, + Indonesian, + Italian, + Hebrew, + Japanese, + Kannada, + Korean, + Lithuanian, + Latvian, + Malayalam, + Marathi, + Dutch, + NorwegianNynorsk, + Norwegian, + Oriya, + Polish, + Portuguese, + PortugueseBrazil, + PortuguesePortugal, + Romansch, + Romanian, + Russian, + Slovak, + Slovenian, + Serbian, + Swedish, + Tamil, + Telugu, + Thai, + Turkish, + Ukrainian, + Vietnamese, + ChineseSimplified, + ChineseTraditional + }; + + static QString StrByType(Types const& value) + { + QMetaObject metaObject = LanguageType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + QString s=metaEnum.valueToKey(value); + return s; + } + static Types TypeByStr(QString const& value) + { + QMetaObject metaObject = LanguageType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + Types s=(Types)metaEnum.keyToValue(value.toLatin1()); + return s; + } + static QStringList TypesList() + { + QStringList ret; + QMetaObject metaObject = LanguageType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + for(int x=0;x -#include -#include - -namespace core { - class MapType:public QObject - { - Q_OBJECT - Q_ENUMS(Types) - public: - enum Types - { - GoogleMap=1, - GoogleSatellite=4, - GoogleLabels=8, - GoogleTerrain=16, - GoogleHybrid=20, - - GoogleMapChina=22, - GoogleSatelliteChina=24, - GoogleLabelsChina=26, - GoogleTerrainChina=28, - GoogleHybridChina=29, - - OpenStreetMap=32, - OpenStreetOsm=33, - OpenStreetMapSurfer=34, - OpenStreetMapSurferTerrain=35, - - YahooMap=64, - YahooSatellite=128, - YahooLabels=256, - YahooHybrid=333, - - BingMap=444, - BingSatellite=555, - BingHybrid=666, - - ArcGIS_Map=777, - ArcGIS_Satellite=788, - ArcGIS_ShadedRelief=799, - ArcGIS_Terrain=811, - - // use these numbers to clean up old stuff - //ArcGIS_MapsLT_Map_Old= 877, - //ArcGIS_MapsLT_OrtoFoto_Old = 888, - //ArcGIS_MapsLT_Map_Labels_Old = 890, - //ArcGIS_MapsLT_Map_Hybrid_Old = 899, - //ArcGIS_MapsLT_Map=977, - //ArcGIS_MapsLT_OrtoFoto=988, - //ArcGIS_MapsLT_Map_Labels=990, - //ArcGIS_MapsLT_Map_Hybrid=999, - //ArcGIS_MapsLT_Map=978, - //ArcGIS_MapsLT_OrtoFoto=989, - //ArcGIS_MapsLT_Map_Labels=991, - //ArcGIS_MapsLT_Map_Hybrid=998, - - ArcGIS_MapsLT_Map=1000, - ArcGIS_MapsLT_OrtoFoto=1001, - ArcGIS_MapsLT_Map_Labels=1002, - ArcGIS_MapsLT_Map_Hybrid=1003, - - PergoTurkeyMap = 2001, - SigPacSpainMap = 3001, - - GoogleMapKorea=4001, - GoogleSatelliteKorea=4002, - GoogleLabelsKorea=4003, - GoogleHybridKorea=4005, - - YandexMapRu = 5000 - }; - static QString StrByType(Types const& value) - { - QMetaObject metaObject = MapType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - QString s=metaEnum.valueToKey(value); - return s; - } - static Types TypeByStr(QString const& value) - { - QMetaObject metaObject = MapType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - Types s=(Types)metaEnum.keyToValue(value.toLatin1()); - return s; - } - static QStringList TypesList() - { - QStringList ret; - QMetaObject metaObject = MapType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - for(int x=0;x +#include +#include + +namespace core { + class MapType:public QObject + { + Q_OBJECT + Q_ENUMS(Types) + public: + enum Types + { + GoogleMap=1, + GoogleSatellite=4, + GoogleLabels=8, + GoogleTerrain=16, + GoogleHybrid=20, + + GoogleMapChina=22, + GoogleSatelliteChina=24, + GoogleLabelsChina=26, + GoogleTerrainChina=28, + GoogleHybridChina=29, + + OpenStreetMap=32, + OpenStreetOsm=33, + OpenStreetMapSurfer=34, + OpenStreetMapSurferTerrain=35, + + YahooMap=64, + YahooSatellite=128, + YahooLabels=256, + YahooHybrid=333, + + BingMap=444, + BingSatellite=555, + BingHybrid=666, + + ArcGIS_Map=777, + ArcGIS_Satellite=788, + ArcGIS_ShadedRelief=799, + ArcGIS_Terrain=811, + + // use these numbers to clean up old stuff + //ArcGIS_MapsLT_Map_Old= 877, + //ArcGIS_MapsLT_OrtoFoto_Old = 888, + //ArcGIS_MapsLT_Map_Labels_Old = 890, + //ArcGIS_MapsLT_Map_Hybrid_Old = 899, + //ArcGIS_MapsLT_Map=977, + //ArcGIS_MapsLT_OrtoFoto=988, + //ArcGIS_MapsLT_Map_Labels=990, + //ArcGIS_MapsLT_Map_Hybrid=999, + //ArcGIS_MapsLT_Map=978, + //ArcGIS_MapsLT_OrtoFoto=989, + //ArcGIS_MapsLT_Map_Labels=991, + //ArcGIS_MapsLT_Map_Hybrid=998, + + ArcGIS_MapsLT_Map=1000, + ArcGIS_MapsLT_OrtoFoto=1001, + ArcGIS_MapsLT_Map_Labels=1002, + ArcGIS_MapsLT_Map_Hybrid=1003, + + PergoTurkeyMap = 2001, + SigPacSpainMap = 3001, + + GoogleMapKorea=4001, + GoogleSatelliteKorea=4002, + GoogleLabelsKorea=4003, + GoogleHybridKorea=4005, + + YandexMapRu = 5000 + }; + static QString StrByType(Types const& value) + { + QMetaObject metaObject = MapType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + QString s=metaEnum.valueToKey(value); + return s; + } + static Types TypeByStr(QString const& value) + { + QMetaObject metaObject = MapType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + Types s=(Types)metaEnum.keyToValue(value.toLatin1()); + return s; + } + static QStringList TypesList() + { + QStringList ret; + QMetaObject metaObject = MapType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + for(int x=0;x -#include -#include -#include "kibertilecache.h" -#include -#include "debugheader.h" -namespace core { - class MemoryCache - { - public: - MemoryCache(); - - KiberTileCache TilesInMemory; - QByteArray GetTileFromMemoryCache(const RawTile &tile); - void AddTileToMemoryCache(const RawTile &tile, const QByteArray &pic); - QReadWriteLock kiberCacheLock; - }; - - -} -#endif // MEMORYCACHE_H +/** +****************************************************************************** +* +* @file memorycache.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef MEMORYCACHE_H +#define MEMORYCACHE_H + +#include "rawtile.h" +#include +#include +#include +#include "kibertilecache.h" +#include +#include "debugheader.h" +namespace core { + class MemoryCache + { + public: + MemoryCache(); + + KiberTileCache TilesInMemory; + QByteArray GetTileFromMemoryCache(const RawTile &tile); + void AddTileToMemoryCache(const RawTile &tile, const QByteArray &pic); + QReadWriteLock kiberCacheLock; + }; + + +} +#endif // MEMORYCACHE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.cpp index 8bee1b057..72d664137 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.cpp @@ -1,28 +1,28 @@ -/** -****************************************************************************** -* -* @file placemark.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "placemark.h" - +/** +****************************************************************************** +* +* @file placemark.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "placemark.h" + diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.h index 3606d9991..7639bc3ca 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/placemark.h @@ -1,54 +1,54 @@ -/** -****************************************************************************** -* -* @file placemark.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef PLACEMARK_H -#define PLACEMARK_H - -#include - - -namespace core { - class Placemark - { - public: - Placemark(const QString &address) - { - this->address = address; - } - QString Address(){return address;} - int Accuracy(){return accuracy;} - void SetAddress(const QString &adr){address=adr;} - void SetAccuracy(const int &value){accuracy=value;} - private: - - QString address; - int accuracy; - protected: - - - }; -} -#endif // PLACEMARK_H +/** +****************************************************************************** +* +* @file placemark.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef PLACEMARK_H +#define PLACEMARK_H + +#include + + +namespace core { + class Placemark + { + public: + Placemark(const QString &address) + { + this->address = address; + } + QString Address(){return address;} + int Accuracy(){return accuracy;} + void SetAddress(const QString &adr){address=adr;} + void SetAccuracy(const int &value){accuracy=value;} + private: + + QString address; + int accuracy; + protected: + + + }; +} +#endif // PLACEMARK_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.cpp index 145c1b225..c41a66880 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.cpp @@ -1,74 +1,74 @@ -/** -****************************************************************************** -* -* @file point.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "point.h" -#include "size.h" - -namespace core { - Point::Point(int dw) - { - this->x=(short)Point::LOWORD(dw); - this->y=(short)Point::HIWORD(dw); - empty=false; - } - Point::Point(Size sz) - { - this->x=sz.Width(); - this->y=sz.Height(); - empty=false; - } - Point::Point(int x, int y) - { - this->x=x; - this->y=y; - empty=false; - } - Point::Point():x(0),y(0),empty(true) - {} - uint qHash(Point const& point) - { - return point.x^point.y; - } - bool operator==(Point const &lhs,Point const &rhs) - { - return (lhs.x==rhs.x && lhs.y==rhs.y); - } - bool operator!=(Point const &lhs,Point const &rhs) - { - return !(lhs==rhs); - } - int Point::HIWORD(int n) - { - return (n >> 16) & 0xffff; - } - - int Point::LOWORD(int n) - { - return n & 0xffff; - } - Point Point::Empty=Point(); - -} +/** +****************************************************************************** +* +* @file point.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "point.h" +#include "size.h" + +namespace core { + Point::Point(int dw) + { + this->x=(short)Point::LOWORD(dw); + this->y=(short)Point::HIWORD(dw); + empty=false; + } + Point::Point(Size sz) + { + this->x=sz.Width(); + this->y=sz.Height(); + empty=false; + } + Point::Point(int x, int y) + { + this->x=x; + this->y=y; + empty=false; + } + Point::Point():x(0),y(0),empty(true) + {} + uint qHash(Point const& point) + { + return point.x^point.y; + } + bool operator==(Point const &lhs,Point const &rhs) + { + return (lhs.x==rhs.x && lhs.y==rhs.y); + } + bool operator!=(Point const &lhs,Point const &rhs) + { + return !(lhs==rhs); + } + int Point::HIWORD(int n) + { + return (n >> 16) & 0xffff; + } + + int Point::LOWORD(int n) + { + return n & 0xffff; + } + Point Point::Empty=Point(); + +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.h index 5e46ca926..318922aa2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/point.h @@ -1,72 +1,72 @@ -/** -****************************************************************************** -* -* @file point.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef OPOINT_H -#define OPOINT_H - - -#include - -namespace core { - struct Size; - struct Point - { - friend uint qHash(Point const& point); - friend bool operator==(Point const& lhs,Point const& rhs); - friend bool operator!=(Point const& lhs,Point const& rhs); - public: - - Point(); - Point(int x,int y); - Point(Size sz); - Point(int dw); - bool IsEmpty(){return empty;} - int X()const{return this->x;} - int Y()const{return this->y;} - void SetX(const int &value){x=value;empty=false;} - void SetY(const int &value){y=value;empty=false;} - QString ToString()const{return "{"+QString::number(x)+","+QString::number(y)+"}";} - - static Point Empty; - void Offset(const int &dx,const int &dy) - { - x += dx; - y += dy; - } - void Offset(Point p) - { - Offset(p.x, p.y); - } - static int HIWORD(int n); - static int LOWORD(int n); - - private: - int x; - int y; - bool empty; - }; -} -#endif // POINT_H +/** +****************************************************************************** +* +* @file point.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef OPOINT_H +#define OPOINT_H + + +#include + +namespace core { + struct Size; + struct Point + { + friend uint qHash(Point const& point); + friend bool operator==(Point const& lhs,Point const& rhs); + friend bool operator!=(Point const& lhs,Point const& rhs); + public: + + Point(); + Point(int x,int y); + Point(Size sz); + Point(int dw); + bool IsEmpty(){return empty;} + int X()const{return this->x;} + int Y()const{return this->y;} + void SetX(const int &value){x=value;empty=false;} + void SetY(const int &value){y=value;empty=false;} + QString ToString()const{return "{"+QString::number(x)+","+QString::number(y)+"}";} + + static Point Empty; + void Offset(const int &dx,const int &dy) + { + x += dx; + y += dy; + } + void Offset(Point p) + { + Offset(p.x, p.y); + } + static int HIWORD(int n); + static int LOWORD(int n); + + private: + int x; + int y; + bool empty; + }; +} +#endif // POINT_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.cpp index 5fda6ac71..7e87503c8 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.cpp @@ -1,88 +1,88 @@ -/** -****************************************************************************** -* -* @file providerstrings.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "providerstrings.h" - - -namespace core { - const QString ProviderStrings::levelsForSigPacSpainMap[] = {"0", "1", "2", "3", "4", - "MTNSIGPAC", - "MTN2000", "MTN2000", "MTN2000", "MTN2000", "MTN2000", - "MTN200", "MTN200", "MTN200", - "MTN25", "MTN25", - "ORTOFOTOS","ORTOFOTOS","ORTOFOTOS","ORTOFOTOS"}; - - ProviderStrings::ProviderStrings() - { -// VersionGoogleMap = "m@132"; -// VersionGoogleSatellite = "71"; -// VersionGoogleLabels = "h@132"; -// VersionGoogleTerrain = "t@125,r@132"; - // Google version strings - VersionGoogleMap = "m@132"; - VersionGoogleSatellite = "71"; - VersionGoogleLabels = "h@132"; - VersionGoogleTerrain = "t@125,r@132"; - SecGoogleWord = "Galileo"; - - // Google (China) version strings - VersionGoogleMapChina = "m@132"; - VersionGoogleSatelliteChina = "s@71"; - VersionGoogleLabelsChina = "h@132"; - VersionGoogleTerrainChina = "t@125,r@132"; - - // Google (Korea) version strings - VersionGoogleMapKorea = "kr1.12"; - VersionGoogleSatelliteKorea = "66"; - VersionGoogleLabelsKorea = "kr1t.12"; - - /// - /// Google Maps API generated using http://greatmaps.codeplex.com/ - /// from http://code.google.com/intl/en-us/apis/maps/signup.html - /// - GoogleMapsAPIKey = "ABQIAAAAWaQgWiEBF3lW97ifKnAczhRAzBk5Igf8Z5n2W3hNnMT0j2TikxTLtVIGU7hCLLHMAuAMt-BO5UrEWA"; - - // Yahoo version strings - VersionYahooMap = "4.3"; - VersionYahooSatellite = "1.9"; - VersionYahooLabels = "4.3"; - - // BingMaps - VersionBingMaps = "563"; - - // YandexMap - VersionYandexMap = "2.16.0"; - //VersionYandexSatellite = "1.19.0"; - //////////////////// - - /// - /// Bing Maps Customer Identification, more info here - /// http://msdn.microsoft.com/en-us/library/bb924353.aspx - /// - BingMapsClientToken = ""; - - } -} +/** +****************************************************************************** +* +* @file providerstrings.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "providerstrings.h" + + +namespace core { + const QString ProviderStrings::levelsForSigPacSpainMap[] = {"0", "1", "2", "3", "4", + "MTNSIGPAC", + "MTN2000", "MTN2000", "MTN2000", "MTN2000", "MTN2000", + "MTN200", "MTN200", "MTN200", + "MTN25", "MTN25", + "ORTOFOTOS","ORTOFOTOS","ORTOFOTOS","ORTOFOTOS"}; + + ProviderStrings::ProviderStrings() + { +// VersionGoogleMap = "m@132"; +// VersionGoogleSatellite = "71"; +// VersionGoogleLabels = "h@132"; +// VersionGoogleTerrain = "t@125,r@132"; + // Google version strings + VersionGoogleMap = "m@132"; + VersionGoogleSatellite = "71"; + VersionGoogleLabels = "h@132"; + VersionGoogleTerrain = "t@125,r@132"; + SecGoogleWord = "Galileo"; + + // Google (China) version strings + VersionGoogleMapChina = "m@132"; + VersionGoogleSatelliteChina = "s@71"; + VersionGoogleLabelsChina = "h@132"; + VersionGoogleTerrainChina = "t@125,r@132"; + + // Google (Korea) version strings + VersionGoogleMapKorea = "kr1.12"; + VersionGoogleSatelliteKorea = "66"; + VersionGoogleLabelsKorea = "kr1t.12"; + + /// + /// Google Maps API generated using http://greatmaps.codeplex.com/ + /// from http://code.google.com/intl/en-us/apis/maps/signup.html + /// + GoogleMapsAPIKey = "ABQIAAAAWaQgWiEBF3lW97ifKnAczhRAzBk5Igf8Z5n2W3hNnMT0j2TikxTLtVIGU7hCLLHMAuAMt-BO5UrEWA"; + + // Yahoo version strings + VersionYahooMap = "4.3"; + VersionYahooSatellite = "1.9"; + VersionYahooLabels = "4.3"; + + // BingMaps + VersionBingMaps = "563"; + + // YandexMap + VersionYandexMap = "2.16.0"; + //VersionYandexSatellite = "1.19.0"; + //////////////////// + + /// + /// Bing Maps Customer Identification, more info here + /// http://msdn.microsoft.com/en-us/library/bb924353.aspx + /// + BingMapsClientToken = ""; + + } +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.h index 504453fd0..c24ccd795 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/providerstrings.h @@ -1,85 +1,85 @@ -/** -****************************************************************************** -* -* @file providerstrings.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef PROVIDERSTRINGS_H -#define PROVIDERSTRINGS_H - -#include - - -namespace core { - class ProviderStrings - { - public: - ProviderStrings(); - static const QString levelsForSigPacSpainMap[]; - QString GoogleMapsAPIKey; - // Google version strings - QString VersionGoogleMap; - QString VersionGoogleSatellite; - QString VersionGoogleLabels; - QString VersionGoogleTerrain; - QString SecGoogleWord; - - // Google (China) version strings - QString VersionGoogleMapChina; - QString VersionGoogleSatelliteChina; - QString VersionGoogleLabelsChina; - QString VersionGoogleTerrainChina; - - // Google (Korea) version strings - QString VersionGoogleMapKorea; - QString VersionGoogleSatelliteKorea; - QString VersionGoogleLabelsKorea; - - /// - /// Google Maps API generated using http://greatmaps.codeplex.com/ - /// from http://code.google.com/intl/en-us/apis/maps/signup.html - /// - - - // Yahoo version strings - QString VersionYahooMap; - QString VersionYahooSatellite; - QString VersionYahooLabels; - - // BingMaps - QString VersionBingMaps; - - // YandexMap - QString VersionYandexMap; - - - - /// - /// Bing Maps Customer Identification, more info here - /// http://msdn.microsoft.com/en-us/library/bb924353.aspx - /// - QString BingMapsClientToken; - }; - -} -#endif // PROVIDERSTRINGS_H +/** +****************************************************************************** +* +* @file providerstrings.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef PROVIDERSTRINGS_H +#define PROVIDERSTRINGS_H + +#include + + +namespace core { + class ProviderStrings + { + public: + ProviderStrings(); + static const QString levelsForSigPacSpainMap[]; + QString GoogleMapsAPIKey; + // Google version strings + QString VersionGoogleMap; + QString VersionGoogleSatellite; + QString VersionGoogleLabels; + QString VersionGoogleTerrain; + QString SecGoogleWord; + + // Google (China) version strings + QString VersionGoogleMapChina; + QString VersionGoogleSatelliteChina; + QString VersionGoogleLabelsChina; + QString VersionGoogleTerrainChina; + + // Google (Korea) version strings + QString VersionGoogleMapKorea; + QString VersionGoogleSatelliteKorea; + QString VersionGoogleLabelsKorea; + + /// + /// Google Maps API generated using http://greatmaps.codeplex.com/ + /// from http://code.google.com/intl/en-us/apis/maps/signup.html + /// + + + // Yahoo version strings + QString VersionYahooMap; + QString VersionYahooSatellite; + QString VersionYahooLabels; + + // BingMaps + QString VersionBingMaps; + + // YandexMap + QString VersionYandexMap; + + + + /// + /// Bing Maps Customer Identification, more info here + /// http://msdn.microsoft.com/en-us/library/bb924353.aspx + /// + QString BingMapsClientToken; + }; + +} +#endif // PROVIDERSTRINGS_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.cpp index fe4dabcab..c64f3c111 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.cpp @@ -1,46 +1,46 @@ -/** -****************************************************************************** -* -* @file pureimage.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "pureimage.h" - - - -namespace core { -PureImageProxy::PureImageProxy() -{ - -} - -QPixmap PureImageProxy::FromStream(const QByteArray &array) -{ - return QPixmap::fromImage(QImage::fromData(array)); -} -bool PureImageProxy::Save(const QByteArray &array, QPixmap &pic) -{ - pic=QPixmap::fromImage(QImage::fromData(array)); - return true; -} -} +/** +****************************************************************************** +* +* @file pureimage.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "pureimage.h" + + + +namespace core { +PureImageProxy::PureImageProxy() +{ + +} + +QPixmap PureImageProxy::FromStream(const QByteArray &array) +{ + return QPixmap::fromImage(QImage::fromData(array)); +} +bool PureImageProxy::Save(const QByteArray &array, QPixmap &pic) +{ + pic=QPixmap::fromImage(QImage::fromData(array)); + return true; +} +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.h index 44e51594b..edc6bd85c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/pureimage.h @@ -1,44 +1,44 @@ -/** -****************************************************************************** -* -* @file pureimage.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef PUREIMAGE_H -#define PUREIMAGE_H - -#include -#include - - -namespace core { - class PureImageProxy - { - public: - PureImageProxy(); - static QPixmap FromStream(const QByteArray &array); - static bool Save(const QByteArray &array,QPixmap &pic); - }; - -} -#endif // PUREIMAGE_H +/** +****************************************************************************** +* +* @file pureimage.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef PUREIMAGE_H +#define PUREIMAGE_H + +#include +#include + + +namespace core { + class PureImageProxy + { + public: + PureImageProxy(); + static QPixmap FromStream(const QByteArray &array); + static bool Save(const QByteArray &array,QPixmap &pic); + }; + +} +#endif // PUREIMAGE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.cpp index 12d58e43d..836d1c6a6 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.cpp @@ -1,76 +1,76 @@ -/** -****************************************************************************** -* -* @file rawtile.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "rawtile.h" - - -namespace core { -RawTile::RawTile(const MapType::Types &Type, const Point &Pos, const int &Zoom) -{ - zoom=Zoom; - type=Type; - pos=Pos; -} -QString RawTile::ToString() -{ - return QString("%1 at zoom %2, pos:%3,%4").arg(type).arg(zoom).arg(pos.X()).arg(pos.Y()); -} -Point RawTile::Pos() -{ - return pos; -} -MapType::Types RawTile::Type() -{ - return type; -} -int RawTile::Zoom() -{ - return zoom; -} -void RawTile::setType(const MapType::Types &value) -{ - type=value; -} -void RawTile::setPos(const Point &value) -{ - pos=value; -} -void RawTile::setZoom(const int &value) -{ - zoom=value; -} -uint qHash(RawTile const& tile) -{ - // RawTile tile=tilee; - quint64 tmp=(((quint64)(tile.zoom))<<54)+(((quint64)(tile.type))<<36)+(((quint64)(tile.pos.X()))<<18)+(((quint64)(tile.pos.Y()))); - // quint64 tmp5=tmp+tmp2+tmp3+tmp4; - return ::qHash(tmp); -} -bool operator==(RawTile const &lhs,RawTile const &rhs) -{ - return (lhs.pos==rhs.pos && lhs.zoom==rhs.zoom && lhs.type==rhs.type); -} -} +/** +****************************************************************************** +* +* @file rawtile.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "rawtile.h" + + +namespace core { +RawTile::RawTile(const MapType::Types &Type, const Point &Pos, const int &Zoom) +{ + zoom=Zoom; + type=Type; + pos=Pos; +} +QString RawTile::ToString() +{ + return QString("%1 at zoom %2, pos:%3,%4").arg(type).arg(zoom).arg(pos.X()).arg(pos.Y()); +} +Point RawTile::Pos() +{ + return pos; +} +MapType::Types RawTile::Type() +{ + return type; +} +int RawTile::Zoom() +{ + return zoom; +} +void RawTile::setType(const MapType::Types &value) +{ + type=value; +} +void RawTile::setPos(const Point &value) +{ + pos=value; +} +void RawTile::setZoom(const int &value) +{ + zoom=value; +} +uint qHash(RawTile const& tile) +{ + // RawTile tile=tilee; + quint64 tmp=(((quint64)(tile.zoom))<<54)+(((quint64)(tile.type))<<36)+(((quint64)(tile.pos.X()))<<18)+(((quint64)(tile.pos.Y()))); + // quint64 tmp5=tmp+tmp2+tmp3+tmp4; + return ::qHash(tmp); +} +bool operator==(RawTile const &lhs,RawTile const &rhs) +{ + return (lhs.pos==rhs.pos && lhs.zoom==rhs.zoom && lhs.type==rhs.type); +} +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.h index 1493b2bb5..ae0796f6c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/rawtile.h @@ -1,56 +1,56 @@ -/** -****************************************************************************** -* -* @file rawtile.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef RAWTILE_H -#define RAWTILE_H - -#include "maptype.h" -#include "point.h" -#include -#include - -namespace core { - class RawTile - { - friend uint qHash(RawTile const& tile); - friend bool operator==(RawTile const& lhs,RawTile const& rhs); - - public: - RawTile(const MapType::Types &Type,const core::Point &Pos,const int &Zoom); - QString ToString(void); - MapType::Types Type(); - core::Point Pos(); - int Zoom(); - void setType(const MapType::Types &value); - void setPos(const core::Point &value); - void setZoom(const int &value); - private: - MapType::Types type; - core::Point pos; - int zoom; - }; -} -#endif // RAWTILE_H +/** +****************************************************************************** +* +* @file rawtile.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef RAWTILE_H +#define RAWTILE_H + +#include "maptype.h" +#include "point.h" +#include +#include + +namespace core { + class RawTile + { + friend uint qHash(RawTile const& tile); + friend bool operator==(RawTile const& lhs,RawTile const& rhs); + + public: + RawTile(const MapType::Types &Type,const core::Point &Pos,const int &Zoom); + QString ToString(void); + MapType::Types Type(); + core::Point Pos(); + int Zoom(); + void setType(const MapType::Types &value); + void setPos(const core::Point &value); + void setZoom(const int &value); + private: + MapType::Types type; + core::Point pos; + int zoom; + }; +} +#endif // RAWTILE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.cpp index 7709de7ee..3d663cde7 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.cpp @@ -1,33 +1,33 @@ -/** -****************************************************************************** -* -* @file size.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "size.h" - - -namespace core { -Size::Size():width(0),height(0) -{} -} +/** +****************************************************************************** +* +* @file size.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "size.h" + + +namespace core { +Size::Size():width(0),height(0) +{} +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.h index 0a0a5a7dc..6949ae28a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/size.h @@ -1,58 +1,58 @@ -/** -****************************************************************************** -* -* @file size.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef SIZE_H -#define SIZE_H - -#include "point.h" -#include -#include - -namespace core { - struct Size - { - - Size(); - Size(Point pt){width=pt.X(); height=pt.Y();}; - Size(int Width,int Height){width=Width; height=Height;}; - friend uint qHash(Size const& size); - // friend bool operator==(Size const& lhs,Size const& rhs); - Size operator-(const Size &sz1){return Size(width-sz1.width,height-sz1.height);} - Size operator+(const Size &sz1){return Size(sz1.width+width,sz1.height+height);} - - int GetHashCode(){return width^height;} - uint qHash(Size const& /*rect*/){return width^height;} - QString ToString(){return "With="+QString::number(width)+" ,Height="+QString::number(height);} - int Width()const {return width;} - int Height()const {return height;} - void SetWidth(int const& value){width=value;} - void SetHeight(int const& value){height=value;} - private: - int width; - int height; - }; -} -#endif // SIZE_H +/** +****************************************************************************** +* +* @file size.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef SIZE_H +#define SIZE_H + +#include "point.h" +#include +#include + +namespace core { + struct Size + { + + Size(); + Size(Point pt){width=pt.X(); height=pt.Y();}; + Size(int Width,int Height){width=Width; height=Height;}; + friend uint qHash(Size const& size); + // friend bool operator==(Size const& lhs,Size const& rhs); + Size operator-(const Size &sz1){return Size(width-sz1.width,height-sz1.height);} + Size operator+(const Size &sz1){return Size(sz1.width+width,sz1.height+height);} + + int GetHashCode(){return width^height;} + uint qHash(Size const& /*rect*/){return width^height;} + QString ToString(){return "With="+QString::number(width)+" ,Height="+QString::number(height);} + int Width()const {return width;} + int Height()const {return height;} + void SetWidth(int const& value){width=value;} + void SetHeight(int const& value){height=value;} + private: + int width; + int height; + }; +} +#endif // SIZE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.h index f53873f3b..2885fcdfe 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/tilecachequeue.h @@ -1,59 +1,59 @@ -/** -****************************************************************************** -* -* @file tilecachequeue.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef TILECACHEQUEUE_H -#define TILECACHEQUEUE_H - -#include -#include "cacheitemqueue.h" -#include -#include -#include -#include -#include -#include "pureimagecache.h" -#include "cache.h" - - -namespace core { - class TileCacheQueue:public QThread - { - Q_OBJECT - public: - TileCacheQueue(); - ~TileCacheQueue(); - void EnqueueCacheTask(CacheItemQueue *task); - - protected: - QQueue tileCacheQueue; - private: - void run(); - QMutex mutex; - QMutex waitmutex; - QWaitCondition waitc; - }; -} -#endif // TILECACHEQUEUE_H +/** +****************************************************************************** +* +* @file tilecachequeue.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef TILECACHEQUEUE_H +#define TILECACHEQUEUE_H + +#include +#include "cacheitemqueue.h" +#include +#include +#include +#include +#include +#include "pureimagecache.h" +#include "cache.h" + + +namespace core { + class TileCacheQueue:public QThread + { + Q_OBJECT + public: + TileCacheQueue(); + ~TileCacheQueue(); + void EnqueueCacheTask(CacheItemQueue *task); + + protected: + QQueue tileCacheQueue; + private: + void run(); + QMutex mutex; + QMutex waitmutex; + QWaitCondition waitc; + }; +} +#endif // TILECACHEQUEUE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/MouseWheelZoomType.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/MouseWheelZoomType.cpp index 3d67f27ec..17fe3b1cd 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/MouseWheelZoomType.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/MouseWheelZoomType.cpp @@ -1,32 +1,32 @@ -/** -****************************************************************************** -* -* @file MouseWheelZoomType.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "mousewheelzoomtype.h" - - -namespace internals { - -} +/** +****************************************************************************** +* +* @file MouseWheelZoomType.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "mousewheelzoomtype.h" + + +namespace internals { + +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/copyrightstrings.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/copyrightstrings.h index edea169c1..36336bf83 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/copyrightstrings.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/copyrightstrings.h @@ -1,41 +1,41 @@ -/** -****************************************************************************** -* -* @file copyrightstrings.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef COPYRIGHTSTRINGS_H -#define COPYRIGHTSTRINGS_H - -#include -#include - -namespace internals { -static const QString googleCopyright = QString("%1 Google - Map data %1 Tele Atlas, Imagery %1 TerraMetrics").arg(QDate::currentDate().year()); -static const QString openStreetMapCopyright = QString(" OpenStreetMap - Map data %1 OpenStreetMap").arg(QDate::currentDate().year()); -static const QString yahooMapCopyright = QString(" Yahoo! Inc. - Map data & Imagery %1 NAVTEQ").arg(QDate::currentDate().year()); -static const QString virtualEarthCopyright = QString("%1 Microsoft Corporation, %1 NAVTEQ, %1 Image courtesy of NASA").arg(QDate::currentDate().year()); -static const QString arcGisCopyright = QString("%1 ESRI - Map data %1 ArcGIS").arg(QDate::currentDate().year()); - -} -#endif // COPYRIGHTSTRINGS_H +/** +****************************************************************************** +* +* @file copyrightstrings.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef COPYRIGHTSTRINGS_H +#define COPYRIGHTSTRINGS_H + +#include +#include + +namespace internals { +static const QString googleCopyright = QString("%1 Google - Map data %1 Tele Atlas, Imagery %1 TerraMetrics").arg(QDate::currentDate().year()); +static const QString openStreetMapCopyright = QString(" OpenStreetMap - Map data %1 OpenStreetMap").arg(QDate::currentDate().year()); +static const QString yahooMapCopyright = QString(" Yahoo! Inc. - Map data & Imagery %1 NAVTEQ").arg(QDate::currentDate().year()); +static const QString virtualEarthCopyright = QString("%1 Microsoft Corporation, %1 NAVTEQ, %1 Image courtesy of NASA").arg(QDate::currentDate().year()); +static const QString arcGisCopyright = QString("%1 ESRI - Map data %1 ArcGIS").arg(QDate::currentDate().year()); + +} +#endif // COPYRIGHTSTRINGS_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/debugheader.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/debugheader.h index 8e5bdba43..50ae028f8 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/debugheader.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/debugheader.h @@ -1,8 +1,8 @@ -#ifndef DEBUGHEADER_H -#define DEBUGHEADER_H - -//#define DEBUG_CORE -//#define DEBUG_TILE -//#define DEBUG_TILEMATRIX - -#endif // DEBUGHEADER_H +#ifndef DEBUGHEADER_H +#define DEBUGHEADER_H + +//#define DEBUG_CORE +//#define DEBUG_TILE +//#define DEBUG_TILEMATRIX + +#endif // DEBUGHEADER_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/internals.pro b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/internals.pro index 21ce6b4b6..787e6ca5c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/internals.pro +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/internals.pro @@ -1,35 +1,35 @@ -include (../common.pri) -HEADERS += core.h \ - mousewheelzoomtype.h \ - rectangle.h \ - tile.h \ - tilematrix.h \ - loadtask.h \ - copyrightstrings.h \ - pureprojection.h \ - pointlatlng.h \ - rectlatlng.h \ - sizelatlng.h \ - debugheader.h -SOURCES += core.cpp \ - rectangle.cpp \ - tile.cpp \ - tilematrix.cpp \ - pureprojection.cpp \ - rectlatlng.cpp \ - sizelatlng.cpp \ - pointlatlng.cpp \ - loadtask.cpp \ - mousewheelzoomtype.cpp -HEADERS += ./projections/lks94projection.h \ - ./projections/mercatorprojection.h \ - ./projections/mercatorprojectionyandex.h \ - ./projections/platecarreeprojection.h \ - ./projections/platecarreeprojectionpergo.h -SOURCES += ./projections/lks94projection.cpp \ - ./projections/mercatorprojection.cpp \ - ./projections/mercatorprojectionyandex.cpp \ - ./projections/platecarreeprojection.cpp \ - ./projections/platecarreeprojectionpergo.cpp -LIBS += -L../build \ - -lcore +include (../common.pri) +HEADERS += core.h \ + mousewheelzoomtype.h \ + rectangle.h \ + tile.h \ + tilematrix.h \ + loadtask.h \ + copyrightstrings.h \ + pureprojection.h \ + pointlatlng.h \ + rectlatlng.h \ + sizelatlng.h \ + debugheader.h +SOURCES += core.cpp \ + rectangle.cpp \ + tile.cpp \ + tilematrix.cpp \ + pureprojection.cpp \ + rectlatlng.cpp \ + sizelatlng.cpp \ + pointlatlng.cpp \ + loadtask.cpp \ + mousewheelzoomtype.cpp +HEADERS += ./projections/lks94projection.h \ + ./projections/mercatorprojection.h \ + ./projections/mercatorprojectionyandex.h \ + ./projections/platecarreeprojection.h \ + ./projections/platecarreeprojectionpergo.h +SOURCES += ./projections/lks94projection.cpp \ + ./projections/mercatorprojection.cpp \ + ./projections/mercatorprojectionyandex.cpp \ + ./projections/platecarreeprojection.cpp \ + ./projections/platecarreeprojectionpergo.cpp +LIBS += -L../build \ + -lcore diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.cpp index 00e373cfb..535c7e615 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.cpp @@ -1,35 +1,35 @@ -/** -****************************************************************************** -* -* @file loadtask.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "loadtask.h" - - -namespace internals { -bool operator==(LoadTask const& lhs,LoadTask const& rhs) -{ - return ((lhs.Pos==rhs.Pos)&&(lhs.Zoom==rhs.Zoom)); -} -} +/** +****************************************************************************** +* +* @file loadtask.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "loadtask.h" + + +namespace internals { +bool operator==(LoadTask const& lhs,LoadTask const& rhs) +{ + return ((lhs.Pos==rhs.Pos)&&(lhs.Zoom==rhs.Zoom)); +} +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.h index 662420d6e..47df78a65 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/loadtask.h @@ -1,65 +1,65 @@ -/** -****************************************************************************** -* -* @file loadtask.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef LOADTASK_H -#define LOADTASK_H - -#include -#include "../core/point.h" - -using namespace core; -namespace internals -{ -struct LoadTask - { - friend bool operator==(LoadTask const& lhs,LoadTask const& rhs); - public: - core::Point Pos; - int Zoom; - - - LoadTask(Point pos, int zoom) - { - Pos = pos; - Zoom = zoom; - } - LoadTask() - { - Pos=core::Point(-1,-1); - Zoom=-1; - } - bool HasValue() - { - return !(Zoom==-1); - } - - QString ToString()const - { - return QString::number(Zoom) + " - " + Pos.ToString(); - } - }; -} -#endif // LOADTASK_H +/** +****************************************************************************** +* +* @file loadtask.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef LOADTASK_H +#define LOADTASK_H + +#include +#include "../core/point.h" + +using namespace core; +namespace internals +{ +struct LoadTask + { + friend bool operator==(LoadTask const& lhs,LoadTask const& rhs); + public: + core::Point Pos; + int Zoom; + + + LoadTask(Point pos, int zoom) + { + Pos = pos; + Zoom = zoom; + } + LoadTask() + { + Pos=core::Point(-1,-1); + Zoom=-1; + } + bool HasValue() + { + return !(Zoom==-1); + } + + QString ToString()const + { + return QString::number(Zoom) + " - " + Pos.ToString(); + } + }; +} +#endif // LOADTASK_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h index 59938129d..d3fe648b9 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/mousewheelzoomtype.h @@ -1,89 +1,89 @@ -/** -****************************************************************************** -* -* @file mousewheelzoomtype.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef MOUSEWHEELZOOMTYPE_H -#define MOUSEWHEELZOOMTYPE_H -#include -#include -#include -#include -#include -namespace internals { - class MouseWheelZoomType:public QObject - { - Q_OBJECT - Q_ENUMS(Types) - public: - enum Types - { - /// - /// zooms map to current mouse position and makes it map center - /// - MousePositionAndCenter, - - /// - /// zooms to current mouse position, but doesn't make it map center, - /// google/bing style ;} - /// - MousePositionWithoutCenter, - - /// - /// zooms map to current view center - /// - ViewCenter - }; - static QString StrByType(Types const& value) - { - QMetaObject metaObject = MouseWheelZoomType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - QString s=metaEnum.valueToKey(value); - return s; - } - static Types TypeByStr(QString const& value) - { - QMetaObject metaObject = MouseWheelZoomType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - Types s=(Types)metaEnum.keyToValue(value.toLatin1()); - return s; - } - static QStringList TypesList() - { - QStringList ret; - QMetaObject metaObject = MouseWheelZoomType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - for(int x=0;x +#include +#include +#include +#include +namespace internals { + class MouseWheelZoomType:public QObject + { + Q_OBJECT + Q_ENUMS(Types) + public: + enum Types + { + /// + /// zooms map to current mouse position and makes it map center + /// + MousePositionAndCenter, + + /// + /// zooms to current mouse position, but doesn't make it map center, + /// google/bing style ;} + /// + MousePositionWithoutCenter, + + /// + /// zooms map to current view center + /// + ViewCenter + }; + static QString StrByType(Types const& value) + { + QMetaObject metaObject = MouseWheelZoomType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + QString s=metaEnum.valueToKey(value); + return s; + } + static Types TypeByStr(QString const& value) + { + QMetaObject metaObject = MouseWheelZoomType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + Types s=(Types)metaEnum.keyToValue(value.toLatin1()); + return s; + } + static QStringList TypesList() + { + QStringList ret; + QMetaObject metaObject = MouseWheelZoomType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + for(int x=0;x -#include -#include "sizelatlng.h" - -namespace internals { -struct PointLatLng -{ - //friend uint qHash(PointLatLng const& point); - friend bool operator==(PointLatLng const& lhs,PointLatLng const& rhs); - friend bool operator!=(PointLatLng const& left, PointLatLng const& right); - friend PointLatLng operator+(PointLatLng pt, SizeLatLng sz); - friend PointLatLng operator-(PointLatLng pt, SizeLatLng sz); - - //TODO Sizelatlng friend PointLatLng operator+(PointLatLng pt, SizeLatLng sz); - - private: - double lat; - double lng; - bool empty; - public: - PointLatLng(); - - - static PointLatLng Empty; - - PointLatLng(const double &lat,const double &lng) - { - this->lat = lat; - this->lng = lng; - empty=false; - } - - bool IsEmpty() - { - return empty; - } - - double Lat()const - { - return this->lat; - } - - void SetLat(const double &value) - { - this->lat = value; - empty=false; - } - - - double Lng()const - { - return this->lng; - } - void SetLng(const double &value) - { - this->lng = value; - empty=false; - } - - - - - - static PointLatLng Add(PointLatLng const& pt, SizeLatLng const& sz) - { - return PointLatLng(pt.Lat() - sz.HeightLat(), pt.Lng() + sz.WidthLng()); - } - - static PointLatLng Subtract(PointLatLng const& pt, SizeLatLng const& sz) - { - return PointLatLng(pt.Lat() + sz.HeightLat(), pt.Lng() - sz.WidthLng()); - } - - - void Offset(PointLatLng const& pos) - { - this->Offset(pos.Lat(), pos.Lng()); - } - - void Offset(double const& lat, double const& lng) - { - this->lng += lng; - this->lat -= lat; - } - - - QString ToString()const - { - return QString("{Lat=%1, Lng=%2}").arg(this->lat).arg(this->lng); - } - -//// static PointLatLng() -//// { -//// Empty = new PointLatLng(); -//// } - }; - - -// -} -#endif // POINTLATLNG_H +/** +****************************************************************************** +* +* @file pointlatlng.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef POINTLATLNG_H +#define POINTLATLNG_H + +#include +#include +#include "sizelatlng.h" + +namespace internals { +struct PointLatLng +{ + //friend uint qHash(PointLatLng const& point); + friend bool operator==(PointLatLng const& lhs,PointLatLng const& rhs); + friend bool operator!=(PointLatLng const& left, PointLatLng const& right); + friend PointLatLng operator+(PointLatLng pt, SizeLatLng sz); + friend PointLatLng operator-(PointLatLng pt, SizeLatLng sz); + + //TODO Sizelatlng friend PointLatLng operator+(PointLatLng pt, SizeLatLng sz); + + private: + double lat; + double lng; + bool empty; + public: + PointLatLng(); + + + static PointLatLng Empty; + + PointLatLng(const double &lat,const double &lng) + { + this->lat = lat; + this->lng = lng; + empty=false; + } + + bool IsEmpty() + { + return empty; + } + + double Lat()const + { + return this->lat; + } + + void SetLat(const double &value) + { + this->lat = value; + empty=false; + } + + + double Lng()const + { + return this->lng; + } + void SetLng(const double &value) + { + this->lng = value; + empty=false; + } + + + + + + static PointLatLng Add(PointLatLng const& pt, SizeLatLng const& sz) + { + return PointLatLng(pt.Lat() - sz.HeightLat(), pt.Lng() + sz.WidthLng()); + } + + static PointLatLng Subtract(PointLatLng const& pt, SizeLatLng const& sz) + { + return PointLatLng(pt.Lat() + sz.HeightLat(), pt.Lng() - sz.WidthLng()); + } + + + void Offset(PointLatLng const& pos) + { + this->Offset(pos.Lat(), pos.Lng()); + } + + void Offset(double const& lat, double const& lng) + { + this->lng += lng; + this->lat -= lat; + } + + + QString ToString()const + { + return QString("{Lat=%1, Lng=%2}").arg(this->lat).arg(this->lng); + } + +//// static PointLatLng() +//// { +//// Empty = new PointLatLng(); +//// } + }; + + +// +} +#endif // POINTLATLNG_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp index 82a59ab23..0273a5bda 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.cpp @@ -1,791 +1,791 @@ -/** -****************************************************************************** -* -* @file lks94projection.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "lks94projection.h" - - - -namespace projections { -LKS94Projection::LKS94Projection():MinLatitude (53.33 ), MaxLatitude (56.55 ), MinLongitude (20.22 ), -MaxLongitude (27.11 ), orignX (5122000 ), orignY (10000100 ),tileSize(256, 256) -{ -} - -Size LKS94Projection::TileSize() const -{ - return tileSize; -} -double LKS94Projection::Axis() const -{ - return 6378137; -} -double LKS94Projection::Flattening() const -{ - - return (1.0 / 298.257222101); - -} - -Point LKS94Projection::FromLatLngToPixel(double lat, double lng, int const& zoom) -{ - Point ret; - - lat = Clip(lat, MinLatitude, MaxLatitude); - lng = Clip(lng, MinLongitude, MaxLongitude); - QVector lks(3); - lks[0]=lng; - lks[1]=lat; - lks = DTM10(lks); - lks = MTD10(lks); - lks = DTM00(lks); - - double res = GetTileMatrixResolution(zoom); - - ret.SetX((int) floor((lks[0] + orignX) / res)); - ret.SetY((int) floor((orignY - lks[1]) / res)); - - return ret; -} - -internals::PointLatLng LKS94Projection::FromPixelToLatLng(int const& x, int const& y, int const& zoom) -{ - internals::PointLatLng ret;// = internals::PointLatLng::Empty; - - double res = GetTileMatrixResolution(zoom); - - QVector lks(2); - lks[0]=(x * res) - orignX; - lks[1]=-(y * res) + orignY; - lks = MTD11(lks); - lks = DTM10(lks); - lks = MTD10(lks); - ret.SetLat(Clip(lks[1], MinLatitude, MaxLatitude)); - ret.SetLng(Clip(lks[0], MinLongitude, MaxLongitude)); - return ret; -} - -QVector LKS94Projection::DTM10(const QVector & lonlat) -{ - double es; // Eccentricity squared : (a^2 - b^2)/a^2 - double semiMajor = 6378137.0; // major axis - double semiMinor = 6356752.3142451793; // minor axis - double ab; // Semi_major / semi_minor - double ba; // Semi_minor / semi_major - double ses; // Second eccentricity squared : (a^2 - b^2)/b^2 - - es = 1.0 - (semiMinor * semiMinor) / (semiMajor * semiMajor); //e^2 - ses = (pow(semiMajor, 2) - pow(semiMinor, 2)) / pow(semiMinor, 2); - ba = semiMinor / semiMajor; - ab = semiMajor / semiMinor; - - // ... - - double lon = DegreesToRadians(lonlat[0]); - double lat = DegreesToRadians(lonlat[1]); - double h = lonlat.count() < 3 ? 0 : std::isnan(lonlat[2]) ? 0 : lonlat[2];//TODO NAN - double v = semiMajor / sqrt(1 - es * pow(sin(lat), 2)); - double x = (v + h) * cos(lat) * cos(lon); - double y = (v + h) * cos(lat) * sin(lon); - double z = ((1 - es) * v + h) * sin(lat); - QVector ret(3); - ret[0]=x; - ret[1]=y; - ret[2]=z; - return ret; -} -QVector LKS94Projection::MTD10(QVector & pnt) -{ - QVector ret(3); - const double COS_67P5 = 0.38268343236508977; // cosine of 67.5 degrees - const double AD_C = 1.0026000; // Toms region 1 constant - - double es; // Eccentricity squared : (a^2 - b^2)/a^2 - double semiMajor = 6378137.0; // major axis - double semiMinor = 6356752.3141403561; // minor axis - double ab; // Semi_major / semi_minor - double ba; // Semi_minor / semi_major - double ses; // Second eccentricity squared : (a^2 - b^2)/b^2 - - es = 1.0 - (semiMinor * semiMinor) / (semiMajor * semiMajor); //e^2 - ses = (pow(semiMajor, 2) - pow(semiMinor, 2)) / pow(semiMinor, 2); - ba = semiMinor / semiMajor; - ab = semiMajor / semiMinor; - - // ... - - bool AtPole = false; // is location in polar region - double Z = pnt.count() < 3 ? 0 : std::isnan(pnt[2]) ? 0 : pnt[2];//TODO NaN - - double lon = 0; - double lat = 0; - double Height = 0; - if(pnt[0] != 0.0) - { - lon = atan2(pnt[1], pnt[0]); - } - else - { - if(pnt[1] > 0) - { - lon = M_PI / 2; - } - else - if(pnt[1] < 0) - { - lon = -M_PI * 0.5; - } - else - { - AtPole = true; - lon = 0.0; - if(Z > 0.0) // north pole - { - lat = M_PI * 0.5; - } - else - if(Z < 0.0) // south pole - { - lat = -M_PI * 0.5; - } - else // center of earth - { - ret[0]=RadiansToDegrees(lon); - ret[1]=RadiansToDegrees(M_PI * 0.5); - ret[2]=-semiMinor; - return ret; - } - } - } - double W2 = pnt[0] * pnt[0] + pnt[1] * pnt[1]; // Square of distance from Z axis - double W = sqrt(W2); // distance from Z axis - double T0 = Z * AD_C; // initial estimate of vertical component - double S0 = sqrt(T0 * T0 + W2); // initial estimate of horizontal component - double Sin_B0 = T0 / S0; // sin(B0), B0 is estimate of Bowring aux variable - double Cos_B0 = W / S0; // cos(B0) - double Sin3_B0 = pow(Sin_B0, 3); - double T1 = Z + semiMinor * ses * Sin3_B0; // corrected estimate of vertical component - double Sum = W - semiMajor * es * Cos_B0 * Cos_B0 * Cos_B0; // numerator of cos(phi1) - double S1 = sqrt(T1 * T1 + Sum * Sum); // corrected estimate of horizontal component - double Sin_p1 = T1 / S1; // sin(phi1), phi1 is estimated latitude - double Cos_p1 = Sum / S1; // cos(phi1) - double Rn = semiMajor / sqrt(1.0 - es * Sin_p1 * Sin_p1); // Earth radius at location - if(Cos_p1 >= COS_67P5) - { - Height = W / Cos_p1 - Rn; - } - else - if(Cos_p1 <= -COS_67P5) - { - Height = W / -Cos_p1 - Rn; - } - else - { - Height = Z / Sin_p1 + Rn * (es - 1.0); - } - - if(!AtPole) - { - lat = atan(Sin_p1 / Cos_p1); - } - ret[0]=RadiansToDegrees(lon); - ret[1]=RadiansToDegrees(lat); - ret[2]=Height; - return ret; -} -QVector LKS94Projection::DTM00(QVector & lonlat) -{ - double scaleFactor = 0.9998; // scale factor - double centralMeridian = 0.41887902047863912; // Center qlonglongitude (projection center) */ - double latOrigin = 0.0; // center latitude - double falseNorthing = 0.0; // y offset in meters - double falseEasting = 500000.0; // x offset in meters - double semiMajor = 6378137.0; // major axis - double semiMinor = 6356752.3141403561; // minor axis - double metersPerUnit = 1.0; - - double e0, e1, e2, e3; // eccentricity constants - double e, es, esp; // eccentricity constants - double ml0; // small value m - - es = 1.0 - pow(semiMinor / semiMajor, 2); - e = sqrt(es); - e0 = e0fn(es); - e1 = e1fn(es); - e2 = e2fn(es); - e3 = e3fn(es); - ml0 = semiMajor * mlfn(e0, e1, e2, e3, latOrigin); - esp = es / (1.0 - es); - - // ... - - double lon = DegreesToRadians(lonlat[0]); - double lat = DegreesToRadians(lonlat[1]); - - double delta_lon = 0.0; // Delta qlonglongitude (Given qlonglongitude - center) - double sin_phi, cos_phi; // sin and cos value - double al, als; // temporary values - double c, t, tq; // temporary values - double con, n, ml; // cone constant, small m - - delta_lon = LKS94Projection::AdjustLongitude(lon - centralMeridian); - LKS94Projection::SinCos(lat, sin_phi, cos_phi); - - al = cos_phi * delta_lon; - als = pow(al, 2); - c = pow(cos_phi, 2); - tq = tan(lat); - t = pow(tq, 2); - con = 1.0 - es * pow(sin_phi, 2); - n = semiMajor / sqrt(con); - ml = semiMajor * mlfn(e0, e1, e2, e3, lat); - - double x = scaleFactor * n * al * (1.0 + als / 6.0 * (1.0 - t + c + als / 20.0 * - (5.0 - 18.0 * t + pow(t, 2) + 72.0 * c - 58.0 * esp))) + falseEasting; - - double y = scaleFactor * (ml - ml0 + n * tq * (als * (0.5 + als / 24.0 * - (5.0 - t + 9.0 * c + 4.0 * pow(c, 2) + als / 30.0 * (61.0 - 58.0 * t - + pow(t, 2) + 600.0 * c - 330.0 * esp))))) + falseNorthing; - - if(lonlat.count() < 3) - { - QVector ret(2); - ret[0]= x / metersPerUnit; - ret[1]= y / metersPerUnit; - return ret; - } - else - { - QVector ret(3); - ret[0]= x / metersPerUnit; - ret[1]= y / metersPerUnit; - ret[2]=lonlat[2]; - return ret; - } -} - -QVector LKS94Projection::DTM01(QVector & lonlat) -{ - double es; // Eccentricity squared : (a^2 - b^2)/a^2 - double semiMajor = 6378137.0; // major axis - double semiMinor = 6356752.3141403561; // minor axis - double ab; // Semi_major / semi_minor - double ba; // Semi_minor / semi_major - double ses; // Second eccentricity squared : (a^2 - b^2)/b^2 - - es = 1.0 - (semiMinor * semiMinor) / (semiMajor * semiMajor); - ses = (pow(semiMajor, 2) -pow(semiMinor, 2)) / pow(semiMinor, 2); - ba = semiMinor / semiMajor; - ab = semiMajor / semiMinor; - - // ... - - double lon = DegreesToRadians(lonlat[0]); - double lat = DegreesToRadians(lonlat[1]); - double h = lonlat.count() < 3 ? 0 : std::isnan(lonlat[2]) ? 0 : lonlat[2];//TODO NaN - double v = semiMajor / sqrt(1 - es * pow(sin(lat), 2)); - double x = (v + h) * cos(lat) * cos(lon); - double y = (v + h) * cos(lat) * sin(lon); - double z = ((1 - es) * v + h) * sin(lat); - QVector ret(3); - ret[0]=x; - ret[1]=y; - ret[2]=z; - return ret; -} -QVector LKS94Projection::MTD01(QVector & pnt) -{ - const double COS_67P5 = 0.38268343236508977; // cosine of 67.5 degrees - const double AD_C = 1.0026000; // Toms region 1 constant - - double es; // Eccentricity squared : (a^2 - b^2)/a^2 - double semiMajor = 6378137.0; // major axis - double semiMinor = 6356752.3142451793; // minor axis - double ab; // Semi_major / semi_minor - double ba; // Semi_minor / semi_major - double ses; // Second eccentricity squared : (a^2 - b^2)/b^2 - - es = 1.0 - (semiMinor * semiMinor) / (semiMajor * semiMajor); - ses = (pow(semiMajor, 2) - pow(semiMinor, 2)) / pow(semiMinor, 2); - ba = semiMinor / semiMajor; - ab = semiMajor / semiMinor; - - // ... - - bool At_Pole = false; // is location in polar region - double Z = pnt.count() < 3 ? 0 : std::isnan(pnt[2]) ? 0 : pnt[2];//TODO NaN - - double lon = 0; - double lat = 0; - double Height = 0; - if(pnt[0] != 0.0) - { - lon = atan2(pnt[1], pnt[0]); - } - else - { - if(pnt[1] > 0) - { - lon = M_PI / 2; - } - else - if(pnt[1] < 0) - { - lon = -M_PI * 0.5; - } - else - { - At_Pole = true; - lon = 0.0; - if(Z > 0.0) // north pole - { - lat = M_PI * 0.5; - } - else - if(Z < 0.0) // south pole - { - lat = -M_PI * 0.5; - } - else // center of earth - { - QVector ret(3); - ret[0]=RadiansToDegrees(lon); - ret[1]=RadiansToDegrees(M_PI * 0.5); - ret[2]=-semiMinor; - return ret; - } - } - } - - double W2 = pnt[0] * pnt[0] + pnt[1] * pnt[1]; // Square of distance from Z axis - double W = sqrt(W2); // distance from Z axis - double T0 = Z * AD_C; // initial estimate of vertical component - double S0 = sqrt(T0 * T0 + W2); //initial estimate of horizontal component - double Sin_B0 = T0 / S0; // sin(B0), B0 is estimate of Bowring aux variable - double Cos_B0 = W / S0; // cos(B0) - double Sin3_B0 = pow(Sin_B0, 3); - double T1 = Z + semiMinor * ses * Sin3_B0; //corrected estimate of vertical component - double Sum = W - semiMajor * es * Cos_B0 * Cos_B0 * Cos_B0; // numerator of cos(phi1) - double S1 = sqrt(T1 * T1 + Sum * Sum); // corrected estimate of horizontal component - double Sin_p1 = T1 / S1; // sin(phi1), phi1 is estimated latitude - double Cos_p1 = Sum / S1; // cos(phi1) - double Rn = semiMajor / sqrt(1.0 - es * Sin_p1 * Sin_p1); // Earth radius at location - - if(Cos_p1 >= COS_67P5) - { - Height = W / Cos_p1 - Rn; - } - else - if(Cos_p1 <= -COS_67P5) - { - Height = W / -Cos_p1 - Rn; - } - else - { - Height = Z / Sin_p1 + Rn * (es - 1.0); - } - - if(!At_Pole) - { - lat = atan(Sin_p1 / Cos_p1); - } - QVector ret(3); - ret[0]=RadiansToDegrees(lon); - ret[1]=RadiansToDegrees(lat); - ret[2]=Height; - return ret; -} -QVector LKS94Projection::MTD11(QVector & p) -{ - double scaleFactor = 0.9998; // scale factor - double centralMeridian = 0.41887902047863912; // Center qlonglongitude (projection center) - double latOrigin = 0.0; // center latitude - double falseNorthing = 0.0; // y offset in meters - double falseEasting = 500000.0; // x offset in meters - double semiMajor = 6378137.0; // major axis - double semiMinor = 6356752.3141403561; // minor axis - double metersPerUnit = 1.0; - - double e0, e1, e2, e3; // eccentricity constants - double e, es, esp; // eccentricity constants - double ml0; // small value m - - es =(semiMinor * semiMinor) / (semiMajor * semiMajor); - es=1.0-es; - e = sqrt(es); - e0 = e0fn(es); - e1 = e1fn(es); - e2 = e2fn(es); - e3 = e3fn(es); - ml0 = semiMajor * mlfn(e0, e1, e2, e3, latOrigin); - esp = es / (1.0 - es); - - // ... - - double con, phi; - double delta_phi; - qlonglong i; - double sin_phi, cos_phi, tan_phi; - double c, cs, t, ts, n, r, d, ds; - qlonglong max_iter = 6; - - double x = p[0] * metersPerUnit - falseEasting; - double y = p[1] * metersPerUnit - falseNorthing; - - con = (ml0 + y / scaleFactor) / semiMajor; - phi = con; - for(i = 0; ; i++) - { - delta_phi = ((con + e1 * sin(2.0 * phi) - e2 * sin(4.0 * phi) + e3 * sin(6.0 * phi)) / e0) - phi; - phi += delta_phi; - if(fabs(delta_phi) <= EPSLoN) - break; - - if(i >= max_iter) - throw "Latitude failed to converge"; - } - - if(fabs(phi) < HALF_PI) - { - SinCos(phi, sin_phi, cos_phi); - tan_phi = tan(phi); - c = esp * pow(cos_phi, 2); - cs = pow(c, 2); - t = pow(tan_phi, 2); - ts = pow(t, 2); - con = 1.0 - es * pow(sin_phi, 2); - n = semiMajor / sqrt(con); - r = n * (1.0 - es) / con; - d = x / (n * scaleFactor); - ds = pow(d, 2); - - double lat = phi - (n * tan_phi * ds / r) * (0.5 - ds / 24.0 * (5.0 + 3.0 * t + - 10.0 * c - 4.0 * cs - 9.0 * esp - ds / 30.0 * (61.0 + 90.0 * t + - 298.0 * c + 45.0 * ts - 252.0 * esp - 3.0 * cs))); - - double lon = AdjustLongitude(centralMeridian + (d * (1.0 - ds / 6.0 * (1.0 + 2.0 * t + - c - ds / 20.0 * (5.0 - 2.0 * c + 28.0 * t - 3.0 * cs + 8.0 * esp + - 24.0 * ts))) / cos_phi)); - - if(p.count() < 3) - { - QVector ret(2); - ret[0]= RadiansToDegrees(lon); - ret[1]= RadiansToDegrees(lat); - return ret; - } - else - { - QVector ret(3); - ret[0]= RadiansToDegrees(lon); - ret[1]= RadiansToDegrees(lat); - ret[2]=p[2]; - return ret; - //return new double[] { RadiansToDegrees(lon), RadiansToDegrees(lat), p[2] }; - } - } - else - { - if(p.count() < 3) - { - QVector ret(2); - ret[0]= RadiansToDegrees(HALF_PI * Sign(y)); - ret[1]= RadiansToDegrees(centralMeridian); - return ret; - } - - else - { - QVector ret(3); - ret[0]= RadiansToDegrees(HALF_PI * Sign(y)); - ret[1]= RadiansToDegrees(centralMeridian); - ret[2]=p[2]; - return ret; - } - - } -} - -double LKS94Projection::Clip(double const& n, double const& minValue, double const& maxValue) -{ - return qMin(qMax(n, minValue), maxValue); -} -double LKS94Projection::GetTileMatrixResolution(int const& zoom) -{ - double ret = 0; - - switch(zoom) - { - case 0: - { - ret = 1587.50317500635; - } - break; - - case 1: - { - ret = 793.751587503175; - } - break; - - case 2: - { - ret = 529.167725002117; - } - break; - - case 3: - { - ret = 264.583862501058; - } - break; - - case 4: - { - ret = 132.291931250529; - } - break; - - case 5: - { - ret = 52.9167725002117; - } - break; - - case 6: - { - ret = 26.4583862501058; - } - break; - - case 7: - { - ret = 13.2291931250529; - } - break; - - case 8: - { - ret = 6.61459656252646; - } - break; - - case 9: - { - ret = 2.64583862501058; - } - break; - - case 10: - { - ret = 1.32291931250529; - } - break; - - case 11: - { - ret = 0.529167725002117; - } - break; - - } - - return ret; -} -/* - * Returns the conversion from pixels to meters - */ -double LKS94Projection::GetGroundResolution(int const& zoom, double const& latitude) -{ - Q_UNUSED(zoom); - Q_UNUSED(latitude); - return GetTileMatrixResolution(zoom); -} -Size LKS94Projection::GetTileMatrixMinXY(int const& zoom) -{ - Size ret; - - switch(zoom) - { - - case 0: - { - ret = Size(12, 8); - } - break; - - case 1: - { - ret = Size(24, 17); - } - break; - - case 2: - { - ret = Size(37, 25); - } - break; - - case 3: - { - ret = Size(74, 51); - } - break; - - case 4: - { - ret = Size(149, 103); - } - break; - - case 5: - { - ret = Size(374, 259); - } - break; - - case 6: - { - ret = Size(749, 519); - } - break; - - case 7: - { - ret = Size(1594, 1100); - } - break; - - case 8: - { - ret = Size(3188, 2201); - } - break; - - case 9: - { - ret = Size(7971, 5502); - } - break; - - case 10: - { - ret = Size(15943, 11005); - } - break; - - case 11: - { - ret = Size(39858, 27514); - } - break; - } - - return ret; -} - -Size LKS94Projection::GetTileMatrixMaxXY(int const& zoom) -{ - Size ret; - - switch(zoom) - { - case 0: - { - ret = Size(14, 10); - } - break; - - case 1: - { - ret = Size(30, 20); - } - break; - - case 2: - { - ret = Size(45, 31); - } - break; - - case 3: - { - ret = Size(90, 62); - } - break; - - case 4: - { - ret = Size(181, 125); - } - break; - - case 5: - { - ret = Size(454, 311); - } - break; - - case 6: - { - ret = Size(903, 623); - } - break; - - case 7: - { - ret = Size(1718, 1193); - } - break; - - case 8: - { - ret = Size(3437, 2386); - } - break; - - case 9: - { - ret = Size(8594, 5966); - } - break; - - case 10: - { - ret = Size(17189, 11932); - } - break; - - case 11: - { - ret = Size(42972, 29831); - } - break; - } - - return ret; -} - -} +/** +****************************************************************************** +* +* @file lks94projection.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "lks94projection.h" + + + +namespace projections { +LKS94Projection::LKS94Projection():MinLatitude (53.33 ), MaxLatitude (56.55 ), MinLongitude (20.22 ), +MaxLongitude (27.11 ), orignX (5122000 ), orignY (10000100 ),tileSize(256, 256) +{ +} + +Size LKS94Projection::TileSize() const +{ + return tileSize; +} +double LKS94Projection::Axis() const +{ + return 6378137; +} +double LKS94Projection::Flattening() const +{ + + return (1.0 / 298.257222101); + +} + +Point LKS94Projection::FromLatLngToPixel(double lat, double lng, int const& zoom) +{ + Point ret; + + lat = Clip(lat, MinLatitude, MaxLatitude); + lng = Clip(lng, MinLongitude, MaxLongitude); + QVector lks(3); + lks[0]=lng; + lks[1]=lat; + lks = DTM10(lks); + lks = MTD10(lks); + lks = DTM00(lks); + + double res = GetTileMatrixResolution(zoom); + + ret.SetX((int) floor((lks[0] + orignX) / res)); + ret.SetY((int) floor((orignY - lks[1]) / res)); + + return ret; +} + +internals::PointLatLng LKS94Projection::FromPixelToLatLng(int const& x, int const& y, int const& zoom) +{ + internals::PointLatLng ret;// = internals::PointLatLng::Empty; + + double res = GetTileMatrixResolution(zoom); + + QVector lks(2); + lks[0]=(x * res) - orignX; + lks[1]=-(y * res) + orignY; + lks = MTD11(lks); + lks = DTM10(lks); + lks = MTD10(lks); + ret.SetLat(Clip(lks[1], MinLatitude, MaxLatitude)); + ret.SetLng(Clip(lks[0], MinLongitude, MaxLongitude)); + return ret; +} + +QVector LKS94Projection::DTM10(const QVector & lonlat) +{ + double es; // Eccentricity squared : (a^2 - b^2)/a^2 + double semiMajor = 6378137.0; // major axis + double semiMinor = 6356752.3142451793; // minor axis + double ab; // Semi_major / semi_minor + double ba; // Semi_minor / semi_major + double ses; // Second eccentricity squared : (a^2 - b^2)/b^2 + + es = 1.0 - (semiMinor * semiMinor) / (semiMajor * semiMajor); //e^2 + ses = (pow(semiMajor, 2) - pow(semiMinor, 2)) / pow(semiMinor, 2); + ba = semiMinor / semiMajor; + ab = semiMajor / semiMinor; + + // ... + + double lon = DegreesToRadians(lonlat[0]); + double lat = DegreesToRadians(lonlat[1]); + double h = lonlat.count() < 3 ? 0 : std::isnan(lonlat[2]) ? 0 : lonlat[2];//TODO NAN + double v = semiMajor / sqrt(1 - es * pow(sin(lat), 2)); + double x = (v + h) * cos(lat) * cos(lon); + double y = (v + h) * cos(lat) * sin(lon); + double z = ((1 - es) * v + h) * sin(lat); + QVector ret(3); + ret[0]=x; + ret[1]=y; + ret[2]=z; + return ret; +} +QVector LKS94Projection::MTD10(QVector & pnt) +{ + QVector ret(3); + const double COS_67P5 = 0.38268343236508977; // cosine of 67.5 degrees + const double AD_C = 1.0026000; // Toms region 1 constant + + double es; // Eccentricity squared : (a^2 - b^2)/a^2 + double semiMajor = 6378137.0; // major axis + double semiMinor = 6356752.3141403561; // minor axis + double ab; // Semi_major / semi_minor + double ba; // Semi_minor / semi_major + double ses; // Second eccentricity squared : (a^2 - b^2)/b^2 + + es = 1.0 - (semiMinor * semiMinor) / (semiMajor * semiMajor); //e^2 + ses = (pow(semiMajor, 2) - pow(semiMinor, 2)) / pow(semiMinor, 2); + ba = semiMinor / semiMajor; + ab = semiMajor / semiMinor; + + // ... + + bool AtPole = false; // is location in polar region + double Z = pnt.count() < 3 ? 0 : std::isnan(pnt[2]) ? 0 : pnt[2];//TODO NaN + + double lon = 0; + double lat = 0; + double Height = 0; + if(pnt[0] != 0.0) + { + lon = atan2(pnt[1], pnt[0]); + } + else + { + if(pnt[1] > 0) + { + lon = M_PI / 2; + } + else + if(pnt[1] < 0) + { + lon = -M_PI * 0.5; + } + else + { + AtPole = true; + lon = 0.0; + if(Z > 0.0) // north pole + { + lat = M_PI * 0.5; + } + else + if(Z < 0.0) // south pole + { + lat = -M_PI * 0.5; + } + else // center of earth + { + ret[0]=RadiansToDegrees(lon); + ret[1]=RadiansToDegrees(M_PI * 0.5); + ret[2]=-semiMinor; + return ret; + } + } + } + double W2 = pnt[0] * pnt[0] + pnt[1] * pnt[1]; // Square of distance from Z axis + double W = sqrt(W2); // distance from Z axis + double T0 = Z * AD_C; // initial estimate of vertical component + double S0 = sqrt(T0 * T0 + W2); // initial estimate of horizontal component + double Sin_B0 = T0 / S0; // sin(B0), B0 is estimate of Bowring aux variable + double Cos_B0 = W / S0; // cos(B0) + double Sin3_B0 = pow(Sin_B0, 3); + double T1 = Z + semiMinor * ses * Sin3_B0; // corrected estimate of vertical component + double Sum = W - semiMajor * es * Cos_B0 * Cos_B0 * Cos_B0; // numerator of cos(phi1) + double S1 = sqrt(T1 * T1 + Sum * Sum); // corrected estimate of horizontal component + double Sin_p1 = T1 / S1; // sin(phi1), phi1 is estimated latitude + double Cos_p1 = Sum / S1; // cos(phi1) + double Rn = semiMajor / sqrt(1.0 - es * Sin_p1 * Sin_p1); // Earth radius at location + if(Cos_p1 >= COS_67P5) + { + Height = W / Cos_p1 - Rn; + } + else + if(Cos_p1 <= -COS_67P5) + { + Height = W / -Cos_p1 - Rn; + } + else + { + Height = Z / Sin_p1 + Rn * (es - 1.0); + } + + if(!AtPole) + { + lat = atan(Sin_p1 / Cos_p1); + } + ret[0]=RadiansToDegrees(lon); + ret[1]=RadiansToDegrees(lat); + ret[2]=Height; + return ret; +} +QVector LKS94Projection::DTM00(QVector & lonlat) +{ + double scaleFactor = 0.9998; // scale factor + double centralMeridian = 0.41887902047863912; // Center qlonglongitude (projection center) */ + double latOrigin = 0.0; // center latitude + double falseNorthing = 0.0; // y offset in meters + double falseEasting = 500000.0; // x offset in meters + double semiMajor = 6378137.0; // major axis + double semiMinor = 6356752.3141403561; // minor axis + double metersPerUnit = 1.0; + + double e0, e1, e2, e3; // eccentricity constants + double e, es, esp; // eccentricity constants + double ml0; // small value m + + es = 1.0 - pow(semiMinor / semiMajor, 2); + e = sqrt(es); + e0 = e0fn(es); + e1 = e1fn(es); + e2 = e2fn(es); + e3 = e3fn(es); + ml0 = semiMajor * mlfn(e0, e1, e2, e3, latOrigin); + esp = es / (1.0 - es); + + // ... + + double lon = DegreesToRadians(lonlat[0]); + double lat = DegreesToRadians(lonlat[1]); + + double delta_lon = 0.0; // Delta qlonglongitude (Given qlonglongitude - center) + double sin_phi, cos_phi; // sin and cos value + double al, als; // temporary values + double c, t, tq; // temporary values + double con, n, ml; // cone constant, small m + + delta_lon = LKS94Projection::AdjustLongitude(lon - centralMeridian); + LKS94Projection::SinCos(lat, sin_phi, cos_phi); + + al = cos_phi * delta_lon; + als = pow(al, 2); + c = pow(cos_phi, 2); + tq = tan(lat); + t = pow(tq, 2); + con = 1.0 - es * pow(sin_phi, 2); + n = semiMajor / sqrt(con); + ml = semiMajor * mlfn(e0, e1, e2, e3, lat); + + double x = scaleFactor * n * al * (1.0 + als / 6.0 * (1.0 - t + c + als / 20.0 * + (5.0 - 18.0 * t + pow(t, 2) + 72.0 * c - 58.0 * esp))) + falseEasting; + + double y = scaleFactor * (ml - ml0 + n * tq * (als * (0.5 + als / 24.0 * + (5.0 - t + 9.0 * c + 4.0 * pow(c, 2) + als / 30.0 * (61.0 - 58.0 * t + + pow(t, 2) + 600.0 * c - 330.0 * esp))))) + falseNorthing; + + if(lonlat.count() < 3) + { + QVector ret(2); + ret[0]= x / metersPerUnit; + ret[1]= y / metersPerUnit; + return ret; + } + else + { + QVector ret(3); + ret[0]= x / metersPerUnit; + ret[1]= y / metersPerUnit; + ret[2]=lonlat[2]; + return ret; + } +} + +QVector LKS94Projection::DTM01(QVector & lonlat) +{ + double es; // Eccentricity squared : (a^2 - b^2)/a^2 + double semiMajor = 6378137.0; // major axis + double semiMinor = 6356752.3141403561; // minor axis + double ab; // Semi_major / semi_minor + double ba; // Semi_minor / semi_major + double ses; // Second eccentricity squared : (a^2 - b^2)/b^2 + + es = 1.0 - (semiMinor * semiMinor) / (semiMajor * semiMajor); + ses = (pow(semiMajor, 2) -pow(semiMinor, 2)) / pow(semiMinor, 2); + ba = semiMinor / semiMajor; + ab = semiMajor / semiMinor; + + // ... + + double lon = DegreesToRadians(lonlat[0]); + double lat = DegreesToRadians(lonlat[1]); + double h = lonlat.count() < 3 ? 0 : std::isnan(lonlat[2]) ? 0 : lonlat[2];//TODO NaN + double v = semiMajor / sqrt(1 - es * pow(sin(lat), 2)); + double x = (v + h) * cos(lat) * cos(lon); + double y = (v + h) * cos(lat) * sin(lon); + double z = ((1 - es) * v + h) * sin(lat); + QVector ret(3); + ret[0]=x; + ret[1]=y; + ret[2]=z; + return ret; +} +QVector LKS94Projection::MTD01(QVector & pnt) +{ + const double COS_67P5 = 0.38268343236508977; // cosine of 67.5 degrees + const double AD_C = 1.0026000; // Toms region 1 constant + + double es; // Eccentricity squared : (a^2 - b^2)/a^2 + double semiMajor = 6378137.0; // major axis + double semiMinor = 6356752.3142451793; // minor axis + double ab; // Semi_major / semi_minor + double ba; // Semi_minor / semi_major + double ses; // Second eccentricity squared : (a^2 - b^2)/b^2 + + es = 1.0 - (semiMinor * semiMinor) / (semiMajor * semiMajor); + ses = (pow(semiMajor, 2) - pow(semiMinor, 2)) / pow(semiMinor, 2); + ba = semiMinor / semiMajor; + ab = semiMajor / semiMinor; + + // ... + + bool At_Pole = false; // is location in polar region + double Z = pnt.count() < 3 ? 0 : std::isnan(pnt[2]) ? 0 : pnt[2];//TODO NaN + + double lon = 0; + double lat = 0; + double Height = 0; + if(pnt[0] != 0.0) + { + lon = atan2(pnt[1], pnt[0]); + } + else + { + if(pnt[1] > 0) + { + lon = M_PI / 2; + } + else + if(pnt[1] < 0) + { + lon = -M_PI * 0.5; + } + else + { + At_Pole = true; + lon = 0.0; + if(Z > 0.0) // north pole + { + lat = M_PI * 0.5; + } + else + if(Z < 0.0) // south pole + { + lat = -M_PI * 0.5; + } + else // center of earth + { + QVector ret(3); + ret[0]=RadiansToDegrees(lon); + ret[1]=RadiansToDegrees(M_PI * 0.5); + ret[2]=-semiMinor; + return ret; + } + } + } + + double W2 = pnt[0] * pnt[0] + pnt[1] * pnt[1]; // Square of distance from Z axis + double W = sqrt(W2); // distance from Z axis + double T0 = Z * AD_C; // initial estimate of vertical component + double S0 = sqrt(T0 * T0 + W2); //initial estimate of horizontal component + double Sin_B0 = T0 / S0; // sin(B0), B0 is estimate of Bowring aux variable + double Cos_B0 = W / S0; // cos(B0) + double Sin3_B0 = pow(Sin_B0, 3); + double T1 = Z + semiMinor * ses * Sin3_B0; //corrected estimate of vertical component + double Sum = W - semiMajor * es * Cos_B0 * Cos_B0 * Cos_B0; // numerator of cos(phi1) + double S1 = sqrt(T1 * T1 + Sum * Sum); // corrected estimate of horizontal component + double Sin_p1 = T1 / S1; // sin(phi1), phi1 is estimated latitude + double Cos_p1 = Sum / S1; // cos(phi1) + double Rn = semiMajor / sqrt(1.0 - es * Sin_p1 * Sin_p1); // Earth radius at location + + if(Cos_p1 >= COS_67P5) + { + Height = W / Cos_p1 - Rn; + } + else + if(Cos_p1 <= -COS_67P5) + { + Height = W / -Cos_p1 - Rn; + } + else + { + Height = Z / Sin_p1 + Rn * (es - 1.0); + } + + if(!At_Pole) + { + lat = atan(Sin_p1 / Cos_p1); + } + QVector ret(3); + ret[0]=RadiansToDegrees(lon); + ret[1]=RadiansToDegrees(lat); + ret[2]=Height; + return ret; +} +QVector LKS94Projection::MTD11(QVector & p) +{ + double scaleFactor = 0.9998; // scale factor + double centralMeridian = 0.41887902047863912; // Center qlonglongitude (projection center) + double latOrigin = 0.0; // center latitude + double falseNorthing = 0.0; // y offset in meters + double falseEasting = 500000.0; // x offset in meters + double semiMajor = 6378137.0; // major axis + double semiMinor = 6356752.3141403561; // minor axis + double metersPerUnit = 1.0; + + double e0, e1, e2, e3; // eccentricity constants + double e, es, esp; // eccentricity constants + double ml0; // small value m + + es =(semiMinor * semiMinor) / (semiMajor * semiMajor); + es=1.0-es; + e = sqrt(es); + e0 = e0fn(es); + e1 = e1fn(es); + e2 = e2fn(es); + e3 = e3fn(es); + ml0 = semiMajor * mlfn(e0, e1, e2, e3, latOrigin); + esp = es / (1.0 - es); + + // ... + + double con, phi; + double delta_phi; + qlonglong i; + double sin_phi, cos_phi, tan_phi; + double c, cs, t, ts, n, r, d, ds; + qlonglong max_iter = 6; + + double x = p[0] * metersPerUnit - falseEasting; + double y = p[1] * metersPerUnit - falseNorthing; + + con = (ml0 + y / scaleFactor) / semiMajor; + phi = con; + for(i = 0; ; i++) + { + delta_phi = ((con + e1 * sin(2.0 * phi) - e2 * sin(4.0 * phi) + e3 * sin(6.0 * phi)) / e0) - phi; + phi += delta_phi; + if(fabs(delta_phi) <= EPSLoN) + break; + + if(i >= max_iter) + throw "Latitude failed to converge"; + } + + if(fabs(phi) < HALF_PI) + { + SinCos(phi, sin_phi, cos_phi); + tan_phi = tan(phi); + c = esp * pow(cos_phi, 2); + cs = pow(c, 2); + t = pow(tan_phi, 2); + ts = pow(t, 2); + con = 1.0 - es * pow(sin_phi, 2); + n = semiMajor / sqrt(con); + r = n * (1.0 - es) / con; + d = x / (n * scaleFactor); + ds = pow(d, 2); + + double lat = phi - (n * tan_phi * ds / r) * (0.5 - ds / 24.0 * (5.0 + 3.0 * t + + 10.0 * c - 4.0 * cs - 9.0 * esp - ds / 30.0 * (61.0 + 90.0 * t + + 298.0 * c + 45.0 * ts - 252.0 * esp - 3.0 * cs))); + + double lon = AdjustLongitude(centralMeridian + (d * (1.0 - ds / 6.0 * (1.0 + 2.0 * t + + c - ds / 20.0 * (5.0 - 2.0 * c + 28.0 * t - 3.0 * cs + 8.0 * esp + + 24.0 * ts))) / cos_phi)); + + if(p.count() < 3) + { + QVector ret(2); + ret[0]= RadiansToDegrees(lon); + ret[1]= RadiansToDegrees(lat); + return ret; + } + else + { + QVector ret(3); + ret[0]= RadiansToDegrees(lon); + ret[1]= RadiansToDegrees(lat); + ret[2]=p[2]; + return ret; + //return new double[] { RadiansToDegrees(lon), RadiansToDegrees(lat), p[2] }; + } + } + else + { + if(p.count() < 3) + { + QVector ret(2); + ret[0]= RadiansToDegrees(HALF_PI * Sign(y)); + ret[1]= RadiansToDegrees(centralMeridian); + return ret; + } + + else + { + QVector ret(3); + ret[0]= RadiansToDegrees(HALF_PI * Sign(y)); + ret[1]= RadiansToDegrees(centralMeridian); + ret[2]=p[2]; + return ret; + } + + } +} + +double LKS94Projection::Clip(double const& n, double const& minValue, double const& maxValue) +{ + return qMin(qMax(n, minValue), maxValue); +} +double LKS94Projection::GetTileMatrixResolution(int const& zoom) +{ + double ret = 0; + + switch(zoom) + { + case 0: + { + ret = 1587.50317500635; + } + break; + + case 1: + { + ret = 793.751587503175; + } + break; + + case 2: + { + ret = 529.167725002117; + } + break; + + case 3: + { + ret = 264.583862501058; + } + break; + + case 4: + { + ret = 132.291931250529; + } + break; + + case 5: + { + ret = 52.9167725002117; + } + break; + + case 6: + { + ret = 26.4583862501058; + } + break; + + case 7: + { + ret = 13.2291931250529; + } + break; + + case 8: + { + ret = 6.61459656252646; + } + break; + + case 9: + { + ret = 2.64583862501058; + } + break; + + case 10: + { + ret = 1.32291931250529; + } + break; + + case 11: + { + ret = 0.529167725002117; + } + break; + + } + + return ret; +} +/* + * Returns the conversion from pixels to meters + */ +double LKS94Projection::GetGroundResolution(int const& zoom, double const& latitude) +{ + Q_UNUSED(zoom); + Q_UNUSED(latitude); + return GetTileMatrixResolution(zoom); +} +Size LKS94Projection::GetTileMatrixMinXY(int const& zoom) +{ + Size ret; + + switch(zoom) + { + + case 0: + { + ret = Size(12, 8); + } + break; + + case 1: + { + ret = Size(24, 17); + } + break; + + case 2: + { + ret = Size(37, 25); + } + break; + + case 3: + { + ret = Size(74, 51); + } + break; + + case 4: + { + ret = Size(149, 103); + } + break; + + case 5: + { + ret = Size(374, 259); + } + break; + + case 6: + { + ret = Size(749, 519); + } + break; + + case 7: + { + ret = Size(1594, 1100); + } + break; + + case 8: + { + ret = Size(3188, 2201); + } + break; + + case 9: + { + ret = Size(7971, 5502); + } + break; + + case 10: + { + ret = Size(15943, 11005); + } + break; + + case 11: + { + ret = Size(39858, 27514); + } + break; + } + + return ret; +} + +Size LKS94Projection::GetTileMatrixMaxXY(int const& zoom) +{ + Size ret; + + switch(zoom) + { + case 0: + { + ret = Size(14, 10); + } + break; + + case 1: + { + ret = Size(30, 20); + } + break; + + case 2: + { + ret = Size(45, 31); + } + break; + + case 3: + { + ret = Size(90, 62); + } + break; + + case 4: + { + ret = Size(181, 125); + } + break; + + case 5: + { + ret = Size(454, 311); + } + break; + + case 6: + { + ret = Size(903, 623); + } + break; + + case 7: + { + ret = Size(1718, 1193); + } + break; + + case 8: + { + ret = Size(3437, 2386); + } + break; + + case 9: + { + ret = Size(8594, 5966); + } + break; + + case 10: + { + ret = Size(17189, 11932); + } + break; + + case 11: + { + ret = Size(42972, 29831); + } + break; + } + + return ret; +} + +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h index d3e09b868..d20289dd7 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h @@ -1,72 +1,72 @@ -/** -****************************************************************************** -* -* @file lks94projection.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef LKS94PROJECTION_H -#define LKS94PROJECTION_H -#include -#include "cmath" -#include "../pureprojection.h" - - -namespace projections { -class LKS94Projection:public internals::PureProjection -{ -public: - LKS94Projection(); - double GetTileMatrixResolution(int const& zoom); - virtual QString Type(){return "LKS94Projection";} - virtual Size TileSize() const; - virtual double Axis() const; - virtual double Flattening() const; - virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom); - virtual internals::PointLatLng FromPixelToLatLng(int const& x, int const& y, int const& zoom); - virtual double GetGroundResolution(int const& zoom, double const& latitude); - virtual Size GetTileMatrixMinXY(int const& zoom); - virtual Size GetTileMatrixMaxXY(int const& zoom); - -private: - const double MinLatitude; - const double MaxLatitude; - const double MinLongitude; - const double MaxLongitude; - const double orignX; - const double orignY; - Size tileSize; - QVector DTM10(const QVector & lonlat); - QVector MTD10(QVector & pnt); - QVector DTM00(QVector & lonlat); - QVector DTM01(QVector & lonlat); - QVector MTD01(QVector & pnt); - QVector MTD11(QVector & p); - double Clip(double const& n, double const& minValue, double const& maxValue); -}; - -} -#endif // LKS94PROJECTION_H - - - - +/** +****************************************************************************** +* +* @file lks94projection.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef LKS94PROJECTION_H +#define LKS94PROJECTION_H +#include +#include "cmath" +#include "../pureprojection.h" + + +namespace projections { +class LKS94Projection:public internals::PureProjection +{ +public: + LKS94Projection(); + double GetTileMatrixResolution(int const& zoom); + virtual QString Type(){return "LKS94Projection";} + virtual Size TileSize() const; + virtual double Axis() const; + virtual double Flattening() const; + virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom); + virtual internals::PointLatLng FromPixelToLatLng(int const& x, int const& y, int const& zoom); + virtual double GetGroundResolution(int const& zoom, double const& latitude); + virtual Size GetTileMatrixMinXY(int const& zoom); + virtual Size GetTileMatrixMaxXY(int const& zoom); + +private: + const double MinLatitude; + const double MaxLatitude; + const double MinLongitude; + const double MaxLongitude; + const double orignX; + const double orignY; + Size tileSize; + QVector DTM10(const QVector & lonlat); + QVector MTD10(QVector & pnt); + QVector DTM00(QVector & lonlat); + QVector DTM01(QVector & lonlat); + QVector MTD01(QVector & pnt); + QVector MTD11(QVector & p); + double Clip(double const& n, double const& minValue, double const& maxValue); +}; + +} +#endif // LKS94PROJECTION_H + + + + diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp index cd5bbb95b..9f3021672 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.cpp @@ -1,98 +1,98 @@ -/** -****************************************************************************** -* -* @file mercatorprojection.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "mercatorprojection.h" - - -namespace projections { -MercatorProjection::MercatorProjection():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-177), -MaxLongitude(177), tileSize(256, 256) -{ -} -Point MercatorProjection::FromLatLngToPixel(double lat, double lng, const int &zoom) -{ - Point ret;// = Point.Empty; - - lat = Clip(lat, MinLatitude, MaxLatitude); - lng = Clip(lng, MinLongitude, MaxLongitude); - - double x = (lng + 180) / 360; - double sinLatitude = sin(lat * M_PI / 180); - double y = 0.5 - log((1 + sinLatitude) / (1 - sinLatitude)) / (4 * M_PI); - - Size s = GetTileMatrixSizePixel(zoom); - int mapSizeX = s.Width(); - int mapSizeY = s.Height(); - - ret.SetX((int) Clip(x * mapSizeX + 0.5, 0, mapSizeX - 1)); - ret.SetY((int) Clip(y * mapSizeY + 0.5, 0, mapSizeY - 1)); - - return ret; -} -internals::PointLatLng MercatorProjection::FromPixelToLatLng(const int &x, const int &y, const int &zoom) -{ - internals::PointLatLng ret;// = internals::PointLatLng.Empty; - - Size s = GetTileMatrixSizePixel(zoom); - double mapSizeX = s.Width(); - double mapSizeY = s.Height(); - - double xx = (Clip(x, 0, mapSizeX - 1) / mapSizeX) - 0.5; - double yy = 0.5 - (Clip(y, 0, mapSizeY - 1) / mapSizeY); - - ret.SetLat(90 - 360 * atan(exp(-yy * 2 * M_PI)) / M_PI); - ret.SetLng(360 * xx); - - return ret; -} -double MercatorProjection::Clip(const double &n, const double &minValue, const double &maxValue) const -{ - return qMin(qMax(n, minValue), maxValue); -} -Size MercatorProjection::TileSize() const -{ - return tileSize; -} -double MercatorProjection::Axis() const -{ - return 6378137; -} -double MercatorProjection::Flattening() const -{ - return (1.0 / 298.257223563); -} -Size MercatorProjection::GetTileMatrixMaxXY(const int &zoom) -{ - Q_UNUSED(zoom); - int xy = (1 << zoom); - return Size(xy - 1, xy - 1); -} -Size MercatorProjection::GetTileMatrixMinXY(const int &zoom) -{ - Q_UNUSED(zoom); - return Size(0, 0); -} -} +/** +****************************************************************************** +* +* @file mercatorprojection.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "mercatorprojection.h" + + +namespace projections { +MercatorProjection::MercatorProjection():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-177), +MaxLongitude(177), tileSize(256, 256) +{ +} +Point MercatorProjection::FromLatLngToPixel(double lat, double lng, const int &zoom) +{ + Point ret;// = Point.Empty; + + lat = Clip(lat, MinLatitude, MaxLatitude); + lng = Clip(lng, MinLongitude, MaxLongitude); + + double x = (lng + 180) / 360; + double sinLatitude = sin(lat * M_PI / 180); + double y = 0.5 - log((1 + sinLatitude) / (1 - sinLatitude)) / (4 * M_PI); + + Size s = GetTileMatrixSizePixel(zoom); + int mapSizeX = s.Width(); + int mapSizeY = s.Height(); + + ret.SetX((int) Clip(x * mapSizeX + 0.5, 0, mapSizeX - 1)); + ret.SetY((int) Clip(y * mapSizeY + 0.5, 0, mapSizeY - 1)); + + return ret; +} +internals::PointLatLng MercatorProjection::FromPixelToLatLng(const int &x, const int &y, const int &zoom) +{ + internals::PointLatLng ret;// = internals::PointLatLng.Empty; + + Size s = GetTileMatrixSizePixel(zoom); + double mapSizeX = s.Width(); + double mapSizeY = s.Height(); + + double xx = (Clip(x, 0, mapSizeX - 1) / mapSizeX) - 0.5; + double yy = 0.5 - (Clip(y, 0, mapSizeY - 1) / mapSizeY); + + ret.SetLat(90 - 360 * atan(exp(-yy * 2 * M_PI)) / M_PI); + ret.SetLng(360 * xx); + + return ret; +} +double MercatorProjection::Clip(const double &n, const double &minValue, const double &maxValue) const +{ + return qMin(qMax(n, minValue), maxValue); +} +Size MercatorProjection::TileSize() const +{ + return tileSize; +} +double MercatorProjection::Axis() const +{ + return 6378137; +} +double MercatorProjection::Flattening() const +{ + return (1.0 / 298.257223563); +} +Size MercatorProjection::GetTileMatrixMaxXY(const int &zoom) +{ + Q_UNUSED(zoom); + int xy = (1 << zoom); + return Size(xy - 1, xy - 1); +} +Size MercatorProjection::GetTileMatrixMinXY(const int &zoom) +{ + Q_UNUSED(zoom); + return Size(0, 0); +} +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.h index 25e52df1b..d36b45c25 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojection.h @@ -1,55 +1,55 @@ -/** -****************************************************************************** -* -* @file mercatorprojection.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef MERCATORPROJECTION_H -#define MERCATORPROJECTION_H -#include "../pureprojection.h" - - -namespace projections { - class MercatorProjection:public internals::PureProjection -{ -public: - MercatorProjection(); - virtual QString Type(){return "MercatorProjection";} - virtual Size TileSize() const; - virtual double Axis() const; - virtual double Flattening()const; - virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom); - virtual internals::PointLatLng FromPixelToLatLng(const int &x,const int &y,const int &zoom); - virtual Size GetTileMatrixMinXY(const int &zoom); - virtual Size GetTileMatrixMaxXY(const int &zoom); -private: - const double MinLatitude; - const double MaxLatitude; - const double MinLongitude; - const double MaxLongitude; - double Clip(double const& n, double const& minValue, double const& maxValue)const; - Size tileSize; -}; - -} -#endif // MERCATORPROJECTION_H +/** +****************************************************************************** +* +* @file mercatorprojection.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef MERCATORPROJECTION_H +#define MERCATORPROJECTION_H +#include "../pureprojection.h" + + +namespace projections { + class MercatorProjection:public internals::PureProjection +{ +public: + MercatorProjection(); + virtual QString Type(){return "MercatorProjection";} + virtual Size TileSize() const; + virtual double Axis() const; + virtual double Flattening()const; + virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom); + virtual internals::PointLatLng FromPixelToLatLng(const int &x,const int &y,const int &zoom); + virtual Size GetTileMatrixMinXY(const int &zoom); + virtual Size GetTileMatrixMaxXY(const int &zoom); +private: + const double MinLatitude; + const double MaxLatitude; + const double MinLongitude; + const double MaxLongitude; + double Clip(double const& n, double const& minValue, double const& maxValue)const; + Size tileSize; +}; + +} +#endif // MERCATORPROJECTION_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp index 54812e60c..f2495c1f4 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp @@ -1,112 +1,112 @@ -/** -****************************************************************************** -* -* @file mercatorprojectionyandex.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "mercatorprojectionyandex.h" - - - -namespace projections { -MercatorProjectionYandex::MercatorProjectionYandex():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-177), -MaxLongitude(177), RAD_DEG(180 / M_PI),DEG_RAD(M_PI / 180),MathPiDiv4(M_PI / 4),tileSize(256, 256) -{ -} -Point MercatorProjectionYandex::FromLatLngToPixel(double lat, double lng, const int &zoom) -{ - lat = Clip(lat, MinLatitude, MaxLatitude); - lng = Clip(lng, MinLongitude, MaxLongitude); - - double rLon = lng * DEG_RAD; // Math.PI / 180; - double rLat = lat * DEG_RAD; // Math.PI / 180; - - double a = 6378137; - double k = 0.0818191908426; - - double z = tan(MathPiDiv4 + rLat / 2) / pow((tan(MathPiDiv4 + asin(k * sin(rLat)) / 2)), k); - double z1 = pow(2, 23 - zoom); - - double DX = ((20037508.342789 + a * rLon) * 53.5865938 / z1); - double DY = ((20037508.342789 - a * log(z)) * 53.5865938 / z1); - - Point ret;// = Point.Empty; - ret.SetX((int) DX); - ret.SetY((int) DY); - - return ret; - -} -internals::PointLatLng MercatorProjectionYandex::FromPixelToLatLng(const int &x, const int &y, const int &zoom) -{ - Size s = GetTileMatrixSizePixel(zoom); - - //double mapSizeX = s.Width(); - //double mapSizeY = s.Height(); - - double a = 6378137; - double c1 = 0.00335655146887969; - double c2 = 0.00000657187271079536; - double c3 = 0.00000001764564338702; - double c4 = 0.00000000005328478445; - double z1 = (23 - zoom); - double mercX = (x * pow(2, z1)) / 53.5865938 - 20037508.342789; - double mercY = 20037508.342789 - (y *pow(2, z1)) / 53.5865938; - - double g = M_PI /2 - 2 *atan(1 / exp(mercY /a)); - double z = g + c1 * sin(2 * g) + c2 * sin(4 * g) + c3 * sin(6 * g) + c4 * sin(8 * g); - - internals::PointLatLng ret;// = internals::PointLatLng.Empty; - ret.SetLat(z * RAD_DEG); - ret.SetLng (mercX / a * RAD_DEG); - - return ret; -} -double MercatorProjectionYandex::Clip(const double &n, const double &minValue, const double &maxValue) const -{ - return qMin(qMax(n, minValue), maxValue); -} -Size MercatorProjectionYandex::TileSize() const -{ - return tileSize; -} -double MercatorProjectionYandex::Axis() const -{ - return 6356752.3142; -} -double MercatorProjectionYandex::Flattening() const -{ - return (1.0 / 298.257223563); -} -Size MercatorProjectionYandex::GetTileMatrixMaxXY(const int &zoom) -{ - int xy = (1 << zoom); - return Size(xy - 1, xy - 1); -} - -Size MercatorProjectionYandex::GetTileMatrixMinXY(const int &zoom) -{ - Q_UNUSED(zoom); - return Size(0, 0); -} -} +/** +****************************************************************************** +* +* @file mercatorprojectionyandex.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "mercatorprojectionyandex.h" + + + +namespace projections { +MercatorProjectionYandex::MercatorProjectionYandex():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-177), +MaxLongitude(177), RAD_DEG(180 / M_PI),DEG_RAD(M_PI / 180),MathPiDiv4(M_PI / 4),tileSize(256, 256) +{ +} +Point MercatorProjectionYandex::FromLatLngToPixel(double lat, double lng, const int &zoom) +{ + lat = Clip(lat, MinLatitude, MaxLatitude); + lng = Clip(lng, MinLongitude, MaxLongitude); + + double rLon = lng * DEG_RAD; // Math.PI / 180; + double rLat = lat * DEG_RAD; // Math.PI / 180; + + double a = 6378137; + double k = 0.0818191908426; + + double z = tan(MathPiDiv4 + rLat / 2) / pow((tan(MathPiDiv4 + asin(k * sin(rLat)) / 2)), k); + double z1 = pow(2, 23 - zoom); + + double DX = ((20037508.342789 + a * rLon) * 53.5865938 / z1); + double DY = ((20037508.342789 - a * log(z)) * 53.5865938 / z1); + + Point ret;// = Point.Empty; + ret.SetX((int) DX); + ret.SetY((int) DY); + + return ret; + +} +internals::PointLatLng MercatorProjectionYandex::FromPixelToLatLng(const int &x, const int &y, const int &zoom) +{ + Size s = GetTileMatrixSizePixel(zoom); + + //double mapSizeX = s.Width(); + //double mapSizeY = s.Height(); + + double a = 6378137; + double c1 = 0.00335655146887969; + double c2 = 0.00000657187271079536; + double c3 = 0.00000001764564338702; + double c4 = 0.00000000005328478445; + double z1 = (23 - zoom); + double mercX = (x * pow(2, z1)) / 53.5865938 - 20037508.342789; + double mercY = 20037508.342789 - (y *pow(2, z1)) / 53.5865938; + + double g = M_PI /2 - 2 *atan(1 / exp(mercY /a)); + double z = g + c1 * sin(2 * g) + c2 * sin(4 * g) + c3 * sin(6 * g) + c4 * sin(8 * g); + + internals::PointLatLng ret;// = internals::PointLatLng.Empty; + ret.SetLat(z * RAD_DEG); + ret.SetLng (mercX / a * RAD_DEG); + + return ret; +} +double MercatorProjectionYandex::Clip(const double &n, const double &minValue, const double &maxValue) const +{ + return qMin(qMax(n, minValue), maxValue); +} +Size MercatorProjectionYandex::TileSize() const +{ + return tileSize; +} +double MercatorProjectionYandex::Axis() const +{ + return 6356752.3142; +} +double MercatorProjectionYandex::Flattening() const +{ + return (1.0 / 298.257223563); +} +Size MercatorProjectionYandex::GetTileMatrixMaxXY(const int &zoom) +{ + int xy = (1 << zoom); + return Size(xy - 1, xy - 1); +} + +Size MercatorProjectionYandex::GetTileMatrixMinXY(const int &zoom) +{ + Q_UNUSED(zoom); + return Size(0, 0); +} +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.h index af9cc620e..f7be2c786 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.h @@ -1,59 +1,59 @@ -/** -****************************************************************************** -* -* @file mercatorprojectionyandex.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef MERCATORPROJECTIONYANDEX_H -#define MERCATORPROJECTIONYANDEX_H - -#include "../pureprojection.h" - - -namespace projections { - class MercatorProjectionYandex:public internals::PureProjection -{ -public: - MercatorProjectionYandex(); - virtual QString Type(){return "MercatorProjectionYandex";} - virtual Size TileSize() const; - virtual double Axis() const; - virtual double Flattening()const; - virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom); - virtual internals::PointLatLng FromPixelToLatLng(const int &x,const int &y,const int &zoom); - virtual Size GetTileMatrixMinXY(const int &zoom); - virtual Size GetTileMatrixMaxXY(const int &zoom); -private: - const double MinLatitude; - const double MaxLatitude; - const double MinLongitude; - const double MaxLongitude; - const double RAD_DEG; - const double DEG_RAD; - const double MathPiDiv4; - double Clip(double const& n, double const& minValue, double const& maxValue)const; - Size tileSize; -}; - -} -#endif // MERCATORPROJECTIONYANDEX_H +/** +****************************************************************************** +* +* @file mercatorprojectionyandex.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef MERCATORPROJECTIONYANDEX_H +#define MERCATORPROJECTIONYANDEX_H + +#include "../pureprojection.h" + + +namespace projections { + class MercatorProjectionYandex:public internals::PureProjection +{ +public: + MercatorProjectionYandex(); + virtual QString Type(){return "MercatorProjectionYandex";} + virtual Size TileSize() const; + virtual double Axis() const; + virtual double Flattening()const; + virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom); + virtual internals::PointLatLng FromPixelToLatLng(const int &x,const int &y,const int &zoom); + virtual Size GetTileMatrixMinXY(const int &zoom); + virtual Size GetTileMatrixMaxXY(const int &zoom); +private: + const double MinLatitude; + const double MaxLatitude; + const double MinLongitude; + const double MaxLongitude; + const double RAD_DEG; + const double DEG_RAD; + const double MathPiDiv4; + double Clip(double const& n, double const& minValue, double const& maxValue)const; + Size tileSize; +}; + +} +#endif // MERCATORPROJECTIONYANDEX_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp index 27fd90808..16b0f0400 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.cpp @@ -1,97 +1,97 @@ -/** -****************************************************************************** -* -* @file platecarreeprojection.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "platecarreeprojection.h" - - - -namespace projections { -PlateCarreeProjection::PlateCarreeProjection():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-180), -MaxLongitude(180), tileSize(512, 512) -{ -} -Point PlateCarreeProjection::FromLatLngToPixel(double lat, double lng, const int &zoom) -{ - Point ret;// = Point.Empty; - - lat = Clip(lat, MinLatitude, MaxLatitude); - lng = Clip(lng, MinLongitude, MaxLongitude); - - Size s = GetTileMatrixSizePixel(zoom); - double mapSizeX = s.Width(); - //double mapSizeY = s.Height(); - - double scale = 360.0 / mapSizeX; - - ret.SetY((int) ((90.0 - lat) / scale)); - ret.SetX((int) ((lng + 180.0) / scale)); - - return ret; - -} -internals::PointLatLng PlateCarreeProjection::FromPixelToLatLng(const int &x, const int &y, const int &zoom) -{ - internals::PointLatLng ret;// = internals::PointLatLng.Empty; - - Size s = GetTileMatrixSizePixel(zoom); - double mapSizeX = s.Width(); - //double mapSizeY = s.Height(); - - double scale = 360.0 / mapSizeX; - - ret.SetLat(90 - (y * scale)); - ret.SetLng((x * scale) - 180); - - return ret; -} -double PlateCarreeProjection::Clip(const double &n, const double &minValue, const double &maxValue) const -{ - return qMin(qMax(n, minValue), maxValue); -} -Size PlateCarreeProjection::TileSize() const -{ - return tileSize; -} -double PlateCarreeProjection::Axis() const -{ - return 6378137; -} -double PlateCarreeProjection::Flattening() const -{ - return (1.0 / 298.257223563); -} -Size PlateCarreeProjection::GetTileMatrixMaxXY(const int &zoom) -{ - int y = (int) pow(2, zoom); - return Size((2*y) - 1, y - 1); -} - -Size PlateCarreeProjection::GetTileMatrixMinXY(const int &zoom) -{ - Q_UNUSED(zoom); - return Size(0, 0); -} -} +/** +****************************************************************************** +* +* @file platecarreeprojection.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "platecarreeprojection.h" + + + +namespace projections { +PlateCarreeProjection::PlateCarreeProjection():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-180), +MaxLongitude(180), tileSize(512, 512) +{ +} +Point PlateCarreeProjection::FromLatLngToPixel(double lat, double lng, const int &zoom) +{ + Point ret;// = Point.Empty; + + lat = Clip(lat, MinLatitude, MaxLatitude); + lng = Clip(lng, MinLongitude, MaxLongitude); + + Size s = GetTileMatrixSizePixel(zoom); + double mapSizeX = s.Width(); + //double mapSizeY = s.Height(); + + double scale = 360.0 / mapSizeX; + + ret.SetY((int) ((90.0 - lat) / scale)); + ret.SetX((int) ((lng + 180.0) / scale)); + + return ret; + +} +internals::PointLatLng PlateCarreeProjection::FromPixelToLatLng(const int &x, const int &y, const int &zoom) +{ + internals::PointLatLng ret;// = internals::PointLatLng.Empty; + + Size s = GetTileMatrixSizePixel(zoom); + double mapSizeX = s.Width(); + //double mapSizeY = s.Height(); + + double scale = 360.0 / mapSizeX; + + ret.SetLat(90 - (y * scale)); + ret.SetLng((x * scale) - 180); + + return ret; +} +double PlateCarreeProjection::Clip(const double &n, const double &minValue, const double &maxValue) const +{ + return qMin(qMax(n, minValue), maxValue); +} +Size PlateCarreeProjection::TileSize() const +{ + return tileSize; +} +double PlateCarreeProjection::Axis() const +{ + return 6378137; +} +double PlateCarreeProjection::Flattening() const +{ + return (1.0 / 298.257223563); +} +Size PlateCarreeProjection::GetTileMatrixMaxXY(const int &zoom) +{ + int y = (int) pow(2, zoom); + return Size((2*y) - 1, y - 1); +} + +Size PlateCarreeProjection::GetTileMatrixMinXY(const int &zoom) +{ + Q_UNUSED(zoom); + return Size(0, 0); +} +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.h index 61454f00d..010cf430a 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojection.h @@ -1,56 +1,56 @@ -/** -****************************************************************************** -* -* @file platecarreeprojection.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef PLATECARREEPROJECTION_H -#define PLATECARREEPROJECTION_H - -#include "../pureprojection.h" - - -namespace projections { -class PlateCarreeProjection:public internals::PureProjection -{ -public: - PlateCarreeProjection(); - virtual QString Type(){return "PlateCarreeProjection";} - virtual Size TileSize() const; - virtual double Axis() const; - virtual double Flattening()const; - virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom); - virtual internals::PointLatLng FromPixelToLatLng(const int &x,const int &y,const int &zoom); - virtual Size GetTileMatrixMinXY(const int &zoom); - virtual Size GetTileMatrixMaxXY(const int &zoom); -private: - const double MinLatitude; - const double MaxLatitude; - const double MinLongitude; - const double MaxLongitude; - - double Clip(double const& n, double const& minValue, double const& maxValue)const; - Size tileSize; -}; -} -#endif // PLATECARREEPROJECTION_H +/** +****************************************************************************** +* +* @file platecarreeprojection.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef PLATECARREEPROJECTION_H +#define PLATECARREEPROJECTION_H + +#include "../pureprojection.h" + + +namespace projections { +class PlateCarreeProjection:public internals::PureProjection +{ +public: + PlateCarreeProjection(); + virtual QString Type(){return "PlateCarreeProjection";} + virtual Size TileSize() const; + virtual double Axis() const; + virtual double Flattening()const; + virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom); + virtual internals::PointLatLng FromPixelToLatLng(const int &x,const int &y,const int &zoom); + virtual Size GetTileMatrixMinXY(const int &zoom); + virtual Size GetTileMatrixMaxXY(const int &zoom); +private: + const double MinLatitude; + const double MaxLatitude; + const double MinLongitude; + const double MaxLongitude; + + double Clip(double const& n, double const& minValue, double const& maxValue)const; + Size tileSize; +}; +} +#endif // PLATECARREEPROJECTION_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp index 89d598bd6..e746036c0 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp @@ -1,96 +1,96 @@ -/** -****************************************************************************** -* -* @file platecarreeprojectionpergo.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "platecarreeprojectionpergo.h" - - -namespace projections { -PlateCarreeProjectionPergo::PlateCarreeProjectionPergo():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-180), -MaxLongitude(180), tileSize(256, 256) -{ -} -Point PlateCarreeProjectionPergo::FromLatLngToPixel(double lat, double lng, const int &zoom) -{ - Point ret;// = Point.Empty; - - lat = Clip(lat, MinLatitude, MaxLatitude); - lng = Clip(lng, MinLongitude, MaxLongitude); - - Size s = GetTileMatrixSizePixel(zoom); - double mapSizeX = s.Width(); - //double mapSizeY = s.Height(); - - double scale = 360.0 / mapSizeX; - - ret.SetY((int) ((90.0 - lat) / scale)); - ret.SetX((int) ((lng + 180.0) / scale)); - - return ret; -} -internals::PointLatLng PlateCarreeProjectionPergo::FromPixelToLatLng(const int &x, const int &y, const int &zoom) -{ - internals::PointLatLng ret;// = internals::PointLatLng.Empty; - - Size s = GetTileMatrixSizePixel(zoom); - double mapSizeX = s.Width(); - //double mapSizeY = s.Height(); - - double scale = 360.0 / mapSizeX; - - ret.SetLat(90 - (y * scale)); - ret.SetLng((x * scale) - 180); - - return ret; -} - -double PlateCarreeProjectionPergo::Clip(const double &n, const double &minValue, const double &maxValue) const -{ - return qMin(qMax(n, minValue), maxValue); -} -Size PlateCarreeProjectionPergo::TileSize() const -{ - return tileSize; -} -double PlateCarreeProjectionPergo::Axis() const -{ - return 6378137; -} -double PlateCarreeProjectionPergo::Flattening() const -{ - return (1.0 / 298.257223563); -} -Size PlateCarreeProjectionPergo::GetTileMatrixMaxXY(const int &zoom) -{ - int y = (int) pow(2, zoom); - return Size((2*y) - 1, y - 1); -} - -Size PlateCarreeProjectionPergo::GetTileMatrixMinXY(const int &zoom) -{ - Q_UNUSED(zoom) - return Size(0, 0); -} -} +/** +****************************************************************************** +* +* @file platecarreeprojectionpergo.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "platecarreeprojectionpergo.h" + + +namespace projections { +PlateCarreeProjectionPergo::PlateCarreeProjectionPergo():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-180), +MaxLongitude(180), tileSize(256, 256) +{ +} +Point PlateCarreeProjectionPergo::FromLatLngToPixel(double lat, double lng, const int &zoom) +{ + Point ret;// = Point.Empty; + + lat = Clip(lat, MinLatitude, MaxLatitude); + lng = Clip(lng, MinLongitude, MaxLongitude); + + Size s = GetTileMatrixSizePixel(zoom); + double mapSizeX = s.Width(); + //double mapSizeY = s.Height(); + + double scale = 360.0 / mapSizeX; + + ret.SetY((int) ((90.0 - lat) / scale)); + ret.SetX((int) ((lng + 180.0) / scale)); + + return ret; +} +internals::PointLatLng PlateCarreeProjectionPergo::FromPixelToLatLng(const int &x, const int &y, const int &zoom) +{ + internals::PointLatLng ret;// = internals::PointLatLng.Empty; + + Size s = GetTileMatrixSizePixel(zoom); + double mapSizeX = s.Width(); + //double mapSizeY = s.Height(); + + double scale = 360.0 / mapSizeX; + + ret.SetLat(90 - (y * scale)); + ret.SetLng((x * scale) - 180); + + return ret; +} + +double PlateCarreeProjectionPergo::Clip(const double &n, const double &minValue, const double &maxValue) const +{ + return qMin(qMax(n, minValue), maxValue); +} +Size PlateCarreeProjectionPergo::TileSize() const +{ + return tileSize; +} +double PlateCarreeProjectionPergo::Axis() const +{ + return 6378137; +} +double PlateCarreeProjectionPergo::Flattening() const +{ + return (1.0 / 298.257223563); +} +Size PlateCarreeProjectionPergo::GetTileMatrixMaxXY(const int &zoom) +{ + int y = (int) pow(2, zoom); + return Size((2*y) - 1, y - 1); +} + +Size PlateCarreeProjectionPergo::GetTileMatrixMinXY(const int &zoom) +{ + Q_UNUSED(zoom) + return Size(0, 0); +} +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.h index cf52aa036..f5f80c316 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/platecarreeprojectionpergo.h @@ -1,56 +1,56 @@ -/** -****************************************************************************** -* -* @file platecarreeprojectionpergo.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef PLATECARREEPROJECTIONPERGO_H -#define PLATECARREEPROJECTIONPERGO_H - -#include "../pureprojection.h" - - -namespace projections { -class PlateCarreeProjectionPergo:public internals::PureProjection -{ -public: - PlateCarreeProjectionPergo(); - virtual QString Type(){return "PlateCarreeProjectionPergo";} - virtual Size TileSize() const; - virtual double Axis() const; - virtual double Flattening()const; - virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom); - virtual internals::PointLatLng FromPixelToLatLng(const int &x,const int &y,const int &zoom); - virtual Size GetTileMatrixMinXY(const int &zoom); - virtual Size GetTileMatrixMaxXY(const int &zoom); -private: - const double MinLatitude; - const double MaxLatitude; - const double MinLongitude; - const double MaxLongitude; - - double Clip(double const& n, double const& minValue, double const& maxValue)const; - Size tileSize; -}; -} -#endif // PLATECARREEPROJECTIONPERGO_H +/** +****************************************************************************** +* +* @file platecarreeprojectionpergo.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef PLATECARREEPROJECTIONPERGO_H +#define PLATECARREEPROJECTIONPERGO_H + +#include "../pureprojection.h" + + +namespace projections { +class PlateCarreeProjectionPergo:public internals::PureProjection +{ +public: + PlateCarreeProjectionPergo(); + virtual QString Type(){return "PlateCarreeProjectionPergo";} + virtual Size TileSize() const; + virtual double Axis() const; + virtual double Flattening()const; + virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom); + virtual internals::PointLatLng FromPixelToLatLng(const int &x,const int &y,const int &zoom); + virtual Size GetTileMatrixMinXY(const int &zoom); + virtual Size GetTileMatrixMaxXY(const int &zoom); +private: + const double MinLatitude; + const double MaxLatitude; + const double MinLongitude; + const double MaxLongitude; + + double Clip(double const& n, double const& minValue, double const& maxValue)const; + Size tileSize; +}; +} +#endif // PLATECARREEPROJECTIONPERGO_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp index b817ff25e..2eab113a1 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.cpp @@ -1,277 +1,277 @@ -/** -****************************************************************************** -* -* @file pureprojection.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "pureprojection.h" - - - - - - -namespace internals { - -const double PureProjection::PI = M_PI; -const double PureProjection::HALF_PI = (M_PI * 0.5); -const double PureProjection::TWO_PI= (M_PI * 2.0); -const double PureProjection::EPSLoN= 1.0e-10; -const double PureProjection::MAX_VAL= 4; -const double PureProjection::MAXLONG= 2147483647; -const double PureProjection::DBLLONG= 4.61168601e18; -const double PureProjection::R2D=180/M_PI; -const double PureProjection::D2R=M_PI/180; - -Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) - { - return FromLatLngToPixel(p.Lat(), p.Lng(), zoom); - } - - - PointLatLng PureProjection::FromPixelToLatLng(const Point &p,const int &zoom) - { - return FromPixelToLatLng(p.X(), p.Y(), zoom); - } - - Point PureProjection::FromPixelToTileXY(const Point &p) - { - return Point((int) (p.X() / TileSize().Width()), (int) (p.Y() / TileSize().Height())); - } - - Point PureProjection::FromTileXYToPixel(const Point &p) - { - return Point((p.X() * TileSize().Width()), (p.Y() * TileSize().Height())); - } - - Size PureProjection::GetTileMatrixSizeXY(const int &zoom) - { - Size sMin = GetTileMatrixMinXY(zoom); - Size sMax = GetTileMatrixMaxXY(zoom); - - return Size(sMax.Width() - sMin.Width() + 1, sMax.Height() - sMin.Height() + 1); - } - int PureProjection::GetTileMatrixItemCount(const int &zoom) - { - Size s = GetTileMatrixSizeXY(zoom); - return (s.Width() * s.Height()); - } - Size PureProjection::GetTileMatrixSizePixel(const int &zoom) - { - Size s = GetTileMatrixSizeXY(zoom); - return Size(s.Width() * TileSize().Width(), s.Height() * TileSize().Height()); - } - QList PureProjection::GetAreaTileList(const RectLatLng &rect,const int &zoom,const int &padding) - { - QList ret; - - Point topLeft = FromPixelToTileXY(FromLatLngToPixel(rect.LocationTopLeft(), zoom)); - Point rightBottom = FromPixelToTileXY(FromLatLngToPixel(rect.Bottom(), rect.Right(), zoom)); - - for(int x = (topLeft.X() - padding); x <= (rightBottom.X() + padding); x++) - { - for(int y = (topLeft.Y() - padding); y <= (rightBottom.Y() + padding); y++) - { - Point p = Point(x, y); - if(!ret.contains(p) && p.X() >= 0 && p.Y() >= 0) - { - ret.append(p); - } - } - } - //ret.TrimExcess(); - - return ret; - } - /* - * Returns the conversion from pixels to meters - */ - double PureProjection::GetGroundResolution(const int &zoom,const double &latitude) - { - return (cos(latitude * (PI / 180)) * 2 * PI * Axis()) / GetTileMatrixSizePixel(zoom).Width(); - } - - double PureProjection::Sign(const double &x) - { - if(x < 0.0) - return (-1); - else - return (1); - } - - double PureProjection::AdjustLongitude(double x) - { - qlonglong count = 0; - while(true) - { - if(qAbs(x) <= PI) - break; - else - if(((qlonglong) qAbs(x / PI)) < 2) - x = x - (Sign(x) * TWO_PI); - - else - if(((qlonglong) qAbs(x / TWO_PI)) < MAXLONG) - { - x = x - (((qlonglong) (x / TWO_PI)) * TWO_PI); - } - else - if(((qlonglong) qAbs(x / (MAXLONG * TWO_PI))) < MAXLONG) - { - x = x - (((qlonglong) (x / (MAXLONG * TWO_PI))) * (TWO_PI * MAXLONG)); - } - else - if(((qlonglong) qAbs(x / (DBLLONG * TWO_PI))) < MAXLONG) - { - x = x - (((qlonglong) (x / (DBLLONG * TWO_PI))) * (TWO_PI * DBLLONG)); - } - else - x = x - (Sign(x) * TWO_PI); - count++; - if(count > MAX_VAL) - break; - } - return (x); - } - - void PureProjection::SinCos(const double &val, double &si, double &co) - { - si = sin(val); - co = cos(val); - } - - double PureProjection::e0fn(const double &x) - { - return (1.0 - 0.25 * x * (1.0 + x / 16.0 * (3.0 + 1.25 * x))); - } - - double PureProjection::e1fn(const double &x) - { - return (0.375 * x * (1.0 + 0.25 * x * (1.0 + 0.46875 * x))); - } - - double PureProjection::e2fn(const double &x) - { - return (0.05859375 * x * x * (1.0 + 0.75 * x)); - } - - double PureProjection::e3fn(const double &x) - { - return (x * x * x * (35.0 / 3072.0)); - } - - double PureProjection::mlfn(const double &e0,const double &e1,const double &e2,const double &e3,const double &phi) - { - return (e0 * phi - e1 * sin(2.0 * phi) + e2 * sin(4.0 * phi) - e3 * sin(6.0 * phi)); - } - - qlonglong PureProjection::GetUTMzone(const double &lon) - { - return ((qlonglong) (((lon + 180.0) / 6.0) + 1.0)); - } - - - void PureProjection::FromGeodeticToCartesian(double Lat,double Lng,double Height, double &X, double &Y, double &Z) - { - Lat = (PI / 180) * Lat; - Lng = (PI / 180) * Lng; - - double B = Axis() * (1.0 - Flattening()); - double ee = 1.0 - (B / Axis()) * (B / Axis()); - double N = (Axis() / sqrt(1.0 - ee * sin(Lat) * sin(Lat))); - - X = (N + Height) * cos(Lat) * cos(Lng); - Y = (N + Height) * cos(Lat) * sin(Lng); - Z = (N * (B / Axis()) * (B / Axis()) + Height) * sin(Lat); - } - void PureProjection::FromCartesianTGeodetic(const double &X,const double &Y,const double &Z, double &Lat, double &Lng) - { - double E = Flattening() * (2.0 - Flattening()); - Lng = atan2(Y, X); - - double P = sqrt(X * X + Y * Y); - double Theta = atan2(Z, (P * (1.0 - Flattening()))); - double st = sin(Theta); - double ct = cos(Theta); - Lat = atan2(Z + E / (1.0 - Flattening()) * Axis() * st * st * st, P - E * Axis() * ct * ct * ct); - - Lat /= (PI / 180); - Lng /= (PI / 180); - } - double PureProjection::courseBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2) - { - - double lon1=p1.Lng()* (M_PI / 180); - double lat1=p1.Lat()* (M_PI / 180); - double lon2=p2.Lng()* (M_PI / 180); - double lat2=p2.Lat()* (M_PI / 180); - - return 2*M_PI-myfmod(atan2(sin(lon1-lon2)*cos(lat2), - cos(lat1)*sin(lat2)-sin(lat1)*cos(lat2)*cos(lon1-lon2)), 2*M_PI); - } - - double PureProjection::DistanceBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2) - { - double R = 6371; // km - double lat1=p1.Lat(); - double lat2=p2.Lat(); - double lon1=p1.Lng(); - double lon2=p2.Lng(); - double dLat = (lat2-lat1)* (PI / 180); - double dLon = (lon2-lon1)* (PI / 180); - double a = sin(dLat/2) * sin(dLat/2) + cos(lat1* (PI / 180)) * cos(lat2* (PI / 180)) * sin(dLon/2) * sin(dLon/2); - double c = 2 * atan2(sqrt(a), sqrt(1-a)); - double d = R * c; - return d; - } - - void PureProjection::offSetFromLatLngs(PointLatLng p1,PointLatLng p2,double &distance,double &bearing) - { - distance=DistanceBetweenLatLng(p1,p2)*1000; - bearing=courseBetweenLatLng(p1,p2); - } - - double PureProjection::myfmod(double x,double y) - { - return x - y*floor(x/y); - } - - PointLatLng PureProjection::translate(PointLatLng p1,double distance,double bearing) - { - PointLatLng ret; - double d=distance; - double tc=bearing; - double lat1=p1.Lat()*M_PI/180; - double lon1=p1.Lng()*M_PI/180; - double R=6378137; - double lat2 = asin(sin(lat1)*cos(d/R) + cos(lat1)*sin(d/R)*cos(tc) ); - double lon2 = lon1 + atan2(sin(tc)*sin(d/R)*cos(lat1), - cos(d/R)-sin(lat1)*sin(lat2)); - lat2=lat2*180/M_PI; - lon2=lon2*180/M_PI; - ret.SetLat(lat2); - ret.SetLng(lon2); - return ret; - } - -} +/** +****************************************************************************** +* +* @file pureprojection.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "pureprojection.h" + + + + + + +namespace internals { + +const double PureProjection::PI = M_PI; +const double PureProjection::HALF_PI = (M_PI * 0.5); +const double PureProjection::TWO_PI= (M_PI * 2.0); +const double PureProjection::EPSLoN= 1.0e-10; +const double PureProjection::MAX_VAL= 4; +const double PureProjection::MAXLONG= 2147483647; +const double PureProjection::DBLLONG= 4.61168601e18; +const double PureProjection::R2D=180/M_PI; +const double PureProjection::D2R=M_PI/180; + +Point PureProjection::FromLatLngToPixel(const PointLatLng &p,const int &zoom) + { + return FromLatLngToPixel(p.Lat(), p.Lng(), zoom); + } + + + PointLatLng PureProjection::FromPixelToLatLng(const Point &p,const int &zoom) + { + return FromPixelToLatLng(p.X(), p.Y(), zoom); + } + + Point PureProjection::FromPixelToTileXY(const Point &p) + { + return Point((int) (p.X() / TileSize().Width()), (int) (p.Y() / TileSize().Height())); + } + + Point PureProjection::FromTileXYToPixel(const Point &p) + { + return Point((p.X() * TileSize().Width()), (p.Y() * TileSize().Height())); + } + + Size PureProjection::GetTileMatrixSizeXY(const int &zoom) + { + Size sMin = GetTileMatrixMinXY(zoom); + Size sMax = GetTileMatrixMaxXY(zoom); + + return Size(sMax.Width() - sMin.Width() + 1, sMax.Height() - sMin.Height() + 1); + } + int PureProjection::GetTileMatrixItemCount(const int &zoom) + { + Size s = GetTileMatrixSizeXY(zoom); + return (s.Width() * s.Height()); + } + Size PureProjection::GetTileMatrixSizePixel(const int &zoom) + { + Size s = GetTileMatrixSizeXY(zoom); + return Size(s.Width() * TileSize().Width(), s.Height() * TileSize().Height()); + } + QList PureProjection::GetAreaTileList(const RectLatLng &rect,const int &zoom,const int &padding) + { + QList ret; + + Point topLeft = FromPixelToTileXY(FromLatLngToPixel(rect.LocationTopLeft(), zoom)); + Point rightBottom = FromPixelToTileXY(FromLatLngToPixel(rect.Bottom(), rect.Right(), zoom)); + + for(int x = (topLeft.X() - padding); x <= (rightBottom.X() + padding); x++) + { + for(int y = (topLeft.Y() - padding); y <= (rightBottom.Y() + padding); y++) + { + Point p = Point(x, y); + if(!ret.contains(p) && p.X() >= 0 && p.Y() >= 0) + { + ret.append(p); + } + } + } + //ret.TrimExcess(); + + return ret; + } + /* + * Returns the conversion from pixels to meters + */ + double PureProjection::GetGroundResolution(const int &zoom,const double &latitude) + { + return (cos(latitude * (PI / 180)) * 2 * PI * Axis()) / GetTileMatrixSizePixel(zoom).Width(); + } + + double PureProjection::Sign(const double &x) + { + if(x < 0.0) + return (-1); + else + return (1); + } + + double PureProjection::AdjustLongitude(double x) + { + qlonglong count = 0; + while(true) + { + if(qAbs(x) <= PI) + break; + else + if(((qlonglong) qAbs(x / PI)) < 2) + x = x - (Sign(x) * TWO_PI); + + else + if(((qlonglong) qAbs(x / TWO_PI)) < MAXLONG) + { + x = x - (((qlonglong) (x / TWO_PI)) * TWO_PI); + } + else + if(((qlonglong) qAbs(x / (MAXLONG * TWO_PI))) < MAXLONG) + { + x = x - (((qlonglong) (x / (MAXLONG * TWO_PI))) * (TWO_PI * MAXLONG)); + } + else + if(((qlonglong) qAbs(x / (DBLLONG * TWO_PI))) < MAXLONG) + { + x = x - (((qlonglong) (x / (DBLLONG * TWO_PI))) * (TWO_PI * DBLLONG)); + } + else + x = x - (Sign(x) * TWO_PI); + count++; + if(count > MAX_VAL) + break; + } + return (x); + } + + void PureProjection::SinCos(const double &val, double &si, double &co) + { + si = sin(val); + co = cos(val); + } + + double PureProjection::e0fn(const double &x) + { + return (1.0 - 0.25 * x * (1.0 + x / 16.0 * (3.0 + 1.25 * x))); + } + + double PureProjection::e1fn(const double &x) + { + return (0.375 * x * (1.0 + 0.25 * x * (1.0 + 0.46875 * x))); + } + + double PureProjection::e2fn(const double &x) + { + return (0.05859375 * x * x * (1.0 + 0.75 * x)); + } + + double PureProjection::e3fn(const double &x) + { + return (x * x * x * (35.0 / 3072.0)); + } + + double PureProjection::mlfn(const double &e0,const double &e1,const double &e2,const double &e3,const double &phi) + { + return (e0 * phi - e1 * sin(2.0 * phi) + e2 * sin(4.0 * phi) - e3 * sin(6.0 * phi)); + } + + qlonglong PureProjection::GetUTMzone(const double &lon) + { + return ((qlonglong) (((lon + 180.0) / 6.0) + 1.0)); + } + + + void PureProjection::FromGeodeticToCartesian(double Lat,double Lng,double Height, double &X, double &Y, double &Z) + { + Lat = (PI / 180) * Lat; + Lng = (PI / 180) * Lng; + + double B = Axis() * (1.0 - Flattening()); + double ee = 1.0 - (B / Axis()) * (B / Axis()); + double N = (Axis() / sqrt(1.0 - ee * sin(Lat) * sin(Lat))); + + X = (N + Height) * cos(Lat) * cos(Lng); + Y = (N + Height) * cos(Lat) * sin(Lng); + Z = (N * (B / Axis()) * (B / Axis()) + Height) * sin(Lat); + } + void PureProjection::FromCartesianTGeodetic(const double &X,const double &Y,const double &Z, double &Lat, double &Lng) + { + double E = Flattening() * (2.0 - Flattening()); + Lng = atan2(Y, X); + + double P = sqrt(X * X + Y * Y); + double Theta = atan2(Z, (P * (1.0 - Flattening()))); + double st = sin(Theta); + double ct = cos(Theta); + Lat = atan2(Z + E / (1.0 - Flattening()) * Axis() * st * st * st, P - E * Axis() * ct * ct * ct); + + Lat /= (PI / 180); + Lng /= (PI / 180); + } + double PureProjection::courseBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2) + { + + double lon1=p1.Lng()* (M_PI / 180); + double lat1=p1.Lat()* (M_PI / 180); + double lon2=p2.Lng()* (M_PI / 180); + double lat2=p2.Lat()* (M_PI / 180); + + return 2*M_PI-myfmod(atan2(sin(lon1-lon2)*cos(lat2), + cos(lat1)*sin(lat2)-sin(lat1)*cos(lat2)*cos(lon1-lon2)), 2*M_PI); + } + + double PureProjection::DistanceBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2) + { + double R = 6371; // km + double lat1=p1.Lat(); + double lat2=p2.Lat(); + double lon1=p1.Lng(); + double lon2=p2.Lng(); + double dLat = (lat2-lat1)* (PI / 180); + double dLon = (lon2-lon1)* (PI / 180); + double a = sin(dLat/2) * sin(dLat/2) + cos(lat1* (PI / 180)) * cos(lat2* (PI / 180)) * sin(dLon/2) * sin(dLon/2); + double c = 2 * atan2(sqrt(a), sqrt(1-a)); + double d = R * c; + return d; + } + + void PureProjection::offSetFromLatLngs(PointLatLng p1,PointLatLng p2,double &distance,double &bearing) + { + distance=DistanceBetweenLatLng(p1,p2)*1000; + bearing=courseBetweenLatLng(p1,p2); + } + + double PureProjection::myfmod(double x,double y) + { + return x - y*floor(x/y); + } + + PointLatLng PureProjection::translate(PointLatLng p1,double distance,double bearing) + { + PointLatLng ret; + double d=distance; + double tc=bearing; + double lat1=p1.Lat()*M_PI/180; + double lon1=p1.Lng()*M_PI/180; + double R=6378137; + double lat2 = asin(sin(lat1)*cos(d/R) + cos(lat1)*sin(d/R)*cos(tc) ); + double lon2 = lon1 + atan2(sin(tc)*sin(d/R)*cos(lat1), + cos(d/R)-sin(lat1)*sin(lat2)); + lat2=lat2*180/M_PI; + lon2=lon2*180/M_PI; + ret.SetLat(lat2); + ret.SetLng(lon2); + return ret; + } + +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h index 5402d13e6..6c41db846 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/pureprojection.h @@ -1,115 +1,115 @@ -/** -****************************************************************************** -* -* @file pureprojection.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef PUREPROJECTION_H -#define PUREPROJECTION_H - -#include "../core/size.h" -#include "../core/point.h" -#include "../internals/pointlatlng.h" -#include "pointlatlng.h" -#include "cmath" -#include "rectlatlng.h" -#include -using namespace core; - -namespace internals -{ - -class PureProjection -{ - - -public: - virtual Size TileSize()const=0; - - virtual double Axis()const=0; - - virtual double Flattening()const=0; - - virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom)=0; - - virtual PointLatLng FromPixelToLatLng(const int &x,const int &y,const int &zoom)=0; - - virtual QString Type(){return "PureProjection";} - core::Point FromLatLngToPixel(const PointLatLng &p,const int &zoom); - - PointLatLng FromPixelToLatLng(const Point &p,const int &zoom); - virtual core::Point FromPixelToTileXY(const core::Point &p); - virtual core::Point FromTileXYToPixel(const core::Point &p); - virtual Size GetTileMatrixMinXY(const int &zoom)=0; - virtual Size GetTileMatrixMaxXY(const int &zoom)=0; - virtual Size GetTileMatrixSizeXY(const int &zoom); - int GetTileMatrixItemCount(const int &zoom); - virtual Size GetTileMatrixSizePixel(const int &zoom); - QList GetAreaTileList(const RectLatLng &rect,const int &zoom,const int &padding); - virtual double GetGroundResolution(const int &zoom,const double &latitude); - - double DegreesToRadians(const double °)const - { - return (D2R * deg); - } - - double RadiansToDegrees(const double &rad)const - { - return (R2D * rad); - } - void FromGeodeticToCartesian(double Lat,double Lng,double Height, double &X, double &Y, double &Z); - void FromCartesianTGeodetic(const double &X,const double &Y,const double &Z, double &Lat, double &Lng); - static double DistanceBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2); - - PointLatLng translate(PointLatLng p1, double distance, double bearing); - double courseBetweenLatLng(const PointLatLng &p1, const PointLatLng &p2); - void offSetFromLatLngs(PointLatLng p1, PointLatLng p2, double &dX, double &dY); -protected: - - static const double PI; - static const double HALF_PI; - static const double TWO_PI; - static const double EPSLoN; - static const double MAX_VAL; - static const double MAXLONG; - static const double DBLLONG; - static const double R2D; - static const double D2R; - - static double Sign(const double &x); - - static double AdjustLongitude(double x); - static void SinCos(const double &val, double &sin, double &cos); - static double e0fn(const double &x); - static double e1fn(const double &x); - static double e2fn(const double &x); - static double e3fn(const double &x); - static double mlfn(const double &e0,const double &e1,const double &e2,const double &e3,const double &phi); - static qlonglong GetUTMzone(const double &lon); -private: - double myfmod(double x, double y); -}; -} - - -#endif // PUREPROJECTION_H +/** +****************************************************************************** +* +* @file pureprojection.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef PUREPROJECTION_H +#define PUREPROJECTION_H + +#include "../core/size.h" +#include "../core/point.h" +#include "../internals/pointlatlng.h" +#include "pointlatlng.h" +#include "cmath" +#include "rectlatlng.h" +#include +using namespace core; + +namespace internals +{ + +class PureProjection +{ + + +public: + virtual Size TileSize()const=0; + + virtual double Axis()const=0; + + virtual double Flattening()const=0; + + virtual core::Point FromLatLngToPixel(double lat, double lng, int const& zoom)=0; + + virtual PointLatLng FromPixelToLatLng(const int &x,const int &y,const int &zoom)=0; + + virtual QString Type(){return "PureProjection";} + core::Point FromLatLngToPixel(const PointLatLng &p,const int &zoom); + + PointLatLng FromPixelToLatLng(const Point &p,const int &zoom); + virtual core::Point FromPixelToTileXY(const core::Point &p); + virtual core::Point FromTileXYToPixel(const core::Point &p); + virtual Size GetTileMatrixMinXY(const int &zoom)=0; + virtual Size GetTileMatrixMaxXY(const int &zoom)=0; + virtual Size GetTileMatrixSizeXY(const int &zoom); + int GetTileMatrixItemCount(const int &zoom); + virtual Size GetTileMatrixSizePixel(const int &zoom); + QList GetAreaTileList(const RectLatLng &rect,const int &zoom,const int &padding); + virtual double GetGroundResolution(const int &zoom,const double &latitude); + + double DegreesToRadians(const double °)const + { + return (D2R * deg); + } + + double RadiansToDegrees(const double &rad)const + { + return (R2D * rad); + } + void FromGeodeticToCartesian(double Lat,double Lng,double Height, double &X, double &Y, double &Z); + void FromCartesianTGeodetic(const double &X,const double &Y,const double &Z, double &Lat, double &Lng); + static double DistanceBetweenLatLng(PointLatLng const& p1,PointLatLng const& p2); + + PointLatLng translate(PointLatLng p1, double distance, double bearing); + double courseBetweenLatLng(const PointLatLng &p1, const PointLatLng &p2); + void offSetFromLatLngs(PointLatLng p1, PointLatLng p2, double &dX, double &dY); +protected: + + static const double PI; + static const double HALF_PI; + static const double TWO_PI; + static const double EPSLoN; + static const double MAX_VAL; + static const double MAXLONG; + static const double DBLLONG; + static const double R2D; + static const double D2R; + + static double Sign(const double &x); + + static double AdjustLongitude(double x); + static void SinCos(const double &val, double &sin, double &cos); + static double e0fn(const double &x); + static double e1fn(const double &x); + static double e2fn(const double &x); + static double e3fn(const double &x); + static double mlfn(const double &e0,const double &e1,const double &e2,const double &e3,const double &phi); + static qlonglong GetUTMzone(const double &lon); +private: + double myfmod(double x, double y); +}; +} + + +#endif // PUREPROJECTION_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.cpp index ac31898af..461a914bb 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.cpp @@ -1,79 +1,79 @@ -/** -****************************************************************************** -* -* @file rectangle.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "rectangle.h" - -namespace internals { -Rectangle Rectangle::Empty=Rectangle(); -Rectangle Rectangle::FromLTRB(int left, int top, int right, int bottom) - { - return Rectangle(left, - top, - right - left, - bottom - top); - } -Rectangle Rectangle::Inflate(Rectangle rect, int x, int y) - { - Rectangle r = rect; - r.Inflate(x, y); - return r; - } -Rectangle Rectangle::Intersect(Rectangle a, Rectangle b) - { - int x1 = std::max(a.X(), b.X()); - int x2 = std::min(a.X() + a.Width(), b.X() + b.Width()); - int y1 = std::max(a.Y(), b.Y()); - int y2 = std::min(a.Y() + a.Height(), b.Y() + b.Height()); - - if(x2 >= x1 - && y2 >= y1) - { - - return Rectangle(x1, y1, x2 - x1, y2 - y1); - } - return Rectangle::Empty; - } -Rectangle Rectangle::Union(const Rectangle &a,const Rectangle &b) - { - int x1 = std::min(a.x, b.x); - int x2 = std::max(a.x + a.width, b.x + b.width); - int y1 = std::min(a.y, b.y); - int y2 = std::max(a.y + a.height, b.y + b.height); - - return Rectangle(x1, y1, x2 - x1, y2 - y1); - } -bool operator==(Rectangle const& lhs,Rectangle const& rhs) -{ - return (lhs.x == rhs.x && lhs.y == rhs.y && lhs.width == rhs.width && lhs.height == rhs.height); -} -uint qHash(Rectangle const& rect) - { - return (int) ((quint32) rect.x ^ - (((quint32) rect.y << 13) | ((quint32) rect.y >> 19)) ^ - (((quint32) rect.width << 26) | ((quint32) rect.width >> 6)) ^ - (((quint32) rect.height << 7) | ((quint32) rect.height >> 25))); - } -} +/** +****************************************************************************** +* +* @file rectangle.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "rectangle.h" + +namespace internals { +Rectangle Rectangle::Empty=Rectangle(); +Rectangle Rectangle::FromLTRB(int left, int top, int right, int bottom) + { + return Rectangle(left, + top, + right - left, + bottom - top); + } +Rectangle Rectangle::Inflate(Rectangle rect, int x, int y) + { + Rectangle r = rect; + r.Inflate(x, y); + return r; + } +Rectangle Rectangle::Intersect(Rectangle a, Rectangle b) + { + int x1 = std::max(a.X(), b.X()); + int x2 = std::min(a.X() + a.Width(), b.X() + b.Width()); + int y1 = std::max(a.Y(), b.Y()); + int y2 = std::min(a.Y() + a.Height(), b.Y() + b.Height()); + + if(x2 >= x1 + && y2 >= y1) + { + + return Rectangle(x1, y1, x2 - x1, y2 - y1); + } + return Rectangle::Empty; + } +Rectangle Rectangle::Union(const Rectangle &a,const Rectangle &b) + { + int x1 = std::min(a.x, b.x); + int x2 = std::max(a.x + a.width, b.x + b.width); + int y1 = std::min(a.y, b.y); + int y2 = std::max(a.y + a.height, b.y + b.height); + + return Rectangle(x1, y1, x2 - x1, y2 - y1); + } +bool operator==(Rectangle const& lhs,Rectangle const& rhs) +{ + return (lhs.x == rhs.x && lhs.y == rhs.y && lhs.width == rhs.width && lhs.height == rhs.height); +} +uint qHash(Rectangle const& rect) + { + return (int) ((quint32) rect.x ^ + (((quint32) rect.y << 13) | ((quint32) rect.y >> 19)) ^ + (((quint32) rect.width << 26) | ((quint32) rect.width >> 6)) ^ + (((quint32) rect.height << 7) | ((quint32) rect.height >> 25))); + } +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.h index 0cc20d1ee..bc70ea28c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectangle.h @@ -1,158 +1,158 @@ -/** -****************************************************************************** -* -* @file rectangle.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef RECTANGLE_H -#define RECTANGLE_H -//#include -#include "../core/size.h" -#include "math.h" -using namespace core; -namespace internals -{ -struct Rectangle -{ - - friend uint qHash(Rectangle const& rect); - friend bool operator==(Rectangle const& lhs,Rectangle const& rhs); -public: - static Rectangle Empty; - static Rectangle FromLTRB(int left, int top, int right, int bottom); - Rectangle(){x=0; y=0; width=0; height=0; }; - Rectangle(int x, int y, int width, int height) - { - this->x = x; - this->y = y; - this->width = width; - this->height = height; - } - Rectangle(core::Point location, core::Size size) - { - this->x = location.X(); - this->y = location.Y(); - this->width = size.Width(); - this->height = size.Height(); - } - core::Point GetLocation() { - return core::Point(x, y); - } - void SetLocation(const core::Point &value) - { - x = value.X(); - y = value.Y(); - } - int X(){return x;} - int Y(){return y;} - void SetX(const int &value){x=value;} - void SetY(const int &value){y=value;} - int Width(){return width;} - void SetWidth(const int &value){width=value;} - int Height(){return height;} - void SetHeight(const int &value){height=value;} - int Left(){return x;} - int Top(){return y;} - int Right(){return x+width;} - int Bottom(){return y+height;} - bool IsEmpty(){return (height==0 && width==0 && x==0 && y==0);} - bool operator==(const Rectangle &cSource) - { - return (cSource.x == x && cSource.y == y && cSource.width == width && cSource.height == height); - } - - - bool operator!=(const Rectangle &cSource){return !(*this==cSource);} - bool Contains(const int &x,const int &y) - { - return this->x<=x && xx+this->width && this->y<=y && yy+this->height; - } - bool Contains(const core::Point &pt) - { - return Contains(pt.X(),pt.Y()); - } - bool Contains(const Rectangle &rect) - { - return (this->x <= rect.x) && - ((rect.x + rect.width) <= (this->x + this->width)) && - (this->y <= rect.y) && - ((rect.y + rect.height) <= (this->y + this->height)); - } - - - void Inflate(const int &width,const int &height) - { - this->x -= width; - this->y -= height; - this->width += 2*width; - this->height += 2*height; - } - void Inflate(Size &size) - { - - Inflate(size.Width(), size.Height()); - } - static Rectangle Inflate(Rectangle rect, int x, int y); - - void Intersect(const Rectangle &rect) - { - Rectangle result = Rectangle::Intersect(rect, *this); - - this->x = result.X(); - this->y = result.Y(); - this->width = result.Width(); - this->height = result.Height(); - } - static Rectangle Intersect(Rectangle a, Rectangle b); - bool IntersectsWith(const Rectangle &rect) - { - return (rect.x < this->x + this->width) && - (this->x < (rect.x + rect.width)) && - (rect.y < this->y + this->height) && - (this->y < rect.y + rect.height); - } - static Rectangle Union(const Rectangle &a,const Rectangle &b); - void Offset(const core::Point &pos) - { - Offset(pos.X(), pos.Y()); - } - - void Offset(const int &x,const int &y) - { - this->x += x; - this->y += y; - } - QString ToString() - { - return "{X=" + QString::number(x) + ",Y=" + QString::number(y) + - ",Width=" + QString::number(width) + - ",Height=" +QString::number(height) +"}"; - } -private: - int x; - int y; - int width; - int height; -}; -} -#endif // RECTANGLE_H +/** +****************************************************************************** +* +* @file rectangle.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef RECTANGLE_H +#define RECTANGLE_H +//#include +#include "../core/size.h" +#include "math.h" +using namespace core; +namespace internals +{ +struct Rectangle +{ + + friend uint qHash(Rectangle const& rect); + friend bool operator==(Rectangle const& lhs,Rectangle const& rhs); +public: + static Rectangle Empty; + static Rectangle FromLTRB(int left, int top, int right, int bottom); + Rectangle(){x=0; y=0; width=0; height=0; }; + Rectangle(int x, int y, int width, int height) + { + this->x = x; + this->y = y; + this->width = width; + this->height = height; + } + Rectangle(core::Point location, core::Size size) + { + this->x = location.X(); + this->y = location.Y(); + this->width = size.Width(); + this->height = size.Height(); + } + core::Point GetLocation() { + return core::Point(x, y); + } + void SetLocation(const core::Point &value) + { + x = value.X(); + y = value.Y(); + } + int X(){return x;} + int Y(){return y;} + void SetX(const int &value){x=value;} + void SetY(const int &value){y=value;} + int Width(){return width;} + void SetWidth(const int &value){width=value;} + int Height(){return height;} + void SetHeight(const int &value){height=value;} + int Left(){return x;} + int Top(){return y;} + int Right(){return x+width;} + int Bottom(){return y+height;} + bool IsEmpty(){return (height==0 && width==0 && x==0 && y==0);} + bool operator==(const Rectangle &cSource) + { + return (cSource.x == x && cSource.y == y && cSource.width == width && cSource.height == height); + } + + + bool operator!=(const Rectangle &cSource){return !(*this==cSource);} + bool Contains(const int &x,const int &y) + { + return this->x<=x && xx+this->width && this->y<=y && yy+this->height; + } + bool Contains(const core::Point &pt) + { + return Contains(pt.X(),pt.Y()); + } + bool Contains(const Rectangle &rect) + { + return (this->x <= rect.x) && + ((rect.x + rect.width) <= (this->x + this->width)) && + (this->y <= rect.y) && + ((rect.y + rect.height) <= (this->y + this->height)); + } + + + void Inflate(const int &width,const int &height) + { + this->x -= width; + this->y -= height; + this->width += 2*width; + this->height += 2*height; + } + void Inflate(Size &size) + { + + Inflate(size.Width(), size.Height()); + } + static Rectangle Inflate(Rectangle rect, int x, int y); + + void Intersect(const Rectangle &rect) + { + Rectangle result = Rectangle::Intersect(rect, *this); + + this->x = result.X(); + this->y = result.Y(); + this->width = result.Width(); + this->height = result.Height(); + } + static Rectangle Intersect(Rectangle a, Rectangle b); + bool IntersectsWith(const Rectangle &rect) + { + return (rect.x < this->x + this->width) && + (this->x < (rect.x + rect.width)) && + (rect.y < this->y + this->height) && + (this->y < rect.y + rect.height); + } + static Rectangle Union(const Rectangle &a,const Rectangle &b); + void Offset(const core::Point &pos) + { + Offset(pos.X(), pos.Y()); + } + + void Offset(const int &x,const int &y) + { + this->x += x; + this->y += y; + } + QString ToString() + { + return "{X=" + QString::number(x) + ",Y=" + QString::number(y) + + ",Width=" + QString::number(width) + + ",Height=" +QString::number(height) +"}"; + } +private: + int x; + int y; + int width; + int height; +}; +} +#endif // RECTANGLE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.cpp index 4cc98f5e3..1d8529623 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.cpp @@ -1,48 +1,48 @@ -/** -****************************************************************************** -* -* @file rectlatlng.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "rectlatlng.h" - - - -namespace internals { -RectLatLng RectLatLng::Empty=RectLatLng(); -uint qHash(RectLatLng const& rect) -{ - return (int) (((((uint) rect.Lng()) ^ ((((uint) rect.Lat()) << 13) | (((uint) rect.Lat()) >> 0x13))) ^ ((((uint) rect.WidthLng()) << 0x1a) | (((uint) rect.WidthLng()) >> 6))) ^ ((((uint) rect.HeightLat()) << 7) | (((uint) rect.HeightLat()) >> 0x19))); -} - -bool operator==(RectLatLng const& left,RectLatLng const& right) -{ - return ((((left.Lng() == right.Lng()) && (left.Lat() == right.Lat())) && (left.WidthLng() == right.WidthLng())) && (left.HeightLat() == right.HeightLat())); -} - -bool operator!=(RectLatLng const& left,RectLatLng const& right) -{ - return !(left == right); -} - -} +/** +****************************************************************************** +* +* @file rectlatlng.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "rectlatlng.h" + + + +namespace internals { +RectLatLng RectLatLng::Empty=RectLatLng(); +uint qHash(RectLatLng const& rect) +{ + return (int) (((((uint) rect.Lng()) ^ ((((uint) rect.Lat()) << 13) | (((uint) rect.Lat()) >> 0x13))) ^ ((((uint) rect.WidthLng()) << 0x1a) | (((uint) rect.WidthLng()) >> 6))) ^ ((((uint) rect.HeightLat()) << 7) | (((uint) rect.HeightLat()) >> 0x19))); +} + +bool operator==(RectLatLng const& left,RectLatLng const& right) +{ + return ((((left.Lng() == right.Lng()) && (left.Lat() == right.Lat())) && (left.WidthLng() == right.WidthLng())) && (left.HeightLat() == right.HeightLat())); +} + +bool operator!=(RectLatLng const& left,RectLatLng const& right) +{ + return !(left == right); +} + +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.h index 8a54cc84b..1e3f56fa2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/rectlatlng.h @@ -1,264 +1,264 @@ -/** -****************************************************************************** -* -* @file rectlatlng.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef RECTLATLNG_H -#define RECTLATLNG_H - -//#include "pointlatlng.h" -#include "../internals/pointlatlng.h" -#include "math.h" -#include -#include "sizelatlng.h" - -namespace internals { -struct RectLatLng -{ -public: - static RectLatLng Empty; - friend uint qHash(RectLatLng const& rect); - friend bool operator==(RectLatLng const& left,RectLatLng const& right); - friend bool operator!=(RectLatLng const& left,RectLatLng const& right); - RectLatLng(double const& lat, double const& lng, double const& widthLng, double const& heightLat) - { - this->lng = lng; - this->lat = lat; - this->widthLng = widthLng; - this->heightLat = heightLat; - isempty=false; - } - RectLatLng(PointLatLng const& location, SizeLatLng const& size) - { - this->lng = location.Lng(); - this->lat = location.Lat(); - this->widthLng = size.WidthLng(); - this->heightLat = size.HeightLat(); - isempty=false; - } - RectLatLng() - { - this->lng = 0; - this->lat = 0; - this->widthLng = 0; - this->heightLat = 0; - isempty=true; - } - - static RectLatLng FromLTRB(double const& lng, double const& lat, double const& rightLng, double const& bottomLat) - { - return RectLatLng(lat, lng, rightLng - lng, lat - bottomLat); - } - PointLatLng LocationTopLeft()const - { - return PointLatLng(this->lat, this->lng); - } - void SetLocationTopLeft(PointLatLng const& value) - { - this->lng = value.Lng(); - this->lat = value.Lat(); - isempty=false; - } - PointLatLng LocationRightBottom() - { - - PointLatLng ret = PointLatLng(this->lat, this->lng); - ret.Offset(HeightLat(), WidthLng()); - return ret; - } - SizeLatLng Size() - { - return SizeLatLng(this->HeightLat(), this->WidthLng()); - } - void SetSize(SizeLatLng const& value) - { - this->widthLng = value.WidthLng(); - this->heightLat = value.HeightLat(); - isempty=false; - } - double Lng()const - { - return this->lng; - } - void SetLng(double const& value) - { - this->lng = value; - isempty=false; - } - - - double Lat()const - { - return this->lat; - } - void SetLat(double const& value) - { - this->lat = value; - isempty=false; - } - - double WidthLng()const - { - return this->widthLng; - } - void SetWidthLng(double const& value) - { - this->widthLng = value; - isempty=false; - } - double HeightLat()const - { - return this->heightLat; - } - void SetHeightLat(double const& value) - { - this->heightLat = value; - isempty=false; - } - double Left()const - { - return this->Lng(); - } - - double Top()const - { - return this->Lat(); - } - - double Right()const - { - return (this->Lng() + this->WidthLng()); - } - - double Bottom()const - { - return (this->Lat() - this->HeightLat()); - } - bool IsEmpty()const - { - return isempty; - } - bool Contains(double const& lat, double const& lng) - { - return ((((this->Lng() <= lng) && (lng < (this->Lng() + this->WidthLng()))) && (this->Lat() >= lat)) && (lat > (this->Lat() - this->HeightLat()))); - } - - bool Contains(PointLatLng const& pt) - { - return this->Contains(pt.Lat(), pt.Lng()); - } - - bool Contains(RectLatLng const& rect) - { - return ((((this->Lng() <= rect.Lng()) && ((rect.Lng() + rect.WidthLng()) <= (this->Lng() + this->WidthLng()))) && (this->Lat() >= rect.Lat())) && ((rect.Lat() - rect.HeightLat()) >= (this->Lat() - this->HeightLat()))); - } - void Inflate(double const& lat, double const& lng) - { - this->lng -= lng; - this->lat += lat; - this->widthLng += (double)2 * lng; - this->heightLat +=(double)2 * lat; - } - - void Inflate(SizeLatLng const& size) - { - this->Inflate(size.HeightLat(), size.WidthLng()); - } - - static RectLatLng Inflate(RectLatLng const& rect, double const& lat, double const& lng) - { - RectLatLng ef = rect; - ef.Inflate(lat, lng); - return ef; - } - - void Intersect(RectLatLng const& rect) - { - RectLatLng ef = Intersect(rect, *this); - this->lng = ef.Lng(); - this->lat = ef.Lat(); - this->widthLng = ef.WidthLng(); - this->heightLat = ef.HeightLat(); - } - static RectLatLng Intersect(RectLatLng const& a, RectLatLng const& b) - { - double lng = std::max(a.Lng(), b.Lng()); - double num2 = std::min((double) (a.Lng() + a.WidthLng()), (double) (b.Lng() + b.WidthLng())); - - double lat = std::max(a.Lat(), b.Lat()); - double num4 = std::min((double) (a.Lat() + a.HeightLat()), (double) (b.Lat() + b.HeightLat())); - - if((num2 >= lng) && (num4 >= lat)) - { - return RectLatLng(lng, lat, num2 - lng, num4 - lat); - } - return Empty; - } - bool IntersectsWith(RectLatLng const& rect) - { - return ((((rect.Lng() < (this->Lng() + this->WidthLng())) && (this->Lng() < (rect.Lng() + rect.WidthLng()))) && (rect.Lat() < (this->Lat() + this->HeightLat()))) && (this->Lat() < (rect.Lat() + rect.HeightLat()))); - } - - static RectLatLng Union(RectLatLng const& a, RectLatLng const& b) - { - double lng = std::min(a.Lng(), b.Lng()); - double num2 = std::max((double) (a.Lng() + a.WidthLng()), (double) (b.Lng() + b.WidthLng())); - double lat = std::min(a.Lat(), b.Lat()); - double num4 = std::max((double) (a.Lat() + a.HeightLat()), (double) (b.Lat() + b.HeightLat())); - return RectLatLng(lng, lat, num2 - lng, num4 - lat); - } - void Offset(PointLatLng const& pos) - { - this->Offset(pos.Lat(), pos.Lng()); - } - - void Offset(double const& lat, double const& lng) - { - this->lng += lng; - this->lat -= lat; - } - - QString ToString() const - { - return ("{Lat=" + QString::number(this->Lat()) + ",Lng=" + QString::number(this->Lng()) + ",WidthLng=" + QString::number(this->WidthLng()) + ",HeightLat=" + QString::number(this->HeightLat()) + "}"); - } - -private: - double lng; - double lat; - double widthLng; - double heightLat; - bool isempty; -}; - -} -#endif // RECTLATLNG_H - - - -// static RectLatLng() -// { -// Empty = new RectLatLng(); -// } -// } +/** +****************************************************************************** +* +* @file rectlatlng.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef RECTLATLNG_H +#define RECTLATLNG_H + +//#include "pointlatlng.h" +#include "../internals/pointlatlng.h" +#include "math.h" +#include +#include "sizelatlng.h" + +namespace internals { +struct RectLatLng +{ +public: + static RectLatLng Empty; + friend uint qHash(RectLatLng const& rect); + friend bool operator==(RectLatLng const& left,RectLatLng const& right); + friend bool operator!=(RectLatLng const& left,RectLatLng const& right); + RectLatLng(double const& lat, double const& lng, double const& widthLng, double const& heightLat) + { + this->lng = lng; + this->lat = lat; + this->widthLng = widthLng; + this->heightLat = heightLat; + isempty=false; + } + RectLatLng(PointLatLng const& location, SizeLatLng const& size) + { + this->lng = location.Lng(); + this->lat = location.Lat(); + this->widthLng = size.WidthLng(); + this->heightLat = size.HeightLat(); + isempty=false; + } + RectLatLng() + { + this->lng = 0; + this->lat = 0; + this->widthLng = 0; + this->heightLat = 0; + isempty=true; + } + + static RectLatLng FromLTRB(double const& lng, double const& lat, double const& rightLng, double const& bottomLat) + { + return RectLatLng(lat, lng, rightLng - lng, lat - bottomLat); + } + PointLatLng LocationTopLeft()const + { + return PointLatLng(this->lat, this->lng); + } + void SetLocationTopLeft(PointLatLng const& value) + { + this->lng = value.Lng(); + this->lat = value.Lat(); + isempty=false; + } + PointLatLng LocationRightBottom() + { + + PointLatLng ret = PointLatLng(this->lat, this->lng); + ret.Offset(HeightLat(), WidthLng()); + return ret; + } + SizeLatLng Size() + { + return SizeLatLng(this->HeightLat(), this->WidthLng()); + } + void SetSize(SizeLatLng const& value) + { + this->widthLng = value.WidthLng(); + this->heightLat = value.HeightLat(); + isempty=false; + } + double Lng()const + { + return this->lng; + } + void SetLng(double const& value) + { + this->lng = value; + isempty=false; + } + + + double Lat()const + { + return this->lat; + } + void SetLat(double const& value) + { + this->lat = value; + isempty=false; + } + + double WidthLng()const + { + return this->widthLng; + } + void SetWidthLng(double const& value) + { + this->widthLng = value; + isempty=false; + } + double HeightLat()const + { + return this->heightLat; + } + void SetHeightLat(double const& value) + { + this->heightLat = value; + isempty=false; + } + double Left()const + { + return this->Lng(); + } + + double Top()const + { + return this->Lat(); + } + + double Right()const + { + return (this->Lng() + this->WidthLng()); + } + + double Bottom()const + { + return (this->Lat() - this->HeightLat()); + } + bool IsEmpty()const + { + return isempty; + } + bool Contains(double const& lat, double const& lng) + { + return ((((this->Lng() <= lng) && (lng < (this->Lng() + this->WidthLng()))) && (this->Lat() >= lat)) && (lat > (this->Lat() - this->HeightLat()))); + } + + bool Contains(PointLatLng const& pt) + { + return this->Contains(pt.Lat(), pt.Lng()); + } + + bool Contains(RectLatLng const& rect) + { + return ((((this->Lng() <= rect.Lng()) && ((rect.Lng() + rect.WidthLng()) <= (this->Lng() + this->WidthLng()))) && (this->Lat() >= rect.Lat())) && ((rect.Lat() - rect.HeightLat()) >= (this->Lat() - this->HeightLat()))); + } + void Inflate(double const& lat, double const& lng) + { + this->lng -= lng; + this->lat += lat; + this->widthLng += (double)2 * lng; + this->heightLat +=(double)2 * lat; + } + + void Inflate(SizeLatLng const& size) + { + this->Inflate(size.HeightLat(), size.WidthLng()); + } + + static RectLatLng Inflate(RectLatLng const& rect, double const& lat, double const& lng) + { + RectLatLng ef = rect; + ef.Inflate(lat, lng); + return ef; + } + + void Intersect(RectLatLng const& rect) + { + RectLatLng ef = Intersect(rect, *this); + this->lng = ef.Lng(); + this->lat = ef.Lat(); + this->widthLng = ef.WidthLng(); + this->heightLat = ef.HeightLat(); + } + static RectLatLng Intersect(RectLatLng const& a, RectLatLng const& b) + { + double lng = std::max(a.Lng(), b.Lng()); + double num2 = std::min((double) (a.Lng() + a.WidthLng()), (double) (b.Lng() + b.WidthLng())); + + double lat = std::max(a.Lat(), b.Lat()); + double num4 = std::min((double) (a.Lat() + a.HeightLat()), (double) (b.Lat() + b.HeightLat())); + + if((num2 >= lng) && (num4 >= lat)) + { + return RectLatLng(lng, lat, num2 - lng, num4 - lat); + } + return Empty; + } + bool IntersectsWith(RectLatLng const& rect) + { + return ((((rect.Lng() < (this->Lng() + this->WidthLng())) && (this->Lng() < (rect.Lng() + rect.WidthLng()))) && (rect.Lat() < (this->Lat() + this->HeightLat()))) && (this->Lat() < (rect.Lat() + rect.HeightLat()))); + } + + static RectLatLng Union(RectLatLng const& a, RectLatLng const& b) + { + double lng = std::min(a.Lng(), b.Lng()); + double num2 = std::max((double) (a.Lng() + a.WidthLng()), (double) (b.Lng() + b.WidthLng())); + double lat = std::min(a.Lat(), b.Lat()); + double num4 = std::max((double) (a.Lat() + a.HeightLat()), (double) (b.Lat() + b.HeightLat())); + return RectLatLng(lng, lat, num2 - lng, num4 - lat); + } + void Offset(PointLatLng const& pos) + { + this->Offset(pos.Lat(), pos.Lng()); + } + + void Offset(double const& lat, double const& lng) + { + this->lng += lng; + this->lat -= lat; + } + + QString ToString() const + { + return ("{Lat=" + QString::number(this->Lat()) + ",Lng=" + QString::number(this->Lng()) + ",WidthLng=" + QString::number(this->WidthLng()) + ",HeightLat=" + QString::number(this->HeightLat()) + "}"); + } + +private: + double lng; + double lat; + double widthLng; + double heightLat; + bool isempty; +}; + +} +#endif // RECTLATLNG_H + + + +// static RectLatLng() +// { +// Empty = new RectLatLng(); +// } +// } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.cpp index e22527429..f66b7a104 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.cpp @@ -1,60 +1,60 @@ -/** -****************************************************************************** -* -* @file sizelatlng.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "sizelatlng.h" -#include "pointlatlng.h" - -namespace internals { -SizeLatLng::SizeLatLng():heightLat(0),widthLng(0) -{ - -} -SizeLatLng::SizeLatLng(PointLatLng const& pt) -{ - this->heightLat = pt.Lat(); - this->widthLng = pt.Lng(); -} -SizeLatLng operator+(SizeLatLng const& sz1, SizeLatLng const& sz2) -{ - return SizeLatLng::Add(sz1, sz2); -} - -SizeLatLng operator-(SizeLatLng const& sz1, SizeLatLng const& sz2) -{ - return SizeLatLng::Subtract(sz1, sz2); -} - -bool operator==(SizeLatLng const& sz1, SizeLatLng const& sz2) -{ - return ((sz1.WidthLng() == sz2.WidthLng()) && (sz1.HeightLat() == sz2.HeightLat())); -} - -bool operator!=(SizeLatLng const& sz1, SizeLatLng const& sz2) -{ - return !(sz1 == sz2); -} -SizeLatLng SizeLatLng::Empty=SizeLatLng(); -} +/** +****************************************************************************** +* +* @file sizelatlng.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "sizelatlng.h" +#include "pointlatlng.h" + +namespace internals { +SizeLatLng::SizeLatLng():heightLat(0),widthLng(0) +{ + +} +SizeLatLng::SizeLatLng(PointLatLng const& pt) +{ + this->heightLat = pt.Lat(); + this->widthLng = pt.Lng(); +} +SizeLatLng operator+(SizeLatLng const& sz1, SizeLatLng const& sz2) +{ + return SizeLatLng::Add(sz1, sz2); +} + +SizeLatLng operator-(SizeLatLng const& sz1, SizeLatLng const& sz2) +{ + return SizeLatLng::Subtract(sz1, sz2); +} + +bool operator==(SizeLatLng const& sz1, SizeLatLng const& sz2) +{ + return ((sz1.WidthLng() == sz2.WidthLng()) && (sz1.HeightLat() == sz2.HeightLat())); +} + +bool operator!=(SizeLatLng const& sz1, SizeLatLng const& sz2) +{ + return !(sz1 == sz2); +} +SizeLatLng SizeLatLng::Empty=SizeLatLng(); +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.h index c22249314..7a4463567 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/sizelatlng.h @@ -1,136 +1,136 @@ -/** -****************************************************************************** -* -* @file sizelatlng.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef SIZELATLNG_H -#define SIZELATLNG_H - - -#include - - -namespace internals { -struct PointLatLng; -struct SizeLatLng -{ -public: - SizeLatLng(); - static SizeLatLng Empty; - - SizeLatLng(SizeLatLng const& size) - { - this->widthLng = size.widthLng; - this->heightLat = size.heightLat; - } - - SizeLatLng(PointLatLng const& pt); - - - SizeLatLng(double const& heightLat, double const& widthLng) - { - this->heightLat = heightLat; - this->widthLng = widthLng; - } - - friend SizeLatLng operator+(SizeLatLng const& sz1, SizeLatLng const& sz2); - friend SizeLatLng operator-(SizeLatLng const& sz1, SizeLatLng const& sz2); - friend bool operator==(SizeLatLng const& sz1, SizeLatLng const& sz2); - friend bool operator!=(SizeLatLng const& sz1, SizeLatLng const& sz2); - - -// static explicit operator PointLatLng(SizeLatLng size) -// { -// return new PointLatLng(size.HeightLat(), size.WidthLng()); -// } - - - bool IsEmpty()const - { - return ((this->widthLng == 0) && (this->heightLat == 0)); - } - - double WidthLng()const - { - return this->widthLng; - } - void SetWidthLng(double const& value) - { - this->widthLng = value; - } - - - double HeightLat()const - { - return this->heightLat; - } - void SetHeightLat(double const& value) - { - this->heightLat = value; - } - - static SizeLatLng Add(SizeLatLng const& sz1, SizeLatLng const& sz2) - { - return SizeLatLng(sz1.HeightLat() + sz2.HeightLat(), sz1.WidthLng() + sz2.WidthLng()); - } - - static SizeLatLng Subtract(SizeLatLng const& sz1, SizeLatLng const& sz2) - { - return SizeLatLng(sz1.HeightLat() - sz2.HeightLat(), sz1.WidthLng() - sz2.WidthLng()); - } - -// override bool Equals(object obj) -// { -// if(!(obj is SizeLatLng)) -// { -// return false; -// } -// SizeLatLng ef = (SizeLatLng) obj; -// return (((ef.WidthLng == this->WidthLng) && (ef.HeightLat == this->HeightLat)) && ef.GetType().Equals(base.GetType())); -// } - -// override int GetHashCode() -// { -// return base.GetHashCode(); -// } - -// PointLatLng ToPointLatLng() -// { -// return (PointLatLng) this; -// } - - QString ToString() - { - return ("{WidthLng=" + QString::number(this->widthLng) + ", HeightLng=" + QString::number(this->heightLat) + "}"); - } - - -private: - double heightLat; - double widthLng; -}; - -} -#endif // SIZELATLNG_H - +/** +****************************************************************************** +* +* @file sizelatlng.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef SIZELATLNG_H +#define SIZELATLNG_H + + +#include + + +namespace internals { +struct PointLatLng; +struct SizeLatLng +{ +public: + SizeLatLng(); + static SizeLatLng Empty; + + SizeLatLng(SizeLatLng const& size) + { + this->widthLng = size.widthLng; + this->heightLat = size.heightLat; + } + + SizeLatLng(PointLatLng const& pt); + + + SizeLatLng(double const& heightLat, double const& widthLng) + { + this->heightLat = heightLat; + this->widthLng = widthLng; + } + + friend SizeLatLng operator+(SizeLatLng const& sz1, SizeLatLng const& sz2); + friend SizeLatLng operator-(SizeLatLng const& sz1, SizeLatLng const& sz2); + friend bool operator==(SizeLatLng const& sz1, SizeLatLng const& sz2); + friend bool operator!=(SizeLatLng const& sz1, SizeLatLng const& sz2); + + +// static explicit operator PointLatLng(SizeLatLng size) +// { +// return new PointLatLng(size.HeightLat(), size.WidthLng()); +// } + + + bool IsEmpty()const + { + return ((this->widthLng == 0) && (this->heightLat == 0)); + } + + double WidthLng()const + { + return this->widthLng; + } + void SetWidthLng(double const& value) + { + this->widthLng = value; + } + + + double HeightLat()const + { + return this->heightLat; + } + void SetHeightLat(double const& value) + { + this->heightLat = value; + } + + static SizeLatLng Add(SizeLatLng const& sz1, SizeLatLng const& sz2) + { + return SizeLatLng(sz1.HeightLat() + sz2.HeightLat(), sz1.WidthLng() + sz2.WidthLng()); + } + + static SizeLatLng Subtract(SizeLatLng const& sz1, SizeLatLng const& sz2) + { + return SizeLatLng(sz1.HeightLat() - sz2.HeightLat(), sz1.WidthLng() - sz2.WidthLng()); + } + +// override bool Equals(object obj) +// { +// if(!(obj is SizeLatLng)) +// { +// return false; +// } +// SizeLatLng ef = (SizeLatLng) obj; +// return (((ef.WidthLng == this->WidthLng) && (ef.HeightLat == this->HeightLat)) && ef.GetType().Equals(base.GetType())); +// } + +// override int GetHashCode() +// { +// return base.GetHashCode(); +// } + +// PointLatLng ToPointLatLng() +// { +// return (PointLatLng) this; +// } + + QString ToString() + { + return ("{WidthLng=" + QString::number(this->widthLng) + ", HeightLng=" + QString::number(this->heightLat) + "}"); + } + + +private: + double heightLat; + double widthLng; +}; + +} +#endif // SIZELATLNG_H + diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.cpp index b70887d7d..e63ccc4be 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.cpp @@ -1,60 +1,60 @@ -/** -****************************************************************************** -* -* @file tile.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "tile.h" - - -namespace internals { -Tile::Tile(int zoom, Point pos) -{ - this->zoom=zoom; - this->pos=pos; -} -void Tile::Clear() -{ -#ifdef DEBUG_TILE - qDebug()<<"Tile:Clear Overlays"; -#endif //DEBUG_TILE - mutex.lock(); - foreach(QByteArray img, Overlays) - { - img.~QByteArray(); - } - Overlays.clear(); - mutex.unlock(); -} -Tile::Tile():zoom(0),pos(0,0) -{ - -} -Tile& Tile::operator =(const Tile &cSource) -{ - this->zoom=cSource.zoom; - this->pos=cSource.pos; - return *this; -} - -} +/** +****************************************************************************** +* +* @file tile.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "tile.h" + + +namespace internals { +Tile::Tile(int zoom, Point pos) +{ + this->zoom=zoom; + this->pos=pos; +} +void Tile::Clear() +{ +#ifdef DEBUG_TILE + qDebug()<<"Tile:Clear Overlays"; +#endif //DEBUG_TILE + mutex.lock(); + foreach(QByteArray img, Overlays) + { + img.~QByteArray(); + } + Overlays.clear(); + mutex.unlock(); +} +Tile::Tile():zoom(0),pos(0,0) +{ + +} +Tile& Tile::operator =(const Tile &cSource) +{ + this->zoom=cSource.zoom; + this->pos=cSource.pos; + return *this; +} + +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.h index 5055ca6c6..0f67ad205 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tile.h @@ -1,67 +1,67 @@ -/** -****************************************************************************** -* -* @file tile.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef TILE_H -#define TILE_H - -#include "QList" -#include -#include "../core/point.h" -#include -#include -#include "debugheader.h" -using namespace core; -namespace internals -{ -class Tile -{ -public: - Tile(int zoom,core::Point pos); - Tile(); - void Clear(); - int GetZoom(){return zoom;} - core::Point GetPos(){return pos;} - void SetZoom(const int &value){zoom=value;} - void SetPos(const core::Point &value){pos=value;} - Tile& operator= (const Tile &cSource); - Tile(const Tile &cSource) - { - this->zoom=cSource.zoom; - this->pos=cSource.pos; - } - bool HasValue(){return !(zoom==0);} - QList Overlays; -protected: - - QMutex mutex; -private: - int zoom; - core::Point pos; - - -}; -} -#endif // TILE_H +/** +****************************************************************************** +* +* @file tile.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef TILE_H +#define TILE_H + +#include "QList" +#include +#include "../core/point.h" +#include +#include +#include "debugheader.h" +using namespace core; +namespace internals +{ +class Tile +{ +public: + Tile(int zoom,core::Point pos); + Tile(); + void Clear(); + int GetZoom(){return zoom;} + core::Point GetPos(){return pos;} + void SetZoom(const int &value){zoom=value;} + void SetPos(const core::Point &value){pos=value;} + Tile& operator= (const Tile &cSource); + Tile(const Tile &cSource) + { + this->zoom=cSource.zoom; + this->pos=cSource.pos; + } + bool HasValue(){return !(zoom==0);} + QList Overlays; +protected: + + QMutex mutex; +private: + int zoom; + core::Point pos; + + +}; +} +#endif // TILE_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.cpp index 9def2e176..b9ad2b003 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/tilematrix.cpp @@ -1,148 +1,148 @@ -/** -****************************************************************************** -* -* @file tilematrix.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "tilematrix.h" - - -namespace internals { -TileMatrix::TileMatrix() -{ -} -void TileMatrix::Clear() -{ - mutex.lock(); - foreach(Tile* t,matrix.values()) - { - delete t; - t=0; - } - matrix.clear(); - mutex.unlock(); -} -//void TileMatrix::RebuildToUpperZoom() -//{ -// mutex.lock(); -// QList newtiles; -// foreach(Tile* t,matrix.values()) -// { -// Point point=Point(t->GetPos().X()*2,t->GetPos().Y()*2); -// Tile* tile1=new Tile(t->GetZoom()+1,point); -// Tile* tile2=new Tile(t->GetZoom()+1,Point(point.X()+1,point.Y()+0)); -// Tile* tile3=new Tile(t->GetZoom()+1,Point(point.X()+0,point.Y()+1)); -// Tile* tile4=new Tile(t->GetZoom()+1,Point(point.X()+1,point.Y()+1)); -// -// foreach(QByteArray arr, t->Overlays) -// { -// QImage ima=QImage::fromData(arr); -// QImage ima1=ima.copy(0,0,ima.width()/2,ima.height()/2); -// QImage ima2=ima.copy(ima.width()/2,0,ima.width()/2,ima.height()/2); -// QImage ima3=ima.copy(0,ima.height()/2,ima.width()/2,ima.height()/2); -// QImage ima4=ima.copy(ima.width()/2,ima.height()/2,ima.width()/2,ima.height()/2); -// QByteArray ba; -// QBuffer buf(&ba); -// ima1.scaled(QSize(ima.width(),ima.height())).save(&buf,"PNG"); -// tile1->Overlays.append(ba); -// QByteArray ba1; -// QBuffer buf1(&ba1); -// ima2.scaled(QSize(ima.width(),ima.height())).save(&buf1,"PNG"); -// tile2->Overlays.append(ba1); -// QByteArray ba2; -// QBuffer buf2(&ba2); -// ima3.scaled(QSize(ima.width(),ima.height())).save(&buf2,"PNG"); -// tile3->Overlays.append(ba2); -// QByteArray ba3; -// QBuffer buf3(&ba3); -// ima4.scaled(QSize(ima.width(),ima.height())).save(&buf3,"PNG"); -// tile4->Overlays.append(ba3); -// newtiles.append(tile1); -// newtiles.append(tile2); -// newtiles.append(tile3); -// newtiles.append(tile4); -// } -// } -// foreach(Tile* t,matrix.values()) -// { -// delete t; -// t=0; -// } -// matrix.clear(); -// foreach(Tile* t,newtiles) -// { -// matrix.insert(t->GetPos(),t); -// } -// -// mutex.unlock(); -//} - -void TileMatrix::ClearPointsNotIn(QListlist) -{ - removals.clear(); - mutex.lock(); - foreach(Point p, matrix.keys()) - { - if(!list.contains(p)) - { - removals.append(p); - } - } - mutex.unlock(); - foreach(Point p,removals) - { - Tile* t=TileAt(p); - if(t!=0) - { - mutex.lock(); - delete t; - t=0; - matrix.remove(p); - mutex.unlock(); - } - - } - removals.clear(); -} -Tile* TileMatrix::TileAt(const Point &p) -{ - -#ifdef DEBUG_TILEMATRIX - qDebug()<<"TileMatrix:TileAt:"< newtiles; +// foreach(Tile* t,matrix.values()) +// { +// Point point=Point(t->GetPos().X()*2,t->GetPos().Y()*2); +// Tile* tile1=new Tile(t->GetZoom()+1,point); +// Tile* tile2=new Tile(t->GetZoom()+1,Point(point.X()+1,point.Y()+0)); +// Tile* tile3=new Tile(t->GetZoom()+1,Point(point.X()+0,point.Y()+1)); +// Tile* tile4=new Tile(t->GetZoom()+1,Point(point.X()+1,point.Y()+1)); +// +// foreach(QByteArray arr, t->Overlays) +// { +// QImage ima=QImage::fromData(arr); +// QImage ima1=ima.copy(0,0,ima.width()/2,ima.height()/2); +// QImage ima2=ima.copy(ima.width()/2,0,ima.width()/2,ima.height()/2); +// QImage ima3=ima.copy(0,ima.height()/2,ima.width()/2,ima.height()/2); +// QImage ima4=ima.copy(ima.width()/2,ima.height()/2,ima.width()/2,ima.height()/2); +// QByteArray ba; +// QBuffer buf(&ba); +// ima1.scaled(QSize(ima.width(),ima.height())).save(&buf,"PNG"); +// tile1->Overlays.append(ba); +// QByteArray ba1; +// QBuffer buf1(&ba1); +// ima2.scaled(QSize(ima.width(),ima.height())).save(&buf1,"PNG"); +// tile2->Overlays.append(ba1); +// QByteArray ba2; +// QBuffer buf2(&ba2); +// ima3.scaled(QSize(ima.width(),ima.height())).save(&buf2,"PNG"); +// tile3->Overlays.append(ba2); +// QByteArray ba3; +// QBuffer buf3(&ba3); +// ima4.scaled(QSize(ima.width(),ima.height())).save(&buf3,"PNG"); +// tile4->Overlays.append(ba3); +// newtiles.append(tile1); +// newtiles.append(tile2); +// newtiles.append(tile3); +// newtiles.append(tile4); +// } +// } +// foreach(Tile* t,matrix.values()) +// { +// delete t; +// t=0; +// } +// matrix.clear(); +// foreach(Tile* t,newtiles) +// { +// matrix.insert(t->GetPos(),t); +// } +// +// mutex.unlock(); +//} + +void TileMatrix::ClearPointsNotIn(QListlist) +{ + removals.clear(); + mutex.lock(); + foreach(Point p, matrix.keys()) + { + if(!list.contains(p)) + { + removals.append(p); + } + } + mutex.unlock(); + foreach(Point p,removals) + { + Tile* t=TileAt(p); + if(t!=0) + { + mutex.lock(); + delete t; + t=0; + matrix.remove(p); + mutex.unlock(); + } + + } + removals.clear(); +} +Tile* TileMatrix::TileAt(const Point &p) +{ + +#ifdef DEBUG_TILEMATRIX + qDebug()<<"TileMatrix:TileAt:"< -#include "tile.h" -#include -#include "../core/point.h" -#include "debugheader.h" -#include -namespace internals { -class TileMatrix -{ -public: - TileMatrix(); - void Clear(); - void ClearPointsNotIn(QList list); - Tile* TileAt(const core::Point &p); - void SetTileAt(const core::Point &p,Tile* tile); - int count()const{return matrix.count();} - // void RebuildToUpperZoom(); -protected: - QHash matrix; - QList removals; - QMutex mutex; -}; - -} -#endif // TILEMATRIX_H +/** +****************************************************************************** +* +* @file tilematrix.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef TILEMATRIX_H +#define TILEMATRIX_H + +#include +#include "tile.h" +#include +#include "../core/point.h" +#include "debugheader.h" +#include +namespace internals { +class TileMatrix +{ +public: + TileMatrix(); + void Clear(); + void ClearPointsNotIn(QList list); + Tile* TileAt(const core::Point &p); + void SetTileAt(const core::Point &p,Tile* tile); + int count()const{return matrix.count();} + // void RebuildToUpperZoom(); +protected: + QHash matrix; + QList removals; + QMutex mutex; +}; + +} +#endif // TILEMATRIX_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.cpp index d32b8dcb2..38a855040 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.cpp @@ -1,60 +1,60 @@ -/** -****************************************************************************** -* -* @file configuration.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A class that centralizes most of the mapcontrol configurations -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "configuration.h" -namespace mapcontrol -{ -Configuration::Configuration() -{ - EmptytileBrush = Qt::cyan; - MissingDataFont =QFont ("Times",10,QFont::Bold); - EmptyTileText = "We are sorry, but we don't\nhave imagery at this zoom\nlevel for this region."; - EmptyTileBorders = QPen(Qt::white); - ScalePen = QPen(Qt::blue); - SelectionPen = QPen(Qt::blue); - DragButton = Qt::LeftButton; -} -void Configuration::SetAccessMode(core::AccessMode::Types const& type) -{ - core::OPMaps::Instance()->setAccessMode(type); -} -core::AccessMode::Types Configuration::AccessMode() -{ - return core::OPMaps::Instance()->GetAccessMode(); -} -void Configuration::SetLanguage(core::LanguageType::Types const& type) -{ - core::OPMaps::Instance()->setLanguage(type); -} -core::LanguageType::Types Configuration::Language() -{ - return core::OPMaps::Instance()->GetLanguage(); -} -void Configuration::SetUseMemoryCache(bool const& value) -{ - core::OPMaps::Instance()->setUseMemoryCache(value); -} -} +/** +****************************************************************************** +* +* @file configuration.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A class that centralizes most of the mapcontrol configurations +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "configuration.h" +namespace mapcontrol +{ +Configuration::Configuration() +{ + EmptytileBrush = Qt::cyan; + MissingDataFont =QFont ("Times",10,QFont::Bold); + EmptyTileText = "We are sorry, but we don't\nhave imagery at this zoom\nlevel for this region."; + EmptyTileBorders = QPen(Qt::white); + ScalePen = QPen(Qt::blue); + SelectionPen = QPen(Qt::blue); + DragButton = Qt::LeftButton; +} +void Configuration::SetAccessMode(core::AccessMode::Types const& type) +{ + core::OPMaps::Instance()->setAccessMode(type); +} +core::AccessMode::Types Configuration::AccessMode() +{ + return core::OPMaps::Instance()->GetAccessMode(); +} +void Configuration::SetLanguage(core::LanguageType::Types const& type) +{ + core::OPMaps::Instance()->setLanguage(type); +} +core::LanguageType::Types Configuration::Language() +{ + return core::OPMaps::Instance()->GetLanguage(); +} +void Configuration::SetUseMemoryCache(bool const& value) +{ + core::OPMaps::Instance()->setUseMemoryCache(value); +} +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.h index cadb045ca..6c3987654 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/configuration.h @@ -1,186 +1,186 @@ -/** -****************************************************************************** -* -* @file configuration.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A class that centralizes most of the mapcontrol configurations -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -#ifndef CONFIGURATION_H -#define CONFIGURATION_H - -#include -#include -#include -#include -#include "../core/opmaps.h" -#include "../core/accessmode.h" -#include "../core/cache.h" -namespace mapcontrol -{ - -/** -* @brief A class that centralizes most of the mapcontrol configurations -* -* @class Configuration configuration.h "configuration.h" -*/ -class Configuration -{ -public: - Configuration(); - /** - * @brief Used to draw empty map tiles - * - * @var EmptytileBrush - */ - QBrush EmptytileBrush; - /** - * @brief Used for empty tiles text - * - * @var EmptyTileText - */ - QString EmptyTileText; - /** - * @brief Used to draw empty tile borders - * - * @var EmptyTileBorders - */ - QPen EmptyTileBorders; - /** - * @brief Used to Draw the maps scale - * - * @var ScalePen - */ - QPen ScalePen; - /** - * @brief Used to draw selection box - * - * @var SelectionPen - */ - QPen SelectionPen; - /** - * @brief - * - * @var MissingDataFont - */ - QFont MissingDataFont; - - /** - * @brief Button used for dragging - * - * @var DragButton - */ - Qt::MouseButton DragButton; - - /** - * @brief Sets the access mode for the map (cache only, server and cache...) - * - * @param type access mode - */ - void SetAccessMode(core::AccessMode::Types const& type); - /** - * @brief Returns the access mode for the map (cache only, server and cache...) - * - * @return core::AccessMode::Types access mode for the map - */ - core::AccessMode::Types AccessMode(); - - /** - * @brief Sets the language used for geocaching - * - * @param type The language to be used - */ - void SetLanguage(core::LanguageType::Types const& type); - /** - * @brief Returns the language used for geocaching - * - * @return core::LanguageType::Types - */ - core::LanguageType::Types Language(); - - /** - * @brief Used to allow disallow use of memory caching - * - * @param value - * @return - */ - void SetUseMemoryCache(bool const& value); - /** - * @brief Return if memory caching is in use - * - * @return - */ - bool UseMemoryCache(){return core::OPMaps::Instance()->UseMemoryCache();} - - /** - * @brief Returns the currently used memory for tiles - * - * @return - */ - double TileMemoryUsed()const{return core::OPMaps::Instance()->TilesInMemory.MemoryCacheSize();} - - /** - * @brief Sets the size of the memory for tiles - * - * @param value size in Mb to use for tiles - * @return - */ - void SetTileMemorySize(int const& value){core::OPMaps::Instance()->TilesInMemory.setMemoryCacheCapacity(value);} - - /** - * @brief Sets the location for the SQLite Database used for caching and the geocoding cache files - * - * @param dir The path location for the cache file-IMPORTANT Must end with closing slash "/" - */ - void SetCacheLocation(QString const& dir) - { - core::Cache::Instance()->setCacheLocation(dir); - - } - - /** - * @brief Deletes tiles in DataBase older than "days" days - * - * @param days - * @return - */ - void DeleteTilesOlderThan(int const& days){core::Cache::Instance()->ImageCache.deleteOlderTiles(days);} - - /** - * @brief Exports tiles from one DB to another. Only new tiles are added. - * - * @param sourceDB the source DB - * @param destDB the destination DB. If it doesnt exhist it will be created. - * @return - */ - void ExportMapDataToDB(QString const& sourceDB, QString const& destDB)const{core::PureImageCache::ExportMapDataToDB(sourceDB,destDB);} - /** - * @brief Returns the location for the SQLite Database used for caching and the geocoding cache files - * - * @return - */ - QString CacheLocation(){return core::Cache::Instance()->CacheLocation();} - - -}; -} -#endif // CONFIGURATION_H +/** +****************************************************************************** +* +* @file configuration.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A class that centralizes most of the mapcontrol configurations +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#ifndef CONFIGURATION_H +#define CONFIGURATION_H + +#include +#include +#include +#include +#include "../core/opmaps.h" +#include "../core/accessmode.h" +#include "../core/cache.h" +namespace mapcontrol +{ + +/** +* @brief A class that centralizes most of the mapcontrol configurations +* +* @class Configuration configuration.h "configuration.h" +*/ +class Configuration +{ +public: + Configuration(); + /** + * @brief Used to draw empty map tiles + * + * @var EmptytileBrush + */ + QBrush EmptytileBrush; + /** + * @brief Used for empty tiles text + * + * @var EmptyTileText + */ + QString EmptyTileText; + /** + * @brief Used to draw empty tile borders + * + * @var EmptyTileBorders + */ + QPen EmptyTileBorders; + /** + * @brief Used to Draw the maps scale + * + * @var ScalePen + */ + QPen ScalePen; + /** + * @brief Used to draw selection box + * + * @var SelectionPen + */ + QPen SelectionPen; + /** + * @brief + * + * @var MissingDataFont + */ + QFont MissingDataFont; + + /** + * @brief Button used for dragging + * + * @var DragButton + */ + Qt::MouseButton DragButton; + + /** + * @brief Sets the access mode for the map (cache only, server and cache...) + * + * @param type access mode + */ + void SetAccessMode(core::AccessMode::Types const& type); + /** + * @brief Returns the access mode for the map (cache only, server and cache...) + * + * @return core::AccessMode::Types access mode for the map + */ + core::AccessMode::Types AccessMode(); + + /** + * @brief Sets the language used for geocaching + * + * @param type The language to be used + */ + void SetLanguage(core::LanguageType::Types const& type); + /** + * @brief Returns the language used for geocaching + * + * @return core::LanguageType::Types + */ + core::LanguageType::Types Language(); + + /** + * @brief Used to allow disallow use of memory caching + * + * @param value + * @return + */ + void SetUseMemoryCache(bool const& value); + /** + * @brief Return if memory caching is in use + * + * @return + */ + bool UseMemoryCache(){return core::OPMaps::Instance()->UseMemoryCache();} + + /** + * @brief Returns the currently used memory for tiles + * + * @return + */ + double TileMemoryUsed()const{return core::OPMaps::Instance()->TilesInMemory.MemoryCacheSize();} + + /** + * @brief Sets the size of the memory for tiles + * + * @param value size in Mb to use for tiles + * @return + */ + void SetTileMemorySize(int const& value){core::OPMaps::Instance()->TilesInMemory.setMemoryCacheCapacity(value);} + + /** + * @brief Sets the location for the SQLite Database used for caching and the geocoding cache files + * + * @param dir The path location for the cache file-IMPORTANT Must end with closing slash "/" + */ + void SetCacheLocation(QString const& dir) + { + core::Cache::Instance()->setCacheLocation(dir); + + } + + /** + * @brief Deletes tiles in DataBase older than "days" days + * + * @param days + * @return + */ + void DeleteTilesOlderThan(int const& days){core::Cache::Instance()->ImageCache.deleteOlderTiles(days);} + + /** + * @brief Exports tiles from one DB to another. Only new tiles are added. + * + * @param sourceDB the source DB + * @param destDB the destination DB. If it doesnt exhist it will be created. + * @return + */ + void ExportMapDataToDB(QString const& sourceDB, QString const& destDB)const{core::PureImageCache::ExportMapDataToDB(sourceDB,destDB);} + /** + * @brief Returns the location for the SQLite Database used for caching and the geocoding cache files + * + * @return + */ + QString CacheLocation(){return core::Cache::Instance()->CacheLocation();} + + +}; +} +#endif // CONFIGURATION_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp index 7aff42e20..fa8bddb48 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.cpp @@ -1,155 +1,155 @@ -/** -****************************************************************************** -* -* @file homeitem.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A graphicsItem representing a trail point -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "homeitem.h" -namespace mapcontrol -{ - HomeItem::HomeItem(MapGraphicItem* map,OPMapWidget* parent):safe(true),map(map),mapwidget(parent), - showsafearea(true),toggleRefresh(true),safearea(1000),altitude(0),isDragging(false) - { - pic.load(QString::fromUtf8(":/markers/images/home2.svg")); - pic=pic.scaled(30,30,Qt::IgnoreAspectRatio); - this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); - this->setFlag(QGraphicsItem::ItemIsMovable,false); - this->setFlag(QGraphicsItem::ItemIsSelectable,true); - localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition()); - this->setPos(localposition.X(),localposition.Y()); - this->setZValue(4); - coord=internals::PointLatLng(50,50); - RefreshToolTip(); - setCacheMode(QGraphicsItem::DeviceCoordinateCache); - connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); - connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); - } - - void HomeItem::RefreshToolTip() - { - QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); - - setToolTip(QString("Waypoint: Home\nCoordinate:%1\nAltitude:%2\n").arg(coord_str).arg(QString::number(altitude))); - } - - - void HomeItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) - { - Q_UNUSED(option); - Q_UNUSED(widget); - painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); - if(showsafearea) - { - if(safe) - painter->setPen(Qt::green); - else - painter->setPen(Qt::red); - painter->drawEllipse(QPointF(0,0),localsafearea,localsafearea); - // painter->drawRect(QRectF(-localsafearea,-localsafearea,localsafearea*2,localsafearea*2)); - } - - } - QRectF HomeItem::boundingRect()const - { - if(pic.width()>localsafearea*2 && !toggleRefresh) - return QRectF(-pic.width()/2,-pic.height()/2,pic.width(),pic.height()); - else - return QRectF(-localsafearea,-localsafearea,localsafearea*2,localsafearea*2); - } - - - int HomeItem::type()const - { - return Type; - } - - void HomeItem::RefreshPos() - { - prepareGeometryChange(); - localposition=map->FromLatLngToLocal(coord); - this->setPos(localposition.X(),localposition.Y()); - if(showsafearea) - localsafearea=safearea/map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat()); - - RefreshToolTip(); - - this->update(); - toggleRefresh=false; - - } - - void HomeItem::setOpacitySlot(qreal opacity) - { - setOpacity(opacity); - } - - void HomeItem::mousePressEvent(QGraphicsSceneMouseEvent *event) - { - if(event->button()==Qt::LeftButton) - { - isDragging=true; - } - QGraphicsItem::mousePressEvent(event); - } - - void HomeItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) - { - if(event->button()==Qt::LeftButton) - { - coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); - isDragging=false; - - emit homePositionChanged(coord,Altitude()); - } - QGraphicsItem::mouseReleaseEvent(event); - - RefreshToolTip(); - } - void HomeItem::mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event) - { - if(event->button()==Qt::LeftButton) - { - emit homedoubleclick(this); - } - } - void HomeItem::mouseMoveEvent(QGraphicsSceneMouseEvent *event) - { - - if(isDragging) - { - coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); - emit homePositionChanged(coord,Altitude()); - } - QGraphicsItem::mouseMoveEvent(event); - } - - //Set clickable area as smaller than the bounding rect. - QPainterPath HomeItem::shape() const - { - QPainterPath path; - path.addEllipse(QRectF(-12, -25, 24, 50)); - return path; - } - -} - +/** +****************************************************************************** +* +* @file homeitem.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A graphicsItem representing a trail point +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "homeitem.h" +namespace mapcontrol +{ + HomeItem::HomeItem(MapGraphicItem* map,OPMapWidget* parent):safe(true),map(map),mapwidget(parent), + showsafearea(true),toggleRefresh(true),safearea(1000),altitude(0),isDragging(false) + { + pic.load(QString::fromUtf8(":/markers/images/home2.svg")); + pic=pic.scaled(30,30,Qt::IgnoreAspectRatio); + this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); + this->setFlag(QGraphicsItem::ItemIsMovable,false); + this->setFlag(QGraphicsItem::ItemIsSelectable,true); + localposition=map->FromLatLngToLocal(mapwidget->CurrentPosition()); + this->setPos(localposition.X(),localposition.Y()); + this->setZValue(4); + coord=internals::PointLatLng(50,50); + RefreshToolTip(); + setCacheMode(QGraphicsItem::DeviceCoordinateCache); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); + } + + void HomeItem::RefreshToolTip() + { + QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); + + setToolTip(QString("Waypoint: Home\nCoordinate:%1\nAltitude:%2\n").arg(coord_str).arg(QString::number(altitude))); + } + + + void HomeItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) + { + Q_UNUSED(option); + Q_UNUSED(widget); + painter->drawPixmap(-pic.width()/2,-pic.height()/2,pic); + if(showsafearea) + { + if(safe) + painter->setPen(Qt::green); + else + painter->setPen(Qt::red); + painter->drawEllipse(QPointF(0,0),localsafearea,localsafearea); + // painter->drawRect(QRectF(-localsafearea,-localsafearea,localsafearea*2,localsafearea*2)); + } + + } + QRectF HomeItem::boundingRect()const + { + if(pic.width()>localsafearea*2 && !toggleRefresh) + return QRectF(-pic.width()/2,-pic.height()/2,pic.width(),pic.height()); + else + return QRectF(-localsafearea,-localsafearea,localsafearea*2,localsafearea*2); + } + + + int HomeItem::type()const + { + return Type; + } + + void HomeItem::RefreshPos() + { + prepareGeometryChange(); + localposition=map->FromLatLngToLocal(coord); + this->setPos(localposition.X(),localposition.Y()); + if(showsafearea) + localsafearea=safearea/map->Projection()->GetGroundResolution(map->ZoomTotal(),coord.Lat()); + + RefreshToolTip(); + + this->update(); + toggleRefresh=false; + + } + + void HomeItem::setOpacitySlot(qreal opacity) + { + setOpacity(opacity); + } + + void HomeItem::mousePressEvent(QGraphicsSceneMouseEvent *event) + { + if(event->button()==Qt::LeftButton) + { + isDragging=true; + } + QGraphicsItem::mousePressEvent(event); + } + + void HomeItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) + { + if(event->button()==Qt::LeftButton) + { + coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); + isDragging=false; + + emit homePositionChanged(coord,Altitude()); + } + QGraphicsItem::mouseReleaseEvent(event); + + RefreshToolTip(); + } + void HomeItem::mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event) + { + if(event->button()==Qt::LeftButton) + { + emit homedoubleclick(this); + } + } + void HomeItem::mouseMoveEvent(QGraphicsSceneMouseEvent *event) + { + + if(isDragging) + { + coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); + emit homePositionChanged(coord,Altitude()); + } + QGraphicsItem::mouseMoveEvent(event); + } + + //Set clickable area as smaller than the bounding rect. + QPainterPath HomeItem::shape() const + { + QPainterPath path; + path.addEllipse(QRectF(-12, -25, 24, 50)); + return path; + } + +} + diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h index 1e19540aa..2cf34b135 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/homeitem.h @@ -1,88 +1,88 @@ -/** -****************************************************************************** -* -* @file homeitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A graphicsItem representing a WayPoint -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef HOMEITEM_H -#define HOMEITEM_H - -#include -#include -#include -#include "../internals/pointlatlng.h" -#include -#include "opmapwidget.h" -namespace mapcontrol -{ - - class HomeItem:public QObject,public QGraphicsItem - { - Q_OBJECT - Q_INTERFACES(QGraphicsItem) - public: - enum { Type = UserType + 4 }; - HomeItem(MapGraphicItem* map,OPMapWidget* parent); - void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, - QWidget *widget); - QRectF boundingRect() const; - int type() const; - bool ShowSafeArea()const{return showsafearea;} - void SetShowSafeArea(bool const& value){showsafearea=value;} - void SetToggleRefresh(bool const& value){toggleRefresh=value;} - int SafeArea()const{return safearea;} - void SetSafeArea(int const& value){safearea=value;} - bool safe; - void SetCoord(internals::PointLatLng const& value){coord=value;emit homePositionChanged(value,Altitude());} - internals::PointLatLng Coord()const{return coord;} - void SetAltitude(float const& value){altitude=value;emit homePositionChanged(Coord(),Altitude());} - float Altitude()const{return altitude;} - void RefreshToolTip(); - private: - - MapGraphicItem* map; - OPMapWidget* mapwidget; - QPixmap pic; - core::Point localposition; - internals::PointLatLng coord; - bool showsafearea; - bool toggleRefresh; - int safearea; - int localsafearea; - float altitude; - bool isDragging; - protected: - void mouseMoveEvent ( QGraphicsSceneMouseEvent * event ); - void mousePressEvent ( QGraphicsSceneMouseEvent * event ); - void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event ); - void mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event); - QPainterPath shape() const; - public slots: - void RefreshPos(); - void setOpacitySlot(qreal opacity); - signals: - void homePositionChanged(internals::PointLatLng coord,float); - void homedoubleclick(HomeItem* waypoint); - }; -} -#endif // HOMEITEM_H +/** +****************************************************************************** +* +* @file homeitem.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A graphicsItem representing a WayPoint +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef HOMEITEM_H +#define HOMEITEM_H + +#include +#include +#include +#include "../internals/pointlatlng.h" +#include +#include "opmapwidget.h" +namespace mapcontrol +{ + + class HomeItem:public QObject,public QGraphicsItem + { + Q_OBJECT + Q_INTERFACES(QGraphicsItem) + public: + enum { Type = UserType + 4 }; + HomeItem(MapGraphicItem* map,OPMapWidget* parent); + void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, + QWidget *widget); + QRectF boundingRect() const; + int type() const; + bool ShowSafeArea()const{return showsafearea;} + void SetShowSafeArea(bool const& value){showsafearea=value;} + void SetToggleRefresh(bool const& value){toggleRefresh=value;} + int SafeArea()const{return safearea;} + void SetSafeArea(int const& value){safearea=value;} + bool safe; + void SetCoord(internals::PointLatLng const& value){coord=value;emit homePositionChanged(value,Altitude());} + internals::PointLatLng Coord()const{return coord;} + void SetAltitude(float const& value){altitude=value;emit homePositionChanged(Coord(),Altitude());} + float Altitude()const{return altitude;} + void RefreshToolTip(); + private: + + MapGraphicItem* map; + OPMapWidget* mapwidget; + QPixmap pic; + core::Point localposition; + internals::PointLatLng coord; + bool showsafearea; + bool toggleRefresh; + int safearea; + int localsafearea; + float altitude; + bool isDragging; + protected: + void mouseMoveEvent ( QGraphicsSceneMouseEvent * event ); + void mousePressEvent ( QGraphicsSceneMouseEvent * event ); + void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event ); + void mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event); + QPainterPath shape() const; + public slots: + void RefreshPos(); + void setOpacitySlot(qreal opacity); + signals: + void homePositionChanged(internals::PointLatLng coord,float); + void homedoubleclick(HomeItem* waypoint); + }; +} +#endif // HOMEITEM_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp index 55eadacc2..78256bd35 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.cpp @@ -1,54 +1,54 @@ -/** -****************************************************************************** -* -* @file mapripform.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief Form to be used with the MapRipper class -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -#include "mapripform.h" -#include "ui_mapripform.h" - -MapRipForm::MapRipForm(QWidget *parent) : - QWidget(parent), - ui(new Ui::MapRipForm) -{ - ui->setupUi(this); - connect(ui->cancelButton,SIGNAL(clicked()),this,SIGNAL(cancelRequest())); -} - -MapRipForm::~MapRipForm() -{ - delete ui; -} -void MapRipForm::SetPercentage(const int &perc) -{ - ui->progressBar->setValue(perc); -} -void MapRipForm::SetProvider(const QString &prov,const int &zoom) -{ - ui->mainlabel->setText(QString("Currently ripping from:%1 at Zoom level %2").arg(prov).arg(zoom)); -} -void MapRipForm::SetNumberOfTiles(const int &total, const int &actual) -{ - ui->statuslabel->setText(QString("Downloading tile %1 of %2").arg(actual).arg(total)); -} +/** +****************************************************************************** +* +* @file mapripform.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief Form to be used with the MapRipper class +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include "mapripform.h" +#include "ui_mapripform.h" + +MapRipForm::MapRipForm(QWidget *parent) : + QWidget(parent), + ui(new Ui::MapRipForm) +{ + ui->setupUi(this); + connect(ui->cancelButton,SIGNAL(clicked()),this,SIGNAL(cancelRequest())); +} + +MapRipForm::~MapRipForm() +{ + delete ui; +} +void MapRipForm::SetPercentage(const int &perc) +{ + ui->progressBar->setValue(perc); +} +void MapRipForm::SetProvider(const QString &prov,const int &zoom) +{ + ui->mainlabel->setText(QString("Currently ripping from:%1 at Zoom level %2").arg(prov).arg(zoom)); +} +void MapRipForm::SetNumberOfTiles(const int &total, const int &actual) +{ + ui->statuslabel->setText(QString("Downloading tile %1 of %2").arg(actual).arg(total)); +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h index d3df3f881..dc0ceb56c 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.h @@ -1,53 +1,53 @@ -/** -****************************************************************************** -* -* @file mapripform.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief Form to be used with the MapRipper class -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef MAPRIPFORM_H -#define MAPRIPFORM_H - -#include - -namespace Ui { - class MapRipForm; -} - -class MapRipForm : public QWidget -{ - Q_OBJECT - -public: - explicit MapRipForm(QWidget *parent = 0); - ~MapRipForm(); -public slots: - void SetPercentage(int const& perc); - void SetProvider(QString const& prov,int const& zoom); - void SetNumberOfTiles(int const& total,int const& actual); -signals: - void cancelRequest(); -private: - Ui::MapRipForm *ui; -}; - -#endif // MAPRIPFORM_H +/** +****************************************************************************** +* +* @file mapripform.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief Form to be used with the MapRipper class +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef MAPRIPFORM_H +#define MAPRIPFORM_H + +#include + +namespace Ui { + class MapRipForm; +} + +class MapRipForm : public QWidget +{ + Q_OBJECT + +public: + explicit MapRipForm(QWidget *parent = 0); + ~MapRipForm(); +public slots: + void SetPercentage(int const& perc); + void SetProvider(QString const& prov,int const& zoom); + void SetNumberOfTiles(int const& total,int const& actual); +signals: + void cancelRequest(); +private: + Ui::MapRipForm *ui; +}; + +#endif // MAPRIPFORM_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui index 1fa6a935d..ecc2882aa 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripform.ui @@ -1,71 +1,71 @@ - - - MapRipForm - - - - 0 - 0 - 521 - 133 - - - - MapRipper - - - - - 20 - 60 - 481 - 23 - - - - 0 - - - - - - 30 - 10 - 481 - 16 - - - - Currently ripping from: - - - - - - 30 - 40 - 341 - 16 - - - - Downloading tile - - - - - - 220 - 100 - 75 - 23 - - - - Cancel - - - - - - + + + MapRipForm + + + + 0 + 0 + 521 + 133 + + + + MapRipper + + + + + 20 + 60 + 481 + 23 + + + + 0 + + + + + + 30 + 10 + 481 + 16 + + + + Currently ripping from: + + + + + + 30 + 40 + 341 + 16 + + + + Downloading tile + + + + + + 220 + 100 + 75 + 23 + + + + Cancel + + + + + + diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp index 4c8bbcd1c..26778d5cb 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.cpp @@ -1,156 +1,156 @@ -/** -****************************************************************************** -* -* @file mapripper.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A class that allows ripping of a selection of the map -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "mapripper.h" -namespace mapcontrol -{ - -MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect):sleep(100),cancel(false),progressForm(0),core(core),yesToAll(false) - { - if(!rect.IsEmpty()) - { - type=core->GetMapType(); - progressForm=new MapRipForm; - connect(progressForm,SIGNAL(cancelRequest()),this,SLOT(stopFetching())); - area=rect; - zoom=core->Zoom(); - maxzoom=core->MaxZoom(); - points=core->Projection()->GetAreaTileList(area,zoom,0); - this->start(); - cancel=false; - progressForm->show(); - connect(this,SIGNAL(percentageChanged(int)),progressForm,SLOT(SetPercentage(int))); - connect(this,SIGNAL(numberOfTilesChanged(int,int)),progressForm,SLOT(SetNumberOfTiles(int,int))); - connect(this,SIGNAL(providerChanged(QString,int)),progressForm,SLOT(SetProvider(QString,int))); - connect(this,SIGNAL(finished()),this,SLOT(finish())); - emit numberOfTilesChanged(0,0); - } - else -#ifdef Q_OS_DARWIN - QMessageBox::information(new QWidget(),"No valid selection","This pre-caches map data.\n\nPlease first select the area of the map to rip with +Left mouse click"); -#else - QMessageBox::information(new QWidget(),"No valid selection","This pre-caches map data.\n\nPlease first select the area of the map to rip with +Left mouse click"); -#endif - } -void MapRipper::finish() -{ - if(zoomProjection()->GetAreaTileList(area,zoom,0); - this->start(); - } - else if(ret==QMessageBox::YesAll) - { - yesToAll=true; - points.clear(); - points=core->Projection()->GetAreaTileList(area,zoom,0); - this->start(); - } - else - { - progressForm->close(); - delete progressForm; - this->deleteLater(); - } - } - else - { - yesToAll=false; - progressForm->close(); - delete progressForm; - this->deleteLater(); - } -} - - - void MapRipper::run() - { - int countOk = 0; - bool goodtile=false; - // Stuff.Shuffle(ref list); - QVector types = OPMaps::Instance()->GetAllLayersOfType(type); - int all=points.count(); - for(int i = 0; i < all; i++) - { - emit numberOfTilesChanged(all,i+1); - if(cancel) - break; - - core::Point p = points[i]; - { - //qDebug()<<"offline fetching:"<GetImageFrom(type, p, zoom); - if(img.length()!=0) - { - goodtile=true; - img=NULL; - } - else - goodtile=false; - } - if(goodtile) - { - countOk++; - } - else - { - i--; - QThread::msleep(1000); - continue; - } - } - emit percentageChanged((int) ((i+1)*100/all));//, i+1); - // worker.ReportProgress((int) ((i+1)*100/all), i+1); - - QThread::msleep(sleep); - } - } - - void MapRipper::stopFetching() - { - QMutexLocker locker(&mutex); - cancel=true; - } -} +/** +****************************************************************************** +* +* @file mapripper.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A class that allows ripping of a selection of the map +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "mapripper.h" +namespace mapcontrol +{ + +MapRipper::MapRipper(internals::Core * core, const internals::RectLatLng & rect):sleep(100),cancel(false),progressForm(0),core(core),yesToAll(false) + { + if(!rect.IsEmpty()) + { + type=core->GetMapType(); + progressForm=new MapRipForm; + connect(progressForm,SIGNAL(cancelRequest()),this,SLOT(stopFetching())); + area=rect; + zoom=core->Zoom(); + maxzoom=core->MaxZoom(); + points=core->Projection()->GetAreaTileList(area,zoom,0); + this->start(); + cancel=false; + progressForm->show(); + connect(this,SIGNAL(percentageChanged(int)),progressForm,SLOT(SetPercentage(int))); + connect(this,SIGNAL(numberOfTilesChanged(int,int)),progressForm,SLOT(SetNumberOfTiles(int,int))); + connect(this,SIGNAL(providerChanged(QString,int)),progressForm,SLOT(SetProvider(QString,int))); + connect(this,SIGNAL(finished()),this,SLOT(finish())); + emit numberOfTilesChanged(0,0); + } + else +#ifdef Q_OS_DARWIN + QMessageBox::information(new QWidget(),"No valid selection","This pre-caches map data.\n\nPlease first select the area of the map to rip with +Left mouse click"); +#else + QMessageBox::information(new QWidget(),"No valid selection","This pre-caches map data.\n\nPlease first select the area of the map to rip with +Left mouse click"); +#endif + } +void MapRipper::finish() +{ + if(zoomProjection()->GetAreaTileList(area,zoom,0); + this->start(); + } + else if(ret==QMessageBox::YesAll) + { + yesToAll=true; + points.clear(); + points=core->Projection()->GetAreaTileList(area,zoom,0); + this->start(); + } + else + { + progressForm->close(); + delete progressForm; + this->deleteLater(); + } + } + else + { + yesToAll=false; + progressForm->close(); + delete progressForm; + this->deleteLater(); + } +} + + + void MapRipper::run() + { + int countOk = 0; + bool goodtile=false; + // Stuff.Shuffle(ref list); + QVector types = OPMaps::Instance()->GetAllLayersOfType(type); + int all=points.count(); + for(int i = 0; i < all; i++) + { + emit numberOfTilesChanged(all,i+1); + if(cancel) + break; + + core::Point p = points[i]; + { + //qDebug()<<"offline fetching:"<GetImageFrom(type, p, zoom); + if(img.length()!=0) + { + goodtile=true; + img=NULL; + } + else + goodtile=false; + } + if(goodtile) + { + countOk++; + } + else + { + i--; + QThread::msleep(1000); + continue; + } + } + emit percentageChanged((int) ((i+1)*100/all));//, i+1); + // worker.ReportProgress((int) ((i+1)*100/all), i+1); + + QThread::msleep(sleep); + } + } + + void MapRipper::stopFetching() + { + QMutexLocker locker(&mutex); + cancel=true; + } +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h index a53c443f5..e6958a1a2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/mapripper.h @@ -1,67 +1,67 @@ -/** -****************************************************************************** -* -* @file mapripper.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A class that allows ripping of a selection of the map -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef MAPRIPPER_H -#define MAPRIPPER_H - -#include -#include "../internals/core.h" -#include "mapripform.h" -#include -#include -namespace mapcontrol -{ - class MapRipper:public QThread - { - Q_OBJECT - public: - MapRipper(internals::Core *,internals::RectLatLng const&); - void run(); - private: - QList points; - int zoom; - core::MapType::Types type; - int sleep; - internals::RectLatLng area; - bool cancel; - MapRipForm * progressForm; - int maxzoom; - internals::Core * core; - bool yesToAll; - QMutex mutex; - - signals: - void percentageChanged(int const& perc); - void numberOfTilesChanged(int const& total,int const& actual); - void providerChanged(QString const& prov,int const& zoom); - - - public slots: - void stopFetching(); - void finish(); - }; -} -#endif // MAPRIPPER_H +/** +****************************************************************************** +* +* @file mapripper.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A class that allows ripping of a selection of the map +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef MAPRIPPER_H +#define MAPRIPPER_H + +#include +#include "../internals/core.h" +#include "mapripform.h" +#include +#include +namespace mapcontrol +{ + class MapRipper:public QThread + { + Q_OBJECT + public: + MapRipper(internals::Core *,internals::RectLatLng const&); + void run(); + private: + QList points; + int zoom; + core::MapType::Types type; + int sleep; + internals::RectLatLng area; + bool cancel; + MapRipForm * progressForm; + int maxzoom; + internals::Core * core; + bool yesToAll; + QMutex mutex; + + signals: + void percentageChanged(int const& perc); + void numberOfTilesChanged(int const& total,int const& actual); + void providerChanged(QString const& prov,int const& zoom); + + + public slots: + void stopFetching(); + void finish(); + }; +} +#endif // MAPRIPPER_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp index ae13de21b..69b2dbbd2 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.cpp @@ -1,61 +1,61 @@ -/** -****************************************************************************** -* -* @file trailitem.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A graphicsItem representing a trail point -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "trailitem.h" -#include -namespace mapcontrol -{ -TrailItem::TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color, MapGraphicItem *map):QGraphicsItem(map),coord(coord),m_brush(color),m_map(map) - { - QDateTime time=QDateTime::currentDateTime(); - QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); - setToolTip(QString(tr("Position:")+"%1\n"+tr("Altitude:")+"%2\n"+tr("Time:")+"%3").arg(coord_str).arg(QString::number(altitude)).arg(time.toString())); - } - - void TrailItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) - { - Q_UNUSED(option); - Q_UNUSED(widget); - - painter->setBrush(m_brush); - painter->drawEllipse(-2,-2,4,4); - } - QRectF TrailItem::boundingRect()const - { - return QRectF(-2,-2,4,4); - } - - - int TrailItem::type()const - { - return Type; - } - - void TrailItem::setPosSLOT() - { - setPos(m_map->FromLatLngToLocal(this->coord).X(),m_map->FromLatLngToLocal(this->coord).Y()); - } -} +/** +****************************************************************************** +* +* @file trailitem.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A graphicsItem representing a trail point +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "trailitem.h" +#include +namespace mapcontrol +{ +TrailItem::TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color, MapGraphicItem *map):QGraphicsItem(map),coord(coord),m_brush(color),m_map(map) + { + QDateTime time=QDateTime::currentDateTime(); + QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); + setToolTip(QString(tr("Position:")+"%1\n"+tr("Altitude:")+"%2\n"+tr("Time:")+"%3").arg(coord_str).arg(QString::number(altitude)).arg(time.toString())); + } + + void TrailItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) + { + Q_UNUSED(option); + Q_UNUSED(widget); + + painter->setBrush(m_brush); + painter->drawEllipse(-2,-2,4,4); + } + QRectF TrailItem::boundingRect()const + { + return QRectF(-2,-2,4,4); + } + + + int TrailItem::type()const + { + return Type; + } + + void TrailItem::setPosSLOT() + { + setPos(m_map->FromLatLngToLocal(this->coord).X(),m_map->FromLatLngToLocal(this->coord).Y()); + } +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h index f926d61fc..bfc58b97d 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/trailitem.h @@ -1,63 +1,63 @@ -/** -****************************************************************************** -* -* @file trailitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A graphicsItem representing a WayPoint -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef TRAILITEM_H -#define TRAILITEM_H - -#include -#include -#include -#include "../internals/pointlatlng.h" -#include -#include "mapgraphicitem.h" - -namespace mapcontrol -{ - - class TrailItem:public QObject,public QGraphicsItem - { - Q_OBJECT - Q_INTERFACES(QGraphicsItem) - public: - enum { Type = UserType + 3 }; - TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color,MapGraphicItem * map); - void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, - QWidget *widget); - QRectF boundingRect() const; - int type() const; - internals::PointLatLng coord; - private: - QBrush m_brush; - MapGraphicItem * m_map; - public slots: - void setPosSLOT(); - signals: - - }; -} -#endif // TRAILITEM_H - - +/** +****************************************************************************** +* +* @file trailitem.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A graphicsItem representing a WayPoint +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef TRAILITEM_H +#define TRAILITEM_H + +#include +#include +#include +#include "../internals/pointlatlng.h" +#include +#include "mapgraphicitem.h" + +namespace mapcontrol +{ + + class TrailItem:public QObject,public QGraphicsItem + { + Q_OBJECT + Q_INTERFACES(QGraphicsItem) + public: + enum { Type = UserType + 3 }; + TrailItem(internals::PointLatLng const& coord,int const& altitude, QBrush color,MapGraphicItem * map); + void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, + QWidget *widget); + QRectF boundingRect() const; + int type() const; + internals::PointLatLng coord; + private: + QBrush m_brush; + MapGraphicItem * m_map; + public slots: + void setPosSLOT(); + signals: + + }; +} +#endif // TRAILITEM_H + + diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp index 4550613db..7ad63109e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.cpp @@ -1,48 +1,48 @@ -/** -****************************************************************************** -* -* @file trailitem.cpp -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A graphicsItem representing a trail point -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#include "traillineitem.h" - -namespace mapcontrol -{ -TrailLineItem::TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color, MapGraphicItem * map):QGraphicsLineItem(map),coord1(coord1),coord2(coord2),m_brush(color),m_map(map) - { - QPen pen; - pen.setBrush(m_brush); - pen.setWidth(1); - this->setPen(pen); - } - - int TrailLineItem::type()const - { - return Type; - } - - void TrailLineItem::setLineSlot() - { - setLine(m_map->FromLatLngToLocal(this->coord1).X(),m_map->FromLatLngToLocal(this->coord1).Y(),m_map->FromLatLngToLocal(this->coord2).X(),m_map->FromLatLngToLocal(this->coord2).Y()); - } -} +/** +****************************************************************************** +* +* @file trailitem.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A graphicsItem representing a trail point +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "traillineitem.h" + +namespace mapcontrol +{ +TrailLineItem::TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color, MapGraphicItem * map):QGraphicsLineItem(map),coord1(coord1),coord2(coord2),m_brush(color),m_map(map) + { + QPen pen; + pen.setBrush(m_brush); + pen.setWidth(1); + this->setPen(pen); + } + + int TrailLineItem::type()const + { + return Type; + } + + void TrailLineItem::setLineSlot() + { + setLine(m_map->FromLatLngToLocal(this->coord1).X(),m_map->FromLatLngToLocal(this->coord1).Y(),m_map->FromLatLngToLocal(this->coord2).X(),m_map->FromLatLngToLocal(this->coord2).Y()); + } +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h index 0243907fa..db195108f 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/traillineitem.h @@ -1,60 +1,60 @@ -/** -****************************************************************************** -* -* @file traillineitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A graphicsItem representing a WayPoint -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef TAILLINEITEM_H -#define TAILLINEITEM_H - -#include -#include -#include -#include "../internals/pointlatlng.h" -#include -#include "mapgraphicitem.h" - -namespace mapcontrol -{ - - class TrailLineItem:public QObject,public QGraphicsLineItem - { - Q_OBJECT - Q_INTERFACES(QGraphicsItem) - public: - enum { Type = UserType + 7 }; - TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color,MapGraphicItem * map); - int type() const; - internals::PointLatLng coord1; - internals::PointLatLng coord2; - private: - QBrush m_brush; - MapGraphicItem * m_map; - public slots: - void setLineSlot(); - signals: - - }; -} - -#endif // TAILLINEITEM_H +/** +****************************************************************************** +* +* @file traillineitem.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A graphicsItem representing a WayPoint +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef TAILLINEITEM_H +#define TAILLINEITEM_H + +#include +#include +#include +#include "../internals/pointlatlng.h" +#include +#include "mapgraphicitem.h" + +namespace mapcontrol +{ + + class TrailLineItem:public QObject,public QGraphicsLineItem + { + Q_OBJECT + Q_INTERFACES(QGraphicsItem) + public: + enum { Type = UserType + 7 }; + TrailLineItem(internals::PointLatLng const& coord1,internals::PointLatLng const& coord2, QBrush color,MapGraphicItem * map); + int type() const; + internals::PointLatLng coord1; + internals::PointLatLng coord2; + private: + QBrush m_brush; + MapGraphicItem * m_map; + public slots: + void setLineSlot(); + signals: + + }; +} + +#endif // TAILLINEITEM_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavmapfollowtype.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavmapfollowtype.h index 5fca96b68..b4c870e87 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavmapfollowtype.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/uavmapfollowtype.h @@ -1,86 +1,86 @@ -/** -****************************************************************************** -* -* @file uavmapfollowtype.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief An enum representing the various map follow modes -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ - -#ifndef UAVMAPFOLLOWTYPE_H -#define UAVMAPFOLLOWTYPE_H -#include -#include -#include -#include -namespace mapcontrol { - class UAVMapFollowType:public QObject - { - Q_OBJECT - Q_ENUMS(Types) - public: - enum Types - { - /// - /// only centers the map on the UAV - /// - CenterMap, - - /// - /// centers and rotates map on the UAV - /// - CenterAndRotateMap, - - /// - /// map is not connected to UAV position or heading - /// - None - }; - static QString StrByType(Types const& value) - { - QMetaObject metaObject = UAVMapFollowType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - QString s=metaEnum.valueToKey(value); - return s; - } - static Types TypeByStr(QString const& value) - { - QMetaObject metaObject = UAVMapFollowType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - Types s=(Types)metaEnum.keyToValue(value.toLatin1()); - return s; - } - static QStringList TypesList() - { - QStringList ret; - QMetaObject metaObject = UAVMapFollowType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - for(int x=0;x +#include +#include +#include +namespace mapcontrol { + class UAVMapFollowType:public QObject + { + Q_OBJECT + Q_ENUMS(Types) + public: + enum Types + { + /// + /// only centers the map on the UAV + /// + CenterMap, + + /// + /// centers and rotates map on the UAV + /// + CenterAndRotateMap, + + /// + /// map is not connected to UAV position or heading + /// + None + }; + static QString StrByType(Types const& value) + { + QMetaObject metaObject = UAVMapFollowType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + QString s=metaEnum.valueToKey(value); + return s; + } + static Types TypeByStr(QString const& value) + { + QMetaObject metaObject = UAVMapFollowType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + Types s=(Types)metaEnum.keyToValue(value.toLatin1()); + return s; + } + static QStringList TypesList() + { + QStringList ret; + QMetaObject metaObject = UAVMapFollowType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + for(int x=0;x -#include -#include -#include -namespace mapcontrol { - class UAVTrailType:public QObject - { - Q_OBJECT - Q_ENUMS(Types) - public: - enum Types - { - /** - * @brief UAV does not plot a trail - * - * @var NoTrail - */ - NoTrail, - /** - * @brief UAV plots a trail point every 'x' seconds - * - * @var ByTimeElapsed - */ - ByTimeElapsed, - /** - * @brief UAV plots a trail point every 'x' meters (ground distance) - * - * @var ByDistance - */ - ByDistance - }; - static QString StrByType(Types const& value) - { - QMetaObject metaObject = UAVTrailType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - QString s=metaEnum.valueToKey(value); - return s; - } - static Types TypeByStr(QString const& value) - { - QMetaObject metaObject = UAVTrailType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - Types s=(Types)metaEnum.keyToValue(value.toLatin1()); - return s; - } - static QStringList TypesList() - { - QStringList ret; - QMetaObject metaObject = UAVTrailType().staticMetaObject; - QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); - for(int x=0;x +#include +#include +#include +namespace mapcontrol { + class UAVTrailType:public QObject + { + Q_OBJECT + Q_ENUMS(Types) + public: + enum Types + { + /** + * @brief UAV does not plot a trail + * + * @var NoTrail + */ + NoTrail, + /** + * @brief UAV plots a trail point every 'x' seconds + * + * @var ByTimeElapsed + */ + ByTimeElapsed, + /** + * @brief UAV plots a trail point every 'x' meters (ground distance) + * + * @var ByDistance + */ + ByDistance + }; + static QString StrByType(Types const& value) + { + QMetaObject metaObject = UAVTrailType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + QString s=metaEnum.valueToKey(value); + return s; + } + static Types TypeByStr(QString const& value) + { + QMetaObject metaObject = UAVTrailType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + Types s=(Types)metaEnum.keyToValue(value.toLatin1()); + return s; + } + static QStringList TypesList() + { + QStringList ret; + QMetaObject metaObject = UAVTrailType().staticMetaObject; + QMetaEnum metaEnum= metaObject.enumerator( metaObject.indexOfEnumerator("Types")); + for(int x=0;xsetFlag(QGraphicsItem::ItemIsMovable,true); - this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); - this->setFlag(QGraphicsItem::ItemIsSelectable,true); - SetShowNumber(shownumber); - RefreshToolTip(); - RefreshPos(); - myHome=NULL; - QList list=map->childItems(); - foreach(QGraphicsItem * obj,list) - { - HomeItem* h=qgraphicsitem_cast (obj); - if(h) - myHome=h; - } - - if(myHome) - { - map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - relativeCoord.altitudeRelative=Altitude()-myHome->Altitude(); - connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); - } - connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); - emit manualCoordChange(this); - connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); - connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); -} - -WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(false),description(""),shownumber(true),isDragging(false),altitude(0),map(map) -{ - relativeCoord.bearing=0; - relativeCoord.distance=0; - relativeCoord.altitudeRelative=0; - myType=relative; - if(magicwaypoint) - { - isMagic=true; - picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); - number=-1; - } - else - { - isMagic=false; - number=WayPointItem::snumber; - ++WayPointItem::snumber; - } - text=0; - numberI=0; - this->setFlag(QGraphicsItem::ItemIsMovable,true); - this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); - this->setFlag(QGraphicsItem::ItemIsSelectable,true); - SetShowNumber(shownumber); - RefreshToolTip(); - RefreshPos(); - myHome=NULL; - QList list=map->childItems(); - foreach(QGraphicsItem * obj,list) - { - HomeItem* h=qgraphicsitem_cast (obj); - if(h) - myHome=h; - } - - if(myHome) - { - coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); - SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); - connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); - } - connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); - emit manualCoordChange(this); - connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); - connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); -} - WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, const QString &description, MapGraphicItem *map,wptype type):coord(coord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map),myType(type) - { - text=0; - numberI=0; - isMagic=false; - picture.load(QString::fromUtf8(":/markers/images/marker.png")); - number=WayPointItem::snumber; - ++WayPointItem::snumber; - this->setFlag(QGraphicsItem::ItemIsMovable,true); - this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); - this->setFlag(QGraphicsItem::ItemIsSelectable,true); - SetShowNumber(shownumber); - RefreshToolTip(); - RefreshPos(); - myHome=NULL; - QList list=map->childItems(); - foreach(QGraphicsItem * obj,list) - { - HomeItem* h=qgraphicsitem_cast (obj); - if(h) - myHome=h; - } - if(myHome) - { - map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - relativeCoord.altitudeRelative=Altitude()-myHome->Altitude(); - connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); - } - connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); - emit manualCoordChange(this); - connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); - connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); - } - - WayPointItem::WayPointItem(const distBearingAltitude &relativeCoordenate, const QString &description, MapGraphicItem *map):relativeCoord(relativeCoordenate),reached(false),description(description),shownumber(true),isDragging(false),map(map) - { - myHome=NULL; - QList list=map->childItems(); - foreach(QGraphicsItem * obj,list) - { - HomeItem* h=qgraphicsitem_cast (obj); - if(h) - myHome=h; - } - if(myHome) - { - connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); - coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); - SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); - } - myType=relative; - text=0; - numberI=0; - isMagic=false; - picture.load(QString::fromUtf8(":/markers/images/marker.png")); - number=WayPointItem::snumber; - ++WayPointItem::snumber; - this->setFlag(QGraphicsItem::ItemIsMovable,true); - this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); - this->setFlag(QGraphicsItem::ItemIsSelectable,true); - SetShowNumber(shownumber); - RefreshToolTip(); - RefreshPos(); - connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); - emit manualCoordChange(this); - connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); - connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); - } - - void WayPointItem::setWPType(wptype type) - { - myType=type; - emit WPValuesChanged(this); - RefreshPos(); - RefreshToolTip(); - this->update(); - } - - QRectF WayPointItem::boundingRect() const - { - return QRectF(-picture.width()/2,-picture.height(),picture.width(),picture.height()); - } - void WayPointItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) - { - Q_UNUSED(option); - Q_UNUSED(widget); - painter->drawPixmap(-picture.width()/2,-picture.height(),picture); - painter->setPen(Qt::green); - if(this->isSelected()) - painter->drawRect(QRectF(-picture.width()/2,-picture.height(),picture.width()-1,picture.height()-1)); - } - void WayPointItem::mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event) - { - if(event->button()==Qt::LeftButton) - { - emit waypointdoubleclick(this); - } - } - - void WayPointItem::mousePressEvent(QGraphicsSceneMouseEvent *event) - { - if(event->button()==Qt::LeftButton) - { - text=new QGraphicsSimpleTextItem(this); - textBG=new QGraphicsRectItem(this); - - textBG->setBrush(Qt::yellow); - - text->setPen(QPen(Qt::red)); - text->setPos(10,-picture.height()); - textBG->setPos(10,-picture.height()); - text->setZValue(3); - RefreshToolTip(); - isDragging=true; - } - QGraphicsItem::mousePressEvent(event); - } - void WayPointItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) - { - if(event->button()==Qt::LeftButton) - { - if(text) - { - delete text; - text=NULL; - } - if(textBG) - { - delete textBG; - textBG=NULL; - } - - isDragging=false; - RefreshToolTip(); - emit manualCoordChange(this); - emit localPositionChanged(this->pos(),this); - emit WPValuesChanged(this); - } - QGraphicsItem::mouseReleaseEvent(event); - } - void WayPointItem::mouseMoveEvent(QGraphicsSceneMouseEvent *event) - { - - if(isDragging) - { - coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); - QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); - if(myHome) - { - map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - } - QString relativeCoord_str = QString::number(relativeCoord.distance) + "m " + QString::number(relativeCoord.bearing*180/M_PI)+"deg"; - text->setText(coord_str+"\n"+relativeCoord_str); - textBG->setRect(text->boundingRect()); - emit localPositionChanged(this->pos(),this); - emit WPValuesChanged(this); - } - QGraphicsItem::mouseMoveEvent(event); - } - void WayPointItem::SetAltitude(const float &value) - { - if(altitude==value) - return; - altitude=value; - if(myHome) - { - relativeCoord.altitudeRelative=altitude-myHome->Altitude(); - } - RefreshToolTip(); - emit WPValuesChanged(this); - this->update(); - } - - void WayPointItem::setRelativeCoord(distBearingAltitude value) - { - if(qAbs(value.distance-relativeCoord.distance)<0.1 - && qAbs(value.bearing-relativeCoord.bearing)<0.01 && value.altitudeRelative==relativeCoord.altitudeRelative) - return; - relativeCoord=value; - if(myHome) - { - SetCoord(map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing)); - SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); - } - RefreshPos(); - RefreshToolTip(); - emit WPValuesChanged(this); - this->update(); - } - - void WayPointItem::SetCoord(const internals::PointLatLng &value) - { - qDebug()<<"1 SetCoord("<Projection()->offSetFromLatLngs(myHome->Coord(),Coord(),back.distance,back.bearing); - if(qAbs(back.bearing-relativeCoord.bearing)>0.01 || qAbs(back.distance-relativeCoord.distance)>0.1) - { - qDebug()<<"4 setCoord-relative coordinates where also updated"; - relativeCoord=back; - } - emit WPValuesChanged(this); - RefreshPos(); - RefreshToolTip(); - this->update(); - qDebug()<<"5 setCoord EXIT"; - } - void WayPointItem::SetDescription(const QString &value) - { - if(description==value) - return; - description=value; - RefreshToolTip(); - emit WPValuesChanged(this); - this->update(); - } - void WayPointItem::SetNumber(const int &value) - { - int oldnumber=number; - number=value; - RefreshToolTip(); - numberI->setText(QString::number(numberAdjusted())); - numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); - this->update(); - emit WPNumberChanged(oldnumber,value,this); - } - void WayPointItem::SetReached(const bool &value) - { - reached=value; - emit WPValuesChanged(this); - if(value) - picture.load(QString::fromUtf8(":/markers/images/bigMarkerGreen.png")); - else - { - if(!isMagic) - { - if(this->flags() & QGraphicsItem::ItemIsMovable==QGraphicsItem::ItemIsMovable) - picture.load(QString::fromUtf8(":/markers/images/marker.png")); - else - picture.load(QString::fromUtf8(":/markers/images/waypoint_marker2.png")); - } - else - { - picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); - } - } - this->update(); - - } - void WayPointItem::SetShowNumber(const bool &value) - { - shownumber=value; - if((numberI==0) && value) - { - numberI=new QGraphicsSimpleTextItem(this); - numberIBG=new QGraphicsRectItem(this); - numberIBG->setBrush(Qt::white); - numberIBG->setOpacity(0.5); - numberI->setZValue(3); - numberI->setPen(QPen(Qt::blue)); - numberI->setPos(0,-13-picture.height()); - numberIBG->setPos(0,-13-picture.height()); - numberI->setText(QString::number(numberAdjusted())); - numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); - } - else if (!value && numberI) - { - delete numberI; - delete numberIBG; - } - this->update(); - } - void WayPointItem::WPDeleted(const int &onumber,WayPointItem *waypoint) - { - Q_UNUSED(waypoint); - int n=number; - if(number>onumber) SetNumber(--n); - } - void WayPointItem::WPInserted(const int &onumber, WayPointItem *waypoint) - { - if(Number()==-1) - return; - - if(waypoint!=this) - { - if(onumber<=number) SetNumber(++number); - } - } - - void WayPointItem::onHomePositionChanged(internals::PointLatLng homepos, float homeAltitude) - { - if(myType==relative) - { - coord=map->Projection()->translate(homepos,relativeCoord.distance,relativeCoord.bearing); - SetAltitude(relativeCoord.altitudeRelative+homeAltitude); - emit WPValuesChanged(this); - RefreshPos(); - RefreshToolTip(); - this->update(); - } - else - { - if(myHome) - { - map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); - relativeCoord.altitudeRelative=Altitude()-homeAltitude; - } - emit WPValuesChanged(this); - } - } - - void WayPointItem::WPRenumbered(const int &oldnumber, const int &newnumber, WayPointItem *waypoint) - { - if (waypoint!=this) - { - if(((oldnumber>number) && (newnumber<=number))) - { - SetNumber(++number); - } - else if (((oldnumbernumber))) - { - SetNumber(--number); - } - else if (newnumber==number) - { - SetNumber(++number); - } - } - } - int WayPointItem::type() const - { - // Enable the use of qgraphicsitem_cast with this item. - return Type; - } - - WayPointItem::~WayPointItem() - { - emit aboutToBeDeleted(this); - --WayPointItem::snumber; - } - void WayPointItem::RefreshPos() - { - core::Point point=map->FromLatLngToLocal(coord); - this->setPos(point.X(),point.Y()); - emit localPositionChanged(this->pos(),this); - } - - void WayPointItem::setOpacitySlot(qreal opacity) - { - setOpacity(opacity); - } - void WayPointItem::RefreshToolTip() - { - QString type_str; - if(myType==relative) - type_str="Relative"; - else - type_str="Absolute"; - QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); - QString relativeCoord_str = " Distance:" + QString::number(relativeCoord.distance) + " Bearing:" + QString::number(relativeCoord.bearing*180/M_PI); - QString relativeAltitude_str=QString::number(relativeCoord.altitudeRelative); - if(Number()!=-1) - setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nRelative altitude:%6\nAltitude:%7\nType:%8\n%9").arg(QString::number(numberAdjusted())).arg(description).arg(coord_str).arg(relativeCoord_str).arg(relativeAltitude_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); - else - setToolTip(QString("Magic WayPoint\nCoordinate:%1\nFrom Home:%2\nAltitude:%3\nType:%4\n%5").arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); - } - - void WayPointItem::setFlag(QGraphicsItem::GraphicsItemFlag flag, bool enabled) - { - if(isMagic) - { - QGraphicsItem::setFlag(flag,enabled); - return; - } - else if(flag==QGraphicsItem::ItemIsMovable) - { - if(enabled) - picture.load(QString::fromUtf8(":/markers/images/marker.png")); - else - picture.load(QString::fromUtf8(":/markers/images/waypoint_marker2.png")); - } - QGraphicsItem::setFlag(flag,enabled); - } - - int WayPointItem::snumber=0; -} +/** +****************************************************************************** +* +* @file waypointitem.cpp +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A graphicsItem representing a WayPoint +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#include "waypointitem.h" +#include "homeitem.h" + +namespace mapcontrol +{ +WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, MapGraphicItem *map,wptype type):coord(coord),reached(false),description(""),shownumber(true),isDragging(false),altitude(altitude),map(map),myType(type) + { + text=0; + numberI=0; + isMagic=false; + picture.load(QString::fromUtf8(":/markers/images/marker.png")); + number=WayPointItem::snumber; + ++WayPointItem::snumber; + this->setFlag(QGraphicsItem::ItemIsMovable,true); + this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); + this->setFlag(QGraphicsItem::ItemIsSelectable,true); + SetShowNumber(shownumber); + RefreshToolTip(); + RefreshPos(); + myHome=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) + { + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + myHome=h; + } + + if(myHome) + { + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); + relativeCoord.altitudeRelative=Altitude()-myHome->Altitude(); + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); + } + connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); + emit manualCoordChange(this); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); +} + +WayPointItem::WayPointItem(MapGraphicItem *map, bool magicwaypoint):reached(false),description(""),shownumber(true),isDragging(false),altitude(0),map(map) +{ + relativeCoord.bearing=0; + relativeCoord.distance=0; + relativeCoord.altitudeRelative=0; + myType=relative; + if(magicwaypoint) + { + isMagic=true; + picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); + number=-1; + } + else + { + isMagic=false; + number=WayPointItem::snumber; + ++WayPointItem::snumber; + } + text=0; + numberI=0; + this->setFlag(QGraphicsItem::ItemIsMovable,true); + this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); + this->setFlag(QGraphicsItem::ItemIsSelectable,true); + SetShowNumber(shownumber); + RefreshToolTip(); + RefreshPos(); + myHome=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) + { + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + myHome=h; + } + + if(myHome) + { + coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); + SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); + } + connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); + emit manualCoordChange(this); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); +} + WayPointItem::WayPointItem(const internals::PointLatLng &coord,int const& altitude, const QString &description, MapGraphicItem *map,wptype type):coord(coord),reached(false),description(description),shownumber(true),isDragging(false),altitude(altitude),map(map),myType(type) + { + text=0; + numberI=0; + isMagic=false; + picture.load(QString::fromUtf8(":/markers/images/marker.png")); + number=WayPointItem::snumber; + ++WayPointItem::snumber; + this->setFlag(QGraphicsItem::ItemIsMovable,true); + this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); + this->setFlag(QGraphicsItem::ItemIsSelectable,true); + SetShowNumber(shownumber); + RefreshToolTip(); + RefreshPos(); + myHome=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) + { + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + myHome=h; + } + if(myHome) + { + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); + relativeCoord.altitudeRelative=Altitude()-myHome->Altitude(); + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); + } + connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); + emit manualCoordChange(this); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); + } + + WayPointItem::WayPointItem(const distBearingAltitude &relativeCoordenate, const QString &description, MapGraphicItem *map):relativeCoord(relativeCoordenate),reached(false),description(description),shownumber(true),isDragging(false),map(map) + { + myHome=NULL; + QList list=map->childItems(); + foreach(QGraphicsItem * obj,list) + { + HomeItem* h=qgraphicsitem_cast (obj); + if(h) + myHome=h; + } + if(myHome) + { + connect(myHome,SIGNAL(homePositionChanged(internals::PointLatLng,float)),this,SLOT(onHomePositionChanged(internals::PointLatLng,float))); + coord=map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing); + SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); + } + myType=relative; + text=0; + numberI=0; + isMagic=false; + picture.load(QString::fromUtf8(":/markers/images/marker.png")); + number=WayPointItem::snumber; + ++WayPointItem::snumber; + this->setFlag(QGraphicsItem::ItemIsMovable,true); + this->setFlag(QGraphicsItem::ItemIgnoresTransformations,true); + this->setFlag(QGraphicsItem::ItemIsSelectable,true); + SetShowNumber(shownumber); + RefreshToolTip(); + RefreshPos(); + connect(this,SIGNAL(waypointdoubleclick(WayPointItem*)),map,SIGNAL(wpdoubleclicked(WayPointItem*))); + emit manualCoordChange(this); + connect(map,SIGNAL(childRefreshPosition()),this,SLOT(RefreshPos())); + connect(map,SIGNAL(childSetOpacity(qreal)),this,SLOT(setOpacitySlot(qreal))); + } + + void WayPointItem::setWPType(wptype type) + { + myType=type; + emit WPValuesChanged(this); + RefreshPos(); + RefreshToolTip(); + this->update(); + } + + QRectF WayPointItem::boundingRect() const + { + return QRectF(-picture.width()/2,-picture.height(),picture.width(),picture.height()); + } + void WayPointItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) + { + Q_UNUSED(option); + Q_UNUSED(widget); + painter->drawPixmap(-picture.width()/2,-picture.height(),picture); + painter->setPen(Qt::green); + if(this->isSelected()) + painter->drawRect(QRectF(-picture.width()/2,-picture.height(),picture.width()-1,picture.height()-1)); + } + void WayPointItem::mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event) + { + if(event->button()==Qt::LeftButton) + { + emit waypointdoubleclick(this); + } + } + + void WayPointItem::mousePressEvent(QGraphicsSceneMouseEvent *event) + { + if(event->button()==Qt::LeftButton) + { + text=new QGraphicsSimpleTextItem(this); + textBG=new QGraphicsRectItem(this); + + textBG->setBrush(Qt::yellow); + + text->setPen(QPen(Qt::red)); + text->setPos(10,-picture.height()); + textBG->setPos(10,-picture.height()); + text->setZValue(3); + RefreshToolTip(); + isDragging=true; + } + QGraphicsItem::mousePressEvent(event); + } + void WayPointItem::mouseReleaseEvent(QGraphicsSceneMouseEvent *event) + { + if(event->button()==Qt::LeftButton) + { + if(text) + { + delete text; + text=NULL; + } + if(textBG) + { + delete textBG; + textBG=NULL; + } + + isDragging=false; + RefreshToolTip(); + emit manualCoordChange(this); + emit localPositionChanged(this->pos(),this); + emit WPValuesChanged(this); + } + QGraphicsItem::mouseReleaseEvent(event); + } + void WayPointItem::mouseMoveEvent(QGraphicsSceneMouseEvent *event) + { + + if(isDragging) + { + coord=map->FromLocalToLatLng(this->pos().x(),this->pos().y()); + QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); + if(myHome) + { + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); + } + QString relativeCoord_str = QString::number(relativeCoord.distance) + "m " + QString::number(relativeCoord.bearing*180/M_PI)+"deg"; + text->setText(coord_str+"\n"+relativeCoord_str); + textBG->setRect(text->boundingRect()); + emit localPositionChanged(this->pos(),this); + emit WPValuesChanged(this); + } + QGraphicsItem::mouseMoveEvent(event); + } + void WayPointItem::SetAltitude(const float &value) + { + if(altitude==value) + return; + altitude=value; + if(myHome) + { + relativeCoord.altitudeRelative=altitude-myHome->Altitude(); + } + RefreshToolTip(); + emit WPValuesChanged(this); + this->update(); + } + + void WayPointItem::setRelativeCoord(distBearingAltitude value) + { + if(qAbs(value.distance-relativeCoord.distance)<0.1 + && qAbs(value.bearing-relativeCoord.bearing)<0.01 && value.altitudeRelative==relativeCoord.altitudeRelative) + return; + relativeCoord=value; + if(myHome) + { + SetCoord(map->Projection()->translate(myHome->Coord(),relativeCoord.distance,relativeCoord.bearing)); + SetAltitude(myHome->Altitude()+relativeCoord.altitudeRelative); + } + RefreshPos(); + RefreshToolTip(); + emit WPValuesChanged(this); + this->update(); + } + + void WayPointItem::SetCoord(const internals::PointLatLng &value) + { + qDebug()<<"1 SetCoord("<Projection()->offSetFromLatLngs(myHome->Coord(),Coord(),back.distance,back.bearing); + if(qAbs(back.bearing-relativeCoord.bearing)>0.01 || qAbs(back.distance-relativeCoord.distance)>0.1) + { + qDebug()<<"4 setCoord-relative coordinates where also updated"; + relativeCoord=back; + } + emit WPValuesChanged(this); + RefreshPos(); + RefreshToolTip(); + this->update(); + qDebug()<<"5 setCoord EXIT"; + } + void WayPointItem::SetDescription(const QString &value) + { + if(description==value) + return; + description=value; + RefreshToolTip(); + emit WPValuesChanged(this); + this->update(); + } + void WayPointItem::SetNumber(const int &value) + { + int oldnumber=number; + number=value; + RefreshToolTip(); + numberI->setText(QString::number(numberAdjusted())); + numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); + this->update(); + emit WPNumberChanged(oldnumber,value,this); + } + void WayPointItem::SetReached(const bool &value) + { + reached=value; + emit WPValuesChanged(this); + if(value) + picture.load(QString::fromUtf8(":/markers/images/bigMarkerGreen.png")); + else + { + if(!isMagic) + { + if(this->flags() & QGraphicsItem::ItemIsMovable==QGraphicsItem::ItemIsMovable) + picture.load(QString::fromUtf8(":/markers/images/marker.png")); + else + picture.load(QString::fromUtf8(":/markers/images/waypoint_marker2.png")); + } + else + { + picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); + } + } + this->update(); + + } + void WayPointItem::SetShowNumber(const bool &value) + { + shownumber=value; + if((numberI==0) && value) + { + numberI=new QGraphicsSimpleTextItem(this); + numberIBG=new QGraphicsRectItem(this); + numberIBG->setBrush(Qt::white); + numberIBG->setOpacity(0.5); + numberI->setZValue(3); + numberI->setPen(QPen(Qt::blue)); + numberI->setPos(0,-13-picture.height()); + numberIBG->setPos(0,-13-picture.height()); + numberI->setText(QString::number(numberAdjusted())); + numberIBG->setRect(numberI->boundingRect().adjusted(-2,0,1,0)); + } + else if (!value && numberI) + { + delete numberI; + delete numberIBG; + } + this->update(); + } + void WayPointItem::WPDeleted(const int &onumber,WayPointItem *waypoint) + { + Q_UNUSED(waypoint); + int n=number; + if(number>onumber) SetNumber(--n); + } + void WayPointItem::WPInserted(const int &onumber, WayPointItem *waypoint) + { + if(Number()==-1) + return; + + if(waypoint!=this) + { + if(onumber<=number) SetNumber(++number); + } + } + + void WayPointItem::onHomePositionChanged(internals::PointLatLng homepos, float homeAltitude) + { + if(myType==relative) + { + coord=map->Projection()->translate(homepos,relativeCoord.distance,relativeCoord.bearing); + SetAltitude(relativeCoord.altitudeRelative+homeAltitude); + emit WPValuesChanged(this); + RefreshPos(); + RefreshToolTip(); + this->update(); + } + else + { + if(myHome) + { + map->Projection()->offSetFromLatLngs(myHome->Coord(),coord,relativeCoord.distance,relativeCoord.bearing); + relativeCoord.altitudeRelative=Altitude()-homeAltitude; + } + emit WPValuesChanged(this); + } + } + + void WayPointItem::WPRenumbered(const int &oldnumber, const int &newnumber, WayPointItem *waypoint) + { + if (waypoint!=this) + { + if(((oldnumber>number) && (newnumber<=number))) + { + SetNumber(++number); + } + else if (((oldnumbernumber))) + { + SetNumber(--number); + } + else if (newnumber==number) + { + SetNumber(++number); + } + } + } + int WayPointItem::type() const + { + // Enable the use of qgraphicsitem_cast with this item. + return Type; + } + + WayPointItem::~WayPointItem() + { + emit aboutToBeDeleted(this); + --WayPointItem::snumber; + } + void WayPointItem::RefreshPos() + { + core::Point point=map->FromLatLngToLocal(coord); + this->setPos(point.X(),point.Y()); + emit localPositionChanged(this->pos(),this); + } + + void WayPointItem::setOpacitySlot(qreal opacity) + { + setOpacity(opacity); + } + void WayPointItem::RefreshToolTip() + { + QString type_str; + if(myType==relative) + type_str="Relative"; + else + type_str="Absolute"; + QString coord_str = " " + QString::number(coord.Lat(), 'f', 6) + " " + QString::number(coord.Lng(), 'f', 6); + QString relativeCoord_str = " Distance:" + QString::number(relativeCoord.distance) + " Bearing:" + QString::number(relativeCoord.bearing*180/M_PI); + QString relativeAltitude_str=QString::number(relativeCoord.altitudeRelative); + if(Number()!=-1) + setToolTip(QString("WayPoint Number:%1\nDescription:%2\nCoordinate:%4\nFrom Home:%5\nRelative altitude:%6\nAltitude:%7\nType:%8\n%9").arg(QString::number(numberAdjusted())).arg(description).arg(coord_str).arg(relativeCoord_str).arg(relativeAltitude_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); + else + setToolTip(QString("Magic WayPoint\nCoordinate:%1\nFrom Home:%2\nAltitude:%3\nType:%4\n%5").arg(coord_str).arg(relativeCoord_str).arg(QString::number(altitude)).arg(type_str).arg(myCustomString)); + } + + void WayPointItem::setFlag(QGraphicsItem::GraphicsItemFlag flag, bool enabled) + { + if(isMagic) + { + QGraphicsItem::setFlag(flag,enabled); + return; + } + else if(flag==QGraphicsItem::ItemIsMovable) + { + if(enabled) + picture.load(QString::fromUtf8(":/markers/images/marker.png")); + else + picture.load(QString::fromUtf8(":/markers/images/waypoint_marker2.png")); + } + QGraphicsItem::setFlag(flag,enabled); + } + + int WayPointItem::snumber=0; +} diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h index cf4f87799..d974a78fc 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/mapwidget/waypointitem.h @@ -1,244 +1,244 @@ -/** -****************************************************************************** -* -* @file waypointitem.h -* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief A graphicsItem representing a WayPoint -* @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget -* @{ -* -*****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or -* (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -* for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., -* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -*/ -#ifndef WAYPOINTITEM_H -#define WAYPOINTITEM_H - -#include -#include -#include -#include "../internals/pointlatlng.h" -#include "mapgraphicitem.h" -#include -#include - -namespace mapcontrol -{ -struct distBearingAltitude -{ - double distance; - double bearing; - float altitudeRelative; - double bearingToDegrees(){return bearing*180/M_PI;} - void setBearingFromDegrees(double degrees){bearing=degrees*M_PI/180;} -}; -class HomeItem; -/** -* @brief A QGraphicsItem representing a WayPoint -* -* @class WayPointItem waypointitem.h "waypointitem.h" -*/ -class WayPointItem:public QObject,public QGraphicsItem -{ - Q_OBJECT - Q_INTERFACES(QGraphicsItem) -public: - enum { Type = UserType + 1 }; - enum wptype {absolute,relative}; - /** - * @brief Constructer - * - * @param coord coordinates in LatLng of the Waypoint - * @param altitude altitude of the WayPoint - * @param map pointer to map to use - * @return - */ - WayPointItem(internals::PointLatLng const& coord,int const& altitude,MapGraphicItem* map,wptype type=absolute); - WayPointItem(MapGraphicItem* map,bool magicwaypoint); - /** - * @brief Constructer - * - * @param coord coordinates in LatLng of the WayPoint - * @param altitude altitude of the WayPoint - * @param description description fo the WayPoint - * @param map pointer to map to use - * @return - */ - WayPointItem(internals::PointLatLng const& coord,int const& altitude,QString const& description,MapGraphicItem* map,wptype type=absolute); - WayPointItem(distBearingAltitude const& relativeCoord,QString const& description,MapGraphicItem* map); - - /** - * @brief Returns the WayPoint description - * - * @return QString - */ - QString Description(){return description;} - /** - * @brief Sets the WayPoint description - * - * @param value - */ - void SetDescription(QString const& value); - /** - * @brief Returns true if WayPoint is Reached - * - * @return bool - */ - bool Reached(){return reached;} - /** - * @brief Sets if WayPoint is Reached - * - * @param value - */ - void SetReached(bool const& value); - /** - * @brief Returns the WayPoint number - * - */ - int Number(){return number;} - int numberAdjusted(){return number+1;} - /** - * @brief Sets WayPoint number - * - * @param value - */ - void SetNumber(int const& value); - /** - * @brief Returns WayPoint LatLng coordinate - * - */ - internals::PointLatLng Coord(){return coord;} - /** - * @brief Sets WayPoint LatLng coordinate - * - * @param value - */ - void SetCoord(internals::PointLatLng const& value); - /** - * @brief Used if WayPoint number is to be drawn on screen - * - */ - bool ShowNumber(){return shownumber;} - /** - * @brief Used to set if WayPoint number is to be drawn on screen - * - * @param value - */ - void SetShowNumber(bool const& value); - /** - * @brief Returns the WayPoint altitude - * - * @return int - */ - float Altitude(){return altitude;} - /** - * @brief Sets the WayPoint Altitude - * - * @param value - */ - void SetAltitude(const float &value); - void setRelativeCoord(distBearingAltitude value); - distBearingAltitude getRelativeCoord(){return relativeCoord;} - int type() const; - QRectF boundingRect() const; - void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, - QWidget *widget); - void RefreshToolTip(); - QPixmap picture; - QString customString(){return myCustomString;} - void setCustomString(QString arg){myCustomString=arg;} - void setFlag(GraphicsItemFlag flag, bool enabled); -~WayPointItem(); - - static int snumber; - void setWPType(wptype type); - wptype WPType(){return myType;} -protected: - void mouseMoveEvent ( QGraphicsSceneMouseEvent * event ); - void mousePressEvent ( QGraphicsSceneMouseEvent * event ); - void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event ); - void mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event); -private: - internals::PointLatLng coord;//coordinates of this WayPoint - distBearingAltitude relativeCoord; - bool reached; - QString description; - bool shownumber; - bool isDragging; - float altitude; - MapGraphicItem* map; - int number; - bool isMagic; - - QGraphicsSimpleTextItem* text; - QGraphicsRectItem* textBG; - QGraphicsSimpleTextItem* numberI; - QGraphicsRectItem* numberIBG; - QTransform transf; - HomeItem * myHome; - wptype myType; - QString myCustomString; - -public slots: - /** - * @brief Called when a WayPoint is deleted - * - * @param number number of the WayPoint that was deleted - */ - void WPDeleted(int const& number,WayPointItem *waypoint); - /** - * @brief Called when a WayPoint is renumbered - * - * @param oldnumber the old WayPoint number - * @param newnumber the new WayPoint number - * @param waypoint a pointer to the WayPoint renumbered - */ - void WPRenumbered(int const& oldnumber,int const& newnumber,WayPointItem* waypoint); - /** - * @brief Called when a WayPoint is inserted - * - * @param number the number of the WayPoint - * @param waypoint a pointer to the WayPoint inserted - */ - void WPInserted(int const& number,WayPointItem* waypoint); - - void onHomePositionChanged(internals::PointLatLng,float altitude); - void RefreshPos(); - void setOpacitySlot(qreal opacity); -signals: - /** - * @brief fires when this WayPoint number changes (not fired if due to a auto-renumbering) - * - * @param oldnumber this WayPoint old number - * @param newnumber this WayPoint new number - * @param waypoint a pointer to this WayPoint - */ - void WPNumberChanged(int const& oldnumber,int const& newnumber,WayPointItem* waypoint); - - /** - * @brief Fired when the description, altitude or coordinates change - * - * @param waypoint a pointer to this WayPoint - */ - - void WPValuesChanged(WayPointItem* waypoint); - void waypointdoubleclick(WayPointItem* waypoint); - void localPositionChanged(QPointF point,WayPointItem* waypoint); - void manualCoordChange(WayPointItem *); - void aboutToBeDeleted(WayPointItem *); -}; -} -#endif // WAYPOINTITEM_H +/** +****************************************************************************** +* +* @file waypointitem.h +* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. +* @brief A graphicsItem representing a WayPoint +* @see The GNU Public License (GPL) Version 3 +* @defgroup OPMapWidget +* @{ +* +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ +#ifndef WAYPOINTITEM_H +#define WAYPOINTITEM_H + +#include +#include +#include +#include "../internals/pointlatlng.h" +#include "mapgraphicitem.h" +#include +#include + +namespace mapcontrol +{ +struct distBearingAltitude +{ + double distance; + double bearing; + float altitudeRelative; + double bearingToDegrees(){return bearing*180/M_PI;} + void setBearingFromDegrees(double degrees){bearing=degrees*M_PI/180;} +}; +class HomeItem; +/** +* @brief A QGraphicsItem representing a WayPoint +* +* @class WayPointItem waypointitem.h "waypointitem.h" +*/ +class WayPointItem:public QObject,public QGraphicsItem +{ + Q_OBJECT + Q_INTERFACES(QGraphicsItem) +public: + enum { Type = UserType + 1 }; + enum wptype {absolute,relative}; + /** + * @brief Constructer + * + * @param coord coordinates in LatLng of the Waypoint + * @param altitude altitude of the WayPoint + * @param map pointer to map to use + * @return + */ + WayPointItem(internals::PointLatLng const& coord,int const& altitude,MapGraphicItem* map,wptype type=absolute); + WayPointItem(MapGraphicItem* map,bool magicwaypoint); + /** + * @brief Constructer + * + * @param coord coordinates in LatLng of the WayPoint + * @param altitude altitude of the WayPoint + * @param description description fo the WayPoint + * @param map pointer to map to use + * @return + */ + WayPointItem(internals::PointLatLng const& coord,int const& altitude,QString const& description,MapGraphicItem* map,wptype type=absolute); + WayPointItem(distBearingAltitude const& relativeCoord,QString const& description,MapGraphicItem* map); + + /** + * @brief Returns the WayPoint description + * + * @return QString + */ + QString Description(){return description;} + /** + * @brief Sets the WayPoint description + * + * @param value + */ + void SetDescription(QString const& value); + /** + * @brief Returns true if WayPoint is Reached + * + * @return bool + */ + bool Reached(){return reached;} + /** + * @brief Sets if WayPoint is Reached + * + * @param value + */ + void SetReached(bool const& value); + /** + * @brief Returns the WayPoint number + * + */ + int Number(){return number;} + int numberAdjusted(){return number+1;} + /** + * @brief Sets WayPoint number + * + * @param value + */ + void SetNumber(int const& value); + /** + * @brief Returns WayPoint LatLng coordinate + * + */ + internals::PointLatLng Coord(){return coord;} + /** + * @brief Sets WayPoint LatLng coordinate + * + * @param value + */ + void SetCoord(internals::PointLatLng const& value); + /** + * @brief Used if WayPoint number is to be drawn on screen + * + */ + bool ShowNumber(){return shownumber;} + /** + * @brief Used to set if WayPoint number is to be drawn on screen + * + * @param value + */ + void SetShowNumber(bool const& value); + /** + * @brief Returns the WayPoint altitude + * + * @return int + */ + float Altitude(){return altitude;} + /** + * @brief Sets the WayPoint Altitude + * + * @param value + */ + void SetAltitude(const float &value); + void setRelativeCoord(distBearingAltitude value); + distBearingAltitude getRelativeCoord(){return relativeCoord;} + int type() const; + QRectF boundingRect() const; + void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, + QWidget *widget); + void RefreshToolTip(); + QPixmap picture; + QString customString(){return myCustomString;} + void setCustomString(QString arg){myCustomString=arg;} + void setFlag(GraphicsItemFlag flag, bool enabled); +~WayPointItem(); + + static int snumber; + void setWPType(wptype type); + wptype WPType(){return myType;} +protected: + void mouseMoveEvent ( QGraphicsSceneMouseEvent * event ); + void mousePressEvent ( QGraphicsSceneMouseEvent * event ); + void mouseReleaseEvent ( QGraphicsSceneMouseEvent * event ); + void mouseDoubleClickEvent(QGraphicsSceneMouseEvent *event); +private: + internals::PointLatLng coord;//coordinates of this WayPoint + distBearingAltitude relativeCoord; + bool reached; + QString description; + bool shownumber; + bool isDragging; + float altitude; + MapGraphicItem* map; + int number; + bool isMagic; + + QGraphicsSimpleTextItem* text; + QGraphicsRectItem* textBG; + QGraphicsSimpleTextItem* numberI; + QGraphicsRectItem* numberIBG; + QTransform transf; + HomeItem * myHome; + wptype myType; + QString myCustomString; + +public slots: + /** + * @brief Called when a WayPoint is deleted + * + * @param number number of the WayPoint that was deleted + */ + void WPDeleted(int const& number,WayPointItem *waypoint); + /** + * @brief Called when a WayPoint is renumbered + * + * @param oldnumber the old WayPoint number + * @param newnumber the new WayPoint number + * @param waypoint a pointer to the WayPoint renumbered + */ + void WPRenumbered(int const& oldnumber,int const& newnumber,WayPointItem* waypoint); + /** + * @brief Called when a WayPoint is inserted + * + * @param number the number of the WayPoint + * @param waypoint a pointer to the WayPoint inserted + */ + void WPInserted(int const& number,WayPointItem* waypoint); + + void onHomePositionChanged(internals::PointLatLng,float altitude); + void RefreshPos(); + void setOpacitySlot(qreal opacity); +signals: + /** + * @brief fires when this WayPoint number changes (not fired if due to a auto-renumbering) + * + * @param oldnumber this WayPoint old number + * @param newnumber this WayPoint new number + * @param waypoint a pointer to this WayPoint + */ + void WPNumberChanged(int const& oldnumber,int const& newnumber,WayPointItem* waypoint); + + /** + * @brief Fired when the description, altitude or coordinates change + * + * @param waypoint a pointer to this WayPoint + */ + + void WPValuesChanged(WayPointItem* waypoint); + void waypointdoubleclick(WayPointItem* waypoint); + void localPositionChanged(QPointF point,WayPointItem* waypoint); + void manualCoordChange(WayPointItem *); + void aboutToBeDeleted(WayPointItem *); +}; +} +#endif // WAYPOINTITEM_H diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/src.pro b/ground/openpilotgcs/src/libs/opmapcontrol/src/src.pro index b676d74dc..28d447759 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/src.pro +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/src.pro @@ -1,6 +1,6 @@ -TEMPLATE = subdirs -CONFIG += ordered -SUBDIRS = core -SUBDIRS += internals -SUBDIRS += mapwidget -#SUBDIRS +=finaltest +TEMPLATE = subdirs +CONFIG += ordered +SUBDIRS = core +SUBDIRS += internals +SUBDIRS += mapwidget +#SUBDIRS +=finaltest diff --git a/ground/openpilotgcs/src/libs/qextserialport/src/qextserialport_global.h b/ground/openpilotgcs/src/libs/qextserialport/src/qextserialport_global.h index 360eb9c0f..a2e65346b 100644 --- a/ground/openpilotgcs/src/libs/qextserialport/src/qextserialport_global.h +++ b/ground/openpilotgcs/src/libs/qextserialport/src/qextserialport_global.h @@ -1,15 +1,15 @@ - - -#ifndef QEXTSERIALPORT_GLOBAL_H -#define QEXTSERIALPORT_GLOBAL_H - -#include - -#ifdef QEXTSERIALPORT_LIBRARY -# define QEXTSERIALPORT_EXPORT Q_DECL_EXPORT -#else -# define QEXTSERIALPORT_EXPORT Q_DECL_IMPORT -#endif - -#endif // QEXTSERIALPORT_GLOBAL_H - + + +#ifndef QEXTSERIALPORT_GLOBAL_H +#define QEXTSERIALPORT_GLOBAL_H + +#include + +#ifdef QEXTSERIALPORT_LIBRARY +# define QEXTSERIALPORT_EXPORT Q_DECL_EXPORT +#else +# define QEXTSERIALPORT_EXPORT Q_DECL_IMPORT +#endif + +#endif // QEXTSERIALPORT_GLOBAL_H + diff --git a/ground/openpilotgcs/src/libs/qextserialport/src/src.pro b/ground/openpilotgcs/src/libs/qextserialport/src/src.pro index 6d52eaf23..309dcc901 100644 --- a/ground/openpilotgcs/src/libs/qextserialport/src/src.pro +++ b/ground/openpilotgcs/src/libs/qextserialport/src/src.pro @@ -1,28 +1,28 @@ -TEMPLATE = lib -TARGET = QExtSerialPort -DEFINES += QEXTSERIALPORT_LIBRARY -include(../../../openpilotgcslibrary.pri) - -#VERSION = 1.2.0 - -# event driven device enumeration on windows requires the gui module -!win32:QT -= gui - -HEADERS = qextserialport.h \ - qextserialenumerator.h \ - qextserialport_global.h -SOURCES = qextserialport.cpp - -unix:SOURCES += posix_qextserialport.cpp -unix:!macx:SOURCES += qextserialenumerator_unix.cpp -macx { - SOURCES += qextserialenumerator_osx.cpp - LIBS += -framework IOKit -framework CoreFoundation -} - -win32 { - SOURCES += win_qextserialport.cpp qextserialenumerator_win.cpp - DEFINES += WINVER=0x0501 # needed for mingw to pull in appropriate dbt business...probably a better way to do this - LIBS += -lsetupapi -} - +TEMPLATE = lib +TARGET = QExtSerialPort +DEFINES += QEXTSERIALPORT_LIBRARY +include(../../../openpilotgcslibrary.pri) + +#VERSION = 1.2.0 + +# event driven device enumeration on windows requires the gui module +!win32:QT -= gui + +HEADERS = qextserialport.h \ + qextserialenumerator.h \ + qextserialport_global.h +SOURCES = qextserialport.cpp + +unix:SOURCES += posix_qextserialport.cpp +unix:!macx:SOURCES += qextserialenumerator_unix.cpp +macx { + SOURCES += qextserialenumerator_osx.cpp + LIBS += -framework IOKit -framework CoreFoundation +} + +win32 { + SOURCES += win_qextserialport.cpp qextserialenumerator_win.cpp + DEFINES += WINVER=0x0501 # needed for mingw to pull in appropriate dbt business...probably a better way to do this + LIBS += -lsetupapi +} + diff --git a/ground/openpilotgcs/src/libs/qscispinbox/QScienceSpinBox.cpp b/ground/openpilotgcs/src/libs/qscispinbox/QScienceSpinBox.cpp index 10b0db0bc..dda8b3cbb 100644 --- a/ground/openpilotgcs/src/libs/qscispinbox/QScienceSpinBox.cpp +++ b/ground/openpilotgcs/src/libs/qscispinbox/QScienceSpinBox.cpp @@ -1,544 +1,544 @@ -/** - * Code copied from http://www.matthiaspospiech.de/blog/2009/01/03/qt-spinbox-widget-with-scientific-notation/ - */ -#include "QScienceSpinBox.h" - -#include - -//#define QSPINBOX_QSBDEBUG -#ifdef QSPINBOX_QSBDEBUG -# define QSBDEBUG qDebug -#else -# define QSBDEBUG if (false) qDebug -#endif - - -QScienceSpinBox::QScienceSpinBox(QWidget * parent) - : QDoubleSpinBox(parent) -{ - initLocalValues(parent); - setDecimals(8); - QDoubleSpinBox::setDecimals(1000); - - // set Range to maximum possible values - double doubleMax = std::numeric_limits::max(); - setRange(-doubleMax, doubleMax); - - v = new QDoubleValidator(this); - v->setDecimals(1000); // (standard anyway) - v->setNotation(QDoubleValidator::ScientificNotation); - this->lineEdit()->setValidator(v); -} - -void QScienceSpinBox::initLocalValues(QWidget *parent) -{ - const QString str = (parent ? parent->locale() : QLocale()).toString(4567.1); - if (str.size() == 6) { - delimiter = str.at(4); - thousand = QChar((ushort)0); - } else if (str.size() == 7) { - thousand = str.at(1); - delimiter = str.at(5); - } - Q_ASSERT(!delimiter.isNull()); -} - -int QScienceSpinBox::decimals() const -{ - return dispDecimals; -} - -void QScienceSpinBox::setDecimals(int value) -{ - dispDecimals = value; -} - -// overwritten virtual function of QAbstractSpinBox -void QScienceSpinBox::stepBy(int steps) -{ - if (steps < 0) - stepDown(); - else - stepUp(); -} - -void QScienceSpinBox::stepDown() -{ - QSBDEBUG() << "stepDown()"; - setValue(value()/10.0); -} - -void QScienceSpinBox::stepUp() -{ - QSBDEBUG() << "stepUp()"; - setValue(value()*10.0); -} - -/*! - * text to be displayed in spinbox - */ -QString QScienceSpinBox::textFromValue(double value) const -{ - - // convert to string -> Using exponetial display with internal decimals - QString str = locale().toString(value, 'e', dispDecimals); - // remove thousand sign - if (qAbs(value) >= 1000.0) { - str.remove(thousand); - } - return str; -} - -double QScienceSpinBox::valueFromText(const QString &text) const -{ - QString copy = text; - int pos = this->lineEdit()->cursorPosition(); - QValidator::State state = QValidator::Acceptable; - return validateAndInterpret(copy, pos, state).toDouble(); -} - -// this function is never used...? -double QScienceSpinBox::round(double value) const -{ - const QString strDbl = locale().toString(value, 'g', dispDecimals); - return locale().toDouble(strDbl); -} - -// overwritten virtual function of QAbstractSpinBox -QValidator::State QScienceSpinBox::validate(QString &text, int &pos) const -{ - QValidator::State state; - validateAndInterpret(text, pos, state); - return state; -} - -// overwritten virtual function of QAbstractSpinBox -void QScienceSpinBox::fixup(QString &input) const -{ - input.remove(thousand); -} - -// reimplemented function, copied from QDoubleSpinBoxPrivate::isIntermediateValue -bool QScienceSpinBox::isIntermediateValue(const QString &str) const -{ - QSBDEBUG() << "input is" << str << minimum() << maximum(); - qint64 dec = 1; - - for (int i=0; i < decimals(); ++i) - dec *= 10; - - const QLatin1Char dot('.'); - - /*! - * determine minimum possible values on left and right of Decimal-char - */ - // I know QString::number() uses CLocale so I use dot - const QString minstr = QString::number(minimum(), 'f', QDoubleSpinBox::decimals()); - qint64 min_left = minstr.left(minstr.indexOf(dot)).toLongLong(); - qint64 min_right = minstr.mid(minstr.indexOf(dot) + 1).toLongLong(); - - const QString maxstr = QString::number(maximum(), 'f', QDoubleSpinBox::decimals()); - qint64 max_left = maxstr.left(maxstr.indexOf(dot)).toLongLong(); - qint64 max_right = maxstr.mid(maxstr.indexOf(dot) + 1).toLongLong(); - - /*! - * determine left and right long values (left and right of delimiter) - */ - const int dotindex = str.indexOf(delimiter); - const bool negative = maximum() < 0; - qint64 left = 0, right = 0; - bool doleft = true; - bool doright = true; - // no separator -> everthing in left - if (dotindex == -1) { - left = str.toLongLong(); - doright = false; - } - // separator on left or contains '+' - else if (dotindex == 0 || (dotindex == 1 && str.at(0) == QLatin1Char('+'))) { - // '+' at negative max - if (negative) { - QSBDEBUG() << __FILE__ << __LINE__ << "returns false"; - return false; - } - doleft = false; - right = str.mid(dotindex + 1).toLongLong(); - } - // contains '-' - else if (dotindex == 1 && str.at(0) == QLatin1Char('-')) { - // '-' at positiv max - if (!negative) { - QSBDEBUG() << __FILE__ << __LINE__ << "returns false"; - return false; - } - doleft = false; - right = str.mid(dotindex + 1).toLongLong(); - } else { - left = str.left(dotindex).toLongLong(); - if (dotindex == str.size() - 1) { // nothing right of Separator - doright = false; - } else { - right = str.mid(dotindex + 1).toLongLong(); - } - } - // left > 0, with max < 0 and no '-' - if ((left >= 0 && max_left < 0 && !str.startsWith(QLatin1Char('-'))) - // left > 0, with min > 0 - || (left < 0 && min_left >= 0)) - { - QSBDEBUG("returns false"); - return false; - } - - qint64 match = min_left; - if (doleft && !isIntermediateValueHelper(left, min_left, max_left, &match)) { - QSBDEBUG() << __FILE__ << __LINE__ << "returns false"; - return false; - } - if (doright) { - QSBDEBUG("match %lld min_left %lld max_left %lld", match, min_left, max_left); - if (!doleft) { - if (min_left == max_left) { - const bool ret = isIntermediateValueHelper(qAbs(left), - negative ? max_right : min_right, - negative ? min_right : max_right); - QSBDEBUG() << __FILE__ << __LINE__ << "returns" << ret; - return ret; - } else if (qAbs(max_left - min_left) == 1) { - const bool ret = isIntermediateValueHelper(qAbs(left), min_right, negative ? 0 : dec) - || isIntermediateValueHelper(qAbs(left), negative ? dec : 0, max_right); - QSBDEBUG() << __FILE__ << __LINE__ << "returns" << ret; - return ret; - } else { - const bool ret = isIntermediateValueHelper(qAbs(left), 0, dec); - QSBDEBUG() << __FILE__ << __LINE__ << "returns" << ret; - return ret; - } - } - if (match != min_left) { - min_right = negative ? dec : 0; - } - if (match != max_left) { - max_right = negative ? 0 : dec; - } - qint64 tmpl = negative ? max_right : min_right; - qint64 tmpr = negative ? min_right : max_right; - const bool ret = isIntermediateValueHelper(right, tmpl, tmpr); - QSBDEBUG() << __FILE__ << __LINE__ << "returns" << ret; - return ret; - } - QSBDEBUG() << __FILE__ << __LINE__ << "returns true"; - return true; -} - - -/*! - \internal Multi purpose function that parses input, sets state to - the appropriate state and returns the value it will be interpreted - as. -*/ -// reimplemented function, copied from QDoubleSpinBoxPrivate::validateAndInterpret -QVariant QScienceSpinBox::validateAndInterpret( - QString &input, - int &pos, - QValidator::State &state) const -{ - /*! return 'cachedText' if - * input = cachedText, or input Empty - */ - - static QString cachedText; - static QValidator::State cachedState; - static QVariant cachedValue; - - if (cachedText == input && !input.isEmpty()) { - state = cachedState; - QSBDEBUG() << "cachedText was" << "'" << cachedText << "'" << "state was " - << state << " and value was " << cachedValue; - return cachedValue; - } - const double max = maximum(); - const double min = minimum(); - - // removes prefix & suffix - QString copy = stripped(input, &pos); - QSBDEBUG() << "input" << input << "copy" << copy; - - int len = copy.size(); - double num = min; - const bool plus = max >= 0; - const bool minus = min <= 0; - - // Test possible 'Intermediate' reasons - switch (len) - { - case 0: - // Length 0 is always 'Intermediate', except for min=max - if (max != min) { - state = QValidator::Intermediate; - } else { - state = QValidator::Invalid; - } - goto end; - case 1: - // if only char is '+' or '-' - if (copy.at(0) == delimiter - || (plus && copy.at(0) == QLatin1Char('+')) - || (minus && copy.at(0) == QLatin1Char('-'))) { - state = QValidator::Intermediate; - goto end; - } - break; - case 2: - // if only chars are '+' or '-' followed by Comma seperator (delimiter) - if (copy.at(1) == delimiter - && ((plus && copy.at(0) == QLatin1Char('+')) || (minus && copy.at(0) == QLatin1Char('-')))) { - state = QValidator::Intermediate; - goto end; - } - break; - default: break; - } // end switch - - - // First char must not be thousand-char - if (copy.at(0) == thousand) - { - QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; - state = QValidator::Invalid; - goto end; - } - // Test possible 'Invalid' reasons - else if (len > 1) - { - const int dec = copy.indexOf(delimiter); // position of delimiter - // if decimal separator (delimiter) exists - if (dec != -1) { - // not two delimiters after one other (meaning something like ',,') - if (dec + 1 < copy.size() && copy.at(dec + 1) == delimiter && pos == dec + 1) { - copy.remove(dec + 1, 1); // typing a delimiter when you are on the delimiter - } // should be treated as typing right arrow - // too many decimal points - if (copy.size() - dec > QDoubleSpinBox::decimals() + 1) { - QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; - state = QValidator::Invalid; - goto end; - } - // after decimal separator no thousand char - for (int i=dec + 1; i 1) - - // block of remaining test before 'end' mark - { - bool ok = false; - bool notAcceptable = false; - - // convert 'copy' to double, and check if that was 'ok' - QLocale loc(locale()); - num = loc.toDouble(copy, &ok); - QSBDEBUG() << __FILE__ << __LINE__ << loc << copy << num << ok; - - - // conversion to double did fail - if (!ok) { - // maybe thousand char was responsable - if (thousand.isPrint()) - { - // if no thousand sign is possible, then - // something else is responable -> Invalid - if (max < 1000 && min > -1000 && copy.contains(thousand)) { - state = QValidator::Invalid; - QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; - goto end; - } - - // two thousand-chars after one other are not valid - const int len = copy.size(); - for (int i=0; i Invalid - if (!ok) { - state = QValidator::Invalid; - QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; - goto end; - } - notAcceptable = true; // -> state = Intermediate - } // endif: (thousand.isPrint()) - } - - // no thousand sign, but still invalid for unknown reason - if (!ok) { - state = QValidator::Invalid; - QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; - } - // number valid and within valid range - else if (num >= min && num <= max) { - if (notAcceptable) { - state = QValidator::Intermediate; // conversion to num initially failed - } else { - state = QValidator::Acceptable; - } - QSBDEBUG() << __FILE__ << __LINE__<< "state is set to " - << (state == QValidator::Intermediate ? "Intermediate" : "Acceptable"); - } - // when max and min is the same the only non-Invalid input is max (or min) - else if (max == min) { - state = QValidator::Invalid; - QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; - } else { - // value out of valid range (coves only special cases) - if ((num >= 0 && num > max) || (num < 0 && num < min)) { - state = QValidator::Invalid; - QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; - } else { - // invalid range, further test with 'isIntermediateValue' - if (isIntermediateValue(copy)) { - state = QValidator::Intermediate; - } else { - state = QValidator::Invalid; - } - QSBDEBUG() << __FILE__ << __LINE__<< "state is set to " - << (state == QValidator::Intermediate ? "Intermediate" : "Acceptable"); - } - } - } - -end: - // if something went wrong, set num to something valid - if (state != QValidator::Acceptable) { - num = max > 0 ? min : max; - } - - // save (private) cache values - cachedText = prefix() + copy + suffix(); - cachedState = state; - cachedValue = QVariant(num); - // return resulting valid num - return QVariant(num); -} - - -/*! - \internal - Strips any prefix/suffix from \a text. -*/ -// reimplemented function, copied from QAbstractSpinBoxPrivate::stripped -QString QScienceSpinBox::stripped(const QString &t, int *pos) const -{ - QString text = t; - QString prefixtext = prefix(); - QString suffixtext = suffix(); - - if (specialValueText().size() == 0 || text != specialValueText()) { - int from = 0; - int size = text.size(); - bool changed = false; - if (prefixtext.size() && text.startsWith(prefixtext)) { - from += prefixtext.size(); - size -= from; - changed = true; - } - if (suffixtext.size() && text.endsWith(suffixtext)) { - size -= suffixtext.size(); - changed = true; - } - if (changed) - text = text.mid(from, size); - } - - const int s = text.size(); - text = text.trimmed(); - if (pos) - (*pos) -= (s - text.size()); - return text; -} - -// reimplemented function, copied from qspinbox.cpp -bool QScienceSpinBox::isIntermediateValueHelper(qint64 num, qint64 min, qint64 max, qint64 *match) -{ - QSBDEBUG("%lld %lld %lld", num, min, max); - - if (num >= min && num <= max) { - if (match) - *match = num; - QSBDEBUG("returns true 0"); - return true; - } - qint64 tmp = num; - - int numDigits = 0; - int digits[10]; - if (tmp == 0) { - numDigits = 1; - digits[0] = 0; - } else { - tmp = qAbs(num); - for (int i=0; tmp > 0; ++i) { - digits[numDigits++] = tmp % 10; - tmp /= 10; - } - } - - int failures = 0; - qint64 number; - for (number=max; number>=min; --number) { - tmp = qAbs(number); - for (int i=0; tmp > 0;) { - if (digits[i] == (tmp % 10)) { - if (++i == numDigits) { - if (match) - *match = number; - QSBDEBUG("returns true 1"); - return true; - } - } - tmp /= 10; - } - if (failures++ == 500000) { //upper bound - if (match) - *match = num; - QSBDEBUG("returns true 2"); - return true; - } - } - QSBDEBUG("returns false"); - return false; -} +/** + * Code copied from http://www.matthiaspospiech.de/blog/2009/01/03/qt-spinbox-widget-with-scientific-notation/ + */ +#include "QScienceSpinBox.h" + +#include + +//#define QSPINBOX_QSBDEBUG +#ifdef QSPINBOX_QSBDEBUG +# define QSBDEBUG qDebug +#else +# define QSBDEBUG if (false) qDebug +#endif + + +QScienceSpinBox::QScienceSpinBox(QWidget * parent) + : QDoubleSpinBox(parent) +{ + initLocalValues(parent); + setDecimals(8); + QDoubleSpinBox::setDecimals(1000); + + // set Range to maximum possible values + double doubleMax = std::numeric_limits::max(); + setRange(-doubleMax, doubleMax); + + v = new QDoubleValidator(this); + v->setDecimals(1000); // (standard anyway) + v->setNotation(QDoubleValidator::ScientificNotation); + this->lineEdit()->setValidator(v); +} + +void QScienceSpinBox::initLocalValues(QWidget *parent) +{ + const QString str = (parent ? parent->locale() : QLocale()).toString(4567.1); + if (str.size() == 6) { + delimiter = str.at(4); + thousand = QChar((ushort)0); + } else if (str.size() == 7) { + thousand = str.at(1); + delimiter = str.at(5); + } + Q_ASSERT(!delimiter.isNull()); +} + +int QScienceSpinBox::decimals() const +{ + return dispDecimals; +} + +void QScienceSpinBox::setDecimals(int value) +{ + dispDecimals = value; +} + +// overwritten virtual function of QAbstractSpinBox +void QScienceSpinBox::stepBy(int steps) +{ + if (steps < 0) + stepDown(); + else + stepUp(); +} + +void QScienceSpinBox::stepDown() +{ + QSBDEBUG() << "stepDown()"; + setValue(value()/10.0); +} + +void QScienceSpinBox::stepUp() +{ + QSBDEBUG() << "stepUp()"; + setValue(value()*10.0); +} + +/*! + * text to be displayed in spinbox + */ +QString QScienceSpinBox::textFromValue(double value) const +{ + + // convert to string -> Using exponetial display with internal decimals + QString str = locale().toString(value, 'e', dispDecimals); + // remove thousand sign + if (qAbs(value) >= 1000.0) { + str.remove(thousand); + } + return str; +} + +double QScienceSpinBox::valueFromText(const QString &text) const +{ + QString copy = text; + int pos = this->lineEdit()->cursorPosition(); + QValidator::State state = QValidator::Acceptable; + return validateAndInterpret(copy, pos, state).toDouble(); +} + +// this function is never used...? +double QScienceSpinBox::round(double value) const +{ + const QString strDbl = locale().toString(value, 'g', dispDecimals); + return locale().toDouble(strDbl); +} + +// overwritten virtual function of QAbstractSpinBox +QValidator::State QScienceSpinBox::validate(QString &text, int &pos) const +{ + QValidator::State state; + validateAndInterpret(text, pos, state); + return state; +} + +// overwritten virtual function of QAbstractSpinBox +void QScienceSpinBox::fixup(QString &input) const +{ + input.remove(thousand); +} + +// reimplemented function, copied from QDoubleSpinBoxPrivate::isIntermediateValue +bool QScienceSpinBox::isIntermediateValue(const QString &str) const +{ + QSBDEBUG() << "input is" << str << minimum() << maximum(); + qint64 dec = 1; + + for (int i=0; i < decimals(); ++i) + dec *= 10; + + const QLatin1Char dot('.'); + + /*! + * determine minimum possible values on left and right of Decimal-char + */ + // I know QString::number() uses CLocale so I use dot + const QString minstr = QString::number(minimum(), 'f', QDoubleSpinBox::decimals()); + qint64 min_left = minstr.left(minstr.indexOf(dot)).toLongLong(); + qint64 min_right = minstr.mid(minstr.indexOf(dot) + 1).toLongLong(); + + const QString maxstr = QString::number(maximum(), 'f', QDoubleSpinBox::decimals()); + qint64 max_left = maxstr.left(maxstr.indexOf(dot)).toLongLong(); + qint64 max_right = maxstr.mid(maxstr.indexOf(dot) + 1).toLongLong(); + + /*! + * determine left and right long values (left and right of delimiter) + */ + const int dotindex = str.indexOf(delimiter); + const bool negative = maximum() < 0; + qint64 left = 0, right = 0; + bool doleft = true; + bool doright = true; + // no separator -> everthing in left + if (dotindex == -1) { + left = str.toLongLong(); + doright = false; + } + // separator on left or contains '+' + else if (dotindex == 0 || (dotindex == 1 && str.at(0) == QLatin1Char('+'))) { + // '+' at negative max + if (negative) { + QSBDEBUG() << __FILE__ << __LINE__ << "returns false"; + return false; + } + doleft = false; + right = str.mid(dotindex + 1).toLongLong(); + } + // contains '-' + else if (dotindex == 1 && str.at(0) == QLatin1Char('-')) { + // '-' at positiv max + if (!negative) { + QSBDEBUG() << __FILE__ << __LINE__ << "returns false"; + return false; + } + doleft = false; + right = str.mid(dotindex + 1).toLongLong(); + } else { + left = str.left(dotindex).toLongLong(); + if (dotindex == str.size() - 1) { // nothing right of Separator + doright = false; + } else { + right = str.mid(dotindex + 1).toLongLong(); + } + } + // left > 0, with max < 0 and no '-' + if ((left >= 0 && max_left < 0 && !str.startsWith(QLatin1Char('-'))) + // left > 0, with min > 0 + || (left < 0 && min_left >= 0)) + { + QSBDEBUG("returns false"); + return false; + } + + qint64 match = min_left; + if (doleft && !isIntermediateValueHelper(left, min_left, max_left, &match)) { + QSBDEBUG() << __FILE__ << __LINE__ << "returns false"; + return false; + } + if (doright) { + QSBDEBUG("match %lld min_left %lld max_left %lld", match, min_left, max_left); + if (!doleft) { + if (min_left == max_left) { + const bool ret = isIntermediateValueHelper(qAbs(left), + negative ? max_right : min_right, + negative ? min_right : max_right); + QSBDEBUG() << __FILE__ << __LINE__ << "returns" << ret; + return ret; + } else if (qAbs(max_left - min_left) == 1) { + const bool ret = isIntermediateValueHelper(qAbs(left), min_right, negative ? 0 : dec) + || isIntermediateValueHelper(qAbs(left), negative ? dec : 0, max_right); + QSBDEBUG() << __FILE__ << __LINE__ << "returns" << ret; + return ret; + } else { + const bool ret = isIntermediateValueHelper(qAbs(left), 0, dec); + QSBDEBUG() << __FILE__ << __LINE__ << "returns" << ret; + return ret; + } + } + if (match != min_left) { + min_right = negative ? dec : 0; + } + if (match != max_left) { + max_right = negative ? 0 : dec; + } + qint64 tmpl = negative ? max_right : min_right; + qint64 tmpr = negative ? min_right : max_right; + const bool ret = isIntermediateValueHelper(right, tmpl, tmpr); + QSBDEBUG() << __FILE__ << __LINE__ << "returns" << ret; + return ret; + } + QSBDEBUG() << __FILE__ << __LINE__ << "returns true"; + return true; +} + + +/*! + \internal Multi purpose function that parses input, sets state to + the appropriate state and returns the value it will be interpreted + as. +*/ +// reimplemented function, copied from QDoubleSpinBoxPrivate::validateAndInterpret +QVariant QScienceSpinBox::validateAndInterpret( + QString &input, + int &pos, + QValidator::State &state) const +{ + /*! return 'cachedText' if + * input = cachedText, or input Empty + */ + + static QString cachedText; + static QValidator::State cachedState; + static QVariant cachedValue; + + if (cachedText == input && !input.isEmpty()) { + state = cachedState; + QSBDEBUG() << "cachedText was" << "'" << cachedText << "'" << "state was " + << state << " and value was " << cachedValue; + return cachedValue; + } + const double max = maximum(); + const double min = minimum(); + + // removes prefix & suffix + QString copy = stripped(input, &pos); + QSBDEBUG() << "input" << input << "copy" << copy; + + int len = copy.size(); + double num = min; + const bool plus = max >= 0; + const bool minus = min <= 0; + + // Test possible 'Intermediate' reasons + switch (len) + { + case 0: + // Length 0 is always 'Intermediate', except for min=max + if (max != min) { + state = QValidator::Intermediate; + } else { + state = QValidator::Invalid; + } + goto end; + case 1: + // if only char is '+' or '-' + if (copy.at(0) == delimiter + || (plus && copy.at(0) == QLatin1Char('+')) + || (minus && copy.at(0) == QLatin1Char('-'))) { + state = QValidator::Intermediate; + goto end; + } + break; + case 2: + // if only chars are '+' or '-' followed by Comma seperator (delimiter) + if (copy.at(1) == delimiter + && ((plus && copy.at(0) == QLatin1Char('+')) || (minus && copy.at(0) == QLatin1Char('-')))) { + state = QValidator::Intermediate; + goto end; + } + break; + default: break; + } // end switch + + + // First char must not be thousand-char + if (copy.at(0) == thousand) + { + QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; + state = QValidator::Invalid; + goto end; + } + // Test possible 'Invalid' reasons + else if (len > 1) + { + const int dec = copy.indexOf(delimiter); // position of delimiter + // if decimal separator (delimiter) exists + if (dec != -1) { + // not two delimiters after one other (meaning something like ',,') + if (dec + 1 < copy.size() && copy.at(dec + 1) == delimiter && pos == dec + 1) { + copy.remove(dec + 1, 1); // typing a delimiter when you are on the delimiter + } // should be treated as typing right arrow + // too many decimal points + if (copy.size() - dec > QDoubleSpinBox::decimals() + 1) { + QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; + state = QValidator::Invalid; + goto end; + } + // after decimal separator no thousand char + for (int i=dec + 1; i 1) + + // block of remaining test before 'end' mark + { + bool ok = false; + bool notAcceptable = false; + + // convert 'copy' to double, and check if that was 'ok' + QLocale loc(locale()); + num = loc.toDouble(copy, &ok); + QSBDEBUG() << __FILE__ << __LINE__ << loc << copy << num << ok; + + + // conversion to double did fail + if (!ok) { + // maybe thousand char was responsable + if (thousand.isPrint()) + { + // if no thousand sign is possible, then + // something else is responable -> Invalid + if (max < 1000 && min > -1000 && copy.contains(thousand)) { + state = QValidator::Invalid; + QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; + goto end; + } + + // two thousand-chars after one other are not valid + const int len = copy.size(); + for (int i=0; i Invalid + if (!ok) { + state = QValidator::Invalid; + QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; + goto end; + } + notAcceptable = true; // -> state = Intermediate + } // endif: (thousand.isPrint()) + } + + // no thousand sign, but still invalid for unknown reason + if (!ok) { + state = QValidator::Invalid; + QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; + } + // number valid and within valid range + else if (num >= min && num <= max) { + if (notAcceptable) { + state = QValidator::Intermediate; // conversion to num initially failed + } else { + state = QValidator::Acceptable; + } + QSBDEBUG() << __FILE__ << __LINE__<< "state is set to " + << (state == QValidator::Intermediate ? "Intermediate" : "Acceptable"); + } + // when max and min is the same the only non-Invalid input is max (or min) + else if (max == min) { + state = QValidator::Invalid; + QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; + } else { + // value out of valid range (coves only special cases) + if ((num >= 0 && num > max) || (num < 0 && num < min)) { + state = QValidator::Invalid; + QSBDEBUG() << __FILE__ << __LINE__<< "state is set to Invalid"; + } else { + // invalid range, further test with 'isIntermediateValue' + if (isIntermediateValue(copy)) { + state = QValidator::Intermediate; + } else { + state = QValidator::Invalid; + } + QSBDEBUG() << __FILE__ << __LINE__<< "state is set to " + << (state == QValidator::Intermediate ? "Intermediate" : "Acceptable"); + } + } + } + +end: + // if something went wrong, set num to something valid + if (state != QValidator::Acceptable) { + num = max > 0 ? min : max; + } + + // save (private) cache values + cachedText = prefix() + copy + suffix(); + cachedState = state; + cachedValue = QVariant(num); + // return resulting valid num + return QVariant(num); +} + + +/*! + \internal + Strips any prefix/suffix from \a text. +*/ +// reimplemented function, copied from QAbstractSpinBoxPrivate::stripped +QString QScienceSpinBox::stripped(const QString &t, int *pos) const +{ + QString text = t; + QString prefixtext = prefix(); + QString suffixtext = suffix(); + + if (specialValueText().size() == 0 || text != specialValueText()) { + int from = 0; + int size = text.size(); + bool changed = false; + if (prefixtext.size() && text.startsWith(prefixtext)) { + from += prefixtext.size(); + size -= from; + changed = true; + } + if (suffixtext.size() && text.endsWith(suffixtext)) { + size -= suffixtext.size(); + changed = true; + } + if (changed) + text = text.mid(from, size); + } + + const int s = text.size(); + text = text.trimmed(); + if (pos) + (*pos) -= (s - text.size()); + return text; +} + +// reimplemented function, copied from qspinbox.cpp +bool QScienceSpinBox::isIntermediateValueHelper(qint64 num, qint64 min, qint64 max, qint64 *match) +{ + QSBDEBUG("%lld %lld %lld", num, min, max); + + if (num >= min && num <= max) { + if (match) + *match = num; + QSBDEBUG("returns true 0"); + return true; + } + qint64 tmp = num; + + int numDigits = 0; + int digits[10]; + if (tmp == 0) { + numDigits = 1; + digits[0] = 0; + } else { + tmp = qAbs(num); + for (int i=0; tmp > 0; ++i) { + digits[numDigits++] = tmp % 10; + tmp /= 10; + } + } + + int failures = 0; + qint64 number; + for (number=max; number>=min; --number) { + tmp = qAbs(number); + for (int i=0; tmp > 0;) { + if (digits[i] == (tmp % 10)) { + if (++i == numDigits) { + if (match) + *match = number; + QSBDEBUG("returns true 1"); + return true; + } + } + tmp /= 10; + } + if (failures++ == 500000) { //upper bound + if (match) + *match = num; + QSBDEBUG("returns true 2"); + return true; + } + } + QSBDEBUG("returns false"); + return false; +} diff --git a/ground/openpilotgcs/src/libs/qscispinbox/QScienceSpinBox.h b/ground/openpilotgcs/src/libs/qscispinbox/QScienceSpinBox.h index 8b2ab98ed..faecd0df1 100644 --- a/ground/openpilotgcs/src/libs/qscispinbox/QScienceSpinBox.h +++ b/ground/openpilotgcs/src/libs/qscispinbox/QScienceSpinBox.h @@ -1,50 +1,50 @@ -/** - * Code copied from http://www.matthiaspospiech.de/blog/2009/01/03/qt-spinbox-widget-with-scientific-notation/ - */ -#ifndef __QScienceSpinBox_H__ -#define __QScienceSpinBox_H__ - -#include -#include -#include -#include -#include -#include - - -class QScienceSpinBox : public QDoubleSpinBox -{ -Q_OBJECT -public: - QScienceSpinBox(QWidget * parent = 0); - - int decimals() const; - void setDecimals(int value); - - QString textFromValue ( double value ) const; - double valueFromText ( const QString & text ) const; - static bool isIntermediateValueHelper(qint64 num, qint64 minimum, qint64 maximum, qint64 *match = 0); - -private: - int dispDecimals; - QChar delimiter, thousand; - QDoubleValidator * v; - - -private: - void initLocalValues(QWidget *parent); - bool isIntermediateValue(const QString &str) const; - QVariant validateAndInterpret(QString &input, int &pos, QValidator::State &state) const; - QValidator::State validate(QString &text, int &pos) const; - void fixup(QString &input) const; - QString stripped(const QString &t, int *pos) const; - double round(double value) const; - void stepBy(int steps); - -public slots: - void stepDown(); - void stepUp(); - -}; - -#endif +/** + * Code copied from http://www.matthiaspospiech.de/blog/2009/01/03/qt-spinbox-widget-with-scientific-notation/ + */ +#ifndef __QScienceSpinBox_H__ +#define __QScienceSpinBox_H__ + +#include +#include +#include +#include +#include +#include + + +class QScienceSpinBox : public QDoubleSpinBox +{ +Q_OBJECT +public: + QScienceSpinBox(QWidget * parent = 0); + + int decimals() const; + void setDecimals(int value); + + QString textFromValue ( double value ) const; + double valueFromText ( const QString & text ) const; + static bool isIntermediateValueHelper(qint64 num, qint64 minimum, qint64 maximum, qint64 *match = 0); + +private: + int dispDecimals; + QChar delimiter, thousand; + QDoubleValidator * v; + + +private: + void initLocalValues(QWidget *parent); + bool isIntermediateValue(const QString &str) const; + QVariant validateAndInterpret(QString &input, int &pos, QValidator::State &state) const; + QValidator::State validate(QString &text, int &pos) const; + void fixup(QString &input) const; + QString stripped(const QString &t, int *pos) const; + double round(double value) const; + void stepBy(int steps); + +public slots: + void stepDown(); + void stepUp(); + +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qscispinbox/qscispinbox.pro b/ground/openpilotgcs/src/libs/qscispinbox/qscispinbox.pro index e71a7e848..8610205eb 100644 --- a/ground/openpilotgcs/src/libs/qscispinbox/qscispinbox.pro +++ b/ground/openpilotgcs/src/libs/qscispinbox/qscispinbox.pro @@ -1,11 +1,11 @@ -TEMPLATE = lib -TARGET = QScienceSpinBox - -include(../../openpilotgcslibrary.pri) - -DEFINES += QSCIENCESPINBOX - -HEADERS = QScienceSpinBox.h - -SOURCES = QScienceSpinBox.cpp - +TEMPLATE = lib +TARGET = QScienceSpinBox + +include(../../openpilotgcslibrary.pri) + +DEFINES += QSCIENCESPINBOX + +HEADERS = QScienceSpinBox.h + +SOURCES = QScienceSpinBox.cpp + diff --git a/ground/openpilotgcs/src/libs/qtconcurrent/qtconcurrent.pro b/ground/openpilotgcs/src/libs/qtconcurrent/qtconcurrent.pro index e914057eb..ef29d9188 100644 --- a/ground/openpilotgcs/src/libs/qtconcurrent/qtconcurrent.pro +++ b/ground/openpilotgcs/src/libs/qtconcurrent/qtconcurrent.pro @@ -1,10 +1,10 @@ -TEMPLATE = lib -TARGET = QtConcurrent -DEFINES += BUILD_QTCONCURRENT - -include(../../openpilotgcslibrary.pri) - -HEADERS += \ - qtconcurrent_global.h \ - multitask.h \ - runextensions.h +TEMPLATE = lib +TARGET = QtConcurrent +DEFINES += BUILD_QTCONCURRENT + +include(../../openpilotgcslibrary.pri) + +HEADERS += \ + qtconcurrent_global.h \ + multitask.h \ + runextensions.h diff --git a/ground/openpilotgcs/src/libs/qwt/qwt.pro b/ground/openpilotgcs/src/libs/qwt/qwt.pro index 7d056a921..722dea7a2 100644 --- a/ground/openpilotgcs/src/libs/qwt/qwt.pro +++ b/ground/openpilotgcs/src/libs/qwt/qwt.pro @@ -1,14 +1,14 @@ -################################################################ -# Qwt Widget Library -# Copyright (C) 1997 Josef Wilgen -# Copyright (C) 2002 Uwe Rathmann -# -# This library is free software; you can redistribute it and/or -# modify it under the terms of the Qwt License, Version 1.0 -################################################################ - -include( qwtconfig.pri ) - -TEMPLATE = subdirs - -SUBDIRS = src +################################################################ +# Qwt Widget Library +# Copyright (C) 1997 Josef Wilgen +# Copyright (C) 2002 Uwe Rathmann +# +# This library is free software; you can redistribute it and/or +# modify it under the terms of the Qwt License, Version 1.0 +################################################################ + +include( qwtconfig.pri ) + +TEMPLATE = subdirs + +SUBDIRS = src diff --git a/ground/openpilotgcs/src/libs/qwt/qwtconfig.pri b/ground/openpilotgcs/src/libs/qwt/qwtconfig.pri index 10e0594f1..7ac24aa52 100644 --- a/ground/openpilotgcs/src/libs/qwt/qwtconfig.pri +++ b/ground/openpilotgcs/src/libs/qwt/qwtconfig.pri @@ -1,126 +1,126 @@ -################################################################ -# Qwt Widget Library -# Copyright (C) 1997 Josef Wilgen -# Copyright (C) 2002 Uwe Rathmann -# -# This library is free software; you can redistribute it and/or -# modify it under the terms of the Qwt License, Version 1.0 -################################################################ - -#QWT_VER_MAJ = 6 -#QWT_VER_MIN = 0 -#QWT_VER_PAT = 1 -#QWT_VERSION = $${QWT_VER_MAJ}.$${QWT_VER_MIN}.$${QWT_VER_PAT} - -###################################################################### -# Install paths -###################################################################### - -#QWT_INSTALL_PREFIX = $$[QT_INSTALL_PREFIX] - -unix { - #QWT_INSTALL_PREFIX = /usr/local/qwt-$$QWT_VERSION -} - -win32 { - #QWT_INSTALL_PREFIX = C:/Qwt-$$QWT_VERSION -} - -#QWT_INSTALL_DOCS = $${QWT_INSTALL_PREFIX}/doc -#QWT_INSTALL_HEADERS = $${QWT_INSTALL_PREFIX}/include -#QWT_INSTALL_LIBS = $${QWT_INSTALL_PREFIX}/lib - -###################################################################### -# Designer plugin -###################################################################### - -#QWT_INSTALL_PLUGINS = $${QWT_INSTALL_PREFIX}/plugins/designer -# QWT_INSTALL_PLUGINS = $${QT_INSTALL_PREFIX}/plugins/designer - -###################################################################### -# Features -# When building a Qwt application with qmake you might want to load -# the compiler/linker flags, that are required to build a Qwt application -# from qwt.prf. Therefore all you need to do is to add "CONFIG += qwt" -# to your project file and take care, that qwt.prf can be found by qmake. -# ( see http://doc.trolltech.com/4.7/qmake-advanced-usage.html#adding-new-configuration-features ) -# I recommend not to install the Qwt features together with the -# Qt features, because you will have to reinstall the Qwt features, -# with every Qt upgrade. -###################################################################### - -#QWT_INSTALL_FEATURES = $${QWT_INSTALL_PREFIX}/features -# QWT_INSTALL_FEATURES = $${QT_INSTALL_PREFIX}/features - -###################################################################### -# Build the static/shared libraries. -# If QwtDll is enabled, a shared library is built, otherwise -# it will be a static library. -###################################################################### - -QWT_CONFIG += QwtDll - -###################################################################### -# QwtPlot enables all classes, that are needed to use the QwtPlot -# widget. -###################################################################### - -QWT_CONFIG += QwtPlot - -###################################################################### -# Build the static/shared libraries. -# If QwtDll is enabled, a shared library is built, otherwise -# it will be a static library. -###################################################################### - -QWT_CONFIG += QwtDll - -###################################################################### -# QwtWidgets enables all classes, that are needed to use the all other -# widgets (sliders, dials, ...), beside QwtPlot. -###################################################################### - -QWT_CONFIG += QwtWidgets - -###################################################################### -# If you want to display svg images on the plot canvas, or -# export a plot to a SVG document -###################################################################### - -QWT_CONFIG += QwtSvg - -###################################################################### -# You can use the MathML renderer of the Qt solutions package to -# enable MathML support in Qwt. Because of license implications -# the ( modified ) code of the MML Widget solution is included and -# linked together with the QwtMathMLTextEngine into an own library. -# To use it you will have to add "CONFIG += qwtmathml" -# to your qmake project file. -###################################################################### - -QWT_CONFIG += QwtMathML - -###################################################################### -# If you want to build the Qwt designer plugin, -# enable the line below. -# Otherwise you have to build it from the designer directory. -###################################################################### - -#QWT_CONFIG += QwtDesigner - -###################################################################### -# If you want to auto build the examples, enable the line below -# Otherwise you have to build them from the examples directory. -###################################################################### - -# QWT_CONFIG += QwtExamples - -###################################################################### -# When Qt has been built as framework qmake ( qtAddLibrary ) wants -# to link frameworks instead of regular libs -###################################################################### - -macx:CONFIG(qt_framework, qt_framework|qt_no_framework) { - - QWT_CONFIG += QwtFramework -} +################################################################ +# Qwt Widget Library +# Copyright (C) 1997 Josef Wilgen +# Copyright (C) 2002 Uwe Rathmann +# +# This library is free software; you can redistribute it and/or +# modify it under the terms of the Qwt License, Version 1.0 +################################################################ + +#QWT_VER_MAJ = 6 +#QWT_VER_MIN = 0 +#QWT_VER_PAT = 1 +#QWT_VERSION = $${QWT_VER_MAJ}.$${QWT_VER_MIN}.$${QWT_VER_PAT} + +###################################################################### +# Install paths +###################################################################### + +#QWT_INSTALL_PREFIX = $$[QT_INSTALL_PREFIX] + +unix { + #QWT_INSTALL_PREFIX = /usr/local/qwt-$$QWT_VERSION +} + +win32 { + #QWT_INSTALL_PREFIX = C:/Qwt-$$QWT_VERSION +} + +#QWT_INSTALL_DOCS = $${QWT_INSTALL_PREFIX}/doc +#QWT_INSTALL_HEADERS = $${QWT_INSTALL_PREFIX}/include +#QWT_INSTALL_LIBS = $${QWT_INSTALL_PREFIX}/lib + +###################################################################### +# Designer plugin +###################################################################### + +#QWT_INSTALL_PLUGINS = $${QWT_INSTALL_PREFIX}/plugins/designer +# QWT_INSTALL_PLUGINS = $${QT_INSTALL_PREFIX}/plugins/designer + +###################################################################### +# Features +# When building a Qwt application with qmake you might want to load +# the compiler/linker flags, that are required to build a Qwt application +# from qwt.prf. Therefore all you need to do is to add "CONFIG += qwt" +# to your project file and take care, that qwt.prf can be found by qmake. +# ( see http://doc.trolltech.com/4.7/qmake-advanced-usage.html#adding-new-configuration-features ) +# I recommend not to install the Qwt features together with the +# Qt features, because you will have to reinstall the Qwt features, +# with every Qt upgrade. +###################################################################### + +#QWT_INSTALL_FEATURES = $${QWT_INSTALL_PREFIX}/features +# QWT_INSTALL_FEATURES = $${QT_INSTALL_PREFIX}/features + +###################################################################### +# Build the static/shared libraries. +# If QwtDll is enabled, a shared library is built, otherwise +# it will be a static library. +###################################################################### + +QWT_CONFIG += QwtDll + +###################################################################### +# QwtPlot enables all classes, that are needed to use the QwtPlot +# widget. +###################################################################### + +QWT_CONFIG += QwtPlot + +###################################################################### +# Build the static/shared libraries. +# If QwtDll is enabled, a shared library is built, otherwise +# it will be a static library. +###################################################################### + +QWT_CONFIG += QwtDll + +###################################################################### +# QwtWidgets enables all classes, that are needed to use the all other +# widgets (sliders, dials, ...), beside QwtPlot. +###################################################################### + +QWT_CONFIG += QwtWidgets + +###################################################################### +# If you want to display svg images on the plot canvas, or +# export a plot to a SVG document +###################################################################### + +QWT_CONFIG += QwtSvg + +###################################################################### +# You can use the MathML renderer of the Qt solutions package to +# enable MathML support in Qwt. Because of license implications +# the ( modified ) code of the MML Widget solution is included and +# linked together with the QwtMathMLTextEngine into an own library. +# To use it you will have to add "CONFIG += qwtmathml" +# to your qmake project file. +###################################################################### + +QWT_CONFIG += QwtMathML + +###################################################################### +# If you want to build the Qwt designer plugin, +# enable the line below. +# Otherwise you have to build it from the designer directory. +###################################################################### + +#QWT_CONFIG += QwtDesigner + +###################################################################### +# If you want to auto build the examples, enable the line below +# Otherwise you have to build them from the examples directory. +###################################################################### + +# QWT_CONFIG += QwtExamples + +###################################################################### +# When Qt has been built as framework qmake ( qtAddLibrary ) wants +# to link frameworks instead of regular libs +###################################################################### + +macx:CONFIG(qt_framework, qt_framework|qt_no_framework) { + + QWT_CONFIG += QwtFramework +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt.h b/ground/openpilotgcs/src/libs/qwt/src/qwt.h index 5aab34dfc..37494933e 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt.h @@ -1,22 +1,22 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_H -#define QWT_H - -#include "qwt_global.h" - -/*! - Some constants for use within Qwt. -*/ -namespace Qwt -{ -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_H +#define QWT_H + +#include "qwt_global.h" + +/*! + Some constants for use within Qwt. +*/ +namespace Qwt +{ +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale.cpp index 485d8b56b..e44776e6e 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale.cpp @@ -1,310 +1,310 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_abstract_scale.h" -#include "qwt_scale_engine.h" -#include "qwt_scale_draw.h" -#include "qwt_scale_div.h" -#include "qwt_scale_map.h" -#include "qwt_interval.h" - -class QwtAbstractScale::PrivateData -{ -public: - PrivateData(): - maxMajor( 5 ), - maxMinor( 3 ), - stepSize( 0.0 ), - autoScale( true ) - { - scaleEngine = new QwtLinearScaleEngine; - scaleDraw = new QwtScaleDraw(); - } - - ~PrivateData() - { - delete scaleEngine; - delete scaleDraw; - } - - QwtScaleEngine *scaleEngine; - QwtAbstractScaleDraw *scaleDraw; - - int maxMajor; - int maxMinor; - double stepSize; - - bool autoScale; -}; - -/*! - Constructor - - Creates a default QwtScaleDraw and a QwtLinearScaleEngine. - Autoscaling is enabled, and the stepSize is initialized by 0.0. -*/ - -QwtAbstractScale::QwtAbstractScale() -{ - d_data = new PrivateData; - rescale( 0.0, 100.0 ); -} - -//! Destructor -QwtAbstractScale::~QwtAbstractScale() -{ - delete d_data; -} - -/*! - \brief Specify a scale. - - Disable autoscaling and define a scale by an interval and a step size - - \param vmin lower limit of the scale interval - \param vmax upper limit of the scale interval - \param stepSize major step size - \sa setAutoScale() -*/ -void QwtAbstractScale::setScale( double vmin, double vmax, double stepSize ) -{ - d_data->autoScale = false; - d_data->stepSize = stepSize; - - rescale( vmin, vmax, stepSize ); -} - -/*! - \brief Specify a scale. - - Disable autoscaling and define a scale by an interval and a step size - - \param interval Interval - \param stepSize major step size - \sa setAutoScale() -*/ -void QwtAbstractScale::setScale( const QwtInterval &interval, double stepSize ) -{ - setScale( interval.minValue(), interval.maxValue(), stepSize ); -} - - -/*! - \brief Specify a scale. - - Disable autoscaling and define a scale by a scale division - - \param scaleDiv Scale division - \sa setAutoScale() -*/ -void QwtAbstractScale::setScale( const QwtScaleDiv &scaleDiv ) -{ - d_data->autoScale = false; - - if ( scaleDiv != d_data->scaleDraw->scaleDiv() ) - { - d_data->scaleDraw->setScaleDiv( scaleDiv ); - scaleChange(); - } -} - -/*! - Recalculate the scale division and update the scale draw. - - \param vmin Lower limit of the scale interval - \param vmax Upper limit of the scale interval - \param stepSize Major step size - - \sa scaleChange() -*/ -void QwtAbstractScale::rescale( double vmin, double vmax, double stepSize ) -{ - const QwtScaleDiv scaleDiv = d_data->scaleEngine->divideScale( - vmin, vmax, d_data->maxMajor, d_data->maxMinor, stepSize ); - - if ( scaleDiv != d_data->scaleDraw->scaleDiv() ) - { - d_data->scaleDraw->setTransformation( - d_data->scaleEngine->transformation() ); - d_data->scaleDraw->setScaleDiv( scaleDiv ); - scaleChange(); - } -} - -/*! - \brief Advise the widget to control the scale range internally. - - Autoscaling is on by default. - \sa setScale(), autoScale() -*/ -void QwtAbstractScale::setAutoScale() -{ - if ( !d_data->autoScale ) - { - d_data->autoScale = true; - scaleChange(); - } -} - -/*! - \return \c true if autoscaling is enabled -*/ -bool QwtAbstractScale::autoScale() const -{ - return d_data->autoScale; -} - -/*! - \brief Set the maximum number of major tick intervals. - - The scale's major ticks are calculated automatically such that - the number of major intervals does not exceed ticks. - The default value is 5. - \param ticks maximal number of major ticks. - \sa QwtAbstractScaleDraw -*/ -void QwtAbstractScale::setScaleMaxMajor( int ticks ) -{ - if ( ticks != d_data->maxMajor ) - { - d_data->maxMajor = ticks; - updateScaleDraw(); - } -} - -/*! - \brief Set the maximum number of minor tick intervals - - The scale's minor ticks are calculated automatically such that - the number of minor intervals does not exceed ticks. - The default value is 3. - \param ticks - \sa QwtAbstractScaleDraw -*/ -void QwtAbstractScale::setScaleMaxMinor( int ticks ) -{ - if ( ticks != d_data->maxMinor ) - { - d_data->maxMinor = ticks; - updateScaleDraw(); - } -} - -/*! - \return Max. number of minor tick intervals - The default value is 3. -*/ -int QwtAbstractScale::scaleMaxMinor() const -{ - return d_data->maxMinor; -} - -/*! - \return Max. number of major tick intervals - The default value is 5. -*/ -int QwtAbstractScale::scaleMaxMajor() const -{ - return d_data->maxMajor; -} - -/*! - \brief Set a scale draw - - scaleDraw has to be created with new and will be deleted in - ~QwtAbstractScale or the next call of setAbstractScaleDraw. -*/ -void QwtAbstractScale::setAbstractScaleDraw( QwtAbstractScaleDraw *scaleDraw ) -{ - if ( scaleDraw == NULL || scaleDraw == d_data->scaleDraw ) - return; - - if ( d_data->scaleDraw != NULL ) - scaleDraw->setScaleDiv( d_data->scaleDraw->scaleDiv() ); - - delete d_data->scaleDraw; - d_data->scaleDraw = scaleDraw; -} - -/*! - \return Scale draw - \sa setAbstractScaleDraw() -*/ -QwtAbstractScaleDraw *QwtAbstractScale::abstractScaleDraw() -{ - return d_data->scaleDraw; -} - -/*! - \return Scale draw - \sa setAbstractScaleDraw() -*/ -const QwtAbstractScaleDraw *QwtAbstractScale::abstractScaleDraw() const -{ - return d_data->scaleDraw; -} - -void QwtAbstractScale::updateScaleDraw() -{ - rescale( d_data->scaleDraw->scaleDiv().lowerBound(), - d_data->scaleDraw->scaleDiv().upperBound(), d_data->stepSize ); -} - -/*! - \brief Set a scale engine - - The scale engine is responsible for calculating the scale division, - and in case of auto scaling how to align the scale. - - scaleEngine has to be created with new and will be deleted in - ~QwtAbstractScale or the next call of setScaleEngine. -*/ -void QwtAbstractScale::setScaleEngine( QwtScaleEngine *scaleEngine ) -{ - if ( scaleEngine != NULL && scaleEngine != d_data->scaleEngine ) - { - delete d_data->scaleEngine; - d_data->scaleEngine = scaleEngine; - } -} - -/*! - \return Scale engine - \sa setScaleEngine() -*/ -const QwtScaleEngine *QwtAbstractScale::scaleEngine() const -{ - return d_data->scaleEngine; -} - -/*! - \return Scale engine - \sa setScaleEngine() -*/ -QwtScaleEngine *QwtAbstractScale::scaleEngine() -{ - return d_data->scaleEngine; -} - -/*! - \brief Notify changed scale - - Dummy empty implementation, intended to be overloaded by derived classes -*/ -void QwtAbstractScale::scaleChange() -{ -} - -/*! - \return abstractScaleDraw()->scaleMap() -*/ -const QwtScaleMap &QwtAbstractScale::scaleMap() const -{ - return d_data->scaleDraw->scaleMap(); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_abstract_scale.h" +#include "qwt_scale_engine.h" +#include "qwt_scale_draw.h" +#include "qwt_scale_div.h" +#include "qwt_scale_map.h" +#include "qwt_interval.h" + +class QwtAbstractScale::PrivateData +{ +public: + PrivateData(): + maxMajor( 5 ), + maxMinor( 3 ), + stepSize( 0.0 ), + autoScale( true ) + { + scaleEngine = new QwtLinearScaleEngine; + scaleDraw = new QwtScaleDraw(); + } + + ~PrivateData() + { + delete scaleEngine; + delete scaleDraw; + } + + QwtScaleEngine *scaleEngine; + QwtAbstractScaleDraw *scaleDraw; + + int maxMajor; + int maxMinor; + double stepSize; + + bool autoScale; +}; + +/*! + Constructor + + Creates a default QwtScaleDraw and a QwtLinearScaleEngine. + Autoscaling is enabled, and the stepSize is initialized by 0.0. +*/ + +QwtAbstractScale::QwtAbstractScale() +{ + d_data = new PrivateData; + rescale( 0.0, 100.0 ); +} + +//! Destructor +QwtAbstractScale::~QwtAbstractScale() +{ + delete d_data; +} + +/*! + \brief Specify a scale. + + Disable autoscaling and define a scale by an interval and a step size + + \param vmin lower limit of the scale interval + \param vmax upper limit of the scale interval + \param stepSize major step size + \sa setAutoScale() +*/ +void QwtAbstractScale::setScale( double vmin, double vmax, double stepSize ) +{ + d_data->autoScale = false; + d_data->stepSize = stepSize; + + rescale( vmin, vmax, stepSize ); +} + +/*! + \brief Specify a scale. + + Disable autoscaling and define a scale by an interval and a step size + + \param interval Interval + \param stepSize major step size + \sa setAutoScale() +*/ +void QwtAbstractScale::setScale( const QwtInterval &interval, double stepSize ) +{ + setScale( interval.minValue(), interval.maxValue(), stepSize ); +} + + +/*! + \brief Specify a scale. + + Disable autoscaling and define a scale by a scale division + + \param scaleDiv Scale division + \sa setAutoScale() +*/ +void QwtAbstractScale::setScale( const QwtScaleDiv &scaleDiv ) +{ + d_data->autoScale = false; + + if ( scaleDiv != d_data->scaleDraw->scaleDiv() ) + { + d_data->scaleDraw->setScaleDiv( scaleDiv ); + scaleChange(); + } +} + +/*! + Recalculate the scale division and update the scale draw. + + \param vmin Lower limit of the scale interval + \param vmax Upper limit of the scale interval + \param stepSize Major step size + + \sa scaleChange() +*/ +void QwtAbstractScale::rescale( double vmin, double vmax, double stepSize ) +{ + const QwtScaleDiv scaleDiv = d_data->scaleEngine->divideScale( + vmin, vmax, d_data->maxMajor, d_data->maxMinor, stepSize ); + + if ( scaleDiv != d_data->scaleDraw->scaleDiv() ) + { + d_data->scaleDraw->setTransformation( + d_data->scaleEngine->transformation() ); + d_data->scaleDraw->setScaleDiv( scaleDiv ); + scaleChange(); + } +} + +/*! + \brief Advise the widget to control the scale range internally. + + Autoscaling is on by default. + \sa setScale(), autoScale() +*/ +void QwtAbstractScale::setAutoScale() +{ + if ( !d_data->autoScale ) + { + d_data->autoScale = true; + scaleChange(); + } +} + +/*! + \return \c true if autoscaling is enabled +*/ +bool QwtAbstractScale::autoScale() const +{ + return d_data->autoScale; +} + +/*! + \brief Set the maximum number of major tick intervals. + + The scale's major ticks are calculated automatically such that + the number of major intervals does not exceed ticks. + The default value is 5. + \param ticks maximal number of major ticks. + \sa QwtAbstractScaleDraw +*/ +void QwtAbstractScale::setScaleMaxMajor( int ticks ) +{ + if ( ticks != d_data->maxMajor ) + { + d_data->maxMajor = ticks; + updateScaleDraw(); + } +} + +/*! + \brief Set the maximum number of minor tick intervals + + The scale's minor ticks are calculated automatically such that + the number of minor intervals does not exceed ticks. + The default value is 3. + \param ticks + \sa QwtAbstractScaleDraw +*/ +void QwtAbstractScale::setScaleMaxMinor( int ticks ) +{ + if ( ticks != d_data->maxMinor ) + { + d_data->maxMinor = ticks; + updateScaleDraw(); + } +} + +/*! + \return Max. number of minor tick intervals + The default value is 3. +*/ +int QwtAbstractScale::scaleMaxMinor() const +{ + return d_data->maxMinor; +} + +/*! + \return Max. number of major tick intervals + The default value is 5. +*/ +int QwtAbstractScale::scaleMaxMajor() const +{ + return d_data->maxMajor; +} + +/*! + \brief Set a scale draw + + scaleDraw has to be created with new and will be deleted in + ~QwtAbstractScale or the next call of setAbstractScaleDraw. +*/ +void QwtAbstractScale::setAbstractScaleDraw( QwtAbstractScaleDraw *scaleDraw ) +{ + if ( scaleDraw == NULL || scaleDraw == d_data->scaleDraw ) + return; + + if ( d_data->scaleDraw != NULL ) + scaleDraw->setScaleDiv( d_data->scaleDraw->scaleDiv() ); + + delete d_data->scaleDraw; + d_data->scaleDraw = scaleDraw; +} + +/*! + \return Scale draw + \sa setAbstractScaleDraw() +*/ +QwtAbstractScaleDraw *QwtAbstractScale::abstractScaleDraw() +{ + return d_data->scaleDraw; +} + +/*! + \return Scale draw + \sa setAbstractScaleDraw() +*/ +const QwtAbstractScaleDraw *QwtAbstractScale::abstractScaleDraw() const +{ + return d_data->scaleDraw; +} + +void QwtAbstractScale::updateScaleDraw() +{ + rescale( d_data->scaleDraw->scaleDiv().lowerBound(), + d_data->scaleDraw->scaleDiv().upperBound(), d_data->stepSize ); +} + +/*! + \brief Set a scale engine + + The scale engine is responsible for calculating the scale division, + and in case of auto scaling how to align the scale. + + scaleEngine has to be created with new and will be deleted in + ~QwtAbstractScale or the next call of setScaleEngine. +*/ +void QwtAbstractScale::setScaleEngine( QwtScaleEngine *scaleEngine ) +{ + if ( scaleEngine != NULL && scaleEngine != d_data->scaleEngine ) + { + delete d_data->scaleEngine; + d_data->scaleEngine = scaleEngine; + } +} + +/*! + \return Scale engine + \sa setScaleEngine() +*/ +const QwtScaleEngine *QwtAbstractScale::scaleEngine() const +{ + return d_data->scaleEngine; +} + +/*! + \return Scale engine + \sa setScaleEngine() +*/ +QwtScaleEngine *QwtAbstractScale::scaleEngine() +{ + return d_data->scaleEngine; +} + +/*! + \brief Notify changed scale + + Dummy empty implementation, intended to be overloaded by derived classes +*/ +void QwtAbstractScale::scaleChange() +{ +} + +/*! + \return abstractScaleDraw()->scaleMap() +*/ +const QwtScaleMap &QwtAbstractScale::scaleMap() const +{ + return d_data->scaleDraw->scaleMap(); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale.h index 7896f61c0..670d2281c 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale.h @@ -1,70 +1,70 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_ABSTRACT_SCALE_H -#define QWT_ABSTRACT_SCALE_H - -#include "qwt_global.h" - -class QwtScaleEngine; -class QwtAbstractScaleDraw; -class QwtScaleDiv; -class QwtScaleMap; -class QwtInterval; - -/*! - \brief An abstract base class for classes containing a scale - - QwtAbstractScale is used to provide classes with a QwtScaleDraw, - and a QwtScaleDiv. The QwtScaleDiv might be set explicitely - or calculated by a QwtScaleEngine. -*/ - -class QWT_EXPORT QwtAbstractScale -{ -public: - QwtAbstractScale(); - virtual ~QwtAbstractScale(); - - void setScale( double vmin, double vmax, double step = 0.0 ); - void setScale( const QwtInterval &, double step = 0.0 ); - void setScale( const QwtScaleDiv & ); - - void setAutoScale(); - bool autoScale() const; - - void setScaleMaxMajor( int ticks ); - int scaleMaxMinor() const; - - void setScaleMaxMinor( int ticks ); - int scaleMaxMajor() const; - - void setScaleEngine( QwtScaleEngine * ); - const QwtScaleEngine *scaleEngine() const; - QwtScaleEngine *scaleEngine(); - - const QwtScaleMap &scaleMap() const; - -protected: - void rescale( double vmin, double vmax, double step = 0.0 ); - - void setAbstractScaleDraw( QwtAbstractScaleDraw * ); - const QwtAbstractScaleDraw *abstractScaleDraw() const; - QwtAbstractScaleDraw *abstractScaleDraw(); - - virtual void scaleChange(); - -private: - void updateScaleDraw(); - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_ABSTRACT_SCALE_H +#define QWT_ABSTRACT_SCALE_H + +#include "qwt_global.h" + +class QwtScaleEngine; +class QwtAbstractScaleDraw; +class QwtScaleDiv; +class QwtScaleMap; +class QwtInterval; + +/*! + \brief An abstract base class for classes containing a scale + + QwtAbstractScale is used to provide classes with a QwtScaleDraw, + and a QwtScaleDiv. The QwtScaleDiv might be set explicitely + or calculated by a QwtScaleEngine. +*/ + +class QWT_EXPORT QwtAbstractScale +{ +public: + QwtAbstractScale(); + virtual ~QwtAbstractScale(); + + void setScale( double vmin, double vmax, double step = 0.0 ); + void setScale( const QwtInterval &, double step = 0.0 ); + void setScale( const QwtScaleDiv & ); + + void setAutoScale(); + bool autoScale() const; + + void setScaleMaxMajor( int ticks ); + int scaleMaxMinor() const; + + void setScaleMaxMinor( int ticks ); + int scaleMaxMajor() const; + + void setScaleEngine( QwtScaleEngine * ); + const QwtScaleEngine *scaleEngine() const; + QwtScaleEngine *scaleEngine(); + + const QwtScaleMap &scaleMap() const; + +protected: + void rescale( double vmin, double vmax, double step = 0.0 ); + + void setAbstractScaleDraw( QwtAbstractScaleDraw * ); + const QwtAbstractScaleDraw *abstractScaleDraw() const; + QwtAbstractScaleDraw *abstractScaleDraw(); + + virtual void scaleChange(); + +private: + void updateScaleDraw(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale_draw.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale_draw.cpp index 7de0051b4..979a9f4b7 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale_draw.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale_draw.cpp @@ -1,412 +1,412 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_abstract_scale_draw.h" -#include "qwt_math.h" -#include "qwt_text.h" -#include "qwt_painter.h" -#include "qwt_scale_map.h" -#include -#include -#include -#include - -class QwtAbstractScaleDraw::PrivateData -{ -public: - PrivateData(): - spacing( 4.0 ), - penWidth( 0 ), - minExtent( 0.0 ) - { - components = QwtAbstractScaleDraw::Backbone - | QwtAbstractScaleDraw::Ticks - | QwtAbstractScaleDraw::Labels; - - tickLength[QwtScaleDiv::MinorTick] = 4.0; - tickLength[QwtScaleDiv::MediumTick] = 6.0; - tickLength[QwtScaleDiv::MajorTick] = 8.0; - } - - ScaleComponents components; - - QwtScaleMap map; - QwtScaleDiv scldiv; - - double spacing; - double tickLength[QwtScaleDiv::NTickTypes]; - int penWidth; - - double minExtent; - - QMap labelCache; -}; - -/*! - \brief Constructor - - The range of the scale is initialized to [0, 100], - The spacing (distance between ticks and labels) is - set to 4, the tick lengths are set to 4,6 and 8 pixels -*/ -QwtAbstractScaleDraw::QwtAbstractScaleDraw() -{ - d_data = new QwtAbstractScaleDraw::PrivateData; -} - -//! Destructor -QwtAbstractScaleDraw::~QwtAbstractScaleDraw() -{ - delete d_data; -} - -/*! - En/Disable a component of the scale - - \param component Scale component - \param enable On/Off - - \sa hasComponent() -*/ -void QwtAbstractScaleDraw::enableComponent( - ScaleComponent component, bool enable ) -{ - if ( enable ) - d_data->components |= component; - else - d_data->components &= ~component; -} - -/*! - Check if a component is enabled - \sa enableComponent() -*/ -bool QwtAbstractScaleDraw::hasComponent( ScaleComponent component ) const -{ - return ( d_data->components & component ); -} - -/*! - Change the scale division - \param sd New scale division -*/ -void QwtAbstractScaleDraw::setScaleDiv( const QwtScaleDiv &sd ) -{ - d_data->scldiv = sd; - d_data->map.setScaleInterval( sd.lowerBound(), sd.upperBound() ); - d_data->labelCache.clear(); -} - -/*! - Change the transformation of the scale - \param transformation New scale transformation -*/ -void QwtAbstractScaleDraw::setTransformation( - QwtScaleTransformation *transformation ) -{ - d_data->map.setTransformation( transformation ); -} - -//! \return Map how to translate between scale and pixel values -const QwtScaleMap &QwtAbstractScaleDraw::scaleMap() const -{ - return d_data->map; -} - -//! \return Map how to translate between scale and pixel values -QwtScaleMap &QwtAbstractScaleDraw::scaleMap() -{ - return d_data->map; -} - -//! \return scale division -const QwtScaleDiv& QwtAbstractScaleDraw::scaleDiv() const -{ - return d_data->scldiv; -} - -/*! - \brief Specify the width of the scale pen - \param width Pen width - \sa penWidth() -*/ -void QwtAbstractScaleDraw::setPenWidth( int width ) -{ - if ( width < 0 ) - width = 0; - - if ( width != d_data->penWidth ) - d_data->penWidth = width; -} - -/*! - \return Scale pen width - \sa setPenWidth() -*/ -int QwtAbstractScaleDraw::penWidth() const -{ - return d_data->penWidth; -} - -/*! - \brief Draw the scale - - \param painter The painter - - \param palette Palette, text color is used for the labels, - foreground color for ticks and backbone -*/ -void QwtAbstractScaleDraw::draw( QPainter *painter, - const QPalette& palette ) const -{ - painter->save(); - - QPen pen = painter->pen(); - pen.setWidth( d_data->penWidth ); - pen.setCosmetic( false ); - painter->setPen( pen ); - - if ( hasComponent( QwtAbstractScaleDraw::Labels ) ) - { - painter->save(); - painter->setPen( palette.color( QPalette::Text ) ); // ignore pen style - - const QList &majorTicks = - d_data->scldiv.ticks( QwtScaleDiv::MajorTick ); - - for ( int i = 0; i < majorTicks.count(); i++ ) - { - const double v = majorTicks[i]; - if ( d_data->scldiv.contains( v ) ) - drawLabel( painter, majorTicks[i] ); - } - - painter->restore(); - } - - if ( hasComponent( QwtAbstractScaleDraw::Ticks ) ) - { - painter->save(); - - QPen pen = painter->pen(); - pen.setColor( palette.color( QPalette::WindowText ) ); - pen.setCapStyle( Qt::FlatCap ); - - painter->setPen( pen ); - - for ( int tickType = QwtScaleDiv::MinorTick; - tickType < QwtScaleDiv::NTickTypes; tickType++ ) - { - const QList &ticks = d_data->scldiv.ticks( tickType ); - for ( int i = 0; i < ticks.count(); i++ ) - { - const double v = ticks[i]; - if ( d_data->scldiv.contains( v ) ) - drawTick( painter, v, d_data->tickLength[tickType] ); - } - } - - painter->restore(); - } - - if ( hasComponent( QwtAbstractScaleDraw::Backbone ) ) - { - painter->save(); - - QPen pen = painter->pen(); - pen.setColor( palette.color( QPalette::WindowText ) ); - pen.setCapStyle( Qt::FlatCap ); - - painter->setPen( pen ); - - drawBackbone( painter ); - - painter->restore(); - } - - painter->restore(); -} - -/*! - \brief Set the spacing between tick and labels - - The spacing is the distance between ticks and labels. - The default spacing is 4 pixels. - - \param spacing Spacing - - \sa spacing() -*/ -void QwtAbstractScaleDraw::setSpacing( double spacing ) -{ - if ( spacing < 0 ) - spacing = 0; - - d_data->spacing = spacing; -} - -/*! - \brief Get the spacing - - The spacing is the distance between ticks and labels. - The default spacing is 4 pixels. - - \sa setSpacing() -*/ -double QwtAbstractScaleDraw::spacing() const -{ - return d_data->spacing; -} - -/*! - \brief Set a minimum for the extent - - The extent is calculated from the coomponents of the - scale draw. In situations, where the labels are - changing and the layout depends on the extent (f.e scrolling - a scale), setting an upper limit as minimum extent will - avoid jumps of the layout. - - \param minExtent Minimum extent - - \sa extent(), minimumExtent() -*/ -void QwtAbstractScaleDraw::setMinimumExtent( double minExtent ) -{ - if ( minExtent < 0.0 ) - minExtent = 0.0; - - d_data->minExtent = minExtent; -} - -/*! - Get the minimum extent - \sa extent(), setMinimumExtent() -*/ -double QwtAbstractScaleDraw::minimumExtent() const -{ - return d_data->minExtent; -} - -/*! - Set the length of the ticks - - \param tickType Tick type - \param length New length - - \warning the length is limited to [0..1000] -*/ -void QwtAbstractScaleDraw::setTickLength( - QwtScaleDiv::TickType tickType, double length ) -{ - if ( tickType < QwtScaleDiv::MinorTick || - tickType > QwtScaleDiv::MajorTick ) - { - return; - } - - if ( length < 0.0 ) - length = 0.0; - - const double maxTickLen = 1000.0; - if ( length > maxTickLen ) - length = maxTickLen; - - d_data->tickLength[tickType] = length; -} - -/*! - Return the length of the ticks - - \sa setTickLength(), maxTickLength() -*/ -double QwtAbstractScaleDraw::tickLength( QwtScaleDiv::TickType tickType ) const -{ - if ( tickType < QwtScaleDiv::MinorTick || - tickType > QwtScaleDiv::MajorTick ) - { - return 0; - } - - return d_data->tickLength[tickType]; -} - -/*! - \return Length of the longest tick - - Useful for layout calculations - \sa tickLength(), setTickLength() -*/ -double QwtAbstractScaleDraw::maxTickLength() const -{ - double length = 0.0; - for ( int i = 0; i < QwtScaleDiv::NTickTypes; i++ ) - length = qMax( length, d_data->tickLength[i] ); - - return length; -} - -/*! - \brief Convert a value into its representing label - - The value is converted to a plain text using - QLocale::system().toString(value). - This method is often overloaded by applications to have individual - labels. - - \param value Value - \return Label string. -*/ -QwtText QwtAbstractScaleDraw::label( double value ) const -{ - return QLocale().toString( value ); -} - -/*! - \brief Convert a value into its representing label and cache it. - - The conversion between value and label is called very often - in the layout and painting code. Unfortunately the - calculation of the label sizes might be slow (really slow - for rich text in Qt4), so it's necessary to cache the labels. - - \param font Font - \param value Value - - \return Tick label -*/ -const QwtText &QwtAbstractScaleDraw::tickLabel( - const QFont &font, double value ) const -{ - QMap::const_iterator it = d_data->labelCache.find( value ); - if ( it == d_data->labelCache.end() ) - { - QwtText lbl = label( value ); - lbl.setRenderFlags( 0 ); - lbl.setLayoutAttribute( QwtText::MinimumLayout ); - - ( void )lbl.textSize( font ); // initialize the internal cache - - it = d_data->labelCache.insert( value, lbl ); - } - - return ( *it ); -} - -/*! - Invalidate the cache used by QwtAbstractScaleDraw::tickLabel - - The cache is invalidated, when a new QwtScaleDiv is set. If - the labels need to be changed. while the same QwtScaleDiv is set, - invalidateCache() needs to be called manually. -*/ -void QwtAbstractScaleDraw::invalidateCache() -{ - d_data->labelCache.clear(); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_abstract_scale_draw.h" +#include "qwt_math.h" +#include "qwt_text.h" +#include "qwt_painter.h" +#include "qwt_scale_map.h" +#include +#include +#include +#include + +class QwtAbstractScaleDraw::PrivateData +{ +public: + PrivateData(): + spacing( 4.0 ), + penWidth( 0 ), + minExtent( 0.0 ) + { + components = QwtAbstractScaleDraw::Backbone + | QwtAbstractScaleDraw::Ticks + | QwtAbstractScaleDraw::Labels; + + tickLength[QwtScaleDiv::MinorTick] = 4.0; + tickLength[QwtScaleDiv::MediumTick] = 6.0; + tickLength[QwtScaleDiv::MajorTick] = 8.0; + } + + ScaleComponents components; + + QwtScaleMap map; + QwtScaleDiv scldiv; + + double spacing; + double tickLength[QwtScaleDiv::NTickTypes]; + int penWidth; + + double minExtent; + + QMap labelCache; +}; + +/*! + \brief Constructor + + The range of the scale is initialized to [0, 100], + The spacing (distance between ticks and labels) is + set to 4, the tick lengths are set to 4,6 and 8 pixels +*/ +QwtAbstractScaleDraw::QwtAbstractScaleDraw() +{ + d_data = new QwtAbstractScaleDraw::PrivateData; +} + +//! Destructor +QwtAbstractScaleDraw::~QwtAbstractScaleDraw() +{ + delete d_data; +} + +/*! + En/Disable a component of the scale + + \param component Scale component + \param enable On/Off + + \sa hasComponent() +*/ +void QwtAbstractScaleDraw::enableComponent( + ScaleComponent component, bool enable ) +{ + if ( enable ) + d_data->components |= component; + else + d_data->components &= ~component; +} + +/*! + Check if a component is enabled + \sa enableComponent() +*/ +bool QwtAbstractScaleDraw::hasComponent( ScaleComponent component ) const +{ + return ( d_data->components & component ); +} + +/*! + Change the scale division + \param sd New scale division +*/ +void QwtAbstractScaleDraw::setScaleDiv( const QwtScaleDiv &sd ) +{ + d_data->scldiv = sd; + d_data->map.setScaleInterval( sd.lowerBound(), sd.upperBound() ); + d_data->labelCache.clear(); +} + +/*! + Change the transformation of the scale + \param transformation New scale transformation +*/ +void QwtAbstractScaleDraw::setTransformation( + QwtScaleTransformation *transformation ) +{ + d_data->map.setTransformation( transformation ); +} + +//! \return Map how to translate between scale and pixel values +const QwtScaleMap &QwtAbstractScaleDraw::scaleMap() const +{ + return d_data->map; +} + +//! \return Map how to translate between scale and pixel values +QwtScaleMap &QwtAbstractScaleDraw::scaleMap() +{ + return d_data->map; +} + +//! \return scale division +const QwtScaleDiv& QwtAbstractScaleDraw::scaleDiv() const +{ + return d_data->scldiv; +} + +/*! + \brief Specify the width of the scale pen + \param width Pen width + \sa penWidth() +*/ +void QwtAbstractScaleDraw::setPenWidth( int width ) +{ + if ( width < 0 ) + width = 0; + + if ( width != d_data->penWidth ) + d_data->penWidth = width; +} + +/*! + \return Scale pen width + \sa setPenWidth() +*/ +int QwtAbstractScaleDraw::penWidth() const +{ + return d_data->penWidth; +} + +/*! + \brief Draw the scale + + \param painter The painter + + \param palette Palette, text color is used for the labels, + foreground color for ticks and backbone +*/ +void QwtAbstractScaleDraw::draw( QPainter *painter, + const QPalette& palette ) const +{ + painter->save(); + + QPen pen = painter->pen(); + pen.setWidth( d_data->penWidth ); + pen.setCosmetic( false ); + painter->setPen( pen ); + + if ( hasComponent( QwtAbstractScaleDraw::Labels ) ) + { + painter->save(); + painter->setPen( palette.color( QPalette::Text ) ); // ignore pen style + + const QList &majorTicks = + d_data->scldiv.ticks( QwtScaleDiv::MajorTick ); + + for ( int i = 0; i < majorTicks.count(); i++ ) + { + const double v = majorTicks[i]; + if ( d_data->scldiv.contains( v ) ) + drawLabel( painter, majorTicks[i] ); + } + + painter->restore(); + } + + if ( hasComponent( QwtAbstractScaleDraw::Ticks ) ) + { + painter->save(); + + QPen pen = painter->pen(); + pen.setColor( palette.color( QPalette::WindowText ) ); + pen.setCapStyle( Qt::FlatCap ); + + painter->setPen( pen ); + + for ( int tickType = QwtScaleDiv::MinorTick; + tickType < QwtScaleDiv::NTickTypes; tickType++ ) + { + const QList &ticks = d_data->scldiv.ticks( tickType ); + for ( int i = 0; i < ticks.count(); i++ ) + { + const double v = ticks[i]; + if ( d_data->scldiv.contains( v ) ) + drawTick( painter, v, d_data->tickLength[tickType] ); + } + } + + painter->restore(); + } + + if ( hasComponent( QwtAbstractScaleDraw::Backbone ) ) + { + painter->save(); + + QPen pen = painter->pen(); + pen.setColor( palette.color( QPalette::WindowText ) ); + pen.setCapStyle( Qt::FlatCap ); + + painter->setPen( pen ); + + drawBackbone( painter ); + + painter->restore(); + } + + painter->restore(); +} + +/*! + \brief Set the spacing between tick and labels + + The spacing is the distance between ticks and labels. + The default spacing is 4 pixels. + + \param spacing Spacing + + \sa spacing() +*/ +void QwtAbstractScaleDraw::setSpacing( double spacing ) +{ + if ( spacing < 0 ) + spacing = 0; + + d_data->spacing = spacing; +} + +/*! + \brief Get the spacing + + The spacing is the distance between ticks and labels. + The default spacing is 4 pixels. + + \sa setSpacing() +*/ +double QwtAbstractScaleDraw::spacing() const +{ + return d_data->spacing; +} + +/*! + \brief Set a minimum for the extent + + The extent is calculated from the coomponents of the + scale draw. In situations, where the labels are + changing and the layout depends on the extent (f.e scrolling + a scale), setting an upper limit as minimum extent will + avoid jumps of the layout. + + \param minExtent Minimum extent + + \sa extent(), minimumExtent() +*/ +void QwtAbstractScaleDraw::setMinimumExtent( double minExtent ) +{ + if ( minExtent < 0.0 ) + minExtent = 0.0; + + d_data->minExtent = minExtent; +} + +/*! + Get the minimum extent + \sa extent(), setMinimumExtent() +*/ +double QwtAbstractScaleDraw::minimumExtent() const +{ + return d_data->minExtent; +} + +/*! + Set the length of the ticks + + \param tickType Tick type + \param length New length + + \warning the length is limited to [0..1000] +*/ +void QwtAbstractScaleDraw::setTickLength( + QwtScaleDiv::TickType tickType, double length ) +{ + if ( tickType < QwtScaleDiv::MinorTick || + tickType > QwtScaleDiv::MajorTick ) + { + return; + } + + if ( length < 0.0 ) + length = 0.0; + + const double maxTickLen = 1000.0; + if ( length > maxTickLen ) + length = maxTickLen; + + d_data->tickLength[tickType] = length; +} + +/*! + Return the length of the ticks + + \sa setTickLength(), maxTickLength() +*/ +double QwtAbstractScaleDraw::tickLength( QwtScaleDiv::TickType tickType ) const +{ + if ( tickType < QwtScaleDiv::MinorTick || + tickType > QwtScaleDiv::MajorTick ) + { + return 0; + } + + return d_data->tickLength[tickType]; +} + +/*! + \return Length of the longest tick + + Useful for layout calculations + \sa tickLength(), setTickLength() +*/ +double QwtAbstractScaleDraw::maxTickLength() const +{ + double length = 0.0; + for ( int i = 0; i < QwtScaleDiv::NTickTypes; i++ ) + length = qMax( length, d_data->tickLength[i] ); + + return length; +} + +/*! + \brief Convert a value into its representing label + + The value is converted to a plain text using + QLocale::system().toString(value). + This method is often overloaded by applications to have individual + labels. + + \param value Value + \return Label string. +*/ +QwtText QwtAbstractScaleDraw::label( double value ) const +{ + return QLocale().toString( value ); +} + +/*! + \brief Convert a value into its representing label and cache it. + + The conversion between value and label is called very often + in the layout and painting code. Unfortunately the + calculation of the label sizes might be slow (really slow + for rich text in Qt4), so it's necessary to cache the labels. + + \param font Font + \param value Value + + \return Tick label +*/ +const QwtText &QwtAbstractScaleDraw::tickLabel( + const QFont &font, double value ) const +{ + QMap::const_iterator it = d_data->labelCache.find( value ); + if ( it == d_data->labelCache.end() ) + { + QwtText lbl = label( value ); + lbl.setRenderFlags( 0 ); + lbl.setLayoutAttribute( QwtText::MinimumLayout ); + + ( void )lbl.textSize( font ); // initialize the internal cache + + it = d_data->labelCache.insert( value, lbl ); + } + + return ( *it ); +} + +/*! + Invalidate the cache used by QwtAbstractScaleDraw::tickLabel + + The cache is invalidated, when a new QwtScaleDiv is set. If + the labels need to be changed. while the same QwtScaleDiv is set, + invalidateCache() needs to be called manually. +*/ +void QwtAbstractScaleDraw::invalidateCache() +{ + d_data->labelCache.clear(); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale_draw.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale_draw.h index bd5150470..1dd64c03b 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale_draw.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_scale_draw.h @@ -1,139 +1,139 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_ABSTRACT_SCALE_DRAW_H -#define QWT_ABSTRACT_SCALE_DRAW_H - -#include "qwt_global.h" -#include "qwt_scale_div.h" -#include "qwt_text.h" - -class QPalette; -class QPainter; -class QFont; -class QwtScaleTransformation; -class QwtScaleMap; - -/*! - \brief A abstract base class for drawing scales - - QwtAbstractScaleDraw can be used to draw linear or logarithmic scales. - - After a scale division has been specified as a QwtScaleDiv object - using QwtAbstractScaleDraw::setScaleDiv(const QwtScaleDiv &s), - the scale can be drawn with the QwtAbstractScaleDraw::draw() member. -*/ -class QWT_EXPORT QwtAbstractScaleDraw -{ -public: - - /*! - Components of a scale - \sa enableComponent(), hasComponent - */ - enum ScaleComponent - { - //! Backbone = the line where the ticks are located - Backbone = 0x01, - - //! Ticks - Ticks = 0x02, - - //! Labels - Labels = 0x04 - }; - - //! Scale components - typedef QFlags ScaleComponents; - - QwtAbstractScaleDraw(); - virtual ~QwtAbstractScaleDraw(); - - void setScaleDiv( const QwtScaleDiv &s ); - const QwtScaleDiv& scaleDiv() const; - - void setTransformation( QwtScaleTransformation * ); - const QwtScaleMap &scaleMap() const; - QwtScaleMap &scaleMap(); - - void enableComponent( ScaleComponent, bool enable = true ); - bool hasComponent( ScaleComponent ) const; - - void setTickLength( QwtScaleDiv::TickType, double length ); - double tickLength( QwtScaleDiv::TickType ) const; - double maxTickLength() const; - - void setSpacing( double margin ); - double spacing() const; - - void setPenWidth( int width ); - int penWidth() const; - - virtual void draw( QPainter *, const QPalette & ) const; - - virtual QwtText label( double ) const; - - /*! - Calculate the extent - - The extent is the distcance from the baseline to the outermost - pixel of the scale draw in opposite to its orientation. - It is at least minimumExtent() pixels. - - \sa setMinimumExtent(), minimumExtent() - */ - virtual double extent( const QFont & ) const = 0; - - void setMinimumExtent( double ); - double minimumExtent() const; - -protected: - /*! - Draw a tick - - \param painter Painter - \param value Value of the tick - \param len Lenght of the tick - - \sa drawBackbone(), drawLabel() - */ - virtual void drawTick( QPainter *painter, double value, double len ) const = 0; - - /*! - Draws the baseline of the scale - \param painter Painter - - \sa drawTick(), drawLabel() - */ - virtual void drawBackbone( QPainter *painter ) const = 0; - - /*! - Draws the label for a major scale tick - - \param painter Painter - \param value Value - - \sa drawTick(), drawBackbone() - */ - virtual void drawLabel( QPainter *painter, double value ) const = 0; - - void invalidateCache(); - const QwtText &tickLabel( const QFont &, double value ) const; - -private: - QwtAbstractScaleDraw( const QwtAbstractScaleDraw & ); - QwtAbstractScaleDraw &operator=( const QwtAbstractScaleDraw & ); - - class PrivateData; - PrivateData *d_data; -}; - -Q_DECLARE_OPERATORS_FOR_FLAGS( QwtAbstractScaleDraw::ScaleComponents ) - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_ABSTRACT_SCALE_DRAW_H +#define QWT_ABSTRACT_SCALE_DRAW_H + +#include "qwt_global.h" +#include "qwt_scale_div.h" +#include "qwt_text.h" + +class QPalette; +class QPainter; +class QFont; +class QwtScaleTransformation; +class QwtScaleMap; + +/*! + \brief A abstract base class for drawing scales + + QwtAbstractScaleDraw can be used to draw linear or logarithmic scales. + + After a scale division has been specified as a QwtScaleDiv object + using QwtAbstractScaleDraw::setScaleDiv(const QwtScaleDiv &s), + the scale can be drawn with the QwtAbstractScaleDraw::draw() member. +*/ +class QWT_EXPORT QwtAbstractScaleDraw +{ +public: + + /*! + Components of a scale + \sa enableComponent(), hasComponent + */ + enum ScaleComponent + { + //! Backbone = the line where the ticks are located + Backbone = 0x01, + + //! Ticks + Ticks = 0x02, + + //! Labels + Labels = 0x04 + }; + + //! Scale components + typedef QFlags ScaleComponents; + + QwtAbstractScaleDraw(); + virtual ~QwtAbstractScaleDraw(); + + void setScaleDiv( const QwtScaleDiv &s ); + const QwtScaleDiv& scaleDiv() const; + + void setTransformation( QwtScaleTransformation * ); + const QwtScaleMap &scaleMap() const; + QwtScaleMap &scaleMap(); + + void enableComponent( ScaleComponent, bool enable = true ); + bool hasComponent( ScaleComponent ) const; + + void setTickLength( QwtScaleDiv::TickType, double length ); + double tickLength( QwtScaleDiv::TickType ) const; + double maxTickLength() const; + + void setSpacing( double margin ); + double spacing() const; + + void setPenWidth( int width ); + int penWidth() const; + + virtual void draw( QPainter *, const QPalette & ) const; + + virtual QwtText label( double ) const; + + /*! + Calculate the extent + + The extent is the distcance from the baseline to the outermost + pixel of the scale draw in opposite to its orientation. + It is at least minimumExtent() pixels. + + \sa setMinimumExtent(), minimumExtent() + */ + virtual double extent( const QFont & ) const = 0; + + void setMinimumExtent( double ); + double minimumExtent() const; + +protected: + /*! + Draw a tick + + \param painter Painter + \param value Value of the tick + \param len Lenght of the tick + + \sa drawBackbone(), drawLabel() + */ + virtual void drawTick( QPainter *painter, double value, double len ) const = 0; + + /*! + Draws the baseline of the scale + \param painter Painter + + \sa drawTick(), drawLabel() + */ + virtual void drawBackbone( QPainter *painter ) const = 0; + + /*! + Draws the label for a major scale tick + + \param painter Painter + \param value Value + + \sa drawTick(), drawBackbone() + */ + virtual void drawLabel( QPainter *painter, double value ) const = 0; + + void invalidateCache(); + const QwtText &tickLabel( const QFont &, double value ) const; + +private: + QwtAbstractScaleDraw( const QwtAbstractScaleDraw & ); + QwtAbstractScaleDraw &operator=( const QwtAbstractScaleDraw & ); + + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtAbstractScaleDraw::ScaleComponents ) + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_slider.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_slider.cpp index b0c127d9e..e2dbcff58 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_slider.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_slider.cpp @@ -1,597 +1,597 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_abstract_slider.h" -#include "qwt_math.h" -#include -#include - -#if QT_VERSION < 0x040601 -#define qFabs(x) ::fabs(x) -#define qExp(x) ::exp(x) -#endif - -class QwtAbstractSlider::PrivateData -{ -public: - PrivateData(): - scrollMode( QwtAbstractSlider::ScrNone ), - mouseOffset( 0.0 ), - tracking( true ), - tmrID( 0 ), - updTime( 150 ), - mass( 0.0 ), - readOnly( false ) - { - } - - QwtAbstractSlider::ScrollMode scrollMode; - double mouseOffset; - int direction; - int tracking; - - int tmrID; - int updTime; - int timerTick; - QTime time; - double speed; - double mass; - Qt::Orientation orientation; - bool readOnly; -}; - -/*! - \brief Constructor - - \param orientation Orientation - \param parent Parent widget -*/ -QwtAbstractSlider::QwtAbstractSlider( - Qt::Orientation orientation, QWidget *parent ): - QWidget( parent, NULL ) -{ - d_data = new QwtAbstractSlider::PrivateData; - d_data->orientation = orientation; - - setFocusPolicy( Qt::TabFocus ); -} - -//! Destructor -QwtAbstractSlider::~QwtAbstractSlider() -{ - if ( d_data->tmrID ) - killTimer( d_data->tmrID ); - - delete d_data; -} - -/*! - En/Disable read only mode - - In read only mode the slider can't be controlled by mouse - or keyboard. - - \param readOnly Enables in case of true - \sa isReadOnly() -*/ -void QwtAbstractSlider::setReadOnly( bool readOnly ) -{ - d_data->readOnly = readOnly; - update(); -} - -/*! - In read only mode the slider can't be controlled by mouse - or keyboard. - - \return true if read only - \sa setReadOnly() -*/ -bool QwtAbstractSlider::isReadOnly() const -{ - return d_data->readOnly; -} - -/*! - \brief Set the orientation. - \param o Orientation. Allowed values are - Qt::Horizontal and Qt::Vertical. -*/ -void QwtAbstractSlider::setOrientation( Qt::Orientation o ) -{ - d_data->orientation = o; -} - -/*! - \return Orientation - \sa setOrientation() -*/ -Qt::Orientation QwtAbstractSlider::orientation() const -{ - return d_data->orientation; -} - -//! Stop updating if automatic scrolling is active - -void QwtAbstractSlider::stopMoving() -{ - if ( d_data->tmrID ) - { - killTimer( d_data->tmrID ); - d_data->tmrID = 0; - } -} - -/*! - \brief Specify the update interval for automatic scrolling - \param t update interval in milliseconds - \sa getScrollMode() -*/ -void QwtAbstractSlider::setUpdateTime( int t ) -{ - if ( t < 50 ) - t = 50; - d_data->updTime = t; -} - - -/*! - Mouse press event handler - \param e Mouse event -*/ -void QwtAbstractSlider::mousePressEvent( QMouseEvent *e ) -{ - if ( isReadOnly() ) - { - e->ignore(); - return; - } - if ( !isValid() ) - return; - - const QPoint &p = e->pos(); - - d_data->timerTick = 0; - - getScrollMode( p, d_data->scrollMode, d_data->direction ); - stopMoving(); - - switch ( d_data->scrollMode ) - { - case ScrPage: - case ScrTimer: - d_data->mouseOffset = 0; - d_data->tmrID = startTimer( qMax( 250, 2 * d_data->updTime ) ); - break; - - case ScrMouse: - d_data->time.start(); - d_data->speed = 0; - d_data->mouseOffset = getValue( p ) - value(); - Q_EMIT sliderPressed(); - break; - - default: - d_data->mouseOffset = 0; - d_data->direction = 0; - break; - } -} - - -//! Emits a valueChanged() signal if necessary -void QwtAbstractSlider::buttonReleased() -{ - if ( ( !d_data->tracking ) || ( value() != prevValue() ) ) - Q_EMIT valueChanged( value() ); -} - - -/*! - Mouse Release Event handler - \param e Mouse event -*/ -void QwtAbstractSlider::mouseReleaseEvent( QMouseEvent *e ) -{ - if ( isReadOnly() ) - { - e->ignore(); - return; - } - if ( !isValid() ) - return; - - const double inc = step(); - - switch ( d_data->scrollMode ) - { - case ScrMouse: - { - setPosition( e->pos() ); - d_data->direction = 0; - d_data->mouseOffset = 0; - if ( d_data->mass > 0.0 ) - { - const int ms = d_data->time.elapsed(); - if ( ( qFabs( d_data->speed ) > 0.0 ) && ( ms < 50 ) ) - d_data->tmrID = startTimer( d_data->updTime ); - } - else - { - d_data->scrollMode = ScrNone; - buttonReleased(); - } - Q_EMIT sliderReleased(); - - break; - } - - case ScrDirect: - { - setPosition( e->pos() ); - d_data->direction = 0; - d_data->mouseOffset = 0; - d_data->scrollMode = ScrNone; - buttonReleased(); - break; - } - - case ScrPage: - { - stopMoving(); - if ( !d_data->timerTick ) - QwtDoubleRange::incPages( d_data->direction ); - d_data->timerTick = 0; - buttonReleased(); - d_data->scrollMode = ScrNone; - break; - } - - case ScrTimer: - { - stopMoving(); - if ( !d_data->timerTick ) - QwtDoubleRange::fitValue( value() + double( d_data->direction ) * inc ); - d_data->timerTick = 0; - buttonReleased(); - d_data->scrollMode = ScrNone; - break; - } - - default: - { - d_data->scrollMode = ScrNone; - buttonReleased(); - } - } -} - - -/*! - Move the slider to a specified point, adjust the value - and emit signals if necessary. -*/ -void QwtAbstractSlider::setPosition( const QPoint &p ) -{ - QwtDoubleRange::fitValue( getValue( p ) - d_data->mouseOffset ); -} - - -/*! - \brief Enables or disables tracking. - - If tracking is enabled, the slider emits a - valueChanged() signal whenever its value - changes (the default behaviour). If tracking - is disabled, the value changed() signal will only - be emitted if:
    -
  • the user releases the mouse - button and the value has changed or -
  • at the end of automatic scrolling.
- Tracking is enabled by default. - \param enable \c true (enable) or \c false (disable) tracking. -*/ -void QwtAbstractSlider::setTracking( bool enable ) -{ - d_data->tracking = enable; -} - -/*! - Mouse Move Event handler - \param e Mouse event -*/ -void QwtAbstractSlider::mouseMoveEvent( QMouseEvent *e ) -{ - if ( isReadOnly() ) - { - e->ignore(); - return; - } - - if ( !isValid() ) - return; - - if ( d_data->scrollMode == ScrMouse ) - { - setPosition( e->pos() ); - if ( d_data->mass > 0.0 ) - { - double ms = double( d_data->time.elapsed() ); - if ( ms < 1.0 ) - ms = 1.0; - d_data->speed = ( exactValue() - exactPrevValue() ) / ms; - d_data->time.start(); - } - if ( value() != prevValue() ) - Q_EMIT sliderMoved( value() ); - } -} - -/*! - Wheel Event handler - \param e Whell event -*/ -void QwtAbstractSlider::wheelEvent( QWheelEvent *e ) -{ - if ( isReadOnly() ) - { - e->ignore(); - return; - } - - if ( !isValid() ) - return; - - QwtAbstractSlider::ScrollMode mode = ScrNone; - int direction = 0; - - // Give derived classes a chance to say ScrNone - getScrollMode( e->pos(), mode, direction ); - if ( mode != QwtAbstractSlider::ScrNone ) - { - // Most mouse types work in steps of 15 degrees, in which case - // the delta value is a multiple of 120 - - const int inc = e->delta() / 120; - QwtDoubleRange::incPages( inc ); - if ( value() != prevValue() ) - Q_EMIT sliderMoved( value() ); - } -} - -/*! - Handles key events - - - Key_Down, KeyLeft\n - Decrement by 1 - - Key_Up, Key_Right\n - Increment by 1 - - \param e Key event - \sa isReadOnly() -*/ -void QwtAbstractSlider::keyPressEvent( QKeyEvent *e ) -{ - if ( isReadOnly() ) - { - e->ignore(); - return; - } - - if ( !isValid() ) - return; - - int increment = 0; - switch ( e->key() ) - { - case Qt::Key_Down: - if ( orientation() == Qt::Vertical ) - increment = -1; - break; - case Qt::Key_Up: - if ( orientation() == Qt::Vertical ) - increment = 1; - break; - case Qt::Key_Left: - if ( orientation() == Qt::Horizontal ) - increment = -1; - break; - case Qt::Key_Right: - if ( orientation() == Qt::Horizontal ) - increment = 1; - break; - default:; - e->ignore(); - } - - if ( increment != 0 ) - { - QwtDoubleRange::incValue( increment ); - if ( value() != prevValue() ) - Q_EMIT sliderMoved( value() ); - } -} - -/*! - Qt timer event - \param e Timer event -*/ -void QwtAbstractSlider::timerEvent( QTimerEvent * ) -{ - const double inc = step(); - - switch ( d_data->scrollMode ) - { - case ScrMouse: - { - if ( d_data->mass > 0.0 ) - { - d_data->speed *= qExp( - double( d_data->updTime ) * 0.001 / d_data->mass ); - const double newval = - exactValue() + d_data->speed * double( d_data->updTime ); - QwtDoubleRange::fitValue( newval ); - // stop if d_data->speed < one step per second - if ( qFabs( d_data->speed ) < 0.001 * qFabs( step() ) ) - { - d_data->speed = 0; - stopMoving(); - buttonReleased(); - } - - } - else - stopMoving(); - break; - } - - case ScrPage: - { - QwtDoubleRange::incPages( d_data->direction ); - if ( !d_data->timerTick ) - { - killTimer( d_data->tmrID ); - d_data->tmrID = startTimer( d_data->updTime ); - } - break; - } - case ScrTimer: - { - QwtDoubleRange::fitValue( value() + double( d_data->direction ) * inc ); - if ( !d_data->timerTick ) - { - killTimer( d_data->tmrID ); - d_data->tmrID = startTimer( d_data->updTime ); - } - break; - } - default: - { - stopMoving(); - break; - } - } - - d_data->timerTick = 1; -} - - -/*! - Notify change of value - - This function can be reimplemented by derived classes - in order to keep track of changes, i.e. repaint the widget. - The default implementation emits a valueChanged() signal - if tracking is enabled. -*/ -void QwtAbstractSlider::valueChange() -{ - if ( d_data->tracking ) - Q_EMIT valueChanged( value() ); -} - -/*! - \brief Set the slider's mass for flywheel effect. - - If the slider's mass is greater then 0, it will continue - to move after the mouse button has been released. Its speed - decreases with time at a rate depending on the slider's mass. - A large mass means that it will continue to move for a - long time. - - Derived widgets may overload this function to make it public. - - \param val New mass in kg - - \bug If the mass is smaller than 1g, it is set to zero. - The maximal mass is limited to 100kg. - \sa mass() -*/ -void QwtAbstractSlider::setMass( double val ) -{ - if ( val < 0.001 ) - d_data->mass = 0.0; - else if ( val > 100.0 ) - d_data->mass = 100.0; - else - d_data->mass = val; -} - -/*! - \return mass - \sa setMass() -*/ -double QwtAbstractSlider::mass() const -{ - return d_data->mass; -} - - -/*! - \brief Move the slider to a specified value - - This function can be used to move the slider to a value - which is not an integer multiple of the step size. - \param val new value - \sa fitValue() -*/ -void QwtAbstractSlider::setValue( double val ) -{ - if ( d_data->scrollMode == ScrMouse ) - stopMoving(); - QwtDoubleRange::setValue( val ); -} - - -/*! - \brief Set the slider's value to the nearest integer multiple - of the step size. - - \param value Value - \sa setValue(), incValue() -*/ -void QwtAbstractSlider::fitValue( double value ) -{ - if ( d_data->scrollMode == ScrMouse ) - stopMoving(); - QwtDoubleRange::fitValue( value ); -} - -/*! - \brief Increment the value by a specified number of steps - \param steps number of steps - \sa setValue() -*/ -void QwtAbstractSlider::incValue( int steps ) -{ - if ( d_data->scrollMode == ScrMouse ) - stopMoving(); - QwtDoubleRange::incValue( steps ); -} - -/*! - \sa mouseOffset() -*/ -void QwtAbstractSlider::setMouseOffset( double offset ) -{ - d_data->mouseOffset = offset; -} - -/*! - \sa setMouseOffset() -*/ -double QwtAbstractSlider::mouseOffset() const -{ - return d_data->mouseOffset; -} - -//! sa ScrollMode -int QwtAbstractSlider::scrollMode() const -{ - return d_data->scrollMode; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_abstract_slider.h" +#include "qwt_math.h" +#include +#include + +#if QT_VERSION < 0x040601 +#define qFabs(x) ::fabs(x) +#define qExp(x) ::exp(x) +#endif + +class QwtAbstractSlider::PrivateData +{ +public: + PrivateData(): + scrollMode( QwtAbstractSlider::ScrNone ), + mouseOffset( 0.0 ), + tracking( true ), + tmrID( 0 ), + updTime( 150 ), + mass( 0.0 ), + readOnly( false ) + { + } + + QwtAbstractSlider::ScrollMode scrollMode; + double mouseOffset; + int direction; + int tracking; + + int tmrID; + int updTime; + int timerTick; + QTime time; + double speed; + double mass; + Qt::Orientation orientation; + bool readOnly; +}; + +/*! + \brief Constructor + + \param orientation Orientation + \param parent Parent widget +*/ +QwtAbstractSlider::QwtAbstractSlider( + Qt::Orientation orientation, QWidget *parent ): + QWidget( parent, NULL ) +{ + d_data = new QwtAbstractSlider::PrivateData; + d_data->orientation = orientation; + + setFocusPolicy( Qt::TabFocus ); +} + +//! Destructor +QwtAbstractSlider::~QwtAbstractSlider() +{ + if ( d_data->tmrID ) + killTimer( d_data->tmrID ); + + delete d_data; +} + +/*! + En/Disable read only mode + + In read only mode the slider can't be controlled by mouse + or keyboard. + + \param readOnly Enables in case of true + \sa isReadOnly() +*/ +void QwtAbstractSlider::setReadOnly( bool readOnly ) +{ + d_data->readOnly = readOnly; + update(); +} + +/*! + In read only mode the slider can't be controlled by mouse + or keyboard. + + \return true if read only + \sa setReadOnly() +*/ +bool QwtAbstractSlider::isReadOnly() const +{ + return d_data->readOnly; +} + +/*! + \brief Set the orientation. + \param o Orientation. Allowed values are + Qt::Horizontal and Qt::Vertical. +*/ +void QwtAbstractSlider::setOrientation( Qt::Orientation o ) +{ + d_data->orientation = o; +} + +/*! + \return Orientation + \sa setOrientation() +*/ +Qt::Orientation QwtAbstractSlider::orientation() const +{ + return d_data->orientation; +} + +//! Stop updating if automatic scrolling is active + +void QwtAbstractSlider::stopMoving() +{ + if ( d_data->tmrID ) + { + killTimer( d_data->tmrID ); + d_data->tmrID = 0; + } +} + +/*! + \brief Specify the update interval for automatic scrolling + \param t update interval in milliseconds + \sa getScrollMode() +*/ +void QwtAbstractSlider::setUpdateTime( int t ) +{ + if ( t < 50 ) + t = 50; + d_data->updTime = t; +} + + +/*! + Mouse press event handler + \param e Mouse event +*/ +void QwtAbstractSlider::mousePressEvent( QMouseEvent *e ) +{ + if ( isReadOnly() ) + { + e->ignore(); + return; + } + if ( !isValid() ) + return; + + const QPoint &p = e->pos(); + + d_data->timerTick = 0; + + getScrollMode( p, d_data->scrollMode, d_data->direction ); + stopMoving(); + + switch ( d_data->scrollMode ) + { + case ScrPage: + case ScrTimer: + d_data->mouseOffset = 0; + d_data->tmrID = startTimer( qMax( 250, 2 * d_data->updTime ) ); + break; + + case ScrMouse: + d_data->time.start(); + d_data->speed = 0; + d_data->mouseOffset = getValue( p ) - value(); + Q_EMIT sliderPressed(); + break; + + default: + d_data->mouseOffset = 0; + d_data->direction = 0; + break; + } +} + + +//! Emits a valueChanged() signal if necessary +void QwtAbstractSlider::buttonReleased() +{ + if ( ( !d_data->tracking ) || ( value() != prevValue() ) ) + Q_EMIT valueChanged( value() ); +} + + +/*! + Mouse Release Event handler + \param e Mouse event +*/ +void QwtAbstractSlider::mouseReleaseEvent( QMouseEvent *e ) +{ + if ( isReadOnly() ) + { + e->ignore(); + return; + } + if ( !isValid() ) + return; + + const double inc = step(); + + switch ( d_data->scrollMode ) + { + case ScrMouse: + { + setPosition( e->pos() ); + d_data->direction = 0; + d_data->mouseOffset = 0; + if ( d_data->mass > 0.0 ) + { + const int ms = d_data->time.elapsed(); + if ( ( qFabs( d_data->speed ) > 0.0 ) && ( ms < 50 ) ) + d_data->tmrID = startTimer( d_data->updTime ); + } + else + { + d_data->scrollMode = ScrNone; + buttonReleased(); + } + Q_EMIT sliderReleased(); + + break; + } + + case ScrDirect: + { + setPosition( e->pos() ); + d_data->direction = 0; + d_data->mouseOffset = 0; + d_data->scrollMode = ScrNone; + buttonReleased(); + break; + } + + case ScrPage: + { + stopMoving(); + if ( !d_data->timerTick ) + QwtDoubleRange::incPages( d_data->direction ); + d_data->timerTick = 0; + buttonReleased(); + d_data->scrollMode = ScrNone; + break; + } + + case ScrTimer: + { + stopMoving(); + if ( !d_data->timerTick ) + QwtDoubleRange::fitValue( value() + double( d_data->direction ) * inc ); + d_data->timerTick = 0; + buttonReleased(); + d_data->scrollMode = ScrNone; + break; + } + + default: + { + d_data->scrollMode = ScrNone; + buttonReleased(); + } + } +} + + +/*! + Move the slider to a specified point, adjust the value + and emit signals if necessary. +*/ +void QwtAbstractSlider::setPosition( const QPoint &p ) +{ + QwtDoubleRange::fitValue( getValue( p ) - d_data->mouseOffset ); +} + + +/*! + \brief Enables or disables tracking. + + If tracking is enabled, the slider emits a + valueChanged() signal whenever its value + changes (the default behaviour). If tracking + is disabled, the value changed() signal will only + be emitted if:
    +
  • the user releases the mouse + button and the value has changed or +
  • at the end of automatic scrolling.
+ Tracking is enabled by default. + \param enable \c true (enable) or \c false (disable) tracking. +*/ +void QwtAbstractSlider::setTracking( bool enable ) +{ + d_data->tracking = enable; +} + +/*! + Mouse Move Event handler + \param e Mouse event +*/ +void QwtAbstractSlider::mouseMoveEvent( QMouseEvent *e ) +{ + if ( isReadOnly() ) + { + e->ignore(); + return; + } + + if ( !isValid() ) + return; + + if ( d_data->scrollMode == ScrMouse ) + { + setPosition( e->pos() ); + if ( d_data->mass > 0.0 ) + { + double ms = double( d_data->time.elapsed() ); + if ( ms < 1.0 ) + ms = 1.0; + d_data->speed = ( exactValue() - exactPrevValue() ) / ms; + d_data->time.start(); + } + if ( value() != prevValue() ) + Q_EMIT sliderMoved( value() ); + } +} + +/*! + Wheel Event handler + \param e Whell event +*/ +void QwtAbstractSlider::wheelEvent( QWheelEvent *e ) +{ + if ( isReadOnly() ) + { + e->ignore(); + return; + } + + if ( !isValid() ) + return; + + QwtAbstractSlider::ScrollMode mode = ScrNone; + int direction = 0; + + // Give derived classes a chance to say ScrNone + getScrollMode( e->pos(), mode, direction ); + if ( mode != QwtAbstractSlider::ScrNone ) + { + // Most mouse types work in steps of 15 degrees, in which case + // the delta value is a multiple of 120 + + const int inc = e->delta() / 120; + QwtDoubleRange::incPages( inc ); + if ( value() != prevValue() ) + Q_EMIT sliderMoved( value() ); + } +} + +/*! + Handles key events + + - Key_Down, KeyLeft\n + Decrement by 1 + - Key_Up, Key_Right\n + Increment by 1 + + \param e Key event + \sa isReadOnly() +*/ +void QwtAbstractSlider::keyPressEvent( QKeyEvent *e ) +{ + if ( isReadOnly() ) + { + e->ignore(); + return; + } + + if ( !isValid() ) + return; + + int increment = 0; + switch ( e->key() ) + { + case Qt::Key_Down: + if ( orientation() == Qt::Vertical ) + increment = -1; + break; + case Qt::Key_Up: + if ( orientation() == Qt::Vertical ) + increment = 1; + break; + case Qt::Key_Left: + if ( orientation() == Qt::Horizontal ) + increment = -1; + break; + case Qt::Key_Right: + if ( orientation() == Qt::Horizontal ) + increment = 1; + break; + default:; + e->ignore(); + } + + if ( increment != 0 ) + { + QwtDoubleRange::incValue( increment ); + if ( value() != prevValue() ) + Q_EMIT sliderMoved( value() ); + } +} + +/*! + Qt timer event + \param e Timer event +*/ +void QwtAbstractSlider::timerEvent( QTimerEvent * ) +{ + const double inc = step(); + + switch ( d_data->scrollMode ) + { + case ScrMouse: + { + if ( d_data->mass > 0.0 ) + { + d_data->speed *= qExp( - double( d_data->updTime ) * 0.001 / d_data->mass ); + const double newval = + exactValue() + d_data->speed * double( d_data->updTime ); + QwtDoubleRange::fitValue( newval ); + // stop if d_data->speed < one step per second + if ( qFabs( d_data->speed ) < 0.001 * qFabs( step() ) ) + { + d_data->speed = 0; + stopMoving(); + buttonReleased(); + } + + } + else + stopMoving(); + break; + } + + case ScrPage: + { + QwtDoubleRange::incPages( d_data->direction ); + if ( !d_data->timerTick ) + { + killTimer( d_data->tmrID ); + d_data->tmrID = startTimer( d_data->updTime ); + } + break; + } + case ScrTimer: + { + QwtDoubleRange::fitValue( value() + double( d_data->direction ) * inc ); + if ( !d_data->timerTick ) + { + killTimer( d_data->tmrID ); + d_data->tmrID = startTimer( d_data->updTime ); + } + break; + } + default: + { + stopMoving(); + break; + } + } + + d_data->timerTick = 1; +} + + +/*! + Notify change of value + + This function can be reimplemented by derived classes + in order to keep track of changes, i.e. repaint the widget. + The default implementation emits a valueChanged() signal + if tracking is enabled. +*/ +void QwtAbstractSlider::valueChange() +{ + if ( d_data->tracking ) + Q_EMIT valueChanged( value() ); +} + +/*! + \brief Set the slider's mass for flywheel effect. + + If the slider's mass is greater then 0, it will continue + to move after the mouse button has been released. Its speed + decreases with time at a rate depending on the slider's mass. + A large mass means that it will continue to move for a + long time. + + Derived widgets may overload this function to make it public. + + \param val New mass in kg + + \bug If the mass is smaller than 1g, it is set to zero. + The maximal mass is limited to 100kg. + \sa mass() +*/ +void QwtAbstractSlider::setMass( double val ) +{ + if ( val < 0.001 ) + d_data->mass = 0.0; + else if ( val > 100.0 ) + d_data->mass = 100.0; + else + d_data->mass = val; +} + +/*! + \return mass + \sa setMass() +*/ +double QwtAbstractSlider::mass() const +{ + return d_data->mass; +} + + +/*! + \brief Move the slider to a specified value + + This function can be used to move the slider to a value + which is not an integer multiple of the step size. + \param val new value + \sa fitValue() +*/ +void QwtAbstractSlider::setValue( double val ) +{ + if ( d_data->scrollMode == ScrMouse ) + stopMoving(); + QwtDoubleRange::setValue( val ); +} + + +/*! + \brief Set the slider's value to the nearest integer multiple + of the step size. + + \param value Value + \sa setValue(), incValue() +*/ +void QwtAbstractSlider::fitValue( double value ) +{ + if ( d_data->scrollMode == ScrMouse ) + stopMoving(); + QwtDoubleRange::fitValue( value ); +} + +/*! + \brief Increment the value by a specified number of steps + \param steps number of steps + \sa setValue() +*/ +void QwtAbstractSlider::incValue( int steps ) +{ + if ( d_data->scrollMode == ScrMouse ) + stopMoving(); + QwtDoubleRange::incValue( steps ); +} + +/*! + \sa mouseOffset() +*/ +void QwtAbstractSlider::setMouseOffset( double offset ) +{ + d_data->mouseOffset = offset; +} + +/*! + \sa setMouseOffset() +*/ +double QwtAbstractSlider::mouseOffset() const +{ + return d_data->mouseOffset; +} + +//! sa ScrollMode +int QwtAbstractSlider::scrollMode() const +{ + return d_data->scrollMode; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_slider.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_slider.h index ab36b53c2..d9facbbed 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_slider.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_abstract_slider.h @@ -1,188 +1,188 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_ABSTRACT_SLIDER_H -#define QWT_ABSTRACT_SLIDER_H - -#include "qwt_global.h" -#include "qwt_double_range.h" -#include - -/*! - \brief An abstract base class for slider widgets - - QwtAbstractSlider is a base class for - slider widgets. It handles mouse events - and updates the slider's value accordingly. Derived classes - only have to implement the getValue() and - getScrollMode() members, and should react to a - valueChange(), which normally requires repainting. -*/ - -class QWT_EXPORT QwtAbstractSlider : public QWidget, public QwtDoubleRange -{ - Q_OBJECT - Q_PROPERTY( bool readOnly READ isReadOnly WRITE setReadOnly ) - Q_PROPERTY( bool valid READ isValid WRITE setValid ) - Q_PROPERTY( double mass READ mass WRITE setMass ) - Q_PROPERTY( Qt::Orientation orientation - READ orientation WRITE setOrientation ) - -public: - /*! - Scroll mode - \sa getScrollMode() - */ - enum ScrollMode - { - //! Scrolling switched off. Don't change the value. - ScrNone, - - /*! - Change the value while the user keeps the - button pressed and moves the mouse. - */ - ScrMouse, - - /*! - Automatic scrolling. Increment the value in the specified direction - as long as the user keeps the button pressed. - */ - ScrTimer, - - ScrDirect, - - //! Automatic scrolling. Same as ScrTimer, but increment by page size. - ScrPage - }; - - explicit QwtAbstractSlider( Qt::Orientation, QWidget *parent = NULL ); - virtual ~QwtAbstractSlider(); - - void setUpdateTime( int t ); - void stopMoving(); - void setTracking( bool enable ); - - virtual void setMass( double val ); - virtual double mass() const; - - virtual void setOrientation( Qt::Orientation o ); - Qt::Orientation orientation() const; - - bool isReadOnly() const; - - /* - Wrappers for QwtDblRange::isValid/QwtDblRange::setValid made - to be available as Q_PROPERTY in the designer. - */ - - /*! - \sa QwtDblRange::isValid() - */ - bool isValid() const - { - return QwtDoubleRange::isValid(); - } - - /*! - \param valid true/false - \sa QwtDblRange::isValid() - */ - void setValid( bool valid ) - { - QwtDoubleRange::setValid( valid ); - } - -public Q_SLOTS: - virtual void setValue( double val ); - virtual void fitValue( double val ); - virtual void incValue( int steps ); - - virtual void setReadOnly( bool ); - -Q_SIGNALS: - - /*! - \brief Notify a change of value. - - In the default setting - (tracking enabled), this signal will be emitted every - time the value changes ( see setTracking() ). - \param value new value - */ - void valueChanged( double value ); - - /*! - This signal is emitted when the user presses the - movable part of the slider (start ScrMouse Mode). - */ - void sliderPressed(); - - /*! - This signal is emitted when the user releases the - movable part of the slider. - */ - - void sliderReleased(); - /*! - This signal is emitted when the user moves the - slider with the mouse. - \param value new value - */ - void sliderMoved( double value ); - -protected: - virtual void setPosition( const QPoint & ); - virtual void valueChange(); - - virtual void timerEvent( QTimerEvent *e ); - virtual void mousePressEvent( QMouseEvent *e ); - virtual void mouseReleaseEvent( QMouseEvent *e ); - virtual void mouseMoveEvent( QMouseEvent *e ); - virtual void keyPressEvent( QKeyEvent *e ); - virtual void wheelEvent( QWheelEvent *e ); - - /*! - \brief Determine the value corresponding to a specified poind - - This is an abstract virtual function which is called when - the user presses or releases a mouse button or moves the - mouse. It has to be implemented by the derived class. - \param p point - */ - virtual double getValue( const QPoint & p ) = 0; - - /*! - \brief Determine what to do when the user presses a mouse button. - - This function is abstract and has to be implemented by derived classes. - It is called on a mousePress event. The derived class can determine - what should happen next in dependence of the position where the mouse - was pressed by returning scrolling mode and direction. - - \param pos point where the mouse was pressed - \retval scrollMode The scrolling mode - \retval direction direction: 1, 0, or -1. - */ - virtual void getScrollMode( const QPoint &pos, - ScrollMode &scrollMode, int &direction ) const = 0; - - void setMouseOffset( double ); - double mouseOffset() const; - - int scrollMode() const; - -private: - void buttonReleased(); - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_ABSTRACT_SLIDER_H +#define QWT_ABSTRACT_SLIDER_H + +#include "qwt_global.h" +#include "qwt_double_range.h" +#include + +/*! + \brief An abstract base class for slider widgets + + QwtAbstractSlider is a base class for + slider widgets. It handles mouse events + and updates the slider's value accordingly. Derived classes + only have to implement the getValue() and + getScrollMode() members, and should react to a + valueChange(), which normally requires repainting. +*/ + +class QWT_EXPORT QwtAbstractSlider : public QWidget, public QwtDoubleRange +{ + Q_OBJECT + Q_PROPERTY( bool readOnly READ isReadOnly WRITE setReadOnly ) + Q_PROPERTY( bool valid READ isValid WRITE setValid ) + Q_PROPERTY( double mass READ mass WRITE setMass ) + Q_PROPERTY( Qt::Orientation orientation + READ orientation WRITE setOrientation ) + +public: + /*! + Scroll mode + \sa getScrollMode() + */ + enum ScrollMode + { + //! Scrolling switched off. Don't change the value. + ScrNone, + + /*! + Change the value while the user keeps the + button pressed and moves the mouse. + */ + ScrMouse, + + /*! + Automatic scrolling. Increment the value in the specified direction + as long as the user keeps the button pressed. + */ + ScrTimer, + + ScrDirect, + + //! Automatic scrolling. Same as ScrTimer, but increment by page size. + ScrPage + }; + + explicit QwtAbstractSlider( Qt::Orientation, QWidget *parent = NULL ); + virtual ~QwtAbstractSlider(); + + void setUpdateTime( int t ); + void stopMoving(); + void setTracking( bool enable ); + + virtual void setMass( double val ); + virtual double mass() const; + + virtual void setOrientation( Qt::Orientation o ); + Qt::Orientation orientation() const; + + bool isReadOnly() const; + + /* + Wrappers for QwtDblRange::isValid/QwtDblRange::setValid made + to be available as Q_PROPERTY in the designer. + */ + + /*! + \sa QwtDblRange::isValid() + */ + bool isValid() const + { + return QwtDoubleRange::isValid(); + } + + /*! + \param valid true/false + \sa QwtDblRange::isValid() + */ + void setValid( bool valid ) + { + QwtDoubleRange::setValid( valid ); + } + +public Q_SLOTS: + virtual void setValue( double val ); + virtual void fitValue( double val ); + virtual void incValue( int steps ); + + virtual void setReadOnly( bool ); + +Q_SIGNALS: + + /*! + \brief Notify a change of value. + + In the default setting + (tracking enabled), this signal will be emitted every + time the value changes ( see setTracking() ). + \param value new value + */ + void valueChanged( double value ); + + /*! + This signal is emitted when the user presses the + movable part of the slider (start ScrMouse Mode). + */ + void sliderPressed(); + + /*! + This signal is emitted when the user releases the + movable part of the slider. + */ + + void sliderReleased(); + /*! + This signal is emitted when the user moves the + slider with the mouse. + \param value new value + */ + void sliderMoved( double value ); + +protected: + virtual void setPosition( const QPoint & ); + virtual void valueChange(); + + virtual void timerEvent( QTimerEvent *e ); + virtual void mousePressEvent( QMouseEvent *e ); + virtual void mouseReleaseEvent( QMouseEvent *e ); + virtual void mouseMoveEvent( QMouseEvent *e ); + virtual void keyPressEvent( QKeyEvent *e ); + virtual void wheelEvent( QWheelEvent *e ); + + /*! + \brief Determine the value corresponding to a specified poind + + This is an abstract virtual function which is called when + the user presses or releases a mouse button or moves the + mouse. It has to be implemented by the derived class. + \param p point + */ + virtual double getValue( const QPoint & p ) = 0; + + /*! + \brief Determine what to do when the user presses a mouse button. + + This function is abstract and has to be implemented by derived classes. + It is called on a mousePress event. The derived class can determine + what should happen next in dependence of the position where the mouse + was pressed by returning scrolling mode and direction. + + \param pos point where the mouse was pressed + \retval scrollMode The scrolling mode + \retval direction direction: 1, 0, or -1. + */ + virtual void getScrollMode( const QPoint &pos, + ScrollMode &scrollMode, int &direction ) const = 0; + + void setMouseOffset( double ); + double mouseOffset() const; + + int scrollMode() const; + +private: + void buttonReleased(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_analog_clock.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_analog_clock.cpp index 042e421aa..95a5ec94b 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_analog_clock.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_analog_clock.cpp @@ -1,228 +1,228 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_analog_clock.h" -#include - -/*! - Constructor - \param parent Parent widget -*/ -QwtAnalogClock::QwtAnalogClock( QWidget *parent ): - QwtDial( parent ) -{ - initClock(); -} - -void QwtAnalogClock::initClock() -{ - setWrapping( true ); - setReadOnly( true ); - - setOrigin( 270.0 ); - setRange( 0.0, 60.0 * 60.0 * 12.0 ); // seconds - setScale( -1, 5, 60.0 * 60.0 ); - - setScaleComponents( - QwtAbstractScaleDraw::Ticks | QwtAbstractScaleDraw::Labels ); - setScaleTicks( 1, 0, 8 ); - scaleDraw()->setSpacing( 8 ); - - QColor knobColor = palette().color( QPalette::Active, QPalette::Text ); - knobColor = knobColor.dark( 120 ); - - QColor handColor; - int width; - - for ( int i = 0; i < NHands; i++ ) - { - if ( i == SecondHand ) - { - width = 2; - handColor = knobColor.dark( 120 ); - } - else - { - width = 8; - handColor = knobColor; - } - - QwtDialSimpleNeedle *hand = new QwtDialSimpleNeedle( - QwtDialSimpleNeedle::Arrow, true, handColor, knobColor ); - hand->setWidth( width ); - - d_hand[i] = NULL; - setHand( ( Hand )i, hand ); - } -} - -//! Destructor -QwtAnalogClock::~QwtAnalogClock() -{ - for ( int i = 0; i < NHands; i++ ) - delete d_hand[i]; -} - -/*! - Nop method, use setHand instead - \sa setHand() -*/ -void QwtAnalogClock::setNeedle( QwtDialNeedle * ) -{ - // no op - return; -} - -/*! - Set a clockhand - \param hand Specifies the type of hand - \param needle Hand - \sa hand() -*/ -void QwtAnalogClock::setHand( Hand hand, QwtDialNeedle *needle ) -{ - if ( hand >= 0 || hand < NHands ) - { - delete d_hand[hand]; - d_hand[hand] = needle; - } -} - -/*! - \return Clock hand - \param hd Specifies the type of hand - \sa setHand() -*/ -QwtDialNeedle *QwtAnalogClock::hand( Hand hd ) -{ - if ( hd < 0 || hd >= NHands ) - return NULL; - - return d_hand[hd]; -} - -/*! - \return Clock hand - \param hd Specifies the type of hand - \sa setHand() -*/ -const QwtDialNeedle *QwtAnalogClock::hand( Hand hd ) const -{ - return const_cast( this )->hand( hd ); -} - -/*! - \brief Set the current time - - This is the same as QwtAnalogClock::setTime(), but Qt < 3.0 - can't handle default parameters for slots. -*/ -void QwtAnalogClock::setCurrentTime() -{ - setTime( QTime::currentTime() ); -} - -/*! - Set a time - \param time Time to display -*/ -void QwtAnalogClock::setTime( const QTime &time ) -{ - if ( time.isValid() ) - { - setValue( ( time.hour() % 12 ) * 60.0 * 60.0 - + time.minute() * 60.0 + time.second() ); - } - else - setValid( false ); -} - -/*! - Find the scale label for a given value - - \param value Value - \return Label -*/ -QwtText QwtAnalogClock::scaleLabel( double value ) const -{ - if ( value == 0.0 ) - value = 60.0 * 60.0 * 12.0; - - return QString::number( int( value / ( 60.0 * 60.0 ) ) ); -} - -/*! - \brief Draw the needle - - A clock has no single needle but three hands instead. drawNeedle - translates value() into directions for the hands and calls - drawHand(). - - \param painter Painter - \param center Center of the clock - \param radius Maximum length for the hands - \param dir Dummy, not used. - \param colorGroup ColorGroup - - \sa drawHand() -*/ -void QwtAnalogClock::drawNeedle( QPainter *painter, const QPointF ¢er, - double radius, double dir, QPalette::ColorGroup colorGroup ) const -{ - Q_UNUSED( dir ); - - if ( isValid() ) - { - const double hours = value() / ( 60.0 * 60.0 ); - const double minutes = - ( value() - qFloor(hours) * 60.0 * 60.0 ) / 60.0; - const double seconds = value() - qFloor(hours) * 60.0 * 60.0 - - qFloor(minutes) * 60.0; - - double angle[NHands]; - angle[HourHand] = 360.0 * hours / 12.0; - angle[MinuteHand] = 360.0 * minutes / 60.0; - angle[SecondHand] = 360.0 * seconds / 60.0; - - for ( int hand = 0; hand < NHands; hand++ ) - { - double d = angle[hand]; - if ( direction() == Clockwise ) - d = 360.0 - d; - - d -= origin(); - - drawHand( painter, ( Hand )hand, center, radius, d, colorGroup ); - } - } -} - -/*! - Draw a clock hand - - \param painter Painter - \param hd Specify the type of hand - \param center Center of the clock - \param radius Maximum length for the hands - \param direction Direction of the hand in degrees, counter clockwise - \param cg ColorGroup -*/ -void QwtAnalogClock::drawHand( QPainter *painter, Hand hd, - const QPointF ¢er, double radius, double direction, - QPalette::ColorGroup cg ) const -{ - const QwtDialNeedle *needle = hand( hd ); - if ( needle ) - { - if ( hd == HourHand ) - radius = qRound( 0.8 * radius ); - - needle->draw( painter, center, radius, direction, cg ); - } -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_analog_clock.h" +#include + +/*! + Constructor + \param parent Parent widget +*/ +QwtAnalogClock::QwtAnalogClock( QWidget *parent ): + QwtDial( parent ) +{ + initClock(); +} + +void QwtAnalogClock::initClock() +{ + setWrapping( true ); + setReadOnly( true ); + + setOrigin( 270.0 ); + setRange( 0.0, 60.0 * 60.0 * 12.0 ); // seconds + setScale( -1, 5, 60.0 * 60.0 ); + + setScaleComponents( + QwtAbstractScaleDraw::Ticks | QwtAbstractScaleDraw::Labels ); + setScaleTicks( 1, 0, 8 ); + scaleDraw()->setSpacing( 8 ); + + QColor knobColor = palette().color( QPalette::Active, QPalette::Text ); + knobColor = knobColor.dark( 120 ); + + QColor handColor; + int width; + + for ( int i = 0; i < NHands; i++ ) + { + if ( i == SecondHand ) + { + width = 2; + handColor = knobColor.dark( 120 ); + } + else + { + width = 8; + handColor = knobColor; + } + + QwtDialSimpleNeedle *hand = new QwtDialSimpleNeedle( + QwtDialSimpleNeedle::Arrow, true, handColor, knobColor ); + hand->setWidth( width ); + + d_hand[i] = NULL; + setHand( ( Hand )i, hand ); + } +} + +//! Destructor +QwtAnalogClock::~QwtAnalogClock() +{ + for ( int i = 0; i < NHands; i++ ) + delete d_hand[i]; +} + +/*! + Nop method, use setHand instead + \sa setHand() +*/ +void QwtAnalogClock::setNeedle( QwtDialNeedle * ) +{ + // no op + return; +} + +/*! + Set a clockhand + \param hand Specifies the type of hand + \param needle Hand + \sa hand() +*/ +void QwtAnalogClock::setHand( Hand hand, QwtDialNeedle *needle ) +{ + if ( hand >= 0 || hand < NHands ) + { + delete d_hand[hand]; + d_hand[hand] = needle; + } +} + +/*! + \return Clock hand + \param hd Specifies the type of hand + \sa setHand() +*/ +QwtDialNeedle *QwtAnalogClock::hand( Hand hd ) +{ + if ( hd < 0 || hd >= NHands ) + return NULL; + + return d_hand[hd]; +} + +/*! + \return Clock hand + \param hd Specifies the type of hand + \sa setHand() +*/ +const QwtDialNeedle *QwtAnalogClock::hand( Hand hd ) const +{ + return const_cast( this )->hand( hd ); +} + +/*! + \brief Set the current time + + This is the same as QwtAnalogClock::setTime(), but Qt < 3.0 + can't handle default parameters for slots. +*/ +void QwtAnalogClock::setCurrentTime() +{ + setTime( QTime::currentTime() ); +} + +/*! + Set a time + \param time Time to display +*/ +void QwtAnalogClock::setTime( const QTime &time ) +{ + if ( time.isValid() ) + { + setValue( ( time.hour() % 12 ) * 60.0 * 60.0 + + time.minute() * 60.0 + time.second() ); + } + else + setValid( false ); +} + +/*! + Find the scale label for a given value + + \param value Value + \return Label +*/ +QwtText QwtAnalogClock::scaleLabel( double value ) const +{ + if ( value == 0.0 ) + value = 60.0 * 60.0 * 12.0; + + return QString::number( int( value / ( 60.0 * 60.0 ) ) ); +} + +/*! + \brief Draw the needle + + A clock has no single needle but three hands instead. drawNeedle + translates value() into directions for the hands and calls + drawHand(). + + \param painter Painter + \param center Center of the clock + \param radius Maximum length for the hands + \param dir Dummy, not used. + \param colorGroup ColorGroup + + \sa drawHand() +*/ +void QwtAnalogClock::drawNeedle( QPainter *painter, const QPointF ¢er, + double radius, double dir, QPalette::ColorGroup colorGroup ) const +{ + Q_UNUSED( dir ); + + if ( isValid() ) + { + const double hours = value() / ( 60.0 * 60.0 ); + const double minutes = + ( value() - qFloor(hours) * 60.0 * 60.0 ) / 60.0; + const double seconds = value() - qFloor(hours) * 60.0 * 60.0 + - qFloor(minutes) * 60.0; + + double angle[NHands]; + angle[HourHand] = 360.0 * hours / 12.0; + angle[MinuteHand] = 360.0 * minutes / 60.0; + angle[SecondHand] = 360.0 * seconds / 60.0; + + for ( int hand = 0; hand < NHands; hand++ ) + { + double d = angle[hand]; + if ( direction() == Clockwise ) + d = 360.0 - d; + + d -= origin(); + + drawHand( painter, ( Hand )hand, center, radius, d, colorGroup ); + } + } +} + +/*! + Draw a clock hand + + \param painter Painter + \param hd Specify the type of hand + \param center Center of the clock + \param radius Maximum length for the hands + \param direction Direction of the hand in degrees, counter clockwise + \param cg ColorGroup +*/ +void QwtAnalogClock::drawHand( QPainter *painter, Hand hd, + const QPointF ¢er, double radius, double direction, + QPalette::ColorGroup cg ) const +{ + const QwtDialNeedle *needle = hand( hd ); + if ( needle ) + { + if ( hd == HourHand ) + radius = qRound( 0.8 * radius ); + + needle->draw( painter, center, radius, direction, cg ); + } +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_analog_clock.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_analog_clock.h index 67c7baf73..f20c3f1f2 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_analog_clock.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_analog_clock.h @@ -1,96 +1,96 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_ANALOG_CLOCK_H -#define QWT_ANALOG_CLOCK_H - -#include "qwt_global.h" -#include "qwt_dial.h" -#include "qwt_dial_needle.h" -#include - -/*! - \brief An analog clock - - \image html analogclock.png - - \par Example - \verbatim #include - - QwtAnalogClock *clock = new QwtAnalogClock(...); - clock->scaleDraw()->setPenWidth(3); - clock->setLineWidth(6); - clock->setFrameShadow(QwtDial::Sunken); - clock->setTime(); - - // update the clock every second - QTimer *timer = new QTimer(clock); - timer->connect(timer, SIGNAL(timeout()), clock, SLOT(setCurrentTime())); - timer->start(1000); - - \endverbatim - - Qwt is missing a set of good looking hands. - Contributions are very welcome. - - \note The examples/dials example shows how to use QwtAnalogClock. -*/ - -class QWT_EXPORT QwtAnalogClock: public QwtDial -{ - Q_OBJECT - -public: - /*! - Hand type - \sa setHand(), hand() - */ - enum Hand - { - //! Needle displaying the seconds - SecondHand, - - //! Needle displaying the minutes - MinuteHand, - - //! Needle displaying the hours - HourHand, - - //! Number of needles - NHands - }; - - explicit QwtAnalogClock( QWidget* parent = NULL ); - virtual ~QwtAnalogClock(); - - virtual void setHand( Hand, QwtDialNeedle * ); - const QwtDialNeedle *hand( Hand ) const; - QwtDialNeedle *hand( Hand ); - -public Q_SLOTS: - void setCurrentTime(); - void setTime( const QTime & = QTime::currentTime() ); - -protected: - virtual QwtText scaleLabel( double ) const; - - virtual void drawNeedle( QPainter *, const QPointF &, - double radius, double direction, QPalette::ColorGroup ) const; - - virtual void drawHand( QPainter *, Hand, const QPointF &, - double radius, double direction, QPalette::ColorGroup ) const; - -private: - virtual void setNeedle( QwtDialNeedle * ); - void initClock(); - - QwtDialNeedle *d_hand[NHands]; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_ANALOG_CLOCK_H +#define QWT_ANALOG_CLOCK_H + +#include "qwt_global.h" +#include "qwt_dial.h" +#include "qwt_dial_needle.h" +#include + +/*! + \brief An analog clock + + \image html analogclock.png + + \par Example + \verbatim #include + + QwtAnalogClock *clock = new QwtAnalogClock(...); + clock->scaleDraw()->setPenWidth(3); + clock->setLineWidth(6); + clock->setFrameShadow(QwtDial::Sunken); + clock->setTime(); + + // update the clock every second + QTimer *timer = new QTimer(clock); + timer->connect(timer, SIGNAL(timeout()), clock, SLOT(setCurrentTime())); + timer->start(1000); + + \endverbatim + + Qwt is missing a set of good looking hands. + Contributions are very welcome. + + \note The examples/dials example shows how to use QwtAnalogClock. +*/ + +class QWT_EXPORT QwtAnalogClock: public QwtDial +{ + Q_OBJECT + +public: + /*! + Hand type + \sa setHand(), hand() + */ + enum Hand + { + //! Needle displaying the seconds + SecondHand, + + //! Needle displaying the minutes + MinuteHand, + + //! Needle displaying the hours + HourHand, + + //! Number of needles + NHands + }; + + explicit QwtAnalogClock( QWidget* parent = NULL ); + virtual ~QwtAnalogClock(); + + virtual void setHand( Hand, QwtDialNeedle * ); + const QwtDialNeedle *hand( Hand ) const; + QwtDialNeedle *hand( Hand ); + +public Q_SLOTS: + void setCurrentTime(); + void setTime( const QTime & = QTime::currentTime() ); + +protected: + virtual QwtText scaleLabel( double ) const; + + virtual void drawNeedle( QPainter *, const QPointF &, + double radius, double direction, QPalette::ColorGroup ) const; + + virtual void drawHand( QPainter *, Hand, const QPointF &, + double radius, double direction, QPalette::ColorGroup ) const; + +private: + virtual void setNeedle( QwtDialNeedle * ); + void initClock(); + + QwtDialNeedle *d_hand[NHands]; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_arrow_button.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_arrow_button.cpp index aa5267b9a..f451b44cd 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_arrow_button.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_arrow_button.cpp @@ -1,332 +1,332 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_arrow_button.h" -#include "qwt_math.h" -#include -#include -#include -#include -#include - -static const int MaxNum = 3; -static const int Margin = 2; -static const int Spacing = 1; - -class QwtArrowButton::PrivateData -{ -public: - int num; - Qt::ArrowType arrowType; -}; - -static QStyleOptionButton styleOpt( const QwtArrowButton* btn ) -{ - QStyleOptionButton option; - option.init( btn ); - option.features = QStyleOptionButton::None; - if ( btn->isFlat() ) - option.features |= QStyleOptionButton::Flat; - if ( btn->menu() ) - option.features |= QStyleOptionButton::HasMenu; - if ( btn->autoDefault() || btn->isDefault() ) - option.features |= QStyleOptionButton::AutoDefaultButton; - if ( btn->isDefault() ) - option.features |= QStyleOptionButton::DefaultButton; - if ( btn->isDown() ) - option.state |= QStyle::State_Sunken; - if ( !btn->isFlat() && !btn->isDown() ) - option.state |= QStyle::State_Raised; - - return option; -} - -/*! - \param num Number of arrows - \param arrowType see Qt::ArowType in the Qt docs. - \param parent Parent widget -*/ -QwtArrowButton::QwtArrowButton( int num, - Qt::ArrowType arrowType, QWidget *parent ): - QPushButton( parent ) -{ - d_data = new PrivateData; - d_data->num = qBound( 1, num, MaxNum ); - d_data->arrowType = arrowType; - - setAutoRepeat( true ); - setAutoDefault( false ); - - switch ( d_data->arrowType ) - { - case Qt::LeftArrow: - case Qt::RightArrow: - setSizePolicy( QSizePolicy::Expanding, - QSizePolicy::Fixed ); - break; - default: - setSizePolicy( QSizePolicy::Fixed, - QSizePolicy::Expanding ); - } -} - -//! Destructor -QwtArrowButton::~QwtArrowButton() -{ - delete d_data; - d_data = NULL; -} - -/*! - \brief The direction of the arrows -*/ -Qt::ArrowType QwtArrowButton::arrowType() const -{ - return d_data->arrowType; -} - -/*! - \brief The number of arrows -*/ -int QwtArrowButton::num() const -{ - return d_data->num; -} - -/*! - \return the bounding rect for the label -*/ -QRect QwtArrowButton::labelRect() const -{ - const int m = Margin; - - QRect r = rect(); - r.setRect( r.x() + m, r.y() + m, - r.width() - 2 * m, r.height() - 2 * m ); - - if ( isDown() ) - { - QStyleOptionButton option = styleOpt( this ); - const int ph = style()->pixelMetric( - QStyle::PM_ButtonShiftHorizontal, &option, this ); - const int pv = style()->pixelMetric( - QStyle::PM_ButtonShiftVertical, &option, this ); - - r.translate( ph, pv ); - } - - return r; -} - -/*! - Paint event handler - \param event Paint event -*/ -void QwtArrowButton::paintEvent( QPaintEvent *event ) -{ - QPushButton::paintEvent( event ); - QPainter painter( this ); - drawButtonLabel( &painter ); -} - -/*! - \brief Draw the button label - - \param painter Painter - \sa The Qt Manual on QPushButton -*/ -void QwtArrowButton::drawButtonLabel( QPainter *painter ) -{ - const bool isVertical = d_data->arrowType == Qt::UpArrow || - d_data->arrowType == Qt::DownArrow; - - const QRect r = labelRect(); - QSize boundingSize = labelRect().size(); - if ( isVertical ) - boundingSize.transpose(); - - const int w = - ( boundingSize.width() - ( MaxNum - 1 ) * Spacing ) / MaxNum; - - QSize arrow = arrowSize( Qt::RightArrow, - QSize( w, boundingSize.height() ) ); - - if ( isVertical ) - arrow.transpose(); - - QRect contentsSize; // aligned rect where to paint all arrows - if ( d_data->arrowType == Qt::LeftArrow || d_data->arrowType == Qt::RightArrow ) - { - contentsSize.setWidth( d_data->num * arrow.width() - + ( d_data->num - 1 ) * Spacing ); - contentsSize.setHeight( arrow.height() ); - } - else - { - contentsSize.setWidth( arrow.width() ); - contentsSize.setHeight( d_data->num * arrow.height() - + ( d_data->num - 1 ) * Spacing ); - } - - QRect arrowRect( contentsSize ); - arrowRect.moveCenter( r.center() ); - arrowRect.setSize( arrow ); - - painter->save(); - for ( int i = 0; i < d_data->num; i++ ) - { - drawArrow( painter, arrowRect, d_data->arrowType ); - - int dx = 0; - int dy = 0; - - if ( isVertical ) - dy = arrow.height() + Spacing; - else - dx = arrow.width() + Spacing; - - arrowRect.translate( dx, dy ); - } - painter->restore(); - - if ( hasFocus() ) - { - QStyleOptionFocusRect option; - option.init( this ); - option.backgroundColor = palette().color( QPalette::Window ); - - style()->drawPrimitive( QStyle::PE_FrameFocusRect, - &option, painter, this ); - } -} - -/*! - Draw an arrow int a bounding rect - - \param painter Painter - \param r Rectangle where to paint the arrow - \param arrowType Arrow type -*/ -void QwtArrowButton::drawArrow( QPainter *painter, - const QRect &r, Qt::ArrowType arrowType ) const -{ - QPolygon pa( 3 ); - - switch ( arrowType ) - { - case Qt::UpArrow: - pa.setPoint( 0, r.bottomLeft() ); - pa.setPoint( 1, r.bottomRight() ); - pa.setPoint( 2, r.center().x(), r.top() ); - break; - case Qt::DownArrow: - pa.setPoint( 0, r.topLeft() ); - pa.setPoint( 1, r.topRight() ); - pa.setPoint( 2, r.center().x(), r.bottom() ); - break; - case Qt::RightArrow: - pa.setPoint( 0, r.topLeft() ); - pa.setPoint( 1, r.bottomLeft() ); - pa.setPoint( 2, r.right(), r.center().y() ); - break; - case Qt::LeftArrow: - pa.setPoint( 0, r.topRight() ); - pa.setPoint( 1, r.bottomRight() ); - pa.setPoint( 2, r.left(), r.center().y() ); - break; - default: - break; - } - - painter->save(); - - painter->setPen( palette().color( QPalette::ButtonText ) ); - painter->setBrush( palette().brush( QPalette::ButtonText ) ); - painter->drawPolygon( pa ); - - painter->restore(); -} - -/*! - \return a size hint -*/ -QSize QwtArrowButton::sizeHint() const -{ - const QSize hint = minimumSizeHint(); - return hint.expandedTo( QApplication::globalStrut() ); -} - -/*! - \brief Return a minimum size hint -*/ -QSize QwtArrowButton::minimumSizeHint() const -{ - const QSize asz = arrowSize( Qt::RightArrow, QSize() ); - - QSize sz( - 2 * Margin + ( MaxNum - 1 ) * Spacing + MaxNum * asz.width(), - 2 * Margin + asz.height() - ); - - if ( d_data->arrowType == Qt::UpArrow || d_data->arrowType == Qt::DownArrow ) - sz.transpose(); - - QStyleOption styleOption; - styleOption.init( this ); - - sz = style()->sizeFromContents( QStyle::CT_PushButton, - &styleOption, sz, this ); - - return sz; -} - -/*! - Calculate the size for a arrow that fits into a rect of a given size - - \param arrowType Arrow type - \param boundingSize Bounding size - \return Size of the arrow -*/ -QSize QwtArrowButton::arrowSize( Qt::ArrowType arrowType, - const QSize &boundingSize ) const -{ - QSize bs = boundingSize; - if ( arrowType == Qt::UpArrow || arrowType == Qt::DownArrow ) - bs.transpose(); - - const int MinLen = 2; - const QSize sz = bs.expandedTo( - QSize( MinLen, 2 * MinLen - 1 ) ); // minimum - - int w = sz.width(); - int h = 2 * w - 1; - - if ( h > sz.height() ) - { - h = sz.height(); - w = ( h + 1 ) / 2; - } - - QSize arrSize( w, h ); - if ( arrowType == Qt::UpArrow || arrowType == Qt::DownArrow ) - arrSize.transpose(); - - return arrSize; -} - -/*! - \brief autoRepeat for the space keys -*/ -void QwtArrowButton::keyPressEvent( QKeyEvent *event ) -{ - if ( event->isAutoRepeat() && event->key() == Qt::Key_Space ) - Q_EMIT clicked(); - - QPushButton::keyPressEvent( event ); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_arrow_button.h" +#include "qwt_math.h" +#include +#include +#include +#include +#include + +static const int MaxNum = 3; +static const int Margin = 2; +static const int Spacing = 1; + +class QwtArrowButton::PrivateData +{ +public: + int num; + Qt::ArrowType arrowType; +}; + +static QStyleOptionButton styleOpt( const QwtArrowButton* btn ) +{ + QStyleOptionButton option; + option.init( btn ); + option.features = QStyleOptionButton::None; + if ( btn->isFlat() ) + option.features |= QStyleOptionButton::Flat; + if ( btn->menu() ) + option.features |= QStyleOptionButton::HasMenu; + if ( btn->autoDefault() || btn->isDefault() ) + option.features |= QStyleOptionButton::AutoDefaultButton; + if ( btn->isDefault() ) + option.features |= QStyleOptionButton::DefaultButton; + if ( btn->isDown() ) + option.state |= QStyle::State_Sunken; + if ( !btn->isFlat() && !btn->isDown() ) + option.state |= QStyle::State_Raised; + + return option; +} + +/*! + \param num Number of arrows + \param arrowType see Qt::ArowType in the Qt docs. + \param parent Parent widget +*/ +QwtArrowButton::QwtArrowButton( int num, + Qt::ArrowType arrowType, QWidget *parent ): + QPushButton( parent ) +{ + d_data = new PrivateData; + d_data->num = qBound( 1, num, MaxNum ); + d_data->arrowType = arrowType; + + setAutoRepeat( true ); + setAutoDefault( false ); + + switch ( d_data->arrowType ) + { + case Qt::LeftArrow: + case Qt::RightArrow: + setSizePolicy( QSizePolicy::Expanding, + QSizePolicy::Fixed ); + break; + default: + setSizePolicy( QSizePolicy::Fixed, + QSizePolicy::Expanding ); + } +} + +//! Destructor +QwtArrowButton::~QwtArrowButton() +{ + delete d_data; + d_data = NULL; +} + +/*! + \brief The direction of the arrows +*/ +Qt::ArrowType QwtArrowButton::arrowType() const +{ + return d_data->arrowType; +} + +/*! + \brief The number of arrows +*/ +int QwtArrowButton::num() const +{ + return d_data->num; +} + +/*! + \return the bounding rect for the label +*/ +QRect QwtArrowButton::labelRect() const +{ + const int m = Margin; + + QRect r = rect(); + r.setRect( r.x() + m, r.y() + m, + r.width() - 2 * m, r.height() - 2 * m ); + + if ( isDown() ) + { + QStyleOptionButton option = styleOpt( this ); + const int ph = style()->pixelMetric( + QStyle::PM_ButtonShiftHorizontal, &option, this ); + const int pv = style()->pixelMetric( + QStyle::PM_ButtonShiftVertical, &option, this ); + + r.translate( ph, pv ); + } + + return r; +} + +/*! + Paint event handler + \param event Paint event +*/ +void QwtArrowButton::paintEvent( QPaintEvent *event ) +{ + QPushButton::paintEvent( event ); + QPainter painter( this ); + drawButtonLabel( &painter ); +} + +/*! + \brief Draw the button label + + \param painter Painter + \sa The Qt Manual on QPushButton +*/ +void QwtArrowButton::drawButtonLabel( QPainter *painter ) +{ + const bool isVertical = d_data->arrowType == Qt::UpArrow || + d_data->arrowType == Qt::DownArrow; + + const QRect r = labelRect(); + QSize boundingSize = labelRect().size(); + if ( isVertical ) + boundingSize.transpose(); + + const int w = + ( boundingSize.width() - ( MaxNum - 1 ) * Spacing ) / MaxNum; + + QSize arrow = arrowSize( Qt::RightArrow, + QSize( w, boundingSize.height() ) ); + + if ( isVertical ) + arrow.transpose(); + + QRect contentsSize; // aligned rect where to paint all arrows + if ( d_data->arrowType == Qt::LeftArrow || d_data->arrowType == Qt::RightArrow ) + { + contentsSize.setWidth( d_data->num * arrow.width() + + ( d_data->num - 1 ) * Spacing ); + contentsSize.setHeight( arrow.height() ); + } + else + { + contentsSize.setWidth( arrow.width() ); + contentsSize.setHeight( d_data->num * arrow.height() + + ( d_data->num - 1 ) * Spacing ); + } + + QRect arrowRect( contentsSize ); + arrowRect.moveCenter( r.center() ); + arrowRect.setSize( arrow ); + + painter->save(); + for ( int i = 0; i < d_data->num; i++ ) + { + drawArrow( painter, arrowRect, d_data->arrowType ); + + int dx = 0; + int dy = 0; + + if ( isVertical ) + dy = arrow.height() + Spacing; + else + dx = arrow.width() + Spacing; + + arrowRect.translate( dx, dy ); + } + painter->restore(); + + if ( hasFocus() ) + { + QStyleOptionFocusRect option; + option.init( this ); + option.backgroundColor = palette().color( QPalette::Window ); + + style()->drawPrimitive( QStyle::PE_FrameFocusRect, + &option, painter, this ); + } +} + +/*! + Draw an arrow int a bounding rect + + \param painter Painter + \param r Rectangle where to paint the arrow + \param arrowType Arrow type +*/ +void QwtArrowButton::drawArrow( QPainter *painter, + const QRect &r, Qt::ArrowType arrowType ) const +{ + QPolygon pa( 3 ); + + switch ( arrowType ) + { + case Qt::UpArrow: + pa.setPoint( 0, r.bottomLeft() ); + pa.setPoint( 1, r.bottomRight() ); + pa.setPoint( 2, r.center().x(), r.top() ); + break; + case Qt::DownArrow: + pa.setPoint( 0, r.topLeft() ); + pa.setPoint( 1, r.topRight() ); + pa.setPoint( 2, r.center().x(), r.bottom() ); + break; + case Qt::RightArrow: + pa.setPoint( 0, r.topLeft() ); + pa.setPoint( 1, r.bottomLeft() ); + pa.setPoint( 2, r.right(), r.center().y() ); + break; + case Qt::LeftArrow: + pa.setPoint( 0, r.topRight() ); + pa.setPoint( 1, r.bottomRight() ); + pa.setPoint( 2, r.left(), r.center().y() ); + break; + default: + break; + } + + painter->save(); + + painter->setPen( palette().color( QPalette::ButtonText ) ); + painter->setBrush( palette().brush( QPalette::ButtonText ) ); + painter->drawPolygon( pa ); + + painter->restore(); +} + +/*! + \return a size hint +*/ +QSize QwtArrowButton::sizeHint() const +{ + const QSize hint = minimumSizeHint(); + return hint.expandedTo( QApplication::globalStrut() ); +} + +/*! + \brief Return a minimum size hint +*/ +QSize QwtArrowButton::minimumSizeHint() const +{ + const QSize asz = arrowSize( Qt::RightArrow, QSize() ); + + QSize sz( + 2 * Margin + ( MaxNum - 1 ) * Spacing + MaxNum * asz.width(), + 2 * Margin + asz.height() + ); + + if ( d_data->arrowType == Qt::UpArrow || d_data->arrowType == Qt::DownArrow ) + sz.transpose(); + + QStyleOption styleOption; + styleOption.init( this ); + + sz = style()->sizeFromContents( QStyle::CT_PushButton, + &styleOption, sz, this ); + + return sz; +} + +/*! + Calculate the size for a arrow that fits into a rect of a given size + + \param arrowType Arrow type + \param boundingSize Bounding size + \return Size of the arrow +*/ +QSize QwtArrowButton::arrowSize( Qt::ArrowType arrowType, + const QSize &boundingSize ) const +{ + QSize bs = boundingSize; + if ( arrowType == Qt::UpArrow || arrowType == Qt::DownArrow ) + bs.transpose(); + + const int MinLen = 2; + const QSize sz = bs.expandedTo( + QSize( MinLen, 2 * MinLen - 1 ) ); // minimum + + int w = sz.width(); + int h = 2 * w - 1; + + if ( h > sz.height() ) + { + h = sz.height(); + w = ( h + 1 ) / 2; + } + + QSize arrSize( w, h ); + if ( arrowType == Qt::UpArrow || arrowType == Qt::DownArrow ) + arrSize.transpose(); + + return arrSize; +} + +/*! + \brief autoRepeat for the space keys +*/ +void QwtArrowButton::keyPressEvent( QKeyEvent *event ) +{ + if ( event->isAutoRepeat() && event->key() == Qt::Key_Space ) + Q_EMIT clicked(); + + QPushButton::keyPressEvent( event ); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_arrow_button.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_arrow_button.h index b3285daa5..ae436fec0 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_arrow_button.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_arrow_button.h @@ -1,52 +1,52 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_ARROW_BUTTON_H -#define QWT_ARROW_BUTTON_H - -#include "qwt_global.h" -#include - -/*! - \brief Arrow Button - - A push button with one or more filled triangles on its front. - An Arrow button can have 1 to 3 arrows in a row, pointing - up, down, left or right. -*/ -class QWT_EXPORT QwtArrowButton : public QPushButton -{ -public: - explicit QwtArrowButton ( int num, Qt::ArrowType, QWidget *parent = NULL ); - virtual ~QwtArrowButton(); - - Qt::ArrowType arrowType() const; - int num() const; - - virtual QSize sizeHint() const; - virtual QSize minimumSizeHint() const; - -protected: - virtual void paintEvent( QPaintEvent *event ); - - virtual void drawButtonLabel( QPainter *p ); - virtual void drawArrow( QPainter *, - const QRect &, Qt::ArrowType ) const; - virtual QRect labelRect() const; - virtual QSize arrowSize( Qt::ArrowType, - const QSize &boundingSize ) const; - - virtual void keyPressEvent( QKeyEvent * ); - -private: - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_ARROW_BUTTON_H +#define QWT_ARROW_BUTTON_H + +#include "qwt_global.h" +#include + +/*! + \brief Arrow Button + + A push button with one or more filled triangles on its front. + An Arrow button can have 1 to 3 arrows in a row, pointing + up, down, left or right. +*/ +class QWT_EXPORT QwtArrowButton : public QPushButton +{ +public: + explicit QwtArrowButton ( int num, Qt::ArrowType, QWidget *parent = NULL ); + virtual ~QwtArrowButton(); + + Qt::ArrowType arrowType() const; + int num() const; + + virtual QSize sizeHint() const; + virtual QSize minimumSizeHint() const; + +protected: + virtual void paintEvent( QPaintEvent *event ); + + virtual void drawButtonLabel( QPainter *p ); + virtual void drawArrow( QPainter *, + const QRect &, Qt::ArrowType ) const; + virtual QRect labelRect() const; + virtual QSize arrowSize( Qt::ArrowType, + const QSize &boundingSize ) const; + + virtual void keyPressEvent( QKeyEvent * ); + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_clipper.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_clipper.cpp index d43c47fa9..fea3fd4b6 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_clipper.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_clipper.cpp @@ -1,486 +1,486 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_clipper.h" -#include "qwt_point_polar.h" -#include - -#if QT_VERSION < 0x040601 -#define qAtan(x) ::atan(x) -#endif - -namespace QwtClip -{ - // some templates used for inlining - template class LeftEdge; - template class RightEdge; - template class TopEdge; - template class BottomEdge; - - template class PointBuffer; -} - -template -class QwtClip::LeftEdge -{ -public: - inline LeftEdge( Value x1, Value, Value, Value ): - d_x1( x1 ) - { - } - - inline bool isInside( const Point &p ) const - { - return p.x() >= d_x1; - } - - inline Point intersection( const Point &p1, const Point &p2 ) const - { - double dy = ( p1.y() - p2.y() ) / double( p1.x() - p2.x() ); - return Point( d_x1, ( Value ) ( p2.y() + ( d_x1 - p2.x() ) * dy ) ); - } -private: - const Value d_x1; -}; - -template -class QwtClip::RightEdge -{ -public: - inline RightEdge( Value, Value x2, Value, Value ): - d_x2( x2 ) - { - } - - inline bool isInside( const Point &p ) const - { - return p.x() <= d_x2; - } - - inline Point intersection( const Point &p1, const Point &p2 ) const - { - double dy = ( p1.y() - p2.y() ) / double( p1.x() - p2.x() ); - return Point( d_x2, ( Value ) ( p2.y() + ( d_x2 - p2.x() ) * dy ) ); - } - -private: - const Value d_x2; -}; - -template -class QwtClip::TopEdge -{ -public: - inline TopEdge( Value, Value, Value y1, Value ): - d_y1( y1 ) - { - } - - inline bool isInside( const Point &p ) const - { - return p.y() >= d_y1; - } - - inline Point intersection( const Point &p1, const Point &p2 ) const - { - double dx = ( p1.x() - p2.x() ) / double( p1.y() - p2.y() ); - return Point( ( Value )( p2.x() + ( d_y1 - p2.y() ) * dx ), d_y1 ); - } - -private: - const Value d_y1; -}; - -template -class QwtClip::BottomEdge -{ -public: - inline BottomEdge( Value, Value, Value, Value y2 ): - d_y2( y2 ) - { - } - - inline bool isInside( const Point &p ) const - { - return p.y() <= d_y2; - } - - inline Point intersection( const Point &p1, const Point &p2 ) const - { - double dx = ( p1.x() - p2.x() ) / double( p1.y() - p2.y() ); - return Point( ( Value )( p2.x() + ( d_y2 - p2.y() ) * dx ), d_y2 ); - } - -private: - const Value d_y2; -}; - -template -class QwtClip::PointBuffer -{ -public: - PointBuffer( int capacity = 0 ): - m_capacity( 0 ), - m_size( 0 ), - m_buffer( NULL ) - { - if ( capacity > 0 ) - reserve( capacity ); - } - - ~PointBuffer() - { - if ( m_buffer ) - qFree( m_buffer ); - } - - inline void setPoints( int numPoints, const Point *points ) - { - reserve( numPoints ); - - m_size = numPoints; - qMemCopy( m_buffer, points, m_size * sizeof( Point ) ); - } - - inline void reset() - { - m_size = 0; - } - - inline int size() const - { - return m_size; - } - - inline Point *data() const - { - return m_buffer; - } - - inline Point &operator[]( int i ) - { - return m_buffer[i]; - } - - inline const Point &operator[]( int i ) const - { - return m_buffer[i]; - } - - inline void add( const Point &point ) - { - if ( m_capacity <= m_size ) - reserve( m_size + 1 ); - - m_buffer[m_size++] = point; - } - -private: - inline void reserve( int size ) - { - if ( m_capacity == 0 ) - m_capacity = 1; - - while ( m_capacity < size ) - m_capacity *= 2; - - m_buffer = ( Point * ) qRealloc( - m_buffer, m_capacity * sizeof( Point ) ); - } - - int m_capacity; - int m_size; - Point *m_buffer; -}; - -using namespace QwtClip; - -template -class QwtPolygonClipper -{ -public: - QwtPolygonClipper( const Rect &clipRect ): - d_clipRect( clipRect ) - { - } - - Polygon clipPolygon( const Polygon &polygon, bool closePolygon ) const - { -#if 0 - if ( d_clipRect.contains( polygon.boundingRect() ) ) - return polygon; -#endif - - PointBuffer points1; - PointBuffer points2( qMin( 256, polygon.size() ) ); - - points1.setPoints( polygon.size(), polygon.data() ); - - clipEdge< LeftEdge >( closePolygon, points1, points2 ); - clipEdge< RightEdge >( closePolygon, points2, points1 ); - clipEdge< TopEdge >( closePolygon, points1, points2 ); - clipEdge< BottomEdge >( closePolygon, points2, points1 ); - - Polygon p; - p.resize( points1.size() ); - qMemCopy( p.data(), points1.data(), points1.size() * sizeof( Point ) ); - - return p; - } - -private: - template - inline void clipEdge( bool closePolygon, - PointBuffer &points, PointBuffer &clippedPoints ) const - { - clippedPoints.reset(); - - if ( points.size() < 2 ) - { - if ( points.size() == 1 ) - clippedPoints.add( points[0] ); - return; - } - - const Edge edge( d_clipRect.x(), d_clipRect.x() + d_clipRect.width(), - d_clipRect.y(), d_clipRect.y() + d_clipRect.height() ); - - int lastPos, start; - if ( closePolygon ) - { - start = 0; - lastPos = points.size() - 1; - } - else - { - start = 1; - lastPos = 0; - - if ( edge.isInside( points[0] ) ) - clippedPoints.add( points[0] ); - } - - const uint nPoints = points.size(); - for ( uint i = start; i < nPoints; i++ ) - { - const Point &p1 = points[i]; - const Point &p2 = points[lastPos]; - - if ( edge.isInside( p1 ) ) - { - if ( edge.isInside( p2 ) ) - { - clippedPoints.add( p1 ); - } - else - { - clippedPoints.add( edge.intersection( p1, p2 ) ); - clippedPoints.add( p1 ); - } - } - else - { - if ( edge.isInside( p2 ) ) - { - clippedPoints.add( edge.intersection( p1, p2 ) ); - } - } - lastPos = i; - } - } - - const Rect d_clipRect; -}; - -class QwtCircleClipper -{ -public: - QwtCircleClipper( const QRectF &r ); - QVector clipCircle( const QPointF &, double radius ) const; - -private: - enum Edge - { - Left, - Top, - Right, - Bottom, - - NEdges - }; - - QList cuttingPoints( - Edge, const QPointF &pos, double radius ) const; - - double toAngle( const QPointF &, const QPointF & ) const; - - const QRectF d_rect; -}; - - -QwtCircleClipper::QwtCircleClipper( const QRectF &r ): - d_rect( r ) -{ -} - -QVector QwtCircleClipper::clipCircle( - const QPointF &pos, double radius ) const -{ - QList points; - for ( int edge = 0; edge < NEdges; edge++ ) - points += cuttingPoints( ( Edge )edge, pos, radius ); - - QVector intv; - if ( points.size() <= 0 ) - { - QRectF cRect( 0, 0, 2 * radius, 2 * radius ); - cRect.moveCenter( pos ); - if ( d_rect.contains( cRect ) ) - intv += QwtInterval( 0.0, 2 * M_PI ); - } - else - { - QList angles; - for ( int i = 0; i < points.size(); i++ ) - angles += toAngle( pos, points[i] ); - qSort( angles ); - - const int in = d_rect.contains( qwtPolar2Pos( pos, radius, - angles[0] + ( angles[1] - angles[0] ) / 2 ) ); - - if ( in ) - { - for ( int i = 0; i < angles.size() - 1; i += 2 ) - intv += QwtInterval( angles[i], angles[i+1] ); - } - else - { - for ( int i = 1; i < angles.size() - 1; i += 2 ) - intv += QwtInterval( angles[i], angles[i+1] ); - intv += QwtInterval( angles.last(), angles.first() ); - } - } - - return intv; -} - -double QwtCircleClipper::toAngle( - const QPointF &from, const QPointF &to ) const -{ - if ( from.x() == to.x() ) - return from.y() <= to.y() ? M_PI / 2.0 : 3 * M_PI / 2.0; - - const double m = qAbs( ( to.y() - from.y() ) / ( to.x() - from.x() ) ); - - double angle = qAtan( m ); - if ( to.x() > from.x() ) - { - if ( to.y() > from.y() ) - angle = 2 * M_PI - angle; - } - else - { - if ( to.y() > from.y() ) - angle = M_PI + angle; - else - angle = M_PI - angle; - } - - return angle; -} - -QList QwtCircleClipper::cuttingPoints( - Edge edge, const QPointF &pos, double radius ) const -{ - QList points; - - if ( edge == Left || edge == Right ) - { - const double x = ( edge == Left ) ? d_rect.left() : d_rect.right(); - if ( qAbs( pos.x() - x ) < radius ) - { - const double off = qSqrt( qwtSqr( radius ) - qwtSqr( pos.x() - x ) ); - const double m_y1 = pos.y() + off; - if ( m_y1 >= d_rect.top() && m_y1 <= d_rect.bottom() ) - points += QPointF( x, m_y1 ); - - const double m_y2 = pos.y() - off; - if ( m_y2 >= d_rect.top() && m_y2 <= d_rect.bottom() ) - points += QPointF( x, m_y2 ); - } - } - else - { - const double y = ( edge == Top ) ? d_rect.top() : d_rect.bottom(); - if ( qAbs( pos.y() - y ) < radius ) - { - const double off = qSqrt( qwtSqr( radius ) - qwtSqr( pos.y() - y ) ); - const double x1 = pos.x() + off; - if ( x1 >= d_rect.left() && x1 <= d_rect.right() ) - points += QPointF( x1, y ); - - const double m_x2 = pos.x() - off; - if ( m_x2 >= d_rect.left() && m_x2 <= d_rect.right() ) - points += QPointF( m_x2, y ); - } - } - return points; -} - -/*! - Sutherland-Hodgman polygon clipping - - \param clipRect Clip rectangle - \param polygon Polygon - \param closePolygon True, when the polygon is closed - - \return Clipped polygon -*/ -QPolygon QwtClipper::clipPolygon( - const QRect &clipRect, const QPolygon &polygon, bool closePolygon ) -{ - QwtPolygonClipper clipper( clipRect ); - return clipper.clipPolygon( polygon, closePolygon ); -} - -/*! - Sutherland-Hodgman polygon clipping - - \param clipRect Clip rectangle - \param polygon Polygon - \param closePolygon True, when the polygon is closed - - \return Clipped polygon -*/ -QPolygonF QwtClipper::clipPolygonF( - const QRectF &clipRect, const QPolygonF &polygon, bool closePolygon ) -{ - QwtPolygonClipper clipper( clipRect ); - return clipper.clipPolygon( polygon, closePolygon ); -} - -/*! - Circle clipping - - clipCircle() devides a circle into intervals of angles representing arcs - of the circle. When the circle is completely inside the clip rectangle - an interval [0.0, 2 * M_PI] is returned. - - \param clipRect Clip rectangle - \param center Center of the circle - \param radius Radius of the circle - - \return Arcs of the circle -*/ -QVector QwtClipper::clipCircle( const QRectF &clipRect, - const QPointF ¢er, double radius ) -{ - QwtCircleClipper clipper( clipRect ); - return clipper.clipCircle( center, radius ); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_clipper.h" +#include "qwt_point_polar.h" +#include + +#if QT_VERSION < 0x040601 +#define qAtan(x) ::atan(x) +#endif + +namespace QwtClip +{ + // some templates used for inlining + template class LeftEdge; + template class RightEdge; + template class TopEdge; + template class BottomEdge; + + template class PointBuffer; +} + +template +class QwtClip::LeftEdge +{ +public: + inline LeftEdge( Value x1, Value, Value, Value ): + d_x1( x1 ) + { + } + + inline bool isInside( const Point &p ) const + { + return p.x() >= d_x1; + } + + inline Point intersection( const Point &p1, const Point &p2 ) const + { + double dy = ( p1.y() - p2.y() ) / double( p1.x() - p2.x() ); + return Point( d_x1, ( Value ) ( p2.y() + ( d_x1 - p2.x() ) * dy ) ); + } +private: + const Value d_x1; +}; + +template +class QwtClip::RightEdge +{ +public: + inline RightEdge( Value, Value x2, Value, Value ): + d_x2( x2 ) + { + } + + inline bool isInside( const Point &p ) const + { + return p.x() <= d_x2; + } + + inline Point intersection( const Point &p1, const Point &p2 ) const + { + double dy = ( p1.y() - p2.y() ) / double( p1.x() - p2.x() ); + return Point( d_x2, ( Value ) ( p2.y() + ( d_x2 - p2.x() ) * dy ) ); + } + +private: + const Value d_x2; +}; + +template +class QwtClip::TopEdge +{ +public: + inline TopEdge( Value, Value, Value y1, Value ): + d_y1( y1 ) + { + } + + inline bool isInside( const Point &p ) const + { + return p.y() >= d_y1; + } + + inline Point intersection( const Point &p1, const Point &p2 ) const + { + double dx = ( p1.x() - p2.x() ) / double( p1.y() - p2.y() ); + return Point( ( Value )( p2.x() + ( d_y1 - p2.y() ) * dx ), d_y1 ); + } + +private: + const Value d_y1; +}; + +template +class QwtClip::BottomEdge +{ +public: + inline BottomEdge( Value, Value, Value, Value y2 ): + d_y2( y2 ) + { + } + + inline bool isInside( const Point &p ) const + { + return p.y() <= d_y2; + } + + inline Point intersection( const Point &p1, const Point &p2 ) const + { + double dx = ( p1.x() - p2.x() ) / double( p1.y() - p2.y() ); + return Point( ( Value )( p2.x() + ( d_y2 - p2.y() ) * dx ), d_y2 ); + } + +private: + const Value d_y2; +}; + +template +class QwtClip::PointBuffer +{ +public: + PointBuffer( int capacity = 0 ): + m_capacity( 0 ), + m_size( 0 ), + m_buffer( NULL ) + { + if ( capacity > 0 ) + reserve( capacity ); + } + + ~PointBuffer() + { + if ( m_buffer ) + qFree( m_buffer ); + } + + inline void setPoints( int numPoints, const Point *points ) + { + reserve( numPoints ); + + m_size = numPoints; + qMemCopy( m_buffer, points, m_size * sizeof( Point ) ); + } + + inline void reset() + { + m_size = 0; + } + + inline int size() const + { + return m_size; + } + + inline Point *data() const + { + return m_buffer; + } + + inline Point &operator[]( int i ) + { + return m_buffer[i]; + } + + inline const Point &operator[]( int i ) const + { + return m_buffer[i]; + } + + inline void add( const Point &point ) + { + if ( m_capacity <= m_size ) + reserve( m_size + 1 ); + + m_buffer[m_size++] = point; + } + +private: + inline void reserve( int size ) + { + if ( m_capacity == 0 ) + m_capacity = 1; + + while ( m_capacity < size ) + m_capacity *= 2; + + m_buffer = ( Point * ) qRealloc( + m_buffer, m_capacity * sizeof( Point ) ); + } + + int m_capacity; + int m_size; + Point *m_buffer; +}; + +using namespace QwtClip; + +template +class QwtPolygonClipper +{ +public: + QwtPolygonClipper( const Rect &clipRect ): + d_clipRect( clipRect ) + { + } + + Polygon clipPolygon( const Polygon &polygon, bool closePolygon ) const + { +#if 0 + if ( d_clipRect.contains( polygon.boundingRect() ) ) + return polygon; +#endif + + PointBuffer points1; + PointBuffer points2( qMin( 256, polygon.size() ) ); + + points1.setPoints( polygon.size(), polygon.data() ); + + clipEdge< LeftEdge >( closePolygon, points1, points2 ); + clipEdge< RightEdge >( closePolygon, points2, points1 ); + clipEdge< TopEdge >( closePolygon, points1, points2 ); + clipEdge< BottomEdge >( closePolygon, points2, points1 ); + + Polygon p; + p.resize( points1.size() ); + qMemCopy( p.data(), points1.data(), points1.size() * sizeof( Point ) ); + + return p; + } + +private: + template + inline void clipEdge( bool closePolygon, + PointBuffer &points, PointBuffer &clippedPoints ) const + { + clippedPoints.reset(); + + if ( points.size() < 2 ) + { + if ( points.size() == 1 ) + clippedPoints.add( points[0] ); + return; + } + + const Edge edge( d_clipRect.x(), d_clipRect.x() + d_clipRect.width(), + d_clipRect.y(), d_clipRect.y() + d_clipRect.height() ); + + int lastPos, start; + if ( closePolygon ) + { + start = 0; + lastPos = points.size() - 1; + } + else + { + start = 1; + lastPos = 0; + + if ( edge.isInside( points[0] ) ) + clippedPoints.add( points[0] ); + } + + const uint nPoints = points.size(); + for ( uint i = start; i < nPoints; i++ ) + { + const Point &p1 = points[i]; + const Point &p2 = points[lastPos]; + + if ( edge.isInside( p1 ) ) + { + if ( edge.isInside( p2 ) ) + { + clippedPoints.add( p1 ); + } + else + { + clippedPoints.add( edge.intersection( p1, p2 ) ); + clippedPoints.add( p1 ); + } + } + else + { + if ( edge.isInside( p2 ) ) + { + clippedPoints.add( edge.intersection( p1, p2 ) ); + } + } + lastPos = i; + } + } + + const Rect d_clipRect; +}; + +class QwtCircleClipper +{ +public: + QwtCircleClipper( const QRectF &r ); + QVector clipCircle( const QPointF &, double radius ) const; + +private: + enum Edge + { + Left, + Top, + Right, + Bottom, + + NEdges + }; + + QList cuttingPoints( + Edge, const QPointF &pos, double radius ) const; + + double toAngle( const QPointF &, const QPointF & ) const; + + const QRectF d_rect; +}; + + +QwtCircleClipper::QwtCircleClipper( const QRectF &r ): + d_rect( r ) +{ +} + +QVector QwtCircleClipper::clipCircle( + const QPointF &pos, double radius ) const +{ + QList points; + for ( int edge = 0; edge < NEdges; edge++ ) + points += cuttingPoints( ( Edge )edge, pos, radius ); + + QVector intv; + if ( points.size() <= 0 ) + { + QRectF cRect( 0, 0, 2 * radius, 2 * radius ); + cRect.moveCenter( pos ); + if ( d_rect.contains( cRect ) ) + intv += QwtInterval( 0.0, 2 * M_PI ); + } + else + { + QList angles; + for ( int i = 0; i < points.size(); i++ ) + angles += toAngle( pos, points[i] ); + qSort( angles ); + + const int in = d_rect.contains( qwtPolar2Pos( pos, radius, + angles[0] + ( angles[1] - angles[0] ) / 2 ) ); + + if ( in ) + { + for ( int i = 0; i < angles.size() - 1; i += 2 ) + intv += QwtInterval( angles[i], angles[i+1] ); + } + else + { + for ( int i = 1; i < angles.size() - 1; i += 2 ) + intv += QwtInterval( angles[i], angles[i+1] ); + intv += QwtInterval( angles.last(), angles.first() ); + } + } + + return intv; +} + +double QwtCircleClipper::toAngle( + const QPointF &from, const QPointF &to ) const +{ + if ( from.x() == to.x() ) + return from.y() <= to.y() ? M_PI / 2.0 : 3 * M_PI / 2.0; + + const double m = qAbs( ( to.y() - from.y() ) / ( to.x() - from.x() ) ); + + double angle = qAtan( m ); + if ( to.x() > from.x() ) + { + if ( to.y() > from.y() ) + angle = 2 * M_PI - angle; + } + else + { + if ( to.y() > from.y() ) + angle = M_PI + angle; + else + angle = M_PI - angle; + } + + return angle; +} + +QList QwtCircleClipper::cuttingPoints( + Edge edge, const QPointF &pos, double radius ) const +{ + QList points; + + if ( edge == Left || edge == Right ) + { + const double x = ( edge == Left ) ? d_rect.left() : d_rect.right(); + if ( qAbs( pos.x() - x ) < radius ) + { + const double off = qSqrt( qwtSqr( radius ) - qwtSqr( pos.x() - x ) ); + const double m_y1 = pos.y() + off; + if ( m_y1 >= d_rect.top() && m_y1 <= d_rect.bottom() ) + points += QPointF( x, m_y1 ); + + const double m_y2 = pos.y() - off; + if ( m_y2 >= d_rect.top() && m_y2 <= d_rect.bottom() ) + points += QPointF( x, m_y2 ); + } + } + else + { + const double y = ( edge == Top ) ? d_rect.top() : d_rect.bottom(); + if ( qAbs( pos.y() - y ) < radius ) + { + const double off = qSqrt( qwtSqr( radius ) - qwtSqr( pos.y() - y ) ); + const double x1 = pos.x() + off; + if ( x1 >= d_rect.left() && x1 <= d_rect.right() ) + points += QPointF( x1, y ); + + const double m_x2 = pos.x() - off; + if ( m_x2 >= d_rect.left() && m_x2 <= d_rect.right() ) + points += QPointF( m_x2, y ); + } + } + return points; +} + +/*! + Sutherland-Hodgman polygon clipping + + \param clipRect Clip rectangle + \param polygon Polygon + \param closePolygon True, when the polygon is closed + + \return Clipped polygon +*/ +QPolygon QwtClipper::clipPolygon( + const QRect &clipRect, const QPolygon &polygon, bool closePolygon ) +{ + QwtPolygonClipper clipper( clipRect ); + return clipper.clipPolygon( polygon, closePolygon ); +} + +/*! + Sutherland-Hodgman polygon clipping + + \param clipRect Clip rectangle + \param polygon Polygon + \param closePolygon True, when the polygon is closed + + \return Clipped polygon +*/ +QPolygonF QwtClipper::clipPolygonF( + const QRectF &clipRect, const QPolygonF &polygon, bool closePolygon ) +{ + QwtPolygonClipper clipper( clipRect ); + return clipper.clipPolygon( polygon, closePolygon ); +} + +/*! + Circle clipping + + clipCircle() devides a circle into intervals of angles representing arcs + of the circle. When the circle is completely inside the clip rectangle + an interval [0.0, 2 * M_PI] is returned. + + \param clipRect Clip rectangle + \param center Center of the circle + \param radius Radius of the circle + + \return Arcs of the circle +*/ +QVector QwtClipper::clipCircle( const QRectF &clipRect, + const QPointF ¢er, double radius ) +{ + QwtCircleClipper clipper( clipRect ); + return clipper.clipCircle( center, radius ); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_clipper.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_clipper.h index 2f28f7982..98316d31f 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_clipper.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_clipper.h @@ -1,37 +1,37 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_CLIPPER_H -#define QWT_CLIPPER_H - -#include "qwt_global.h" -#include "qwt_interval.h" -#include -#include - -class QRect; -class QRectF; - -/*! - \brief Some clipping algos -*/ - -class QWT_EXPORT QwtClipper -{ -public: - static QPolygon clipPolygon( const QRect &, - const QPolygon &, bool closePolygon = false ); - static QPolygonF clipPolygonF( const QRectF &, - const QPolygonF &, bool closePolygon = false ); - - static QVector clipCircle( - const QRectF &, const QPointF &, double radius ); -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_CLIPPER_H +#define QWT_CLIPPER_H + +#include "qwt_global.h" +#include "qwt_interval.h" +#include +#include + +class QRect; +class QRectF; + +/*! + \brief Some clipping algos +*/ + +class QWT_EXPORT QwtClipper +{ +public: + static QPolygon clipPolygon( const QRect &, + const QPolygon &, bool closePolygon = false ); + static QPolygonF clipPolygonF( const QRectF &, + const QPolygonF &, bool closePolygon = false ); + + static QVector clipCircle( + const QRectF &, const QPointF &, double radius ); +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_color_map.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_color_map.cpp index 48ce721ed..4318e5a0a 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_color_map.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_color_map.cpp @@ -1,440 +1,440 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_color_map.h" -#include "qwt_math.h" -#include "qwt_interval.h" -#include - -class QwtLinearColorMap::ColorStops -{ -public: - ColorStops() - { - _stops.reserve( 256 ); - } - - void insert( double pos, const QColor &color ); - QRgb rgb( QwtLinearColorMap::Mode, double pos ) const; - - QVector stops() const; - -private: - - class ColorStop - { - public: - ColorStop(): - pos( 0.0 ), - rgb( 0 ) - { - }; - - ColorStop( double p, const QColor &c ): - pos( p ), - rgb( c.rgb() ) - { - r = qRed( rgb ); - g = qGreen( rgb ); - b = qBlue( rgb ); - } - - double pos; - QRgb rgb; - int r, g, b; - }; - - inline int findUpper( double pos ) const; - QVector _stops; -}; - -void QwtLinearColorMap::ColorStops::insert( double pos, const QColor &color ) -{ - // Lookups need to be very fast, insertions are not so important. - // Anyway, a balanced tree is what we need here. TODO ... - - if ( pos < 0.0 || pos > 1.0 ) - return; - - int index; - if ( _stops.size() == 0 ) - { - index = 0; - _stops.resize( 1 ); - } - else - { - index = findUpper( pos ); - if ( index == _stops.size() || - qAbs( _stops[index].pos - pos ) >= 0.001 ) - { - _stops.resize( _stops.size() + 1 ); - for ( int i = _stops.size() - 1; i > index; i-- ) - _stops[i] = _stops[i-1]; - } - } - - _stops[index] = ColorStop( pos, color ); -} - -inline QVector QwtLinearColorMap::ColorStops::stops() const -{ - QVector positions( _stops.size() ); - for ( int i = 0; i < _stops.size(); i++ ) - positions[i] = _stops[i].pos; - return positions; -} - -inline int QwtLinearColorMap::ColorStops::findUpper( double pos ) const -{ - int index = 0; - int n = _stops.size(); - - const ColorStop *stops = _stops.data(); - - while ( n > 0 ) - { - const int half = n >> 1; - const int middle = index + half; - - if ( stops[middle].pos <= pos ) - { - index = middle + 1; - n -= half + 1; - } - else - n = half; - } - - return index; -} - -inline QRgb QwtLinearColorMap::ColorStops::rgb( - QwtLinearColorMap::Mode mode, double pos ) const -{ - if ( pos <= 0.0 ) - return _stops[0].rgb; - if ( pos >= 1.0 ) - return _stops[ _stops.size() - 1 ].rgb; - - const int index = findUpper( pos ); - if ( mode == FixedColors ) - { - return _stops[index-1].rgb; - } - else - { - const ColorStop &s1 = _stops[index-1]; - const ColorStop &s2 = _stops[index]; - - const double ratio = ( pos - s1.pos ) / ( s2.pos - s1.pos ); - - const int r = s1.r + qRound( ratio * ( s2.r - s1.r ) ); - const int g = s1.g + qRound( ratio * ( s2.g - s1.g ) ); - const int b = s1.b + qRound( ratio * ( s2.b - s1.b ) ); - - return qRgb( r, g, b ); - } -} - -//! Constructor -QwtColorMap::QwtColorMap( Format format ): - d_format( format ) -{ -} - -//! Destructor -QwtColorMap::~QwtColorMap() -{ -} - -/*! - Build and return a color map of 256 colors - - The color table is needed for rendering indexed images in combination - with using colorIndex(). - - \param interval Range for the values - \return A color table, that can be used for a QImage -*/ -QVector QwtColorMap::colorTable( const QwtInterval &interval ) const -{ - QVector table( 256 ); - - if ( interval.isValid() ) - { - const double step = interval.width() / ( table.size() - 1 ); - for ( int i = 0; i < table.size(); i++ ) - table[i] = rgb( interval, interval.minValue() + step * i ); - } - - return table; -} - -class QwtLinearColorMap::PrivateData -{ -public: - ColorStops colorStops; - QwtLinearColorMap::Mode mode; -}; - -/*! - Build a color map with two stops at 0.0 and 1.0. The color - at 0.0 is Qt::blue, at 1.0 it is Qt::yellow. - - \param format Preferred format of the color map -*/ -QwtLinearColorMap::QwtLinearColorMap( QwtColorMap::Format format ): - QwtColorMap( format ) -{ - d_data = new PrivateData; - d_data->mode = ScaledColors; - - setColorInterval( Qt::blue, Qt::yellow ); -} - -/*! - Build a color map with two stops at 0.0 and 1.0. - - \param color1 Color used for the minimum value of the value interval - \param color2 Color used for the maximum value of the value interval - \param format Preferred format of the coor map -*/ -QwtLinearColorMap::QwtLinearColorMap( const QColor &color1, - const QColor &color2, QwtColorMap::Format format ): - QwtColorMap( format ) -{ - d_data = new PrivateData; - d_data->mode = ScaledColors; - setColorInterval( color1, color2 ); -} - -//! Destructor -QwtLinearColorMap::~QwtLinearColorMap() -{ - delete d_data; -} - -/*! - \brief Set the mode of the color map - - FixedColors means the color is calculated from the next lower - color stop. ScaledColors means the color is calculated - by interpolating the colors of the adjacent stops. - - \sa mode() -*/ -void QwtLinearColorMap::setMode( Mode mode ) -{ - d_data->mode = mode; -} - -/*! - \return Mode of the color map - \sa setMode() -*/ -QwtLinearColorMap::Mode QwtLinearColorMap::mode() const -{ - return d_data->mode; -} - -/*! - Set the color range - - Add stops at 0.0 and 1.0. - - \param color1 Color used for the minimum value of the value interval - \param color2 Color used for the maximum value of the value interval - - \sa color1(), color2() -*/ -void QwtLinearColorMap::setColorInterval( - const QColor &color1, const QColor &color2 ) -{ - d_data->colorStops = ColorStops(); - d_data->colorStops.insert( 0.0, color1 ); - d_data->colorStops.insert( 1.0, color2 ); -} - -/*! - Add a color stop - - The value has to be in the range [0.0, 1.0]. - F.e. a stop at position 17.0 for a range [10.0,20.0] must be - passed as: (17.0 - 10.0) / (20.0 - 10.0) - - \param value Value between [0.0, 1.0] - \param color Color stop -*/ -void QwtLinearColorMap::addColorStop( double value, const QColor& color ) -{ - if ( value >= 0.0 && value <= 1.0 ) - d_data->colorStops.insert( value, color ); -} - -/*! - Return all positions of color stops in increasing order -*/ -QVector QwtLinearColorMap::colorStops() const -{ - return d_data->colorStops.stops(); -} - -/*! - \return the first color of the color range - \sa setColorInterval() -*/ -QColor QwtLinearColorMap::color1() const -{ - return QColor( d_data->colorStops.rgb( d_data->mode, 0.0 ) ); -} - -/*! - \return the second color of the color range - \sa setColorInterval() -*/ -QColor QwtLinearColorMap::color2() const -{ - return QColor( d_data->colorStops.rgb( d_data->mode, 1.0 ) ); -} - -/*! - Map a value of a given interval into a rgb value - - \param interval Range for all values - \param value Value to map into a rgb value -*/ -QRgb QwtLinearColorMap::rgb( - const QwtInterval &interval, double value ) const -{ - if ( qIsNaN(value) ) - return qRgba(0, 0, 0, 0); - - const double width = interval.width(); - - double ratio = 0.0; - if ( width > 0.0 ) - ratio = ( value - interval.minValue() ) / width; - - return d_data->colorStops.rgb( d_data->mode, ratio ); -} - -/*! - Map a value of a given interval into a color index, between 0 and 255 - - \param interval Range for all values - \param value Value to map into a color index -*/ -unsigned char QwtLinearColorMap::colorIndex( - const QwtInterval &interval, double value ) const -{ - const double width = interval.width(); - - if ( qIsNaN(value) || width <= 0.0 || value <= interval.minValue() ) - return 0; - - if ( value >= interval.maxValue() ) - return ( unsigned char )255; - - const double ratio = ( value - interval.minValue() ) / width; - - unsigned char index; - if ( d_data->mode == FixedColors ) - index = ( unsigned char )( ratio * 255 ); // always floor - else - index = ( unsigned char )qRound( ratio * 255 ); - - return index; -} - -class QwtAlphaColorMap::PrivateData -{ -public: - QColor color; - QRgb rgb; -}; - - -/*! - Constructor - \param color Color of the map -*/ -QwtAlphaColorMap::QwtAlphaColorMap( const QColor &color ): - QwtColorMap( QwtColorMap::RGB ) -{ - d_data = new PrivateData; - d_data->color = color; - d_data->rgb = color.rgb() & qRgba( 255, 255, 255, 0 ); -} - -//! Destructor -QwtAlphaColorMap::~QwtAlphaColorMap() -{ - delete d_data; -} - -/*! - Set the color - - \param color Color - \sa color() -*/ -void QwtAlphaColorMap::setColor( const QColor &color ) -{ - d_data->color = color; - d_data->rgb = color.rgb(); -} - -/*! - \return the color - \sa setColor() -*/ -QColor QwtAlphaColorMap::color() const -{ - return d_data->color; -} - -/*! - \brief Map a value of a given interval into a alpha value - - alpha := (value - interval.minValue()) / interval.width(); - - \param interval Range for all values - \param value Value to map into a rgb value - \return rgb value, with an alpha value -*/ -QRgb QwtAlphaColorMap::rgb( const QwtInterval &interval, double value ) const -{ - const double width = interval.width(); - if ( !qIsNaN(value) && width >= 0.0 ) - { - const double ratio = ( value - interval.minValue() ) / width; - int alpha = qRound( 255 * ratio ); - if ( alpha < 0 ) - alpha = 0; - if ( alpha > 255 ) - alpha = 255; - - return d_data->rgb | ( alpha << 24 ); - } - return d_data->rgb; -} - -/*! - Dummy function, needed to be implemented as it is pure virtual - in QwtColorMap. Color indices make no sense in combination with - an alpha channel. - - \return Always 0 -*/ -unsigned char QwtAlphaColorMap::colorIndex( - const QwtInterval &, double ) const -{ - return 0; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_color_map.h" +#include "qwt_math.h" +#include "qwt_interval.h" +#include + +class QwtLinearColorMap::ColorStops +{ +public: + ColorStops() + { + _stops.reserve( 256 ); + } + + void insert( double pos, const QColor &color ); + QRgb rgb( QwtLinearColorMap::Mode, double pos ) const; + + QVector stops() const; + +private: + + class ColorStop + { + public: + ColorStop(): + pos( 0.0 ), + rgb( 0 ) + { + }; + + ColorStop( double p, const QColor &c ): + pos( p ), + rgb( c.rgb() ) + { + r = qRed( rgb ); + g = qGreen( rgb ); + b = qBlue( rgb ); + } + + double pos; + QRgb rgb; + int r, g, b; + }; + + inline int findUpper( double pos ) const; + QVector _stops; +}; + +void QwtLinearColorMap::ColorStops::insert( double pos, const QColor &color ) +{ + // Lookups need to be very fast, insertions are not so important. + // Anyway, a balanced tree is what we need here. TODO ... + + if ( pos < 0.0 || pos > 1.0 ) + return; + + int index; + if ( _stops.size() == 0 ) + { + index = 0; + _stops.resize( 1 ); + } + else + { + index = findUpper( pos ); + if ( index == _stops.size() || + qAbs( _stops[index].pos - pos ) >= 0.001 ) + { + _stops.resize( _stops.size() + 1 ); + for ( int i = _stops.size() - 1; i > index; i-- ) + _stops[i] = _stops[i-1]; + } + } + + _stops[index] = ColorStop( pos, color ); +} + +inline QVector QwtLinearColorMap::ColorStops::stops() const +{ + QVector positions( _stops.size() ); + for ( int i = 0; i < _stops.size(); i++ ) + positions[i] = _stops[i].pos; + return positions; +} + +inline int QwtLinearColorMap::ColorStops::findUpper( double pos ) const +{ + int index = 0; + int n = _stops.size(); + + const ColorStop *stops = _stops.data(); + + while ( n > 0 ) + { + const int half = n >> 1; + const int middle = index + half; + + if ( stops[middle].pos <= pos ) + { + index = middle + 1; + n -= half + 1; + } + else + n = half; + } + + return index; +} + +inline QRgb QwtLinearColorMap::ColorStops::rgb( + QwtLinearColorMap::Mode mode, double pos ) const +{ + if ( pos <= 0.0 ) + return _stops[0].rgb; + if ( pos >= 1.0 ) + return _stops[ _stops.size() - 1 ].rgb; + + const int index = findUpper( pos ); + if ( mode == FixedColors ) + { + return _stops[index-1].rgb; + } + else + { + const ColorStop &s1 = _stops[index-1]; + const ColorStop &s2 = _stops[index]; + + const double ratio = ( pos - s1.pos ) / ( s2.pos - s1.pos ); + + const int r = s1.r + qRound( ratio * ( s2.r - s1.r ) ); + const int g = s1.g + qRound( ratio * ( s2.g - s1.g ) ); + const int b = s1.b + qRound( ratio * ( s2.b - s1.b ) ); + + return qRgb( r, g, b ); + } +} + +//! Constructor +QwtColorMap::QwtColorMap( Format format ): + d_format( format ) +{ +} + +//! Destructor +QwtColorMap::~QwtColorMap() +{ +} + +/*! + Build and return a color map of 256 colors + + The color table is needed for rendering indexed images in combination + with using colorIndex(). + + \param interval Range for the values + \return A color table, that can be used for a QImage +*/ +QVector QwtColorMap::colorTable( const QwtInterval &interval ) const +{ + QVector table( 256 ); + + if ( interval.isValid() ) + { + const double step = interval.width() / ( table.size() - 1 ); + for ( int i = 0; i < table.size(); i++ ) + table[i] = rgb( interval, interval.minValue() + step * i ); + } + + return table; +} + +class QwtLinearColorMap::PrivateData +{ +public: + ColorStops colorStops; + QwtLinearColorMap::Mode mode; +}; + +/*! + Build a color map with two stops at 0.0 and 1.0. The color + at 0.0 is Qt::blue, at 1.0 it is Qt::yellow. + + \param format Preferred format of the color map +*/ +QwtLinearColorMap::QwtLinearColorMap( QwtColorMap::Format format ): + QwtColorMap( format ) +{ + d_data = new PrivateData; + d_data->mode = ScaledColors; + + setColorInterval( Qt::blue, Qt::yellow ); +} + +/*! + Build a color map with two stops at 0.0 and 1.0. + + \param color1 Color used for the minimum value of the value interval + \param color2 Color used for the maximum value of the value interval + \param format Preferred format of the coor map +*/ +QwtLinearColorMap::QwtLinearColorMap( const QColor &color1, + const QColor &color2, QwtColorMap::Format format ): + QwtColorMap( format ) +{ + d_data = new PrivateData; + d_data->mode = ScaledColors; + setColorInterval( color1, color2 ); +} + +//! Destructor +QwtLinearColorMap::~QwtLinearColorMap() +{ + delete d_data; +} + +/*! + \brief Set the mode of the color map + + FixedColors means the color is calculated from the next lower + color stop. ScaledColors means the color is calculated + by interpolating the colors of the adjacent stops. + + \sa mode() +*/ +void QwtLinearColorMap::setMode( Mode mode ) +{ + d_data->mode = mode; +} + +/*! + \return Mode of the color map + \sa setMode() +*/ +QwtLinearColorMap::Mode QwtLinearColorMap::mode() const +{ + return d_data->mode; +} + +/*! + Set the color range + + Add stops at 0.0 and 1.0. + + \param color1 Color used for the minimum value of the value interval + \param color2 Color used for the maximum value of the value interval + + \sa color1(), color2() +*/ +void QwtLinearColorMap::setColorInterval( + const QColor &color1, const QColor &color2 ) +{ + d_data->colorStops = ColorStops(); + d_data->colorStops.insert( 0.0, color1 ); + d_data->colorStops.insert( 1.0, color2 ); +} + +/*! + Add a color stop + + The value has to be in the range [0.0, 1.0]. + F.e. a stop at position 17.0 for a range [10.0,20.0] must be + passed as: (17.0 - 10.0) / (20.0 - 10.0) + + \param value Value between [0.0, 1.0] + \param color Color stop +*/ +void QwtLinearColorMap::addColorStop( double value, const QColor& color ) +{ + if ( value >= 0.0 && value <= 1.0 ) + d_data->colorStops.insert( value, color ); +} + +/*! + Return all positions of color stops in increasing order +*/ +QVector QwtLinearColorMap::colorStops() const +{ + return d_data->colorStops.stops(); +} + +/*! + \return the first color of the color range + \sa setColorInterval() +*/ +QColor QwtLinearColorMap::color1() const +{ + return QColor( d_data->colorStops.rgb( d_data->mode, 0.0 ) ); +} + +/*! + \return the second color of the color range + \sa setColorInterval() +*/ +QColor QwtLinearColorMap::color2() const +{ + return QColor( d_data->colorStops.rgb( d_data->mode, 1.0 ) ); +} + +/*! + Map a value of a given interval into a rgb value + + \param interval Range for all values + \param value Value to map into a rgb value +*/ +QRgb QwtLinearColorMap::rgb( + const QwtInterval &interval, double value ) const +{ + if ( qIsNaN(value) ) + return qRgba(0, 0, 0, 0); + + const double width = interval.width(); + + double ratio = 0.0; + if ( width > 0.0 ) + ratio = ( value - interval.minValue() ) / width; + + return d_data->colorStops.rgb( d_data->mode, ratio ); +} + +/*! + Map a value of a given interval into a color index, between 0 and 255 + + \param interval Range for all values + \param value Value to map into a color index +*/ +unsigned char QwtLinearColorMap::colorIndex( + const QwtInterval &interval, double value ) const +{ + const double width = interval.width(); + + if ( qIsNaN(value) || width <= 0.0 || value <= interval.minValue() ) + return 0; + + if ( value >= interval.maxValue() ) + return ( unsigned char )255; + + const double ratio = ( value - interval.minValue() ) / width; + + unsigned char index; + if ( d_data->mode == FixedColors ) + index = ( unsigned char )( ratio * 255 ); // always floor + else + index = ( unsigned char )qRound( ratio * 255 ); + + return index; +} + +class QwtAlphaColorMap::PrivateData +{ +public: + QColor color; + QRgb rgb; +}; + + +/*! + Constructor + \param color Color of the map +*/ +QwtAlphaColorMap::QwtAlphaColorMap( const QColor &color ): + QwtColorMap( QwtColorMap::RGB ) +{ + d_data = new PrivateData; + d_data->color = color; + d_data->rgb = color.rgb() & qRgba( 255, 255, 255, 0 ); +} + +//! Destructor +QwtAlphaColorMap::~QwtAlphaColorMap() +{ + delete d_data; +} + +/*! + Set the color + + \param color Color + \sa color() +*/ +void QwtAlphaColorMap::setColor( const QColor &color ) +{ + d_data->color = color; + d_data->rgb = color.rgb(); +} + +/*! + \return the color + \sa setColor() +*/ +QColor QwtAlphaColorMap::color() const +{ + return d_data->color; +} + +/*! + \brief Map a value of a given interval into a alpha value + + alpha := (value - interval.minValue()) / interval.width(); + + \param interval Range for all values + \param value Value to map into a rgb value + \return rgb value, with an alpha value +*/ +QRgb QwtAlphaColorMap::rgb( const QwtInterval &interval, double value ) const +{ + const double width = interval.width(); + if ( !qIsNaN(value) && width >= 0.0 ) + { + const double ratio = ( value - interval.minValue() ) / width; + int alpha = qRound( 255 * ratio ); + if ( alpha < 0 ) + alpha = 0; + if ( alpha > 255 ) + alpha = 255; + + return d_data->rgb | ( alpha << 24 ); + } + return d_data->rgb; +} + +/*! + Dummy function, needed to be implemented as it is pure virtual + in QwtColorMap. Color indices make no sense in combination with + an alpha channel. + + \return Always 0 +*/ +unsigned char QwtAlphaColorMap::colorIndex( + const QwtInterval &, double ) const +{ + return 0; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_color_map.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_color_map.h index a59530c3f..e75483026 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_color_map.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_color_map.h @@ -1,198 +1,198 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_COLOR_MAP_H -#define QWT_COLOR_MAP_H - -#include "qwt_global.h" -#include "qwt_interval.h" -#include -#include - -/*! - \brief QwtColorMap is used to map values into colors. - - For displaying 3D data on a 2D plane the 3rd dimension is often - displayed using colors, like f.e in a spectrogram. - - Each color map is optimized to return colors for only one of the - following image formats: - - - QImage::Format_Indexed8\n - - QImage::Format_ARGB32\n - - \sa QwtPlotSpectrogram, QwtScaleWidget -*/ - -class QWT_EXPORT QwtColorMap -{ -public: - /*! - Format for color mapping - \sa rgb(), colorIndex(), colorTable() - */ - - enum Format - { - //! The map is intended to map into QRgb values. - RGB, - - /*! - The map is intended to map into 8 bit values, that - are indices into the color table. - */ - Indexed - }; - - QwtColorMap( Format = QwtColorMap::RGB ); - virtual ~QwtColorMap(); - - Format format() const; - - /*! - Map a value of a given interval into a rgb value. - \param interval Range for the values - \param value Value - \return rgb value, corresponding to value - */ - virtual QRgb rgb( const QwtInterval &interval, - double value ) const = 0; - - /*! - Map a value of a given interval into a color index - \param interval Range for the values - \param value Value - \return color index, corresponding to value - */ - virtual unsigned char colorIndex( - const QwtInterval &interval, double value ) const = 0; - - QColor color( const QwtInterval &, double value ) const; - virtual QVector colorTable( const QwtInterval & ) const; - -private: - Format d_format; -}; - -/*! - \brief QwtLinearColorMap builds a color map from color stops. - - A color stop is a color at a specific position. The valid - range for the positions is [0.0, 1.0]. When mapping a value - into a color it is translated into this interval according to mode(). -*/ -class QWT_EXPORT QwtLinearColorMap: public QwtColorMap -{ -public: - /*! - Mode of color map - \sa setMode(), mode() - */ - enum Mode - { - //! Return the color from the next lower color stop - FixedColors, - - //! Interpolating the colors of the adjacent stops. - ScaledColors - }; - - QwtLinearColorMap( QwtColorMap::Format = QwtColorMap::RGB ); - QwtLinearColorMap( const QColor &from, const QColor &to, - QwtColorMap::Format = QwtColorMap::RGB ); - - virtual ~QwtLinearColorMap(); - - void setMode( Mode ); - Mode mode() const; - - void setColorInterval( const QColor &color1, const QColor &color2 ); - void addColorStop( double value, const QColor& ); - QVector colorStops() const; - - QColor color1() const; - QColor color2() const; - - virtual QRgb rgb( const QwtInterval &, double value ) const; - virtual unsigned char colorIndex( - const QwtInterval &, double value ) const; - - class ColorStops; - -private: - // Disabled copy constructor and operator= - QwtLinearColorMap( const QwtLinearColorMap & ); - QwtLinearColorMap &operator=( const QwtLinearColorMap & ); - - class PrivateData; - PrivateData *d_data; -}; - -/*! - \brief QwtAlphaColorMap variies the alpha value of a color -*/ -class QWT_EXPORT QwtAlphaColorMap: public QwtColorMap -{ -public: - QwtAlphaColorMap( const QColor & = QColor( Qt::gray ) ); - virtual ~QwtAlphaColorMap(); - - void setColor( const QColor & ); - QColor color() const; - - virtual QRgb rgb( const QwtInterval &, double value ) const; - -private: - QwtAlphaColorMap( const QwtAlphaColorMap & ); - QwtAlphaColorMap &operator=( const QwtAlphaColorMap & ); - - virtual unsigned char colorIndex( - const QwtInterval &, double value ) const; - - class PrivateData; - PrivateData *d_data; -}; - - -/*! - Map a value into a color - - \param interval Valid interval for values - \param value Value - - \return Color corresponding to value - - \warning This method is slow for Indexed color maps. If it is - necessary to map many values, its better to get the - color table once and find the color using colorIndex(). -*/ -inline QColor QwtColorMap::color( - const QwtInterval &interval, double value ) const -{ - if ( d_format == RGB ) - { - return QColor( rgb( interval, value ) ); - } - else - { - const unsigned int index = colorIndex( interval, value ); - return colorTable( interval )[index]; // slow - } -} - -/*! - \return Intended format of the color map - \sa Format -*/ -inline QwtColorMap::Format QwtColorMap::format() const -{ - return d_format; -} - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_COLOR_MAP_H +#define QWT_COLOR_MAP_H + +#include "qwt_global.h" +#include "qwt_interval.h" +#include +#include + +/*! + \brief QwtColorMap is used to map values into colors. + + For displaying 3D data on a 2D plane the 3rd dimension is often + displayed using colors, like f.e in a spectrogram. + + Each color map is optimized to return colors for only one of the + following image formats: + + - QImage::Format_Indexed8\n + - QImage::Format_ARGB32\n + + \sa QwtPlotSpectrogram, QwtScaleWidget +*/ + +class QWT_EXPORT QwtColorMap +{ +public: + /*! + Format for color mapping + \sa rgb(), colorIndex(), colorTable() + */ + + enum Format + { + //! The map is intended to map into QRgb values. + RGB, + + /*! + The map is intended to map into 8 bit values, that + are indices into the color table. + */ + Indexed + }; + + QwtColorMap( Format = QwtColorMap::RGB ); + virtual ~QwtColorMap(); + + Format format() const; + + /*! + Map a value of a given interval into a rgb value. + \param interval Range for the values + \param value Value + \return rgb value, corresponding to value + */ + virtual QRgb rgb( const QwtInterval &interval, + double value ) const = 0; + + /*! + Map a value of a given interval into a color index + \param interval Range for the values + \param value Value + \return color index, corresponding to value + */ + virtual unsigned char colorIndex( + const QwtInterval &interval, double value ) const = 0; + + QColor color( const QwtInterval &, double value ) const; + virtual QVector colorTable( const QwtInterval & ) const; + +private: + Format d_format; +}; + +/*! + \brief QwtLinearColorMap builds a color map from color stops. + + A color stop is a color at a specific position. The valid + range for the positions is [0.0, 1.0]. When mapping a value + into a color it is translated into this interval according to mode(). +*/ +class QWT_EXPORT QwtLinearColorMap: public QwtColorMap +{ +public: + /*! + Mode of color map + \sa setMode(), mode() + */ + enum Mode + { + //! Return the color from the next lower color stop + FixedColors, + + //! Interpolating the colors of the adjacent stops. + ScaledColors + }; + + QwtLinearColorMap( QwtColorMap::Format = QwtColorMap::RGB ); + QwtLinearColorMap( const QColor &from, const QColor &to, + QwtColorMap::Format = QwtColorMap::RGB ); + + virtual ~QwtLinearColorMap(); + + void setMode( Mode ); + Mode mode() const; + + void setColorInterval( const QColor &color1, const QColor &color2 ); + void addColorStop( double value, const QColor& ); + QVector colorStops() const; + + QColor color1() const; + QColor color2() const; + + virtual QRgb rgb( const QwtInterval &, double value ) const; + virtual unsigned char colorIndex( + const QwtInterval &, double value ) const; + + class ColorStops; + +private: + // Disabled copy constructor and operator= + QwtLinearColorMap( const QwtLinearColorMap & ); + QwtLinearColorMap &operator=( const QwtLinearColorMap & ); + + class PrivateData; + PrivateData *d_data; +}; + +/*! + \brief QwtAlphaColorMap variies the alpha value of a color +*/ +class QWT_EXPORT QwtAlphaColorMap: public QwtColorMap +{ +public: + QwtAlphaColorMap( const QColor & = QColor( Qt::gray ) ); + virtual ~QwtAlphaColorMap(); + + void setColor( const QColor & ); + QColor color() const; + + virtual QRgb rgb( const QwtInterval &, double value ) const; + +private: + QwtAlphaColorMap( const QwtAlphaColorMap & ); + QwtAlphaColorMap &operator=( const QwtAlphaColorMap & ); + + virtual unsigned char colorIndex( + const QwtInterval &, double value ) const; + + class PrivateData; + PrivateData *d_data; +}; + + +/*! + Map a value into a color + + \param interval Valid interval for values + \param value Value + + \return Color corresponding to value + + \warning This method is slow for Indexed color maps. If it is + necessary to map many values, its better to get the + color table once and find the color using colorIndex(). +*/ +inline QColor QwtColorMap::color( + const QwtInterval &interval, double value ) const +{ + if ( d_format == RGB ) + { + return QColor( rgb( interval, value ) ); + } + else + { + const unsigned int index = colorIndex( interval, value ); + return colorTable( interval )[index]; // slow + } +} + +/*! + \return Intended format of the color map + \sa Format +*/ +inline QwtColorMap::Format QwtColorMap::format() const +{ + return d_format; +} + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_column_symbol.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_column_symbol.cpp index f46d79ad7..314e9d2f1 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_column_symbol.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_column_symbol.cpp @@ -1,296 +1,296 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_column_symbol.h" -#include "qwt_math.h" -#include "qwt_text.h" -#include "qwt_painter.h" -#include -#include - -static void drawBox( QPainter *p, const QRectF &rect, - const QPalette &pal, double lw ) -{ - if ( lw > 0.0 ) - { - if ( rect.width() == 0.0 ) - { - p->setPen( pal.dark().color() ); - p->drawLine( rect.topLeft(), rect.bottomLeft() ); - return; - } - - if ( rect.height() == 0.0 ) - { - p->setPen( pal.dark().color() ); - p->drawLine( rect.topLeft(), rect.topRight() ); - return; - } - - lw = qMin( lw, rect.height() / 2.0 - 1.0 ); - lw = qMin( lw, rect.width() / 2.0 - 1.0 ); - - const QRectF outerRect = rect.adjusted( 0, 0, 1, 1 ); - QPolygonF polygon( outerRect ); - - if ( outerRect.width() > 2 * lw && - outerRect.height() > 2 * lw ) - { - const QRectF innerRect = outerRect.adjusted( lw, lw, -lw, -lw ); - polygon = polygon.subtracted( innerRect ); - } - - p->setPen( Qt::NoPen ); - - p->setBrush( pal.dark() ); - p->drawPolygon( polygon ); - } - - const QRectF windowRect = rect.adjusted( lw, lw, -lw + 1, -lw + 1 ); - if ( windowRect.isValid() ) - p->fillRect( windowRect, pal.window() ); -} - -static void drawPanel( QPainter *painter, const QRectF &rect, - const QPalette &pal, double lw ) -{ - if ( lw > 0.0 ) - { - if ( rect.width() == 0.0 ) - { - painter->setPen( pal.window().color() ); - painter->drawLine( rect.topLeft(), rect.bottomLeft() ); - return; - } - - if ( rect.height() == 0.0 ) - { - painter->setPen( pal.window().color() ); - painter->drawLine( rect.topLeft(), rect.topRight() ); - return; - } - - lw = qMin( lw, rect.height() / 2.0 - 1.0 ); - lw = qMin( lw, rect.width() / 2.0 - 1.0 ); - - const QRectF outerRect = rect.adjusted( 0, 0, 1, 1 ); - const QRectF innerRect = outerRect.adjusted( lw, lw, -lw, -lw ); - - QPolygonF lines[2]; - - lines[0] += outerRect.bottomLeft(); - lines[0] += outerRect.topLeft(); - lines[0] += outerRect.topRight(); - lines[0] += innerRect.topRight(); - lines[0] += innerRect.topLeft(); - lines[0] += innerRect.bottomLeft(); - - lines[1] += outerRect.topRight(); - lines[1] += outerRect.bottomRight(); - lines[1] += outerRect.bottomLeft(); - lines[1] += innerRect.bottomLeft(); - lines[1] += innerRect.bottomRight(); - lines[1] += innerRect.topRight(); - - painter->setPen( Qt::NoPen ); - - painter->setBrush( pal.light() ); - painter->drawPolygon( lines[0] ); - painter->setBrush( pal.dark() ); - painter->drawPolygon( lines[1] ); - } - - painter->fillRect( rect.adjusted( lw, lw, -lw + 1, -lw + 1 ), pal.window() ); -} - -class QwtColumnSymbol::PrivateData -{ -public: - PrivateData(): - style( QwtColumnSymbol::Box ), - frameStyle( QwtColumnSymbol::Raised ), - lineWidth( 2 ) - { - palette = QPalette( Qt::gray ); - } - - QwtColumnSymbol::Style style; - QwtColumnSymbol::FrameStyle frameStyle; - - QPalette palette; - QwtText label; - - int lineWidth; -}; - -/*! - Constructor - - \param style Style of the symbol - \sa setStyle(), style(), Style -*/ -QwtColumnSymbol::QwtColumnSymbol( Style style ) -{ - d_data = new PrivateData(); - d_data->style = style; -} - -//! Destructor -QwtColumnSymbol::~QwtColumnSymbol() -{ - delete d_data; -} - -/*! - Specify the symbol style - - \param style Style - \sa style(), setPalette() -*/ -void QwtColumnSymbol::setStyle( Style style ) -{ - d_data->style = style; -} - -/*! - \return Current symbol style - \sa setStyle() -*/ -QwtColumnSymbol::Style QwtColumnSymbol::style() const -{ - return d_data->style; -} - -/*! - Assign a palette for the symbol - - \param palette Palette - \sa palette(), setStyle() -*/ -void QwtColumnSymbol::setPalette( const QPalette &palette ) -{ - d_data->palette = palette; -} - -/*! - \return Current palette - \sa setPalette() -*/ -const QPalette& QwtColumnSymbol::palette() const -{ - return d_data->palette; -} - -/*! - Set the frame, that is used for the Box style. - - \param frameStyle Frame style - \sa frameStyle(), setLineWidth(), setStyle() -*/ -void QwtColumnSymbol::setFrameStyle( FrameStyle frameStyle ) -{ - d_data->frameStyle = frameStyle; -} - -/*! - \return Current frame style, that is used for the Box style. - \sa setFrameStyle(), lineWidth(), setStyle() -*/ -QwtColumnSymbol::FrameStyle QwtColumnSymbol::frameStyle() const -{ - return d_data->frameStyle; -} - -/*! - Set the line width of the frame, that is used for the Box style. - - \param width Width - \sa lineWidth(), setFrameStyle() -*/ -void QwtColumnSymbol::setLineWidth( int width ) -{ - if ( width < 0 ) - width = 0; - - d_data->lineWidth = width; -} - -/*! - \return Line width of the frame, that is used for the Box style. - \sa setLineWidth(), frameStyle(), setStyle() -*/ -int QwtColumnSymbol::lineWidth() const -{ - return d_data->lineWidth; -} - -/*! - Draw the symbol depending on its style. - - \param painter Painter - \param rect Directed rectangle - - \sa drawBox() -*/ -void QwtColumnSymbol::draw( QPainter *painter, - const QwtColumnRect &rect ) const -{ - painter->save(); - - switch ( d_data->style ) - { - case QwtColumnSymbol::Box: - { - drawBox( painter, rect ); - break; - } - default:; - } - - painter->restore(); -} - -/*! - Draw the symbol when it is in Box style. - - \param painter Painter - \param rect Directed rectangle - - \sa draw() -*/ -void QwtColumnSymbol::drawBox( QPainter *painter, - const QwtColumnRect &rect ) const -{ - QRectF r = rect.toRect(); - if ( QwtPainter::roundingAlignment( painter ) ) - { - r.setLeft( qRound( r.left() ) ); - r.setRight( qRound( r.right() ) ); - r.setTop( qRound( r.top() ) ); - r.setBottom( qRound( r.bottom() ) ); - } - - switch ( d_data->frameStyle ) - { - case QwtColumnSymbol::Raised: - { - ::drawPanel( painter, r, d_data->palette, d_data->lineWidth ); - break; - } - case QwtColumnSymbol::Plain: - { - ::drawBox( painter, r, d_data->palette, d_data->lineWidth ); - break; - } - default: - { - painter->fillRect( r, d_data->palette.window() ); - } - } -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_column_symbol.h" +#include "qwt_math.h" +#include "qwt_text.h" +#include "qwt_painter.h" +#include +#include + +static void drawBox( QPainter *p, const QRectF &rect, + const QPalette &pal, double lw ) +{ + if ( lw > 0.0 ) + { + if ( rect.width() == 0.0 ) + { + p->setPen( pal.dark().color() ); + p->drawLine( rect.topLeft(), rect.bottomLeft() ); + return; + } + + if ( rect.height() == 0.0 ) + { + p->setPen( pal.dark().color() ); + p->drawLine( rect.topLeft(), rect.topRight() ); + return; + } + + lw = qMin( lw, rect.height() / 2.0 - 1.0 ); + lw = qMin( lw, rect.width() / 2.0 - 1.0 ); + + const QRectF outerRect = rect.adjusted( 0, 0, 1, 1 ); + QPolygonF polygon( outerRect ); + + if ( outerRect.width() > 2 * lw && + outerRect.height() > 2 * lw ) + { + const QRectF innerRect = outerRect.adjusted( lw, lw, -lw, -lw ); + polygon = polygon.subtracted( innerRect ); + } + + p->setPen( Qt::NoPen ); + + p->setBrush( pal.dark() ); + p->drawPolygon( polygon ); + } + + const QRectF windowRect = rect.adjusted( lw, lw, -lw + 1, -lw + 1 ); + if ( windowRect.isValid() ) + p->fillRect( windowRect, pal.window() ); +} + +static void drawPanel( QPainter *painter, const QRectF &rect, + const QPalette &pal, double lw ) +{ + if ( lw > 0.0 ) + { + if ( rect.width() == 0.0 ) + { + painter->setPen( pal.window().color() ); + painter->drawLine( rect.topLeft(), rect.bottomLeft() ); + return; + } + + if ( rect.height() == 0.0 ) + { + painter->setPen( pal.window().color() ); + painter->drawLine( rect.topLeft(), rect.topRight() ); + return; + } + + lw = qMin( lw, rect.height() / 2.0 - 1.0 ); + lw = qMin( lw, rect.width() / 2.0 - 1.0 ); + + const QRectF outerRect = rect.adjusted( 0, 0, 1, 1 ); + const QRectF innerRect = outerRect.adjusted( lw, lw, -lw, -lw ); + + QPolygonF lines[2]; + + lines[0] += outerRect.bottomLeft(); + lines[0] += outerRect.topLeft(); + lines[0] += outerRect.topRight(); + lines[0] += innerRect.topRight(); + lines[0] += innerRect.topLeft(); + lines[0] += innerRect.bottomLeft(); + + lines[1] += outerRect.topRight(); + lines[1] += outerRect.bottomRight(); + lines[1] += outerRect.bottomLeft(); + lines[1] += innerRect.bottomLeft(); + lines[1] += innerRect.bottomRight(); + lines[1] += innerRect.topRight(); + + painter->setPen( Qt::NoPen ); + + painter->setBrush( pal.light() ); + painter->drawPolygon( lines[0] ); + painter->setBrush( pal.dark() ); + painter->drawPolygon( lines[1] ); + } + + painter->fillRect( rect.adjusted( lw, lw, -lw + 1, -lw + 1 ), pal.window() ); +} + +class QwtColumnSymbol::PrivateData +{ +public: + PrivateData(): + style( QwtColumnSymbol::Box ), + frameStyle( QwtColumnSymbol::Raised ), + lineWidth( 2 ) + { + palette = QPalette( Qt::gray ); + } + + QwtColumnSymbol::Style style; + QwtColumnSymbol::FrameStyle frameStyle; + + QPalette palette; + QwtText label; + + int lineWidth; +}; + +/*! + Constructor + + \param style Style of the symbol + \sa setStyle(), style(), Style +*/ +QwtColumnSymbol::QwtColumnSymbol( Style style ) +{ + d_data = new PrivateData(); + d_data->style = style; +} + +//! Destructor +QwtColumnSymbol::~QwtColumnSymbol() +{ + delete d_data; +} + +/*! + Specify the symbol style + + \param style Style + \sa style(), setPalette() +*/ +void QwtColumnSymbol::setStyle( Style style ) +{ + d_data->style = style; +} + +/*! + \return Current symbol style + \sa setStyle() +*/ +QwtColumnSymbol::Style QwtColumnSymbol::style() const +{ + return d_data->style; +} + +/*! + Assign a palette for the symbol + + \param palette Palette + \sa palette(), setStyle() +*/ +void QwtColumnSymbol::setPalette( const QPalette &palette ) +{ + d_data->palette = palette; +} + +/*! + \return Current palette + \sa setPalette() +*/ +const QPalette& QwtColumnSymbol::palette() const +{ + return d_data->palette; +} + +/*! + Set the frame, that is used for the Box style. + + \param frameStyle Frame style + \sa frameStyle(), setLineWidth(), setStyle() +*/ +void QwtColumnSymbol::setFrameStyle( FrameStyle frameStyle ) +{ + d_data->frameStyle = frameStyle; +} + +/*! + \return Current frame style, that is used for the Box style. + \sa setFrameStyle(), lineWidth(), setStyle() +*/ +QwtColumnSymbol::FrameStyle QwtColumnSymbol::frameStyle() const +{ + return d_data->frameStyle; +} + +/*! + Set the line width of the frame, that is used for the Box style. + + \param width Width + \sa lineWidth(), setFrameStyle() +*/ +void QwtColumnSymbol::setLineWidth( int width ) +{ + if ( width < 0 ) + width = 0; + + d_data->lineWidth = width; +} + +/*! + \return Line width of the frame, that is used for the Box style. + \sa setLineWidth(), frameStyle(), setStyle() +*/ +int QwtColumnSymbol::lineWidth() const +{ + return d_data->lineWidth; +} + +/*! + Draw the symbol depending on its style. + + \param painter Painter + \param rect Directed rectangle + + \sa drawBox() +*/ +void QwtColumnSymbol::draw( QPainter *painter, + const QwtColumnRect &rect ) const +{ + painter->save(); + + switch ( d_data->style ) + { + case QwtColumnSymbol::Box: + { + drawBox( painter, rect ); + break; + } + default:; + } + + painter->restore(); +} + +/*! + Draw the symbol when it is in Box style. + + \param painter Painter + \param rect Directed rectangle + + \sa draw() +*/ +void QwtColumnSymbol::drawBox( QPainter *painter, + const QwtColumnRect &rect ) const +{ + QRectF r = rect.toRect(); + if ( QwtPainter::roundingAlignment( painter ) ) + { + r.setLeft( qRound( r.left() ) ); + r.setRight( qRound( r.right() ) ); + r.setTop( qRound( r.top() ) ); + r.setBottom( qRound( r.bottom() ) ); + } + + switch ( d_data->frameStyle ) + { + case QwtColumnSymbol::Raised: + { + ::drawPanel( painter, r, d_data->palette, d_data->lineWidth ); + break; + } + case QwtColumnSymbol::Plain: + { + ::drawBox( painter, r, d_data->palette, d_data->lineWidth ); + break; + } + default: + { + painter->fillRect( r, d_data->palette.window() ); + } + } +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_column_symbol.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_column_symbol.h index 5c38960a3..3c278f19a 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_column_symbol.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_column_symbol.h @@ -1,161 +1,161 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_COLUMN_SYMBOL_H -#define QWT_COLUMN_SYMBOL_H - -#include "qwt_global.h" -#include "qwt_interval.h" -#include -#include -#include - -class QPainter; -class QPalette; -class QRect; -class QwtText; - -/*! - \brief Directed rectangle representing bounding rectangle und orientation - of a column. -*/ -class QWT_EXPORT QwtColumnRect -{ -public: - //! Direction of the column - enum Direction - { - //! From left to right - LeftToRight, - - //! From right to left - RightToLeft, - - //! From bottom to top - BottomToTop, - - //! From top to bottom - TopToBottom - }; - - //! Build an rectangle with invalid intervals directed BottomToTop. - QwtColumnRect(): - direction( BottomToTop ) - { - } - - //! \return A normalized QRect built from the intervals - QRectF toRect() const - { - QRectF r( hInterval.minValue(), vInterval.minValue(), - hInterval.maxValue() - hInterval.minValue(), - vInterval.maxValue() - vInterval.minValue() ); - r = r.normalized(); - - if ( hInterval.borderFlags() & QwtInterval::ExcludeMinimum ) - r.adjust( 1, 0, 0, 0 ); - if ( hInterval.borderFlags() & QwtInterval::ExcludeMaximum ) - r.adjust( 0, 0, -1, 0 ); - if ( vInterval.borderFlags() & QwtInterval::ExcludeMinimum ) - r.adjust( 0, 1, 0, 0 ); - if ( vInterval.borderFlags() & QwtInterval::ExcludeMaximum ) - r.adjust( 0, 0, 0, -1 ); - - return r; - } - - //! \return Orientation - Qt::Orientation orientation() const - { - if ( direction == LeftToRight || direction == RightToLeft ) - return Qt::Horizontal; - - return Qt::Vertical; - } - - //! Interval for the horizontal coordinates - QwtInterval hInterval; - - //! Interval for the vertical coordinates - QwtInterval vInterval; - - //! Direction - Direction direction; -}; - -//! A drawing primitive for columns -class QWT_EXPORT QwtColumnSymbol -{ -public: - /*! - Style - \sa setStyle(), style() - */ - enum Style - { - //! No Style, the symbol draws nothing - NoStyle = -1, - - /*! - The column is painted with a frame depending on the frameStyle() - and lineWidth() using the palette(). - */ - Box, - - /*! - Styles >= QwtColumnSymbol::UserStyle are reserved for derived - classes of QwtColumnSymbol that overload draw() with - additional application specific symbol types. - */ - UserStyle = 1000 - }; - - /*! - Frame Style used in Box style(). - \sa Style, setFrameStyle(), frameStyle(), setStyle(), setPalette() - */ - enum FrameStyle - { - //! No frame - NoFrame, - - //! A plain frame style - Plain, - - //! A raised frame style - Raised - }; - -public: - QwtColumnSymbol( Style = NoStyle ); - virtual ~QwtColumnSymbol(); - - void setFrameStyle( FrameStyle style ); - FrameStyle frameStyle() const; - - void setLineWidth( int width ); - int lineWidth() const; - - void setPalette( const QPalette & ); - const QPalette &palette() const; - - void setStyle( Style ); - Style style() const; - - virtual void draw( QPainter *, const QwtColumnRect & ) const; - -protected: - void drawBox( QPainter *, const QwtColumnRect & ) const; - -private: - class PrivateData; - PrivateData* d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_COLUMN_SYMBOL_H +#define QWT_COLUMN_SYMBOL_H + +#include "qwt_global.h" +#include "qwt_interval.h" +#include +#include +#include + +class QPainter; +class QPalette; +class QRect; +class QwtText; + +/*! + \brief Directed rectangle representing bounding rectangle und orientation + of a column. +*/ +class QWT_EXPORT QwtColumnRect +{ +public: + //! Direction of the column + enum Direction + { + //! From left to right + LeftToRight, + + //! From right to left + RightToLeft, + + //! From bottom to top + BottomToTop, + + //! From top to bottom + TopToBottom + }; + + //! Build an rectangle with invalid intervals directed BottomToTop. + QwtColumnRect(): + direction( BottomToTop ) + { + } + + //! \return A normalized QRect built from the intervals + QRectF toRect() const + { + QRectF r( hInterval.minValue(), vInterval.minValue(), + hInterval.maxValue() - hInterval.minValue(), + vInterval.maxValue() - vInterval.minValue() ); + r = r.normalized(); + + if ( hInterval.borderFlags() & QwtInterval::ExcludeMinimum ) + r.adjust( 1, 0, 0, 0 ); + if ( hInterval.borderFlags() & QwtInterval::ExcludeMaximum ) + r.adjust( 0, 0, -1, 0 ); + if ( vInterval.borderFlags() & QwtInterval::ExcludeMinimum ) + r.adjust( 0, 1, 0, 0 ); + if ( vInterval.borderFlags() & QwtInterval::ExcludeMaximum ) + r.adjust( 0, 0, 0, -1 ); + + return r; + } + + //! \return Orientation + Qt::Orientation orientation() const + { + if ( direction == LeftToRight || direction == RightToLeft ) + return Qt::Horizontal; + + return Qt::Vertical; + } + + //! Interval for the horizontal coordinates + QwtInterval hInterval; + + //! Interval for the vertical coordinates + QwtInterval vInterval; + + //! Direction + Direction direction; +}; + +//! A drawing primitive for columns +class QWT_EXPORT QwtColumnSymbol +{ +public: + /*! + Style + \sa setStyle(), style() + */ + enum Style + { + //! No Style, the symbol draws nothing + NoStyle = -1, + + /*! + The column is painted with a frame depending on the frameStyle() + and lineWidth() using the palette(). + */ + Box, + + /*! + Styles >= QwtColumnSymbol::UserStyle are reserved for derived + classes of QwtColumnSymbol that overload draw() with + additional application specific symbol types. + */ + UserStyle = 1000 + }; + + /*! + Frame Style used in Box style(). + \sa Style, setFrameStyle(), frameStyle(), setStyle(), setPalette() + */ + enum FrameStyle + { + //! No frame + NoFrame, + + //! A plain frame style + Plain, + + //! A raised frame style + Raised + }; + +public: + QwtColumnSymbol( Style = NoStyle ); + virtual ~QwtColumnSymbol(); + + void setFrameStyle( FrameStyle style ); + FrameStyle frameStyle() const; + + void setLineWidth( int width ); + int lineWidth() const; + + void setPalette( const QPalette & ); + const QPalette &palette() const; + + void setStyle( Style ); + Style style() const; + + virtual void draw( QPainter *, const QwtColumnRect & ) const; + +protected: + void drawBox( QPainter *, const QwtColumnRect & ) const; + +private: + class PrivateData; + PrivateData* d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_compass.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_compass.cpp index 1aaf9f8bc..1e247dc10 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_compass.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_compass.cpp @@ -1,292 +1,292 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_compass.h" -#include "qwt_compass_rose.h" -#include "qwt_math.h" -#include "qwt_scale_draw.h" -#include "qwt_painter.h" -#include "qwt_dial_needle.h" -#include -#include -#include - -class QwtCompass::PrivateData -{ -public: - PrivateData(): - rose( NULL ) - { - } - - ~PrivateData() - { - delete rose; - } - - QwtCompassRose *rose; - QMap labelMap; -}; - -/*! - \brief Constructor - \param parent Parent widget - - Create a compass widget with a scale, no needle and no rose. - The default origin is 270.0 with no valid value. It accepts - mouse and keyboard inputs and has no step size. The default mode - is QwtDial::RotateNeedle. -*/ -QwtCompass::QwtCompass( QWidget* parent ): - QwtDial( parent ) -{ - initCompass(); -} - -//! Destructor -QwtCompass::~QwtCompass() -{ - delete d_data; -} - -void QwtCompass::initCompass() -{ - d_data = new PrivateData; - - // Only labels, no backbone, no ticks - setScaleComponents( QwtAbstractScaleDraw::Labels ); - - setOrigin( 270.0 ); - setWrapping( true ); - - - d_data->labelMap.insert( 0.0, QString::fromLatin1( "N" ) ); - d_data->labelMap.insert( 45.0, QString::fromLatin1( "NE" ) ); - d_data->labelMap.insert( 90.0, QString::fromLatin1( "E" ) ); - d_data->labelMap.insert( 135.0, QString::fromLatin1( "SE" ) ); - d_data->labelMap.insert( 180.0, QString::fromLatin1( "S" ) ); - d_data->labelMap.insert( 225.0, QString::fromLatin1( "SW" ) ); - d_data->labelMap.insert( 270.0, QString::fromLatin1( "W" ) ); - d_data->labelMap.insert( 315.0, QString::fromLatin1( "NW" ) ); - -#if 0 - d_data->labelMap.insert( 22.5, QString::fromLatin1( "NNE" ) ); - d_data->labelMap.insert( 67.5, QString::fromLatin1( "NEE" ) ); - d_data->labelMap.insert( 112.5, QString::fromLatin1( "SEE" ) ); - d_data->labelMap.insert( 157.5, QString::fromLatin1( "SSE" ) ); - d_data->labelMap.insert( 202.5, QString::fromLatin1( "SSW" ) ); - d_data->labelMap.insert( 247.5, QString::fromLatin1( "SWW" ) ); - d_data->labelMap.insert( 292.5, QString::fromLatin1( "NWW" ) ); - d_data->labelMap.insert( 337.5, QString::fromLatin1( "NNW" ) ); -#endif -} - -/*! - Draw the contents of the scale - - \param painter Painter - \param center Center of the content circle - \param radius Radius of the content circle -*/ -void QwtCompass::drawScaleContents( QPainter *painter, - const QPointF ¢er, double radius ) const -{ - QPalette::ColorGroup cg; - if ( isEnabled() ) - cg = hasFocus() ? QPalette::Active : QPalette::Inactive; - else - cg = QPalette::Disabled; - - double north = origin(); - if ( isValid() ) - { - if ( mode() == RotateScale ) - north -= value(); - } - - const int margin = 4; - drawRose( painter, center, radius - margin, 360.0 - north, cg ); -} - -/*! - Draw the compass rose - - \param painter Painter - \param center Center of the compass - \param radius of the circle, where to paint the rose - \param north Direction pointing north, in degrees counter clockwise - \param cg Color group -*/ -void QwtCompass::drawRose( QPainter *painter, const QPointF ¢er, - double radius, double north, QPalette::ColorGroup cg ) const -{ - if ( d_data->rose ) - d_data->rose->draw( painter, center, radius, north, cg ); -} - -/*! - Set a rose for the compass - \param rose Compass rose - \warning The rose will be deleted, when a different rose is - set or in ~QwtCompass - \sa rose() -*/ -void QwtCompass::setRose( QwtCompassRose *rose ) -{ - if ( rose != d_data->rose ) - { - if ( d_data->rose ) - delete d_data->rose; - - d_data->rose = rose; - update(); - } -} - -/*! - \return rose - \sa setRose() -*/ -const QwtCompassRose *QwtCompass::rose() const -{ - return d_data->rose; -} - -/*! - \return rose - \sa setRose() -*/ -QwtCompassRose *QwtCompass::rose() -{ - return d_data->rose; -} - -/*! - Handles key events - - Beside the keys described in QwtDial::keyPressEvent numbers - from 1-9 (without 5) set the direction according to their - position on the num pad. - - \sa isReadOnly() -*/ -void QwtCompass::keyPressEvent( QKeyEvent *kev ) -{ - if ( isReadOnly() ) - return; - -#if 0 - if ( kev->key() == Key_5 ) - { - invalidate(); // signal ??? - return; - } -#endif - - double newValue = value(); - - if ( kev->key() >= Qt::Key_1 && kev->key() <= Qt::Key_9 ) - { - if ( mode() != RotateNeedle || kev->key() == Qt::Key_5 ) - return; - - switch ( kev->key() ) - { - case Qt::Key_6: - newValue = 180.0 * 0.0; - break; - case Qt::Key_3: - newValue = 180.0 * 0.25; - break; - case Qt::Key_2: - newValue = 180.0 * 0.5; - break; - case Qt::Key_1: - newValue = 180.0 * 0.75; - break; - case Qt::Key_4: - newValue = 180.0 * 1.0; - break; - case Qt::Key_7: - newValue = 180.0 * 1.25; - break; - case Qt::Key_8: - newValue = 180.0 * 1.5; - break; - case Qt::Key_9: - newValue = 180.0 * 1.75; - break; - } - newValue -= origin(); - setValue( newValue ); - } - else - { - QwtDial::keyPressEvent( kev ); - } -} - -/*! - \return map, mapping values to labels - \sa setLabelMap() -*/ -const QMap &QwtCompass::labelMap() const -{ - return d_data->labelMap; -} - -/*! - \return map, mapping values to labels - \sa setLabelMap() -*/ -QMap &QwtCompass::labelMap() -{ - return d_data->labelMap; -} - -/*! - \brief Set a map, mapping values to labels - \param map value to label map - - The values of the major ticks are found by looking into this - map. The default map consists of the labels N, NE, E, SE, S, SW, W, NW. - - \warning The map will have no effect for values that are no major - tick values. Major ticks can be changed by QwtScaleDraw::setScale - - \sa labelMap(), scaleDraw(), setScale() -*/ -void QwtCompass::setLabelMap( const QMap &map ) -{ - d_data->labelMap = map; -} - -/*! - Map a value to a corresponding label - \param value Value that will be mapped - \return Label, or QString::null - - label() looks in a map for a corresponding label for value - or return an null text. - \sa labelMap(), setLabelMap() -*/ - -QwtText QwtCompass::scaleLabel( double value ) const -{ - if ( qFuzzyCompare( value, 0.0 ) ) - value = 0.0; - - if ( value < 0.0 ) - value += 360.0; - - if ( d_data->labelMap.contains( value ) ) - return d_data->labelMap[value]; - - return QwtText(); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_compass.h" +#include "qwt_compass_rose.h" +#include "qwt_math.h" +#include "qwt_scale_draw.h" +#include "qwt_painter.h" +#include "qwt_dial_needle.h" +#include +#include +#include + +class QwtCompass::PrivateData +{ +public: + PrivateData(): + rose( NULL ) + { + } + + ~PrivateData() + { + delete rose; + } + + QwtCompassRose *rose; + QMap labelMap; +}; + +/*! + \brief Constructor + \param parent Parent widget + + Create a compass widget with a scale, no needle and no rose. + The default origin is 270.0 with no valid value. It accepts + mouse and keyboard inputs and has no step size. The default mode + is QwtDial::RotateNeedle. +*/ +QwtCompass::QwtCompass( QWidget* parent ): + QwtDial( parent ) +{ + initCompass(); +} + +//! Destructor +QwtCompass::~QwtCompass() +{ + delete d_data; +} + +void QwtCompass::initCompass() +{ + d_data = new PrivateData; + + // Only labels, no backbone, no ticks + setScaleComponents( QwtAbstractScaleDraw::Labels ); + + setOrigin( 270.0 ); + setWrapping( true ); + + + d_data->labelMap.insert( 0.0, QString::fromLatin1( "N" ) ); + d_data->labelMap.insert( 45.0, QString::fromLatin1( "NE" ) ); + d_data->labelMap.insert( 90.0, QString::fromLatin1( "E" ) ); + d_data->labelMap.insert( 135.0, QString::fromLatin1( "SE" ) ); + d_data->labelMap.insert( 180.0, QString::fromLatin1( "S" ) ); + d_data->labelMap.insert( 225.0, QString::fromLatin1( "SW" ) ); + d_data->labelMap.insert( 270.0, QString::fromLatin1( "W" ) ); + d_data->labelMap.insert( 315.0, QString::fromLatin1( "NW" ) ); + +#if 0 + d_data->labelMap.insert( 22.5, QString::fromLatin1( "NNE" ) ); + d_data->labelMap.insert( 67.5, QString::fromLatin1( "NEE" ) ); + d_data->labelMap.insert( 112.5, QString::fromLatin1( "SEE" ) ); + d_data->labelMap.insert( 157.5, QString::fromLatin1( "SSE" ) ); + d_data->labelMap.insert( 202.5, QString::fromLatin1( "SSW" ) ); + d_data->labelMap.insert( 247.5, QString::fromLatin1( "SWW" ) ); + d_data->labelMap.insert( 292.5, QString::fromLatin1( "NWW" ) ); + d_data->labelMap.insert( 337.5, QString::fromLatin1( "NNW" ) ); +#endif +} + +/*! + Draw the contents of the scale + + \param painter Painter + \param center Center of the content circle + \param radius Radius of the content circle +*/ +void QwtCompass::drawScaleContents( QPainter *painter, + const QPointF ¢er, double radius ) const +{ + QPalette::ColorGroup cg; + if ( isEnabled() ) + cg = hasFocus() ? QPalette::Active : QPalette::Inactive; + else + cg = QPalette::Disabled; + + double north = origin(); + if ( isValid() ) + { + if ( mode() == RotateScale ) + north -= value(); + } + + const int margin = 4; + drawRose( painter, center, radius - margin, 360.0 - north, cg ); +} + +/*! + Draw the compass rose + + \param painter Painter + \param center Center of the compass + \param radius of the circle, where to paint the rose + \param north Direction pointing north, in degrees counter clockwise + \param cg Color group +*/ +void QwtCompass::drawRose( QPainter *painter, const QPointF ¢er, + double radius, double north, QPalette::ColorGroup cg ) const +{ + if ( d_data->rose ) + d_data->rose->draw( painter, center, radius, north, cg ); +} + +/*! + Set a rose for the compass + \param rose Compass rose + \warning The rose will be deleted, when a different rose is + set or in ~QwtCompass + \sa rose() +*/ +void QwtCompass::setRose( QwtCompassRose *rose ) +{ + if ( rose != d_data->rose ) + { + if ( d_data->rose ) + delete d_data->rose; + + d_data->rose = rose; + update(); + } +} + +/*! + \return rose + \sa setRose() +*/ +const QwtCompassRose *QwtCompass::rose() const +{ + return d_data->rose; +} + +/*! + \return rose + \sa setRose() +*/ +QwtCompassRose *QwtCompass::rose() +{ + return d_data->rose; +} + +/*! + Handles key events + + Beside the keys described in QwtDial::keyPressEvent numbers + from 1-9 (without 5) set the direction according to their + position on the num pad. + + \sa isReadOnly() +*/ +void QwtCompass::keyPressEvent( QKeyEvent *kev ) +{ + if ( isReadOnly() ) + return; + +#if 0 + if ( kev->key() == Key_5 ) + { + invalidate(); // signal ??? + return; + } +#endif + + double newValue = value(); + + if ( kev->key() >= Qt::Key_1 && kev->key() <= Qt::Key_9 ) + { + if ( mode() != RotateNeedle || kev->key() == Qt::Key_5 ) + return; + + switch ( kev->key() ) + { + case Qt::Key_6: + newValue = 180.0 * 0.0; + break; + case Qt::Key_3: + newValue = 180.0 * 0.25; + break; + case Qt::Key_2: + newValue = 180.0 * 0.5; + break; + case Qt::Key_1: + newValue = 180.0 * 0.75; + break; + case Qt::Key_4: + newValue = 180.0 * 1.0; + break; + case Qt::Key_7: + newValue = 180.0 * 1.25; + break; + case Qt::Key_8: + newValue = 180.0 * 1.5; + break; + case Qt::Key_9: + newValue = 180.0 * 1.75; + break; + } + newValue -= origin(); + setValue( newValue ); + } + else + { + QwtDial::keyPressEvent( kev ); + } +} + +/*! + \return map, mapping values to labels + \sa setLabelMap() +*/ +const QMap &QwtCompass::labelMap() const +{ + return d_data->labelMap; +} + +/*! + \return map, mapping values to labels + \sa setLabelMap() +*/ +QMap &QwtCompass::labelMap() +{ + return d_data->labelMap; +} + +/*! + \brief Set a map, mapping values to labels + \param map value to label map + + The values of the major ticks are found by looking into this + map. The default map consists of the labels N, NE, E, SE, S, SW, W, NW. + + \warning The map will have no effect for values that are no major + tick values. Major ticks can be changed by QwtScaleDraw::setScale + + \sa labelMap(), scaleDraw(), setScale() +*/ +void QwtCompass::setLabelMap( const QMap &map ) +{ + d_data->labelMap = map; +} + +/*! + Map a value to a corresponding label + \param value Value that will be mapped + \return Label, or QString::null + + label() looks in a map for a corresponding label for value + or return an null text. + \sa labelMap(), setLabelMap() +*/ + +QwtText QwtCompass::scaleLabel( double value ) const +{ + if ( qFuzzyCompare( value, 0.0 ) ) + value = 0.0; + + if ( value < 0.0 ) + value += 360.0; + + if ( d_data->labelMap.contains( value ) ) + return d_data->labelMap[value]; + + return QwtText(); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_compass.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_compass.h index 294cb3b81..a1044b7f5 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_compass.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_compass.h @@ -1,65 +1,65 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_COMPASS_H -#define QWT_COMPASS_H 1 - -#include "qwt_global.h" -#include "qwt_dial.h" -#include -#include - -class QwtCompassRose; - -/*! - \brief A Compass Widget - - QwtCompass is a widget to display and enter directions. It consists - of a scale, an optional needle and rose. - - \image html dials1.png - - \note The examples/dials example shows how to use QwtCompass. -*/ - -class QWT_EXPORT QwtCompass: public QwtDial -{ - Q_OBJECT - -public: - explicit QwtCompass( QWidget* parent = NULL ); - virtual ~QwtCompass(); - - void setRose( QwtCompassRose *rose ); - const QwtCompassRose *rose() const; - QwtCompassRose *rose(); - - const QMap &labelMap() const; - QMap &labelMap(); - void setLabelMap( const QMap &map ); - -protected: - virtual QwtText scaleLabel( double value ) const; - - virtual void drawRose( QPainter *, const QPointF ¢er, - double radius, double north, QPalette::ColorGroup ) const; - - virtual void drawScaleContents( QPainter *, - const QPointF ¢er, double radius ) const; - - virtual void keyPressEvent( QKeyEvent * ); - -private: - void initCompass(); - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_COMPASS_H +#define QWT_COMPASS_H 1 + +#include "qwt_global.h" +#include "qwt_dial.h" +#include +#include + +class QwtCompassRose; + +/*! + \brief A Compass Widget + + QwtCompass is a widget to display and enter directions. It consists + of a scale, an optional needle and rose. + + \image html dials1.png + + \note The examples/dials example shows how to use QwtCompass. +*/ + +class QWT_EXPORT QwtCompass: public QwtDial +{ + Q_OBJECT + +public: + explicit QwtCompass( QWidget* parent = NULL ); + virtual ~QwtCompass(); + + void setRose( QwtCompassRose *rose ); + const QwtCompassRose *rose() const; + QwtCompassRose *rose(); + + const QMap &labelMap() const; + QMap &labelMap(); + void setLabelMap( const QMap &map ); + +protected: + virtual QwtText scaleLabel( double value ) const; + + virtual void drawRose( QPainter *, const QPointF ¢er, + double radius, double north, QPalette::ColorGroup ) const; + + virtual void drawScaleContents( QPainter *, + const QPointF ¢er, double radius ) const; + + virtual void keyPressEvent( QKeyEvent * ); + +private: + void initCompass(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_compass_rose.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_compass_rose.cpp index bc83c5663..357afa028 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_compass_rose.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_compass_rose.cpp @@ -1,270 +1,270 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_compass_rose.h" -#include "qwt_point_polar.h" -#include "qwt_painter.h" -#include - -static QPointF qwtIntersection( - QPointF p11, QPointF p12, QPointF p21, QPointF p22 ) -{ - const QLineF line1( p11, p12 ); - const QLineF line2( p21, p22 ); - - QPointF pos; - if ( line1.intersect( line2, &pos ) == QLineF::NoIntersection ) - return QPointF(); - - return pos; -} - -class QwtSimpleCompassRose::PrivateData -{ -public: - PrivateData(): - width( 0.2 ), - numThorns( 8 ), - numThornLevels( -1 ), - shrinkFactor( 0.9 ) - { - } - - double width; - int numThorns; - int numThornLevels; - double shrinkFactor; -}; - -/*! - Constructor - - \param numThorns Number of thorns - \param numThornLevels Number of thorn levels -*/ -QwtSimpleCompassRose::QwtSimpleCompassRose( - int numThorns, int numThornLevels ) -{ - d_data = new PrivateData(); - d_data->numThorns = numThorns; - d_data->numThornLevels = numThornLevels; - - const QColor dark( 128, 128, 255 ); - const QColor light( 192, 255, 255 ); - - QPalette palette; - for ( int i = 0; i < QPalette::NColorGroups; i++ ) - { - palette.setColor( ( QPalette::ColorGroup )i, - QPalette::Dark, dark ); - palette.setColor( ( QPalette::ColorGroup )i, - QPalette::Light, light ); - } - - setPalette( palette ); -} - -//! Destructor -QwtSimpleCompassRose::~QwtSimpleCompassRose() -{ - delete d_data; -} - -/*! - Set the Factor how to shrink the thorns with each level - The default value is 0.9. - - \sa shrinkFactor() -*/ -void QwtSimpleCompassRose::setShrinkFactor( double factor ) -{ - d_data->shrinkFactor = factor; -} - -/*! - \return Factor how to shrink the thorns with each level - \sa setShrinkFactor() -*/ -double QwtSimpleCompassRose::shrinkFactor() const -{ - return d_data->shrinkFactor; -} - -/*! - Draw the rose - - \param painter Painter - \param center Center point - \param radius Radius of the rose - \param north Position - \param cg Color group -*/ -void QwtSimpleCompassRose::draw( QPainter *painter, const QPointF ¢er, - double radius, double north, QPalette::ColorGroup cg ) const -{ - QPalette pal = palette(); - pal.setCurrentColorGroup( cg ); - - drawRose( painter, pal, center, radius, north, d_data->width, - d_data->numThorns, d_data->numThornLevels, d_data->shrinkFactor ); -} - -/*! - Draw the rose - - \param painter Painter - \param palette Palette - \param center Center of the rose - \param radius Radius of the rose - \param north Position pointing to north - \param width Width of the rose - \param numThorns Number of thorns - \param numThornLevels Number of thorn levels - \param shrinkFactor Factor to shrink the thorns with each level -*/ -void QwtSimpleCompassRose::drawRose( - QPainter *painter, - const QPalette &palette, - const QPointF ¢er, double radius, double north, double width, - int numThorns, int numThornLevels, double shrinkFactor ) -{ - if ( numThorns < 4 ) - numThorns = 4; - - if ( numThorns % 4 ) - numThorns += 4 - numThorns % 4; - - if ( numThornLevels <= 0 ) - numThornLevels = numThorns / 4; - - if ( shrinkFactor >= 1.0 ) - shrinkFactor = 1.0; - - if ( shrinkFactor <= 0.5 ) - shrinkFactor = 0.5; - - painter->save(); - - painter->setPen( Qt::NoPen ); - - for ( int j = 1; j <= numThornLevels; j++ ) - { - double step = qPow( 2.0, j ) * M_PI / numThorns; - if ( step > M_PI_2 ) - break; - - double r = radius; - for ( int k = 0; k < 3; k++ ) - { - if ( j + k < numThornLevels ) - r *= shrinkFactor; - } - - double leafWidth = r * width; - if ( 2.0 * M_PI / step > 32 ) - leafWidth = 16; - - const double origin = north / 180.0 * M_PI; - for ( double angle = origin; - angle < 2.0 * M_PI + origin; angle += step ) - { - const QPointF p = qwtPolar2Pos( center, r, angle ); - const QPointF p1 = qwtPolar2Pos( center, leafWidth, angle + M_PI_2 ); - const QPointF p2 = qwtPolar2Pos( center, leafWidth, angle - M_PI_2 ); - const QPointF p3 = qwtPolar2Pos( center, r, angle + step / 2.0 ); - const QPointF p4 = qwtPolar2Pos( center, r, angle - step / 2.0 ); - - QPainterPath darkPath; - darkPath.moveTo( center ); - darkPath.lineTo( p ); - darkPath.lineTo( qwtIntersection( center, p3, p1, p ) ); - - painter->setBrush( palette.brush( QPalette::Dark ) ); - painter->drawPath( darkPath ); - - QPainterPath lightPath; - lightPath.moveTo( center ); - lightPath.lineTo( p ); - lightPath.lineTo( qwtIntersection( center, p4, p2, p ) ); - - painter->setBrush( palette.brush( QPalette::Light ) ); - painter->drawPath( lightPath ); - } - } - painter->restore(); -} - -/*! - Set the width of the rose heads. Lower value make thinner heads. - The range is limited from 0.03 to 0.4. - - \param width Width -*/ -void QwtSimpleCompassRose::setWidth( double width ) -{ - d_data->width = width; - if ( d_data->width < 0.03 ) - d_data->width = 0.03; - - if ( d_data->width > 0.4 ) - d_data->width = 0.4; -} - -//! \sa setWidth() -double QwtSimpleCompassRose::width() const -{ - return d_data->width; -} - -/*! - Set the number of thorns on one level - The number is aligned to a multiple of 4, with a minimum of 4 - - \param numThorns Number of thorns - \sa numThorns(), setNumThornLevels() -*/ -void QwtSimpleCompassRose::setNumThorns( int numThorns ) -{ - if ( numThorns < 4 ) - numThorns = 4; - - if ( numThorns % 4 ) - numThorns += 4 - numThorns % 4; - - d_data->numThorns = numThorns; -} - -/*! - \return Number of thorns - \sa setNumThorns(), setNumThornLevels() -*/ -int QwtSimpleCompassRose::numThorns() const -{ - return d_data->numThorns; -} - -/*! - Set the of thorns levels - - \param numThornLevels Number of thorns levels - \sa setNumThorns(), numThornLevels() -*/ -void QwtSimpleCompassRose::setNumThornLevels( int numThornLevels ) -{ - d_data->numThornLevels = numThornLevels; -} - -/*! - \return Number of thorn levels - \sa setNumThorns(), setNumThornLevels() -*/ -int QwtSimpleCompassRose::numThornLevels() const -{ - return d_data->numThornLevels; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_compass_rose.h" +#include "qwt_point_polar.h" +#include "qwt_painter.h" +#include + +static QPointF qwtIntersection( + QPointF p11, QPointF p12, QPointF p21, QPointF p22 ) +{ + const QLineF line1( p11, p12 ); + const QLineF line2( p21, p22 ); + + QPointF pos; + if ( line1.intersect( line2, &pos ) == QLineF::NoIntersection ) + return QPointF(); + + return pos; +} + +class QwtSimpleCompassRose::PrivateData +{ +public: + PrivateData(): + width( 0.2 ), + numThorns( 8 ), + numThornLevels( -1 ), + shrinkFactor( 0.9 ) + { + } + + double width; + int numThorns; + int numThornLevels; + double shrinkFactor; +}; + +/*! + Constructor + + \param numThorns Number of thorns + \param numThornLevels Number of thorn levels +*/ +QwtSimpleCompassRose::QwtSimpleCompassRose( + int numThorns, int numThornLevels ) +{ + d_data = new PrivateData(); + d_data->numThorns = numThorns; + d_data->numThornLevels = numThornLevels; + + const QColor dark( 128, 128, 255 ); + const QColor light( 192, 255, 255 ); + + QPalette palette; + for ( int i = 0; i < QPalette::NColorGroups; i++ ) + { + palette.setColor( ( QPalette::ColorGroup )i, + QPalette::Dark, dark ); + palette.setColor( ( QPalette::ColorGroup )i, + QPalette::Light, light ); + } + + setPalette( palette ); +} + +//! Destructor +QwtSimpleCompassRose::~QwtSimpleCompassRose() +{ + delete d_data; +} + +/*! + Set the Factor how to shrink the thorns with each level + The default value is 0.9. + + \sa shrinkFactor() +*/ +void QwtSimpleCompassRose::setShrinkFactor( double factor ) +{ + d_data->shrinkFactor = factor; +} + +/*! + \return Factor how to shrink the thorns with each level + \sa setShrinkFactor() +*/ +double QwtSimpleCompassRose::shrinkFactor() const +{ + return d_data->shrinkFactor; +} + +/*! + Draw the rose + + \param painter Painter + \param center Center point + \param radius Radius of the rose + \param north Position + \param cg Color group +*/ +void QwtSimpleCompassRose::draw( QPainter *painter, const QPointF ¢er, + double radius, double north, QPalette::ColorGroup cg ) const +{ + QPalette pal = palette(); + pal.setCurrentColorGroup( cg ); + + drawRose( painter, pal, center, radius, north, d_data->width, + d_data->numThorns, d_data->numThornLevels, d_data->shrinkFactor ); +} + +/*! + Draw the rose + + \param painter Painter + \param palette Palette + \param center Center of the rose + \param radius Radius of the rose + \param north Position pointing to north + \param width Width of the rose + \param numThorns Number of thorns + \param numThornLevels Number of thorn levels + \param shrinkFactor Factor to shrink the thorns with each level +*/ +void QwtSimpleCompassRose::drawRose( + QPainter *painter, + const QPalette &palette, + const QPointF ¢er, double radius, double north, double width, + int numThorns, int numThornLevels, double shrinkFactor ) +{ + if ( numThorns < 4 ) + numThorns = 4; + + if ( numThorns % 4 ) + numThorns += 4 - numThorns % 4; + + if ( numThornLevels <= 0 ) + numThornLevels = numThorns / 4; + + if ( shrinkFactor >= 1.0 ) + shrinkFactor = 1.0; + + if ( shrinkFactor <= 0.5 ) + shrinkFactor = 0.5; + + painter->save(); + + painter->setPen( Qt::NoPen ); + + for ( int j = 1; j <= numThornLevels; j++ ) + { + double step = qPow( 2.0, j ) * M_PI / numThorns; + if ( step > M_PI_2 ) + break; + + double r = radius; + for ( int k = 0; k < 3; k++ ) + { + if ( j + k < numThornLevels ) + r *= shrinkFactor; + } + + double leafWidth = r * width; + if ( 2.0 * M_PI / step > 32 ) + leafWidth = 16; + + const double origin = north / 180.0 * M_PI; + for ( double angle = origin; + angle < 2.0 * M_PI + origin; angle += step ) + { + const QPointF p = qwtPolar2Pos( center, r, angle ); + const QPointF p1 = qwtPolar2Pos( center, leafWidth, angle + M_PI_2 ); + const QPointF p2 = qwtPolar2Pos( center, leafWidth, angle - M_PI_2 ); + const QPointF p3 = qwtPolar2Pos( center, r, angle + step / 2.0 ); + const QPointF p4 = qwtPolar2Pos( center, r, angle - step / 2.0 ); + + QPainterPath darkPath; + darkPath.moveTo( center ); + darkPath.lineTo( p ); + darkPath.lineTo( qwtIntersection( center, p3, p1, p ) ); + + painter->setBrush( palette.brush( QPalette::Dark ) ); + painter->drawPath( darkPath ); + + QPainterPath lightPath; + lightPath.moveTo( center ); + lightPath.lineTo( p ); + lightPath.lineTo( qwtIntersection( center, p4, p2, p ) ); + + painter->setBrush( palette.brush( QPalette::Light ) ); + painter->drawPath( lightPath ); + } + } + painter->restore(); +} + +/*! + Set the width of the rose heads. Lower value make thinner heads. + The range is limited from 0.03 to 0.4. + + \param width Width +*/ +void QwtSimpleCompassRose::setWidth( double width ) +{ + d_data->width = width; + if ( d_data->width < 0.03 ) + d_data->width = 0.03; + + if ( d_data->width > 0.4 ) + d_data->width = 0.4; +} + +//! \sa setWidth() +double QwtSimpleCompassRose::width() const +{ + return d_data->width; +} + +/*! + Set the number of thorns on one level + The number is aligned to a multiple of 4, with a minimum of 4 + + \param numThorns Number of thorns + \sa numThorns(), setNumThornLevels() +*/ +void QwtSimpleCompassRose::setNumThorns( int numThorns ) +{ + if ( numThorns < 4 ) + numThorns = 4; + + if ( numThorns % 4 ) + numThorns += 4 - numThorns % 4; + + d_data->numThorns = numThorns; +} + +/*! + \return Number of thorns + \sa setNumThorns(), setNumThornLevels() +*/ +int QwtSimpleCompassRose::numThorns() const +{ + return d_data->numThorns; +} + +/*! + Set the of thorns levels + + \param numThornLevels Number of thorns levels + \sa setNumThorns(), numThornLevels() +*/ +void QwtSimpleCompassRose::setNumThornLevels( int numThornLevels ) +{ + d_data->numThornLevels = numThornLevels; +} + +/*! + \return Number of thorn levels + \sa setNumThorns(), setNumThornLevels() +*/ +int QwtSimpleCompassRose::numThornLevels() const +{ + return d_data->numThornLevels; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_compass_rose.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_compass_rose.h index 8a8f1ce17..9b715dfe0 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_compass_rose.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_compass_rose.h @@ -1,89 +1,89 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_COMPASS_ROSE_H -#define QWT_COMPASS_ROSE_H 1 - -#include "qwt_global.h" -#include - -class QPainter; - -/*! - \brief Abstract base class for a compass rose -*/ -class QWT_EXPORT QwtCompassRose -{ -public: - //! Destructor - virtual ~QwtCompassRose() {}; - - //! Assign a palette - virtual void setPalette( const QPalette &p ) - { - d_palette = p; - } - - //! \return Current palette - const QPalette &palette() const - { - return d_palette; - } - - /*! - Draw the rose - - \param painter Painter - \param center Center point - \param radius Radius of the rose - \param north Position - \param colorGroup Color group - */ - virtual void draw( QPainter *painter, - const QPointF ¢er, double radius, double north, - QPalette::ColorGroup colorGroup = QPalette::Active ) const = 0; - -private: - QPalette d_palette; -}; - -/*! - \brief A simple rose for QwtCompass -*/ -class QWT_EXPORT QwtSimpleCompassRose: public QwtCompassRose -{ -public: - QwtSimpleCompassRose( int numThorns = 8, int numThornLevels = -1 ); - virtual ~QwtSimpleCompassRose(); - - void setWidth( double w ); - double width() const; - - void setNumThorns( int count ); - int numThorns() const; - - void setNumThornLevels( int count ); - int numThornLevels() const; - - void setShrinkFactor( double factor ); - double shrinkFactor() const; - - virtual void draw( QPainter *, const QPointF ¢er, double radius, - double north, QPalette::ColorGroup = QPalette::Active ) const; - - static void drawRose( QPainter *, const QPalette &, - const QPointF ¢er, double radius, double origin, double width, - int numThorns, int numThornLevels, double shrinkFactor ); - -private: - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_COMPASS_ROSE_H +#define QWT_COMPASS_ROSE_H 1 + +#include "qwt_global.h" +#include + +class QPainter; + +/*! + \brief Abstract base class for a compass rose +*/ +class QWT_EXPORT QwtCompassRose +{ +public: + //! Destructor + virtual ~QwtCompassRose() {}; + + //! Assign a palette + virtual void setPalette( const QPalette &p ) + { + d_palette = p; + } + + //! \return Current palette + const QPalette &palette() const + { + return d_palette; + } + + /*! + Draw the rose + + \param painter Painter + \param center Center point + \param radius Radius of the rose + \param north Position + \param colorGroup Color group + */ + virtual void draw( QPainter *painter, + const QPointF ¢er, double radius, double north, + QPalette::ColorGroup colorGroup = QPalette::Active ) const = 0; + +private: + QPalette d_palette; +}; + +/*! + \brief A simple rose for QwtCompass +*/ +class QWT_EXPORT QwtSimpleCompassRose: public QwtCompassRose +{ +public: + QwtSimpleCompassRose( int numThorns = 8, int numThornLevels = -1 ); + virtual ~QwtSimpleCompassRose(); + + void setWidth( double w ); + double width() const; + + void setNumThorns( int count ); + int numThorns() const; + + void setNumThornLevels( int count ); + int numThornLevels() const; + + void setShrinkFactor( double factor ); + double shrinkFactor() const; + + virtual void draw( QPainter *, const QPointF ¢er, double radius, + double north, QPalette::ColorGroup = QPalette::Active ) const; + + static void drawRose( QPainter *, const QPalette &, + const QPointF ¢er, double radius, double origin, double width, + int numThorns, int numThornLevels, double shrinkFactor ); + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_compat.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_compat.h index 81b45ca22..dc74a5d28 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_compat.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_compat.h @@ -1,40 +1,40 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef _QWT_COMPAT_H_ -#define _QWT_COMPAT_H_ - -#include "qwt_global.h" -#include -#include -#include -#include -#include -#include - -// A couple of definition for Qwt5 compatibility - -#define qwtMax qMax -#define qwtMin qMin -#define qwtAbs qAbs -#define qwtRound qRound - -#define QwtArray QVector - -typedef QList QwtValueList; -typedef QPointF QwtDoublePoint; -typedef QSizeF QwtDoubleSize; -typedef QRectF QwtDoubleRect; - -typedef QPolygon QwtPolygon; -typedef QPolygonF QwtPolygonF; -typedef QwtInterval QwtDoubleInterval; -typedef QwtPoint3D QwtDoublePoint3D; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef _QWT_COMPAT_H_ +#define _QWT_COMPAT_H_ + +#include "qwt_global.h" +#include +#include +#include +#include +#include +#include + +// A couple of definition for Qwt5 compatibility + +#define qwtMax qMax +#define qwtMin qMin +#define qwtAbs qAbs +#define qwtRound qRound + +#define QwtArray QVector + +typedef QList QwtValueList; +typedef QPointF QwtDoublePoint; +typedef QSizeF QwtDoubleSize; +typedef QRectF QwtDoubleRect; + +typedef QPolygon QwtPolygon; +typedef QPolygonF QwtPolygonF; +typedef QwtInterval QwtDoubleInterval; +typedef QwtPoint3D QwtDoublePoint3D; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_counter.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_counter.cpp index bb7f201dd..2c7a8958c 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_counter.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_counter.cpp @@ -1,603 +1,603 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_arrow_button.h" -#include "qwt_math.h" -#include "qwt_counter.h" -#include -#include -#include -#include -#include - -class QwtCounter::PrivateData -{ -public: - PrivateData(): - editable( true ) - { - increment[Button1] = 1; - increment[Button2] = 10; - increment[Button3] = 100; - } - - QwtArrowButton *buttonDown[ButtonCnt]; - QwtArrowButton *buttonUp[ButtonCnt]; - QLineEdit *valueEdit; - - int increment[ButtonCnt]; - int numButtons; - - bool editable; -}; - -/*! - The default number of buttons is set to 2. The default increments are: - \li Button 1: 1 step - \li Button 2: 10 steps - \li Button 3: 100 steps - - \param parent - */ -QwtCounter::QwtCounter( QWidget *parent ): - QWidget( parent ) -{ - initCounter(); -} - -void QwtCounter::initCounter() -{ - d_data = new PrivateData; - - QHBoxLayout *layout = new QHBoxLayout( this ); - layout->setSpacing( 0 ); - layout->setMargin( 0 ); - - for ( int i = ButtonCnt - 1; i >= 0; i-- ) - { - QwtArrowButton *btn = - new QwtArrowButton( i + 1, Qt::DownArrow, this ); - btn->setFocusPolicy( Qt::NoFocus ); - btn->installEventFilter( this ); - layout->addWidget( btn ); - - connect( btn, SIGNAL( released() ), SLOT( btnReleased() ) ); - connect( btn, SIGNAL( clicked() ), SLOT( btnClicked() ) ); - - d_data->buttonDown[i] = btn; - } - - d_data->valueEdit = new QLineEdit( this ); - d_data->valueEdit->setReadOnly( false ); - d_data->valueEdit->setValidator( new QDoubleValidator( d_data->valueEdit ) ); - layout->addWidget( d_data->valueEdit ); - - connect( d_data->valueEdit, SIGNAL( editingFinished() ), - SLOT( textChanged() ) ); - - layout->setStretchFactor( d_data->valueEdit, 10 ); - - for ( int i = 0; i < ButtonCnt; i++ ) - { - QwtArrowButton *btn = - new QwtArrowButton( i + 1, Qt::UpArrow, this ); - btn->setFocusPolicy( Qt::NoFocus ); - btn->installEventFilter( this ); - layout->addWidget( btn ); - - connect( btn, SIGNAL( released() ), SLOT( btnReleased() ) ); - connect( btn, SIGNAL( clicked() ), SLOT( btnClicked() ) ); - - d_data->buttonUp[i] = btn; - } - - setNumButtons( 2 ); - setRange( 0.0, 1.0, 0.001 ); - setValue( 0.0 ); - - setSizePolicy( - QSizePolicy( QSizePolicy::Preferred, QSizePolicy::Fixed ) ); - - setFocusProxy( d_data->valueEdit ); - setFocusPolicy( Qt::StrongFocus ); -} - -//! Destructor -QwtCounter::~QwtCounter() -{ - delete d_data; -} - -//! Set from lineedit -void QwtCounter::textChanged() -{ - if ( !d_data->editable ) - return; - - bool converted = false; - - const double value = d_data->valueEdit->text().toDouble( &converted ); - if ( converted ) - setValue( value ); -} - -/** - \brief Allow/disallow the user to manually edit the value - - \param editable true enables editing - \sa editable() -*/ -void QwtCounter::setEditable( bool editable ) -{ - if ( editable == d_data->editable ) - return; - - d_data->editable = editable; - d_data->valueEdit->setReadOnly( !editable ); -} - -//! returns whether the line edit is edatble. (default is yes) -bool QwtCounter::editable() const -{ - return d_data->editable; -} - -/*! - Handle PolishRequest events - \param event Event -*/ -bool QwtCounter::event( QEvent *event ) -{ - if ( event->type() == QEvent::PolishRequest ) - { - const int w = d_data->valueEdit->fontMetrics().width( "W" ) + 8; - for ( int i = 0; i < ButtonCnt; i++ ) - { - d_data->buttonDown[i]->setMinimumWidth( w ); - d_data->buttonUp[i]->setMinimumWidth( w ); - } - } - - return QWidget::event( event ); -} - -/*! - Handle key events - - - Ctrl + Qt::Key_Home\n - Step to minValue() - - Ctrl + Qt::Key_End\n - Step to maxValue() - - Qt::Key_Up\n - Increment by incSteps(QwtCounter::Button1) - - Qt::Key_Down\n - Decrement by incSteps(QwtCounter::Button1) - - Qt::Key_PageUp\n - Increment by incSteps(QwtCounter::Button2) - - Qt::Key_PageDown\n - Decrement by incSteps(QwtCounter::Button2) - - Shift + Qt::Key_PageUp\n - Increment by incSteps(QwtCounter::Button3) - - Shift + Qt::Key_PageDown\n - Decrement by incSteps(QwtCounter::Button3) - - \param event Key event -*/ -void QwtCounter::keyPressEvent ( QKeyEvent *event ) -{ - bool accepted = true; - - switch ( event->key() ) - { - case Qt::Key_Home: - { - if ( event->modifiers() & Qt::ControlModifier ) - setValue( minValue() ); - else - accepted = false; - break; - } - case Qt::Key_End: - { - if ( event->modifiers() & Qt::ControlModifier ) - setValue( maxValue() ); - else - accepted = false; - break; - } - case Qt::Key_Up: - { - incValue( d_data->increment[0] ); - break; - } - case Qt::Key_Down: - { - incValue( -d_data->increment[0] ); - break; - } - case Qt::Key_PageUp: - case Qt::Key_PageDown: - { - int increment = d_data->increment[0]; - if ( d_data->numButtons >= 2 ) - increment = d_data->increment[1]; - if ( d_data->numButtons >= 3 ) - { - if ( event->modifiers() & Qt::ShiftModifier ) - increment = d_data->increment[2]; - } - if ( event->key() == Qt::Key_PageDown ) - increment = -increment; - incValue( increment ); - break; - } - default: - { - accepted = false; - } - } - - if ( accepted ) - { - event->accept(); - return; - } - - QWidget::keyPressEvent ( event ); -} - -/*! - Handle wheel events - \param event Wheel event -*/ -void QwtCounter::wheelEvent( QWheelEvent *event ) -{ - event->accept(); - - if ( d_data->numButtons <= 0 ) - return; - - int increment = d_data->increment[0]; - if ( d_data->numButtons >= 2 ) - { - if ( event->modifiers() & Qt::ControlModifier ) - increment = d_data->increment[1]; - } - if ( d_data->numButtons >= 3 ) - { - if ( event->modifiers() & Qt::ShiftModifier ) - increment = d_data->increment[2]; - } - - for ( int i = 0; i < d_data->numButtons; i++ ) - { - if ( d_data->buttonDown[i]->geometry().contains( event->pos() ) || - d_data->buttonUp[i]->geometry().contains( event->pos() ) ) - { - increment = d_data->increment[i]; - } - } - - const int wheel_delta = 120; - - int delta = event->delta(); - if ( delta >= 2 * wheel_delta ) - delta /= 2; // Never saw an abs(delta) < 240 - - incValue( delta / wheel_delta * increment ); -} - -/*! - Specify the number of steps by which the value - is incremented or decremented when a specified button - is pushed. - - \param button Button index - \param nSteps Number of steps - - \sa incSteps() -*/ -void QwtCounter::setIncSteps( QwtCounter::Button button, int nSteps ) -{ - if ( button >= 0 && button < ButtonCnt ) - d_data->increment[button] = nSteps; -} - -/*! - \return the number of steps by which a specified button increments the value - or 0 if the button is invalid. - \param button Button index - - \sa setIncSteps() -*/ -int QwtCounter::incSteps( QwtCounter::Button button ) const -{ - if ( button >= 0 && button < ButtonCnt ) - return d_data->increment[button]; - - return 0; -} - -/*! - \brief Set a new value - - Calls QwtDoubleRange::setValue and does all visual updates. - - \param value New value - \sa QwtDoubleRange::setValue() -*/ - -void QwtCounter::setValue( double value ) -{ - QwtDoubleRange::setValue( value ); - - showNum( this->value() ); - updateButtons(); -} - -/*! - \brief Notify a change of value -*/ -void QwtCounter::valueChange() -{ - if ( isValid() ) - showNum( value() ); - else - d_data->valueEdit->setText( QString::null ); - - updateButtons(); - - if ( isValid() ) - Q_EMIT valueChanged( value() ); -} - -/*! - \brief Update buttons according to the current value - - When the QwtCounter under- or over-flows, the focus is set to the smallest - up- or down-button and counting is disabled. - - Counting is re-enabled on a button release event (mouse or space bar). -*/ -void QwtCounter::updateButtons() -{ - if ( isValid() ) - { - // 1. save enabled state of the smallest down- and up-button - // 2. change enabled state on under- or over-flow - - for ( int i = 0; i < QwtCounter::ButtonCnt; i++ ) - { - d_data->buttonDown[i]->setEnabled( value() > minValue() ); - d_data->buttonUp[i]->setEnabled( value() < maxValue() ); - } - } - else - { - for ( int i = 0; i < QwtCounter::ButtonCnt; i++ ) - { - d_data->buttonDown[i]->setEnabled( false ); - d_data->buttonUp[i]->setEnabled( false ); - } - } -} - -/*! - \brief Specify the number of buttons on each side of the label - \param numButtons Number of buttons -*/ -void QwtCounter::setNumButtons( int numButtons ) -{ - if ( numButtons < 0 || numButtons > QwtCounter::ButtonCnt ) - return; - - for ( int i = 0; i < QwtCounter::ButtonCnt; i++ ) - { - if ( i < numButtons ) - { - d_data->buttonDown[i]->show(); - d_data->buttonUp[i]->show(); - } - else - { - d_data->buttonDown[i]->hide(); - d_data->buttonUp[i]->hide(); - } - } - - d_data->numButtons = numButtons; -} - -/*! - \return The number of buttons on each side of the widget. -*/ -int QwtCounter::numButtons() const -{ - return d_data->numButtons; -} - -/*! - Display number string - - \param number Number -*/ -void QwtCounter::showNum( double number ) -{ - QString text; - text.setNum( number ); - - const int cursorPos = d_data->valueEdit->cursorPosition(); - d_data->valueEdit->setText( text ); - d_data->valueEdit->setCursorPosition( cursorPos ); -} - -//! Button clicked -void QwtCounter::btnClicked() -{ - for ( int i = 0; i < ButtonCnt; i++ ) - { - if ( d_data->buttonUp[i] == sender() ) - incValue( d_data->increment[i] ); - - if ( d_data->buttonDown[i] == sender() ) - incValue( -d_data->increment[i] ); - } -} - -//! Button released -void QwtCounter::btnReleased() -{ - Q_EMIT buttonReleased( value() ); -} - -/*! - \brief Notify change of range - - This function updates the enabled property of - all buttons contained in QwtCounter. -*/ -void QwtCounter::rangeChange() -{ - updateButtons(); -} - -//! A size hint -QSize QwtCounter::sizeHint() const -{ - QString tmp; - - int w = tmp.setNum( minValue() ).length(); - int w1 = tmp.setNum( maxValue() ).length(); - if ( w1 > w ) - w = w1; - w1 = tmp.setNum( minValue() + step() ).length(); - if ( w1 > w ) - w = w1; - w1 = tmp.setNum( maxValue() - step() ).length(); - if ( w1 > w ) - w = w1; - - tmp.fill( '9', w ); - - QFontMetrics fm( d_data->valueEdit->font() ); - w = fm.width( tmp ) + 2; - if ( d_data->valueEdit->hasFrame() ) - w += 2 * style()->pixelMetric( QStyle::PM_DefaultFrameWidth ); - - // Now we replace default sizeHint contribution of d_data->valueEdit by - // what we really need. - - w += QWidget::sizeHint().width() - d_data->valueEdit->sizeHint().width(); - - const int h = qMin( QWidget::sizeHint().height(), - d_data->valueEdit->minimumSizeHint().height() ); - return QSize( w, h ); -} - -//! returns the step size -double QwtCounter::step() const -{ - return QwtDoubleRange::step(); -} - -/*! - Set the step size - \param stepSize Step size - \sa QwtDoubleRange::setStep() -*/ -void QwtCounter::setStep( double stepSize ) -{ - QwtDoubleRange::setStep( stepSize ); -} - -//! returns the minimum value of the range -double QwtCounter::minValue() const -{ - return QwtDoubleRange::minValue(); -} - -/*! - Set the minimum value of the range - - \param value Minimum value - \sa setMaxValue(), minValue() -*/ -void QwtCounter::setMinValue( double value ) -{ - setRange( value, maxValue(), step() ); -} - -//! returns the maximum value of the range -double QwtCounter::maxValue() const -{ - return QwtDoubleRange::maxValue(); -} - -/*! - Set the maximum value of the range - - \param value Maximum value - \sa setMinValue(), maxVal() -*/ -void QwtCounter::setMaxValue( double value ) -{ - setRange( minValue(), value, step() ); -} - -/*! - Set the number of increment steps for button 1 - \param nSteps Number of steps -*/ -void QwtCounter::setStepButton1( int nSteps ) -{ - setIncSteps( Button1, nSteps ); -} - -//! returns the number of increment steps for button 1 -int QwtCounter::stepButton1() const -{ - return incSteps( Button1 ); -} - -/*! - Set the number of increment steps for button 2 - \param nSteps Number of steps -*/ -void QwtCounter::setStepButton2( int nSteps ) -{ - setIncSteps( Button2, nSteps ); -} - -//! returns the number of increment steps for button 2 -int QwtCounter::stepButton2() const -{ - return incSteps( Button2 ); -} - -/*! - Set the number of increment steps for button 3 - \param nSteps Number of steps -*/ -void QwtCounter::setStepButton3( int nSteps ) -{ - setIncSteps( Button3, nSteps ); -} - -//! returns the number of increment steps for button 3 -int QwtCounter::stepButton3() const -{ - return incSteps( Button3 ); -} - -//! \return Current value -double QwtCounter::value() const -{ - return QwtDoubleRange::value(); -} - +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_arrow_button.h" +#include "qwt_math.h" +#include "qwt_counter.h" +#include +#include +#include +#include +#include + +class QwtCounter::PrivateData +{ +public: + PrivateData(): + editable( true ) + { + increment[Button1] = 1; + increment[Button2] = 10; + increment[Button3] = 100; + } + + QwtArrowButton *buttonDown[ButtonCnt]; + QwtArrowButton *buttonUp[ButtonCnt]; + QLineEdit *valueEdit; + + int increment[ButtonCnt]; + int numButtons; + + bool editable; +}; + +/*! + The default number of buttons is set to 2. The default increments are: + \li Button 1: 1 step + \li Button 2: 10 steps + \li Button 3: 100 steps + + \param parent + */ +QwtCounter::QwtCounter( QWidget *parent ): + QWidget( parent ) +{ + initCounter(); +} + +void QwtCounter::initCounter() +{ + d_data = new PrivateData; + + QHBoxLayout *layout = new QHBoxLayout( this ); + layout->setSpacing( 0 ); + layout->setMargin( 0 ); + + for ( int i = ButtonCnt - 1; i >= 0; i-- ) + { + QwtArrowButton *btn = + new QwtArrowButton( i + 1, Qt::DownArrow, this ); + btn->setFocusPolicy( Qt::NoFocus ); + btn->installEventFilter( this ); + layout->addWidget( btn ); + + connect( btn, SIGNAL( released() ), SLOT( btnReleased() ) ); + connect( btn, SIGNAL( clicked() ), SLOT( btnClicked() ) ); + + d_data->buttonDown[i] = btn; + } + + d_data->valueEdit = new QLineEdit( this ); + d_data->valueEdit->setReadOnly( false ); + d_data->valueEdit->setValidator( new QDoubleValidator( d_data->valueEdit ) ); + layout->addWidget( d_data->valueEdit ); + + connect( d_data->valueEdit, SIGNAL( editingFinished() ), + SLOT( textChanged() ) ); + + layout->setStretchFactor( d_data->valueEdit, 10 ); + + for ( int i = 0; i < ButtonCnt; i++ ) + { + QwtArrowButton *btn = + new QwtArrowButton( i + 1, Qt::UpArrow, this ); + btn->setFocusPolicy( Qt::NoFocus ); + btn->installEventFilter( this ); + layout->addWidget( btn ); + + connect( btn, SIGNAL( released() ), SLOT( btnReleased() ) ); + connect( btn, SIGNAL( clicked() ), SLOT( btnClicked() ) ); + + d_data->buttonUp[i] = btn; + } + + setNumButtons( 2 ); + setRange( 0.0, 1.0, 0.001 ); + setValue( 0.0 ); + + setSizePolicy( + QSizePolicy( QSizePolicy::Preferred, QSizePolicy::Fixed ) ); + + setFocusProxy( d_data->valueEdit ); + setFocusPolicy( Qt::StrongFocus ); +} + +//! Destructor +QwtCounter::~QwtCounter() +{ + delete d_data; +} + +//! Set from lineedit +void QwtCounter::textChanged() +{ + if ( !d_data->editable ) + return; + + bool converted = false; + + const double value = d_data->valueEdit->text().toDouble( &converted ); + if ( converted ) + setValue( value ); +} + +/** + \brief Allow/disallow the user to manually edit the value + + \param editable true enables editing + \sa editable() +*/ +void QwtCounter::setEditable( bool editable ) +{ + if ( editable == d_data->editable ) + return; + + d_data->editable = editable; + d_data->valueEdit->setReadOnly( !editable ); +} + +//! returns whether the line edit is edatble. (default is yes) +bool QwtCounter::editable() const +{ + return d_data->editable; +} + +/*! + Handle PolishRequest events + \param event Event +*/ +bool QwtCounter::event( QEvent *event ) +{ + if ( event->type() == QEvent::PolishRequest ) + { + const int w = d_data->valueEdit->fontMetrics().width( "W" ) + 8; + for ( int i = 0; i < ButtonCnt; i++ ) + { + d_data->buttonDown[i]->setMinimumWidth( w ); + d_data->buttonUp[i]->setMinimumWidth( w ); + } + } + + return QWidget::event( event ); +} + +/*! + Handle key events + + - Ctrl + Qt::Key_Home\n + Step to minValue() + - Ctrl + Qt::Key_End\n + Step to maxValue() + - Qt::Key_Up\n + Increment by incSteps(QwtCounter::Button1) + - Qt::Key_Down\n + Decrement by incSteps(QwtCounter::Button1) + - Qt::Key_PageUp\n + Increment by incSteps(QwtCounter::Button2) + - Qt::Key_PageDown\n + Decrement by incSteps(QwtCounter::Button2) + - Shift + Qt::Key_PageUp\n + Increment by incSteps(QwtCounter::Button3) + - Shift + Qt::Key_PageDown\n + Decrement by incSteps(QwtCounter::Button3) + + \param event Key event +*/ +void QwtCounter::keyPressEvent ( QKeyEvent *event ) +{ + bool accepted = true; + + switch ( event->key() ) + { + case Qt::Key_Home: + { + if ( event->modifiers() & Qt::ControlModifier ) + setValue( minValue() ); + else + accepted = false; + break; + } + case Qt::Key_End: + { + if ( event->modifiers() & Qt::ControlModifier ) + setValue( maxValue() ); + else + accepted = false; + break; + } + case Qt::Key_Up: + { + incValue( d_data->increment[0] ); + break; + } + case Qt::Key_Down: + { + incValue( -d_data->increment[0] ); + break; + } + case Qt::Key_PageUp: + case Qt::Key_PageDown: + { + int increment = d_data->increment[0]; + if ( d_data->numButtons >= 2 ) + increment = d_data->increment[1]; + if ( d_data->numButtons >= 3 ) + { + if ( event->modifiers() & Qt::ShiftModifier ) + increment = d_data->increment[2]; + } + if ( event->key() == Qt::Key_PageDown ) + increment = -increment; + incValue( increment ); + break; + } + default: + { + accepted = false; + } + } + + if ( accepted ) + { + event->accept(); + return; + } + + QWidget::keyPressEvent ( event ); +} + +/*! + Handle wheel events + \param event Wheel event +*/ +void QwtCounter::wheelEvent( QWheelEvent *event ) +{ + event->accept(); + + if ( d_data->numButtons <= 0 ) + return; + + int increment = d_data->increment[0]; + if ( d_data->numButtons >= 2 ) + { + if ( event->modifiers() & Qt::ControlModifier ) + increment = d_data->increment[1]; + } + if ( d_data->numButtons >= 3 ) + { + if ( event->modifiers() & Qt::ShiftModifier ) + increment = d_data->increment[2]; + } + + for ( int i = 0; i < d_data->numButtons; i++ ) + { + if ( d_data->buttonDown[i]->geometry().contains( event->pos() ) || + d_data->buttonUp[i]->geometry().contains( event->pos() ) ) + { + increment = d_data->increment[i]; + } + } + + const int wheel_delta = 120; + + int delta = event->delta(); + if ( delta >= 2 * wheel_delta ) + delta /= 2; // Never saw an abs(delta) < 240 + + incValue( delta / wheel_delta * increment ); +} + +/*! + Specify the number of steps by which the value + is incremented or decremented when a specified button + is pushed. + + \param button Button index + \param nSteps Number of steps + + \sa incSteps() +*/ +void QwtCounter::setIncSteps( QwtCounter::Button button, int nSteps ) +{ + if ( button >= 0 && button < ButtonCnt ) + d_data->increment[button] = nSteps; +} + +/*! + \return the number of steps by which a specified button increments the value + or 0 if the button is invalid. + \param button Button index + + \sa setIncSteps() +*/ +int QwtCounter::incSteps( QwtCounter::Button button ) const +{ + if ( button >= 0 && button < ButtonCnt ) + return d_data->increment[button]; + + return 0; +} + +/*! + \brief Set a new value + + Calls QwtDoubleRange::setValue and does all visual updates. + + \param value New value + \sa QwtDoubleRange::setValue() +*/ + +void QwtCounter::setValue( double value ) +{ + QwtDoubleRange::setValue( value ); + + showNum( this->value() ); + updateButtons(); +} + +/*! + \brief Notify a change of value +*/ +void QwtCounter::valueChange() +{ + if ( isValid() ) + showNum( value() ); + else + d_data->valueEdit->setText( QString::null ); + + updateButtons(); + + if ( isValid() ) + Q_EMIT valueChanged( value() ); +} + +/*! + \brief Update buttons according to the current value + + When the QwtCounter under- or over-flows, the focus is set to the smallest + up- or down-button and counting is disabled. + + Counting is re-enabled on a button release event (mouse or space bar). +*/ +void QwtCounter::updateButtons() +{ + if ( isValid() ) + { + // 1. save enabled state of the smallest down- and up-button + // 2. change enabled state on under- or over-flow + + for ( int i = 0; i < QwtCounter::ButtonCnt; i++ ) + { + d_data->buttonDown[i]->setEnabled( value() > minValue() ); + d_data->buttonUp[i]->setEnabled( value() < maxValue() ); + } + } + else + { + for ( int i = 0; i < QwtCounter::ButtonCnt; i++ ) + { + d_data->buttonDown[i]->setEnabled( false ); + d_data->buttonUp[i]->setEnabled( false ); + } + } +} + +/*! + \brief Specify the number of buttons on each side of the label + \param numButtons Number of buttons +*/ +void QwtCounter::setNumButtons( int numButtons ) +{ + if ( numButtons < 0 || numButtons > QwtCounter::ButtonCnt ) + return; + + for ( int i = 0; i < QwtCounter::ButtonCnt; i++ ) + { + if ( i < numButtons ) + { + d_data->buttonDown[i]->show(); + d_data->buttonUp[i]->show(); + } + else + { + d_data->buttonDown[i]->hide(); + d_data->buttonUp[i]->hide(); + } + } + + d_data->numButtons = numButtons; +} + +/*! + \return The number of buttons on each side of the widget. +*/ +int QwtCounter::numButtons() const +{ + return d_data->numButtons; +} + +/*! + Display number string + + \param number Number +*/ +void QwtCounter::showNum( double number ) +{ + QString text; + text.setNum( number ); + + const int cursorPos = d_data->valueEdit->cursorPosition(); + d_data->valueEdit->setText( text ); + d_data->valueEdit->setCursorPosition( cursorPos ); +} + +//! Button clicked +void QwtCounter::btnClicked() +{ + for ( int i = 0; i < ButtonCnt; i++ ) + { + if ( d_data->buttonUp[i] == sender() ) + incValue( d_data->increment[i] ); + + if ( d_data->buttonDown[i] == sender() ) + incValue( -d_data->increment[i] ); + } +} + +//! Button released +void QwtCounter::btnReleased() +{ + Q_EMIT buttonReleased( value() ); +} + +/*! + \brief Notify change of range + + This function updates the enabled property of + all buttons contained in QwtCounter. +*/ +void QwtCounter::rangeChange() +{ + updateButtons(); +} + +//! A size hint +QSize QwtCounter::sizeHint() const +{ + QString tmp; + + int w = tmp.setNum( minValue() ).length(); + int w1 = tmp.setNum( maxValue() ).length(); + if ( w1 > w ) + w = w1; + w1 = tmp.setNum( minValue() + step() ).length(); + if ( w1 > w ) + w = w1; + w1 = tmp.setNum( maxValue() - step() ).length(); + if ( w1 > w ) + w = w1; + + tmp.fill( '9', w ); + + QFontMetrics fm( d_data->valueEdit->font() ); + w = fm.width( tmp ) + 2; + if ( d_data->valueEdit->hasFrame() ) + w += 2 * style()->pixelMetric( QStyle::PM_DefaultFrameWidth ); + + // Now we replace default sizeHint contribution of d_data->valueEdit by + // what we really need. + + w += QWidget::sizeHint().width() - d_data->valueEdit->sizeHint().width(); + + const int h = qMin( QWidget::sizeHint().height(), + d_data->valueEdit->minimumSizeHint().height() ); + return QSize( w, h ); +} + +//! returns the step size +double QwtCounter::step() const +{ + return QwtDoubleRange::step(); +} + +/*! + Set the step size + \param stepSize Step size + \sa QwtDoubleRange::setStep() +*/ +void QwtCounter::setStep( double stepSize ) +{ + QwtDoubleRange::setStep( stepSize ); +} + +//! returns the minimum value of the range +double QwtCounter::minValue() const +{ + return QwtDoubleRange::minValue(); +} + +/*! + Set the minimum value of the range + + \param value Minimum value + \sa setMaxValue(), minValue() +*/ +void QwtCounter::setMinValue( double value ) +{ + setRange( value, maxValue(), step() ); +} + +//! returns the maximum value of the range +double QwtCounter::maxValue() const +{ + return QwtDoubleRange::maxValue(); +} + +/*! + Set the maximum value of the range + + \param value Maximum value + \sa setMinValue(), maxVal() +*/ +void QwtCounter::setMaxValue( double value ) +{ + setRange( minValue(), value, step() ); +} + +/*! + Set the number of increment steps for button 1 + \param nSteps Number of steps +*/ +void QwtCounter::setStepButton1( int nSteps ) +{ + setIncSteps( Button1, nSteps ); +} + +//! returns the number of increment steps for button 1 +int QwtCounter::stepButton1() const +{ + return incSteps( Button1 ); +} + +/*! + Set the number of increment steps for button 2 + \param nSteps Number of steps +*/ +void QwtCounter::setStepButton2( int nSteps ) +{ + setIncSteps( Button2, nSteps ); +} + +//! returns the number of increment steps for button 2 +int QwtCounter::stepButton2() const +{ + return incSteps( Button2 ); +} + +/*! + Set the number of increment steps for button 3 + \param nSteps Number of steps +*/ +void QwtCounter::setStepButton3( int nSteps ) +{ + setIncSteps( Button3, nSteps ); +} + +//! returns the number of increment steps for button 3 +int QwtCounter::stepButton3() const +{ + return incSteps( Button3 ); +} + +//! \return Current value +double QwtCounter::value() const +{ + return QwtDoubleRange::value(); +} + diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_counter.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_counter.h index e3d40ada8..b3f4ad549 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_counter.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_counter.h @@ -1,160 +1,160 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_COUNTER_H -#define QWT_COUNTER_H - -#include "qwt_global.h" -#include "qwt_double_range.h" -#include - -/*! - \brief The Counter Widget - - A Counter consists of a label displaying a number and - one ore more (up to three) push buttons on each side - of the label which can be used to increment or decrement - the counter's value. - - A Counter has a range from a minimum value to a maximum value - and a step size. The range can be specified using - QwtDblRange::setRange(). - The counter's value is an integer multiple of the step size. - The number of steps by which a button increments or decrements - the value can be specified using QwtCounter::setIncSteps(). - The number of buttons can be changed with - QwtCounter::setNumButtons(). - - Holding the space bar down with focus on a button is the - fastest method to step through the counter values. - When the counter underflows/overflows, the focus is set - to the smallest up/down button and counting is disabled. - Counting is re-enabled on a button release event (mouse or - space bar). - - Example: -\code -#include "../include/qwt_counter.h> - -QwtCounter *cnt; - -cnt = new QwtCounter(parent, name); - -cnt->setRange(0.0, 100.0, 1.0); // From 0.0 to 100, step 1.0 -cnt->setNumButtons(2); // Two buttons each side -cnt->setIncSteps(QwtCounter::Button1, 1); // Button 1 increments 1 step -cnt->setIncSteps(QwtCounter::Button2, 20); // Button 2 increments 20 steps - -connect(cnt, SIGNAL(valueChanged(double)), my_class, SLOT(newValue(double))); -\endcode - */ - -class QWT_EXPORT QwtCounter : public QWidget, public QwtDoubleRange -{ - Q_OBJECT - - Q_PROPERTY( int numButtons READ numButtons WRITE setNumButtons ) - Q_PROPERTY( double basicstep READ step WRITE setStep ) - Q_PROPERTY( double minValue READ minValue WRITE setMinValue ) - Q_PROPERTY( double maxValue READ maxValue WRITE setMaxValue ) - Q_PROPERTY( int stepButton1 READ stepButton1 WRITE setStepButton1 ) - Q_PROPERTY( int stepButton2 READ stepButton2 WRITE setStepButton2 ) - Q_PROPERTY( int stepButton3 READ stepButton3 WRITE setStepButton3 ) - Q_PROPERTY( double value READ value WRITE setValue ) - Q_PROPERTY( bool editable READ editable WRITE setEditable ) - -public: - //! Button index - enum Button - { - //! Button intended for minor steps - Button1, - - //! Button intended for medium steps - Button2, - - //! Button intended for large steps - Button3, - - //! Number of buttons - ButtonCnt - }; - - explicit QwtCounter( QWidget *parent = NULL ); - virtual ~QwtCounter(); - - bool editable() const; - void setEditable( bool ); - - void setNumButtons( int n ); - int numButtons() const; - - void setIncSteps( QwtCounter::Button btn, int nSteps ); - int incSteps( QwtCounter::Button btn ) const; - - virtual void setValue( double ); - virtual QSize sizeHint() const; - - // a set of dummies to help the designer - - double step() const; - void setStep( double s ); - - double minValue() const; - void setMinValue( double m ); - - double maxValue() const; - void setMaxValue( double m ); - - void setStepButton1( int nSteps ); - int stepButton1() const; - - void setStepButton2( int nSteps ); - int stepButton2() const; - - void setStepButton3( int nSteps ); - int stepButton3() const; - - virtual double value() const; - -Q_SIGNALS: - /*! - This signal is emitted when a button has been released - \param value The new value - */ - void buttonReleased ( double value ); - - /*! - This signal is emitted when the counter's value has changed - \param value The new value - */ - void valueChanged ( double value ); - -protected: - virtual bool event( QEvent * ); - virtual void wheelEvent( QWheelEvent * ); - virtual void keyPressEvent( QKeyEvent * ); - virtual void rangeChange(); - -private Q_SLOTS: - void btnReleased(); - void btnClicked(); - void textChanged(); - -private: - void initCounter(); - void updateButtons(); - void showNum( double ); - virtual void valueChange(); - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_COUNTER_H +#define QWT_COUNTER_H + +#include "qwt_global.h" +#include "qwt_double_range.h" +#include + +/*! + \brief The Counter Widget + + A Counter consists of a label displaying a number and + one ore more (up to three) push buttons on each side + of the label which can be used to increment or decrement + the counter's value. + + A Counter has a range from a minimum value to a maximum value + and a step size. The range can be specified using + QwtDblRange::setRange(). + The counter's value is an integer multiple of the step size. + The number of steps by which a button increments or decrements + the value can be specified using QwtCounter::setIncSteps(). + The number of buttons can be changed with + QwtCounter::setNumButtons(). + + Holding the space bar down with focus on a button is the + fastest method to step through the counter values. + When the counter underflows/overflows, the focus is set + to the smallest up/down button and counting is disabled. + Counting is re-enabled on a button release event (mouse or + space bar). + + Example: +\code +#include "../include/qwt_counter.h> + +QwtCounter *cnt; + +cnt = new QwtCounter(parent, name); + +cnt->setRange(0.0, 100.0, 1.0); // From 0.0 to 100, step 1.0 +cnt->setNumButtons(2); // Two buttons each side +cnt->setIncSteps(QwtCounter::Button1, 1); // Button 1 increments 1 step +cnt->setIncSteps(QwtCounter::Button2, 20); // Button 2 increments 20 steps + +connect(cnt, SIGNAL(valueChanged(double)), my_class, SLOT(newValue(double))); +\endcode + */ + +class QWT_EXPORT QwtCounter : public QWidget, public QwtDoubleRange +{ + Q_OBJECT + + Q_PROPERTY( int numButtons READ numButtons WRITE setNumButtons ) + Q_PROPERTY( double basicstep READ step WRITE setStep ) + Q_PROPERTY( double minValue READ minValue WRITE setMinValue ) + Q_PROPERTY( double maxValue READ maxValue WRITE setMaxValue ) + Q_PROPERTY( int stepButton1 READ stepButton1 WRITE setStepButton1 ) + Q_PROPERTY( int stepButton2 READ stepButton2 WRITE setStepButton2 ) + Q_PROPERTY( int stepButton3 READ stepButton3 WRITE setStepButton3 ) + Q_PROPERTY( double value READ value WRITE setValue ) + Q_PROPERTY( bool editable READ editable WRITE setEditable ) + +public: + //! Button index + enum Button + { + //! Button intended for minor steps + Button1, + + //! Button intended for medium steps + Button2, + + //! Button intended for large steps + Button3, + + //! Number of buttons + ButtonCnt + }; + + explicit QwtCounter( QWidget *parent = NULL ); + virtual ~QwtCounter(); + + bool editable() const; + void setEditable( bool ); + + void setNumButtons( int n ); + int numButtons() const; + + void setIncSteps( QwtCounter::Button btn, int nSteps ); + int incSteps( QwtCounter::Button btn ) const; + + virtual void setValue( double ); + virtual QSize sizeHint() const; + + // a set of dummies to help the designer + + double step() const; + void setStep( double s ); + + double minValue() const; + void setMinValue( double m ); + + double maxValue() const; + void setMaxValue( double m ); + + void setStepButton1( int nSteps ); + int stepButton1() const; + + void setStepButton2( int nSteps ); + int stepButton2() const; + + void setStepButton3( int nSteps ); + int stepButton3() const; + + virtual double value() const; + +Q_SIGNALS: + /*! + This signal is emitted when a button has been released + \param value The new value + */ + void buttonReleased ( double value ); + + /*! + This signal is emitted when the counter's value has changed + \param value The new value + */ + void valueChanged ( double value ); + +protected: + virtual bool event( QEvent * ); + virtual void wheelEvent( QWheelEvent * ); + virtual void keyPressEvent( QKeyEvent * ); + virtual void rangeChange(); + +private Q_SLOTS: + void btnReleased(); + void btnClicked(); + void textChanged(); + +private: + void initCounter(); + void updateButtons(); + void showNum( double ); + virtual void valueChange(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_curve_fitter.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_curve_fitter.cpp index 275954f08..639a80dab 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_curve_fitter.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_curve_fitter.cpp @@ -1,405 +1,405 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_curve_fitter.h" -#include "qwt_math.h" -#include "qwt_spline.h" -#include -#include - -#if QT_VERSION < 0x040601 -#define qFabs(x) ::fabs(x) -#endif - -//! Constructor -QwtCurveFitter::QwtCurveFitter() -{ -} - -//! Destructor -QwtCurveFitter::~QwtCurveFitter() -{ -} - -class QwtSplineCurveFitter::PrivateData -{ -public: - PrivateData(): - fitMode( QwtSplineCurveFitter::Auto ), - splineSize( 250 ) - { - } - - QwtSpline spline; - QwtSplineCurveFitter::FitMode fitMode; - int splineSize; -}; - -//! Constructor -QwtSplineCurveFitter::QwtSplineCurveFitter() -{ - d_data = new PrivateData; -} - -//! Destructor -QwtSplineCurveFitter::~QwtSplineCurveFitter() -{ - delete d_data; -} - -/*! - Select the algorithm used for building the spline - - \param mode Mode representing a spline algorithm - \sa fitMode() -*/ -void QwtSplineCurveFitter::setFitMode( FitMode mode ) -{ - d_data->fitMode = mode; -} - -/*! - \return Mode representing a spline algorithm - \sa setFitMode() -*/ -QwtSplineCurveFitter::FitMode QwtSplineCurveFitter::fitMode() const -{ - return d_data->fitMode; -} - -/*! - Assign a spline - - \param spline Spline - \sa spline() -*/ -void QwtSplineCurveFitter::setSpline( const QwtSpline &spline ) -{ - d_data->spline = spline; - d_data->spline.reset(); -} - -/*! - \return Spline - \sa setSpline() -*/ -const QwtSpline &QwtSplineCurveFitter::spline() const -{ - return d_data->spline; -} - -/*! - \return Spline - \sa setSpline() -*/ -QwtSpline &QwtSplineCurveFitter::spline() -{ - return d_data->spline; -} - -/*! - Assign a spline size ( has to be at least 10 points ) - - \param splineSize Spline size - \sa splineSize() -*/ -void QwtSplineCurveFitter::setSplineSize( int splineSize ) -{ - d_data->splineSize = qMax( splineSize, 10 ); -} - -/*! - \return Spline size - \sa setSplineSize() -*/ -int QwtSplineCurveFitter::splineSize() const -{ - return d_data->splineSize; -} - -/*! - Find a curve which has the best fit to a series of data points - - \param points Series of data points - \return Curve points -*/ -QPolygonF QwtSplineCurveFitter::fitCurve( const QPolygonF &points ) const -{ - const int size = points.size(); - if ( size <= 2 ) - return points; - - FitMode fitMode = d_data->fitMode; - if ( fitMode == Auto ) - { - fitMode = Spline; - - const QPointF *p = points.data(); - for ( int i = 1; i < size; i++ ) - { - if ( p[i].x() <= p[i-1].x() ) - { - fitMode = ParametricSpline; - break; - } - }; - } - - if ( fitMode == ParametricSpline ) - return fitParametric( points ); - else - return fitSpline( points ); -} - -QPolygonF QwtSplineCurveFitter::fitSpline( const QPolygonF &points ) const -{ - d_data->spline.setPoints( points ); - if ( !d_data->spline.isValid() ) - return points; - - QPolygonF fittedPoints( d_data->splineSize ); - - const double x1 = points[0].x(); - const double x2 = points[int( points.size() - 1 )].x(); - const double dx = x2 - x1; - const double delta = dx / ( d_data->splineSize - 1 ); - - for ( int i = 0; i < d_data->splineSize; i++ ) - { - QPointF &p = fittedPoints[i]; - - const double v = x1 + i * delta; - const double sv = d_data->spline.value( v ); - - p.setX( v ); - p.setY( sv ); - } - d_data->spline.reset(); - - return fittedPoints; -} - -QPolygonF QwtSplineCurveFitter::fitParametric( const QPolygonF &points ) const -{ - int i; - const int size = points.size(); - - QPolygonF fittedPoints( d_data->splineSize ); - QPolygonF splinePointsX( size ); - QPolygonF splinePointsY( size ); - - const QPointF *p = points.data(); - QPointF *spX = splinePointsX.data(); - QPointF *spY = splinePointsY.data(); - - double param = 0.0; - for ( i = 0; i < size; i++ ) - { - const double x = p[i].x(); - const double y = p[i].y(); - if ( i > 0 ) - { - const double delta = qSqrt( qwtSqr( x - spX[i-1].y() ) - + qwtSqr( y - spY[i-1].y() ) ); - param += qMax( delta, 1.0 ); - } - spX[i].setX( param ); - spX[i].setY( x ); - spY[i].setX( param ); - spY[i].setY( y ); - } - - d_data->spline.setPoints( splinePointsX ); - if ( !d_data->spline.isValid() ) - return points; - - const double deltaX = - splinePointsX[size - 1].x() / ( d_data->splineSize - 1 ); - for ( i = 0; i < d_data->splineSize; i++ ) - { - const double dtmp = i * deltaX; - fittedPoints[i].setX( d_data->spline.value( dtmp ) ); - } - - d_data->spline.setPoints( splinePointsY ); - if ( !d_data->spline.isValid() ) - return points; - - const double deltaY = - splinePointsY[size - 1].x() / ( d_data->splineSize - 1 ); - for ( i = 0; i < d_data->splineSize; i++ ) - { - const double dtmp = i * deltaY; - fittedPoints[i].setY( d_data->spline.value( dtmp ) ); - } - - return fittedPoints; -} - -class QwtWeedingCurveFitter::PrivateData -{ -public: - PrivateData(): - tolerance( 1.0 ) - { - } - - double tolerance; -}; - -class QwtWeedingCurveFitter::Line -{ -public: - Line( int i1 = 0, int i2 = 0 ): - from( i1 ), - to( i2 ) - { - } - - int from; - int to; -}; - -/*! - Constructor - - \param tolerance Tolerance - \sa setTolerance(), tolerance() -*/ -QwtWeedingCurveFitter::QwtWeedingCurveFitter( double tolerance ) -{ - d_data = new PrivateData; - setTolerance( tolerance ); -} - -//! Destructor -QwtWeedingCurveFitter::~QwtWeedingCurveFitter() -{ - delete d_data; -} - -/*! - Assign the tolerance - - The tolerance is the maximum distance, that is accaptable - between the original curve and the smoothed curve. - - Increasing the tolerance will reduce the number of the - resulting points. - - \param tolerance Tolerance - - \sa tolerance() -*/ -void QwtWeedingCurveFitter::setTolerance( double tolerance ) -{ - d_data->tolerance = qMax( tolerance, 0.0 ); -} - -/*! - \return Tolerance - \sa setTolerance() -*/ -double QwtWeedingCurveFitter::tolerance() const -{ - return d_data->tolerance; -} - -/*! - \param points Series of data points - \return Curve points -*/ -QPolygonF QwtWeedingCurveFitter::fitCurve( const QPolygonF &points ) const -{ - QStack stack; - stack.reserve( 500 ); - - const QPointF *p = points.data(); - const int nPoints = points.size(); - - QVector usePoint( nPoints, false ); - - double distToSegment; - - stack.push( Line( 0, nPoints - 1 ) ); - - while ( !stack.isEmpty() ) - { - const Line r = stack.pop(); - - // initialize line segment - const double vecX = p[r.to].x() - p[r.from].x(); - const double vecY = p[r.to].y() - p[r.from].y(); - - const double vecLength = qSqrt( vecX * vecX + vecY * vecY ); - - const double unitVecX = ( vecLength != 0.0 ) ? vecX / vecLength : 0.0; - const double unitVecY = ( vecLength != 0.0 ) ? vecY / vecLength : 0.0; - - double maxDist = 0.0; - int nVertexIndexMaxDistance = r.from + 1; - for ( int i = r.from + 1; i < r.to; i++ ) - { - //compare to anchor - const double fromVecX = p[i].x() - p[r.from].x(); - const double fromVecY = p[i].y() - p[r.from].y(); - const double fromVecLength = - qSqrt( fromVecX * fromVecX + fromVecY * fromVecY ); - - if ( fromVecX * unitVecX + fromVecY * unitVecY < 0.0 ) - { - distToSegment = fromVecLength; - } - if ( fromVecX * unitVecX + fromVecY * unitVecY < 0.0 ) - { - distToSegment = fromVecLength; - } - else - { - const double toVecX = p[i].x() - p[r.to].x(); - const double toVecY = p[i].y() - p[r.to].y(); - const double toVecLength = qSqrt( toVecX * toVecX + toVecY * toVecY ); - const double s = toVecX * ( -unitVecX ) + toVecY * ( -unitVecY ); - if ( s < 0.0 ) - distToSegment = toVecLength; - else - { - distToSegment = qSqrt( qFabs( toVecLength * toVecLength - s * s ) ); - } - } - - if ( maxDist < distToSegment ) - { - maxDist = distToSegment; - nVertexIndexMaxDistance = i; - } - } - if ( maxDist <= d_data->tolerance ) - { - usePoint[r.from] = true; - usePoint[r.to] = true; - } - else - { - stack.push( Line( r.from, nVertexIndexMaxDistance ) ); - stack.push( Line( nVertexIndexMaxDistance, r.to ) ); - } - } - - int cnt = 0; - - QPolygonF stripped( nPoints ); - for ( int i = 0; i < nPoints; i++ ) - { - if ( usePoint[i] ) - stripped[cnt++] = p[i]; - } - stripped.resize( cnt ); - return stripped; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_curve_fitter.h" +#include "qwt_math.h" +#include "qwt_spline.h" +#include +#include + +#if QT_VERSION < 0x040601 +#define qFabs(x) ::fabs(x) +#endif + +//! Constructor +QwtCurveFitter::QwtCurveFitter() +{ +} + +//! Destructor +QwtCurveFitter::~QwtCurveFitter() +{ +} + +class QwtSplineCurveFitter::PrivateData +{ +public: + PrivateData(): + fitMode( QwtSplineCurveFitter::Auto ), + splineSize( 250 ) + { + } + + QwtSpline spline; + QwtSplineCurveFitter::FitMode fitMode; + int splineSize; +}; + +//! Constructor +QwtSplineCurveFitter::QwtSplineCurveFitter() +{ + d_data = new PrivateData; +} + +//! Destructor +QwtSplineCurveFitter::~QwtSplineCurveFitter() +{ + delete d_data; +} + +/*! + Select the algorithm used for building the spline + + \param mode Mode representing a spline algorithm + \sa fitMode() +*/ +void QwtSplineCurveFitter::setFitMode( FitMode mode ) +{ + d_data->fitMode = mode; +} + +/*! + \return Mode representing a spline algorithm + \sa setFitMode() +*/ +QwtSplineCurveFitter::FitMode QwtSplineCurveFitter::fitMode() const +{ + return d_data->fitMode; +} + +/*! + Assign a spline + + \param spline Spline + \sa spline() +*/ +void QwtSplineCurveFitter::setSpline( const QwtSpline &spline ) +{ + d_data->spline = spline; + d_data->spline.reset(); +} + +/*! + \return Spline + \sa setSpline() +*/ +const QwtSpline &QwtSplineCurveFitter::spline() const +{ + return d_data->spline; +} + +/*! + \return Spline + \sa setSpline() +*/ +QwtSpline &QwtSplineCurveFitter::spline() +{ + return d_data->spline; +} + +/*! + Assign a spline size ( has to be at least 10 points ) + + \param splineSize Spline size + \sa splineSize() +*/ +void QwtSplineCurveFitter::setSplineSize( int splineSize ) +{ + d_data->splineSize = qMax( splineSize, 10 ); +} + +/*! + \return Spline size + \sa setSplineSize() +*/ +int QwtSplineCurveFitter::splineSize() const +{ + return d_data->splineSize; +} + +/*! + Find a curve which has the best fit to a series of data points + + \param points Series of data points + \return Curve points +*/ +QPolygonF QwtSplineCurveFitter::fitCurve( const QPolygonF &points ) const +{ + const int size = points.size(); + if ( size <= 2 ) + return points; + + FitMode fitMode = d_data->fitMode; + if ( fitMode == Auto ) + { + fitMode = Spline; + + const QPointF *p = points.data(); + for ( int i = 1; i < size; i++ ) + { + if ( p[i].x() <= p[i-1].x() ) + { + fitMode = ParametricSpline; + break; + } + }; + } + + if ( fitMode == ParametricSpline ) + return fitParametric( points ); + else + return fitSpline( points ); +} + +QPolygonF QwtSplineCurveFitter::fitSpline( const QPolygonF &points ) const +{ + d_data->spline.setPoints( points ); + if ( !d_data->spline.isValid() ) + return points; + + QPolygonF fittedPoints( d_data->splineSize ); + + const double x1 = points[0].x(); + const double x2 = points[int( points.size() - 1 )].x(); + const double dx = x2 - x1; + const double delta = dx / ( d_data->splineSize - 1 ); + + for ( int i = 0; i < d_data->splineSize; i++ ) + { + QPointF &p = fittedPoints[i]; + + const double v = x1 + i * delta; + const double sv = d_data->spline.value( v ); + + p.setX( v ); + p.setY( sv ); + } + d_data->spline.reset(); + + return fittedPoints; +} + +QPolygonF QwtSplineCurveFitter::fitParametric( const QPolygonF &points ) const +{ + int i; + const int size = points.size(); + + QPolygonF fittedPoints( d_data->splineSize ); + QPolygonF splinePointsX( size ); + QPolygonF splinePointsY( size ); + + const QPointF *p = points.data(); + QPointF *spX = splinePointsX.data(); + QPointF *spY = splinePointsY.data(); + + double param = 0.0; + for ( i = 0; i < size; i++ ) + { + const double x = p[i].x(); + const double y = p[i].y(); + if ( i > 0 ) + { + const double delta = qSqrt( qwtSqr( x - spX[i-1].y() ) + + qwtSqr( y - spY[i-1].y() ) ); + param += qMax( delta, 1.0 ); + } + spX[i].setX( param ); + spX[i].setY( x ); + spY[i].setX( param ); + spY[i].setY( y ); + } + + d_data->spline.setPoints( splinePointsX ); + if ( !d_data->spline.isValid() ) + return points; + + const double deltaX = + splinePointsX[size - 1].x() / ( d_data->splineSize - 1 ); + for ( i = 0; i < d_data->splineSize; i++ ) + { + const double dtmp = i * deltaX; + fittedPoints[i].setX( d_data->spline.value( dtmp ) ); + } + + d_data->spline.setPoints( splinePointsY ); + if ( !d_data->spline.isValid() ) + return points; + + const double deltaY = + splinePointsY[size - 1].x() / ( d_data->splineSize - 1 ); + for ( i = 0; i < d_data->splineSize; i++ ) + { + const double dtmp = i * deltaY; + fittedPoints[i].setY( d_data->spline.value( dtmp ) ); + } + + return fittedPoints; +} + +class QwtWeedingCurveFitter::PrivateData +{ +public: + PrivateData(): + tolerance( 1.0 ) + { + } + + double tolerance; +}; + +class QwtWeedingCurveFitter::Line +{ +public: + Line( int i1 = 0, int i2 = 0 ): + from( i1 ), + to( i2 ) + { + } + + int from; + int to; +}; + +/*! + Constructor + + \param tolerance Tolerance + \sa setTolerance(), tolerance() +*/ +QwtWeedingCurveFitter::QwtWeedingCurveFitter( double tolerance ) +{ + d_data = new PrivateData; + setTolerance( tolerance ); +} + +//! Destructor +QwtWeedingCurveFitter::~QwtWeedingCurveFitter() +{ + delete d_data; +} + +/*! + Assign the tolerance + + The tolerance is the maximum distance, that is accaptable + between the original curve and the smoothed curve. + + Increasing the tolerance will reduce the number of the + resulting points. + + \param tolerance Tolerance + + \sa tolerance() +*/ +void QwtWeedingCurveFitter::setTolerance( double tolerance ) +{ + d_data->tolerance = qMax( tolerance, 0.0 ); +} + +/*! + \return Tolerance + \sa setTolerance() +*/ +double QwtWeedingCurveFitter::tolerance() const +{ + return d_data->tolerance; +} + +/*! + \param points Series of data points + \return Curve points +*/ +QPolygonF QwtWeedingCurveFitter::fitCurve( const QPolygonF &points ) const +{ + QStack stack; + stack.reserve( 500 ); + + const QPointF *p = points.data(); + const int nPoints = points.size(); + + QVector usePoint( nPoints, false ); + + double distToSegment; + + stack.push( Line( 0, nPoints - 1 ) ); + + while ( !stack.isEmpty() ) + { + const Line r = stack.pop(); + + // initialize line segment + const double vecX = p[r.to].x() - p[r.from].x(); + const double vecY = p[r.to].y() - p[r.from].y(); + + const double vecLength = qSqrt( vecX * vecX + vecY * vecY ); + + const double unitVecX = ( vecLength != 0.0 ) ? vecX / vecLength : 0.0; + const double unitVecY = ( vecLength != 0.0 ) ? vecY / vecLength : 0.0; + + double maxDist = 0.0; + int nVertexIndexMaxDistance = r.from + 1; + for ( int i = r.from + 1; i < r.to; i++ ) + { + //compare to anchor + const double fromVecX = p[i].x() - p[r.from].x(); + const double fromVecY = p[i].y() - p[r.from].y(); + const double fromVecLength = + qSqrt( fromVecX * fromVecX + fromVecY * fromVecY ); + + if ( fromVecX * unitVecX + fromVecY * unitVecY < 0.0 ) + { + distToSegment = fromVecLength; + } + if ( fromVecX * unitVecX + fromVecY * unitVecY < 0.0 ) + { + distToSegment = fromVecLength; + } + else + { + const double toVecX = p[i].x() - p[r.to].x(); + const double toVecY = p[i].y() - p[r.to].y(); + const double toVecLength = qSqrt( toVecX * toVecX + toVecY * toVecY ); + const double s = toVecX * ( -unitVecX ) + toVecY * ( -unitVecY ); + if ( s < 0.0 ) + distToSegment = toVecLength; + else + { + distToSegment = qSqrt( qFabs( toVecLength * toVecLength - s * s ) ); + } + } + + if ( maxDist < distToSegment ) + { + maxDist = distToSegment; + nVertexIndexMaxDistance = i; + } + } + if ( maxDist <= d_data->tolerance ) + { + usePoint[r.from] = true; + usePoint[r.to] = true; + } + else + { + stack.push( Line( r.from, nVertexIndexMaxDistance ) ); + stack.push( Line( nVertexIndexMaxDistance, r.to ) ); + } + } + + int cnt = 0; + + QPolygonF stripped( nPoints ); + for ( int i = 0; i < nPoints; i++ ) + { + if ( usePoint[i] ) + stripped[cnt++] = p[i]; + } + stripped.resize( cnt ); + return stripped; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_curve_fitter.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_curve_fitter.h index b84ad2069..c9ae60373 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_curve_fitter.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_curve_fitter.h @@ -1,128 +1,128 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_CURVE_FITTER_H -#define QWT_CURVE_FITTER_H - -#include "qwt_global.h" -#include -#include - -class QwtSpline; - -/*! - \brief Abstract base class for a curve fitter -*/ -class QWT_EXPORT QwtCurveFitter -{ -public: - virtual ~QwtCurveFitter(); - - /*! - Find a curve which has the best fit to a series of data points - - \param polygon Series of data points - \return Curve points - */ - virtual QPolygonF fitCurve( const QPolygonF &polygon ) const = 0; - -protected: - QwtCurveFitter(); - -private: - QwtCurveFitter( const QwtCurveFitter & ); - QwtCurveFitter &operator=( const QwtCurveFitter & ); -}; - -/*! - \brief A curve fitter using cubic splines -*/ -class QWT_EXPORT QwtSplineCurveFitter: public QwtCurveFitter -{ -public: - /*! - Spline type - The default setting is Auto - \sa setFitMode(), FitMode() - */ - enum FitMode - { - /*! - Use the default spline algorithm for polygons with - increasing x values ( p[i-1] < p[i] ), otherwise use - a parametric spline algorithm. - */ - Auto, - - //! Use a default spline algorithm - Spline, - - //! Use a parametric spline algorithm - ParametricSpline - }; - - QwtSplineCurveFitter(); - virtual ~QwtSplineCurveFitter(); - - void setFitMode( FitMode ); - FitMode fitMode() const; - - void setSpline( const QwtSpline& ); - const QwtSpline &spline() const; - QwtSpline &spline(); - - void setSplineSize( int size ); - int splineSize() const; - - virtual QPolygonF fitCurve( const QPolygonF & ) const; - -private: - QPolygonF fitSpline( const QPolygonF & ) const; - QPolygonF fitParametric( const QPolygonF & ) const; - - class PrivateData; - PrivateData *d_data; -}; - -/*! - \brief A curve fitter implementing Douglas and Peucker algorithm - - The purpose of the Douglas and Peucker algorithm is that given a 'curve' - composed of line segments to find a curve not too dissimilar but that - has fewer points. The algorithm defines 'too dissimilar' based on the - maximum distance (tolerance) between the original curve and the - smoothed curve. - - The smoothed curve consists of a subset of the points that defined the - original curve. - - In opposite to QwtSplineCurveFitter the Douglas and Peucker algorithm reduces - the number of points. By adjusting the tolerance parameter according to the - axis scales QwtSplineCurveFitter can be used to implement different - level of details to speed up painting of curves of many points. -*/ -class QWT_EXPORT QwtWeedingCurveFitter: public QwtCurveFitter -{ -public: - QwtWeedingCurveFitter( double tolerance = 1.0 ); - virtual ~QwtWeedingCurveFitter(); - - void setTolerance( double ); - double tolerance() const; - - virtual QPolygonF fitCurve( const QPolygonF & ) const; - -private: - class Line; - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_CURVE_FITTER_H +#define QWT_CURVE_FITTER_H + +#include "qwt_global.h" +#include +#include + +class QwtSpline; + +/*! + \brief Abstract base class for a curve fitter +*/ +class QWT_EXPORT QwtCurveFitter +{ +public: + virtual ~QwtCurveFitter(); + + /*! + Find a curve which has the best fit to a series of data points + + \param polygon Series of data points + \return Curve points + */ + virtual QPolygonF fitCurve( const QPolygonF &polygon ) const = 0; + +protected: + QwtCurveFitter(); + +private: + QwtCurveFitter( const QwtCurveFitter & ); + QwtCurveFitter &operator=( const QwtCurveFitter & ); +}; + +/*! + \brief A curve fitter using cubic splines +*/ +class QWT_EXPORT QwtSplineCurveFitter: public QwtCurveFitter +{ +public: + /*! + Spline type + The default setting is Auto + \sa setFitMode(), FitMode() + */ + enum FitMode + { + /*! + Use the default spline algorithm for polygons with + increasing x values ( p[i-1] < p[i] ), otherwise use + a parametric spline algorithm. + */ + Auto, + + //! Use a default spline algorithm + Spline, + + //! Use a parametric spline algorithm + ParametricSpline + }; + + QwtSplineCurveFitter(); + virtual ~QwtSplineCurveFitter(); + + void setFitMode( FitMode ); + FitMode fitMode() const; + + void setSpline( const QwtSpline& ); + const QwtSpline &spline() const; + QwtSpline &spline(); + + void setSplineSize( int size ); + int splineSize() const; + + virtual QPolygonF fitCurve( const QPolygonF & ) const; + +private: + QPolygonF fitSpline( const QPolygonF & ) const; + QPolygonF fitParametric( const QPolygonF & ) const; + + class PrivateData; + PrivateData *d_data; +}; + +/*! + \brief A curve fitter implementing Douglas and Peucker algorithm + + The purpose of the Douglas and Peucker algorithm is that given a 'curve' + composed of line segments to find a curve not too dissimilar but that + has fewer points. The algorithm defines 'too dissimilar' based on the + maximum distance (tolerance) between the original curve and the + smoothed curve. + + The smoothed curve consists of a subset of the points that defined the + original curve. + + In opposite to QwtSplineCurveFitter the Douglas and Peucker algorithm reduces + the number of points. By adjusting the tolerance parameter according to the + axis scales QwtSplineCurveFitter can be used to implement different + level of details to speed up painting of curves of many points. +*/ +class QWT_EXPORT QwtWeedingCurveFitter: public QwtCurveFitter +{ +public: + QwtWeedingCurveFitter( double tolerance = 1.0 ); + virtual ~QwtWeedingCurveFitter(); + + void setTolerance( double ); + double tolerance() const; + + virtual QPolygonF fitCurve( const QPolygonF & ) const; + +private: + class Line; + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_dial.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_dial.cpp index f7e00a1e9..7aa9ddcfa 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_dial.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_dial.cpp @@ -1,1155 +1,1155 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_dial.h" -#include "qwt_dial_needle.h" -#include "qwt_math.h" -#include "qwt_scale_engine.h" -#include "qwt_scale_map.h" -#include "qwt_painter.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#if QT_VERSION < 0x040601 -#define qAtan(x) ::atan(x) -#endif - -class QwtDial::PrivateData -{ -public: - PrivateData(): - frameShadow( Sunken ), - lineWidth( 0 ), - mode( RotateNeedle ), - direction( Clockwise ), - origin( 90.0 ), - minScaleArc( 0.0 ), - maxScaleArc( 0.0 ), - scaleDraw( 0 ), - maxMajIntv( 36 ), - maxMinIntv( 10 ), - scaleStep( 0.0 ), - needle( 0 ) - { - } - - ~PrivateData() - { - delete scaleDraw; - delete needle; - } - Shadow frameShadow; - int lineWidth; - - QwtDial::Mode mode; - QwtDial::Direction direction; - - double origin; - double minScaleArc; - double maxScaleArc; - - QwtDialScaleDraw *scaleDraw; - int maxMajIntv; - int maxMinIntv; - double scaleStep; - - QwtDialNeedle *needle; - - static double previousDir; -}; - -double QwtDial::PrivateData::previousDir = -1.0; - -/*! - Constructor - - \param parent Parent dial widget -*/ -QwtDialScaleDraw::QwtDialScaleDraw( QwtDial *parent ): - d_parent( parent ), - d_penWidth( 1.0 ) -{ -} - -/*! - Set the pen width used for painting the scale - - \param penWidth Pen width - \sa penWidth(), QwtDial::drawScale() -*/ - -void QwtDialScaleDraw::setPenWidth( double penWidth ) -{ - d_penWidth = qMax( penWidth, 0.0 ); -} - -/*! - \return Pen width used for painting the scale - \sa setPenWidth, QwtDial::drawScale() -*/ -double QwtDialScaleDraw::penWidth() const -{ - return d_penWidth; -} - -/*! - Call QwtDial::scaleLabel of the parent dial widget. - - \param value Value to display - - \sa QwtDial::scaleLabel() -*/ -QwtText QwtDialScaleDraw::label( double value ) const -{ - if ( d_parent == NULL ) - return QwtRoundScaleDraw::label( value ); - - return d_parent->scaleLabel( value ); -} - -/*! - \brief Constructor - \param parent Parent widget - - Create a dial widget with no scale and no needle. - The default origin is 90.0 with no valid value. It accepts - mouse and keyboard inputs and has no step size. The default mode - is QwtDial::RotateNeedle. -*/ -QwtDial::QwtDial( QWidget* parent ): - QwtAbstractSlider( Qt::Horizontal, parent ) -{ - initDial(); -} - -void QwtDial::initDial() -{ - d_data = new PrivateData; - - setFocusPolicy( Qt::TabFocus ); - - QPalette p = palette(); - for ( int i = 0; i < QPalette::NColorGroups; i++ ) - { - const QPalette::ColorGroup cg = ( QPalette::ColorGroup )i; - - // Base: background color of the circle inside the frame. - // WindowText: background color of the circle inside the scale - - p.setColor( cg, QPalette::WindowText, - p.color( cg, QPalette::Base ) ); - } - setPalette( p ); - - d_data->scaleDraw = new QwtDialScaleDraw( this ); - d_data->scaleDraw->setRadius( 0 ); - - setScaleArc( 0.0, 360.0 ); // scale as a full circle - setRange( 0.0, 360.0, 1.0, 10 ); // degrees as deafult -} - -//! Destructor -QwtDial::~QwtDial() -{ - delete d_data; -} - -/*! - Sets the frame shadow value from the frame style. - \param shadow Frame shadow - \sa setLineWidth(), QFrame::setFrameShadow() -*/ -void QwtDial::setFrameShadow( Shadow shadow ) -{ - if ( shadow != d_data->frameShadow ) - { - d_data->frameShadow = shadow; - if ( lineWidth() > 0 ) - update(); - } -} - -/*! - \return Frame shadow - /sa setFrameShadow(), lineWidth(), QFrame::frameShadow -*/ -QwtDial::Shadow QwtDial::frameShadow() const -{ - return d_data->frameShadow; -} - -/*! - Sets the line width - - \param lineWidth Line width - \sa setFrameShadow() -*/ -void QwtDial::setLineWidth( int lineWidth ) -{ - if ( lineWidth < 0 ) - lineWidth = 0; - - if ( d_data->lineWidth != lineWidth ) - { - d_data->lineWidth = lineWidth; - update(); - } -} - -/*! - \return Line width of the frame - \sa setLineWidth(), frameShadow(), lineWidth() -*/ -int QwtDial::lineWidth() const -{ - return d_data->lineWidth; -} - -/*! - \return bounding rect of the circle inside the frame - \sa setLineWidth(), scaleInnerRect(), boundingRect() -*/ -QRectF QwtDial::innerRect() const -{ - const double lw = lineWidth(); - return boundingRect().adjusted( lw, lw, -lw, -lw ); -} - -/*! - \return bounding rect of the dial including the frame - \sa setLineWidth(), scaleInnerRect(), innerRect() -*/ -QRectF QwtDial::boundingRect() const -{ - const QRectF cr = contentsRect(); - - const double dim = qMin( cr.width(), cr.height() ); - - QRectF inner( 0, 0, dim, dim ); - inner.moveCenter( cr.center() ); - - return inner; -} - -/*! - \return rect inside the scale - \sa setLineWidth(), boundingRect(), innerRect() -*/ -QRectF QwtDial::scaleInnerRect() const -{ - QRectF rect = innerRect(); - - if ( d_data->scaleDraw ) - { - double scaleDist = qCeil( d_data->scaleDraw->extent( font() ) ); - scaleDist++; // margin - - rect.adjust( scaleDist, scaleDist, -scaleDist, -scaleDist ); - } - - return rect; -} - -/*! - \brief Change the mode of the meter. - \param mode New mode - - The value of the meter is indicated by the difference - between north of the scale and the direction of the needle. - In case of QwtDial::RotateNeedle north is pointing - to the origin() and the needle is rotating, in case of - QwtDial::RotateScale, the needle points to origin() - and the scale is rotating. - - The default mode is QwtDial::RotateNeedle. - - \sa mode(), setValue(), setOrigin() -*/ -void QwtDial::setMode( Mode mode ) -{ - if ( mode != d_data->mode ) - { - d_data->mode = mode; - update(); - } -} - -/*! - \return mode of the dial. - - The value of the dial is indicated by the difference - between the origin and the direction of the needle. - In case of QwtDial::RotateNeedle the scale arc is fixed - to the origin() and the needle is rotating, in case of - QwtDial::RotateScale, the needle points to origin() - and the scale is rotating. - - The default mode is QwtDial::RotateNeedle. - - \sa setMode(), origin(), setScaleArc(), value() -*/ -QwtDial::Mode QwtDial::mode() const -{ - return d_data->mode; -} - -/*! - Sets whether it is possible to step the value from the highest value to - the lowest value and vice versa to on. - - \param wrapping en/disables wrapping - - \sa wrapping(), QwtDoubleRange::periodic() - \note The meaning of wrapping is like the wrapping property of QSpinBox, - but not like it is used in QDial. -*/ -void QwtDial::setWrapping( bool wrapping ) -{ - setPeriodic( wrapping ); -} - -/*! - wrapping() holds whether it is possible to step the value from the - highest value to the lowest value and vice versa. - - \sa setWrapping(), QwtDoubleRange::setPeriodic() - \note The meaning of wrapping is like the wrapping property of QSpinBox, - but not like it is used in QDial. -*/ -bool QwtDial::wrapping() const -{ - return periodic(); -} - -/*! - Set the direction of the dial (clockwise/counterclockwise) - - \param direction Direction - \sa direction() -*/ -void QwtDial::setDirection( Direction direction ) -{ - if ( direction != d_data->direction ) - { - d_data->direction = direction; - update(); - } -} - -/*! - \return Direction of the dial - - The default direction of a dial is QwtDial::Clockwise - - \sa setDirection() -*/ -QwtDial::Direction QwtDial::direction() const -{ - return d_data->direction; -} - -/*! - Paint the dial - \param event Paint event -*/ -void QwtDial::paintEvent( QPaintEvent *event ) -{ - QPainter painter( this ); - painter.setClipRegion( event->region() ); - - QStyleOption opt; - opt.init(this); - style()->drawPrimitive(QStyle::PE_Widget, &opt, &painter, this); - - painter.setRenderHint( QPainter::Antialiasing, true ); - - painter.save(); - drawContents( &painter ); - painter.restore(); - - painter.save(); - drawFrame( &painter ); - painter.restore(); - - if ( hasFocus() ) - drawFocusIndicator( &painter ); -} - -/*! - Draw a dotted round circle, if !isReadOnly() - - \param painter Painter -*/ -void QwtDial::drawFocusIndicator( QPainter *painter ) const -{ - if ( !isReadOnly() ) - { - QRectF focusRect = innerRect(); - - const int margin = 2; - focusRect.adjust( margin, margin, -margin, -margin ); - - QColor color = palette().color( QPalette::Base ); - if ( color.isValid() ) - { - const QColor gray( Qt::gray ); - - int h, s, v; - color.getHsv( &h, &s, &v ); - color = ( v > 128 ) ? gray.dark( 120 ) : gray.light( 120 ); - } - else - color = Qt::darkGray; - - painter->save(); - painter->setBrush( Qt::NoBrush ); - painter->setPen( QPen( color, 0, Qt::DotLine ) ); - painter->drawEllipse( focusRect ); - painter->restore(); - } -} - -/*! - Draw the frame around the dial - - \param painter Painter - \sa lineWidth(), frameShadow() -*/ -void QwtDial::drawFrame( QPainter *painter ) -{ - if ( lineWidth() <= 0 ) - return; - - const double lw2 = 0.5 * lineWidth(); - - QRectF r = boundingRect(); - r.adjust( lw2, lw2, -lw2, -lw2 ); - - QPen pen; - - switch ( d_data->frameShadow ) - { - case QwtDial::Raised: - case QwtDial::Sunken: - { - QColor c1 = palette().color( QPalette::Light ); - QColor c2 = palette().color( QPalette::Dark ); - - if ( d_data->frameShadow == QwtDial::Sunken ) - qSwap( c1, c2 ); - - QLinearGradient gradient( r.topLeft(), r.bottomRight() ); - gradient.setColorAt( 0.0, c1 ); -#if 0 - gradient.setColorAt( 0.3, c1 ); - gradient.setColorAt( 0.7, c2 ); -#endif - gradient.setColorAt( 1.0, c2 ); - - pen = QPen( gradient, lineWidth() ); - break; - } - default: // Plain - { - pen = QPen( palette().brush( QPalette::Dark ), lineWidth() ); - } - } - - painter->save(); - - painter->setPen( pen ); - painter->setBrush( Qt::NoBrush ); - painter->drawEllipse( r ); - - painter->restore(); -} - -/*! - \brief Draw the contents inside the frame - - QPalette::Window is the background color outside of the frame. - QPalette::Base is the background color inside the frame. - QPalette::WindowText is the background color inside the scale. - - \param painter Painter - \sa boundingRect(), innerRect(), - scaleInnerRect(), QWidget::setPalette() -*/ -void QwtDial::drawContents( QPainter *painter ) const -{ - if ( testAttribute( Qt::WA_NoSystemBackground ) || - palette().brush( QPalette::Base ) != - palette().brush( QPalette::Window ) ) - { - const QRectF br = boundingRect(); - - painter->save(); - painter->setPen( Qt::NoPen ); - painter->setBrush( palette().brush( QPalette::Base ) ); - painter->drawEllipse( br ); - painter->restore(); - } - - - const QRectF insideScaleRect = scaleInnerRect(); - if ( palette().brush( QPalette::WindowText ) != - palette().brush( QPalette::Base ) ) - { - painter->save(); - painter->setPen( Qt::NoPen ); - painter->setBrush( palette().brush( QPalette::WindowText ) ); - painter->drawEllipse( insideScaleRect ); - painter->restore(); - } - - const QPointF center = insideScaleRect.center(); - const double radius = 0.5 * insideScaleRect.width(); - - double direction = d_data->origin; - - if ( isValid() ) - { - direction = d_data->minScaleArc; - if ( maxValue() > minValue() && - d_data->maxScaleArc > d_data->minScaleArc ) - { - const double ratio = - ( value() - minValue() ) / ( maxValue() - minValue() ); - direction += ratio * ( d_data->maxScaleArc - d_data->minScaleArc ); - } - - if ( d_data->direction == QwtDial::CounterClockwise ) - direction = d_data->maxScaleArc - ( direction - d_data->minScaleArc ); - - direction += d_data->origin; - if ( direction >= 360.0 ) - direction -= 360.0; - else if ( direction < 0.0 ) - direction += 360.0; - } - - double origin = d_data->origin; - if ( mode() == RotateScale ) - { - origin -= direction - d_data->origin; - direction = d_data->origin; - } - - painter->save(); - drawScale( painter, center, radius, origin, - d_data->minScaleArc, d_data->maxScaleArc ); - painter->restore(); - - painter->save(); - drawScaleContents( painter, center, radius ); - painter->restore(); - - if ( isValid() ) - { - QPalette::ColorGroup cg; - if ( isEnabled() ) - cg = hasFocus() ? QPalette::Active : QPalette::Inactive; - else - cg = QPalette::Disabled; - - painter->save(); - drawNeedle( painter, center, radius, direction, cg ); - painter->restore(); - } -} - -/*! - Draw the needle - - \param painter Painter - \param center Center of the dial - \param radius Length for the needle - \param direction Direction of the needle in degrees, counter clockwise - \param cg ColorGroup -*/ -void QwtDial::drawNeedle( QPainter *painter, const QPointF ¢er, - double radius, double direction, QPalette::ColorGroup cg ) const -{ - if ( d_data->needle ) - { - direction = 360.0 - direction; // counter clockwise - d_data->needle->draw( painter, center, radius, direction, cg ); - } -} - -/*! - Draw the scale - - \param painter Painter - \param center Center of the dial - \param radius Radius of the scale - \param origin Origin of the scale - \param minArc Minimum of the arc - \param maxArc Minimum of the arc - - \sa QwtRoundScaleDraw::setAngleRange() -*/ -void QwtDial::drawScale( QPainter *painter, const QPointF ¢er, - double radius, double origin, double minArc, double maxArc ) const -{ - if ( d_data->scaleDraw == NULL ) - return; - - origin -= 270.0; // hardcoded origin of QwtScaleDraw - - double angle = maxArc - minArc; - if ( angle > 360.0 ) - angle = ::fmod( angle, 360.0 ); - - minArc += origin; - if ( minArc < -360.0 ) - minArc = ::fmod( minArc, 360.0 ); - - maxArc = minArc + angle; - if ( maxArc > 360.0 ) - { - // QwtRoundScaleDraw::setAngleRange accepts only values - // in the range [-360.0..360.0] - minArc -= 360.0; - maxArc -= 360.0; - } - - if ( d_data->direction == QwtDial::CounterClockwise ) - qSwap( minArc, maxArc ); - - painter->setFont( font() ); - - d_data->scaleDraw->setAngleRange( minArc, maxArc ); - d_data->scaleDraw->setRadius( radius ); - d_data->scaleDraw->moveCenter( center ); - - QPalette pal = palette(); - - const QColor textColor = pal.color( QPalette::Text ); - pal.setColor( QPalette::WindowText, textColor ); //ticks, backbone - - painter->setPen( QPen( textColor, d_data->scaleDraw->penWidth() ) ); - - painter->setBrush( Qt::red ); - d_data->scaleDraw->draw( painter, pal ); -} - -/*! - Draw the contents inside the scale - - Paints nothing. - - \param painter Painter - \param center Center of the contents circle - \param radius Radius of the contents circle -*/ - -void QwtDial::drawScaleContents( QPainter *painter, - const QPointF ¢er, double radius ) const -{ - Q_UNUSED(painter); - Q_UNUSED(center); - Q_UNUSED(radius); -} - -/*! - Set a needle for the dial - - Qwt is missing a set of good looking needles. - Contributions are very welcome. - - \param needle Needle - \warning The needle will be deleted, when a different needle is - set or in ~QwtDial() -*/ -void QwtDial::setNeedle( QwtDialNeedle *needle ) -{ - if ( needle != d_data->needle ) - { - if ( d_data->needle ) - delete d_data->needle; - - d_data->needle = needle; - update(); - } -} - -/*! - \return needle - \sa setNeedle() -*/ -const QwtDialNeedle *QwtDial::needle() const -{ - return d_data->needle; -} - -/*! - \return needle - \sa setNeedle() -*/ -QwtDialNeedle *QwtDial::needle() -{ - return d_data->needle; -} - -//! QwtDoubleRange update hook -void QwtDial::rangeChange() -{ - updateScale(); -} - -/*! - Update the scale with the current attributes - \sa setScale() -*/ -void QwtDial::updateScale() -{ - if ( d_data->scaleDraw ) - { - QwtLinearScaleEngine scaleEngine; - - const QwtScaleDiv scaleDiv = scaleEngine.divideScale( - minValue(), maxValue(), - d_data->maxMajIntv, d_data->maxMinIntv, d_data->scaleStep ); - - d_data->scaleDraw->setTransformation( scaleEngine.transformation() ); - d_data->scaleDraw->setScaleDiv( scaleDiv ); - } -} - -//! Return the scale draw -QwtDialScaleDraw *QwtDial::scaleDraw() -{ - return d_data->scaleDraw; -} - -//! Return the scale draw -const QwtDialScaleDraw *QwtDial::scaleDraw() const -{ - return d_data->scaleDraw; -} - -/*! - Set an individual scale draw - - \param scaleDraw Scale draw - \warning The previous scale draw is deleted -*/ -void QwtDial::setScaleDraw( QwtDialScaleDraw *scaleDraw ) -{ - if ( scaleDraw != d_data->scaleDraw ) - { - if ( d_data->scaleDraw ) - delete d_data->scaleDraw; - - d_data->scaleDraw = scaleDraw; - updateScale(); - update(); - } -} - -/*! - Change the intervals of the scale - - \param maxMajIntv Maximum for the number of major steps - \param maxMinIntv Maximum number of minor steps - \param step Step size - - \sa QwtScaleEngine::divideScale() -*/ -void QwtDial::setScale( int maxMajIntv, int maxMinIntv, double step ) -{ - d_data->maxMajIntv = maxMajIntv; - d_data->maxMinIntv = maxMinIntv; - d_data->scaleStep = step; - - updateScale(); -} - -/*! - A wrapper method for accessing the scale draw. - - \param components Scale components - \sa QwtAbstractScaleDraw::enableComponent() -*/ -void QwtDial::setScaleComponents( - QwtAbstractScaleDraw::ScaleComponents components ) -{ - if ( components == 0 ) - setScaleDraw( NULL ); - - QwtDialScaleDraw *sd = d_data->scaleDraw; - if ( sd == NULL ) - return; - - sd->enableComponent( QwtAbstractScaleDraw::Backbone, - components & QwtAbstractScaleDraw::Backbone ); - - sd->enableComponent( QwtAbstractScaleDraw::Ticks, - components & QwtAbstractScaleDraw::Ticks ); - - sd->enableComponent( QwtAbstractScaleDraw::Labels, - components & QwtAbstractScaleDraw::Labels ); -} - -/*! - Assign length and width of the ticks - - \param minLen Length of the minor ticks - \param medLen Length of the medium ticks - \param majLen Length of the major ticks - \param penWidth Width of the pen for all ticks - - \sa QwtAbstractScaleDraw::setTickLength(), QwtDialScaleDraw::setPenWidth() -*/ -void QwtDial::setScaleTicks( int minLen, int medLen, - int majLen, int penWidth ) -{ - QwtDialScaleDraw *sd = d_data->scaleDraw; - if ( sd ) - { - sd->setTickLength( QwtScaleDiv::MinorTick, minLen ); - sd->setTickLength( QwtScaleDiv::MediumTick, medLen ); - sd->setTickLength( QwtScaleDiv::MajorTick, majLen ); - sd->setPenWidth( penWidth ); - } -} - -/*! - Find the label for a value - - \param value Value - \return label -*/ -QwtText QwtDial::scaleLabel( double value ) const -{ -#if 1 - if ( value == -0 ) - value = 0; -#endif - - return QString::number( value ); -} - -//! \return Lower limit of the scale arc -double QwtDial::minScaleArc() const -{ - return d_data->minScaleArc; -} - -//! \return Upper limit of the scale arc -double QwtDial::maxScaleArc() const -{ - return d_data->maxScaleArc; -} - -/*! - \brief Change the origin - - The origin is the angle where scale and needle is relative to. - - \param origin New origin - \sa origin() -*/ -void QwtDial::setOrigin( double origin ) -{ - d_data->origin = origin; - update(); -} - -/*! - The origin is the angle where scale and needle is relative to. - - \return Origin of the dial - \sa setOrigin() -*/ -double QwtDial::origin() const -{ - return d_data->origin; -} - -/*! - Change the arc of the scale - - \param minArc Lower limit - \param maxArc Upper limit -*/ -void QwtDial::setScaleArc( double minArc, double maxArc ) -{ - if ( minArc != 360.0 && minArc != -360.0 ) - minArc = ::fmod( minArc, 360.0 ); - if ( maxArc != 360.0 && maxArc != -360.0 ) - maxArc = ::fmod( maxArc, 360.0 ); - - d_data->minScaleArc = qMin( minArc, maxArc ); - d_data->maxScaleArc = qMax( minArc, maxArc ); - if ( d_data->maxScaleArc - d_data->minScaleArc > 360.0 ) - d_data->maxScaleArc = d_data->minScaleArc + 360.0; - - update(); -} - -//! QwtDoubleRange update hook -void QwtDial::valueChange() -{ - update(); - QwtAbstractSlider::valueChange(); -} - -/*! - \return Size hint -*/ -QSize QwtDial::sizeHint() const -{ - int sh = 0; - if ( d_data->scaleDraw ) - sh = qCeil( d_data->scaleDraw->extent( font() ) ); - - const int d = 6 * sh + 2 * lineWidth(); - - QSize hint( d, d ); - if ( !isReadOnly() ) - hint = hint.expandedTo( QApplication::globalStrut() ); - - return hint; -} - -/*! - \brief Return a minimum size hint - \warning The return value of QwtDial::minimumSizeHint() depends on the - font and the scale. -*/ -QSize QwtDial::minimumSizeHint() const -{ - int sh = 0; - if ( d_data->scaleDraw ) - sh = qCeil( d_data->scaleDraw->extent( font() ) ); - - const int d = 3 * sh + 2 * lineWidth(); - - return QSize( d, d ); -} - -static double line2Radians( const QPointF &p1, const QPointF &p2 ) -{ - const QPointF p = p2 - p1; - - double angle; - if ( p.x() == 0 ) - angle = ( p.y() <= 0.0 ) ? M_PI_2 : 3 * M_PI_2; - else - { - angle = qAtan( double( -p.y() ) / double( p.x() ) ); - if ( p.x() < 0.0 ) - angle += M_PI; - if ( angle < 0.0 ) - angle += 2 * M_PI; - } - return 360.0 - angle * 180.0 / M_PI; -} - -/*! - Find the value for a given position - - \param pos Position - \return Value -*/ -double QwtDial::getValue( const QPoint &pos ) -{ - if ( d_data->maxScaleArc == d_data->minScaleArc || maxValue() == minValue() ) - return minValue(); - - double dir = line2Radians( innerRect().center(), pos ) - d_data->origin; - if ( dir < 0.0 ) - dir += 360.0; - - if ( mode() == RotateScale ) - dir = 360.0 - dir; - - // The position might be in the area that is outside the scale arc. - // We need the range of the scale if it was a complete circle. - - const double completeCircle = 360.0 / ( d_data->maxScaleArc - d_data->minScaleArc ) - * ( maxValue() - minValue() ); - - double posValue = minValue() + completeCircle * dir / 360.0; - - if ( scrollMode() == ScrMouse ) - { - if ( d_data->previousDir >= 0.0 ) // valid direction - { - // We have to find out whether the mouse is moving - // clock or counter clockwise - - bool clockWise = false; - - const double angle = dir - d_data->previousDir; - if ( ( angle >= 0.0 && angle <= 180.0 ) || angle < -180.0 ) - clockWise = true; - - if ( clockWise ) - { - if ( dir < d_data->previousDir && mouseOffset() > 0.0 ) - { - // We passed 360 -> 0 - setMouseOffset( mouseOffset() - completeCircle ); - } - - if ( wrapping() ) - { - if ( posValue - mouseOffset() > maxValue() ) - { - // We passed maxValue and the value will be set - // to minValue. We have to adjust the mouseOffset. - - setMouseOffset( posValue - minValue() ); - } - } - else - { - if ( posValue - mouseOffset() > maxValue() || - value() == maxValue() ) - { - // We fix the value at maxValue by adjusting - // the mouse offset. - - setMouseOffset( posValue - maxValue() ); - } - } - } - else - { - if ( dir > d_data->previousDir && mouseOffset() < 0.0 ) - { - // We passed 0 -> 360 - setMouseOffset( mouseOffset() + completeCircle ); - } - - if ( wrapping() ) - { - if ( posValue - mouseOffset() < minValue() ) - { - // We passed minValue and the value will be set - // to maxValue. We have to adjust the mouseOffset. - - setMouseOffset( posValue - maxValue() ); - } - } - else - { - if ( posValue - mouseOffset() < minValue() || - value() == minValue() ) - { - // We fix the value at minValue by adjusting - // the mouse offset. - - setMouseOffset( posValue - minValue() ); - } - } - } - } - d_data->previousDir = dir; - } - - return posValue; -} - -/*! - See QwtAbstractSlider::getScrollMode() - - \param pos point where the mouse was pressed - \retval scrollMode The scrolling mode - \retval direction direction: 1, 0, or -1. - - \sa QwtAbstractSlider::getScrollMode() -*/ -void QwtDial::getScrollMode( const QPoint &pos, - QwtAbstractSlider::ScrollMode &scrollMode, int &direction ) const -{ - direction = 0; - scrollMode = QwtAbstractSlider::ScrNone; - - const QRegion region( innerRect().toRect(), QRegion::Ellipse ); - if ( region.contains( pos ) && pos != innerRect().center() ) - { - scrollMode = QwtAbstractSlider::ScrMouse; - d_data->previousDir = -1.0; - } -} - -/*! - Handles key events - - - Key_Down, KeyLeft\n - Decrement by 1 - - Key_Prior\n - Decrement by pageSize() - - Key_Home\n - Set the value to minValue() - - - Key_Up, KeyRight\n - Increment by 1 - - Key_Next\n - Increment by pageSize() - - Key_End\n - Set the value to maxValue() - - \param event Key event - \sa isReadOnly() -*/ -void QwtDial::keyPressEvent( QKeyEvent *event ) -{ - if ( isReadOnly() ) - { - event->ignore(); - return; - } - - if ( !isValid() ) - return; - - double previous = prevValue(); - switch ( event->key() ) - { - case Qt::Key_Down: - case Qt::Key_Left: - QwtDoubleRange::incValue( -1 ); - break; - case Qt::Key_PageUp: - QwtDoubleRange::incValue( -pageSize() ); - break; - case Qt::Key_Home: - setValue( minValue() ); - break; - - case Qt::Key_Up: - case Qt::Key_Right: - QwtDoubleRange::incValue( 1 ); - break; - case Qt::Key_PageDown: - QwtDoubleRange::incValue( pageSize() ); - break; - case Qt::Key_End: - setValue( maxValue() ); - break; - default:; - event->ignore(); - } - - if ( value() != previous ) - Q_EMIT sliderMoved( value() ); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_dial.h" +#include "qwt_dial_needle.h" +#include "qwt_math.h" +#include "qwt_scale_engine.h" +#include "qwt_scale_map.h" +#include "qwt_painter.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if QT_VERSION < 0x040601 +#define qAtan(x) ::atan(x) +#endif + +class QwtDial::PrivateData +{ +public: + PrivateData(): + frameShadow( Sunken ), + lineWidth( 0 ), + mode( RotateNeedle ), + direction( Clockwise ), + origin( 90.0 ), + minScaleArc( 0.0 ), + maxScaleArc( 0.0 ), + scaleDraw( 0 ), + maxMajIntv( 36 ), + maxMinIntv( 10 ), + scaleStep( 0.0 ), + needle( 0 ) + { + } + + ~PrivateData() + { + delete scaleDraw; + delete needle; + } + Shadow frameShadow; + int lineWidth; + + QwtDial::Mode mode; + QwtDial::Direction direction; + + double origin; + double minScaleArc; + double maxScaleArc; + + QwtDialScaleDraw *scaleDraw; + int maxMajIntv; + int maxMinIntv; + double scaleStep; + + QwtDialNeedle *needle; + + static double previousDir; +}; + +double QwtDial::PrivateData::previousDir = -1.0; + +/*! + Constructor + + \param parent Parent dial widget +*/ +QwtDialScaleDraw::QwtDialScaleDraw( QwtDial *parent ): + d_parent( parent ), + d_penWidth( 1.0 ) +{ +} + +/*! + Set the pen width used for painting the scale + + \param penWidth Pen width + \sa penWidth(), QwtDial::drawScale() +*/ + +void QwtDialScaleDraw::setPenWidth( double penWidth ) +{ + d_penWidth = qMax( penWidth, 0.0 ); +} + +/*! + \return Pen width used for painting the scale + \sa setPenWidth, QwtDial::drawScale() +*/ +double QwtDialScaleDraw::penWidth() const +{ + return d_penWidth; +} + +/*! + Call QwtDial::scaleLabel of the parent dial widget. + + \param value Value to display + + \sa QwtDial::scaleLabel() +*/ +QwtText QwtDialScaleDraw::label( double value ) const +{ + if ( d_parent == NULL ) + return QwtRoundScaleDraw::label( value ); + + return d_parent->scaleLabel( value ); +} + +/*! + \brief Constructor + \param parent Parent widget + + Create a dial widget with no scale and no needle. + The default origin is 90.0 with no valid value. It accepts + mouse and keyboard inputs and has no step size. The default mode + is QwtDial::RotateNeedle. +*/ +QwtDial::QwtDial( QWidget* parent ): + QwtAbstractSlider( Qt::Horizontal, parent ) +{ + initDial(); +} + +void QwtDial::initDial() +{ + d_data = new PrivateData; + + setFocusPolicy( Qt::TabFocus ); + + QPalette p = palette(); + for ( int i = 0; i < QPalette::NColorGroups; i++ ) + { + const QPalette::ColorGroup cg = ( QPalette::ColorGroup )i; + + // Base: background color of the circle inside the frame. + // WindowText: background color of the circle inside the scale + + p.setColor( cg, QPalette::WindowText, + p.color( cg, QPalette::Base ) ); + } + setPalette( p ); + + d_data->scaleDraw = new QwtDialScaleDraw( this ); + d_data->scaleDraw->setRadius( 0 ); + + setScaleArc( 0.0, 360.0 ); // scale as a full circle + setRange( 0.0, 360.0, 1.0, 10 ); // degrees as deafult +} + +//! Destructor +QwtDial::~QwtDial() +{ + delete d_data; +} + +/*! + Sets the frame shadow value from the frame style. + \param shadow Frame shadow + \sa setLineWidth(), QFrame::setFrameShadow() +*/ +void QwtDial::setFrameShadow( Shadow shadow ) +{ + if ( shadow != d_data->frameShadow ) + { + d_data->frameShadow = shadow; + if ( lineWidth() > 0 ) + update(); + } +} + +/*! + \return Frame shadow + /sa setFrameShadow(), lineWidth(), QFrame::frameShadow +*/ +QwtDial::Shadow QwtDial::frameShadow() const +{ + return d_data->frameShadow; +} + +/*! + Sets the line width + + \param lineWidth Line width + \sa setFrameShadow() +*/ +void QwtDial::setLineWidth( int lineWidth ) +{ + if ( lineWidth < 0 ) + lineWidth = 0; + + if ( d_data->lineWidth != lineWidth ) + { + d_data->lineWidth = lineWidth; + update(); + } +} + +/*! + \return Line width of the frame + \sa setLineWidth(), frameShadow(), lineWidth() +*/ +int QwtDial::lineWidth() const +{ + return d_data->lineWidth; +} + +/*! + \return bounding rect of the circle inside the frame + \sa setLineWidth(), scaleInnerRect(), boundingRect() +*/ +QRectF QwtDial::innerRect() const +{ + const double lw = lineWidth(); + return boundingRect().adjusted( lw, lw, -lw, -lw ); +} + +/*! + \return bounding rect of the dial including the frame + \sa setLineWidth(), scaleInnerRect(), innerRect() +*/ +QRectF QwtDial::boundingRect() const +{ + const QRectF cr = contentsRect(); + + const double dim = qMin( cr.width(), cr.height() ); + + QRectF inner( 0, 0, dim, dim ); + inner.moveCenter( cr.center() ); + + return inner; +} + +/*! + \return rect inside the scale + \sa setLineWidth(), boundingRect(), innerRect() +*/ +QRectF QwtDial::scaleInnerRect() const +{ + QRectF rect = innerRect(); + + if ( d_data->scaleDraw ) + { + double scaleDist = qCeil( d_data->scaleDraw->extent( font() ) ); + scaleDist++; // margin + + rect.adjust( scaleDist, scaleDist, -scaleDist, -scaleDist ); + } + + return rect; +} + +/*! + \brief Change the mode of the meter. + \param mode New mode + + The value of the meter is indicated by the difference + between north of the scale and the direction of the needle. + In case of QwtDial::RotateNeedle north is pointing + to the origin() and the needle is rotating, in case of + QwtDial::RotateScale, the needle points to origin() + and the scale is rotating. + + The default mode is QwtDial::RotateNeedle. + + \sa mode(), setValue(), setOrigin() +*/ +void QwtDial::setMode( Mode mode ) +{ + if ( mode != d_data->mode ) + { + d_data->mode = mode; + update(); + } +} + +/*! + \return mode of the dial. + + The value of the dial is indicated by the difference + between the origin and the direction of the needle. + In case of QwtDial::RotateNeedle the scale arc is fixed + to the origin() and the needle is rotating, in case of + QwtDial::RotateScale, the needle points to origin() + and the scale is rotating. + + The default mode is QwtDial::RotateNeedle. + + \sa setMode(), origin(), setScaleArc(), value() +*/ +QwtDial::Mode QwtDial::mode() const +{ + return d_data->mode; +} + +/*! + Sets whether it is possible to step the value from the highest value to + the lowest value and vice versa to on. + + \param wrapping en/disables wrapping + + \sa wrapping(), QwtDoubleRange::periodic() + \note The meaning of wrapping is like the wrapping property of QSpinBox, + but not like it is used in QDial. +*/ +void QwtDial::setWrapping( bool wrapping ) +{ + setPeriodic( wrapping ); +} + +/*! + wrapping() holds whether it is possible to step the value from the + highest value to the lowest value and vice versa. + + \sa setWrapping(), QwtDoubleRange::setPeriodic() + \note The meaning of wrapping is like the wrapping property of QSpinBox, + but not like it is used in QDial. +*/ +bool QwtDial::wrapping() const +{ + return periodic(); +} + +/*! + Set the direction of the dial (clockwise/counterclockwise) + + \param direction Direction + \sa direction() +*/ +void QwtDial::setDirection( Direction direction ) +{ + if ( direction != d_data->direction ) + { + d_data->direction = direction; + update(); + } +} + +/*! + \return Direction of the dial + + The default direction of a dial is QwtDial::Clockwise + + \sa setDirection() +*/ +QwtDial::Direction QwtDial::direction() const +{ + return d_data->direction; +} + +/*! + Paint the dial + \param event Paint event +*/ +void QwtDial::paintEvent( QPaintEvent *event ) +{ + QPainter painter( this ); + painter.setClipRegion( event->region() ); + + QStyleOption opt; + opt.init(this); + style()->drawPrimitive(QStyle::PE_Widget, &opt, &painter, this); + + painter.setRenderHint( QPainter::Antialiasing, true ); + + painter.save(); + drawContents( &painter ); + painter.restore(); + + painter.save(); + drawFrame( &painter ); + painter.restore(); + + if ( hasFocus() ) + drawFocusIndicator( &painter ); +} + +/*! + Draw a dotted round circle, if !isReadOnly() + + \param painter Painter +*/ +void QwtDial::drawFocusIndicator( QPainter *painter ) const +{ + if ( !isReadOnly() ) + { + QRectF focusRect = innerRect(); + + const int margin = 2; + focusRect.adjust( margin, margin, -margin, -margin ); + + QColor color = palette().color( QPalette::Base ); + if ( color.isValid() ) + { + const QColor gray( Qt::gray ); + + int h, s, v; + color.getHsv( &h, &s, &v ); + color = ( v > 128 ) ? gray.dark( 120 ) : gray.light( 120 ); + } + else + color = Qt::darkGray; + + painter->save(); + painter->setBrush( Qt::NoBrush ); + painter->setPen( QPen( color, 0, Qt::DotLine ) ); + painter->drawEllipse( focusRect ); + painter->restore(); + } +} + +/*! + Draw the frame around the dial + + \param painter Painter + \sa lineWidth(), frameShadow() +*/ +void QwtDial::drawFrame( QPainter *painter ) +{ + if ( lineWidth() <= 0 ) + return; + + const double lw2 = 0.5 * lineWidth(); + + QRectF r = boundingRect(); + r.adjust( lw2, lw2, -lw2, -lw2 ); + + QPen pen; + + switch ( d_data->frameShadow ) + { + case QwtDial::Raised: + case QwtDial::Sunken: + { + QColor c1 = palette().color( QPalette::Light ); + QColor c2 = palette().color( QPalette::Dark ); + + if ( d_data->frameShadow == QwtDial::Sunken ) + qSwap( c1, c2 ); + + QLinearGradient gradient( r.topLeft(), r.bottomRight() ); + gradient.setColorAt( 0.0, c1 ); +#if 0 + gradient.setColorAt( 0.3, c1 ); + gradient.setColorAt( 0.7, c2 ); +#endif + gradient.setColorAt( 1.0, c2 ); + + pen = QPen( gradient, lineWidth() ); + break; + } + default: // Plain + { + pen = QPen( palette().brush( QPalette::Dark ), lineWidth() ); + } + } + + painter->save(); + + painter->setPen( pen ); + painter->setBrush( Qt::NoBrush ); + painter->drawEllipse( r ); + + painter->restore(); +} + +/*! + \brief Draw the contents inside the frame + + QPalette::Window is the background color outside of the frame. + QPalette::Base is the background color inside the frame. + QPalette::WindowText is the background color inside the scale. + + \param painter Painter + \sa boundingRect(), innerRect(), + scaleInnerRect(), QWidget::setPalette() +*/ +void QwtDial::drawContents( QPainter *painter ) const +{ + if ( testAttribute( Qt::WA_NoSystemBackground ) || + palette().brush( QPalette::Base ) != + palette().brush( QPalette::Window ) ) + { + const QRectF br = boundingRect(); + + painter->save(); + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().brush( QPalette::Base ) ); + painter->drawEllipse( br ); + painter->restore(); + } + + + const QRectF insideScaleRect = scaleInnerRect(); + if ( palette().brush( QPalette::WindowText ) != + palette().brush( QPalette::Base ) ) + { + painter->save(); + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().brush( QPalette::WindowText ) ); + painter->drawEllipse( insideScaleRect ); + painter->restore(); + } + + const QPointF center = insideScaleRect.center(); + const double radius = 0.5 * insideScaleRect.width(); + + double direction = d_data->origin; + + if ( isValid() ) + { + direction = d_data->minScaleArc; + if ( maxValue() > minValue() && + d_data->maxScaleArc > d_data->minScaleArc ) + { + const double ratio = + ( value() - minValue() ) / ( maxValue() - minValue() ); + direction += ratio * ( d_data->maxScaleArc - d_data->minScaleArc ); + } + + if ( d_data->direction == QwtDial::CounterClockwise ) + direction = d_data->maxScaleArc - ( direction - d_data->minScaleArc ); + + direction += d_data->origin; + if ( direction >= 360.0 ) + direction -= 360.0; + else if ( direction < 0.0 ) + direction += 360.0; + } + + double origin = d_data->origin; + if ( mode() == RotateScale ) + { + origin -= direction - d_data->origin; + direction = d_data->origin; + } + + painter->save(); + drawScale( painter, center, radius, origin, + d_data->minScaleArc, d_data->maxScaleArc ); + painter->restore(); + + painter->save(); + drawScaleContents( painter, center, radius ); + painter->restore(); + + if ( isValid() ) + { + QPalette::ColorGroup cg; + if ( isEnabled() ) + cg = hasFocus() ? QPalette::Active : QPalette::Inactive; + else + cg = QPalette::Disabled; + + painter->save(); + drawNeedle( painter, center, radius, direction, cg ); + painter->restore(); + } +} + +/*! + Draw the needle + + \param painter Painter + \param center Center of the dial + \param radius Length for the needle + \param direction Direction of the needle in degrees, counter clockwise + \param cg ColorGroup +*/ +void QwtDial::drawNeedle( QPainter *painter, const QPointF ¢er, + double radius, double direction, QPalette::ColorGroup cg ) const +{ + if ( d_data->needle ) + { + direction = 360.0 - direction; // counter clockwise + d_data->needle->draw( painter, center, radius, direction, cg ); + } +} + +/*! + Draw the scale + + \param painter Painter + \param center Center of the dial + \param radius Radius of the scale + \param origin Origin of the scale + \param minArc Minimum of the arc + \param maxArc Minimum of the arc + + \sa QwtRoundScaleDraw::setAngleRange() +*/ +void QwtDial::drawScale( QPainter *painter, const QPointF ¢er, + double radius, double origin, double minArc, double maxArc ) const +{ + if ( d_data->scaleDraw == NULL ) + return; + + origin -= 270.0; // hardcoded origin of QwtScaleDraw + + double angle = maxArc - minArc; + if ( angle > 360.0 ) + angle = ::fmod( angle, 360.0 ); + + minArc += origin; + if ( minArc < -360.0 ) + minArc = ::fmod( minArc, 360.0 ); + + maxArc = minArc + angle; + if ( maxArc > 360.0 ) + { + // QwtRoundScaleDraw::setAngleRange accepts only values + // in the range [-360.0..360.0] + minArc -= 360.0; + maxArc -= 360.0; + } + + if ( d_data->direction == QwtDial::CounterClockwise ) + qSwap( minArc, maxArc ); + + painter->setFont( font() ); + + d_data->scaleDraw->setAngleRange( minArc, maxArc ); + d_data->scaleDraw->setRadius( radius ); + d_data->scaleDraw->moveCenter( center ); + + QPalette pal = palette(); + + const QColor textColor = pal.color( QPalette::Text ); + pal.setColor( QPalette::WindowText, textColor ); //ticks, backbone + + painter->setPen( QPen( textColor, d_data->scaleDraw->penWidth() ) ); + + painter->setBrush( Qt::red ); + d_data->scaleDraw->draw( painter, pal ); +} + +/*! + Draw the contents inside the scale + + Paints nothing. + + \param painter Painter + \param center Center of the contents circle + \param radius Radius of the contents circle +*/ + +void QwtDial::drawScaleContents( QPainter *painter, + const QPointF ¢er, double radius ) const +{ + Q_UNUSED(painter); + Q_UNUSED(center); + Q_UNUSED(radius); +} + +/*! + Set a needle for the dial + + Qwt is missing a set of good looking needles. + Contributions are very welcome. + + \param needle Needle + \warning The needle will be deleted, when a different needle is + set or in ~QwtDial() +*/ +void QwtDial::setNeedle( QwtDialNeedle *needle ) +{ + if ( needle != d_data->needle ) + { + if ( d_data->needle ) + delete d_data->needle; + + d_data->needle = needle; + update(); + } +} + +/*! + \return needle + \sa setNeedle() +*/ +const QwtDialNeedle *QwtDial::needle() const +{ + return d_data->needle; +} + +/*! + \return needle + \sa setNeedle() +*/ +QwtDialNeedle *QwtDial::needle() +{ + return d_data->needle; +} + +//! QwtDoubleRange update hook +void QwtDial::rangeChange() +{ + updateScale(); +} + +/*! + Update the scale with the current attributes + \sa setScale() +*/ +void QwtDial::updateScale() +{ + if ( d_data->scaleDraw ) + { + QwtLinearScaleEngine scaleEngine; + + const QwtScaleDiv scaleDiv = scaleEngine.divideScale( + minValue(), maxValue(), + d_data->maxMajIntv, d_data->maxMinIntv, d_data->scaleStep ); + + d_data->scaleDraw->setTransformation( scaleEngine.transformation() ); + d_data->scaleDraw->setScaleDiv( scaleDiv ); + } +} + +//! Return the scale draw +QwtDialScaleDraw *QwtDial::scaleDraw() +{ + return d_data->scaleDraw; +} + +//! Return the scale draw +const QwtDialScaleDraw *QwtDial::scaleDraw() const +{ + return d_data->scaleDraw; +} + +/*! + Set an individual scale draw + + \param scaleDraw Scale draw + \warning The previous scale draw is deleted +*/ +void QwtDial::setScaleDraw( QwtDialScaleDraw *scaleDraw ) +{ + if ( scaleDraw != d_data->scaleDraw ) + { + if ( d_data->scaleDraw ) + delete d_data->scaleDraw; + + d_data->scaleDraw = scaleDraw; + updateScale(); + update(); + } +} + +/*! + Change the intervals of the scale + + \param maxMajIntv Maximum for the number of major steps + \param maxMinIntv Maximum number of minor steps + \param step Step size + + \sa QwtScaleEngine::divideScale() +*/ +void QwtDial::setScale( int maxMajIntv, int maxMinIntv, double step ) +{ + d_data->maxMajIntv = maxMajIntv; + d_data->maxMinIntv = maxMinIntv; + d_data->scaleStep = step; + + updateScale(); +} + +/*! + A wrapper method for accessing the scale draw. + + \param components Scale components + \sa QwtAbstractScaleDraw::enableComponent() +*/ +void QwtDial::setScaleComponents( + QwtAbstractScaleDraw::ScaleComponents components ) +{ + if ( components == 0 ) + setScaleDraw( NULL ); + + QwtDialScaleDraw *sd = d_data->scaleDraw; + if ( sd == NULL ) + return; + + sd->enableComponent( QwtAbstractScaleDraw::Backbone, + components & QwtAbstractScaleDraw::Backbone ); + + sd->enableComponent( QwtAbstractScaleDraw::Ticks, + components & QwtAbstractScaleDraw::Ticks ); + + sd->enableComponent( QwtAbstractScaleDraw::Labels, + components & QwtAbstractScaleDraw::Labels ); +} + +/*! + Assign length and width of the ticks + + \param minLen Length of the minor ticks + \param medLen Length of the medium ticks + \param majLen Length of the major ticks + \param penWidth Width of the pen for all ticks + + \sa QwtAbstractScaleDraw::setTickLength(), QwtDialScaleDraw::setPenWidth() +*/ +void QwtDial::setScaleTicks( int minLen, int medLen, + int majLen, int penWidth ) +{ + QwtDialScaleDraw *sd = d_data->scaleDraw; + if ( sd ) + { + sd->setTickLength( QwtScaleDiv::MinorTick, minLen ); + sd->setTickLength( QwtScaleDiv::MediumTick, medLen ); + sd->setTickLength( QwtScaleDiv::MajorTick, majLen ); + sd->setPenWidth( penWidth ); + } +} + +/*! + Find the label for a value + + \param value Value + \return label +*/ +QwtText QwtDial::scaleLabel( double value ) const +{ +#if 1 + if ( value == -0 ) + value = 0; +#endif + + return QString::number( value ); +} + +//! \return Lower limit of the scale arc +double QwtDial::minScaleArc() const +{ + return d_data->minScaleArc; +} + +//! \return Upper limit of the scale arc +double QwtDial::maxScaleArc() const +{ + return d_data->maxScaleArc; +} + +/*! + \brief Change the origin + + The origin is the angle where scale and needle is relative to. + + \param origin New origin + \sa origin() +*/ +void QwtDial::setOrigin( double origin ) +{ + d_data->origin = origin; + update(); +} + +/*! + The origin is the angle where scale and needle is relative to. + + \return Origin of the dial + \sa setOrigin() +*/ +double QwtDial::origin() const +{ + return d_data->origin; +} + +/*! + Change the arc of the scale + + \param minArc Lower limit + \param maxArc Upper limit +*/ +void QwtDial::setScaleArc( double minArc, double maxArc ) +{ + if ( minArc != 360.0 && minArc != -360.0 ) + minArc = ::fmod( minArc, 360.0 ); + if ( maxArc != 360.0 && maxArc != -360.0 ) + maxArc = ::fmod( maxArc, 360.0 ); + + d_data->minScaleArc = qMin( minArc, maxArc ); + d_data->maxScaleArc = qMax( minArc, maxArc ); + if ( d_data->maxScaleArc - d_data->minScaleArc > 360.0 ) + d_data->maxScaleArc = d_data->minScaleArc + 360.0; + + update(); +} + +//! QwtDoubleRange update hook +void QwtDial::valueChange() +{ + update(); + QwtAbstractSlider::valueChange(); +} + +/*! + \return Size hint +*/ +QSize QwtDial::sizeHint() const +{ + int sh = 0; + if ( d_data->scaleDraw ) + sh = qCeil( d_data->scaleDraw->extent( font() ) ); + + const int d = 6 * sh + 2 * lineWidth(); + + QSize hint( d, d ); + if ( !isReadOnly() ) + hint = hint.expandedTo( QApplication::globalStrut() ); + + return hint; +} + +/*! + \brief Return a minimum size hint + \warning The return value of QwtDial::minimumSizeHint() depends on the + font and the scale. +*/ +QSize QwtDial::minimumSizeHint() const +{ + int sh = 0; + if ( d_data->scaleDraw ) + sh = qCeil( d_data->scaleDraw->extent( font() ) ); + + const int d = 3 * sh + 2 * lineWidth(); + + return QSize( d, d ); +} + +static double line2Radians( const QPointF &p1, const QPointF &p2 ) +{ + const QPointF p = p2 - p1; + + double angle; + if ( p.x() == 0 ) + angle = ( p.y() <= 0.0 ) ? M_PI_2 : 3 * M_PI_2; + else + { + angle = qAtan( double( -p.y() ) / double( p.x() ) ); + if ( p.x() < 0.0 ) + angle += M_PI; + if ( angle < 0.0 ) + angle += 2 * M_PI; + } + return 360.0 - angle * 180.0 / M_PI; +} + +/*! + Find the value for a given position + + \param pos Position + \return Value +*/ +double QwtDial::getValue( const QPoint &pos ) +{ + if ( d_data->maxScaleArc == d_data->minScaleArc || maxValue() == minValue() ) + return minValue(); + + double dir = line2Radians( innerRect().center(), pos ) - d_data->origin; + if ( dir < 0.0 ) + dir += 360.0; + + if ( mode() == RotateScale ) + dir = 360.0 - dir; + + // The position might be in the area that is outside the scale arc. + // We need the range of the scale if it was a complete circle. + + const double completeCircle = 360.0 / ( d_data->maxScaleArc - d_data->minScaleArc ) + * ( maxValue() - minValue() ); + + double posValue = minValue() + completeCircle * dir / 360.0; + + if ( scrollMode() == ScrMouse ) + { + if ( d_data->previousDir >= 0.0 ) // valid direction + { + // We have to find out whether the mouse is moving + // clock or counter clockwise + + bool clockWise = false; + + const double angle = dir - d_data->previousDir; + if ( ( angle >= 0.0 && angle <= 180.0 ) || angle < -180.0 ) + clockWise = true; + + if ( clockWise ) + { + if ( dir < d_data->previousDir && mouseOffset() > 0.0 ) + { + // We passed 360 -> 0 + setMouseOffset( mouseOffset() - completeCircle ); + } + + if ( wrapping() ) + { + if ( posValue - mouseOffset() > maxValue() ) + { + // We passed maxValue and the value will be set + // to minValue. We have to adjust the mouseOffset. + + setMouseOffset( posValue - minValue() ); + } + } + else + { + if ( posValue - mouseOffset() > maxValue() || + value() == maxValue() ) + { + // We fix the value at maxValue by adjusting + // the mouse offset. + + setMouseOffset( posValue - maxValue() ); + } + } + } + else + { + if ( dir > d_data->previousDir && mouseOffset() < 0.0 ) + { + // We passed 0 -> 360 + setMouseOffset( mouseOffset() + completeCircle ); + } + + if ( wrapping() ) + { + if ( posValue - mouseOffset() < minValue() ) + { + // We passed minValue and the value will be set + // to maxValue. We have to adjust the mouseOffset. + + setMouseOffset( posValue - maxValue() ); + } + } + else + { + if ( posValue - mouseOffset() < minValue() || + value() == minValue() ) + { + // We fix the value at minValue by adjusting + // the mouse offset. + + setMouseOffset( posValue - minValue() ); + } + } + } + } + d_data->previousDir = dir; + } + + return posValue; +} + +/*! + See QwtAbstractSlider::getScrollMode() + + \param pos point where the mouse was pressed + \retval scrollMode The scrolling mode + \retval direction direction: 1, 0, or -1. + + \sa QwtAbstractSlider::getScrollMode() +*/ +void QwtDial::getScrollMode( const QPoint &pos, + QwtAbstractSlider::ScrollMode &scrollMode, int &direction ) const +{ + direction = 0; + scrollMode = QwtAbstractSlider::ScrNone; + + const QRegion region( innerRect().toRect(), QRegion::Ellipse ); + if ( region.contains( pos ) && pos != innerRect().center() ) + { + scrollMode = QwtAbstractSlider::ScrMouse; + d_data->previousDir = -1.0; + } +} + +/*! + Handles key events + + - Key_Down, KeyLeft\n + Decrement by 1 + - Key_Prior\n + Decrement by pageSize() + - Key_Home\n + Set the value to minValue() + + - Key_Up, KeyRight\n + Increment by 1 + - Key_Next\n + Increment by pageSize() + - Key_End\n + Set the value to maxValue() + + \param event Key event + \sa isReadOnly() +*/ +void QwtDial::keyPressEvent( QKeyEvent *event ) +{ + if ( isReadOnly() ) + { + event->ignore(); + return; + } + + if ( !isValid() ) + return; + + double previous = prevValue(); + switch ( event->key() ) + { + case Qt::Key_Down: + case Qt::Key_Left: + QwtDoubleRange::incValue( -1 ); + break; + case Qt::Key_PageUp: + QwtDoubleRange::incValue( -pageSize() ); + break; + case Qt::Key_Home: + setValue( minValue() ); + break; + + case Qt::Key_Up: + case Qt::Key_Right: + QwtDoubleRange::incValue( 1 ); + break; + case Qt::Key_PageDown: + QwtDoubleRange::incValue( pageSize() ); + break; + case Qt::Key_End: + setValue( maxValue() ); + break; + default:; + event->ignore(); + } + + if ( value() != previous ) + Q_EMIT sliderMoved( value() ); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_dial.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_dial.h index 969b529c0..128ceda3b 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_dial.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_dial.h @@ -1,215 +1,215 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_DIAL_H -#define QWT_DIAL_H 1 - -#include "qwt_global.h" -#include "qwt_abstract_slider.h" -#include "qwt_round_scale_draw.h" -#include -#include - -class QwtDialNeedle; -class QwtDial; - -/*! - \brief A special scale draw made for QwtDial - - \sa QwtDial, QwtCompass -*/ -class QWT_EXPORT QwtDialScaleDraw: public QwtRoundScaleDraw -{ -public: - explicit QwtDialScaleDraw( QwtDial * ); - - virtual QwtText label( double value ) const; - - void setPenWidth( double ); - double penWidth() const; - -private: - QwtDial *d_parent; - double d_penWidth; -}; - -/*! - \brief QwtDial class provides a rounded range control. - - QwtDial is intended as base class for dial widgets like - speedometers, compass widgets, clocks ... - - \image html dials2.png - - A dial contains a scale and a needle indicating the current value - of the dial. Depending on Mode one of them is fixed and the - other is rotating. If not isReadOnly() the - dial can be rotated by dragging the mouse or using keyboard inputs - (see keyPressEvent()). A dial might be wrapping, what means - a rotation below/above one limit continues on the other limit (f.e compass). - The scale might cover any arc of the dial, its values are related to - the origin() of the dial. - - Qwt is missing a set of good looking needles (QwtDialNeedle). - Contributions are very welcome. - - \sa QwtCompass, QwtAnalogClock, QwtDialNeedle - \note The examples/dials example shows different types of dials. -*/ - -class QWT_EXPORT QwtDial: public QwtAbstractSlider -{ - Q_OBJECT - - Q_ENUMS( Shadow ) - Q_ENUMS( Mode ) - Q_ENUMS( Direction ) - - Q_PROPERTY( int lineWidth READ lineWidth WRITE setLineWidth ) - Q_PROPERTY( Shadow frameShadow READ frameShadow WRITE setFrameShadow ) - Q_PROPERTY( Mode mode READ mode WRITE setMode ) - Q_PROPERTY( double origin READ origin WRITE setOrigin ) - Q_PROPERTY( bool wrapping READ wrapping WRITE setWrapping ) - Q_PROPERTY( Direction direction READ direction WRITE setDirection ) - - friend class QwtDialScaleDraw; -public: - - /*! - \brief Frame shadow - - Unfortunately it is not possible to use QFrame::Shadow - as a property of a widget that is not derived from QFrame. - The following enum is made for the designer only. It is safe - to use QFrame::Shadow instead. - */ - enum Shadow - { - //! QFrame::Plain - Plain = QFrame::Plain, - - //! QFrame::Raised - Raised = QFrame::Raised, - - //! QFrame::Sunken - Sunken = QFrame::Sunken - }; - - //! Mode controlling wether the needle or the scale is rotating - enum Mode - { - //! The needle is rotating - RotateNeedle, - - //! The needle is fixed, the scales are rotating - RotateScale - }; - - //! Direction of the dial - enum Direction - { - //! Clockwise - Clockwise, - - //! Counter clockwise - CounterClockwise - }; - - explicit QwtDial( QWidget *parent = NULL ); - virtual ~QwtDial(); - - void setFrameShadow( Shadow ); - Shadow frameShadow() const; - - void setLineWidth( int ); - int lineWidth() const; - - void setMode( Mode ); - Mode mode() const; - - virtual void setWrapping( bool ); - bool wrapping() const; - - virtual void setScale( int maxMajIntv, int maxMinIntv, double step = 0.0 ); - - void setScaleArc( double min, double max ); - void setScaleComponents( QwtAbstractScaleDraw::ScaleComponents ); - void setScaleTicks( int minLen, int medLen, int majLen, int penWidth = 1 ); - - double minScaleArc() const; - double maxScaleArc() const; - - virtual void setOrigin( double ); - double origin() const; - - void setDirection( Direction ); - Direction direction() const; - - virtual void setNeedle( QwtDialNeedle * ); - const QwtDialNeedle *needle() const; - QwtDialNeedle *needle(); - - QRectF boundingRect() const; - QRectF innerRect() const; - virtual QRectF scaleInnerRect() const; - - virtual QSize sizeHint() const; - virtual QSize minimumSizeHint() const; - - virtual void setScaleDraw( QwtDialScaleDraw * ); - - QwtDialScaleDraw *scaleDraw(); - const QwtDialScaleDraw *scaleDraw() const; - -protected: - virtual void paintEvent( QPaintEvent * ); - virtual void keyPressEvent( QKeyEvent * ); - - virtual void drawFrame( QPainter *p ); - virtual void drawContents( QPainter * ) const; - virtual void drawFocusIndicator( QPainter * ) const; - - virtual void drawScale( - QPainter *, const QPointF ¢er, - double radius, double origin, - double arcMin, double arcMax ) const; - - /*! - Draw the contents inside the scale - - Paints nothing. - - \param painter Painter - \param center Center of the contents circle - \param radius Radius of the contents circle - */ - virtual void drawScaleContents( QPainter *painter, - const QPointF ¢er, double radius ) const; - - virtual void drawNeedle( QPainter *, const QPointF &, - double radius, double direction, QPalette::ColorGroup ) const; - - virtual QwtText scaleLabel( double ) const; - void updateScale(); - - virtual void rangeChange(); - virtual void valueChange(); - - virtual double getValue( const QPoint & ); - virtual void getScrollMode( const QPoint &, - QwtAbstractSlider::ScrollMode &, int &direction ) const; - -private: - void initDial(); - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_DIAL_H +#define QWT_DIAL_H 1 + +#include "qwt_global.h" +#include "qwt_abstract_slider.h" +#include "qwt_round_scale_draw.h" +#include +#include + +class QwtDialNeedle; +class QwtDial; + +/*! + \brief A special scale draw made for QwtDial + + \sa QwtDial, QwtCompass +*/ +class QWT_EXPORT QwtDialScaleDraw: public QwtRoundScaleDraw +{ +public: + explicit QwtDialScaleDraw( QwtDial * ); + + virtual QwtText label( double value ) const; + + void setPenWidth( double ); + double penWidth() const; + +private: + QwtDial *d_parent; + double d_penWidth; +}; + +/*! + \brief QwtDial class provides a rounded range control. + + QwtDial is intended as base class for dial widgets like + speedometers, compass widgets, clocks ... + + \image html dials2.png + + A dial contains a scale and a needle indicating the current value + of the dial. Depending on Mode one of them is fixed and the + other is rotating. If not isReadOnly() the + dial can be rotated by dragging the mouse or using keyboard inputs + (see keyPressEvent()). A dial might be wrapping, what means + a rotation below/above one limit continues on the other limit (f.e compass). + The scale might cover any arc of the dial, its values are related to + the origin() of the dial. + + Qwt is missing a set of good looking needles (QwtDialNeedle). + Contributions are very welcome. + + \sa QwtCompass, QwtAnalogClock, QwtDialNeedle + \note The examples/dials example shows different types of dials. +*/ + +class QWT_EXPORT QwtDial: public QwtAbstractSlider +{ + Q_OBJECT + + Q_ENUMS( Shadow ) + Q_ENUMS( Mode ) + Q_ENUMS( Direction ) + + Q_PROPERTY( int lineWidth READ lineWidth WRITE setLineWidth ) + Q_PROPERTY( Shadow frameShadow READ frameShadow WRITE setFrameShadow ) + Q_PROPERTY( Mode mode READ mode WRITE setMode ) + Q_PROPERTY( double origin READ origin WRITE setOrigin ) + Q_PROPERTY( bool wrapping READ wrapping WRITE setWrapping ) + Q_PROPERTY( Direction direction READ direction WRITE setDirection ) + + friend class QwtDialScaleDraw; +public: + + /*! + \brief Frame shadow + + Unfortunately it is not possible to use QFrame::Shadow + as a property of a widget that is not derived from QFrame. + The following enum is made for the designer only. It is safe + to use QFrame::Shadow instead. + */ + enum Shadow + { + //! QFrame::Plain + Plain = QFrame::Plain, + + //! QFrame::Raised + Raised = QFrame::Raised, + + //! QFrame::Sunken + Sunken = QFrame::Sunken + }; + + //! Mode controlling wether the needle or the scale is rotating + enum Mode + { + //! The needle is rotating + RotateNeedle, + + //! The needle is fixed, the scales are rotating + RotateScale + }; + + //! Direction of the dial + enum Direction + { + //! Clockwise + Clockwise, + + //! Counter clockwise + CounterClockwise + }; + + explicit QwtDial( QWidget *parent = NULL ); + virtual ~QwtDial(); + + void setFrameShadow( Shadow ); + Shadow frameShadow() const; + + void setLineWidth( int ); + int lineWidth() const; + + void setMode( Mode ); + Mode mode() const; + + virtual void setWrapping( bool ); + bool wrapping() const; + + virtual void setScale( int maxMajIntv, int maxMinIntv, double step = 0.0 ); + + void setScaleArc( double min, double max ); + void setScaleComponents( QwtAbstractScaleDraw::ScaleComponents ); + void setScaleTicks( int minLen, int medLen, int majLen, int penWidth = 1 ); + + double minScaleArc() const; + double maxScaleArc() const; + + virtual void setOrigin( double ); + double origin() const; + + void setDirection( Direction ); + Direction direction() const; + + virtual void setNeedle( QwtDialNeedle * ); + const QwtDialNeedle *needle() const; + QwtDialNeedle *needle(); + + QRectF boundingRect() const; + QRectF innerRect() const; + virtual QRectF scaleInnerRect() const; + + virtual QSize sizeHint() const; + virtual QSize minimumSizeHint() const; + + virtual void setScaleDraw( QwtDialScaleDraw * ); + + QwtDialScaleDraw *scaleDraw(); + const QwtDialScaleDraw *scaleDraw() const; + +protected: + virtual void paintEvent( QPaintEvent * ); + virtual void keyPressEvent( QKeyEvent * ); + + virtual void drawFrame( QPainter *p ); + virtual void drawContents( QPainter * ) const; + virtual void drawFocusIndicator( QPainter * ) const; + + virtual void drawScale( + QPainter *, const QPointF ¢er, + double radius, double origin, + double arcMin, double arcMax ) const; + + /*! + Draw the contents inside the scale + + Paints nothing. + + \param painter Painter + \param center Center of the contents circle + \param radius Radius of the contents circle + */ + virtual void drawScaleContents( QPainter *painter, + const QPointF ¢er, double radius ) const; + + virtual void drawNeedle( QPainter *, const QPointF &, + double radius, double direction, QPalette::ColorGroup ) const; + + virtual QwtText scaleLabel( double ) const; + void updateScale(); + + virtual void rangeChange(); + virtual void valueChange(); + + virtual double getValue( const QPoint & ); + virtual void getScrollMode( const QPoint &, + QwtAbstractSlider::ScrollMode &, int &direction ) const; + +private: + void initDial(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_dial_needle.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_dial_needle.cpp index d4c03e73a..2f8bada19 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_dial_needle.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_dial_needle.cpp @@ -1,452 +1,452 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_dial_needle.h" -#include "qwt_global.h" -#include "qwt_math.h" -#include "qwt_painter.h" -#include -#include - -static void qwtDrawStyle1Needle( QPainter *painter, - const QPalette &palette, QPalette::ColorGroup colorGroup, - double length ) -{ - const double r[] = { 0.4, 0.3, 1, 0.8, 1, 0.3, 0.4 }; - const double a[] = { -45, -20, -15, 0, 15, 20, 45 }; - - QPainterPath path; - for ( int i = 0; i < 7; i++ ) - { - const double angle = a[i] / 180.0 * M_PI; - const double radius = r[i] * length; - - const double x = radius * qCos( angle ); - const double y = radius * qSin( angle ); - - path.lineTo( x, -y ); - } - - painter->setPen( Qt::NoPen ); - painter->setBrush( palette.brush( colorGroup, QPalette::Light ) ); - painter->drawPath( path ); -} - -static void qwtDrawStyle2Needle( QPainter *painter, - const QPalette &palette, QPalette::ColorGroup colorGroup, double length ) -{ - const double ratioX = 0.7; - const double ratioY = 0.3; - - QPainterPath path1; - path1.lineTo( ratioX * length, 0.0 ); - path1.lineTo( length, ratioY * length ); - - QPainterPath path2; - path2.lineTo( ratioX * length, 0.0 ); - path2.lineTo( length, -ratioY * length ); - - painter->setPen( Qt::NoPen ); - - painter->setBrush( palette.brush( colorGroup, QPalette::Light ) ); - painter->drawPath( path1 ); - - painter->setBrush( palette.brush( colorGroup, QPalette::Dark ) ); - painter->drawPath( path2 ); -} - -static void qwtDrawShadedPointer( QPainter *painter, - const QColor &lightColor, const QColor &darkColor, - double length, double width ) -{ - const double peak = qMax( length / 10.0, 5.0 ); - - const double knobWidth = width + 8; - QRectF knobRect( 0, 0, knobWidth, knobWidth ); - knobRect.moveCenter( QPointF(0, 0) ); - - QPainterPath path1; - path1.lineTo( 0.0, 0.5 * width ); - path1.lineTo( length - peak, 0.5 * width ); - path1.lineTo( length, 0.0 ); - path1.lineTo( 0.0, 0.0 ); - - QPainterPath arcPath1; - arcPath1.arcTo( knobRect, 0.0, -90.0 ); - - path1 = path1.united( arcPath1 ); - - QPainterPath path2; - path2.lineTo( 0.0, -0.5 * width ); - path2.lineTo( length - peak, -0.5 * width ); - path2.lineTo( length, 0.0 ); - path2.lineTo( 0.0, 0.0 ); - - QPainterPath arcPath2; - arcPath2.arcTo( knobRect, 0.0, 90.0 ); - - path2 = path2.united( arcPath2 ); - - painter->setPen( Qt::NoPen ); - - painter->setBrush( lightColor ); - painter->drawPath( path1 ); - - painter->setBrush( darkColor ); - painter->drawPath( path2 ); -} - -static void qwtDrawArrowNeedle( QPainter *painter, - const QPalette &palette, QPalette::ColorGroup colorGroup, - double length, double width ) -{ - if ( width <= 0 ) - width = qMax( length * 0.06, 9.0 ); - - const double peak = qMax( 2.0, 0.4 * width ); - - QPainterPath path; - path.moveTo( 0.0, 0.5 * width ); - path.lineTo( length - peak, 0.3 * width ); - path.lineTo( length, 0.0 ); - path.lineTo( length - peak, -0.3 * width ); - path.lineTo( 0.0, -0.5 * width ); - - QRectF br = path.boundingRect(); - - QPalette pal( palette.color( QPalette::Mid ) ); - QColor c1 = pal.color( QPalette::Light ); - QColor c2 = pal.color( QPalette::Dark ); - - QLinearGradient gradient( br.topLeft(), br.bottomLeft() ); - gradient.setColorAt( 0.0, c1 ); - gradient.setColorAt( 0.5, c1 ); - gradient.setColorAt( 0.5001, c2 ); - gradient.setColorAt( 1.0, c2 ); - - QPen pen( gradient, 1 ); - pen.setJoinStyle( Qt::MiterJoin ); - - painter->setPen( pen ); - painter->setBrush( palette.brush( colorGroup, QPalette::Mid ) ); - - painter->drawPath( path ); -} - -static void qwtDrawTriangleNeedle( QPainter *painter, - const QPalette &palette, QPalette::ColorGroup colorGroup, - double length ) -{ - const double width = qRound( length / 3.0 ); - - QPainterPath path[4]; - - path[0].lineTo( length, 0.0 ); - path[0].lineTo( 0.0, width / 2 ); - - path[1].lineTo( length, 0.0 ); - path[1].lineTo( 0.0, -width / 2 ); - - path[2].lineTo( -length, 0.0 ); - path[2].lineTo( 0.0, width / 2 ); - - path[3].lineTo( -length, 0.0 ); - path[3].lineTo( 0.0, -width / 2 ); - - - const int colorOffset = 10; - const QColor darkColor = palette.color( colorGroup, QPalette::Dark ); - const QColor lightColor = palette.color( colorGroup, QPalette::Light ); - - QColor color[4]; - color[0] = darkColor.light( 100 + colorOffset ); - color[1] = darkColor.dark( 100 + colorOffset ); - color[2] = lightColor.light( 100 + colorOffset ); - color[3] = lightColor.dark( 100 + colorOffset ); - - painter->setPen( Qt::NoPen ); - - for ( int i = 0; i < 4; i++ ) - { - painter->setBrush( color[i] ); - painter->drawPath( path[i] ); - } -} - -//! Constructor -QwtDialNeedle::QwtDialNeedle(): - d_palette( QApplication::palette() ) -{ -} - -//! Destructor -QwtDialNeedle::~QwtDialNeedle() -{ -} - -/*! - Sets the palette for the needle. - - \param palette New Palette -*/ -void QwtDialNeedle::setPalette( const QPalette &palette ) -{ - d_palette = palette; -} - -/*! - \return the palette of the needle. -*/ -const QPalette &QwtDialNeedle::palette() const -{ - return d_palette; -} - -/*! - Draw the needle - - \param painter Painter - \param center Center of the dial, start position for the needle - \param length Length of the needle - \param direction Direction of the needle, in degrees counter clockwise - \param colorGroup Color group, used for painting -*/ -void QwtDialNeedle::draw( QPainter *painter, - const QPointF ¢er, double length, double direction, - QPalette::ColorGroup colorGroup ) const -{ - painter->save(); - - painter->translate( center ); - painter->rotate( -direction ); - - drawNeedle( painter, length, colorGroup ); - - painter->restore(); -} - -//! Draw the knob -void QwtDialNeedle::drawKnob( QPainter *painter, - double width, const QBrush &brush, bool sunken ) const -{ - QPalette palette( brush.color() ); - - QColor c1 = palette.color( QPalette::Light ); - QColor c2 = palette.color( QPalette::Dark ); - - if ( sunken ) - qSwap( c1, c2 ); - - QRectF rect( 0.0, 0.0, width, width ); - rect.moveCenter( painter->combinedTransform().map( QPointF() ) ); - - QLinearGradient gradient( rect.topLeft(), rect.bottomRight() ); - gradient.setColorAt( 0.0, c1 ); - gradient.setColorAt( 0.3, c1 ); - gradient.setColorAt( 0.7, c2 ); - gradient.setColorAt( 1.0, c2 ); - - painter->save(); - - painter->resetTransform(); - - painter->setPen( QPen( gradient, 1 ) ); - painter->setBrush( brush ); - painter->drawEllipse( rect ); - - painter->restore(); -} - -/*! - Constructor - - \param style Style - \param hasKnob With/Without knob - \param mid Middle color - \param base Base color -*/ -QwtDialSimpleNeedle::QwtDialSimpleNeedle( Style style, bool hasKnob, - const QColor &mid, const QColor &base ): - d_style( style ), - d_hasKnob( hasKnob ), - d_width( -1 ) -{ - QPalette palette; - for ( int i = 0; i < QPalette::NColorGroups; i++ ) - { - palette.setColor( ( QPalette::ColorGroup )i, - QPalette::Mid, mid ); - palette.setColor( ( QPalette::ColorGroup )i, - QPalette::Base, base ); - } - - setPalette( palette ); -} - -/*! - Set the width of the needle - \param width Width - \sa width() -*/ -void QwtDialSimpleNeedle::setWidth( double width ) -{ - d_width = width; -} - -/*! - \return the width of the needle - \sa setWidth() -*/ -double QwtDialSimpleNeedle::width() const -{ - return d_width; -} - -/*! - Draw the needle - - \param painter Painter - \param length Length of the needle - \param colorGroup Color group, used for painting -*/ -void QwtDialSimpleNeedle::drawNeedle( QPainter *painter, - double length, QPalette::ColorGroup colorGroup ) const -{ - double knobWidth = 0.0; - double width = d_width; - - if ( d_style == Arrow ) - { - if ( width <= 0.0 ) - width = qMax(length * 0.06, 6.0); - - qwtDrawArrowNeedle( painter, - palette(), colorGroup, length, width ); - - knobWidth = qMin( width * 2.0, 0.2 * length ); - } - else - { - if ( width <= 0.0 ) - width = 5.0; - - QPen pen ( palette().brush( colorGroup, QPalette::Mid ), width ); - pen.setCapStyle( Qt::FlatCap ); - - painter->setPen( pen ); - painter->drawLine( 0, 0, length, 0 ); - - knobWidth = qMax( width * 3.0, 5.0 ); - } - - if ( d_hasKnob && knobWidth > 0.0 ) - { - drawKnob( painter, knobWidth, - palette().brush( colorGroup, QPalette::Base ), false ); - } -} - -//! Constructor - -QwtCompassMagnetNeedle::QwtCompassMagnetNeedle( Style style, - const QColor &light, const QColor &dark ): - d_style( style ) -{ - QPalette palette; - for ( int i = 0; i < QPalette::NColorGroups; i++ ) - { - palette.setColor( ( QPalette::ColorGroup )i, - QPalette::Light, light ); - palette.setColor( ( QPalette::ColorGroup )i, - QPalette::Dark, dark ); - palette.setColor( ( QPalette::ColorGroup )i, - QPalette::Base, Qt::gray ); - } - - setPalette( palette ); -} - -/*! - Draw the needle - - \param painter Painter - \param length Length of the needle - \param colorGroup Color group, used for painting -*/ -void QwtCompassMagnetNeedle::drawNeedle( QPainter *painter, - double length, QPalette::ColorGroup colorGroup ) const -{ - if ( d_style == ThinStyle ) - { - const double width = qMax( length / 6.0, 3.0 ); - - const int colorOffset = 10; - - const QColor light = palette().color( colorGroup, QPalette::Light ); - const QColor dark = palette().color( colorGroup, QPalette::Dark ); - - qwtDrawShadedPointer( painter, - dark.light( 100 + colorOffset ), - dark.dark( 100 + colorOffset ), - length, width ); - - painter->rotate( 180.0 ); - - qwtDrawShadedPointer( painter, - light.light( 100 + colorOffset ), - light.dark( 100 + colorOffset ), - length, width ); - - const QBrush baseBrush = palette().brush( colorGroup, QPalette::Base ); - drawKnob( painter, width, baseBrush, true ); - } - else - { - qwtDrawTriangleNeedle( painter, palette(), colorGroup, length ); - } -} - -/*! - Constructor - - \param style Arrow style - \param light Light color - \param dark Dark color -*/ -QwtCompassWindArrow::QwtCompassWindArrow( Style style, - const QColor &light, const QColor &dark ): - d_style( style ) -{ - QPalette palette; - for ( int i = 0; i < QPalette::NColorGroups; i++ ) - { - palette.setColor( ( QPalette::ColorGroup )i, - QPalette::Light, light ); - palette.setColor( ( QPalette::ColorGroup )i, - QPalette::Dark, dark ); - } - - setPalette( palette ); -} - -/*! - Draw the needle - - \param painter Painter - \param length Length of the needle - \param colorGroup Color group, used for painting -*/ -void QwtCompassWindArrow::drawNeedle( QPainter *painter, - double length, QPalette::ColorGroup colorGroup ) const -{ - if ( d_style == Style1 ) - qwtDrawStyle1Needle( painter, palette(), colorGroup, length ); - else - qwtDrawStyle2Needle( painter, palette(), colorGroup, length ); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_dial_needle.h" +#include "qwt_global.h" +#include "qwt_math.h" +#include "qwt_painter.h" +#include +#include + +static void qwtDrawStyle1Needle( QPainter *painter, + const QPalette &palette, QPalette::ColorGroup colorGroup, + double length ) +{ + const double r[] = { 0.4, 0.3, 1, 0.8, 1, 0.3, 0.4 }; + const double a[] = { -45, -20, -15, 0, 15, 20, 45 }; + + QPainterPath path; + for ( int i = 0; i < 7; i++ ) + { + const double angle = a[i] / 180.0 * M_PI; + const double radius = r[i] * length; + + const double x = radius * qCos( angle ); + const double y = radius * qSin( angle ); + + path.lineTo( x, -y ); + } + + painter->setPen( Qt::NoPen ); + painter->setBrush( palette.brush( colorGroup, QPalette::Light ) ); + painter->drawPath( path ); +} + +static void qwtDrawStyle2Needle( QPainter *painter, + const QPalette &palette, QPalette::ColorGroup colorGroup, double length ) +{ + const double ratioX = 0.7; + const double ratioY = 0.3; + + QPainterPath path1; + path1.lineTo( ratioX * length, 0.0 ); + path1.lineTo( length, ratioY * length ); + + QPainterPath path2; + path2.lineTo( ratioX * length, 0.0 ); + path2.lineTo( length, -ratioY * length ); + + painter->setPen( Qt::NoPen ); + + painter->setBrush( palette.brush( colorGroup, QPalette::Light ) ); + painter->drawPath( path1 ); + + painter->setBrush( palette.brush( colorGroup, QPalette::Dark ) ); + painter->drawPath( path2 ); +} + +static void qwtDrawShadedPointer( QPainter *painter, + const QColor &lightColor, const QColor &darkColor, + double length, double width ) +{ + const double peak = qMax( length / 10.0, 5.0 ); + + const double knobWidth = width + 8; + QRectF knobRect( 0, 0, knobWidth, knobWidth ); + knobRect.moveCenter( QPointF(0, 0) ); + + QPainterPath path1; + path1.lineTo( 0.0, 0.5 * width ); + path1.lineTo( length - peak, 0.5 * width ); + path1.lineTo( length, 0.0 ); + path1.lineTo( 0.0, 0.0 ); + + QPainterPath arcPath1; + arcPath1.arcTo( knobRect, 0.0, -90.0 ); + + path1 = path1.united( arcPath1 ); + + QPainterPath path2; + path2.lineTo( 0.0, -0.5 * width ); + path2.lineTo( length - peak, -0.5 * width ); + path2.lineTo( length, 0.0 ); + path2.lineTo( 0.0, 0.0 ); + + QPainterPath arcPath2; + arcPath2.arcTo( knobRect, 0.0, 90.0 ); + + path2 = path2.united( arcPath2 ); + + painter->setPen( Qt::NoPen ); + + painter->setBrush( lightColor ); + painter->drawPath( path1 ); + + painter->setBrush( darkColor ); + painter->drawPath( path2 ); +} + +static void qwtDrawArrowNeedle( QPainter *painter, + const QPalette &palette, QPalette::ColorGroup colorGroup, + double length, double width ) +{ + if ( width <= 0 ) + width = qMax( length * 0.06, 9.0 ); + + const double peak = qMax( 2.0, 0.4 * width ); + + QPainterPath path; + path.moveTo( 0.0, 0.5 * width ); + path.lineTo( length - peak, 0.3 * width ); + path.lineTo( length, 0.0 ); + path.lineTo( length - peak, -0.3 * width ); + path.lineTo( 0.0, -0.5 * width ); + + QRectF br = path.boundingRect(); + + QPalette pal( palette.color( QPalette::Mid ) ); + QColor c1 = pal.color( QPalette::Light ); + QColor c2 = pal.color( QPalette::Dark ); + + QLinearGradient gradient( br.topLeft(), br.bottomLeft() ); + gradient.setColorAt( 0.0, c1 ); + gradient.setColorAt( 0.5, c1 ); + gradient.setColorAt( 0.5001, c2 ); + gradient.setColorAt( 1.0, c2 ); + + QPen pen( gradient, 1 ); + pen.setJoinStyle( Qt::MiterJoin ); + + painter->setPen( pen ); + painter->setBrush( palette.brush( colorGroup, QPalette::Mid ) ); + + painter->drawPath( path ); +} + +static void qwtDrawTriangleNeedle( QPainter *painter, + const QPalette &palette, QPalette::ColorGroup colorGroup, + double length ) +{ + const double width = qRound( length / 3.0 ); + + QPainterPath path[4]; + + path[0].lineTo( length, 0.0 ); + path[0].lineTo( 0.0, width / 2 ); + + path[1].lineTo( length, 0.0 ); + path[1].lineTo( 0.0, -width / 2 ); + + path[2].lineTo( -length, 0.0 ); + path[2].lineTo( 0.0, width / 2 ); + + path[3].lineTo( -length, 0.0 ); + path[3].lineTo( 0.0, -width / 2 ); + + + const int colorOffset = 10; + const QColor darkColor = palette.color( colorGroup, QPalette::Dark ); + const QColor lightColor = palette.color( colorGroup, QPalette::Light ); + + QColor color[4]; + color[0] = darkColor.light( 100 + colorOffset ); + color[1] = darkColor.dark( 100 + colorOffset ); + color[2] = lightColor.light( 100 + colorOffset ); + color[3] = lightColor.dark( 100 + colorOffset ); + + painter->setPen( Qt::NoPen ); + + for ( int i = 0; i < 4; i++ ) + { + painter->setBrush( color[i] ); + painter->drawPath( path[i] ); + } +} + +//! Constructor +QwtDialNeedle::QwtDialNeedle(): + d_palette( QApplication::palette() ) +{ +} + +//! Destructor +QwtDialNeedle::~QwtDialNeedle() +{ +} + +/*! + Sets the palette for the needle. + + \param palette New Palette +*/ +void QwtDialNeedle::setPalette( const QPalette &palette ) +{ + d_palette = palette; +} + +/*! + \return the palette of the needle. +*/ +const QPalette &QwtDialNeedle::palette() const +{ + return d_palette; +} + +/*! + Draw the needle + + \param painter Painter + \param center Center of the dial, start position for the needle + \param length Length of the needle + \param direction Direction of the needle, in degrees counter clockwise + \param colorGroup Color group, used for painting +*/ +void QwtDialNeedle::draw( QPainter *painter, + const QPointF ¢er, double length, double direction, + QPalette::ColorGroup colorGroup ) const +{ + painter->save(); + + painter->translate( center ); + painter->rotate( -direction ); + + drawNeedle( painter, length, colorGroup ); + + painter->restore(); +} + +//! Draw the knob +void QwtDialNeedle::drawKnob( QPainter *painter, + double width, const QBrush &brush, bool sunken ) const +{ + QPalette palette( brush.color() ); + + QColor c1 = palette.color( QPalette::Light ); + QColor c2 = palette.color( QPalette::Dark ); + + if ( sunken ) + qSwap( c1, c2 ); + + QRectF rect( 0.0, 0.0, width, width ); + rect.moveCenter( painter->combinedTransform().map( QPointF() ) ); + + QLinearGradient gradient( rect.topLeft(), rect.bottomRight() ); + gradient.setColorAt( 0.0, c1 ); + gradient.setColorAt( 0.3, c1 ); + gradient.setColorAt( 0.7, c2 ); + gradient.setColorAt( 1.0, c2 ); + + painter->save(); + + painter->resetTransform(); + + painter->setPen( QPen( gradient, 1 ) ); + painter->setBrush( brush ); + painter->drawEllipse( rect ); + + painter->restore(); +} + +/*! + Constructor + + \param style Style + \param hasKnob With/Without knob + \param mid Middle color + \param base Base color +*/ +QwtDialSimpleNeedle::QwtDialSimpleNeedle( Style style, bool hasKnob, + const QColor &mid, const QColor &base ): + d_style( style ), + d_hasKnob( hasKnob ), + d_width( -1 ) +{ + QPalette palette; + for ( int i = 0; i < QPalette::NColorGroups; i++ ) + { + palette.setColor( ( QPalette::ColorGroup )i, + QPalette::Mid, mid ); + palette.setColor( ( QPalette::ColorGroup )i, + QPalette::Base, base ); + } + + setPalette( palette ); +} + +/*! + Set the width of the needle + \param width Width + \sa width() +*/ +void QwtDialSimpleNeedle::setWidth( double width ) +{ + d_width = width; +} + +/*! + \return the width of the needle + \sa setWidth() +*/ +double QwtDialSimpleNeedle::width() const +{ + return d_width; +} + +/*! + Draw the needle + + \param painter Painter + \param length Length of the needle + \param colorGroup Color group, used for painting +*/ +void QwtDialSimpleNeedle::drawNeedle( QPainter *painter, + double length, QPalette::ColorGroup colorGroup ) const +{ + double knobWidth = 0.0; + double width = d_width; + + if ( d_style == Arrow ) + { + if ( width <= 0.0 ) + width = qMax(length * 0.06, 6.0); + + qwtDrawArrowNeedle( painter, + palette(), colorGroup, length, width ); + + knobWidth = qMin( width * 2.0, 0.2 * length ); + } + else + { + if ( width <= 0.0 ) + width = 5.0; + + QPen pen ( palette().brush( colorGroup, QPalette::Mid ), width ); + pen.setCapStyle( Qt::FlatCap ); + + painter->setPen( pen ); + painter->drawLine( 0, 0, length, 0 ); + + knobWidth = qMax( width * 3.0, 5.0 ); + } + + if ( d_hasKnob && knobWidth > 0.0 ) + { + drawKnob( painter, knobWidth, + palette().brush( colorGroup, QPalette::Base ), false ); + } +} + +//! Constructor + +QwtCompassMagnetNeedle::QwtCompassMagnetNeedle( Style style, + const QColor &light, const QColor &dark ): + d_style( style ) +{ + QPalette palette; + for ( int i = 0; i < QPalette::NColorGroups; i++ ) + { + palette.setColor( ( QPalette::ColorGroup )i, + QPalette::Light, light ); + palette.setColor( ( QPalette::ColorGroup )i, + QPalette::Dark, dark ); + palette.setColor( ( QPalette::ColorGroup )i, + QPalette::Base, Qt::gray ); + } + + setPalette( palette ); +} + +/*! + Draw the needle + + \param painter Painter + \param length Length of the needle + \param colorGroup Color group, used for painting +*/ +void QwtCompassMagnetNeedle::drawNeedle( QPainter *painter, + double length, QPalette::ColorGroup colorGroup ) const +{ + if ( d_style == ThinStyle ) + { + const double width = qMax( length / 6.0, 3.0 ); + + const int colorOffset = 10; + + const QColor light = palette().color( colorGroup, QPalette::Light ); + const QColor dark = palette().color( colorGroup, QPalette::Dark ); + + qwtDrawShadedPointer( painter, + dark.light( 100 + colorOffset ), + dark.dark( 100 + colorOffset ), + length, width ); + + painter->rotate( 180.0 ); + + qwtDrawShadedPointer( painter, + light.light( 100 + colorOffset ), + light.dark( 100 + colorOffset ), + length, width ); + + const QBrush baseBrush = palette().brush( colorGroup, QPalette::Base ); + drawKnob( painter, width, baseBrush, true ); + } + else + { + qwtDrawTriangleNeedle( painter, palette(), colorGroup, length ); + } +} + +/*! + Constructor + + \param style Arrow style + \param light Light color + \param dark Dark color +*/ +QwtCompassWindArrow::QwtCompassWindArrow( Style style, + const QColor &light, const QColor &dark ): + d_style( style ) +{ + QPalette palette; + for ( int i = 0; i < QPalette::NColorGroups; i++ ) + { + palette.setColor( ( QPalette::ColorGroup )i, + QPalette::Light, light ); + palette.setColor( ( QPalette::ColorGroup )i, + QPalette::Dark, dark ); + } + + setPalette( palette ); +} + +/*! + Draw the needle + + \param painter Painter + \param length Length of the needle + \param colorGroup Color group, used for painting +*/ +void QwtCompassWindArrow::drawNeedle( QPainter *painter, + double length, QPalette::ColorGroup colorGroup ) const +{ + if ( d_style == Style1 ) + qwtDrawStyle1Needle( painter, palette(), colorGroup, length ); + else + qwtDrawStyle2Needle( painter, palette(), colorGroup, length ); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_dial_needle.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_dial_needle.h index 49beebb59..a02a590b2 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_dial_needle.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_dial_needle.h @@ -1,190 +1,190 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_DIAL_NEEDLE_H -#define QWT_DIAL_NEEDLE_H 1 - -#include "qwt_global.h" -#include - -class QPainter; -class QPoint; - -/*! - \brief Base class for needles that can be used in a QwtDial. - - QwtDialNeedle is a pointer that indicates a value by pointing - to a specific direction. - - Qwt is missing a set of good looking needles. - Contributions are very welcome. - - \sa QwtDial, QwtCompass -*/ - -class QWT_EXPORT QwtDialNeedle -{ -public: - QwtDialNeedle(); - virtual ~QwtDialNeedle(); - - virtual void setPalette( const QPalette & ); - const QPalette &palette() const; - - virtual void draw( QPainter *painter, const QPointF ¢er, - double length, double direction, - QPalette::ColorGroup = QPalette::Active ) const; - -protected: - /*! - \brief Draw the needle - - The origin of the needle is at position (0.0, 0.0 ) - pointing in direction 0.0 ( = east ). - - The painter is already initilaized with translation and - rotation. - - \param painter Painter - \param length Length of the needle - \param colorGroup Color group, used for painting - - \sa setPalette(), palette() - */ - virtual void drawNeedle( QPainter *painter, - double length, QPalette::ColorGroup colorGroup ) const = 0; - - virtual void drawKnob( QPainter *, double width, - const QBrush &, bool sunken ) const; - -private: - QPalette d_palette; -}; - -/*! - \brief A needle for dial widgets - - The following colors are used: - - - QPalette::Mid\n - Pointer - - QPalette::Base\n - Knob - - \sa QwtDial, QwtCompass -*/ - -class QWT_EXPORT QwtDialSimpleNeedle: public QwtDialNeedle -{ -public: - //! Style of the needle - enum Style - { - //! Arrow - Arrow, - - //! A straight line from the center - Ray - }; - - QwtDialSimpleNeedle( Style, bool hasKnob = true, - const QColor &mid = Qt::gray, const QColor &base = Qt::darkGray ); - - void setWidth( double width ); - double width() const; - -protected: - virtual void drawNeedle( QPainter *, double length, - QPalette::ColorGroup ) const; - -private: - Style d_style; - bool d_hasKnob; - double d_width; -}; - -/*! - \brief A magnet needle for compass widgets - - A magnet needle points to two opposite directions indicating - north and south. - - The following colors are used: - - QPalette::Light\n - Used for pointing south - - QPalette::Dark\n - Used for pointing north - - QPalette::Base\n - Knob (ThinStyle only) - - \sa QwtDial, QwtCompass -*/ - -class QWT_EXPORT QwtCompassMagnetNeedle: public QwtDialNeedle -{ -public: - //! Style of the needle - enum Style - { - //! A needle with a triangular shape - TriangleStyle, - - //! A thin needle - ThinStyle - }; - - QwtCompassMagnetNeedle( Style = TriangleStyle, - const QColor &light = Qt::white, const QColor &dark = Qt::red ); - -protected: - virtual void drawNeedle( QPainter *, - double length, QPalette::ColorGroup ) const; - -private: - Style d_style; -}; - -/*! - \brief An indicator for the wind direction - - QwtCompassWindArrow shows the direction where the wind comes from. - - - QPalette::Light\n - Used for Style1, or the light half of Style2 - - QPalette::Dark\n - Used for the dark half of Style2 - - \sa QwtDial, QwtCompass -*/ - -class QWT_EXPORT QwtCompassWindArrow: public QwtDialNeedle -{ -public: - //! Style of the arrow - enum Style - { - //! A needle pointing to the center - Style1, - - //! A needle pointing to the center - Style2 - }; - - QwtCompassWindArrow( Style, const QColor &light = Qt::white, - const QColor &dark = Qt::gray ); - -protected: - virtual void drawNeedle( QPainter *, - double length, QPalette::ColorGroup ) const; - -private: - Style d_style; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_DIAL_NEEDLE_H +#define QWT_DIAL_NEEDLE_H 1 + +#include "qwt_global.h" +#include + +class QPainter; +class QPoint; + +/*! + \brief Base class for needles that can be used in a QwtDial. + + QwtDialNeedle is a pointer that indicates a value by pointing + to a specific direction. + + Qwt is missing a set of good looking needles. + Contributions are very welcome. + + \sa QwtDial, QwtCompass +*/ + +class QWT_EXPORT QwtDialNeedle +{ +public: + QwtDialNeedle(); + virtual ~QwtDialNeedle(); + + virtual void setPalette( const QPalette & ); + const QPalette &palette() const; + + virtual void draw( QPainter *painter, const QPointF ¢er, + double length, double direction, + QPalette::ColorGroup = QPalette::Active ) const; + +protected: + /*! + \brief Draw the needle + + The origin of the needle is at position (0.0, 0.0 ) + pointing in direction 0.0 ( = east ). + + The painter is already initilaized with translation and + rotation. + + \param painter Painter + \param length Length of the needle + \param colorGroup Color group, used for painting + + \sa setPalette(), palette() + */ + virtual void drawNeedle( QPainter *painter, + double length, QPalette::ColorGroup colorGroup ) const = 0; + + virtual void drawKnob( QPainter *, double width, + const QBrush &, bool sunken ) const; + +private: + QPalette d_palette; +}; + +/*! + \brief A needle for dial widgets + + The following colors are used: + + - QPalette::Mid\n + Pointer + - QPalette::Base\n + Knob + + \sa QwtDial, QwtCompass +*/ + +class QWT_EXPORT QwtDialSimpleNeedle: public QwtDialNeedle +{ +public: + //! Style of the needle + enum Style + { + //! Arrow + Arrow, + + //! A straight line from the center + Ray + }; + + QwtDialSimpleNeedle( Style, bool hasKnob = true, + const QColor &mid = Qt::gray, const QColor &base = Qt::darkGray ); + + void setWidth( double width ); + double width() const; + +protected: + virtual void drawNeedle( QPainter *, double length, + QPalette::ColorGroup ) const; + +private: + Style d_style; + bool d_hasKnob; + double d_width; +}; + +/*! + \brief A magnet needle for compass widgets + + A magnet needle points to two opposite directions indicating + north and south. + + The following colors are used: + - QPalette::Light\n + Used for pointing south + - QPalette::Dark\n + Used for pointing north + - QPalette::Base\n + Knob (ThinStyle only) + + \sa QwtDial, QwtCompass +*/ + +class QWT_EXPORT QwtCompassMagnetNeedle: public QwtDialNeedle +{ +public: + //! Style of the needle + enum Style + { + //! A needle with a triangular shape + TriangleStyle, + + //! A thin needle + ThinStyle + }; + + QwtCompassMagnetNeedle( Style = TriangleStyle, + const QColor &light = Qt::white, const QColor &dark = Qt::red ); + +protected: + virtual void drawNeedle( QPainter *, + double length, QPalette::ColorGroup ) const; + +private: + Style d_style; +}; + +/*! + \brief An indicator for the wind direction + + QwtCompassWindArrow shows the direction where the wind comes from. + + - QPalette::Light\n + Used for Style1, or the light half of Style2 + - QPalette::Dark\n + Used for the dark half of Style2 + + \sa QwtDial, QwtCompass +*/ + +class QWT_EXPORT QwtCompassWindArrow: public QwtDialNeedle +{ +public: + //! Style of the arrow + enum Style + { + //! A needle pointing to the center + Style1, + + //! A needle pointing to the center + Style2 + }; + + QwtCompassWindArrow( Style, const QColor &light = Qt::white, + const QColor &dark = Qt::gray ); + +protected: + virtual void drawNeedle( QPainter *, + double length, QPalette::ColorGroup ) const; + +private: + Style d_style; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_double_range.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_double_range.cpp index 6e9216457..5e1c02fc2 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_double_range.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_double_range.cpp @@ -1,410 +1,410 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_double_range.h" -#include "qwt_math.h" - -#if QT_VERSION < 0x040601 -#define qFabs(x) ::fabs(x) -#endif - -class QwtDoubleRange::PrivateData -{ -public: - PrivateData(): - minValue( 0.0 ), - maxValue( 0.0 ), - step( 1.0 ), - pageSize( 1 ), - isValid( false ), - value( 0.0 ), - exactValue( 0.0 ), - exactPrevValue( 0.0 ), - prevValue( 0.0 ), - periodic( false ) - { - } - - double minValue; - double maxValue; - double step; - int pageSize; - - bool isValid; - double value; - double exactValue; - double exactPrevValue; - double prevValue; - - bool periodic; -}; - -/*! - The range is initialized to [0.0, 100.0], the - step size to 1.0, and the value to 0.0. -*/ -QwtDoubleRange::QwtDoubleRange() -{ - d_data = new PrivateData(); -} - -//! Destroys the QwtDoubleRange -QwtDoubleRange::~QwtDoubleRange() -{ - delete d_data; -} - -//! Set the value to be valid/invalid -void QwtDoubleRange::setValid( bool isValid ) -{ - if ( isValid != d_data->isValid ) - { - d_data->isValid = isValid; - valueChange(); - } -} - -//! Indicates if the value is valid -bool QwtDoubleRange::isValid() const -{ - return d_data->isValid; -} - -void QwtDoubleRange::setNewValue( double value, bool align ) -{ - d_data->prevValue = d_data->value; - - const double vmin = qMin( d_data->minValue, d_data->maxValue ); - const double vmax = qMax( d_data->minValue, d_data->maxValue ); - - if ( value < vmin ) - { - if ( d_data->periodic && vmin != vmax ) - { - d_data->value = value + - qwtCeilF( ( vmin - value ) / ( vmax - vmin ) ) * ( vmax - vmin ); - } - else - d_data->value = vmin; - } - else if ( value > vmax ) - { - if ( ( d_data->periodic ) && ( vmin != vmax ) ) - { - d_data->value = value - - qwtCeilF( ( value - vmax ) / ( vmax - vmin ) ) * ( vmax - vmin ); - } - else - d_data->value = vmax; - } - else - { - d_data->value = value; - } - - d_data->exactPrevValue = d_data->exactValue; - d_data->exactValue = d_data->value; - - if ( align ) - { - if ( d_data->step != 0.0 ) - { - d_data->value = d_data->minValue + - qRound( ( d_data->value - d_data->minValue ) / d_data->step ) * d_data->step; - } - else - d_data->value = d_data->minValue; - - const double minEps = 1.0e-10; - // correct rounding error at the border - if ( qFabs( d_data->value - d_data->maxValue ) < minEps * qAbs( d_data->step ) ) - d_data->value = d_data->maxValue; - - // correct rounding error if value = 0 - if ( qFabs( d_data->value ) < minEps * qAbs( d_data->step ) ) - d_data->value = 0.0; - } - - if ( !d_data->isValid || d_data->prevValue != d_data->value ) - { - d_data->isValid = true; - valueChange(); - } -} - -/*! - \brief Adjust the value to the closest point in the step raster. - \param x value - \warning The value is clipped when it lies outside the range. - When the range is QwtDoubleRange::periodic, it will - be mapped to a point in the interval such that - \verbatim new value := x + n * (max. value - min. value)\endverbatim - with an integer number n. -*/ -void QwtDoubleRange::fitValue( double x ) -{ - setNewValue( x, true ); -} - - -/*! - \brief Set a new value without adjusting to the step raster - \param x new value - \warning The value is clipped when it lies outside the range. - When the range is QwtDoubleRange::periodic, it will - be mapped to a point in the interval such that - \verbatim new value := x + n * (max. value - min. value)\endverbatim - with an integer number n. -*/ -void QwtDoubleRange::setValue( double x ) -{ - setNewValue( x, false ); -} - -/*! - \brief Specify range and step size - - \param vmin lower boundary of the interval - \param vmax higher boundary of the interval - \param vstep step width - \param pageSize page size in steps - \warning - \li A change of the range changes the value if it lies outside the - new range. The current value - will *not* be adjusted to the new step raster. - \li vmax < vmin is allowed. - \li If the step size is left out or set to zero, it will be - set to 1/100 of the interval length. - \li If the step size has an absurd value, it will be corrected - to a better one. -*/ -void QwtDoubleRange::setRange( - double vmin, double vmax, double vstep, int pageSize ) -{ - const bool rchg = ( d_data->maxValue != vmax || d_data->minValue != vmin ); - - if ( rchg ) - { - d_data->minValue = vmin; - d_data->maxValue = vmax; - } - - // look if the step width has an acceptable - // value or otherwise change it. - setStep( vstep ); - - // limit page size - const int max = - int( qAbs( ( d_data->maxValue - d_data->minValue ) / d_data->step ) ); - d_data->pageSize = qBound( 0, pageSize, max ); - - // If the value lies out of the range, it - // will be changed. Note that it will not be adjusted to - // the new step width. - setNewValue( d_data->value, false ); - - // call notifier after the step width has been - // adjusted. - if ( rchg ) - rangeChange(); -} - -/*! - \brief Change the step raster - \param vstep new step width - \warning The value will \e not be adjusted to the new step raster. -*/ -void QwtDoubleRange::setStep( double vstep ) -{ - const double intv = d_data->maxValue - d_data->minValue; - - double newStep; - if ( vstep == 0.0 ) - { - const double defaultRelStep = 1.0e-2; - newStep = intv * defaultRelStep; - } - else - { - if ( ( intv > 0.0 && vstep < 0.0 ) || ( intv < 0.0 && vstep > 0.0 ) ) - newStep = -vstep; - else - newStep = vstep; - - const double minRelStep = 1.0e-10; - if ( qFabs( newStep ) < qFabs( minRelStep * intv ) ) - newStep = minRelStep * intv; - } - - if ( newStep != d_data->step ) - { - d_data->step = newStep; - stepChange(); - } -} - - -/*! - \brief Make the range periodic - - When the range is periodic, the value will be set to a point - inside the interval such that - - \verbatim point = value + n * width \endverbatim - - if the user tries to set a new value which is outside the range. - If the range is nonperiodic (the default), values outside the - range will be clipped. - - \param tf true for a periodic range -*/ -void QwtDoubleRange::setPeriodic( bool tf ) -{ - d_data->periodic = tf; -} - -/*! - \brief Increment the value by a specified number of steps - \param nSteps Number of steps to increment - \warning As a result of this operation, the new value will always be - adjusted to the step raster. -*/ -void QwtDoubleRange::incValue( int nSteps ) -{ - if ( isValid() ) - setNewValue( d_data->value + double( nSteps ) * d_data->step, true ); -} - -/*! - \brief Increment the value by a specified number of pages - \param nPages Number of pages to increment. - A negative number decrements the value. - \warning The Page size is specified in the constructor. -*/ -void QwtDoubleRange::incPages( int nPages ) -{ - if ( isValid() ) - { - const double off = d_data->step * d_data->pageSize * nPages; - setNewValue( d_data->value + off, true ); - } -} - -/*! - \brief Notify a change of value - - This virtual function is called whenever the value changes. - The default implementation does nothing. -*/ -void QwtDoubleRange::valueChange() -{ -} - - -/*! - \brief Notify a change of the range - - This virtual function is called whenever the range changes. - The default implementation does nothing. -*/ -void QwtDoubleRange::rangeChange() -{ -} - - -/*! - \brief Notify a change of the step size - - This virtual function is called whenever the step size changes. - The default implementation does nothing. -*/ -void QwtDoubleRange::stepChange() -{ -} - -/*! - \return the step size - \sa setStep(), setRange() -*/ -double QwtDoubleRange::step() const -{ - return qAbs( d_data->step ); -} - -/*! - \brief Returns the value of the second border of the range - - maxValue returns the value which has been specified - as the second parameter in QwtDoubleRange::setRange. - - \sa setRange() -*/ -double QwtDoubleRange::maxValue() const -{ - return d_data->maxValue; -} - -/*! - \brief Returns the value at the first border of the range - - minValue returns the value which has been specified - as the first parameter in setRange(). - - \sa setRange() -*/ -double QwtDoubleRange::minValue() const -{ - return d_data->minValue; -} - -/*! - \brief Returns true if the range is periodic - \sa setPeriodic() -*/ -bool QwtDoubleRange::periodic() const -{ - return d_data->periodic; -} - -//! Returns the page size in steps. -int QwtDoubleRange::pageSize() const -{ - return d_data->pageSize; -} - -//! Returns the current value. -double QwtDoubleRange::value() const -{ - return d_data->value; -} - -/*! - \brief Returns the exact value - - The exact value is the value which QwtDoubleRange::value would return - if the value were not adjusted to the step raster. It differs from - the current value only if fitValue() or incValue() have been used before. - This function is intended for internal use in derived classes. -*/ -double QwtDoubleRange::exactValue() const -{ - return d_data->exactValue; -} - -//! Returns the exact previous value -double QwtDoubleRange::exactPrevValue() const -{ - return d_data->exactPrevValue; -} - -//! Returns the previous value -double QwtDoubleRange::prevValue() const -{ - return d_data->prevValue; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_double_range.h" +#include "qwt_math.h" + +#if QT_VERSION < 0x040601 +#define qFabs(x) ::fabs(x) +#endif + +class QwtDoubleRange::PrivateData +{ +public: + PrivateData(): + minValue( 0.0 ), + maxValue( 0.0 ), + step( 1.0 ), + pageSize( 1 ), + isValid( false ), + value( 0.0 ), + exactValue( 0.0 ), + exactPrevValue( 0.0 ), + prevValue( 0.0 ), + periodic( false ) + { + } + + double minValue; + double maxValue; + double step; + int pageSize; + + bool isValid; + double value; + double exactValue; + double exactPrevValue; + double prevValue; + + bool periodic; +}; + +/*! + The range is initialized to [0.0, 100.0], the + step size to 1.0, and the value to 0.0. +*/ +QwtDoubleRange::QwtDoubleRange() +{ + d_data = new PrivateData(); +} + +//! Destroys the QwtDoubleRange +QwtDoubleRange::~QwtDoubleRange() +{ + delete d_data; +} + +//! Set the value to be valid/invalid +void QwtDoubleRange::setValid( bool isValid ) +{ + if ( isValid != d_data->isValid ) + { + d_data->isValid = isValid; + valueChange(); + } +} + +//! Indicates if the value is valid +bool QwtDoubleRange::isValid() const +{ + return d_data->isValid; +} + +void QwtDoubleRange::setNewValue( double value, bool align ) +{ + d_data->prevValue = d_data->value; + + const double vmin = qMin( d_data->minValue, d_data->maxValue ); + const double vmax = qMax( d_data->minValue, d_data->maxValue ); + + if ( value < vmin ) + { + if ( d_data->periodic && vmin != vmax ) + { + d_data->value = value + + qwtCeilF( ( vmin - value ) / ( vmax - vmin ) ) * ( vmax - vmin ); + } + else + d_data->value = vmin; + } + else if ( value > vmax ) + { + if ( ( d_data->periodic ) && ( vmin != vmax ) ) + { + d_data->value = value - + qwtCeilF( ( value - vmax ) / ( vmax - vmin ) ) * ( vmax - vmin ); + } + else + d_data->value = vmax; + } + else + { + d_data->value = value; + } + + d_data->exactPrevValue = d_data->exactValue; + d_data->exactValue = d_data->value; + + if ( align ) + { + if ( d_data->step != 0.0 ) + { + d_data->value = d_data->minValue + + qRound( ( d_data->value - d_data->minValue ) / d_data->step ) * d_data->step; + } + else + d_data->value = d_data->minValue; + + const double minEps = 1.0e-10; + // correct rounding error at the border + if ( qFabs( d_data->value - d_data->maxValue ) < minEps * qAbs( d_data->step ) ) + d_data->value = d_data->maxValue; + + // correct rounding error if value = 0 + if ( qFabs( d_data->value ) < minEps * qAbs( d_data->step ) ) + d_data->value = 0.0; + } + + if ( !d_data->isValid || d_data->prevValue != d_data->value ) + { + d_data->isValid = true; + valueChange(); + } +} + +/*! + \brief Adjust the value to the closest point in the step raster. + \param x value + \warning The value is clipped when it lies outside the range. + When the range is QwtDoubleRange::periodic, it will + be mapped to a point in the interval such that + \verbatim new value := x + n * (max. value - min. value)\endverbatim + with an integer number n. +*/ +void QwtDoubleRange::fitValue( double x ) +{ + setNewValue( x, true ); +} + + +/*! + \brief Set a new value without adjusting to the step raster + \param x new value + \warning The value is clipped when it lies outside the range. + When the range is QwtDoubleRange::periodic, it will + be mapped to a point in the interval such that + \verbatim new value := x + n * (max. value - min. value)\endverbatim + with an integer number n. +*/ +void QwtDoubleRange::setValue( double x ) +{ + setNewValue( x, false ); +} + +/*! + \brief Specify range and step size + + \param vmin lower boundary of the interval + \param vmax higher boundary of the interval + \param vstep step width + \param pageSize page size in steps + \warning + \li A change of the range changes the value if it lies outside the + new range. The current value + will *not* be adjusted to the new step raster. + \li vmax < vmin is allowed. + \li If the step size is left out or set to zero, it will be + set to 1/100 of the interval length. + \li If the step size has an absurd value, it will be corrected + to a better one. +*/ +void QwtDoubleRange::setRange( + double vmin, double vmax, double vstep, int pageSize ) +{ + const bool rchg = ( d_data->maxValue != vmax || d_data->minValue != vmin ); + + if ( rchg ) + { + d_data->minValue = vmin; + d_data->maxValue = vmax; + } + + // look if the step width has an acceptable + // value or otherwise change it. + setStep( vstep ); + + // limit page size + const int max = + int( qAbs( ( d_data->maxValue - d_data->minValue ) / d_data->step ) ); + d_data->pageSize = qBound( 0, pageSize, max ); + + // If the value lies out of the range, it + // will be changed. Note that it will not be adjusted to + // the new step width. + setNewValue( d_data->value, false ); + + // call notifier after the step width has been + // adjusted. + if ( rchg ) + rangeChange(); +} + +/*! + \brief Change the step raster + \param vstep new step width + \warning The value will \e not be adjusted to the new step raster. +*/ +void QwtDoubleRange::setStep( double vstep ) +{ + const double intv = d_data->maxValue - d_data->minValue; + + double newStep; + if ( vstep == 0.0 ) + { + const double defaultRelStep = 1.0e-2; + newStep = intv * defaultRelStep; + } + else + { + if ( ( intv > 0.0 && vstep < 0.0 ) || ( intv < 0.0 && vstep > 0.0 ) ) + newStep = -vstep; + else + newStep = vstep; + + const double minRelStep = 1.0e-10; + if ( qFabs( newStep ) < qFabs( minRelStep * intv ) ) + newStep = minRelStep * intv; + } + + if ( newStep != d_data->step ) + { + d_data->step = newStep; + stepChange(); + } +} + + +/*! + \brief Make the range periodic + + When the range is periodic, the value will be set to a point + inside the interval such that + + \verbatim point = value + n * width \endverbatim + + if the user tries to set a new value which is outside the range. + If the range is nonperiodic (the default), values outside the + range will be clipped. + + \param tf true for a periodic range +*/ +void QwtDoubleRange::setPeriodic( bool tf ) +{ + d_data->periodic = tf; +} + +/*! + \brief Increment the value by a specified number of steps + \param nSteps Number of steps to increment + \warning As a result of this operation, the new value will always be + adjusted to the step raster. +*/ +void QwtDoubleRange::incValue( int nSteps ) +{ + if ( isValid() ) + setNewValue( d_data->value + double( nSteps ) * d_data->step, true ); +} + +/*! + \brief Increment the value by a specified number of pages + \param nPages Number of pages to increment. + A negative number decrements the value. + \warning The Page size is specified in the constructor. +*/ +void QwtDoubleRange::incPages( int nPages ) +{ + if ( isValid() ) + { + const double off = d_data->step * d_data->pageSize * nPages; + setNewValue( d_data->value + off, true ); + } +} + +/*! + \brief Notify a change of value + + This virtual function is called whenever the value changes. + The default implementation does nothing. +*/ +void QwtDoubleRange::valueChange() +{ +} + + +/*! + \brief Notify a change of the range + + This virtual function is called whenever the range changes. + The default implementation does nothing. +*/ +void QwtDoubleRange::rangeChange() +{ +} + + +/*! + \brief Notify a change of the step size + + This virtual function is called whenever the step size changes. + The default implementation does nothing. +*/ +void QwtDoubleRange::stepChange() +{ +} + +/*! + \return the step size + \sa setStep(), setRange() +*/ +double QwtDoubleRange::step() const +{ + return qAbs( d_data->step ); +} + +/*! + \brief Returns the value of the second border of the range + + maxValue returns the value which has been specified + as the second parameter in QwtDoubleRange::setRange. + + \sa setRange() +*/ +double QwtDoubleRange::maxValue() const +{ + return d_data->maxValue; +} + +/*! + \brief Returns the value at the first border of the range + + minValue returns the value which has been specified + as the first parameter in setRange(). + + \sa setRange() +*/ +double QwtDoubleRange::minValue() const +{ + return d_data->minValue; +} + +/*! + \brief Returns true if the range is periodic + \sa setPeriodic() +*/ +bool QwtDoubleRange::periodic() const +{ + return d_data->periodic; +} + +//! Returns the page size in steps. +int QwtDoubleRange::pageSize() const +{ + return d_data->pageSize; +} + +//! Returns the current value. +double QwtDoubleRange::value() const +{ + return d_data->value; +} + +/*! + \brief Returns the exact value + + The exact value is the value which QwtDoubleRange::value would return + if the value were not adjusted to the step raster. It differs from + the current value only if fitValue() or incValue() have been used before. + This function is intended for internal use in derived classes. +*/ +double QwtDoubleRange::exactValue() const +{ + return d_data->exactValue; +} + +//! Returns the exact previous value +double QwtDoubleRange::exactPrevValue() const +{ + return d_data->exactPrevValue; +} + +//! Returns the previous value +double QwtDoubleRange::prevValue() const +{ + return d_data->prevValue; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_double_range.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_double_range.h index bd9ad8332..29f2f66fd 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_double_range.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_double_range.h @@ -1,78 +1,78 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_DOUBLE_RANGE_H -#define QWT_DOUBLE_RANGE_H - -#include "qwt_global.h" - -/*! - \brief A class which controls a value within an interval - - This class is useful as a base class or a member for sliders. - It represents an interval of type double within which a value can - be moved. The value can be either an arbitrary point inside - the interval (see QwtDoubleRange::setValue), or it can be fitted - into a step raster (see QwtDoubleRange::fitValue and - QwtDoubleRange::incValue). - - As a special case, a QwtDoubleRange can be periodic, which means that - a value outside the interval will be mapped to a value inside the - interval when QwtDoubleRange::setValue(), QwtDoubleRange::fitValue(), - QwtDoubleRange::incValue() or QwtDoubleRange::incPages() are called. -*/ - -class QWT_EXPORT QwtDoubleRange -{ -public: - QwtDoubleRange(); - virtual ~QwtDoubleRange(); - - void setRange( double vmin, double vmax, - double vstep = 0.0, int pagesize = 1 ); - - void setValid( bool ); - bool isValid() const; - - virtual void setValue( double ); - double value() const; - - void setPeriodic( bool tf ); - bool periodic() const; - - void setStep( double ); - double step() const; - - double maxValue() const; - double minValue() const; - - int pageSize() const; - - virtual void incValue( int ); - virtual void incPages( int ); - virtual void fitValue( double ); - -protected: - - double exactValue() const; - double exactPrevValue() const; - double prevValue() const; - - virtual void valueChange(); - virtual void stepChange(); - virtual void rangeChange(); - -private: - void setNewValue( double value, bool align = false ); - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_DOUBLE_RANGE_H +#define QWT_DOUBLE_RANGE_H + +#include "qwt_global.h" + +/*! + \brief A class which controls a value within an interval + + This class is useful as a base class or a member for sliders. + It represents an interval of type double within which a value can + be moved. The value can be either an arbitrary point inside + the interval (see QwtDoubleRange::setValue), or it can be fitted + into a step raster (see QwtDoubleRange::fitValue and + QwtDoubleRange::incValue). + + As a special case, a QwtDoubleRange can be periodic, which means that + a value outside the interval will be mapped to a value inside the + interval when QwtDoubleRange::setValue(), QwtDoubleRange::fitValue(), + QwtDoubleRange::incValue() or QwtDoubleRange::incPages() are called. +*/ + +class QWT_EXPORT QwtDoubleRange +{ +public: + QwtDoubleRange(); + virtual ~QwtDoubleRange(); + + void setRange( double vmin, double vmax, + double vstep = 0.0, int pagesize = 1 ); + + void setValid( bool ); + bool isValid() const; + + virtual void setValue( double ); + double value() const; + + void setPeriodic( bool tf ); + bool periodic() const; + + void setStep( double ); + double step() const; + + double maxValue() const; + double minValue() const; + + int pageSize() const; + + virtual void incValue( int ); + virtual void incPages( int ); + virtual void fitValue( double ); + +protected: + + double exactValue() const; + double exactPrevValue() const; + double prevValue() const; + + virtual void valueChange(); + virtual void stepChange(); + virtual void rangeChange(); + +private: + void setNewValue( double value, bool align = false ); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_dyngrid_layout.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_dyngrid_layout.cpp index 26ccac2f8..cd621dcfc 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_dyngrid_layout.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_dyngrid_layout.cpp @@ -1,571 +1,571 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_dyngrid_layout.h" -#include "qwt_math.h" -#include -#include - -class QwtDynGridLayout::PrivateData -{ -public: - PrivateData(): - isDirty( true ) - { - } - - void updateLayoutCache(); - - mutable QList itemList; - - uint maxCols; - uint numRows; - uint numCols; - - Qt::Orientations expanding; - - bool isDirty; - QVector itemSizeHints; -}; - -void QwtDynGridLayout::PrivateData::updateLayoutCache() -{ - itemSizeHints.resize( itemList.count() ); - - int index = 0; - - for ( QList::iterator it = itemList.begin(); - it != itemList.end(); ++it, index++ ) - { - itemSizeHints[ index ] = ( *it )->sizeHint(); - } - - isDirty = false; -} - -/*! - \param parent Parent widget - \param margin Margin - \param spacing Spacing -*/ - -QwtDynGridLayout::QwtDynGridLayout( QWidget *parent, - int margin, int spacing ): - QLayout( parent ) -{ - init(); - - setSpacing( spacing ); - setMargin( margin ); -} - -/*! - \param spacing Spacing -*/ - -QwtDynGridLayout::QwtDynGridLayout( int spacing ) -{ - init(); - setSpacing( spacing ); -} - -/*! - Initialize the layout with default values. -*/ -void QwtDynGridLayout::init() -{ - d_data = new QwtDynGridLayout::PrivateData; - d_data->maxCols = d_data->numRows = d_data->numCols = 0; - d_data->expanding = 0; -} - -//! Destructor - -QwtDynGridLayout::~QwtDynGridLayout() -{ - for ( int i = 0; i < d_data->itemList.size(); i++ ) - delete d_data->itemList[i]; - - delete d_data; -} - -//! Invalidate all internal caches -void QwtDynGridLayout::invalidate() -{ - d_data->isDirty = true; - QLayout::invalidate(); -} - -/*! - Limit the number of columns. - \param maxCols upper limit, 0 means unlimited - \sa maxCols() -*/ -void QwtDynGridLayout::setMaxCols( uint maxCols ) -{ - d_data->maxCols = maxCols; -} - -/*! - Return the upper limit for the number of columns. - 0 means unlimited, what is the default. - \sa setMaxCols() -*/ - -uint QwtDynGridLayout::maxCols() const -{ - return d_data->maxCols; -} - -//! Adds item to the next free position. - -void QwtDynGridLayout::addItem( QLayoutItem *item ) -{ - d_data->itemList.append( item ); - invalidate(); -} - -/*! - \return true if this layout is empty. -*/ - -bool QwtDynGridLayout::isEmpty() const -{ - return d_data->itemList.isEmpty(); -} - -/*! - \return number of layout items -*/ - -uint QwtDynGridLayout::itemCount() const -{ - return d_data->itemList.count(); -} - -/*! - Find the item at a spcific index - - \param index Index - \sa takeAt() -*/ -QLayoutItem *QwtDynGridLayout::itemAt( int index ) const -{ - if ( index < 0 || index >= d_data->itemList.count() ) - return NULL; - - return d_data->itemList.at( index ); -} - -/*! - Find the item at a spcific index and remove it from the layout - - \param index Index - \sa itemAt() -*/ -QLayoutItem *QwtDynGridLayout::takeAt( int index ) -{ - if ( index < 0 || index >= d_data->itemList.count() ) - return NULL; - - d_data->isDirty = true; - return d_data->itemList.takeAt( index ); -} - -//! \return Number of items in the layout -int QwtDynGridLayout::count() const -{ - return d_data->itemList.count(); -} - -/*! - Set whether this layout can make use of more space than sizeHint(). - A value of Qt::Vertical or Qt::Horizontal means that it wants to grow in only - one dimension, while Qt::Vertical | Qt::Horizontal means that it wants - to grow in both dimensions. The default value is 0. - - \param expanding Or'd orientations - \sa expandingDirections() -*/ -void QwtDynGridLayout::setExpandingDirections( Qt::Orientations expanding ) -{ - d_data->expanding = expanding; -} - -/*! - Returns whether this layout can make use of more space than sizeHint(). - A value of Qt::Vertical or Qt::Horizontal means that it wants to grow in only - one dimension, while Qt::Vertical | Qt::Horizontal means that it wants - to grow in both dimensions. - \sa setExpandingDirections() -*/ -Qt::Orientations QwtDynGridLayout::expandingDirections() const -{ - return d_data->expanding; -} - -/*! - Reorganizes columns and rows and resizes managed widgets within - the rectangle rect. - - \param rect Layout geometry -*/ -void QwtDynGridLayout::setGeometry( const QRect &rect ) -{ - QLayout::setGeometry( rect ); - - if ( isEmpty() ) - return; - - d_data->numCols = columnsForWidth( rect.width() ); - d_data->numRows = itemCount() / d_data->numCols; - if ( itemCount() % d_data->numCols ) - d_data->numRows++; - - QList itemGeometries = layoutItems( rect, d_data->numCols ); - - int index = 0; - for ( QList::iterator it = d_data->itemList.begin(); - it != d_data->itemList.end(); ++it ) - { - QWidget *w = ( *it )->widget(); - if ( w ) - { - w->setGeometry( itemGeometries[index] ); - index++; - } - } -} - -/*! - Calculate the number of columns for a given width. It tries to - use as many columns as possible (limited by maxCols()) - - \param width Available width for all columns - \sa maxCols(), setMaxCols() -*/ - -uint QwtDynGridLayout::columnsForWidth( int width ) const -{ - if ( isEmpty() ) - return 0; - - const int maxCols = ( d_data->maxCols > 0 ) ? d_data->maxCols : itemCount(); - if ( maxRowWidth( maxCols ) <= width ) - return maxCols; - - for ( int numCols = 2; numCols <= maxCols; numCols++ ) - { - const int rowWidth = maxRowWidth( numCols ); - if ( rowWidth > width ) - return numCols - 1; - } - - return 1; // At least 1 column -} - -/*! - Calculate the width of a layout for a given number of - columns. - - \param numCols Given number of columns - \param itemWidth Array of the width hints for all items -*/ -int QwtDynGridLayout::maxRowWidth( int numCols ) const -{ - int col; - - QVector colWidth( numCols ); - for ( col = 0; col < numCols; col++ ) - colWidth[col] = 0; - - if ( d_data->isDirty ) - d_data->updateLayoutCache(); - - for ( int index = 0; - index < d_data->itemSizeHints.count(); index++ ) - { - col = index % numCols; - colWidth[col] = qMax( colWidth[col], - d_data->itemSizeHints[int( index )].width() ); - } - - int rowWidth = 2 * margin() + ( numCols - 1 ) * spacing(); - for ( col = 0; col < numCols; col++ ) - rowWidth += colWidth[col]; - - return rowWidth; -} - -/*! - \return the maximum width of all layout items -*/ -int QwtDynGridLayout::maxItemWidth() const -{ - if ( isEmpty() ) - return 0; - - if ( d_data->isDirty ) - d_data->updateLayoutCache(); - - int w = 0; - for ( int i = 0; i < d_data->itemSizeHints.count(); i++ ) - { - const int itemW = d_data->itemSizeHints[i].width(); - if ( itemW > w ) - w = itemW; - } - - return w; -} - -/*! - Calculate the geometries of the layout items for a layout - with numCols columns and a given rect. - - \param rect Rect where to place the items - \param numCols Number of columns - \return item geometries -*/ - -QList QwtDynGridLayout::layoutItems( const QRect &rect, - uint numCols ) const -{ - QList itemGeometries; - if ( numCols == 0 || isEmpty() ) - return itemGeometries; - - uint numRows = itemCount() / numCols; - if ( numRows % itemCount() ) - numRows++; - - QVector rowHeight( numRows ); - QVector colWidth( numCols ); - - layoutGrid( numCols, rowHeight, colWidth ); - - bool expandH, expandV; - expandH = expandingDirections() & Qt::Horizontal; - expandV = expandingDirections() & Qt::Vertical; - - if ( expandH || expandV ) - stretchGrid( rect, numCols, rowHeight, colWidth ); - - const int maxCols = d_data->maxCols; - d_data->maxCols = numCols; - const QRect alignedRect = alignmentRect( rect ); - d_data->maxCols = maxCols; - - const int xOffset = expandH ? 0 : alignedRect.x(); - const int yOffset = expandV ? 0 : alignedRect.y(); - - QVector colX( numCols ); - QVector rowY( numRows ); - - const int xySpace = spacing(); - - rowY[0] = yOffset + margin(); - for ( int r = 1; r < ( int )numRows; r++ ) - rowY[r] = rowY[r-1] + rowHeight[r-1] + xySpace; - - colX[0] = xOffset + margin(); - for ( int c = 1; c < ( int )numCols; c++ ) - colX[c] = colX[c-1] + colWidth[c-1] + xySpace; - - const int itemCount = d_data->itemList.size(); - for ( int i = 0; i < itemCount; i++ ) - { - const int row = i / numCols; - const int col = i % numCols; - - QRect itemGeometry( colX[col], rowY[row], - colWidth[col], rowHeight[row] ); - itemGeometries.append( itemGeometry ); - } - - return itemGeometries; -} - - -/*! - Calculate the dimensions for the columns and rows for a grid - of numCols columns. - - \param numCols Number of columns. - \param rowHeight Array where to fill in the calculated row heights. - \param colWidth Array where to fill in the calculated column widths. -*/ - -void QwtDynGridLayout::layoutGrid( uint numCols, - QVector& rowHeight, QVector& colWidth ) const -{ - if ( numCols <= 0 ) - return; - - if ( d_data->isDirty ) - d_data->updateLayoutCache(); - - for ( uint index = 0; - index < ( uint )d_data->itemSizeHints.count(); index++ ) - { - const int row = index / numCols; - const int col = index % numCols; - - const QSize &size = d_data->itemSizeHints[int( index )]; - - rowHeight[row] = ( col == 0 ) - ? size.height() : qMax( rowHeight[row], size.height() ); - colWidth[col] = ( row == 0 ) - ? size.width() : qMax( colWidth[col], size.width() ); - } -} - -/*! - \return true: QwtDynGridLayout implements heightForWidth. - \sa heightForWidth() -*/ -bool QwtDynGridLayout::hasHeightForWidth() const -{ - return true; -} - -/*! - \return The preferred height for this layout, given the width w. - \sa hasHeightForWidth() -*/ -int QwtDynGridLayout::heightForWidth( int width ) const -{ - if ( isEmpty() ) - return 0; - - const uint numCols = columnsForWidth( width ); - uint numRows = itemCount() / numCols; - if ( itemCount() % numCols ) - numRows++; - - QVector rowHeight( numRows ); - QVector colWidth( numCols ); - - layoutGrid( numCols, rowHeight, colWidth ); - - int h = 2 * margin() + ( numRows - 1 ) * spacing(); - for ( int row = 0; row < ( int )numRows; row++ ) - h += rowHeight[row]; - - return h; -} - -/*! - Stretch columns in case of expanding() & QSizePolicy::Horizontal and - rows in case of expanding() & QSizePolicy::Vertical to fill the entire - rect. Rows and columns are stretched with the same factor. - - \sa setExpanding(), expanding() -*/ -void QwtDynGridLayout::stretchGrid( const QRect &rect, - uint numCols, QVector& rowHeight, QVector& colWidth ) const -{ - if ( numCols == 0 || isEmpty() ) - return; - - bool expandH, expandV; - expandH = expandingDirections() & Qt::Horizontal; - expandV = expandingDirections() & Qt::Vertical; - - if ( expandH ) - { - int xDelta = rect.width() - 2 * margin() - ( numCols - 1 ) * spacing(); - for ( int col = 0; col < ( int )numCols; col++ ) - xDelta -= colWidth[col]; - - if ( xDelta > 0 ) - { - for ( int col = 0; col < ( int )numCols; col++ ) - { - const int space = xDelta / ( numCols - col ); - colWidth[col] += space; - xDelta -= space; - } - } - } - - if ( expandV ) - { - uint numRows = itemCount() / numCols; - if ( itemCount() % numCols ) - numRows++; - - int yDelta = rect.height() - 2 * margin() - ( numRows - 1 ) * spacing(); - for ( int row = 0; row < ( int )numRows; row++ ) - yDelta -= rowHeight[row]; - - if ( yDelta > 0 ) - { - for ( int row = 0; row < ( int )numRows; row++ ) - { - const int space = yDelta / ( numRows - row ); - rowHeight[row] += space; - yDelta -= space; - } - } - } -} - -/*! - Return the size hint. If maxCols() > 0 it is the size for - a grid with maxCols() columns, otherwise it is the size for - a grid with only one row. - - \sa maxCols(), setMaxCols() -*/ -QSize QwtDynGridLayout::sizeHint() const -{ - if ( isEmpty() ) - return QSize(); - - const uint numCols = ( d_data->maxCols > 0 ) ? d_data->maxCols : itemCount(); - uint numRows = itemCount() / numCols; - if ( itemCount() % numCols ) - numRows++; - - QVector rowHeight( numRows ); - QVector colWidth( numCols ); - - layoutGrid( numCols, rowHeight, colWidth ); - - int h = 2 * margin() + ( numRows - 1 ) * spacing(); - for ( int row = 0; row < ( int )numRows; row++ ) - h += rowHeight[row]; - - int w = 2 * margin() + ( numCols - 1 ) * spacing(); - for ( int col = 0; col < ( int )numCols; col++ ) - w += colWidth[col]; - - return QSize( w, h ); -} - -/*! - \return Number of rows of the current layout. - \sa numCols() - \warning The number of rows might change whenever the geometry changes -*/ -uint QwtDynGridLayout::numRows() const -{ - return d_data->numRows; -} - -/*! - \return Number of columns of the current layout. - \sa numRows() - \warning The number of columns might change whenever the geometry changes -*/ -uint QwtDynGridLayout::numCols() const -{ - return d_data->numCols; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_dyngrid_layout.h" +#include "qwt_math.h" +#include +#include + +class QwtDynGridLayout::PrivateData +{ +public: + PrivateData(): + isDirty( true ) + { + } + + void updateLayoutCache(); + + mutable QList itemList; + + uint maxCols; + uint numRows; + uint numCols; + + Qt::Orientations expanding; + + bool isDirty; + QVector itemSizeHints; +}; + +void QwtDynGridLayout::PrivateData::updateLayoutCache() +{ + itemSizeHints.resize( itemList.count() ); + + int index = 0; + + for ( QList::iterator it = itemList.begin(); + it != itemList.end(); ++it, index++ ) + { + itemSizeHints[ index ] = ( *it )->sizeHint(); + } + + isDirty = false; +} + +/*! + \param parent Parent widget + \param margin Margin + \param spacing Spacing +*/ + +QwtDynGridLayout::QwtDynGridLayout( QWidget *parent, + int margin, int spacing ): + QLayout( parent ) +{ + init(); + + setSpacing( spacing ); + setMargin( margin ); +} + +/*! + \param spacing Spacing +*/ + +QwtDynGridLayout::QwtDynGridLayout( int spacing ) +{ + init(); + setSpacing( spacing ); +} + +/*! + Initialize the layout with default values. +*/ +void QwtDynGridLayout::init() +{ + d_data = new QwtDynGridLayout::PrivateData; + d_data->maxCols = d_data->numRows = d_data->numCols = 0; + d_data->expanding = 0; +} + +//! Destructor + +QwtDynGridLayout::~QwtDynGridLayout() +{ + for ( int i = 0; i < d_data->itemList.size(); i++ ) + delete d_data->itemList[i]; + + delete d_data; +} + +//! Invalidate all internal caches +void QwtDynGridLayout::invalidate() +{ + d_data->isDirty = true; + QLayout::invalidate(); +} + +/*! + Limit the number of columns. + \param maxCols upper limit, 0 means unlimited + \sa maxCols() +*/ +void QwtDynGridLayout::setMaxCols( uint maxCols ) +{ + d_data->maxCols = maxCols; +} + +/*! + Return the upper limit for the number of columns. + 0 means unlimited, what is the default. + \sa setMaxCols() +*/ + +uint QwtDynGridLayout::maxCols() const +{ + return d_data->maxCols; +} + +//! Adds item to the next free position. + +void QwtDynGridLayout::addItem( QLayoutItem *item ) +{ + d_data->itemList.append( item ); + invalidate(); +} + +/*! + \return true if this layout is empty. +*/ + +bool QwtDynGridLayout::isEmpty() const +{ + return d_data->itemList.isEmpty(); +} + +/*! + \return number of layout items +*/ + +uint QwtDynGridLayout::itemCount() const +{ + return d_data->itemList.count(); +} + +/*! + Find the item at a spcific index + + \param index Index + \sa takeAt() +*/ +QLayoutItem *QwtDynGridLayout::itemAt( int index ) const +{ + if ( index < 0 || index >= d_data->itemList.count() ) + return NULL; + + return d_data->itemList.at( index ); +} + +/*! + Find the item at a spcific index and remove it from the layout + + \param index Index + \sa itemAt() +*/ +QLayoutItem *QwtDynGridLayout::takeAt( int index ) +{ + if ( index < 0 || index >= d_data->itemList.count() ) + return NULL; + + d_data->isDirty = true; + return d_data->itemList.takeAt( index ); +} + +//! \return Number of items in the layout +int QwtDynGridLayout::count() const +{ + return d_data->itemList.count(); +} + +/*! + Set whether this layout can make use of more space than sizeHint(). + A value of Qt::Vertical or Qt::Horizontal means that it wants to grow in only + one dimension, while Qt::Vertical | Qt::Horizontal means that it wants + to grow in both dimensions. The default value is 0. + + \param expanding Or'd orientations + \sa expandingDirections() +*/ +void QwtDynGridLayout::setExpandingDirections( Qt::Orientations expanding ) +{ + d_data->expanding = expanding; +} + +/*! + Returns whether this layout can make use of more space than sizeHint(). + A value of Qt::Vertical or Qt::Horizontal means that it wants to grow in only + one dimension, while Qt::Vertical | Qt::Horizontal means that it wants + to grow in both dimensions. + \sa setExpandingDirections() +*/ +Qt::Orientations QwtDynGridLayout::expandingDirections() const +{ + return d_data->expanding; +} + +/*! + Reorganizes columns and rows and resizes managed widgets within + the rectangle rect. + + \param rect Layout geometry +*/ +void QwtDynGridLayout::setGeometry( const QRect &rect ) +{ + QLayout::setGeometry( rect ); + + if ( isEmpty() ) + return; + + d_data->numCols = columnsForWidth( rect.width() ); + d_data->numRows = itemCount() / d_data->numCols; + if ( itemCount() % d_data->numCols ) + d_data->numRows++; + + QList itemGeometries = layoutItems( rect, d_data->numCols ); + + int index = 0; + for ( QList::iterator it = d_data->itemList.begin(); + it != d_data->itemList.end(); ++it ) + { + QWidget *w = ( *it )->widget(); + if ( w ) + { + w->setGeometry( itemGeometries[index] ); + index++; + } + } +} + +/*! + Calculate the number of columns for a given width. It tries to + use as many columns as possible (limited by maxCols()) + + \param width Available width for all columns + \sa maxCols(), setMaxCols() +*/ + +uint QwtDynGridLayout::columnsForWidth( int width ) const +{ + if ( isEmpty() ) + return 0; + + const int maxCols = ( d_data->maxCols > 0 ) ? d_data->maxCols : itemCount(); + if ( maxRowWidth( maxCols ) <= width ) + return maxCols; + + for ( int numCols = 2; numCols <= maxCols; numCols++ ) + { + const int rowWidth = maxRowWidth( numCols ); + if ( rowWidth > width ) + return numCols - 1; + } + + return 1; // At least 1 column +} + +/*! + Calculate the width of a layout for a given number of + columns. + + \param numCols Given number of columns + \param itemWidth Array of the width hints for all items +*/ +int QwtDynGridLayout::maxRowWidth( int numCols ) const +{ + int col; + + QVector colWidth( numCols ); + for ( col = 0; col < numCols; col++ ) + colWidth[col] = 0; + + if ( d_data->isDirty ) + d_data->updateLayoutCache(); + + for ( int index = 0; + index < d_data->itemSizeHints.count(); index++ ) + { + col = index % numCols; + colWidth[col] = qMax( colWidth[col], + d_data->itemSizeHints[int( index )].width() ); + } + + int rowWidth = 2 * margin() + ( numCols - 1 ) * spacing(); + for ( col = 0; col < numCols; col++ ) + rowWidth += colWidth[col]; + + return rowWidth; +} + +/*! + \return the maximum width of all layout items +*/ +int QwtDynGridLayout::maxItemWidth() const +{ + if ( isEmpty() ) + return 0; + + if ( d_data->isDirty ) + d_data->updateLayoutCache(); + + int w = 0; + for ( int i = 0; i < d_data->itemSizeHints.count(); i++ ) + { + const int itemW = d_data->itemSizeHints[i].width(); + if ( itemW > w ) + w = itemW; + } + + return w; +} + +/*! + Calculate the geometries of the layout items for a layout + with numCols columns and a given rect. + + \param rect Rect where to place the items + \param numCols Number of columns + \return item geometries +*/ + +QList QwtDynGridLayout::layoutItems( const QRect &rect, + uint numCols ) const +{ + QList itemGeometries; + if ( numCols == 0 || isEmpty() ) + return itemGeometries; + + uint numRows = itemCount() / numCols; + if ( numRows % itemCount() ) + numRows++; + + QVector rowHeight( numRows ); + QVector colWidth( numCols ); + + layoutGrid( numCols, rowHeight, colWidth ); + + bool expandH, expandV; + expandH = expandingDirections() & Qt::Horizontal; + expandV = expandingDirections() & Qt::Vertical; + + if ( expandH || expandV ) + stretchGrid( rect, numCols, rowHeight, colWidth ); + + const int maxCols = d_data->maxCols; + d_data->maxCols = numCols; + const QRect alignedRect = alignmentRect( rect ); + d_data->maxCols = maxCols; + + const int xOffset = expandH ? 0 : alignedRect.x(); + const int yOffset = expandV ? 0 : alignedRect.y(); + + QVector colX( numCols ); + QVector rowY( numRows ); + + const int xySpace = spacing(); + + rowY[0] = yOffset + margin(); + for ( int r = 1; r < ( int )numRows; r++ ) + rowY[r] = rowY[r-1] + rowHeight[r-1] + xySpace; + + colX[0] = xOffset + margin(); + for ( int c = 1; c < ( int )numCols; c++ ) + colX[c] = colX[c-1] + colWidth[c-1] + xySpace; + + const int itemCount = d_data->itemList.size(); + for ( int i = 0; i < itemCount; i++ ) + { + const int row = i / numCols; + const int col = i % numCols; + + QRect itemGeometry( colX[col], rowY[row], + colWidth[col], rowHeight[row] ); + itemGeometries.append( itemGeometry ); + } + + return itemGeometries; +} + + +/*! + Calculate the dimensions for the columns and rows for a grid + of numCols columns. + + \param numCols Number of columns. + \param rowHeight Array where to fill in the calculated row heights. + \param colWidth Array where to fill in the calculated column widths. +*/ + +void QwtDynGridLayout::layoutGrid( uint numCols, + QVector& rowHeight, QVector& colWidth ) const +{ + if ( numCols <= 0 ) + return; + + if ( d_data->isDirty ) + d_data->updateLayoutCache(); + + for ( uint index = 0; + index < ( uint )d_data->itemSizeHints.count(); index++ ) + { + const int row = index / numCols; + const int col = index % numCols; + + const QSize &size = d_data->itemSizeHints[int( index )]; + + rowHeight[row] = ( col == 0 ) + ? size.height() : qMax( rowHeight[row], size.height() ); + colWidth[col] = ( row == 0 ) + ? size.width() : qMax( colWidth[col], size.width() ); + } +} + +/*! + \return true: QwtDynGridLayout implements heightForWidth. + \sa heightForWidth() +*/ +bool QwtDynGridLayout::hasHeightForWidth() const +{ + return true; +} + +/*! + \return The preferred height for this layout, given the width w. + \sa hasHeightForWidth() +*/ +int QwtDynGridLayout::heightForWidth( int width ) const +{ + if ( isEmpty() ) + return 0; + + const uint numCols = columnsForWidth( width ); + uint numRows = itemCount() / numCols; + if ( itemCount() % numCols ) + numRows++; + + QVector rowHeight( numRows ); + QVector colWidth( numCols ); + + layoutGrid( numCols, rowHeight, colWidth ); + + int h = 2 * margin() + ( numRows - 1 ) * spacing(); + for ( int row = 0; row < ( int )numRows; row++ ) + h += rowHeight[row]; + + return h; +} + +/*! + Stretch columns in case of expanding() & QSizePolicy::Horizontal and + rows in case of expanding() & QSizePolicy::Vertical to fill the entire + rect. Rows and columns are stretched with the same factor. + + \sa setExpanding(), expanding() +*/ +void QwtDynGridLayout::stretchGrid( const QRect &rect, + uint numCols, QVector& rowHeight, QVector& colWidth ) const +{ + if ( numCols == 0 || isEmpty() ) + return; + + bool expandH, expandV; + expandH = expandingDirections() & Qt::Horizontal; + expandV = expandingDirections() & Qt::Vertical; + + if ( expandH ) + { + int xDelta = rect.width() - 2 * margin() - ( numCols - 1 ) * spacing(); + for ( int col = 0; col < ( int )numCols; col++ ) + xDelta -= colWidth[col]; + + if ( xDelta > 0 ) + { + for ( int col = 0; col < ( int )numCols; col++ ) + { + const int space = xDelta / ( numCols - col ); + colWidth[col] += space; + xDelta -= space; + } + } + } + + if ( expandV ) + { + uint numRows = itemCount() / numCols; + if ( itemCount() % numCols ) + numRows++; + + int yDelta = rect.height() - 2 * margin() - ( numRows - 1 ) * spacing(); + for ( int row = 0; row < ( int )numRows; row++ ) + yDelta -= rowHeight[row]; + + if ( yDelta > 0 ) + { + for ( int row = 0; row < ( int )numRows; row++ ) + { + const int space = yDelta / ( numRows - row ); + rowHeight[row] += space; + yDelta -= space; + } + } + } +} + +/*! + Return the size hint. If maxCols() > 0 it is the size for + a grid with maxCols() columns, otherwise it is the size for + a grid with only one row. + + \sa maxCols(), setMaxCols() +*/ +QSize QwtDynGridLayout::sizeHint() const +{ + if ( isEmpty() ) + return QSize(); + + const uint numCols = ( d_data->maxCols > 0 ) ? d_data->maxCols : itemCount(); + uint numRows = itemCount() / numCols; + if ( itemCount() % numCols ) + numRows++; + + QVector rowHeight( numRows ); + QVector colWidth( numCols ); + + layoutGrid( numCols, rowHeight, colWidth ); + + int h = 2 * margin() + ( numRows - 1 ) * spacing(); + for ( int row = 0; row < ( int )numRows; row++ ) + h += rowHeight[row]; + + int w = 2 * margin() + ( numCols - 1 ) * spacing(); + for ( int col = 0; col < ( int )numCols; col++ ) + w += colWidth[col]; + + return QSize( w, h ); +} + +/*! + \return Number of rows of the current layout. + \sa numCols() + \warning The number of rows might change whenever the geometry changes +*/ +uint QwtDynGridLayout::numRows() const +{ + return d_data->numRows; +} + +/*! + \return Number of columns of the current layout. + \sa numRows() + \warning The number of columns might change whenever the geometry changes +*/ +uint QwtDynGridLayout::numCols() const +{ + return d_data->numCols; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_dyngrid_layout.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_dyngrid_layout.h index c4262b849..0b835f03a 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_dyngrid_layout.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_dyngrid_layout.h @@ -1,83 +1,83 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_DYNGRID_LAYOUT_H -#define QWT_DYNGRID_LAYOUT_H - -#include "qwt_global.h" -#include -#include -#include - -/*! - \brief The QwtDynGridLayout class lays out widgets in a grid, - adjusting the number of columns and rows to the current size. - - QwtDynGridLayout takes the space it gets, divides it up into rows and - columns, and puts each of the widgets it manages into the correct cell(s). - It lays out as many number of columns as possible (limited by maxCols()). -*/ - -class QWT_EXPORT QwtDynGridLayout : public QLayout -{ - Q_OBJECT -public: - explicit QwtDynGridLayout( QWidget *, int margin = 0, int space = -1 ); - explicit QwtDynGridLayout( int space = -1 ); - - virtual ~QwtDynGridLayout(); - - virtual void invalidate(); - - void setMaxCols( uint maxCols ); - uint maxCols() const; - - uint numRows () const; - uint numCols () const; - - virtual void addItem( QLayoutItem * ); - - virtual QLayoutItem *itemAt( int index ) const; - virtual QLayoutItem *takeAt( int index ); - virtual int count() const; - - void setExpandingDirections( Qt::Orientations ); - virtual Qt::Orientations expandingDirections() const; - QList layoutItems( const QRect &, uint numCols ) const; - - virtual int maxItemWidth() const; - - virtual void setGeometry( const QRect &rect ); - - virtual bool hasHeightForWidth() const; - virtual int heightForWidth( int ) const; - - virtual QSize sizeHint() const; - - virtual bool isEmpty() const; - uint itemCount() const; - - virtual uint columnsForWidth( int width ) const; - -protected: - - void layoutGrid( uint numCols, - QVector& rowHeight, QVector& colWidth ) const; - void stretchGrid( const QRect &rect, uint numCols, - QVector& rowHeight, QVector& colWidth ) const; - -private: - void init(); - int maxRowWidth( int numCols ) const; - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_DYNGRID_LAYOUT_H +#define QWT_DYNGRID_LAYOUT_H + +#include "qwt_global.h" +#include +#include +#include + +/*! + \brief The QwtDynGridLayout class lays out widgets in a grid, + adjusting the number of columns and rows to the current size. + + QwtDynGridLayout takes the space it gets, divides it up into rows and + columns, and puts each of the widgets it manages into the correct cell(s). + It lays out as many number of columns as possible (limited by maxCols()). +*/ + +class QWT_EXPORT QwtDynGridLayout : public QLayout +{ + Q_OBJECT +public: + explicit QwtDynGridLayout( QWidget *, int margin = 0, int space = -1 ); + explicit QwtDynGridLayout( int space = -1 ); + + virtual ~QwtDynGridLayout(); + + virtual void invalidate(); + + void setMaxCols( uint maxCols ); + uint maxCols() const; + + uint numRows () const; + uint numCols () const; + + virtual void addItem( QLayoutItem * ); + + virtual QLayoutItem *itemAt( int index ) const; + virtual QLayoutItem *takeAt( int index ); + virtual int count() const; + + void setExpandingDirections( Qt::Orientations ); + virtual Qt::Orientations expandingDirections() const; + QList layoutItems( const QRect &, uint numCols ) const; + + virtual int maxItemWidth() const; + + virtual void setGeometry( const QRect &rect ); + + virtual bool hasHeightForWidth() const; + virtual int heightForWidth( int ) const; + + virtual QSize sizeHint() const; + + virtual bool isEmpty() const; + uint itemCount() const; + + virtual uint columnsForWidth( int width ) const; + +protected: + + void layoutGrid( uint numCols, + QVector& rowHeight, QVector& colWidth ) const; + void stretchGrid( const QRect &rect, uint numCols, + QVector& rowHeight, QVector& colWidth ) const; + +private: + void init(); + int maxRowWidth( int numCols ) const; + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_event_pattern.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_event_pattern.cpp index 82d844508..24bcbbcc1 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_event_pattern.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_event_pattern.cpp @@ -1,274 +1,274 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_event_pattern.h" -#include - -/*! - Constructor - - \sa MousePatternCode, KeyPatternCode -*/ - -QwtEventPattern::QwtEventPattern(): - d_mousePattern( MousePatternCount ), - d_keyPattern( KeyPatternCount ) -{ - initKeyPattern(); - initMousePattern( 3 ); -} - -//! Destructor -QwtEventPattern::~QwtEventPattern() -{ -} - -/*! - Set default mouse patterns, depending on the number of mouse buttons - - \param numButtons Number of mouse buttons ( <= 3 ) - \sa MousePatternCode -*/ -void QwtEventPattern::initMousePattern( int numButtons ) -{ - const int altButton = Qt::AltModifier; - const int controlButton = Qt::ControlModifier; - const int shiftButton = Qt::ShiftModifier; - - d_mousePattern.resize( MousePatternCount ); - - switch ( numButtons ) - { - case 1: - { - setMousePattern( MouseSelect1, Qt::LeftButton ); - setMousePattern( MouseSelect2, Qt::LeftButton, controlButton ); - setMousePattern( MouseSelect3, Qt::LeftButton, altButton ); - break; - } - case 2: - { - setMousePattern( MouseSelect1, Qt::LeftButton ); - setMousePattern( MouseSelect2, Qt::RightButton ); - setMousePattern( MouseSelect3, Qt::LeftButton, altButton ); - break; - } - default: - { - setMousePattern( MouseSelect1, Qt::LeftButton ); - setMousePattern( MouseSelect2, Qt::RightButton ); - setMousePattern( MouseSelect3, Qt::MidButton ); - } - } - for ( int i = 0; i < 3; i++ ) - { - setMousePattern( MouseSelect4 + i, - d_mousePattern[MouseSelect1 + i].button, - d_mousePattern[MouseSelect1 + i].state | shiftButton ); - } -} - -/*! - Set default mouse patterns. - - \sa KeyPatternCode -*/ -void QwtEventPattern::initKeyPattern() -{ - d_keyPattern.resize( KeyPatternCount ); - - setKeyPattern( KeySelect1, Qt::Key_Return ); - setKeyPattern( KeySelect2, Qt::Key_Space ); - setKeyPattern( KeyAbort, Qt::Key_Escape ); - - setKeyPattern( KeyLeft, Qt::Key_Left ); - setKeyPattern( KeyRight, Qt::Key_Right ); - setKeyPattern( KeyUp, Qt::Key_Up ); - setKeyPattern( KeyDown, Qt::Key_Down ); - - setKeyPattern( KeyRedo, Qt::Key_Plus ); - setKeyPattern( KeyUndo, Qt::Key_Minus ); - setKeyPattern( KeyHome, Qt::Key_Escape ); -} - -/*! - Change one mouse pattern - - \param pattern Index of the pattern - \param button Button - \param state State - - \sa QMouseEvent -*/ -void QwtEventPattern::setMousePattern( uint pattern, int button, int state ) -{ - if ( pattern < ( uint )d_mousePattern.count() ) - { - d_mousePattern[int( pattern )].button = button; - d_mousePattern[int( pattern )].state = state; - } -} - -/*! - Change one key pattern - - \param pattern Index of the pattern - \param key Key - \param state State - - \sa QKeyEvent -*/ -void QwtEventPattern::setKeyPattern( uint pattern, int key, int state ) -{ - if ( pattern < ( uint )d_keyPattern.count() ) - { - d_keyPattern[int( pattern )].key = key; - d_keyPattern[int( pattern )].state = state; - } -} - -//! Change the mouse event patterns -void QwtEventPattern::setMousePattern( const QVector &pattern ) -{ - d_mousePattern = pattern; -} - -//! Change the key event patterns -void QwtEventPattern::setKeyPattern( const QVector &pattern ) -{ - d_keyPattern = pattern; -} - -//! Return mouse patterns -const QVector & -QwtEventPattern::mousePattern() const -{ - return d_mousePattern; -} - -//! Return key patterns -const QVector & -QwtEventPattern::keyPattern() const -{ - return d_keyPattern; -} - -//! Return ,ouse patterns -QVector &QwtEventPattern::mousePattern() -{ - return d_mousePattern; -} - -//! Return Key patterns -QVector &QwtEventPattern::keyPattern() -{ - return d_keyPattern; -} - -/*! - \brief Compare a mouse event with an event pattern. - - A mouse event matches the pattern when both have the same button - value and in the state value the same key flags(Qt::KeyButtonMask) - are set. - - \param pattern Index of the event pattern - \param event Mouse event - \return true if matches - - \sa keyMatch() -*/ -bool QwtEventPattern::mouseMatch( uint pattern, - const QMouseEvent *event ) const -{ - bool ok = false; - - if ( event && pattern < ( uint )d_mousePattern.count() ) - ok = mouseMatch( d_mousePattern[int( pattern )], event ); - - return ok; -} - -/*! - \brief Compare a mouse event with an event pattern. - - A mouse event matches the pattern when both have the same button - value and in the state value the same key flags(Qt::KeyButtonMask) - are set. - - \param pattern Mouse event pattern - \param event Mouse event - \return true if matches - - \sa keyMatch() -*/ - -bool QwtEventPattern::mouseMatch( const MousePattern &pattern, - const QMouseEvent *event ) const -{ - if ( event->button() != pattern.button ) - return false; - - const bool matched = - ( event->modifiers() & Qt::KeyboardModifierMask ) == - ( int )( pattern.state & Qt::KeyboardModifierMask ); - - return matched; -} - -/*! - \brief Compare a key event with an event pattern. - - A key event matches the pattern when both have the same key - value and in the state value the same key flags (Qt::KeyButtonMask) - are set. - - \param pattern Index of the event pattern - \param event Key event - \return true if matches - - \sa mouseMatch() -*/ -bool QwtEventPattern::keyMatch( uint pattern, - const QKeyEvent *event ) const -{ - bool ok = false; - - if ( event && pattern < ( uint )d_keyPattern.count() ) - ok = keyMatch( d_keyPattern[int( pattern )], event ); - - return ok; -} - -/*! - \brief Compare a key event with an event pattern. - - A key event matches the pattern when both have the same key - value and in the state value the same key flags (Qt::KeyButtonMask) - are set. - - \param pattern Key event pattern - \param event Key event - \return true if matches - - \sa mouseMatch() -*/ - -bool QwtEventPattern::keyMatch( - const KeyPattern &pattern, const QKeyEvent *event ) const -{ - if ( event->key() != pattern.key ) - return false; - - const bool matched = - ( event->modifiers() & Qt::KeyboardModifierMask ) == - ( int )( pattern.state & Qt::KeyboardModifierMask ); - - return matched; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_event_pattern.h" +#include + +/*! + Constructor + + \sa MousePatternCode, KeyPatternCode +*/ + +QwtEventPattern::QwtEventPattern(): + d_mousePattern( MousePatternCount ), + d_keyPattern( KeyPatternCount ) +{ + initKeyPattern(); + initMousePattern( 3 ); +} + +//! Destructor +QwtEventPattern::~QwtEventPattern() +{ +} + +/*! + Set default mouse patterns, depending on the number of mouse buttons + + \param numButtons Number of mouse buttons ( <= 3 ) + \sa MousePatternCode +*/ +void QwtEventPattern::initMousePattern( int numButtons ) +{ + const int altButton = Qt::AltModifier; + const int controlButton = Qt::ControlModifier; + const int shiftButton = Qt::ShiftModifier; + + d_mousePattern.resize( MousePatternCount ); + + switch ( numButtons ) + { + case 1: + { + setMousePattern( MouseSelect1, Qt::LeftButton ); + setMousePattern( MouseSelect2, Qt::LeftButton, controlButton ); + setMousePattern( MouseSelect3, Qt::LeftButton, altButton ); + break; + } + case 2: + { + setMousePattern( MouseSelect1, Qt::LeftButton ); + setMousePattern( MouseSelect2, Qt::RightButton ); + setMousePattern( MouseSelect3, Qt::LeftButton, altButton ); + break; + } + default: + { + setMousePattern( MouseSelect1, Qt::LeftButton ); + setMousePattern( MouseSelect2, Qt::RightButton ); + setMousePattern( MouseSelect3, Qt::MidButton ); + } + } + for ( int i = 0; i < 3; i++ ) + { + setMousePattern( MouseSelect4 + i, + d_mousePattern[MouseSelect1 + i].button, + d_mousePattern[MouseSelect1 + i].state | shiftButton ); + } +} + +/*! + Set default mouse patterns. + + \sa KeyPatternCode +*/ +void QwtEventPattern::initKeyPattern() +{ + d_keyPattern.resize( KeyPatternCount ); + + setKeyPattern( KeySelect1, Qt::Key_Return ); + setKeyPattern( KeySelect2, Qt::Key_Space ); + setKeyPattern( KeyAbort, Qt::Key_Escape ); + + setKeyPattern( KeyLeft, Qt::Key_Left ); + setKeyPattern( KeyRight, Qt::Key_Right ); + setKeyPattern( KeyUp, Qt::Key_Up ); + setKeyPattern( KeyDown, Qt::Key_Down ); + + setKeyPattern( KeyRedo, Qt::Key_Plus ); + setKeyPattern( KeyUndo, Qt::Key_Minus ); + setKeyPattern( KeyHome, Qt::Key_Escape ); +} + +/*! + Change one mouse pattern + + \param pattern Index of the pattern + \param button Button + \param state State + + \sa QMouseEvent +*/ +void QwtEventPattern::setMousePattern( uint pattern, int button, int state ) +{ + if ( pattern < ( uint )d_mousePattern.count() ) + { + d_mousePattern[int( pattern )].button = button; + d_mousePattern[int( pattern )].state = state; + } +} + +/*! + Change one key pattern + + \param pattern Index of the pattern + \param key Key + \param state State + + \sa QKeyEvent +*/ +void QwtEventPattern::setKeyPattern( uint pattern, int key, int state ) +{ + if ( pattern < ( uint )d_keyPattern.count() ) + { + d_keyPattern[int( pattern )].key = key; + d_keyPattern[int( pattern )].state = state; + } +} + +//! Change the mouse event patterns +void QwtEventPattern::setMousePattern( const QVector &pattern ) +{ + d_mousePattern = pattern; +} + +//! Change the key event patterns +void QwtEventPattern::setKeyPattern( const QVector &pattern ) +{ + d_keyPattern = pattern; +} + +//! Return mouse patterns +const QVector & +QwtEventPattern::mousePattern() const +{ + return d_mousePattern; +} + +//! Return key patterns +const QVector & +QwtEventPattern::keyPattern() const +{ + return d_keyPattern; +} + +//! Return ,ouse patterns +QVector &QwtEventPattern::mousePattern() +{ + return d_mousePattern; +} + +//! Return Key patterns +QVector &QwtEventPattern::keyPattern() +{ + return d_keyPattern; +} + +/*! + \brief Compare a mouse event with an event pattern. + + A mouse event matches the pattern when both have the same button + value and in the state value the same key flags(Qt::KeyButtonMask) + are set. + + \param pattern Index of the event pattern + \param event Mouse event + \return true if matches + + \sa keyMatch() +*/ +bool QwtEventPattern::mouseMatch( uint pattern, + const QMouseEvent *event ) const +{ + bool ok = false; + + if ( event && pattern < ( uint )d_mousePattern.count() ) + ok = mouseMatch( d_mousePattern[int( pattern )], event ); + + return ok; +} + +/*! + \brief Compare a mouse event with an event pattern. + + A mouse event matches the pattern when both have the same button + value and in the state value the same key flags(Qt::KeyButtonMask) + are set. + + \param pattern Mouse event pattern + \param event Mouse event + \return true if matches + + \sa keyMatch() +*/ + +bool QwtEventPattern::mouseMatch( const MousePattern &pattern, + const QMouseEvent *event ) const +{ + if ( event->button() != pattern.button ) + return false; + + const bool matched = + ( event->modifiers() & Qt::KeyboardModifierMask ) == + ( int )( pattern.state & Qt::KeyboardModifierMask ); + + return matched; +} + +/*! + \brief Compare a key event with an event pattern. + + A key event matches the pattern when both have the same key + value and in the state value the same key flags (Qt::KeyButtonMask) + are set. + + \param pattern Index of the event pattern + \param event Key event + \return true if matches + + \sa mouseMatch() +*/ +bool QwtEventPattern::keyMatch( uint pattern, + const QKeyEvent *event ) const +{ + bool ok = false; + + if ( event && pattern < ( uint )d_keyPattern.count() ) + ok = keyMatch( d_keyPattern[int( pattern )], event ); + + return ok; +} + +/*! + \brief Compare a key event with an event pattern. + + A key event matches the pattern when both have the same key + value and in the state value the same key flags (Qt::KeyButtonMask) + are set. + + \param pattern Key event pattern + \param event Key event + \return true if matches + + \sa mouseMatch() +*/ + +bool QwtEventPattern::keyMatch( + const KeyPattern &pattern, const QKeyEvent *event ) const +{ + if ( event->key() != pattern.key ) + return false; + + const bool matched = + ( event->modifiers() & Qt::KeyboardModifierMask ) == + ( int )( pattern.state & Qt::KeyboardModifierMask ); + + return matched; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_event_pattern.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_event_pattern.h index 5aaaaea0a..a88f5f4a9 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_event_pattern.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_event_pattern.h @@ -1,225 +1,225 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_EVENT_PATTERN -#define QWT_EVENT_PATTERN 1 - -#include "qwt_global.h" -#include -#include - -class QMouseEvent; -class QKeyEvent; - -/*! - \brief A collection of event patterns - - QwtEventPattern introduces an level of indirection for mouse and - keyboard inputs. Those are represented by symbolic names, so - the application code can be configured by individual mappings. - - \sa QwtPicker, QwtPickerMachine, QwtPlotZoomer -*/ -class QWT_EXPORT QwtEventPattern -{ -public: - /*! - \brief Symbolic mouse input codes - - The default initialization for 3 button mice is: - - MouseSelect1\n - Qt::LeftButton - - MouseSelect2\n - Qt::RightButton - - MouseSelect3\n - Qt::MidButton - - MouseSelect4\n - Qt::LeftButton + Qt::ShiftButton - - MouseSelect5\n - Qt::RightButton + Qt::ShiftButton - - MouseSelect6\n - Qt::MidButton + Qt::ShiftButton - - The default initialization for 2 button mice is: - - MouseSelect1\n - Qt::LeftButton - - MouseSelect2\n - Qt::RightButton - - MouseSelect3\n - Qt::LeftButton + Qt::AltButton - - MouseSelect4\n - Qt::LeftButton + Qt::ShiftButton - - MouseSelect5\n - Qt::RightButton + Qt::ShiftButton - - MouseSelect6\n - Qt::LeftButton + Qt::AltButton + Qt::ShiftButton - - The default initialization for 1 button mice is: - - MouseSelect1\n - Qt::LeftButton - - MouseSelect2\n - Qt::LeftButton + Qt::ControlButton - - MouseSelect3\n - Qt::LeftButton + Qt::AltButton - - MouseSelect4\n - Qt::LeftButton + Qt::ShiftButton - - MouseSelect5\n - Qt::LeftButton + Qt::ControlButton + Qt::ShiftButton - - MouseSelect6\n - Qt::LeftButton + Qt::AltButton + Qt::ShiftButton - - \sa initMousePattern() - */ - - enum MousePatternCode - { - MouseSelect1, - MouseSelect2, - MouseSelect3, - MouseSelect4, - MouseSelect5, - MouseSelect6, - - MousePatternCount - }; - - /*! - \brief Symbolic keyboard input codes - - Default initialization: - - KeySelect1\n - Qt::Key_Return - - KeySelect2\n - Qt::Key_Space - - KeyAbort\n - Qt::Key_Escape - - - KeyLeft\n - Qt::Key_Left - - KeyRight\n - Qt::Key_Right - - KeyUp\n - Qt::Key_Up - - KeyDown\n - Qt::Key_Down - - - KeyUndo\n - Qt::Key_Minus - - KeyRedo\n - Qt::Key_Plus - - KeyHome\n - Qt::Key_Escape - */ - enum KeyPatternCode - { - KeySelect1, - KeySelect2, - KeyAbort, - - KeyLeft, - KeyRight, - KeyUp, - KeyDown, - - KeyRedo, - KeyUndo, - KeyHome, - - KeyPatternCount - }; - - //! A pattern for mouse events - class MousePattern - { - public: - //! Constructor - MousePattern( int btn = Qt::NoButton, int st = Qt::NoButton ) - { - button = btn; - state = st; - } - - //! Button code - int button; - - //! State - int state; - }; - - //! A pattern for key events - class KeyPattern - { - public: - //! Constructor - KeyPattern( int k = 0, int st = Qt::NoButton ) - { - key = k; - state = st; - } - - //! Key code - int key; - - //! State - int state; - }; - - QwtEventPattern(); - virtual ~QwtEventPattern(); - - void initMousePattern( int numButtons ); - void initKeyPattern(); - - void setMousePattern( uint pattern, int button, int state = Qt::NoButton ); - void setKeyPattern( uint pattern, int key, int state = Qt::NoButton ); - - void setMousePattern( const QVector & ); - void setKeyPattern( const QVector & ); - - const QVector &mousePattern() const; - const QVector &keyPattern() const; - - QVector &mousePattern(); - QVector &keyPattern(); - - bool mouseMatch( uint pattern, const QMouseEvent * ) const; - bool keyMatch( uint pattern, const QKeyEvent * ) const; - -protected: - virtual bool mouseMatch( const MousePattern &, const QMouseEvent * ) const; - virtual bool keyMatch( const KeyPattern &, const QKeyEvent * ) const; - -private: - -#if defined(_MSC_VER) -#pragma warning(push) -#pragma warning(disable: 4251) -#endif - QVector d_mousePattern; - QVector d_keyPattern; -#if defined(_MSC_VER) -#pragma warning(pop) -#endif -}; - -//! Compare operator -inline bool operator==( QwtEventPattern::MousePattern b1, - QwtEventPattern::MousePattern b2 ) -{ - return b1.button == b2.button && b1.state == b2.state; -} - -//! Compare operator -inline bool operator==( QwtEventPattern::KeyPattern b1, - QwtEventPattern::KeyPattern b2 ) -{ - return b1.key == b2.key && b1.state == b2.state; -} - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_EVENT_PATTERN +#define QWT_EVENT_PATTERN 1 + +#include "qwt_global.h" +#include +#include + +class QMouseEvent; +class QKeyEvent; + +/*! + \brief A collection of event patterns + + QwtEventPattern introduces an level of indirection for mouse and + keyboard inputs. Those are represented by symbolic names, so + the application code can be configured by individual mappings. + + \sa QwtPicker, QwtPickerMachine, QwtPlotZoomer +*/ +class QWT_EXPORT QwtEventPattern +{ +public: + /*! + \brief Symbolic mouse input codes + + The default initialization for 3 button mice is: + - MouseSelect1\n + Qt::LeftButton + - MouseSelect2\n + Qt::RightButton + - MouseSelect3\n + Qt::MidButton + - MouseSelect4\n + Qt::LeftButton + Qt::ShiftButton + - MouseSelect5\n + Qt::RightButton + Qt::ShiftButton + - MouseSelect6\n + Qt::MidButton + Qt::ShiftButton + + The default initialization for 2 button mice is: + - MouseSelect1\n + Qt::LeftButton + - MouseSelect2\n + Qt::RightButton + - MouseSelect3\n + Qt::LeftButton + Qt::AltButton + - MouseSelect4\n + Qt::LeftButton + Qt::ShiftButton + - MouseSelect5\n + Qt::RightButton + Qt::ShiftButton + - MouseSelect6\n + Qt::LeftButton + Qt::AltButton + Qt::ShiftButton + + The default initialization for 1 button mice is: + - MouseSelect1\n + Qt::LeftButton + - MouseSelect2\n + Qt::LeftButton + Qt::ControlButton + - MouseSelect3\n + Qt::LeftButton + Qt::AltButton + - MouseSelect4\n + Qt::LeftButton + Qt::ShiftButton + - MouseSelect5\n + Qt::LeftButton + Qt::ControlButton + Qt::ShiftButton + - MouseSelect6\n + Qt::LeftButton + Qt::AltButton + Qt::ShiftButton + + \sa initMousePattern() + */ + + enum MousePatternCode + { + MouseSelect1, + MouseSelect2, + MouseSelect3, + MouseSelect4, + MouseSelect5, + MouseSelect6, + + MousePatternCount + }; + + /*! + \brief Symbolic keyboard input codes + + Default initialization: + - KeySelect1\n + Qt::Key_Return + - KeySelect2\n + Qt::Key_Space + - KeyAbort\n + Qt::Key_Escape + + - KeyLeft\n + Qt::Key_Left + - KeyRight\n + Qt::Key_Right + - KeyUp\n + Qt::Key_Up + - KeyDown\n + Qt::Key_Down + + - KeyUndo\n + Qt::Key_Minus + - KeyRedo\n + Qt::Key_Plus + - KeyHome\n + Qt::Key_Escape + */ + enum KeyPatternCode + { + KeySelect1, + KeySelect2, + KeyAbort, + + KeyLeft, + KeyRight, + KeyUp, + KeyDown, + + KeyRedo, + KeyUndo, + KeyHome, + + KeyPatternCount + }; + + //! A pattern for mouse events + class MousePattern + { + public: + //! Constructor + MousePattern( int btn = Qt::NoButton, int st = Qt::NoButton ) + { + button = btn; + state = st; + } + + //! Button code + int button; + + //! State + int state; + }; + + //! A pattern for key events + class KeyPattern + { + public: + //! Constructor + KeyPattern( int k = 0, int st = Qt::NoButton ) + { + key = k; + state = st; + } + + //! Key code + int key; + + //! State + int state; + }; + + QwtEventPattern(); + virtual ~QwtEventPattern(); + + void initMousePattern( int numButtons ); + void initKeyPattern(); + + void setMousePattern( uint pattern, int button, int state = Qt::NoButton ); + void setKeyPattern( uint pattern, int key, int state = Qt::NoButton ); + + void setMousePattern( const QVector & ); + void setKeyPattern( const QVector & ); + + const QVector &mousePattern() const; + const QVector &keyPattern() const; + + QVector &mousePattern(); + QVector &keyPattern(); + + bool mouseMatch( uint pattern, const QMouseEvent * ) const; + bool keyMatch( uint pattern, const QKeyEvent * ) const; + +protected: + virtual bool mouseMatch( const MousePattern &, const QMouseEvent * ) const; + virtual bool keyMatch( const KeyPattern &, const QKeyEvent * ) const; + +private: + +#if defined(_MSC_VER) +#pragma warning(push) +#pragma warning(disable: 4251) +#endif + QVector d_mousePattern; + QVector d_keyPattern; +#if defined(_MSC_VER) +#pragma warning(pop) +#endif +}; + +//! Compare operator +inline bool operator==( QwtEventPattern::MousePattern b1, + QwtEventPattern::MousePattern b2 ) +{ + return b1.button == b2.button && b1.state == b2.state; +} + +//! Compare operator +inline bool operator==( QwtEventPattern::KeyPattern b1, + QwtEventPattern::KeyPattern b2 ) +{ + return b1.key == b2.key && b1.state == b2.state; +} + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_global.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_global.h index 59974b5a9..f9a0efa1f 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_global.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_global.h @@ -1,44 +1,44 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_GLOBAL_H -#define QWT_GLOBAL_H - -#include - -// QWT_VERSION is (major << 16) + (minor << 8) + patch. - -#define QWT_VERSION 0x060001 -#define QWT_VERSION_STR "6.0.1" - -#if defined(Q_WS_WIN) || defined(Q_WS_S60) - -#if defined(_MSC_VER) /* MSVC Compiler */ -/* template-class specialization 'identifier' is already instantiated */ -#pragma warning(disable: 4660) -#endif // _MSC_VER - - -#if defined(QWT_MAKEDLL) // create a Qwt DLL library -#define QWT_EXPORT Q_DECL_EXPORT -#define QWT_TEMPLATEDLL -#else // use a Qwt DLL library -#define QWT_EXPORT Q_DECL_IMPORT -#endif - - -#endif // Q_WS_WIN || Q_WS_S60 - -#ifndef QWT_EXPORT -#define QWT_EXPORT -#endif - -// #define QWT_NO_COMPAT 1 // disable withdrawn functionality - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_GLOBAL_H +#define QWT_GLOBAL_H + +#include + +// QWT_VERSION is (major << 16) + (minor << 8) + patch. + +#define QWT_VERSION 0x060001 +#define QWT_VERSION_STR "6.0.1" + +#if defined(Q_WS_WIN) || defined(Q_WS_S60) + +#if defined(_MSC_VER) /* MSVC Compiler */ +/* template-class specialization 'identifier' is already instantiated */ +#pragma warning(disable: 4660) +#endif // _MSC_VER + + +#if defined(QWT_MAKEDLL) // create a Qwt DLL library +#define QWT_EXPORT Q_DECL_EXPORT +#define QWT_TEMPLATEDLL +#else // use a Qwt DLL library +#define QWT_EXPORT Q_DECL_IMPORT +#endif + + +#endif // Q_WS_WIN || Q_WS_S60 + +#ifndef QWT_EXPORT +#define QWT_EXPORT +#endif + +// #define QWT_NO_COMPAT 1 // disable withdrawn functionality + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_interval.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_interval.cpp index 59de21b42..f8355671e 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_interval.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_interval.cpp @@ -1,334 +1,334 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_interval.h" -#include "qwt_math.h" -#include - -/*! - \brief Normalize the limits of the interval - - If maxValue() < minValue() the limits will be inverted. - \return Normalized interval - - \sa isValid(), inverted() -*/ -QwtInterval QwtInterval::normalized() const -{ - if ( d_minValue > d_maxValue ) - { - return inverted(); - } - if ( d_minValue == d_maxValue && d_borderFlags == ExcludeMinimum ) - { - return inverted(); - } - - return *this; -} - -/*! - Invert the limits of the interval - \return Inverted interval - \sa normalized() -*/ -QwtInterval QwtInterval::inverted() const -{ - BorderFlags borderFlags = IncludeBorders; - if ( d_borderFlags & ExcludeMinimum ) - borderFlags |= ExcludeMaximum; - if ( d_borderFlags & ExcludeMaximum ) - borderFlags |= ExcludeMinimum; - - return QwtInterval( d_maxValue, d_minValue, borderFlags ); -} - -/*! - Test if a value is inside an interval - - \param value Value - \return true, if value >= minValue() && value <= maxValue() -*/ -bool QwtInterval::contains( double value ) const -{ - if ( !isValid() ) - return false; - - if ( value < d_minValue || value > d_maxValue ) - return false; - - if ( value == d_minValue && d_borderFlags & ExcludeMinimum ) - return false; - - if ( value == d_maxValue && d_borderFlags & ExcludeMaximum ) - return false; - - return true; -} - -//! Unite 2 intervals -QwtInterval QwtInterval::unite( const QwtInterval &other ) const -{ - /* - If one of the intervals is invalid return the other one. - If both are invalid return an invalid default interval - */ - if ( !isValid() ) - { - if ( !other.isValid() ) - return QwtInterval(); - else - return other; - } - if ( !other.isValid() ) - return *this; - - QwtInterval united; - BorderFlags flags = IncludeBorders; - - // minimum - if ( d_minValue < other.minValue() ) - { - united.setMinValue( d_minValue ); - flags &= d_borderFlags & ExcludeMinimum; - } - else if ( other.minValue() < d_minValue ) - { - united.setMinValue( other.minValue() ); - flags &= other.borderFlags() & ExcludeMinimum; - } - else // d_minValue == other.minValue() - { - united.setMinValue( d_minValue ); - flags &= ( d_borderFlags & other.borderFlags() ) & ExcludeMinimum; - } - - // maximum - if ( d_maxValue > other.maxValue() ) - { - united.setMaxValue( d_maxValue ); - flags &= d_borderFlags & ExcludeMaximum; - } - else if ( other.maxValue() > d_maxValue ) - { - united.setMaxValue( other.maxValue() ); - flags &= other.borderFlags() & ExcludeMaximum; - } - else // d_maxValue == other.maxValue() ) - { - united.setMaxValue( d_maxValue ); - flags &= d_borderFlags & other.borderFlags() & ExcludeMaximum; - } - - united.setBorderFlags( flags ); - return united; -} - -//! Intersect 2 intervals -QwtInterval QwtInterval::intersect( const QwtInterval &other ) const -{ - if ( !other.isValid() || !isValid() ) - return QwtInterval(); - - QwtInterval i1 = *this; - QwtInterval i2 = other; - - // swap i1/i2, so that the minimum of i1 - // is smaller then the minimum of i2 - - if ( i1.minValue() > i2.minValue() ) - { - qSwap( i1, i2 ); - } - else if ( i1.minValue() == i2.minValue() ) - { - if ( i1.borderFlags() & ExcludeMinimum ) - qSwap( i1, i2 ); - } - - if ( i1.maxValue() < i2.minValue() ) - { - return QwtInterval(); - } - - if ( i1.maxValue() == i2.minValue() ) - { - if ( i1.borderFlags() & ExcludeMaximum || - i2.borderFlags() & ExcludeMinimum ) - { - return QwtInterval(); - } - } - - QwtInterval intersected; - BorderFlags flags = IncludeBorders; - - intersected.setMinValue( i2.minValue() ); - flags |= i2.borderFlags() & ExcludeMinimum; - - if ( i1.maxValue() < i2.maxValue() ) - { - intersected.setMaxValue( i1.maxValue() ); - flags |= i1.borderFlags() & ExcludeMaximum; - } - else if ( i2.maxValue() < i1.maxValue() ) - { - intersected.setMaxValue( i2.maxValue() ); - flags |= i2.borderFlags() & ExcludeMaximum; - } - else // i1.maxValue() == i2.maxValue() - { - intersected.setMaxValue( i1.maxValue() ); - flags |= i1.borderFlags() & i2.borderFlags() & ExcludeMaximum; - } - - intersected.setBorderFlags( flags ); - return intersected; -} - -//! Unites this interval with the given interval. -QwtInterval& QwtInterval::operator|=( const QwtInterval & interval ) -{ - *this = *this | interval; - return *this; -} - -//! Intersects this interval with the given interval. -QwtInterval& QwtInterval::operator&=( const QwtInterval & interval ) -{ - *this = *this & interval; - return *this; -} - -/*! - Test if two intervals overlap -*/ -bool QwtInterval::intersects( const QwtInterval &other ) const -{ - if ( !isValid() || !other.isValid() ) - return false; - - QwtInterval i1 = *this; - QwtInterval i2 = other; - - // swap i1/i2, so that the minimum of i1 - // is smaller then the minimum of i2 - - if ( i1.minValue() > i2.minValue() ) - { - qSwap( i1, i2 ); - } - else if ( i1.minValue() == i2.minValue() && - i1.borderFlags() & ExcludeMinimum ) - { - qSwap( i1, i2 ); - } - - if ( i1.maxValue() > i2.minValue() ) - { - return true; - } - if ( i1.maxValue() == i2.minValue() ) - { - return !( ( i1.borderFlags() & ExcludeMaximum ) || - ( i2.borderFlags() & ExcludeMinimum ) ); - } - return false; -} - -/*! - Adjust the limit that is closer to value, so that value becomes - the center of the interval. - - \param value Center - \return Interval with value as center -*/ -QwtInterval QwtInterval::symmetrize( double value ) const -{ - if ( !isValid() ) - return *this; - - const double delta = - qMax( qAbs( value - d_maxValue ), qAbs( value - d_minValue ) ); - - return QwtInterval( value - delta, value + delta ); -} - -/*! - Limit the interval, keeping the border modes - - \param lowerBound Lower limit - \param upperBound Upper limit - - \return Limited interval -*/ -QwtInterval QwtInterval::limited( double lowerBound, double upperBound ) const -{ - if ( !isValid() || lowerBound > upperBound ) - return QwtInterval(); - - double minValue = qMax( d_minValue, lowerBound ); - minValue = qMin( minValue, upperBound ); - - double maxValue = qMax( d_maxValue, lowerBound ); - maxValue = qMin( maxValue, upperBound ); - - return QwtInterval( minValue, maxValue, d_borderFlags ); -} - -/*! - Extend the interval - - If value is below minValue, value becomes the lower limit. - If value is above maxValue, value becomes the upper limit. - - extend has no effect for invalid intervals - - \param value Value - \sa isValid() -*/ -QwtInterval QwtInterval::extend( double value ) const -{ - if ( !isValid() ) - return *this; - - return QwtInterval( qMin( value, d_minValue ), - qMax( value, d_maxValue ), d_borderFlags ); -} - -/*! - Extend an interval - - \param value Value - \return Reference of the extended interval - - \sa extend() -*/ -QwtInterval& QwtInterval::operator|=( double value ) -{ - *this = *this | value; - return *this; -} - -#ifndef QT_NO_DEBUG_STREAM - -QDebug operator<<( QDebug debug, const QwtInterval &interval ) -{ - const int flags = interval.borderFlags(); - - debug.nospace() << "QwtInterval(" - << ( ( flags & QwtInterval::ExcludeMinimum ) ? "]" : "[" ) - << interval.minValue() << "," << interval.maxValue() - << ( ( flags & QwtInterval::ExcludeMaximum ) ? "[" : "]" ) - << ")"; - - return debug.space(); -} - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_interval.h" +#include "qwt_math.h" +#include + +/*! + \brief Normalize the limits of the interval + + If maxValue() < minValue() the limits will be inverted. + \return Normalized interval + + \sa isValid(), inverted() +*/ +QwtInterval QwtInterval::normalized() const +{ + if ( d_minValue > d_maxValue ) + { + return inverted(); + } + if ( d_minValue == d_maxValue && d_borderFlags == ExcludeMinimum ) + { + return inverted(); + } + + return *this; +} + +/*! + Invert the limits of the interval + \return Inverted interval + \sa normalized() +*/ +QwtInterval QwtInterval::inverted() const +{ + BorderFlags borderFlags = IncludeBorders; + if ( d_borderFlags & ExcludeMinimum ) + borderFlags |= ExcludeMaximum; + if ( d_borderFlags & ExcludeMaximum ) + borderFlags |= ExcludeMinimum; + + return QwtInterval( d_maxValue, d_minValue, borderFlags ); +} + +/*! + Test if a value is inside an interval + + \param value Value + \return true, if value >= minValue() && value <= maxValue() +*/ +bool QwtInterval::contains( double value ) const +{ + if ( !isValid() ) + return false; + + if ( value < d_minValue || value > d_maxValue ) + return false; + + if ( value == d_minValue && d_borderFlags & ExcludeMinimum ) + return false; + + if ( value == d_maxValue && d_borderFlags & ExcludeMaximum ) + return false; + + return true; +} + +//! Unite 2 intervals +QwtInterval QwtInterval::unite( const QwtInterval &other ) const +{ + /* + If one of the intervals is invalid return the other one. + If both are invalid return an invalid default interval + */ + if ( !isValid() ) + { + if ( !other.isValid() ) + return QwtInterval(); + else + return other; + } + if ( !other.isValid() ) + return *this; + + QwtInterval united; + BorderFlags flags = IncludeBorders; + + // minimum + if ( d_minValue < other.minValue() ) + { + united.setMinValue( d_minValue ); + flags &= d_borderFlags & ExcludeMinimum; + } + else if ( other.minValue() < d_minValue ) + { + united.setMinValue( other.minValue() ); + flags &= other.borderFlags() & ExcludeMinimum; + } + else // d_minValue == other.minValue() + { + united.setMinValue( d_minValue ); + flags &= ( d_borderFlags & other.borderFlags() ) & ExcludeMinimum; + } + + // maximum + if ( d_maxValue > other.maxValue() ) + { + united.setMaxValue( d_maxValue ); + flags &= d_borderFlags & ExcludeMaximum; + } + else if ( other.maxValue() > d_maxValue ) + { + united.setMaxValue( other.maxValue() ); + flags &= other.borderFlags() & ExcludeMaximum; + } + else // d_maxValue == other.maxValue() ) + { + united.setMaxValue( d_maxValue ); + flags &= d_borderFlags & other.borderFlags() & ExcludeMaximum; + } + + united.setBorderFlags( flags ); + return united; +} + +//! Intersect 2 intervals +QwtInterval QwtInterval::intersect( const QwtInterval &other ) const +{ + if ( !other.isValid() || !isValid() ) + return QwtInterval(); + + QwtInterval i1 = *this; + QwtInterval i2 = other; + + // swap i1/i2, so that the minimum of i1 + // is smaller then the minimum of i2 + + if ( i1.minValue() > i2.minValue() ) + { + qSwap( i1, i2 ); + } + else if ( i1.minValue() == i2.minValue() ) + { + if ( i1.borderFlags() & ExcludeMinimum ) + qSwap( i1, i2 ); + } + + if ( i1.maxValue() < i2.minValue() ) + { + return QwtInterval(); + } + + if ( i1.maxValue() == i2.minValue() ) + { + if ( i1.borderFlags() & ExcludeMaximum || + i2.borderFlags() & ExcludeMinimum ) + { + return QwtInterval(); + } + } + + QwtInterval intersected; + BorderFlags flags = IncludeBorders; + + intersected.setMinValue( i2.minValue() ); + flags |= i2.borderFlags() & ExcludeMinimum; + + if ( i1.maxValue() < i2.maxValue() ) + { + intersected.setMaxValue( i1.maxValue() ); + flags |= i1.borderFlags() & ExcludeMaximum; + } + else if ( i2.maxValue() < i1.maxValue() ) + { + intersected.setMaxValue( i2.maxValue() ); + flags |= i2.borderFlags() & ExcludeMaximum; + } + else // i1.maxValue() == i2.maxValue() + { + intersected.setMaxValue( i1.maxValue() ); + flags |= i1.borderFlags() & i2.borderFlags() & ExcludeMaximum; + } + + intersected.setBorderFlags( flags ); + return intersected; +} + +//! Unites this interval with the given interval. +QwtInterval& QwtInterval::operator|=( const QwtInterval & interval ) +{ + *this = *this | interval; + return *this; +} + +//! Intersects this interval with the given interval. +QwtInterval& QwtInterval::operator&=( const QwtInterval & interval ) +{ + *this = *this & interval; + return *this; +} + +/*! + Test if two intervals overlap +*/ +bool QwtInterval::intersects( const QwtInterval &other ) const +{ + if ( !isValid() || !other.isValid() ) + return false; + + QwtInterval i1 = *this; + QwtInterval i2 = other; + + // swap i1/i2, so that the minimum of i1 + // is smaller then the minimum of i2 + + if ( i1.minValue() > i2.minValue() ) + { + qSwap( i1, i2 ); + } + else if ( i1.minValue() == i2.minValue() && + i1.borderFlags() & ExcludeMinimum ) + { + qSwap( i1, i2 ); + } + + if ( i1.maxValue() > i2.minValue() ) + { + return true; + } + if ( i1.maxValue() == i2.minValue() ) + { + return !( ( i1.borderFlags() & ExcludeMaximum ) || + ( i2.borderFlags() & ExcludeMinimum ) ); + } + return false; +} + +/*! + Adjust the limit that is closer to value, so that value becomes + the center of the interval. + + \param value Center + \return Interval with value as center +*/ +QwtInterval QwtInterval::symmetrize( double value ) const +{ + if ( !isValid() ) + return *this; + + const double delta = + qMax( qAbs( value - d_maxValue ), qAbs( value - d_minValue ) ); + + return QwtInterval( value - delta, value + delta ); +} + +/*! + Limit the interval, keeping the border modes + + \param lowerBound Lower limit + \param upperBound Upper limit + + \return Limited interval +*/ +QwtInterval QwtInterval::limited( double lowerBound, double upperBound ) const +{ + if ( !isValid() || lowerBound > upperBound ) + return QwtInterval(); + + double minValue = qMax( d_minValue, lowerBound ); + minValue = qMin( minValue, upperBound ); + + double maxValue = qMax( d_maxValue, lowerBound ); + maxValue = qMin( maxValue, upperBound ); + + return QwtInterval( minValue, maxValue, d_borderFlags ); +} + +/*! + Extend the interval + + If value is below minValue, value becomes the lower limit. + If value is above maxValue, value becomes the upper limit. + + extend has no effect for invalid intervals + + \param value Value + \sa isValid() +*/ +QwtInterval QwtInterval::extend( double value ) const +{ + if ( !isValid() ) + return *this; + + return QwtInterval( qMin( value, d_minValue ), + qMax( value, d_maxValue ), d_borderFlags ); +} + +/*! + Extend an interval + + \param value Value + \return Reference of the extended interval + + \sa extend() +*/ +QwtInterval& QwtInterval::operator|=( double value ) +{ + *this = *this | value; + return *this; +} + +#ifndef QT_NO_DEBUG_STREAM + +QDebug operator<<( QDebug debug, const QwtInterval &interval ) +{ + const int flags = interval.borderFlags(); + + debug.nospace() << "QwtInterval(" + << ( ( flags & QwtInterval::ExcludeMinimum ) ? "]" : "[" ) + << interval.minValue() << "," << interval.maxValue() + << ( ( flags & QwtInterval::ExcludeMaximum ) ? "[" : "]" ) + << ")"; + + return debug.space(); +} + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_interval.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_interval.h index 5666f7206..fddeea6f5 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_interval.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_interval.h @@ -1,296 +1,296 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_INTERVAL_H -#define QWT_INTERVAL_H - -#include "qwt_global.h" -#ifndef QT_NO_DEBUG_STREAM -#include -#endif - -/*! - \brief A class representing an interval - - The interval is represented by 2 doubles, the lower and the upper limit. -*/ - -class QWT_EXPORT QwtInterval -{ -public: - /*! - Flag indicating if a border is included or excluded - \sa setBorderFlags(), borderFlags() - */ - enum BorderFlag - { - //! Min/Max values are inside the interval - IncludeBorders = 0x00, - - //! Min value is not included in the interval - ExcludeMinimum = 0x01, - - //! Max value is not included in the interval - ExcludeMaximum = 0x02, - - //! Min/Max values are not included in the interval - ExcludeBorders = ExcludeMinimum | ExcludeMaximum - }; - - //! Border flags - typedef QFlags BorderFlags; - - QwtInterval(); - QwtInterval( double minValue, double maxValue, - BorderFlags = IncludeBorders ); - - void setInterval( double minValue, double maxValue, - BorderFlags = IncludeBorders ); - - QwtInterval normalized() const; - QwtInterval inverted() const; - QwtInterval limited( double minValue, double maxValue ) const; - - bool operator==( const QwtInterval & ) const; - bool operator!=( const QwtInterval & ) const; - - void setBorderFlags( BorderFlags ); - BorderFlags borderFlags() const; - - double minValue() const; - double maxValue() const; - - double width() const; - - void setMinValue( double ); - void setMaxValue( double ); - - bool contains( double value ) const; - - bool intersects( const QwtInterval & ) const; - QwtInterval intersect( const QwtInterval & ) const; - QwtInterval unite( const QwtInterval & ) const; - - QwtInterval operator|( const QwtInterval & ) const; - QwtInterval operator&( const QwtInterval & ) const; - - QwtInterval &operator|=( const QwtInterval & ); - QwtInterval &operator&=( const QwtInterval & ); - - QwtInterval extend( double value ) const; - QwtInterval operator|( double ) const; - QwtInterval &operator|=( double ); - - bool isValid() const; - bool isNull() const; - void invalidate(); - - QwtInterval symmetrize( double value ) const; - -private: - double d_minValue; - double d_maxValue; - BorderFlags d_borderFlags; -}; - -Q_DECLARE_TYPEINFO(QwtInterval, Q_MOVABLE_TYPE); - -/*! - \brief Default Constructor - - Creates an invalid interval [0.0, -1.0] - \sa setInterval(), isValid() -*/ -inline QwtInterval::QwtInterval(): - d_minValue( 0.0 ), - d_maxValue( -1.0 ), - d_borderFlags( IncludeBorders ) -{ -} - -/*! - Constructor - - Build an interval with from min/max values - - \param minValue Minimum value - \param maxValue Maximum value - \param borderFlags Include/Exclude borders -*/ -inline QwtInterval::QwtInterval( - double minValue, double maxValue, BorderFlags borderFlags ): - d_minValue( minValue ), - d_maxValue( maxValue ), - d_borderFlags( borderFlags ) -{ -} - -/*! - Assign the limits of the interval - - \param minValue Minimum value - \param maxValue Maximum value - \param borderFlags Include/Exclude borders -*/ -inline void QwtInterval::setInterval( - double minValue, double maxValue, BorderFlags borderFlags ) -{ - d_minValue = minValue; - d_maxValue = maxValue; - d_borderFlags = borderFlags; -} - -/*! - Change the border flags - - \param borderFlags Or'd BorderMode flags - \sa borderFlags() -*/ -inline void QwtInterval::setBorderFlags( BorderFlags borderFlags ) -{ - d_borderFlags = borderFlags; -} - -/*! - \return Border flags - \sa setBorderFlags() -*/ -inline QwtInterval::BorderFlags QwtInterval::borderFlags() const -{ - return d_borderFlags; -} - -/*! - Assign the lower limit of the interval - - \param minValue Minimum value -*/ -inline void QwtInterval::setMinValue( double minValue ) -{ - d_minValue = minValue; -} - -/*! - Assign the upper limit of the interval - - \param maxValue Maximum value -*/ -inline void QwtInterval::setMaxValue( double maxValue ) -{ - d_maxValue = maxValue; -} - -//! \return Lower limit of the interval -inline double QwtInterval::minValue() const -{ - return d_minValue; -} - -//! \return Upper limit of the interval -inline double QwtInterval::maxValue() const -{ - return d_maxValue; -} - -/*! - Return the width of an interval - The width of invalid intervals is 0.0, otherwise the result is - maxValue() - minValue(). - - \sa isValid() -*/ -inline double QwtInterval::width() const -{ - return isValid() ? ( d_maxValue - d_minValue ) : 0.0; -} - -/*! - Intersection of two intervals - \sa intersect() -*/ -inline QwtInterval QwtInterval::operator&( - const QwtInterval &interval ) const -{ - return intersect( interval ); -} - -/*! - Union of two intervals - \sa unite() -*/ -inline QwtInterval QwtInterval::operator|( - const QwtInterval &interval ) const -{ - return unite( interval ); -} - -//! Compare two intervals -inline bool QwtInterval::operator==( const QwtInterval &other ) const -{ - return ( d_minValue == other.d_minValue ) && - ( d_maxValue == other.d_maxValue ) && - ( d_borderFlags == other.d_borderFlags ); -} - -//! Compare two intervals -inline bool QwtInterval::operator!=( const QwtInterval &other ) const -{ - return ( !( *this == other ) ); -} - -/*! - Extend an interval - - \param value Value - \return Extended interval - \sa extend() -*/ -inline QwtInterval QwtInterval::operator|( double value ) const -{ - return extend( value ); -} - -//! \return true, if isValid() && (minValue() >= maxValue()) -inline bool QwtInterval::isNull() const -{ - return isValid() && d_minValue >= d_maxValue; -} - -/*! - A interval is valid when minValue() <= maxValue(). - In case of QwtInterval::ExcludeBorders it is true - when minValue() < maxValue() -*/ -inline bool QwtInterval::isValid() const -{ - if ( ( d_borderFlags & ExcludeBorders ) == 0 ) - return d_minValue <= d_maxValue; - else - return d_minValue < d_maxValue; -} - -/*! - Invalidate the interval - - The limits are set to interval [0.0, -1.0] - \sa isValid() -*/ -inline void QwtInterval::invalidate() -{ - d_minValue = 0.0; - d_maxValue = -1.0; -} - -Q_DECLARE_OPERATORS_FOR_FLAGS( QwtInterval::BorderFlags ) - -#ifndef QT_NO_DEBUG_STREAM -QWT_EXPORT QDebug operator<<( QDebug, const QwtInterval & ); -#endif - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_INTERVAL_H +#define QWT_INTERVAL_H + +#include "qwt_global.h" +#ifndef QT_NO_DEBUG_STREAM +#include +#endif + +/*! + \brief A class representing an interval + + The interval is represented by 2 doubles, the lower and the upper limit. +*/ + +class QWT_EXPORT QwtInterval +{ +public: + /*! + Flag indicating if a border is included or excluded + \sa setBorderFlags(), borderFlags() + */ + enum BorderFlag + { + //! Min/Max values are inside the interval + IncludeBorders = 0x00, + + //! Min value is not included in the interval + ExcludeMinimum = 0x01, + + //! Max value is not included in the interval + ExcludeMaximum = 0x02, + + //! Min/Max values are not included in the interval + ExcludeBorders = ExcludeMinimum | ExcludeMaximum + }; + + //! Border flags + typedef QFlags BorderFlags; + + QwtInterval(); + QwtInterval( double minValue, double maxValue, + BorderFlags = IncludeBorders ); + + void setInterval( double minValue, double maxValue, + BorderFlags = IncludeBorders ); + + QwtInterval normalized() const; + QwtInterval inverted() const; + QwtInterval limited( double minValue, double maxValue ) const; + + bool operator==( const QwtInterval & ) const; + bool operator!=( const QwtInterval & ) const; + + void setBorderFlags( BorderFlags ); + BorderFlags borderFlags() const; + + double minValue() const; + double maxValue() const; + + double width() const; + + void setMinValue( double ); + void setMaxValue( double ); + + bool contains( double value ) const; + + bool intersects( const QwtInterval & ) const; + QwtInterval intersect( const QwtInterval & ) const; + QwtInterval unite( const QwtInterval & ) const; + + QwtInterval operator|( const QwtInterval & ) const; + QwtInterval operator&( const QwtInterval & ) const; + + QwtInterval &operator|=( const QwtInterval & ); + QwtInterval &operator&=( const QwtInterval & ); + + QwtInterval extend( double value ) const; + QwtInterval operator|( double ) const; + QwtInterval &operator|=( double ); + + bool isValid() const; + bool isNull() const; + void invalidate(); + + QwtInterval symmetrize( double value ) const; + +private: + double d_minValue; + double d_maxValue; + BorderFlags d_borderFlags; +}; + +Q_DECLARE_TYPEINFO(QwtInterval, Q_MOVABLE_TYPE); + +/*! + \brief Default Constructor + + Creates an invalid interval [0.0, -1.0] + \sa setInterval(), isValid() +*/ +inline QwtInterval::QwtInterval(): + d_minValue( 0.0 ), + d_maxValue( -1.0 ), + d_borderFlags( IncludeBorders ) +{ +} + +/*! + Constructor + + Build an interval with from min/max values + + \param minValue Minimum value + \param maxValue Maximum value + \param borderFlags Include/Exclude borders +*/ +inline QwtInterval::QwtInterval( + double minValue, double maxValue, BorderFlags borderFlags ): + d_minValue( minValue ), + d_maxValue( maxValue ), + d_borderFlags( borderFlags ) +{ +} + +/*! + Assign the limits of the interval + + \param minValue Minimum value + \param maxValue Maximum value + \param borderFlags Include/Exclude borders +*/ +inline void QwtInterval::setInterval( + double minValue, double maxValue, BorderFlags borderFlags ) +{ + d_minValue = minValue; + d_maxValue = maxValue; + d_borderFlags = borderFlags; +} + +/*! + Change the border flags + + \param borderFlags Or'd BorderMode flags + \sa borderFlags() +*/ +inline void QwtInterval::setBorderFlags( BorderFlags borderFlags ) +{ + d_borderFlags = borderFlags; +} + +/*! + \return Border flags + \sa setBorderFlags() +*/ +inline QwtInterval::BorderFlags QwtInterval::borderFlags() const +{ + return d_borderFlags; +} + +/*! + Assign the lower limit of the interval + + \param minValue Minimum value +*/ +inline void QwtInterval::setMinValue( double minValue ) +{ + d_minValue = minValue; +} + +/*! + Assign the upper limit of the interval + + \param maxValue Maximum value +*/ +inline void QwtInterval::setMaxValue( double maxValue ) +{ + d_maxValue = maxValue; +} + +//! \return Lower limit of the interval +inline double QwtInterval::minValue() const +{ + return d_minValue; +} + +//! \return Upper limit of the interval +inline double QwtInterval::maxValue() const +{ + return d_maxValue; +} + +/*! + Return the width of an interval + The width of invalid intervals is 0.0, otherwise the result is + maxValue() - minValue(). + + \sa isValid() +*/ +inline double QwtInterval::width() const +{ + return isValid() ? ( d_maxValue - d_minValue ) : 0.0; +} + +/*! + Intersection of two intervals + \sa intersect() +*/ +inline QwtInterval QwtInterval::operator&( + const QwtInterval &interval ) const +{ + return intersect( interval ); +} + +/*! + Union of two intervals + \sa unite() +*/ +inline QwtInterval QwtInterval::operator|( + const QwtInterval &interval ) const +{ + return unite( interval ); +} + +//! Compare two intervals +inline bool QwtInterval::operator==( const QwtInterval &other ) const +{ + return ( d_minValue == other.d_minValue ) && + ( d_maxValue == other.d_maxValue ) && + ( d_borderFlags == other.d_borderFlags ); +} + +//! Compare two intervals +inline bool QwtInterval::operator!=( const QwtInterval &other ) const +{ + return ( !( *this == other ) ); +} + +/*! + Extend an interval + + \param value Value + \return Extended interval + \sa extend() +*/ +inline QwtInterval QwtInterval::operator|( double value ) const +{ + return extend( value ); +} + +//! \return true, if isValid() && (minValue() >= maxValue()) +inline bool QwtInterval::isNull() const +{ + return isValid() && d_minValue >= d_maxValue; +} + +/*! + A interval is valid when minValue() <= maxValue(). + In case of QwtInterval::ExcludeBorders it is true + when minValue() < maxValue() +*/ +inline bool QwtInterval::isValid() const +{ + if ( ( d_borderFlags & ExcludeBorders ) == 0 ) + return d_minValue <= d_maxValue; + else + return d_minValue < d_maxValue; +} + +/*! + Invalidate the interval + + The limits are set to interval [0.0, -1.0] + \sa isValid() +*/ +inline void QwtInterval::invalidate() +{ + d_minValue = 0.0; + d_maxValue = -1.0; +} + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtInterval::BorderFlags ) + +#ifndef QT_NO_DEBUG_STREAM +QWT_EXPORT QDebug operator<<( QDebug, const QwtInterval & ); +#endif + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_interval_symbol.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_interval_symbol.cpp index 69ab0b4c0..25d9e04c7 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_interval_symbol.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_interval_symbol.cpp @@ -1,298 +1,298 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_interval_symbol.h" -#include "qwt_painter.h" -#include "qwt_math.h" -#include - -#if QT_VERSION < 0x040601 -#define qAtan2(y, x) ::atan2(y, x) -#endif - -class QwtIntervalSymbol::PrivateData -{ -public: - PrivateData(): - style( QwtIntervalSymbol::NoSymbol ), - width( 6 ) - { - } - - bool operator==( const PrivateData &other ) const - { - return ( style == other.style ) - && ( width == other.width ) - && ( brush == other.brush ) - && ( pen == other.pen ); - } - - QwtIntervalSymbol::Style style; - int width; - - QPen pen; - QBrush brush; -}; - -/*! - Constructor - - \param style Style of the symbol - \sa setStyle(), style(), Style -*/ -QwtIntervalSymbol::QwtIntervalSymbol( Style style ) -{ - d_data = new PrivateData(); - d_data->style = style; -} - -//! Copy constructor -QwtIntervalSymbol::QwtIntervalSymbol( const QwtIntervalSymbol &other ) -{ - d_data = new PrivateData(); - *d_data = *other.d_data; -} - -//! Destructor -QwtIntervalSymbol::~QwtIntervalSymbol() -{ - delete d_data; -} - -//! \brief Assignment operator -QwtIntervalSymbol &QwtIntervalSymbol::operator=( - const QwtIntervalSymbol &other ) -{ - *d_data = *other.d_data; - return *this; -} - -//! \brief Compare two symbols -bool QwtIntervalSymbol::operator==( - const QwtIntervalSymbol &other ) const -{ - return *d_data == *other.d_data; -} - -//! \brief Compare two symbols -bool QwtIntervalSymbol::operator!=( - const QwtIntervalSymbol &other ) const -{ - return !( *d_data == *other.d_data ); -} - -/*! - Specify the symbol style - - \param style Style - \sa style(), Style -*/ -void QwtIntervalSymbol::setStyle( Style style ) -{ - d_data->style = style; -} - -/*! - \return Current symbol style - \sa setStyle() -*/ -QwtIntervalSymbol::Style QwtIntervalSymbol::style() const -{ - return d_data->style; -} - -/*! - Specify the width of the symbol - It is used depending on the style. - - \param width Width - \sa width(), setStyle() -*/ -void QwtIntervalSymbol::setWidth( int width ) -{ - d_data->width = width; -} - -/*! - \return Width of the symbol. - \sa setWidth(), setStyle() -*/ -int QwtIntervalSymbol::width() const -{ - return d_data->width; -} - -/*! - \brief Assign a brush - - The brush is used for the Box style. - - \param brush Brush - \sa brush() -*/ -void QwtIntervalSymbol::setBrush( const QBrush &brush ) -{ - d_data->brush = brush; -} - -/*! - \return Brush - \sa setBrush() -*/ -const QBrush& QwtIntervalSymbol::brush() const -{ - return d_data->brush; -} - -/*! - Assign a pen - - \param pen Pen - \sa pen(), setBrush() -*/ -void QwtIntervalSymbol::setPen( const QPen &pen ) -{ - d_data->pen = pen; -} - -/*! - \return Pen - \sa setPen(), brush() -*/ -const QPen& QwtIntervalSymbol::pen() const -{ - return d_data->pen; -} - -/*! - Draw a symbol depending on its style - - \param painter Painter - \param orientation Orientation - \param from Start point of the interval in target device coordinates - \param to End point of the interval in target device coordinates - - \sa setStyle() -*/ -void QwtIntervalSymbol::draw( QPainter *painter, Qt::Orientation orientation, - const QPointF &from, const QPointF &to ) const -{ - const qreal pw = qMax( painter->pen().widthF(), qreal( 1.0 ) ); - - QPointF p1 = from; - QPointF p2 = to; - if ( QwtPainter::roundingAlignment( painter ) ) - { - p1 = p1.toPoint(); - p2 = p2.toPoint(); - } - - switch ( d_data->style ) - { - case QwtIntervalSymbol::Bar: - { - QwtPainter::drawLine( painter, p1, p2 ); - if ( d_data->width > pw ) - { - if ( ( orientation == Qt::Horizontal ) - && ( p1.y() == p2.y() ) ) - { - const double sw = d_data->width; - - const double y = p1.y() - sw / 2; - QwtPainter::drawLine( painter, - p1.x(), y, p1.x(), y + sw ); - QwtPainter::drawLine( painter, - p2.x(), y, p2.x(), y + sw ); - } - else if ( ( orientation == Qt::Vertical ) - && ( p1.x() == p2.x() ) ) - { - const double sw = d_data->width; - - const double x = p1.x() - sw / 2; - QwtPainter::drawLine( painter, - x, p1.y(), x + sw, p1.y() ); - QwtPainter::drawLine( painter, - x, p2.y(), x + sw, p2.y() ); - } - else - { - const double sw = d_data->width; - - const double dx = p2.x() - p1.x(); - const double dy = p2.y() - p1.y(); - const double angle = qAtan2( dy, dx ) + M_PI_2; - double dw2 = sw / 2.0; - - const double cx = qCos( angle ) * dw2; - const double sy = qSin( angle ) * dw2; - - QwtPainter::drawLine( painter, - p1.x() - cx, p1.y() - sy, - p1.x() + cx, p1.y() + sy ); - QwtPainter::drawLine( painter, - p2.x() - cx, p2.y() - sy, - p2.x() + cx, p2.y() + sy ); - } - } - break; - } - case QwtIntervalSymbol::Box: - { - if ( d_data->width <= pw ) - { - QwtPainter::drawLine( painter, p1, p2 ); - } - else - { - if ( ( orientation == Qt::Horizontal ) - && ( p1.y() == p2.y() ) ) - { - const double sw = d_data->width; - - const double y = p1.y() - d_data->width / 2; - QwtPainter::drawRect( painter, - p1.x(), y, p2.x() - p1.x(), sw ); - } - else if ( ( orientation == Qt::Vertical ) - && ( p1.x() == p2.x() ) ) - { - const double sw = d_data->width; - - const double x = p1.x() - d_data->width / 2; - QwtPainter::drawRect( painter, - x, p1.y(), sw, p2.y() - p1.y() ); - } - else - { - const double sw = d_data->width; - - const double dx = p2.x() - p1.x(); - const double dy = p2.y() - p1.y(); - const double angle = qAtan2( dy, dx ) + M_PI_2; - double dw2 = sw / 2.0; - - const int cx = qCos( angle ) * dw2; - const int sy = qSin( angle ) * dw2; - - QPolygonF polygon; - polygon += QPointF( p1.x() - cx, p1.y() - sy ); - polygon += QPointF( p1.x() + cx, p1.y() + sy ); - polygon += QPointF( p2.x() + cx, p2.y() + sy ); - polygon += QPointF( p2.x() - cx, p2.y() - sy ); - - QwtPainter::drawPolygon( painter, polygon ); - } - } - break; - } - default:; - } -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_interval_symbol.h" +#include "qwt_painter.h" +#include "qwt_math.h" +#include + +#if QT_VERSION < 0x040601 +#define qAtan2(y, x) ::atan2(y, x) +#endif + +class QwtIntervalSymbol::PrivateData +{ +public: + PrivateData(): + style( QwtIntervalSymbol::NoSymbol ), + width( 6 ) + { + } + + bool operator==( const PrivateData &other ) const + { + return ( style == other.style ) + && ( width == other.width ) + && ( brush == other.brush ) + && ( pen == other.pen ); + } + + QwtIntervalSymbol::Style style; + int width; + + QPen pen; + QBrush brush; +}; + +/*! + Constructor + + \param style Style of the symbol + \sa setStyle(), style(), Style +*/ +QwtIntervalSymbol::QwtIntervalSymbol( Style style ) +{ + d_data = new PrivateData(); + d_data->style = style; +} + +//! Copy constructor +QwtIntervalSymbol::QwtIntervalSymbol( const QwtIntervalSymbol &other ) +{ + d_data = new PrivateData(); + *d_data = *other.d_data; +} + +//! Destructor +QwtIntervalSymbol::~QwtIntervalSymbol() +{ + delete d_data; +} + +//! \brief Assignment operator +QwtIntervalSymbol &QwtIntervalSymbol::operator=( + const QwtIntervalSymbol &other ) +{ + *d_data = *other.d_data; + return *this; +} + +//! \brief Compare two symbols +bool QwtIntervalSymbol::operator==( + const QwtIntervalSymbol &other ) const +{ + return *d_data == *other.d_data; +} + +//! \brief Compare two symbols +bool QwtIntervalSymbol::operator!=( + const QwtIntervalSymbol &other ) const +{ + return !( *d_data == *other.d_data ); +} + +/*! + Specify the symbol style + + \param style Style + \sa style(), Style +*/ +void QwtIntervalSymbol::setStyle( Style style ) +{ + d_data->style = style; +} + +/*! + \return Current symbol style + \sa setStyle() +*/ +QwtIntervalSymbol::Style QwtIntervalSymbol::style() const +{ + return d_data->style; +} + +/*! + Specify the width of the symbol + It is used depending on the style. + + \param width Width + \sa width(), setStyle() +*/ +void QwtIntervalSymbol::setWidth( int width ) +{ + d_data->width = width; +} + +/*! + \return Width of the symbol. + \sa setWidth(), setStyle() +*/ +int QwtIntervalSymbol::width() const +{ + return d_data->width; +} + +/*! + \brief Assign a brush + + The brush is used for the Box style. + + \param brush Brush + \sa brush() +*/ +void QwtIntervalSymbol::setBrush( const QBrush &brush ) +{ + d_data->brush = brush; +} + +/*! + \return Brush + \sa setBrush() +*/ +const QBrush& QwtIntervalSymbol::brush() const +{ + return d_data->brush; +} + +/*! + Assign a pen + + \param pen Pen + \sa pen(), setBrush() +*/ +void QwtIntervalSymbol::setPen( const QPen &pen ) +{ + d_data->pen = pen; +} + +/*! + \return Pen + \sa setPen(), brush() +*/ +const QPen& QwtIntervalSymbol::pen() const +{ + return d_data->pen; +} + +/*! + Draw a symbol depending on its style + + \param painter Painter + \param orientation Orientation + \param from Start point of the interval in target device coordinates + \param to End point of the interval in target device coordinates + + \sa setStyle() +*/ +void QwtIntervalSymbol::draw( QPainter *painter, Qt::Orientation orientation, + const QPointF &from, const QPointF &to ) const +{ + const qreal pw = qMax( painter->pen().widthF(), qreal( 1.0 ) ); + + QPointF p1 = from; + QPointF p2 = to; + if ( QwtPainter::roundingAlignment( painter ) ) + { + p1 = p1.toPoint(); + p2 = p2.toPoint(); + } + + switch ( d_data->style ) + { + case QwtIntervalSymbol::Bar: + { + QwtPainter::drawLine( painter, p1, p2 ); + if ( d_data->width > pw ) + { + if ( ( orientation == Qt::Horizontal ) + && ( p1.y() == p2.y() ) ) + { + const double sw = d_data->width; + + const double y = p1.y() - sw / 2; + QwtPainter::drawLine( painter, + p1.x(), y, p1.x(), y + sw ); + QwtPainter::drawLine( painter, + p2.x(), y, p2.x(), y + sw ); + } + else if ( ( orientation == Qt::Vertical ) + && ( p1.x() == p2.x() ) ) + { + const double sw = d_data->width; + + const double x = p1.x() - sw / 2; + QwtPainter::drawLine( painter, + x, p1.y(), x + sw, p1.y() ); + QwtPainter::drawLine( painter, + x, p2.y(), x + sw, p2.y() ); + } + else + { + const double sw = d_data->width; + + const double dx = p2.x() - p1.x(); + const double dy = p2.y() - p1.y(); + const double angle = qAtan2( dy, dx ) + M_PI_2; + double dw2 = sw / 2.0; + + const double cx = qCos( angle ) * dw2; + const double sy = qSin( angle ) * dw2; + + QwtPainter::drawLine( painter, + p1.x() - cx, p1.y() - sy, + p1.x() + cx, p1.y() + sy ); + QwtPainter::drawLine( painter, + p2.x() - cx, p2.y() - sy, + p2.x() + cx, p2.y() + sy ); + } + } + break; + } + case QwtIntervalSymbol::Box: + { + if ( d_data->width <= pw ) + { + QwtPainter::drawLine( painter, p1, p2 ); + } + else + { + if ( ( orientation == Qt::Horizontal ) + && ( p1.y() == p2.y() ) ) + { + const double sw = d_data->width; + + const double y = p1.y() - d_data->width / 2; + QwtPainter::drawRect( painter, + p1.x(), y, p2.x() - p1.x(), sw ); + } + else if ( ( orientation == Qt::Vertical ) + && ( p1.x() == p2.x() ) ) + { + const double sw = d_data->width; + + const double x = p1.x() - d_data->width / 2; + QwtPainter::drawRect( painter, + x, p1.y(), sw, p2.y() - p1.y() ); + } + else + { + const double sw = d_data->width; + + const double dx = p2.x() - p1.x(); + const double dy = p2.y() - p1.y(); + const double angle = qAtan2( dy, dx ) + M_PI_2; + double dw2 = sw / 2.0; + + const int cx = qCos( angle ) * dw2; + const int sy = qSin( angle ) * dw2; + + QPolygonF polygon; + polygon += QPointF( p1.x() - cx, p1.y() - sy ); + polygon += QPointF( p1.x() + cx, p1.y() + sy ); + polygon += QPointF( p2.x() + cx, p2.y() + sy ); + polygon += QPointF( p2.x() - cx, p2.y() - sy ); + + QwtPainter::drawPolygon( painter, polygon ); + } + } + break; + } + default:; + } +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_interval_symbol.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_interval_symbol.h index e0397c73c..3ea4fe4fa 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_interval_symbol.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_interval_symbol.h @@ -1,86 +1,86 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_INTERVAL_SYMBOL_H -#define QWT_INTERVAL_SYMBOL_H - -#include "qwt_global.h" -#include -#include - -class QPainter; -class QRect; -class QPointF; - -/*! - \brief A drawing primitive for displaying an interval like an error bar - - \sa QwtPlotIntervalCurve -*/ -class QWT_EXPORT QwtIntervalSymbol -{ -public: - //! Symbol style - enum Style - { - //! No Style. The symbol cannot be drawn. - NoSymbol = -1, - - /*! - The symbol displays a line with caps at the beginning/end. - The size of the caps depends on the symbol width(). - */ - Bar, - - /*! - The symbol displays a plain rectangle using pen() and brush(). - The size of the rectangle depends on the translated interval and - the width(), - */ - Box, - - /*! - Styles >= UserSymbol are reserved for derived - classes of QwtIntervalSymbol that overload draw() with - additional application specific symbol types. - */ - UserSymbol = 1000 - }; - -public: - QwtIntervalSymbol( Style = NoSymbol ); - QwtIntervalSymbol( const QwtIntervalSymbol & ); - virtual ~QwtIntervalSymbol(); - - QwtIntervalSymbol &operator=( const QwtIntervalSymbol & ); - bool operator==( const QwtIntervalSymbol & ) const; - bool operator!=( const QwtIntervalSymbol & ) const; - - void setWidth( int ); - int width() const; - - void setBrush( const QBrush& b ); - const QBrush& brush() const; - - void setPen( const QPen & ); - const QPen& pen() const; - - void setStyle( Style ); - Style style() const; - - virtual void draw( QPainter *, Qt::Orientation, - const QPointF& from, const QPointF& to ) const; - -private: - - class PrivateData; - PrivateData* d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_INTERVAL_SYMBOL_H +#define QWT_INTERVAL_SYMBOL_H + +#include "qwt_global.h" +#include +#include + +class QPainter; +class QRect; +class QPointF; + +/*! + \brief A drawing primitive for displaying an interval like an error bar + + \sa QwtPlotIntervalCurve +*/ +class QWT_EXPORT QwtIntervalSymbol +{ +public: + //! Symbol style + enum Style + { + //! No Style. The symbol cannot be drawn. + NoSymbol = -1, + + /*! + The symbol displays a line with caps at the beginning/end. + The size of the caps depends on the symbol width(). + */ + Bar, + + /*! + The symbol displays a plain rectangle using pen() and brush(). + The size of the rectangle depends on the translated interval and + the width(), + */ + Box, + + /*! + Styles >= UserSymbol are reserved for derived + classes of QwtIntervalSymbol that overload draw() with + additional application specific symbol types. + */ + UserSymbol = 1000 + }; + +public: + QwtIntervalSymbol( Style = NoSymbol ); + QwtIntervalSymbol( const QwtIntervalSymbol & ); + virtual ~QwtIntervalSymbol(); + + QwtIntervalSymbol &operator=( const QwtIntervalSymbol & ); + bool operator==( const QwtIntervalSymbol & ) const; + bool operator!=( const QwtIntervalSymbol & ) const; + + void setWidth( int ); + int width() const; + + void setBrush( const QBrush& b ); + const QBrush& brush() const; + + void setPen( const QPen & ); + const QPen& pen() const; + + void setStyle( Style ); + Style style() const; + + virtual void draw( QPainter *, Qt::Orientation, + const QPointF& from, const QPointF& to ) const; + +private: + + class PrivateData; + PrivateData* d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_knob.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_knob.cpp index a4036d479..769903312 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_knob.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_knob.cpp @@ -1,666 +1,666 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_knob.h" -#include "qwt_round_scale_draw.h" -#include "qwt_math.h" -#include "qwt_painter.h" -#include -#include -#include -#include -#include -#include -#include - -#if QT_VERSION < 0x040601 -#define qAtan2(y, x) ::atan2(y, x) -#define qFabs(x) ::fabs(x) -#define qFastCos(x) ::cos(x) -#define qFastSin(x) ::sin(x) -#endif - -class QwtKnob::PrivateData -{ -public: - PrivateData() - { - angle = 0.0; - nTurns = 0.0; - borderWidth = 2; - borderDist = 4; - totalAngle = 270.0; - scaleDist = 4; - markerStyle = QwtKnob::Notch; - maxScaleTicks = 11; - knobStyle = QwtKnob::Raised; - knobWidth = 50; - markerSize = 8; - } - - QwtKnob::KnobStyle knobStyle; - QwtKnob::MarkerStyle markerStyle; - - int borderWidth; - int borderDist; - int scaleDist; - int maxScaleTicks; - int knobWidth; - int markerSize; - - double angle; - double totalAngle; - double nTurns; - - mutable QRectF knobRect; // bounding rect of the knob without scale -}; - -/*! - Constructor - \param parent Parent widget -*/ -QwtKnob::QwtKnob( QWidget* parent ): - QwtAbstractSlider( Qt::Horizontal, parent ) -{ - initKnob(); -} - -void QwtKnob::initKnob() -{ - d_data = new PrivateData; - - setScaleDraw( new QwtRoundScaleDraw() ); - - setUpdateTime( 50 ); - setTotalAngle( 270.0 ); - recalcAngle(); - setSizePolicy( QSizePolicy( QSizePolicy::Minimum, QSizePolicy::Minimum ) ); - - setRange( 0.0, 10.0, 1.0 ); - setValue( 0.0 ); -} - -//! Destructor -QwtKnob::~QwtKnob() -{ - delete d_data; -} - -/*! - \brief Set the knob type - - \param knobStyle Knob type - \sa knobStyle(), setBorderWidth() -*/ -void QwtKnob::setKnobStyle( KnobStyle knobStyle ) -{ - if ( d_data->knobStyle != knobStyle ) - { - d_data->knobStyle = knobStyle; - update(); - } -} - -/*! - \return Marker type of the knob - \sa setKnobStyle(), setBorderWidth() -*/ -QwtKnob::KnobStyle QwtKnob::knobStyle() const -{ - return d_data->knobStyle; -} - -/*! - \brief Set the marker type of the knob - - \param markerStyle Marker type - \sa markerStyle(), setMarkerSize() -*/ -void QwtKnob::setMarkerStyle( MarkerStyle markerStyle ) -{ - if ( d_data->markerStyle != markerStyle ) - { - d_data->markerStyle = markerStyle; - update(); - } -} - -/*! - \return Marker type of the knob - \sa setMarkerStyle(), setMarkerSize() -*/ -QwtKnob::MarkerStyle QwtKnob::markerStyle() const -{ - return d_data->markerStyle; -} - -/*! - \brief Set the total angle by which the knob can be turned - \param angle Angle in degrees. - - The default angle is 270 degrees. It is possible to specify - an angle of more than 360 degrees so that the knob can be - turned several times around its axis. -*/ -void QwtKnob::setTotalAngle ( double angle ) -{ - if ( angle < 10.0 ) - d_data->totalAngle = 10.0; - else - d_data->totalAngle = angle; - - scaleDraw()->setAngleRange( -0.5 * d_data->totalAngle, - 0.5 * d_data->totalAngle ); - layoutKnob( true ); -} - -//! Return the total angle -double QwtKnob::totalAngle() const -{ - return d_data->totalAngle; -} - -/*! - Change the scale draw of the knob - - For changing the labels of the scales, it - is necessary to derive from QwtRoundScaleDraw and - overload QwtRoundScaleDraw::label(). - - \sa scaleDraw() -*/ -void QwtKnob::setScaleDraw( QwtRoundScaleDraw *scaleDraw ) -{ - setAbstractScaleDraw( scaleDraw ); - setTotalAngle( d_data->totalAngle ); -} - -/*! - \return the scale draw of the knob - \sa setScaleDraw() -*/ -const QwtRoundScaleDraw *QwtKnob::scaleDraw() const -{ - return static_cast( abstractScaleDraw() ); -} - -/*! - \return the scale draw of the knob - \sa setScaleDraw() -*/ -QwtRoundScaleDraw *QwtKnob::scaleDraw() -{ - return static_cast( abstractScaleDraw() ); -} - -/*! - \brief Notify change of value - - Sets the knob's value to the nearest multiple - of the step size. -*/ -void QwtKnob::valueChange() -{ - recalcAngle(); - update(); - QwtAbstractSlider::valueChange(); -} - -/*! - \brief Determine the value corresponding to a specified position - - Called by QwtAbstractSlider - \param pos point -*/ -double QwtKnob::getValue( const QPoint &pos ) -{ - const double dx = rect().center().x() - pos.x(); - const double dy = rect().center().y() - pos.y(); - - const double arc = qAtan2( -dx, dy ) * 180.0 / M_PI; - - double newValue = 0.5 * ( minValue() + maxValue() ) - + ( arc + d_data->nTurns * 360.0 ) * ( maxValue() - minValue() ) - / d_data->totalAngle; - - const double oneTurn = qFabs( maxValue() - minValue() ) * 360.0 / d_data->totalAngle; - const double eqValue = value() + mouseOffset(); - - if ( qFabs( newValue - eqValue ) > 0.5 * oneTurn ) - { - if ( newValue < eqValue ) - newValue += oneTurn; - else - newValue -= oneTurn; - } - - return newValue; -} - -/*! - \brief Set the scrolling mode and direction - - Called by QwtAbstractSlider - \param pos Point in question - \param scrollMode Scrolling mode - \param direction Direction -*/ -void QwtKnob::getScrollMode( const QPoint &pos, - QwtAbstractSlider::ScrollMode &scrollMode, int &direction ) const -{ - const int r = d_data->knobRect.width() / 2; - - const int dx = d_data->knobRect.x() + r - pos.x(); - const int dy = d_data->knobRect.y() + r - pos.y(); - - if ( ( dx * dx ) + ( dy * dy ) <= ( r * r ) ) // point is inside the knob - { - scrollMode = QwtAbstractSlider::ScrMouse; - direction = 0; - } - else // point lies outside - { - scrollMode = QwtAbstractSlider::ScrTimer; - double arc = qAtan2( double( -dx ), double( dy ) ) * 180.0 / M_PI; - if ( arc < d_data->angle ) - direction = -1; - else if ( arc > d_data->angle ) - direction = 1; - else - direction = 0; - } -} - -/*! - \brief Notify a change of the range - - Called by QwtAbstractSlider -*/ -void QwtKnob::rangeChange() -{ - if ( autoScale() ) - rescale( minValue(), maxValue() ); - - layoutKnob( true ); - recalcAngle(); -} - -/*! - Qt Resize Event - \param event Resize event -*/ -void QwtKnob::resizeEvent( QResizeEvent *event ) -{ - Q_UNUSED( event ); - layoutKnob( false ); -} - -/*! - Handle QEvent::StyleChange and QEvent::FontChange; - \param event Change event -*/ -void QwtKnob::changeEvent( QEvent *event ) -{ - switch( event->type() ) - { - case QEvent::StyleChange: - case QEvent::FontChange: - layoutKnob( true ); - break; - default: - break; - } -} - -/*! - Recalculate the knob's geometry and layout based on - the current rect and fonts. - - \param update_geometry notify the layout system and call update - to redraw the scale -*/ -void QwtKnob::layoutKnob( bool update_geometry ) -{ - const double d = d_data->knobWidth; - - d_data->knobRect.setWidth( d ); - d_data->knobRect.setHeight( d ); - d_data->knobRect.moveCenter( rect().center() ); - - scaleDraw()->setRadius( 0.5 * d + d_data->scaleDist ); - scaleDraw()->moveCenter( rect().center() ); - - if ( update_geometry ) - { - updateGeometry(); - update(); - } -} - -/*! - Repaint the knob - \param event Paint event -*/ -void QwtKnob::paintEvent( QPaintEvent *event ) -{ - QPainter painter( this ); - painter.setClipRegion( event->region() ); - - QStyleOption opt; - opt.init(this); - style()->drawPrimitive(QStyle::PE_Widget, &opt, &painter, this); - - painter.setRenderHint( QPainter::Antialiasing, true ); - - if ( !d_data->knobRect.contains( event->region().boundingRect() ) ) - scaleDraw()->draw( &painter, palette() ); - - drawKnob( &painter, d_data->knobRect ); - drawMarker( &painter, d_data->knobRect, d_data->angle ); - - painter.setRenderHint( QPainter::Antialiasing, false ); - - if ( hasFocus() ) - QwtPainter::drawFocusRect( &painter, this ); -} - -/*! - \brief Draw the knob - \param painter painter - \param knobRect Bounding rectangle of the knob (without scale) -*/ -void QwtKnob::drawKnob( QPainter *painter, - const QRectF &knobRect ) const -{ - double dim = qMin( knobRect.width(), knobRect.height() ); - dim -= d_data->borderWidth * 0.5; - - QRectF aRect( 0, 0, dim, dim ); - aRect.moveCenter( knobRect.center() ); - - QPen pen( Qt::NoPen ); - if ( d_data->borderWidth > 0 ) - { - QColor c1 = palette().color( QPalette::Light ); - QColor c2 = palette().color( QPalette::Dark ); - - QLinearGradient gradient( aRect.topLeft(), aRect.bottomRight() ); - gradient.setColorAt( 0.0, c1 ); - gradient.setColorAt( 0.3, c1 ); - gradient.setColorAt( 0.7, c2 ); - gradient.setColorAt( 1.0, c2 ); - - pen = QPen( gradient, d_data->borderWidth ); - } - - QBrush brush; - switch( d_data->knobStyle ) - { - case QwtKnob::Raised: - { - double off = 0.3 * knobRect.width(); - QRadialGradient gradient( knobRect.center(), - knobRect.width(), knobRect.topLeft() + QPoint( off, off ) ); - - gradient.setColorAt( 0.0, palette().color( QPalette::Midlight ) ); - gradient.setColorAt( 1.0, palette().color( QPalette::Button ) ); - - brush = QBrush( gradient ); - - break; - } - case QwtKnob::Sunken: - { - QLinearGradient gradient( - knobRect.topLeft(), knobRect.bottomRight() ); - gradient.setColorAt( 0.0, palette().color( QPalette::Mid ) ); - gradient.setColorAt( 0.5, palette().color( QPalette::Button ) ); - gradient.setColorAt( 1.0, palette().color( QPalette::Midlight ) ); - brush = QBrush( gradient ); - - break; - } - default: - brush = palette().brush( QPalette::Button ); - } - - painter->setPen( pen ); - painter->setBrush( brush ); - painter->drawEllipse( aRect ); -} - - -/*! - \brief Draw the marker at the knob's front - \param painter Painter - \param rect Bounding rectangle of the knob without scale - \param angle Angle of the marker in degrees -*/ -void QwtKnob::drawMarker( QPainter *painter, - const QRectF &rect, double angle ) const -{ - if ( d_data->markerStyle == NoMarker || !isValid() ) - return; - - const double radians = angle * M_PI / 180.0; - const double sinA = -qFastSin( radians ); - const double cosA = qFastCos( radians ); - - const double xm = rect.center().x(); - const double ym = rect.center().y(); - const double margin = 4.0; - - double radius = 0.5 * ( rect.width() - d_data->borderWidth ) - margin; - if ( radius < 1.0 ) - radius = 1.0; - - switch ( d_data->markerStyle ) - { - case Notch: - case Nub: - { - const double dotWidth = - qMin( double( d_data->markerSize ), radius); - - const double dotCenterDist = radius - 0.5 * dotWidth; - if ( dotCenterDist > 0.0 ) - { - const QPointF center( xm - sinA * dotCenterDist, - ym - cosA * dotCenterDist ); - - QRectF ellipse( 0.0, 0.0, dotWidth, dotWidth ); - ellipse.moveCenter( center ); - - QColor c1 = palette().color( QPalette::Light ); - QColor c2 = palette().color( QPalette::Mid ); - - if ( d_data->markerStyle == Notch ) - qSwap( c1, c2 ); - - QLinearGradient gradient( - ellipse.topLeft(), ellipse.bottomRight() ); - gradient.setColorAt( 0.0, c1 ); - gradient.setColorAt( 1.0, c2 ); - - painter->setPen( Qt::NoPen ); - painter->setBrush( gradient ); - - painter->drawEllipse( ellipse ); - } - break; - } - case Dot: - { - const double dotWidth = - qMin( double( d_data->markerSize ), radius); - - const double dotCenterDist = radius - 0.5 * dotWidth; - if ( dotCenterDist > 0.0 ) - { - const QPointF center( xm - sinA * dotCenterDist, - ym - cosA * dotCenterDist ); - - QRectF ellipse( 0.0, 0.0, dotWidth, dotWidth ); - ellipse.moveCenter( center ); - - painter->setPen( Qt::NoPen ); - painter->setBrush( palette().color( QPalette::ButtonText ) ); - painter->drawEllipse( ellipse ); - } - - break; - } - case Tick: - { - const double rb = qMax( radius - d_data->markerSize, 1.0 ); - const double re = radius; - - const QLine line( xm - sinA * rb, ym - cosA * rb, - xm - sinA * re, ym - cosA * re ); - - QPen pen( palette().color( QPalette::ButtonText ), 0 ); - pen.setCapStyle( Qt::FlatCap ); - painter->setPen( pen ); - painter->drawLine ( line ); - - break; - } -#if 0 - case Triangle: - { - const double rb = qMax( radius - d_data->markerSize, 1.0 ); - const double re = radius; - - painter->translate( rect.center() ); - painter->rotate( angle - 90.0 ); - - QPolygonF polygon; - polygon += QPointF( re, 0.0 ); - polygon += QPointF( rb, 0.5 * ( re - rb ) ); - polygon += QPointF( rb, -0.5 * ( re - rb ) ); - - painter->setPen( Qt::NoPen ); - painter->setBrush( palette().color( QPalette::Text ) ); - painter->drawPolygon( polygon ); - break; - } -#endif - default: - break; - } -} - -/*! - \brief Change the knob's width. - - The specified width must be >= 5, or it will be clipped. - \param width New width -*/ -void QwtKnob::setKnobWidth( int width ) -{ - d_data->knobWidth = qMax( width, 5 ); - layoutKnob( true ); -} - -//! Return the width of the knob -int QwtKnob::knobWidth() const -{ - return d_data->knobWidth; -} - -/*! - \brief Set the knob's border width - \param borderWidth new border width -*/ -void QwtKnob::setBorderWidth( int borderWidth ) -{ - d_data->borderWidth = qMax( borderWidth, 0 ); - layoutKnob( true ); -} - -//! Return the border width -int QwtKnob::borderWidth() const -{ - return d_data->borderWidth; -} - -/*! - \brief Set the size of the marker - \sa markerSize(), markerStyle() -*/ -void QwtKnob::setMarkerSize( int size ) -{ - if ( d_data->markerSize != size ) - { - d_data->markerSize = size; - update(); - } -} - -//! Return the marker size -int QwtKnob::markerSize() const -{ - return d_data->markerSize; -} - -/*! - \brief Recalculate the marker angle corresponding to the - current value -*/ -void QwtKnob::recalcAngle() -{ - // - // calculate the angle corresponding to the value - // - if ( maxValue() == minValue() ) - { - d_data->angle = 0; - d_data->nTurns = 0; - } - else - { - d_data->angle = ( value() - 0.5 * ( minValue() + maxValue() ) ) - / ( maxValue() - minValue() ) * d_data->totalAngle; - d_data->nTurns = qFloor( ( d_data->angle + 180.0 ) / 360.0 ); - d_data->angle = d_data->angle - d_data->nTurns * 360.0; - } -} - - -/*! - Recalculates the layout - \sa layoutKnob() -*/ -void QwtKnob::scaleChange() -{ - layoutKnob( true ); -} - -/*! - \return minimumSizeHint() -*/ -QSize QwtKnob::sizeHint() const -{ - const QSize hint = minimumSizeHint(); - return hint.expandedTo( QApplication::globalStrut() ); -} - -/*! - \brief Return a minimum size hint - \warning The return value of QwtKnob::minimumSizeHint() depends on the - font and the scale. -*/ -QSize QwtKnob::minimumSizeHint() const -{ - // Add the scale radial thickness to the knobWidth - const int sh = qCeil( scaleDraw()->extent( font() ) ); - const int d = 2 * sh + 2 * d_data->scaleDist + d_data->knobWidth; - - return QSize( d, d ); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_knob.h" +#include "qwt_round_scale_draw.h" +#include "qwt_math.h" +#include "qwt_painter.h" +#include +#include +#include +#include +#include +#include +#include + +#if QT_VERSION < 0x040601 +#define qAtan2(y, x) ::atan2(y, x) +#define qFabs(x) ::fabs(x) +#define qFastCos(x) ::cos(x) +#define qFastSin(x) ::sin(x) +#endif + +class QwtKnob::PrivateData +{ +public: + PrivateData() + { + angle = 0.0; + nTurns = 0.0; + borderWidth = 2; + borderDist = 4; + totalAngle = 270.0; + scaleDist = 4; + markerStyle = QwtKnob::Notch; + maxScaleTicks = 11; + knobStyle = QwtKnob::Raised; + knobWidth = 50; + markerSize = 8; + } + + QwtKnob::KnobStyle knobStyle; + QwtKnob::MarkerStyle markerStyle; + + int borderWidth; + int borderDist; + int scaleDist; + int maxScaleTicks; + int knobWidth; + int markerSize; + + double angle; + double totalAngle; + double nTurns; + + mutable QRectF knobRect; // bounding rect of the knob without scale +}; + +/*! + Constructor + \param parent Parent widget +*/ +QwtKnob::QwtKnob( QWidget* parent ): + QwtAbstractSlider( Qt::Horizontal, parent ) +{ + initKnob(); +} + +void QwtKnob::initKnob() +{ + d_data = new PrivateData; + + setScaleDraw( new QwtRoundScaleDraw() ); + + setUpdateTime( 50 ); + setTotalAngle( 270.0 ); + recalcAngle(); + setSizePolicy( QSizePolicy( QSizePolicy::Minimum, QSizePolicy::Minimum ) ); + + setRange( 0.0, 10.0, 1.0 ); + setValue( 0.0 ); +} + +//! Destructor +QwtKnob::~QwtKnob() +{ + delete d_data; +} + +/*! + \brief Set the knob type + + \param knobStyle Knob type + \sa knobStyle(), setBorderWidth() +*/ +void QwtKnob::setKnobStyle( KnobStyle knobStyle ) +{ + if ( d_data->knobStyle != knobStyle ) + { + d_data->knobStyle = knobStyle; + update(); + } +} + +/*! + \return Marker type of the knob + \sa setKnobStyle(), setBorderWidth() +*/ +QwtKnob::KnobStyle QwtKnob::knobStyle() const +{ + return d_data->knobStyle; +} + +/*! + \brief Set the marker type of the knob + + \param markerStyle Marker type + \sa markerStyle(), setMarkerSize() +*/ +void QwtKnob::setMarkerStyle( MarkerStyle markerStyle ) +{ + if ( d_data->markerStyle != markerStyle ) + { + d_data->markerStyle = markerStyle; + update(); + } +} + +/*! + \return Marker type of the knob + \sa setMarkerStyle(), setMarkerSize() +*/ +QwtKnob::MarkerStyle QwtKnob::markerStyle() const +{ + return d_data->markerStyle; +} + +/*! + \brief Set the total angle by which the knob can be turned + \param angle Angle in degrees. + + The default angle is 270 degrees. It is possible to specify + an angle of more than 360 degrees so that the knob can be + turned several times around its axis. +*/ +void QwtKnob::setTotalAngle ( double angle ) +{ + if ( angle < 10.0 ) + d_data->totalAngle = 10.0; + else + d_data->totalAngle = angle; + + scaleDraw()->setAngleRange( -0.5 * d_data->totalAngle, + 0.5 * d_data->totalAngle ); + layoutKnob( true ); +} + +//! Return the total angle +double QwtKnob::totalAngle() const +{ + return d_data->totalAngle; +} + +/*! + Change the scale draw of the knob + + For changing the labels of the scales, it + is necessary to derive from QwtRoundScaleDraw and + overload QwtRoundScaleDraw::label(). + + \sa scaleDraw() +*/ +void QwtKnob::setScaleDraw( QwtRoundScaleDraw *scaleDraw ) +{ + setAbstractScaleDraw( scaleDraw ); + setTotalAngle( d_data->totalAngle ); +} + +/*! + \return the scale draw of the knob + \sa setScaleDraw() +*/ +const QwtRoundScaleDraw *QwtKnob::scaleDraw() const +{ + return static_cast( abstractScaleDraw() ); +} + +/*! + \return the scale draw of the knob + \sa setScaleDraw() +*/ +QwtRoundScaleDraw *QwtKnob::scaleDraw() +{ + return static_cast( abstractScaleDraw() ); +} + +/*! + \brief Notify change of value + + Sets the knob's value to the nearest multiple + of the step size. +*/ +void QwtKnob::valueChange() +{ + recalcAngle(); + update(); + QwtAbstractSlider::valueChange(); +} + +/*! + \brief Determine the value corresponding to a specified position + + Called by QwtAbstractSlider + \param pos point +*/ +double QwtKnob::getValue( const QPoint &pos ) +{ + const double dx = rect().center().x() - pos.x(); + const double dy = rect().center().y() - pos.y(); + + const double arc = qAtan2( -dx, dy ) * 180.0 / M_PI; + + double newValue = 0.5 * ( minValue() + maxValue() ) + + ( arc + d_data->nTurns * 360.0 ) * ( maxValue() - minValue() ) + / d_data->totalAngle; + + const double oneTurn = qFabs( maxValue() - minValue() ) * 360.0 / d_data->totalAngle; + const double eqValue = value() + mouseOffset(); + + if ( qFabs( newValue - eqValue ) > 0.5 * oneTurn ) + { + if ( newValue < eqValue ) + newValue += oneTurn; + else + newValue -= oneTurn; + } + + return newValue; +} + +/*! + \brief Set the scrolling mode and direction + + Called by QwtAbstractSlider + \param pos Point in question + \param scrollMode Scrolling mode + \param direction Direction +*/ +void QwtKnob::getScrollMode( const QPoint &pos, + QwtAbstractSlider::ScrollMode &scrollMode, int &direction ) const +{ + const int r = d_data->knobRect.width() / 2; + + const int dx = d_data->knobRect.x() + r - pos.x(); + const int dy = d_data->knobRect.y() + r - pos.y(); + + if ( ( dx * dx ) + ( dy * dy ) <= ( r * r ) ) // point is inside the knob + { + scrollMode = QwtAbstractSlider::ScrMouse; + direction = 0; + } + else // point lies outside + { + scrollMode = QwtAbstractSlider::ScrTimer; + double arc = qAtan2( double( -dx ), double( dy ) ) * 180.0 / M_PI; + if ( arc < d_data->angle ) + direction = -1; + else if ( arc > d_data->angle ) + direction = 1; + else + direction = 0; + } +} + +/*! + \brief Notify a change of the range + + Called by QwtAbstractSlider +*/ +void QwtKnob::rangeChange() +{ + if ( autoScale() ) + rescale( minValue(), maxValue() ); + + layoutKnob( true ); + recalcAngle(); +} + +/*! + Qt Resize Event + \param event Resize event +*/ +void QwtKnob::resizeEvent( QResizeEvent *event ) +{ + Q_UNUSED( event ); + layoutKnob( false ); +} + +/*! + Handle QEvent::StyleChange and QEvent::FontChange; + \param event Change event +*/ +void QwtKnob::changeEvent( QEvent *event ) +{ + switch( event->type() ) + { + case QEvent::StyleChange: + case QEvent::FontChange: + layoutKnob( true ); + break; + default: + break; + } +} + +/*! + Recalculate the knob's geometry and layout based on + the current rect and fonts. + + \param update_geometry notify the layout system and call update + to redraw the scale +*/ +void QwtKnob::layoutKnob( bool update_geometry ) +{ + const double d = d_data->knobWidth; + + d_data->knobRect.setWidth( d ); + d_data->knobRect.setHeight( d ); + d_data->knobRect.moveCenter( rect().center() ); + + scaleDraw()->setRadius( 0.5 * d + d_data->scaleDist ); + scaleDraw()->moveCenter( rect().center() ); + + if ( update_geometry ) + { + updateGeometry(); + update(); + } +} + +/*! + Repaint the knob + \param event Paint event +*/ +void QwtKnob::paintEvent( QPaintEvent *event ) +{ + QPainter painter( this ); + painter.setClipRegion( event->region() ); + + QStyleOption opt; + opt.init(this); + style()->drawPrimitive(QStyle::PE_Widget, &opt, &painter, this); + + painter.setRenderHint( QPainter::Antialiasing, true ); + + if ( !d_data->knobRect.contains( event->region().boundingRect() ) ) + scaleDraw()->draw( &painter, palette() ); + + drawKnob( &painter, d_data->knobRect ); + drawMarker( &painter, d_data->knobRect, d_data->angle ); + + painter.setRenderHint( QPainter::Antialiasing, false ); + + if ( hasFocus() ) + QwtPainter::drawFocusRect( &painter, this ); +} + +/*! + \brief Draw the knob + \param painter painter + \param knobRect Bounding rectangle of the knob (without scale) +*/ +void QwtKnob::drawKnob( QPainter *painter, + const QRectF &knobRect ) const +{ + double dim = qMin( knobRect.width(), knobRect.height() ); + dim -= d_data->borderWidth * 0.5; + + QRectF aRect( 0, 0, dim, dim ); + aRect.moveCenter( knobRect.center() ); + + QPen pen( Qt::NoPen ); + if ( d_data->borderWidth > 0 ) + { + QColor c1 = palette().color( QPalette::Light ); + QColor c2 = palette().color( QPalette::Dark ); + + QLinearGradient gradient( aRect.topLeft(), aRect.bottomRight() ); + gradient.setColorAt( 0.0, c1 ); + gradient.setColorAt( 0.3, c1 ); + gradient.setColorAt( 0.7, c2 ); + gradient.setColorAt( 1.0, c2 ); + + pen = QPen( gradient, d_data->borderWidth ); + } + + QBrush brush; + switch( d_data->knobStyle ) + { + case QwtKnob::Raised: + { + double off = 0.3 * knobRect.width(); + QRadialGradient gradient( knobRect.center(), + knobRect.width(), knobRect.topLeft() + QPoint( off, off ) ); + + gradient.setColorAt( 0.0, palette().color( QPalette::Midlight ) ); + gradient.setColorAt( 1.0, palette().color( QPalette::Button ) ); + + brush = QBrush( gradient ); + + break; + } + case QwtKnob::Sunken: + { + QLinearGradient gradient( + knobRect.topLeft(), knobRect.bottomRight() ); + gradient.setColorAt( 0.0, palette().color( QPalette::Mid ) ); + gradient.setColorAt( 0.5, palette().color( QPalette::Button ) ); + gradient.setColorAt( 1.0, palette().color( QPalette::Midlight ) ); + brush = QBrush( gradient ); + + break; + } + default: + brush = palette().brush( QPalette::Button ); + } + + painter->setPen( pen ); + painter->setBrush( brush ); + painter->drawEllipse( aRect ); +} + + +/*! + \brief Draw the marker at the knob's front + \param painter Painter + \param rect Bounding rectangle of the knob without scale + \param angle Angle of the marker in degrees +*/ +void QwtKnob::drawMarker( QPainter *painter, + const QRectF &rect, double angle ) const +{ + if ( d_data->markerStyle == NoMarker || !isValid() ) + return; + + const double radians = angle * M_PI / 180.0; + const double sinA = -qFastSin( radians ); + const double cosA = qFastCos( radians ); + + const double xm = rect.center().x(); + const double ym = rect.center().y(); + const double margin = 4.0; + + double radius = 0.5 * ( rect.width() - d_data->borderWidth ) - margin; + if ( radius < 1.0 ) + radius = 1.0; + + switch ( d_data->markerStyle ) + { + case Notch: + case Nub: + { + const double dotWidth = + qMin( double( d_data->markerSize ), radius); + + const double dotCenterDist = radius - 0.5 * dotWidth; + if ( dotCenterDist > 0.0 ) + { + const QPointF center( xm - sinA * dotCenterDist, + ym - cosA * dotCenterDist ); + + QRectF ellipse( 0.0, 0.0, dotWidth, dotWidth ); + ellipse.moveCenter( center ); + + QColor c1 = palette().color( QPalette::Light ); + QColor c2 = palette().color( QPalette::Mid ); + + if ( d_data->markerStyle == Notch ) + qSwap( c1, c2 ); + + QLinearGradient gradient( + ellipse.topLeft(), ellipse.bottomRight() ); + gradient.setColorAt( 0.0, c1 ); + gradient.setColorAt( 1.0, c2 ); + + painter->setPen( Qt::NoPen ); + painter->setBrush( gradient ); + + painter->drawEllipse( ellipse ); + } + break; + } + case Dot: + { + const double dotWidth = + qMin( double( d_data->markerSize ), radius); + + const double dotCenterDist = radius - 0.5 * dotWidth; + if ( dotCenterDist > 0.0 ) + { + const QPointF center( xm - sinA * dotCenterDist, + ym - cosA * dotCenterDist ); + + QRectF ellipse( 0.0, 0.0, dotWidth, dotWidth ); + ellipse.moveCenter( center ); + + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().color( QPalette::ButtonText ) ); + painter->drawEllipse( ellipse ); + } + + break; + } + case Tick: + { + const double rb = qMax( radius - d_data->markerSize, 1.0 ); + const double re = radius; + + const QLine line( xm - sinA * rb, ym - cosA * rb, + xm - sinA * re, ym - cosA * re ); + + QPen pen( palette().color( QPalette::ButtonText ), 0 ); + pen.setCapStyle( Qt::FlatCap ); + painter->setPen( pen ); + painter->drawLine ( line ); + + break; + } +#if 0 + case Triangle: + { + const double rb = qMax( radius - d_data->markerSize, 1.0 ); + const double re = radius; + + painter->translate( rect.center() ); + painter->rotate( angle - 90.0 ); + + QPolygonF polygon; + polygon += QPointF( re, 0.0 ); + polygon += QPointF( rb, 0.5 * ( re - rb ) ); + polygon += QPointF( rb, -0.5 * ( re - rb ) ); + + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().color( QPalette::Text ) ); + painter->drawPolygon( polygon ); + break; + } +#endif + default: + break; + } +} + +/*! + \brief Change the knob's width. + + The specified width must be >= 5, or it will be clipped. + \param width New width +*/ +void QwtKnob::setKnobWidth( int width ) +{ + d_data->knobWidth = qMax( width, 5 ); + layoutKnob( true ); +} + +//! Return the width of the knob +int QwtKnob::knobWidth() const +{ + return d_data->knobWidth; +} + +/*! + \brief Set the knob's border width + \param borderWidth new border width +*/ +void QwtKnob::setBorderWidth( int borderWidth ) +{ + d_data->borderWidth = qMax( borderWidth, 0 ); + layoutKnob( true ); +} + +//! Return the border width +int QwtKnob::borderWidth() const +{ + return d_data->borderWidth; +} + +/*! + \brief Set the size of the marker + \sa markerSize(), markerStyle() +*/ +void QwtKnob::setMarkerSize( int size ) +{ + if ( d_data->markerSize != size ) + { + d_data->markerSize = size; + update(); + } +} + +//! Return the marker size +int QwtKnob::markerSize() const +{ + return d_data->markerSize; +} + +/*! + \brief Recalculate the marker angle corresponding to the + current value +*/ +void QwtKnob::recalcAngle() +{ + // + // calculate the angle corresponding to the value + // + if ( maxValue() == minValue() ) + { + d_data->angle = 0; + d_data->nTurns = 0; + } + else + { + d_data->angle = ( value() - 0.5 * ( minValue() + maxValue() ) ) + / ( maxValue() - minValue() ) * d_data->totalAngle; + d_data->nTurns = qFloor( ( d_data->angle + 180.0 ) / 360.0 ); + d_data->angle = d_data->angle - d_data->nTurns * 360.0; + } +} + + +/*! + Recalculates the layout + \sa layoutKnob() +*/ +void QwtKnob::scaleChange() +{ + layoutKnob( true ); +} + +/*! + \return minimumSizeHint() +*/ +QSize QwtKnob::sizeHint() const +{ + const QSize hint = minimumSizeHint(); + return hint.expandedTo( QApplication::globalStrut() ); +} + +/*! + \brief Return a minimum size hint + \warning The return value of QwtKnob::minimumSizeHint() depends on the + font and the scale. +*/ +QSize QwtKnob::minimumSizeHint() const +{ + // Add the scale radial thickness to the knobWidth + const int sh = qCeil( scaleDraw()->extent( font() ) ); + const int d = 2 * sh + 2 * d_data->scaleDist + d_data->knobWidth; + + return QSize( d, d ); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_knob.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_knob.h index c820128c5..355b4c573 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_knob.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_knob.h @@ -1,159 +1,159 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_KNOB_H -#define QWT_KNOB_H - -#include "qwt_global.h" -#include "qwt_abstract_slider.h" -#include "qwt_abstract_scale.h" - -class QwtRoundScaleDraw; - -/*! - \brief The Knob Widget - - The QwtKnob widget imitates look and behaviour of a volume knob on a radio. - It contains a scale around the knob which is set up automatically or can - be configured manually (see QwtAbstractScale). - Automatic scrolling is enabled when the user presses a mouse - button on the scale. For a description of signals, slots and other - members, see QwtAbstractSlider. - - \image html knob.png - \sa QwtAbstractSlider and QwtAbstractScale for the descriptions - of the inherited members. -*/ - -class QWT_EXPORT QwtKnob : public QwtAbstractSlider, public QwtAbstractScale -{ - Q_OBJECT - - Q_ENUMS ( KnobStyle ) - Q_ENUMS ( MarkerStyle ) - - Q_PROPERTY( KnobStyle knobStyle READ knobStyle WRITE setKnobStyle ) - Q_PROPERTY( MarkerStyle markerStyle READ markerStyle WRITE setMarkerStyle ) - Q_PROPERTY( int knobWidth READ knobWidth WRITE setKnobWidth ) - Q_PROPERTY( int borderWidth READ borderWidth WRITE setBorderWidth ) - Q_PROPERTY( double totalAngle READ totalAngle WRITE setTotalAngle ) - Q_PROPERTY( int markerSize READ markerSize WRITE setMarkerSize ) - Q_PROPERTY( int borderWidth READ borderWidth WRITE setBorderWidth ) - -public: - /*! - \brief Style of the knob surface - - Depending on the KnobStyle the surface of the knob is - filled from the brushes of the widget palette(). - - \sa setKnobStyle(), knobStyle() - */ - enum KnobStyle - { - //! Fill the knob with a brush from QPalette::Button. - NoStyle = -1, - - //! Build a gradient from QPalette::Midlight and QPalette::Button - Raised, - - /*! - Build a gradient from QPalette::Midlight, QPalette::Button - and QPalette::Midlight - */ - Sunken - }; - - /*! - \brief Marker type - - The marker indicates the current value on the knob - The default setting is a Notch marker. - - \sa setMarkerStyle(), setMarkerSize() - */ - enum MarkerStyle - { - //! Don't paint any marker - NoMarker = -1, - - //! Paint a single tick in QPalette::ButtonText color - Tick, - - //! Paint a circle in QPalette::ButtonText color - Dot, - - /*! - Draw a raised ellipse with a gradient build from - QPalette::Light and QPalette::Mid - */ - Nub, - - /*! - Draw a sunken ellipse with a gradient build from - QPalette::Light and QPalette::Mid - */ - Notch - }; - - explicit QwtKnob( QWidget* parent = NULL ); - virtual ~QwtKnob(); - - void setKnobWidth( int w ); - int knobWidth() const; - - void setTotalAngle ( double angle ); - double totalAngle() const; - - void setKnobStyle( KnobStyle ); - KnobStyle knobStyle() const; - - void setBorderWidth( int bw ); - int borderWidth() const; - - void setMarkerStyle( MarkerStyle ); - MarkerStyle markerStyle() const; - - void setMarkerSize( int ); - int markerSize() const; - - virtual QSize sizeHint() const; - virtual QSize minimumSizeHint() const; - - void setScaleDraw( QwtRoundScaleDraw * ); - const QwtRoundScaleDraw *scaleDraw() const; - QwtRoundScaleDraw *scaleDraw(); - -protected: - virtual void paintEvent( QPaintEvent * ); - virtual void resizeEvent( QResizeEvent * ); - virtual void changeEvent( QEvent * ); - - virtual void drawKnob( QPainter *, const QRectF & ) const; - virtual void drawMarker( QPainter *, - const QRectF &, double arc ) const; - - virtual double getValue( const QPoint &p ); - virtual void getScrollMode( const QPoint &, - QwtAbstractSlider::ScrollMode &, int &direction ) const; - -private: - void initKnob(); - void layoutKnob( bool update ); - void recalcAngle(); - - virtual void valueChange(); - virtual void rangeChange(); - virtual void scaleChange(); - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_KNOB_H +#define QWT_KNOB_H + +#include "qwt_global.h" +#include "qwt_abstract_slider.h" +#include "qwt_abstract_scale.h" + +class QwtRoundScaleDraw; + +/*! + \brief The Knob Widget + + The QwtKnob widget imitates look and behaviour of a volume knob on a radio. + It contains a scale around the knob which is set up automatically or can + be configured manually (see QwtAbstractScale). + Automatic scrolling is enabled when the user presses a mouse + button on the scale. For a description of signals, slots and other + members, see QwtAbstractSlider. + + \image html knob.png + \sa QwtAbstractSlider and QwtAbstractScale for the descriptions + of the inherited members. +*/ + +class QWT_EXPORT QwtKnob : public QwtAbstractSlider, public QwtAbstractScale +{ + Q_OBJECT + + Q_ENUMS ( KnobStyle ) + Q_ENUMS ( MarkerStyle ) + + Q_PROPERTY( KnobStyle knobStyle READ knobStyle WRITE setKnobStyle ) + Q_PROPERTY( MarkerStyle markerStyle READ markerStyle WRITE setMarkerStyle ) + Q_PROPERTY( int knobWidth READ knobWidth WRITE setKnobWidth ) + Q_PROPERTY( int borderWidth READ borderWidth WRITE setBorderWidth ) + Q_PROPERTY( double totalAngle READ totalAngle WRITE setTotalAngle ) + Q_PROPERTY( int markerSize READ markerSize WRITE setMarkerSize ) + Q_PROPERTY( int borderWidth READ borderWidth WRITE setBorderWidth ) + +public: + /*! + \brief Style of the knob surface + + Depending on the KnobStyle the surface of the knob is + filled from the brushes of the widget palette(). + + \sa setKnobStyle(), knobStyle() + */ + enum KnobStyle + { + //! Fill the knob with a brush from QPalette::Button. + NoStyle = -1, + + //! Build a gradient from QPalette::Midlight and QPalette::Button + Raised, + + /*! + Build a gradient from QPalette::Midlight, QPalette::Button + and QPalette::Midlight + */ + Sunken + }; + + /*! + \brief Marker type + + The marker indicates the current value on the knob + The default setting is a Notch marker. + + \sa setMarkerStyle(), setMarkerSize() + */ + enum MarkerStyle + { + //! Don't paint any marker + NoMarker = -1, + + //! Paint a single tick in QPalette::ButtonText color + Tick, + + //! Paint a circle in QPalette::ButtonText color + Dot, + + /*! + Draw a raised ellipse with a gradient build from + QPalette::Light and QPalette::Mid + */ + Nub, + + /*! + Draw a sunken ellipse with a gradient build from + QPalette::Light and QPalette::Mid + */ + Notch + }; + + explicit QwtKnob( QWidget* parent = NULL ); + virtual ~QwtKnob(); + + void setKnobWidth( int w ); + int knobWidth() const; + + void setTotalAngle ( double angle ); + double totalAngle() const; + + void setKnobStyle( KnobStyle ); + KnobStyle knobStyle() const; + + void setBorderWidth( int bw ); + int borderWidth() const; + + void setMarkerStyle( MarkerStyle ); + MarkerStyle markerStyle() const; + + void setMarkerSize( int ); + int markerSize() const; + + virtual QSize sizeHint() const; + virtual QSize minimumSizeHint() const; + + void setScaleDraw( QwtRoundScaleDraw * ); + const QwtRoundScaleDraw *scaleDraw() const; + QwtRoundScaleDraw *scaleDraw(); + +protected: + virtual void paintEvent( QPaintEvent * ); + virtual void resizeEvent( QResizeEvent * ); + virtual void changeEvent( QEvent * ); + + virtual void drawKnob( QPainter *, const QRectF & ) const; + virtual void drawMarker( QPainter *, + const QRectF &, double arc ) const; + + virtual double getValue( const QPoint &p ); + virtual void getScrollMode( const QPoint &, + QwtAbstractSlider::ScrollMode &, int &direction ) const; + +private: + void initKnob(); + void layoutKnob( bool update ); + void recalcAngle(); + + virtual void valueChange(); + virtual void rangeChange(); + virtual void scaleChange(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_legend.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_legend.cpp index 1e73accd0..f4797e60b 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_legend.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_legend.cpp @@ -1,519 +1,519 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_legend.h" -#include "qwt_legend_itemmanager.h" -#include "qwt_legend_item.h" -#include "qwt_dyngrid_layout.h" -#include "qwt_math.h" -#include -#include -#include -#include - -class QwtLegend::PrivateData -{ -public: - class LegendMap - { - public: - void insert( const QwtLegendItemManager *, QWidget * ); - - void remove( const QwtLegendItemManager * ); - void remove( QWidget * ); - - void clear(); - - uint count() const; - - inline const QWidget *find( const QwtLegendItemManager * ) const; - inline QWidget *find( const QwtLegendItemManager * ); - - inline const QwtLegendItemManager *find( const QWidget * ) const; - inline QwtLegendItemManager *find( const QWidget * ); - - const QMap &widgetMap() const; - QMap &widgetMap(); - - private: - QMap d_widgetMap; - QMap d_itemMap; - }; - - QwtLegend::LegendItemMode itemMode; - - LegendMap map; - - class LegendView; - LegendView *view; -}; - -class QwtLegend::PrivateData::LegendView: public QScrollArea -{ -public: - LegendView( QWidget *parent ): - QScrollArea( parent ) - { - setFocusPolicy( Qt::NoFocus ); - - contentsWidget = new QWidget( this ); - contentsWidget->setObjectName( "QwtLegendViewContents" ); - - setWidget( contentsWidget ); - setWidgetResizable( false ); - - viewport()->setObjectName( "QwtLegendViewport" ); - - // QScrollArea::setWidget internally sets autoFillBackground to true - // But we don't want a background. - contentsWidget->setAutoFillBackground( false ); - viewport()->setAutoFillBackground( false ); - } - - virtual bool viewportEvent( QEvent *e ) - { - bool ok = QScrollArea::viewportEvent( e ); - - if ( e->type() == QEvent::Resize ) - { - QEvent event( QEvent::LayoutRequest ); - QApplication::sendEvent( contentsWidget, &event ); - } - return ok; - } - - QSize viewportSize( int w, int h ) const - { - const int sbHeight = horizontalScrollBar()->sizeHint().height(); - const int sbWidth = verticalScrollBar()->sizeHint().width(); - - const int cw = contentsRect().width(); - const int ch = contentsRect().height(); - - int vw = cw; - int vh = ch; - - if ( w > vw ) - vh -= sbHeight; - - if ( h > vh ) - { - vw -= sbWidth; - if ( w > vw && vh == ch ) - vh -= sbHeight; - } - return QSize( vw, vh ); - } - - QWidget *contentsWidget; -}; - -void QwtLegend::PrivateData::LegendMap::insert( - const QwtLegendItemManager *item, QWidget *widget ) -{ - d_itemMap.insert( item, widget ); - d_widgetMap.insert( widget, item ); -} - -void QwtLegend::PrivateData::LegendMap::remove( const QwtLegendItemManager *item ) -{ - QWidget *widget = d_itemMap[item]; - d_itemMap.remove( item ); - d_widgetMap.remove( widget ); -} - -void QwtLegend::PrivateData::LegendMap::remove( QWidget *widget ) -{ - const QwtLegendItemManager *item = d_widgetMap[widget]; - d_itemMap.remove( item ); - d_widgetMap.remove( widget ); -} - -void QwtLegend::PrivateData::LegendMap::clear() -{ - - /* - We can't delete the widgets in the following loop, because - we would get ChildRemoved events, changing d_itemMap, while - we are iterating. - */ - - QList widgets; - - QMap::const_iterator it; - for ( it = d_itemMap.begin(); it != d_itemMap.end(); ++it ) - widgets.append( it.value() ); - - d_itemMap.clear(); - d_widgetMap.clear(); - - for ( int i = 0; i < widgets.size(); i++ ) - delete widgets[i]; -} - -uint QwtLegend::PrivateData::LegendMap::count() const -{ - return d_itemMap.count(); -} - -inline const QWidget *QwtLegend::PrivateData::LegendMap::find( - const QwtLegendItemManager *item ) const -{ - if ( !d_itemMap.contains( item ) ) - return NULL; - - return d_itemMap[item]; -} - -inline QWidget *QwtLegend::PrivateData::LegendMap::find( - const QwtLegendItemManager *item ) -{ - if ( !d_itemMap.contains( item ) ) - return NULL; - - return d_itemMap[item]; -} - -inline const QwtLegendItemManager *QwtLegend::PrivateData::LegendMap::find( - const QWidget *widget ) const -{ - QWidget *w = const_cast( widget ); - if ( !d_widgetMap.contains( w ) ) - return NULL; - - return d_widgetMap[w]; -} - -inline QwtLegendItemManager *QwtLegend::PrivateData::LegendMap::find( - const QWidget *widget ) -{ - QWidget *w = const_cast( widget ); - if ( !d_widgetMap.contains( w ) ) - return NULL; - - return const_cast( d_widgetMap[w] ); -} - -inline const QMap & -QwtLegend::PrivateData::LegendMap::widgetMap() const -{ - return d_widgetMap; -} - -inline QMap & -QwtLegend::PrivateData::LegendMap::widgetMap() -{ - return d_widgetMap; -} - -/*! - Constructor - - \param parent Parent widget -*/ -QwtLegend::QwtLegend( QWidget *parent ): - QFrame( parent ) -{ - setFrameStyle( NoFrame ); - - d_data = new QwtLegend::PrivateData; - d_data->itemMode = QwtLegend::ReadOnlyItem; - - d_data->view = new QwtLegend::PrivateData::LegendView( this ); - d_data->view->setObjectName( "QwtLegendView" ); - d_data->view->setFrameStyle( NoFrame ); - - QwtDynGridLayout *gridLayout = new QwtDynGridLayout( - d_data->view->contentsWidget ); - gridLayout->setAlignment( Qt::AlignHCenter | Qt::AlignTop ); - - d_data->view->contentsWidget->installEventFilter( this ); - - QVBoxLayout *layout = new QVBoxLayout( this ); - layout->setContentsMargins( 0, 0, 0, 0 ); - layout->addWidget( d_data->view ); -} - -//! Destructor -QwtLegend::~QwtLegend() -{ - delete d_data; -} - -//! \sa LegendItemMode -void QwtLegend::setItemMode( LegendItemMode mode ) -{ - d_data->itemMode = mode; -} - -//! \sa LegendItemMode -QwtLegend::LegendItemMode QwtLegend::itemMode() const -{ - return d_data->itemMode; -} - -/*! - The contents widget is the only child of the viewport of - the internal QScrollArea and the parent widget of all legend items. - - \return Container widget of the legend items -*/ -QWidget *QwtLegend::contentsWidget() -{ - return d_data->view->contentsWidget; -} - -/*! - \return Horizontal scrollbar - \sa verticalScrollBar() -*/ -QScrollBar *QwtLegend::horizontalScrollBar() const -{ - return d_data->view->horizontalScrollBar(); -} - -/*! - \return Vertical scrollbar - \sa horizontalScrollBar() -*/ -QScrollBar *QwtLegend::verticalScrollBar() const -{ - return d_data->view->verticalScrollBar(); -} - -/*! - The contents widget is the only child of the viewport of - the internal QScrollArea and the parent widget of all legend items. - - \return Container widget of the legend items - -*/ -const QWidget *QwtLegend::contentsWidget() const -{ - return d_data->view->contentsWidget; -} - -/*! - Insert a new item for a plot item - \param plotItem Plot item - \param legendItem New legend item - \note The parent of item will be changed to contentsWidget() -*/ -void QwtLegend::insert( const QwtLegendItemManager *plotItem, QWidget *legendItem ) -{ - if ( legendItem == NULL || plotItem == NULL ) - return; - - QWidget *contentsWidget = d_data->view->contentsWidget; - - if ( legendItem->parent() != contentsWidget ) - legendItem->setParent( contentsWidget ); - - legendItem->show(); - - d_data->map.insert( plotItem, legendItem ); - - layoutContents(); - - if ( contentsWidget->layout() ) - { - contentsWidget->layout()->addWidget( legendItem ); - - // set tab focus chain - - QWidget *w = NULL; - - for ( int i = 0; i < contentsWidget->layout()->count(); i++ ) - { - QLayoutItem *item = contentsWidget->layout()->itemAt( i ); - if ( w && item->widget() ) - QWidget::setTabOrder( w, item->widget() ); - - w = item->widget(); - } - } - if ( parentWidget() && parentWidget()->layout() == NULL ) - { - /* - updateGeometry() doesn't post LayoutRequest in certain - situations, like when we are hidden. But we want the - parent widget notified, so it can show/hide the legend - depending on its items. - */ - QApplication::postEvent( parentWidget(), - new QEvent( QEvent::LayoutRequest ) ); - } -} - -/*! - Find the widget that represents a plot item - - \param plotItem Plot item - \return Widget on the legend, or NULL -*/ -QWidget *QwtLegend::find( const QwtLegendItemManager *plotItem ) const -{ - return d_data->map.find( plotItem ); -} - -/*! - Find the widget that represents a plot item - - \param legendItem Legend item - \return Widget on the legend, or NULL -*/ -QwtLegendItemManager *QwtLegend::find( const QWidget *legendItem ) const -{ - return d_data->map.find( legendItem ); -} - -/*! - Find the corresponding item for a plotItem and remove it - from the item list. - - \param plotItem Plot item -*/ -void QwtLegend::remove( const QwtLegendItemManager *plotItem ) -{ - QWidget *legendItem = d_data->map.find( plotItem ); - d_data->map.remove( legendItem ); - delete legendItem; -} - -//! Remove all items. -void QwtLegend::clear() -{ - bool doUpdate = updatesEnabled(); - if ( doUpdate ) - setUpdatesEnabled( false ); - - d_data->map.clear(); - - if ( doUpdate ) - setUpdatesEnabled( true ); - - update(); -} - -//! Return a size hint. -QSize QwtLegend::sizeHint() const -{ - QSize hint = d_data->view->contentsWidget->sizeHint(); - hint += QSize( 2 * frameWidth(), 2 * frameWidth() ); - - return hint; -} - -/*! - \return The preferred height, for the width w. - \param width Width -*/ -int QwtLegend::heightForWidth( int width ) const -{ - width -= 2 * frameWidth(); - - int h = d_data->view->contentsWidget->heightForWidth( width ); - if ( h >= 0 ) - h += 2 * frameWidth(); - - return h; -} - -/*! - Adjust contents widget and item layout to the size of the viewport(). -*/ -void QwtLegend::layoutContents() -{ - const QSize visibleSize = - d_data->view->viewport()->contentsRect().size(); - - const QwtDynGridLayout *tl = qobject_cast( - d_data->view->contentsWidget->layout() ); - if ( tl ) - { - const int minW = int( tl->maxItemWidth() ) + 2 * tl->margin(); - - int w = qMax( visibleSize.width(), minW ); - int h = qMax( tl->heightForWidth( w ), visibleSize.height() ); - - const int vpWidth = d_data->view->viewportSize( w, h ).width(); - if ( w > vpWidth ) - { - w = qMax( vpWidth, minW ); - h = qMax( tl->heightForWidth( w ), visibleSize.height() ); - } - - d_data->view->contentsWidget->resize( w, h ); - } -} - -/*! - Handle QEvent::ChildRemoved andQEvent::LayoutRequest events - for the contentsWidget(). - - \param object Object to be filtered - \param event Event -*/ -bool QwtLegend::eventFilter( QObject *object, QEvent *event ) -{ - if ( object == d_data->view->contentsWidget ) - { - switch ( event->type() ) - { - case QEvent::ChildRemoved: - { - const QChildEvent *ce = - static_cast(event); - if ( ce->child()->isWidgetType() ) - { - QWidget *w = static_cast< QWidget * >( ce->child() ); - d_data->map.remove( w ); - } - break; - } - case QEvent::LayoutRequest: - { - layoutContents(); - break; - } - default: - break; - } - } - - return QFrame::eventFilter( object, event ); -} - - -//! Return true, if there are no legend items. -bool QwtLegend::isEmpty() const -{ - return d_data->map.count() == 0; -} - -//! Return the number of legend items. -uint QwtLegend::itemCount() const -{ - return d_data->map.count(); -} - -//! Return a list of all legend items -QList QwtLegend::legendItems() const -{ - const QMap &map = - d_data->map.widgetMap(); - - QList list; - - QMap::const_iterator it; - for ( it = map.begin(); it != map.end(); ++it ) - list += it.key(); - - return list; +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_legend.h" +#include "qwt_legend_itemmanager.h" +#include "qwt_legend_item.h" +#include "qwt_dyngrid_layout.h" +#include "qwt_math.h" +#include +#include +#include +#include + +class QwtLegend::PrivateData +{ +public: + class LegendMap + { + public: + void insert( const QwtLegendItemManager *, QWidget * ); + + void remove( const QwtLegendItemManager * ); + void remove( QWidget * ); + + void clear(); + + uint count() const; + + inline const QWidget *find( const QwtLegendItemManager * ) const; + inline QWidget *find( const QwtLegendItemManager * ); + + inline const QwtLegendItemManager *find( const QWidget * ) const; + inline QwtLegendItemManager *find( const QWidget * ); + + const QMap &widgetMap() const; + QMap &widgetMap(); + + private: + QMap d_widgetMap; + QMap d_itemMap; + }; + + QwtLegend::LegendItemMode itemMode; + + LegendMap map; + + class LegendView; + LegendView *view; +}; + +class QwtLegend::PrivateData::LegendView: public QScrollArea +{ +public: + LegendView( QWidget *parent ): + QScrollArea( parent ) + { + setFocusPolicy( Qt::NoFocus ); + + contentsWidget = new QWidget( this ); + contentsWidget->setObjectName( "QwtLegendViewContents" ); + + setWidget( contentsWidget ); + setWidgetResizable( false ); + + viewport()->setObjectName( "QwtLegendViewport" ); + + // QScrollArea::setWidget internally sets autoFillBackground to true + // But we don't want a background. + contentsWidget->setAutoFillBackground( false ); + viewport()->setAutoFillBackground( false ); + } + + virtual bool viewportEvent( QEvent *e ) + { + bool ok = QScrollArea::viewportEvent( e ); + + if ( e->type() == QEvent::Resize ) + { + QEvent event( QEvent::LayoutRequest ); + QApplication::sendEvent( contentsWidget, &event ); + } + return ok; + } + + QSize viewportSize( int w, int h ) const + { + const int sbHeight = horizontalScrollBar()->sizeHint().height(); + const int sbWidth = verticalScrollBar()->sizeHint().width(); + + const int cw = contentsRect().width(); + const int ch = contentsRect().height(); + + int vw = cw; + int vh = ch; + + if ( w > vw ) + vh -= sbHeight; + + if ( h > vh ) + { + vw -= sbWidth; + if ( w > vw && vh == ch ) + vh -= sbHeight; + } + return QSize( vw, vh ); + } + + QWidget *contentsWidget; +}; + +void QwtLegend::PrivateData::LegendMap::insert( + const QwtLegendItemManager *item, QWidget *widget ) +{ + d_itemMap.insert( item, widget ); + d_widgetMap.insert( widget, item ); +} + +void QwtLegend::PrivateData::LegendMap::remove( const QwtLegendItemManager *item ) +{ + QWidget *widget = d_itemMap[item]; + d_itemMap.remove( item ); + d_widgetMap.remove( widget ); +} + +void QwtLegend::PrivateData::LegendMap::remove( QWidget *widget ) +{ + const QwtLegendItemManager *item = d_widgetMap[widget]; + d_itemMap.remove( item ); + d_widgetMap.remove( widget ); +} + +void QwtLegend::PrivateData::LegendMap::clear() +{ + + /* + We can't delete the widgets in the following loop, because + we would get ChildRemoved events, changing d_itemMap, while + we are iterating. + */ + + QList widgets; + + QMap::const_iterator it; + for ( it = d_itemMap.begin(); it != d_itemMap.end(); ++it ) + widgets.append( it.value() ); + + d_itemMap.clear(); + d_widgetMap.clear(); + + for ( int i = 0; i < widgets.size(); i++ ) + delete widgets[i]; +} + +uint QwtLegend::PrivateData::LegendMap::count() const +{ + return d_itemMap.count(); +} + +inline const QWidget *QwtLegend::PrivateData::LegendMap::find( + const QwtLegendItemManager *item ) const +{ + if ( !d_itemMap.contains( item ) ) + return NULL; + + return d_itemMap[item]; +} + +inline QWidget *QwtLegend::PrivateData::LegendMap::find( + const QwtLegendItemManager *item ) +{ + if ( !d_itemMap.contains( item ) ) + return NULL; + + return d_itemMap[item]; +} + +inline const QwtLegendItemManager *QwtLegend::PrivateData::LegendMap::find( + const QWidget *widget ) const +{ + QWidget *w = const_cast( widget ); + if ( !d_widgetMap.contains( w ) ) + return NULL; + + return d_widgetMap[w]; +} + +inline QwtLegendItemManager *QwtLegend::PrivateData::LegendMap::find( + const QWidget *widget ) +{ + QWidget *w = const_cast( widget ); + if ( !d_widgetMap.contains( w ) ) + return NULL; + + return const_cast( d_widgetMap[w] ); +} + +inline const QMap & +QwtLegend::PrivateData::LegendMap::widgetMap() const +{ + return d_widgetMap; +} + +inline QMap & +QwtLegend::PrivateData::LegendMap::widgetMap() +{ + return d_widgetMap; +} + +/*! + Constructor + + \param parent Parent widget +*/ +QwtLegend::QwtLegend( QWidget *parent ): + QFrame( parent ) +{ + setFrameStyle( NoFrame ); + + d_data = new QwtLegend::PrivateData; + d_data->itemMode = QwtLegend::ReadOnlyItem; + + d_data->view = new QwtLegend::PrivateData::LegendView( this ); + d_data->view->setObjectName( "QwtLegendView" ); + d_data->view->setFrameStyle( NoFrame ); + + QwtDynGridLayout *gridLayout = new QwtDynGridLayout( + d_data->view->contentsWidget ); + gridLayout->setAlignment( Qt::AlignHCenter | Qt::AlignTop ); + + d_data->view->contentsWidget->installEventFilter( this ); + + QVBoxLayout *layout = new QVBoxLayout( this ); + layout->setContentsMargins( 0, 0, 0, 0 ); + layout->addWidget( d_data->view ); +} + +//! Destructor +QwtLegend::~QwtLegend() +{ + delete d_data; +} + +//! \sa LegendItemMode +void QwtLegend::setItemMode( LegendItemMode mode ) +{ + d_data->itemMode = mode; +} + +//! \sa LegendItemMode +QwtLegend::LegendItemMode QwtLegend::itemMode() const +{ + return d_data->itemMode; +} + +/*! + The contents widget is the only child of the viewport of + the internal QScrollArea and the parent widget of all legend items. + + \return Container widget of the legend items +*/ +QWidget *QwtLegend::contentsWidget() +{ + return d_data->view->contentsWidget; +} + +/*! + \return Horizontal scrollbar + \sa verticalScrollBar() +*/ +QScrollBar *QwtLegend::horizontalScrollBar() const +{ + return d_data->view->horizontalScrollBar(); +} + +/*! + \return Vertical scrollbar + \sa horizontalScrollBar() +*/ +QScrollBar *QwtLegend::verticalScrollBar() const +{ + return d_data->view->verticalScrollBar(); +} + +/*! + The contents widget is the only child of the viewport of + the internal QScrollArea and the parent widget of all legend items. + + \return Container widget of the legend items + +*/ +const QWidget *QwtLegend::contentsWidget() const +{ + return d_data->view->contentsWidget; +} + +/*! + Insert a new item for a plot item + \param plotItem Plot item + \param legendItem New legend item + \note The parent of item will be changed to contentsWidget() +*/ +void QwtLegend::insert( const QwtLegendItemManager *plotItem, QWidget *legendItem ) +{ + if ( legendItem == NULL || plotItem == NULL ) + return; + + QWidget *contentsWidget = d_data->view->contentsWidget; + + if ( legendItem->parent() != contentsWidget ) + legendItem->setParent( contentsWidget ); + + legendItem->show(); + + d_data->map.insert( plotItem, legendItem ); + + layoutContents(); + + if ( contentsWidget->layout() ) + { + contentsWidget->layout()->addWidget( legendItem ); + + // set tab focus chain + + QWidget *w = NULL; + + for ( int i = 0; i < contentsWidget->layout()->count(); i++ ) + { + QLayoutItem *item = contentsWidget->layout()->itemAt( i ); + if ( w && item->widget() ) + QWidget::setTabOrder( w, item->widget() ); + + w = item->widget(); + } + } + if ( parentWidget() && parentWidget()->layout() == NULL ) + { + /* + updateGeometry() doesn't post LayoutRequest in certain + situations, like when we are hidden. But we want the + parent widget notified, so it can show/hide the legend + depending on its items. + */ + QApplication::postEvent( parentWidget(), + new QEvent( QEvent::LayoutRequest ) ); + } +} + +/*! + Find the widget that represents a plot item + + \param plotItem Plot item + \return Widget on the legend, or NULL +*/ +QWidget *QwtLegend::find( const QwtLegendItemManager *plotItem ) const +{ + return d_data->map.find( plotItem ); +} + +/*! + Find the widget that represents a plot item + + \param legendItem Legend item + \return Widget on the legend, or NULL +*/ +QwtLegendItemManager *QwtLegend::find( const QWidget *legendItem ) const +{ + return d_data->map.find( legendItem ); +} + +/*! + Find the corresponding item for a plotItem and remove it + from the item list. + + \param plotItem Plot item +*/ +void QwtLegend::remove( const QwtLegendItemManager *plotItem ) +{ + QWidget *legendItem = d_data->map.find( plotItem ); + d_data->map.remove( legendItem ); + delete legendItem; +} + +//! Remove all items. +void QwtLegend::clear() +{ + bool doUpdate = updatesEnabled(); + if ( doUpdate ) + setUpdatesEnabled( false ); + + d_data->map.clear(); + + if ( doUpdate ) + setUpdatesEnabled( true ); + + update(); +} + +//! Return a size hint. +QSize QwtLegend::sizeHint() const +{ + QSize hint = d_data->view->contentsWidget->sizeHint(); + hint += QSize( 2 * frameWidth(), 2 * frameWidth() ); + + return hint; +} + +/*! + \return The preferred height, for the width w. + \param width Width +*/ +int QwtLegend::heightForWidth( int width ) const +{ + width -= 2 * frameWidth(); + + int h = d_data->view->contentsWidget->heightForWidth( width ); + if ( h >= 0 ) + h += 2 * frameWidth(); + + return h; +} + +/*! + Adjust contents widget and item layout to the size of the viewport(). +*/ +void QwtLegend::layoutContents() +{ + const QSize visibleSize = + d_data->view->viewport()->contentsRect().size(); + + const QwtDynGridLayout *tl = qobject_cast( + d_data->view->contentsWidget->layout() ); + if ( tl ) + { + const int minW = int( tl->maxItemWidth() ) + 2 * tl->margin(); + + int w = qMax( visibleSize.width(), minW ); + int h = qMax( tl->heightForWidth( w ), visibleSize.height() ); + + const int vpWidth = d_data->view->viewportSize( w, h ).width(); + if ( w > vpWidth ) + { + w = qMax( vpWidth, minW ); + h = qMax( tl->heightForWidth( w ), visibleSize.height() ); + } + + d_data->view->contentsWidget->resize( w, h ); + } +} + +/*! + Handle QEvent::ChildRemoved andQEvent::LayoutRequest events + for the contentsWidget(). + + \param object Object to be filtered + \param event Event +*/ +bool QwtLegend::eventFilter( QObject *object, QEvent *event ) +{ + if ( object == d_data->view->contentsWidget ) + { + switch ( event->type() ) + { + case QEvent::ChildRemoved: + { + const QChildEvent *ce = + static_cast(event); + if ( ce->child()->isWidgetType() ) + { + QWidget *w = static_cast< QWidget * >( ce->child() ); + d_data->map.remove( w ); + } + break; + } + case QEvent::LayoutRequest: + { + layoutContents(); + break; + } + default: + break; + } + } + + return QFrame::eventFilter( object, event ); +} + + +//! Return true, if there are no legend items. +bool QwtLegend::isEmpty() const +{ + return d_data->map.count() == 0; +} + +//! Return the number of legend items. +uint QwtLegend::itemCount() const +{ + return d_data->map.count(); +} + +//! Return a list of all legend items +QList QwtLegend::legendItems() const +{ + const QMap &map = + d_data->map.widgetMap(); + + QList list; + + QMap::const_iterator it; + for ( it = map.begin(); it != map.end(); ++it ) + list += it.key(); + + return list; } \ No newline at end of file diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_legend.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_legend.h index 03cdb4b57..e24178321 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_legend.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_legend.h @@ -1,95 +1,95 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_LEGEND_H -#define QWT_LEGEND_H - -#include "qwt_global.h" -#include -#include - -class QScrollBar; -class QwtLegendItemManager; - -/*! - \brief The legend widget - - The QwtLegend widget is a tabular arrangement of legend items. Legend - items might be any type of widget, but in general they will be - a QwtLegendItem. - - \sa QwtLegendItem, QwtLegendItemManager QwtPlot -*/ - -class QWT_EXPORT QwtLegend : public QFrame -{ - Q_OBJECT - -public: - /*! - \brief Interaction mode for the legend items - - The default is QwtLegend::ReadOnlyItem. - - \sa setItemMode(), itemMode(), QwtLegendItem::IdentifierMode - QwtLegendItem::clicked(), QwtLegendItem::checked(), - QwtPlot::legendClicked(), QwtPlot::legendChecked() - */ - - enum LegendItemMode - { - //! The legend item is not interactive, like a label - ReadOnlyItem, - - //! The legend item is clickable, like a push button - ClickableItem, - - //! The legend item is checkable, like a checkable button - CheckableItem - }; - - explicit QwtLegend( QWidget *parent = NULL ); - virtual ~QwtLegend(); - - void setItemMode( LegendItemMode ); - LegendItemMode itemMode() const; - - QWidget *contentsWidget(); - const QWidget *contentsWidget() const; - - void insert( const QwtLegendItemManager *, QWidget * ); - void remove( const QwtLegendItemManager * ); - - QWidget *find( const QwtLegendItemManager * ) const; - QwtLegendItemManager *find( const QWidget * ) const; - - virtual QList legendItems() const; - - void clear(); - - bool isEmpty() const; - uint itemCount() const; - - virtual bool eventFilter( QObject *, QEvent * ); - - virtual QSize sizeHint() const; - virtual int heightForWidth( int w ) const; - - QScrollBar *horizontalScrollBar() const; - QScrollBar *verticalScrollBar() const; - -protected: - virtual void layoutContents(); - -private: - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_LEGEND_H +#define QWT_LEGEND_H + +#include "qwt_global.h" +#include +#include + +class QScrollBar; +class QwtLegendItemManager; + +/*! + \brief The legend widget + + The QwtLegend widget is a tabular arrangement of legend items. Legend + items might be any type of widget, but in general they will be + a QwtLegendItem. + + \sa QwtLegendItem, QwtLegendItemManager QwtPlot +*/ + +class QWT_EXPORT QwtLegend : public QFrame +{ + Q_OBJECT + +public: + /*! + \brief Interaction mode for the legend items + + The default is QwtLegend::ReadOnlyItem. + + \sa setItemMode(), itemMode(), QwtLegendItem::IdentifierMode + QwtLegendItem::clicked(), QwtLegendItem::checked(), + QwtPlot::legendClicked(), QwtPlot::legendChecked() + */ + + enum LegendItemMode + { + //! The legend item is not interactive, like a label + ReadOnlyItem, + + //! The legend item is clickable, like a push button + ClickableItem, + + //! The legend item is checkable, like a checkable button + CheckableItem + }; + + explicit QwtLegend( QWidget *parent = NULL ); + virtual ~QwtLegend(); + + void setItemMode( LegendItemMode ); + LegendItemMode itemMode() const; + + QWidget *contentsWidget(); + const QWidget *contentsWidget() const; + + void insert( const QwtLegendItemManager *, QWidget * ); + void remove( const QwtLegendItemManager * ); + + QWidget *find( const QwtLegendItemManager * ) const; + QwtLegendItemManager *find( const QWidget * ) const; + + virtual QList legendItems() const; + + void clear(); + + bool isEmpty() const; + uint itemCount() const; + + virtual bool eventFilter( QObject *, QEvent * ); + + virtual QSize sizeHint() const; + virtual int heightForWidth( int w ) const; + + QScrollBar *horizontalScrollBar() const; + QScrollBar *verticalScrollBar() const; + +protected: + virtual void layoutContents(); + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_item.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_item.cpp index 67cc7b012..81a30ac36 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_item.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_item.cpp @@ -1,405 +1,405 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_legend_item.h" -#include "qwt_math.h" -#include "qwt_painter.h" -#include "qwt_symbol.h" -#include -#include -#include -#include -#include -#include -#include - -static const int ButtonFrame = 2; -static const int Margin = 2; - -static QSize buttonShift( const QwtLegendItem *w ) -{ - QStyleOption option; - option.init( w ); - - const int ph = w->style()->pixelMetric( - QStyle::PM_ButtonShiftHorizontal, &option, w ); - const int pv = w->style()->pixelMetric( - QStyle::PM_ButtonShiftVertical, &option, w ); - return QSize( ph, pv ); -} - -class QwtLegendItem::PrivateData -{ -public: - PrivateData(): - itemMode( QwtLegend::ReadOnlyItem ), - isDown( false ), - identifierSize( 8, 8 ), - spacing( Margin ) - { - } - - QwtLegend::LegendItemMode itemMode; - bool isDown; - - QSize identifierSize; - QPixmap identifier; - - int spacing; -}; - -/*! - \param parent Parent widget -*/ -QwtLegendItem::QwtLegendItem( QWidget *parent ): - QwtTextLabel( parent ) -{ - d_data = new PrivateData; - setMargin( Margin ); - setIndent( Margin + d_data->identifierSize.width() + 2 * d_data->spacing ); -} - -//! Destructor -QwtLegendItem::~QwtLegendItem() -{ - delete d_data; - d_data = NULL; -} - -/*! - Set the text to the legend item - - \param text Text label - \sa QwtTextLabel::text() -*/ -void QwtLegendItem::setText( const QwtText &text ) -{ - const int flags = Qt::AlignLeft | Qt::AlignVCenter - | Qt::TextExpandTabs | Qt::TextWordWrap; - - QwtText txt = text; - txt.setRenderFlags( flags ); - - QwtTextLabel::setText( txt ); -} - -/*! - Set the item mode - The default is QwtLegend::ReadOnlyItem - - \param mode Item mode - \sa itemMode() -*/ -void QwtLegendItem::setItemMode( QwtLegend::LegendItemMode mode ) -{ - if ( mode != d_data->itemMode ) - { - d_data->itemMode = mode; - d_data->isDown = false; - - setFocusPolicy( mode != QwtLegend::ReadOnlyItem ? Qt::TabFocus : Qt::NoFocus ); - setMargin( ButtonFrame + Margin ); - - updateGeometry(); - } -} - -/*! - Return the item mode - - \sa setItemMode() -*/ -QwtLegend::LegendItemMode QwtLegendItem::itemMode() const -{ - return d_data->itemMode; -} - -/*! - Assign the identifier - The identifier needs to be created according to the identifierWidth() - - \param identifier Pixmap representing a plot item - - \sa identifier(), identifierWidth() -*/ -void QwtLegendItem::setIdentifier( const QPixmap &identifier ) -{ - d_data->identifier = identifier; - update(); -} - -/*! - \return pixmap representing a plot item - \sa setIdentifier() -*/ -QPixmap QwtLegendItem::identifier() const -{ - return d_data->identifier; -} - -/*! - Set the size for the identifier - Default is 8x8 pixels - - \param size New size - - \sa identifierSize() -*/ -void QwtLegendItem::setIdentifierSize( const QSize &size ) -{ - QSize sz = size.expandedTo( QSize( 0, 0 ) ); - if ( sz != d_data->identifierSize ) - { - d_data->identifierSize = sz; - setIndent( margin() + d_data->identifierSize.width() - + 2 * d_data->spacing ); - updateGeometry(); - } -} -/*! - Return the width of the identifier - - \sa setIdentifierSize() -*/ -QSize QwtLegendItem::identifierSize() const -{ - return d_data->identifierSize; -} - -/*! - Change the spacing - \param spacing Spacing - \sa spacing(), identifierWidth(), QwtTextLabel::margin() -*/ -void QwtLegendItem::setSpacing( int spacing ) -{ - spacing = qMax( spacing, 0 ); - if ( spacing != d_data->spacing ) - { - d_data->spacing = spacing; - setIndent( margin() + d_data->identifierSize.width() - + 2 * d_data->spacing ); - } -} - -/*! - Return the spacing - \sa setSpacing(), identifierWidth(), QwtTextLabel::margin() -*/ -int QwtLegendItem::spacing() const -{ - return d_data->spacing; -} - -/*! - Check/Uncheck a the item - - \param on check/uncheck - \sa setItemMode() -*/ -void QwtLegendItem::setChecked( bool on ) -{ - if ( d_data->itemMode == QwtLegend::CheckableItem ) - { - const bool isBlocked = signalsBlocked(); - blockSignals( true ); - - setDown( on ); - - blockSignals( isBlocked ); - } -} - -//! Return true, if the item is checked -bool QwtLegendItem::isChecked() const -{ - return d_data->itemMode == QwtLegend::CheckableItem && isDown(); -} - -//! Set the item being down -void QwtLegendItem::setDown( bool down ) -{ - if ( down == d_data->isDown ) - return; - - d_data->isDown = down; - update(); - - if ( d_data->itemMode == QwtLegend::ClickableItem ) - { - if ( d_data->isDown ) - Q_EMIT pressed(); - else - { - Q_EMIT released(); - Q_EMIT clicked(); - } - } - - if ( d_data->itemMode == QwtLegend::CheckableItem ) - Q_EMIT checked( d_data->isDown ); -} - -//! Return true, if the item is down -bool QwtLegendItem::isDown() const -{ - return d_data->isDown; -} - -//! Return a size hint -QSize QwtLegendItem::sizeHint() const -{ - QSize sz = QwtTextLabel::sizeHint(); - sz.setHeight( qMax( sz.height(), d_data->identifier.height() + 4 ) ); - - if ( d_data->itemMode != QwtLegend::ReadOnlyItem ) - { - sz += buttonShift( this ); - sz = sz.expandedTo( QApplication::globalStrut() ); - } - - return sz; -} - -//! Paint event -void QwtLegendItem::paintEvent( QPaintEvent *e ) -{ - const QRect cr = contentsRect(); - - QPainter painter( this ); - painter.setClipRegion( e->region() ); - - if ( d_data->isDown ) - { - qDrawWinButton( &painter, 0, 0, width(), height(), - palette(), true ); - } - - painter.save(); - - if ( d_data->isDown ) - { - const QSize shiftSize = buttonShift( this ); - painter.translate( shiftSize.width(), shiftSize.height() ); - } - - painter.setClipRect( cr ); - - drawContents( &painter ); - - if ( !d_data->identifier.isNull() ) - { - QRect identRect = cr; - identRect.setX( identRect.x() + margin() ); - if ( d_data->itemMode != QwtLegend::ReadOnlyItem ) - identRect.setX( identRect.x() + ButtonFrame ); - - identRect.setSize( d_data->identifier.size() ); - identRect.moveCenter( QPoint( identRect.center().x(), cr.center().y() ) ); - - painter.drawPixmap( identRect, d_data->identifier ); - } - - painter.restore(); -} - -//! Handle mouse press events -void QwtLegendItem::mousePressEvent( QMouseEvent *e ) -{ - if ( e->button() == Qt::LeftButton ) - { - switch ( d_data->itemMode ) - { - case QwtLegend::ClickableItem: - { - setDown( true ); - return; - } - case QwtLegend::CheckableItem: - { - setDown( !isDown() ); - return; - } - default:; - } - } - QwtTextLabel::mousePressEvent( e ); -} - -//! Handle mouse release events -void QwtLegendItem::mouseReleaseEvent( QMouseEvent *e ) -{ - if ( e->button() == Qt::LeftButton ) - { - switch ( d_data->itemMode ) - { - case QwtLegend::ClickableItem: - { - setDown( false ); - return; - } - case QwtLegend::CheckableItem: - { - return; // do nothing, but accept - } - default:; - } - } - QwtTextLabel::mouseReleaseEvent( e ); -} - -//! Handle key press events -void QwtLegendItem::keyPressEvent( QKeyEvent *e ) -{ - if ( e->key() == Qt::Key_Space ) - { - switch ( d_data->itemMode ) - { - case QwtLegend::ClickableItem: - { - if ( !e->isAutoRepeat() ) - setDown( true ); - return; - } - case QwtLegend::CheckableItem: - { - if ( !e->isAutoRepeat() ) - setDown( !isDown() ); - return; - } - default:; - } - } - - QwtTextLabel::keyPressEvent( e ); -} - -//! Handle key release events -void QwtLegendItem::keyReleaseEvent( QKeyEvent *e ) -{ - if ( e->key() == Qt::Key_Space ) - { - switch ( d_data->itemMode ) - { - case QwtLegend::ClickableItem: - { - if ( !e->isAutoRepeat() ) - setDown( false ); - return; - } - case QwtLegend::CheckableItem: - { - return; // do nothing, but accept - } - default:; - } - } - - QwtTextLabel::keyReleaseEvent( e ); +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_legend_item.h" +#include "qwt_math.h" +#include "qwt_painter.h" +#include "qwt_symbol.h" +#include +#include +#include +#include +#include +#include +#include + +static const int ButtonFrame = 2; +static const int Margin = 2; + +static QSize buttonShift( const QwtLegendItem *w ) +{ + QStyleOption option; + option.init( w ); + + const int ph = w->style()->pixelMetric( + QStyle::PM_ButtonShiftHorizontal, &option, w ); + const int pv = w->style()->pixelMetric( + QStyle::PM_ButtonShiftVertical, &option, w ); + return QSize( ph, pv ); +} + +class QwtLegendItem::PrivateData +{ +public: + PrivateData(): + itemMode( QwtLegend::ReadOnlyItem ), + isDown( false ), + identifierSize( 8, 8 ), + spacing( Margin ) + { + } + + QwtLegend::LegendItemMode itemMode; + bool isDown; + + QSize identifierSize; + QPixmap identifier; + + int spacing; +}; + +/*! + \param parent Parent widget +*/ +QwtLegendItem::QwtLegendItem( QWidget *parent ): + QwtTextLabel( parent ) +{ + d_data = new PrivateData; + setMargin( Margin ); + setIndent( Margin + d_data->identifierSize.width() + 2 * d_data->spacing ); +} + +//! Destructor +QwtLegendItem::~QwtLegendItem() +{ + delete d_data; + d_data = NULL; +} + +/*! + Set the text to the legend item + + \param text Text label + \sa QwtTextLabel::text() +*/ +void QwtLegendItem::setText( const QwtText &text ) +{ + const int flags = Qt::AlignLeft | Qt::AlignVCenter + | Qt::TextExpandTabs | Qt::TextWordWrap; + + QwtText txt = text; + txt.setRenderFlags( flags ); + + QwtTextLabel::setText( txt ); +} + +/*! + Set the item mode + The default is QwtLegend::ReadOnlyItem + + \param mode Item mode + \sa itemMode() +*/ +void QwtLegendItem::setItemMode( QwtLegend::LegendItemMode mode ) +{ + if ( mode != d_data->itemMode ) + { + d_data->itemMode = mode; + d_data->isDown = false; + + setFocusPolicy( mode != QwtLegend::ReadOnlyItem ? Qt::TabFocus : Qt::NoFocus ); + setMargin( ButtonFrame + Margin ); + + updateGeometry(); + } +} + +/*! + Return the item mode + + \sa setItemMode() +*/ +QwtLegend::LegendItemMode QwtLegendItem::itemMode() const +{ + return d_data->itemMode; +} + +/*! + Assign the identifier + The identifier needs to be created according to the identifierWidth() + + \param identifier Pixmap representing a plot item + + \sa identifier(), identifierWidth() +*/ +void QwtLegendItem::setIdentifier( const QPixmap &identifier ) +{ + d_data->identifier = identifier; + update(); +} + +/*! + \return pixmap representing a plot item + \sa setIdentifier() +*/ +QPixmap QwtLegendItem::identifier() const +{ + return d_data->identifier; +} + +/*! + Set the size for the identifier + Default is 8x8 pixels + + \param size New size + + \sa identifierSize() +*/ +void QwtLegendItem::setIdentifierSize( const QSize &size ) +{ + QSize sz = size.expandedTo( QSize( 0, 0 ) ); + if ( sz != d_data->identifierSize ) + { + d_data->identifierSize = sz; + setIndent( margin() + d_data->identifierSize.width() + + 2 * d_data->spacing ); + updateGeometry(); + } +} +/*! + Return the width of the identifier + + \sa setIdentifierSize() +*/ +QSize QwtLegendItem::identifierSize() const +{ + return d_data->identifierSize; +} + +/*! + Change the spacing + \param spacing Spacing + \sa spacing(), identifierWidth(), QwtTextLabel::margin() +*/ +void QwtLegendItem::setSpacing( int spacing ) +{ + spacing = qMax( spacing, 0 ); + if ( spacing != d_data->spacing ) + { + d_data->spacing = spacing; + setIndent( margin() + d_data->identifierSize.width() + + 2 * d_data->spacing ); + } +} + +/*! + Return the spacing + \sa setSpacing(), identifierWidth(), QwtTextLabel::margin() +*/ +int QwtLegendItem::spacing() const +{ + return d_data->spacing; +} + +/*! + Check/Uncheck a the item + + \param on check/uncheck + \sa setItemMode() +*/ +void QwtLegendItem::setChecked( bool on ) +{ + if ( d_data->itemMode == QwtLegend::CheckableItem ) + { + const bool isBlocked = signalsBlocked(); + blockSignals( true ); + + setDown( on ); + + blockSignals( isBlocked ); + } +} + +//! Return true, if the item is checked +bool QwtLegendItem::isChecked() const +{ + return d_data->itemMode == QwtLegend::CheckableItem && isDown(); +} + +//! Set the item being down +void QwtLegendItem::setDown( bool down ) +{ + if ( down == d_data->isDown ) + return; + + d_data->isDown = down; + update(); + + if ( d_data->itemMode == QwtLegend::ClickableItem ) + { + if ( d_data->isDown ) + Q_EMIT pressed(); + else + { + Q_EMIT released(); + Q_EMIT clicked(); + } + } + + if ( d_data->itemMode == QwtLegend::CheckableItem ) + Q_EMIT checked( d_data->isDown ); +} + +//! Return true, if the item is down +bool QwtLegendItem::isDown() const +{ + return d_data->isDown; +} + +//! Return a size hint +QSize QwtLegendItem::sizeHint() const +{ + QSize sz = QwtTextLabel::sizeHint(); + sz.setHeight( qMax( sz.height(), d_data->identifier.height() + 4 ) ); + + if ( d_data->itemMode != QwtLegend::ReadOnlyItem ) + { + sz += buttonShift( this ); + sz = sz.expandedTo( QApplication::globalStrut() ); + } + + return sz; +} + +//! Paint event +void QwtLegendItem::paintEvent( QPaintEvent *e ) +{ + const QRect cr = contentsRect(); + + QPainter painter( this ); + painter.setClipRegion( e->region() ); + + if ( d_data->isDown ) + { + qDrawWinButton( &painter, 0, 0, width(), height(), + palette(), true ); + } + + painter.save(); + + if ( d_data->isDown ) + { + const QSize shiftSize = buttonShift( this ); + painter.translate( shiftSize.width(), shiftSize.height() ); + } + + painter.setClipRect( cr ); + + drawContents( &painter ); + + if ( !d_data->identifier.isNull() ) + { + QRect identRect = cr; + identRect.setX( identRect.x() + margin() ); + if ( d_data->itemMode != QwtLegend::ReadOnlyItem ) + identRect.setX( identRect.x() + ButtonFrame ); + + identRect.setSize( d_data->identifier.size() ); + identRect.moveCenter( QPoint( identRect.center().x(), cr.center().y() ) ); + + painter.drawPixmap( identRect, d_data->identifier ); + } + + painter.restore(); +} + +//! Handle mouse press events +void QwtLegendItem::mousePressEvent( QMouseEvent *e ) +{ + if ( e->button() == Qt::LeftButton ) + { + switch ( d_data->itemMode ) + { + case QwtLegend::ClickableItem: + { + setDown( true ); + return; + } + case QwtLegend::CheckableItem: + { + setDown( !isDown() ); + return; + } + default:; + } + } + QwtTextLabel::mousePressEvent( e ); +} + +//! Handle mouse release events +void QwtLegendItem::mouseReleaseEvent( QMouseEvent *e ) +{ + if ( e->button() == Qt::LeftButton ) + { + switch ( d_data->itemMode ) + { + case QwtLegend::ClickableItem: + { + setDown( false ); + return; + } + case QwtLegend::CheckableItem: + { + return; // do nothing, but accept + } + default:; + } + } + QwtTextLabel::mouseReleaseEvent( e ); +} + +//! Handle key press events +void QwtLegendItem::keyPressEvent( QKeyEvent *e ) +{ + if ( e->key() == Qt::Key_Space ) + { + switch ( d_data->itemMode ) + { + case QwtLegend::ClickableItem: + { + if ( !e->isAutoRepeat() ) + setDown( true ); + return; + } + case QwtLegend::CheckableItem: + { + if ( !e->isAutoRepeat() ) + setDown( !isDown() ); + return; + } + default:; + } + } + + QwtTextLabel::keyPressEvent( e ); +} + +//! Handle key release events +void QwtLegendItem::keyReleaseEvent( QKeyEvent *e ) +{ + if ( e->key() == Qt::Key_Space ) + { + switch ( d_data->itemMode ) + { + case QwtLegend::ClickableItem: + { + if ( !e->isAutoRepeat() ) + setDown( false ); + return; + } + case QwtLegend::CheckableItem: + { + return; // do nothing, but accept + } + default:; + } + } + + QwtTextLabel::keyReleaseEvent( e ); } \ No newline at end of file diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_item.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_item.h index 5a2b0dee5..1d315f6b0 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_item.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_item.h @@ -1,78 +1,78 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_LEGEND_ITEM_H -#define QWT_LEGEND_ITEM_H - -#include "qwt_global.h" -#include "qwt_legend.h" -#include "qwt_text.h" -#include "qwt_text_label.h" -#include - -/*! - \brief A widget representing something on a QwtLegend(). -*/ -class QWT_EXPORT QwtLegendItem: public QwtTextLabel -{ - Q_OBJECT -public: - explicit QwtLegendItem( QWidget *parent = 0 ); - virtual ~QwtLegendItem(); - - void setItemMode( QwtLegend::LegendItemMode ); - QwtLegend::LegendItemMode itemMode() const; - - void setSpacing( int spacing ); - int spacing() const; - - virtual void setText( const QwtText & ); - - void setIdentifier( const QPixmap & ); - QPixmap identifier() const; - - void setIdentifierSize( const QSize & ); - QSize identifierSize() const; - - virtual QSize sizeHint() const; - - bool isChecked() const; - -public Q_SLOTS: - void setChecked( bool on ); - -Q_SIGNALS: - //! Signal, when the legend item has been clicked - void clicked(); - - //! Signal, when the legend item has been pressed - void pressed(); - - //! Signal, when the legend item has been relased - void released(); - - //! Signal, when the legend item has been toggled - void checked( bool ); - -protected: - void setDown( bool ); - bool isDown() const; - - virtual void paintEvent( QPaintEvent * ); - virtual void mousePressEvent( QMouseEvent * ); - virtual void mouseReleaseEvent( QMouseEvent * ); - virtual void keyPressEvent( QKeyEvent * ); - virtual void keyReleaseEvent( QKeyEvent * ); - -private: - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_LEGEND_ITEM_H +#define QWT_LEGEND_ITEM_H + +#include "qwt_global.h" +#include "qwt_legend.h" +#include "qwt_text.h" +#include "qwt_text_label.h" +#include + +/*! + \brief A widget representing something on a QwtLegend(). +*/ +class QWT_EXPORT QwtLegendItem: public QwtTextLabel +{ + Q_OBJECT +public: + explicit QwtLegendItem( QWidget *parent = 0 ); + virtual ~QwtLegendItem(); + + void setItemMode( QwtLegend::LegendItemMode ); + QwtLegend::LegendItemMode itemMode() const; + + void setSpacing( int spacing ); + int spacing() const; + + virtual void setText( const QwtText & ); + + void setIdentifier( const QPixmap & ); + QPixmap identifier() const; + + void setIdentifierSize( const QSize & ); + QSize identifierSize() const; + + virtual QSize sizeHint() const; + + bool isChecked() const; + +public Q_SLOTS: + void setChecked( bool on ); + +Q_SIGNALS: + //! Signal, when the legend item has been clicked + void clicked(); + + //! Signal, when the legend item has been pressed + void pressed(); + + //! Signal, when the legend item has been relased + void released(); + + //! Signal, when the legend item has been toggled + void checked( bool ); + +protected: + void setDown( bool ); + bool isDown() const; + + virtual void paintEvent( QPaintEvent * ); + virtual void mousePressEvent( QMouseEvent * ); + virtual void mouseReleaseEvent( QMouseEvent * ); + virtual void keyPressEvent( QKeyEvent * ); + virtual void keyReleaseEvent( QKeyEvent * ); + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_itemmanager.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_itemmanager.h index f87515e32..ccea82001 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_itemmanager.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_legend_itemmanager.h @@ -1,66 +1,66 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_LEGEND_ITEM_MANAGER_H -#define QWT_LEGEND_ITEM_MANAGER_H - -#include "qwt_global.h" - -class QwtLegend; -class QWidget; -class QRectF; -class QPainter; - -/*! - \brief Abstract API to bind plot items to the legend -*/ - -class QWT_EXPORT QwtLegendItemManager -{ -public: - //! Constructor - QwtLegendItemManager() - { - } - - //! Destructor - virtual ~QwtLegendItemManager() - { - } - - /*! - Update the widget that represents the item on the legend - \param legend Legend - \sa legendItem() - */ - virtual void updateLegend( QwtLegend *legend ) const = 0; - - /*! - Allocate the widget that represents the item on the legend - \return Allocated widget - \sa updateLegend() QwtLegend() - */ - - virtual QWidget *legendItem() const = 0; - - /*! - QwtLegendItem can display an icon-identifier followed - by a text. The icon helps to identify a plot item on - the plot canvas and depends on the type of information, - that is displayed. - - The default implementation paints nothing. - */ - virtual void drawLegendIdentifier( QPainter *, const QRectF & ) const - { - } -}; - -#endif - +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_LEGEND_ITEM_MANAGER_H +#define QWT_LEGEND_ITEM_MANAGER_H + +#include "qwt_global.h" + +class QwtLegend; +class QWidget; +class QRectF; +class QPainter; + +/*! + \brief Abstract API to bind plot items to the legend +*/ + +class QWT_EXPORT QwtLegendItemManager +{ +public: + //! Constructor + QwtLegendItemManager() + { + } + + //! Destructor + virtual ~QwtLegendItemManager() + { + } + + /*! + Update the widget that represents the item on the legend + \param legend Legend + \sa legendItem() + */ + virtual void updateLegend( QwtLegend *legend ) const = 0; + + /*! + Allocate the widget that represents the item on the legend + \return Allocated widget + \sa updateLegend() QwtLegend() + */ + + virtual QWidget *legendItem() const = 0; + + /*! + QwtLegendItem can display an icon-identifier followed + by a text. The icon helps to identify a plot item on + the plot canvas and depends on the type of information, + that is displayed. + + The default implementation paints nothing. + */ + virtual void drawLegendIdentifier( QPainter *, const QRectF & ) const + { + } +}; + +#endif + diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_magnifier.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_magnifier.cpp index 6179bc50b..77a916c83 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_magnifier.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_magnifier.cpp @@ -1,473 +1,473 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_magnifier.h" -#include "qwt_math.h" -#include -#include - -class QwtMagnifier::PrivateData -{ -public: - PrivateData(): - isEnabled( false ), - wheelFactor( 0.9 ), - wheelButtonState( Qt::NoButton ), - mouseFactor( 0.95 ), - mouseButton( Qt::RightButton ), - mouseButtonState( Qt::NoButton ), - keyFactor( 0.9 ), - zoomInKey( Qt::Key_Plus ), - zoomOutKey( Qt::Key_Minus ), - zoomInKeyModifiers( Qt::NoModifier ), - zoomOutKeyModifiers( Qt::NoModifier ), - mousePressed( false ) - { - } - - bool isEnabled; - - double wheelFactor; - int wheelButtonState; - - double mouseFactor; - int mouseButton; - int mouseButtonState; - - double keyFactor; - int zoomInKey; - int zoomOutKey; - int zoomInKeyModifiers; - int zoomOutKeyModifiers; - - bool mousePressed; - bool hasMouseTracking; - QPoint mousePos; -}; - -/*! - Constructor - \param parent Widget to be magnified -*/ -QwtMagnifier::QwtMagnifier( QWidget *parent ): - QObject( parent ) -{ - d_data = new PrivateData(); - setEnabled( true ); -} - -//! Destructor -QwtMagnifier::~QwtMagnifier() -{ - delete d_data; -} - -/*! - \brief En/disable the magnifier - - When enabled is true an event filter is installed for - the observed widget, otherwise the event filter is removed. - - \param on true or false - \sa isEnabled(), eventFilter() -*/ -void QwtMagnifier::setEnabled( bool on ) -{ - if ( d_data->isEnabled != on ) - { - d_data->isEnabled = on; - - QObject *o = parent(); - if ( o ) - { - if ( d_data->isEnabled ) - o->installEventFilter( this ); - else - o->removeEventFilter( this ); - } - } -} - -/*! - \return true when enabled, false otherwise - \sa setEnabled(), eventFilter() -*/ -bool QwtMagnifier::isEnabled() const -{ - return d_data->isEnabled; -} - -/*! - \brief Change the wheel factor - - The wheel factor defines the ratio between the current range - on the parent widget and the zoomed range for each step of the wheel. - The default value is 0.9. - - \param factor Wheel factor - \sa wheelFactor(), setWheelButtonState(), - setMouseFactor(), setKeyFactor() -*/ -void QwtMagnifier::setWheelFactor( double factor ) -{ - d_data->wheelFactor = factor; -} - -/*! - \return Wheel factor - \sa setWheelFactor() -*/ -double QwtMagnifier::wheelFactor() const -{ - return d_data->wheelFactor; -} - -/*! - Assign a mandatory button state for zooming in/out using the wheel. - The default button state is Qt::NoButton. - - \param buttonState Button state - \sa wheelButtonState() -*/ -void QwtMagnifier::setWheelButtonState( int buttonState ) -{ - d_data->wheelButtonState = buttonState; -} - -/*! - \return Wheel button state - \sa setWheelButtonState() -*/ -int QwtMagnifier::wheelButtonState() const -{ - return d_data->wheelButtonState; -} - -/*! - \brief Change the mouse factor - - The mouse factor defines the ratio between the current range - on the parent widget and the zoomed range for each vertical mouse movement. - The default value is 0.95. - - \param factor Wheel factor - \sa mouseFactor(), setMouseButton(), setWheelFactor(), setKeyFactor() -*/ -void QwtMagnifier::setMouseFactor( double factor ) -{ - d_data->mouseFactor = factor; -} - -/*! - \return Mouse factor - \sa setMouseFactor() -*/ -double QwtMagnifier::mouseFactor() const -{ - return d_data->mouseFactor; -} - -/*! - Assign the mouse button, that is used for zooming in/out. - The default value is Qt::RightButton. - - \param button Button - \param buttonState Button state - \sa getMouseButton() -*/ -void QwtMagnifier::setMouseButton( int button, int buttonState ) -{ - d_data->mouseButton = button; - d_data->mouseButtonState = buttonState; -} - -//! \sa setMouseButton() -void QwtMagnifier::getMouseButton( - int &button, int &buttonState ) const -{ - button = d_data->mouseButton; - buttonState = d_data->mouseButtonState; -} - -/*! - \brief Change the key factor - - The key factor defines the ratio between the current range - on the parent widget and the zoomed range for each key press of - the zoom in/out keys. The default value is 0.9. - - \param factor Key factor - \sa keyFactor(), setZoomInKey(), setZoomOutKey(), - setWheelFactor, setMouseFactor() -*/ -void QwtMagnifier::setKeyFactor( double factor ) -{ - d_data->keyFactor = factor; -} - -/*! - \return Key factor - \sa setKeyFactor() -*/ -double QwtMagnifier::keyFactor() const -{ - return d_data->keyFactor; -} - -/*! - Assign the key, that is used for zooming in. - The default combination is Qt::Key_Plus + Qt::NoModifier. - - \param key - \param modifiers - \sa getZoomInKey(), setZoomOutKey() -*/ -void QwtMagnifier::setZoomInKey( int key, int modifiers ) -{ - d_data->zoomInKey = key; - d_data->zoomInKeyModifiers = modifiers; -} - -//! \sa setZoomInKey() -void QwtMagnifier::getZoomInKey( int &key, int &modifiers ) const -{ - key = d_data->zoomInKey; - modifiers = d_data->zoomInKeyModifiers; -} - -/*! - Assign the key, that is used for zooming out. - The default combination is Qt::Key_Minus + Qt::NoModifier. - - \param key - \param modifiers - \sa getZoomOutKey(), setZoomOutKey() -*/ -void QwtMagnifier::setZoomOutKey( int key, int modifiers ) -{ - d_data->zoomOutKey = key; - d_data->zoomOutKeyModifiers = modifiers; -} - -//! \sa setZoomOutKey() -void QwtMagnifier::getZoomOutKey( int &key, int &modifiers ) const -{ - key = d_data->zoomOutKey; - modifiers = d_data->zoomOutKeyModifiers; -} - -/*! - \brief Event filter - - When isEnabled() the mouse events of the observed widget are filtered. - - \param object Object to be filtered - \param event Event - - \sa widgetMousePressEvent(), widgetMouseReleaseEvent(), - widgetMouseMoveEvent(), widgetWheelEvent(), widgetKeyPressEvent() - widgetKeyReleaseEvent() -*/ -bool QwtMagnifier::eventFilter( QObject *object, QEvent *event ) -{ - if ( object && object == parent() ) - { - switch ( event->type() ) - { - case QEvent::MouseButtonPress: - { - widgetMousePressEvent( ( QMouseEvent * )event ); - break; - } - case QEvent::MouseMove: - { - widgetMouseMoveEvent( ( QMouseEvent * )event ); - break; - } - case QEvent::MouseButtonRelease: - { - widgetMouseReleaseEvent( ( QMouseEvent * )event ); - break; - } - case QEvent::Wheel: - { - widgetWheelEvent( ( QWheelEvent * )event ); - break; - } - case QEvent::KeyPress: - { - widgetKeyPressEvent( ( QKeyEvent * )event ); - break; - } - case QEvent::KeyRelease: - { - widgetKeyReleaseEvent( ( QKeyEvent * )event ); - break; - } - default:; - } - } - return QObject::eventFilter( object, event ); -} - -/*! - Handle a mouse press event for the observed widget. - - \param mouseEvent Mouse event - \sa eventFilter(), widgetMouseReleaseEvent(), widgetMouseMoveEvent() -*/ -void QwtMagnifier::widgetMousePressEvent( QMouseEvent *mouseEvent ) -{ - if ( ( mouseEvent->button() != d_data->mouseButton) - || parentWidget() == NULL ) - { - return; - } - - if ( ( mouseEvent->modifiers() & Qt::KeyboardModifierMask ) != - ( int )( d_data->mouseButtonState & Qt::KeyboardModifierMask ) ) - { - return; - } - - d_data->hasMouseTracking = parentWidget()->hasMouseTracking(); - parentWidget()->setMouseTracking( true ); - d_data->mousePos = mouseEvent->pos(); - d_data->mousePressed = true; -} - -/*! - Handle a mouse release event for the observed widget. - - \param mouseEvent Mouse event - - \sa eventFilter(), widgetMousePressEvent(), widgetMouseMoveEvent(), -*/ -void QwtMagnifier::widgetMouseReleaseEvent( QMouseEvent *mouseEvent ) -{ - Q_UNUSED( mouseEvent ); - - if ( d_data->mousePressed && parentWidget() ) - { - d_data->mousePressed = false; - parentWidget()->setMouseTracking( d_data->hasMouseTracking ); - } -} - -/*! - Handle a mouse move event for the observed widget. - - \param mouseEvent Mouse event - \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), -*/ -void QwtMagnifier::widgetMouseMoveEvent( QMouseEvent *mouseEvent ) -{ - if ( !d_data->mousePressed ) - return; - - const int dy = mouseEvent->pos().y() - d_data->mousePos.y(); - if ( dy != 0 ) - { - double f = d_data->mouseFactor; - if ( dy < 0 ) - f = 1 / f; - - rescale( f ); - } - - d_data->mousePos = mouseEvent->pos(); -} - -/*! - Handle a wheel event for the observed widget. - - \param wheelEvent Wheel event - \sa eventFilter() -*/ -void QwtMagnifier::widgetWheelEvent( QWheelEvent *wheelEvent ) -{ - if ( ( wheelEvent->modifiers() & Qt::KeyboardModifierMask ) != - ( int )( d_data->wheelButtonState & Qt::KeyboardModifierMask ) ) - { - return; - } - - if ( d_data->wheelFactor != 0.0 ) - { - /* - A positive delta indicates that the wheel was - rotated forwards away from the user; a negative - value indicates that the wheel was rotated - backwards toward the user. - Most mouse types work in steps of 15 degrees, - in which case the delta value is a multiple - of 120 (== 15 * 8). - */ - double f = qPow( d_data->wheelFactor, - qAbs( wheelEvent->delta() / 120 ) ); - - if ( wheelEvent->delta() > 0 ) - f = 1 / f; - - rescale( f ); - } -} - -/*! - Handle a key press event for the observed widget. - - \param keyEvent Key event - \sa eventFilter(), widgetKeyReleaseEvent() -*/ -void QwtMagnifier::widgetKeyPressEvent( QKeyEvent *keyEvent ) -{ - const int key = keyEvent->key(); - const int state = keyEvent->modifiers(); - - if ( key == d_data->zoomInKey && - state == d_data->zoomInKeyModifiers ) - { - rescale( d_data->keyFactor ); - } - else if ( key == d_data->zoomOutKey && - state == d_data->zoomOutKeyModifiers ) - { - rescale( 1.0 / d_data->keyFactor ); - } -} - -/*! - Handle a key release event for the observed widget. - - \param keyEvent Key event - \sa eventFilter(), widgetKeyReleaseEvent() -*/ -void QwtMagnifier::widgetKeyReleaseEvent( QKeyEvent *keyEvent ) -{ - Q_UNUSED( keyEvent ); -} - -//! \return Parent widget, where the rescaling happens -QWidget *QwtMagnifier::parentWidget() -{ - if ( parent()->inherits( "QWidget" ) ) - return ( QWidget * )parent(); - - return NULL; -} - -//! \return Parent widget, where the rescaling happens -const QWidget *QwtMagnifier::parentWidget() const -{ - if ( parent()->inherits( "QWidget" ) ) - return ( const QWidget * )parent(); - - return NULL; -} - +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_magnifier.h" +#include "qwt_math.h" +#include +#include + +class QwtMagnifier::PrivateData +{ +public: + PrivateData(): + isEnabled( false ), + wheelFactor( 0.9 ), + wheelButtonState( Qt::NoButton ), + mouseFactor( 0.95 ), + mouseButton( Qt::RightButton ), + mouseButtonState( Qt::NoButton ), + keyFactor( 0.9 ), + zoomInKey( Qt::Key_Plus ), + zoomOutKey( Qt::Key_Minus ), + zoomInKeyModifiers( Qt::NoModifier ), + zoomOutKeyModifiers( Qt::NoModifier ), + mousePressed( false ) + { + } + + bool isEnabled; + + double wheelFactor; + int wheelButtonState; + + double mouseFactor; + int mouseButton; + int mouseButtonState; + + double keyFactor; + int zoomInKey; + int zoomOutKey; + int zoomInKeyModifiers; + int zoomOutKeyModifiers; + + bool mousePressed; + bool hasMouseTracking; + QPoint mousePos; +}; + +/*! + Constructor + \param parent Widget to be magnified +*/ +QwtMagnifier::QwtMagnifier( QWidget *parent ): + QObject( parent ) +{ + d_data = new PrivateData(); + setEnabled( true ); +} + +//! Destructor +QwtMagnifier::~QwtMagnifier() +{ + delete d_data; +} + +/*! + \brief En/disable the magnifier + + When enabled is true an event filter is installed for + the observed widget, otherwise the event filter is removed. + + \param on true or false + \sa isEnabled(), eventFilter() +*/ +void QwtMagnifier::setEnabled( bool on ) +{ + if ( d_data->isEnabled != on ) + { + d_data->isEnabled = on; + + QObject *o = parent(); + if ( o ) + { + if ( d_data->isEnabled ) + o->installEventFilter( this ); + else + o->removeEventFilter( this ); + } + } +} + +/*! + \return true when enabled, false otherwise + \sa setEnabled(), eventFilter() +*/ +bool QwtMagnifier::isEnabled() const +{ + return d_data->isEnabled; +} + +/*! + \brief Change the wheel factor + + The wheel factor defines the ratio between the current range + on the parent widget and the zoomed range for each step of the wheel. + The default value is 0.9. + + \param factor Wheel factor + \sa wheelFactor(), setWheelButtonState(), + setMouseFactor(), setKeyFactor() +*/ +void QwtMagnifier::setWheelFactor( double factor ) +{ + d_data->wheelFactor = factor; +} + +/*! + \return Wheel factor + \sa setWheelFactor() +*/ +double QwtMagnifier::wheelFactor() const +{ + return d_data->wheelFactor; +} + +/*! + Assign a mandatory button state for zooming in/out using the wheel. + The default button state is Qt::NoButton. + + \param buttonState Button state + \sa wheelButtonState() +*/ +void QwtMagnifier::setWheelButtonState( int buttonState ) +{ + d_data->wheelButtonState = buttonState; +} + +/*! + \return Wheel button state + \sa setWheelButtonState() +*/ +int QwtMagnifier::wheelButtonState() const +{ + return d_data->wheelButtonState; +} + +/*! + \brief Change the mouse factor + + The mouse factor defines the ratio between the current range + on the parent widget and the zoomed range for each vertical mouse movement. + The default value is 0.95. + + \param factor Wheel factor + \sa mouseFactor(), setMouseButton(), setWheelFactor(), setKeyFactor() +*/ +void QwtMagnifier::setMouseFactor( double factor ) +{ + d_data->mouseFactor = factor; +} + +/*! + \return Mouse factor + \sa setMouseFactor() +*/ +double QwtMagnifier::mouseFactor() const +{ + return d_data->mouseFactor; +} + +/*! + Assign the mouse button, that is used for zooming in/out. + The default value is Qt::RightButton. + + \param button Button + \param buttonState Button state + \sa getMouseButton() +*/ +void QwtMagnifier::setMouseButton( int button, int buttonState ) +{ + d_data->mouseButton = button; + d_data->mouseButtonState = buttonState; +} + +//! \sa setMouseButton() +void QwtMagnifier::getMouseButton( + int &button, int &buttonState ) const +{ + button = d_data->mouseButton; + buttonState = d_data->mouseButtonState; +} + +/*! + \brief Change the key factor + + The key factor defines the ratio between the current range + on the parent widget and the zoomed range for each key press of + the zoom in/out keys. The default value is 0.9. + + \param factor Key factor + \sa keyFactor(), setZoomInKey(), setZoomOutKey(), + setWheelFactor, setMouseFactor() +*/ +void QwtMagnifier::setKeyFactor( double factor ) +{ + d_data->keyFactor = factor; +} + +/*! + \return Key factor + \sa setKeyFactor() +*/ +double QwtMagnifier::keyFactor() const +{ + return d_data->keyFactor; +} + +/*! + Assign the key, that is used for zooming in. + The default combination is Qt::Key_Plus + Qt::NoModifier. + + \param key + \param modifiers + \sa getZoomInKey(), setZoomOutKey() +*/ +void QwtMagnifier::setZoomInKey( int key, int modifiers ) +{ + d_data->zoomInKey = key; + d_data->zoomInKeyModifiers = modifiers; +} + +//! \sa setZoomInKey() +void QwtMagnifier::getZoomInKey( int &key, int &modifiers ) const +{ + key = d_data->zoomInKey; + modifiers = d_data->zoomInKeyModifiers; +} + +/*! + Assign the key, that is used for zooming out. + The default combination is Qt::Key_Minus + Qt::NoModifier. + + \param key + \param modifiers + \sa getZoomOutKey(), setZoomOutKey() +*/ +void QwtMagnifier::setZoomOutKey( int key, int modifiers ) +{ + d_data->zoomOutKey = key; + d_data->zoomOutKeyModifiers = modifiers; +} + +//! \sa setZoomOutKey() +void QwtMagnifier::getZoomOutKey( int &key, int &modifiers ) const +{ + key = d_data->zoomOutKey; + modifiers = d_data->zoomOutKeyModifiers; +} + +/*! + \brief Event filter + + When isEnabled() the mouse events of the observed widget are filtered. + + \param object Object to be filtered + \param event Event + + \sa widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseMoveEvent(), widgetWheelEvent(), widgetKeyPressEvent() + widgetKeyReleaseEvent() +*/ +bool QwtMagnifier::eventFilter( QObject *object, QEvent *event ) +{ + if ( object && object == parent() ) + { + switch ( event->type() ) + { + case QEvent::MouseButtonPress: + { + widgetMousePressEvent( ( QMouseEvent * )event ); + break; + } + case QEvent::MouseMove: + { + widgetMouseMoveEvent( ( QMouseEvent * )event ); + break; + } + case QEvent::MouseButtonRelease: + { + widgetMouseReleaseEvent( ( QMouseEvent * )event ); + break; + } + case QEvent::Wheel: + { + widgetWheelEvent( ( QWheelEvent * )event ); + break; + } + case QEvent::KeyPress: + { + widgetKeyPressEvent( ( QKeyEvent * )event ); + break; + } + case QEvent::KeyRelease: + { + widgetKeyReleaseEvent( ( QKeyEvent * )event ); + break; + } + default:; + } + } + return QObject::eventFilter( object, event ); +} + +/*! + Handle a mouse press event for the observed widget. + + \param mouseEvent Mouse event + \sa eventFilter(), widgetMouseReleaseEvent(), widgetMouseMoveEvent() +*/ +void QwtMagnifier::widgetMousePressEvent( QMouseEvent *mouseEvent ) +{ + if ( ( mouseEvent->button() != d_data->mouseButton) + || parentWidget() == NULL ) + { + return; + } + + if ( ( mouseEvent->modifiers() & Qt::KeyboardModifierMask ) != + ( int )( d_data->mouseButtonState & Qt::KeyboardModifierMask ) ) + { + return; + } + + d_data->hasMouseTracking = parentWidget()->hasMouseTracking(); + parentWidget()->setMouseTracking( true ); + d_data->mousePos = mouseEvent->pos(); + d_data->mousePressed = true; +} + +/*! + Handle a mouse release event for the observed widget. + + \param mouseEvent Mouse event + + \sa eventFilter(), widgetMousePressEvent(), widgetMouseMoveEvent(), +*/ +void QwtMagnifier::widgetMouseReleaseEvent( QMouseEvent *mouseEvent ) +{ + Q_UNUSED( mouseEvent ); + + if ( d_data->mousePressed && parentWidget() ) + { + d_data->mousePressed = false; + parentWidget()->setMouseTracking( d_data->hasMouseTracking ); + } +} + +/*! + Handle a mouse move event for the observed widget. + + \param mouseEvent Mouse event + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), +*/ +void QwtMagnifier::widgetMouseMoveEvent( QMouseEvent *mouseEvent ) +{ + if ( !d_data->mousePressed ) + return; + + const int dy = mouseEvent->pos().y() - d_data->mousePos.y(); + if ( dy != 0 ) + { + double f = d_data->mouseFactor; + if ( dy < 0 ) + f = 1 / f; + + rescale( f ); + } + + d_data->mousePos = mouseEvent->pos(); +} + +/*! + Handle a wheel event for the observed widget. + + \param wheelEvent Wheel event + \sa eventFilter() +*/ +void QwtMagnifier::widgetWheelEvent( QWheelEvent *wheelEvent ) +{ + if ( ( wheelEvent->modifiers() & Qt::KeyboardModifierMask ) != + ( int )( d_data->wheelButtonState & Qt::KeyboardModifierMask ) ) + { + return; + } + + if ( d_data->wheelFactor != 0.0 ) + { + /* + A positive delta indicates that the wheel was + rotated forwards away from the user; a negative + value indicates that the wheel was rotated + backwards toward the user. + Most mouse types work in steps of 15 degrees, + in which case the delta value is a multiple + of 120 (== 15 * 8). + */ + double f = qPow( d_data->wheelFactor, + qAbs( wheelEvent->delta() / 120 ) ); + + if ( wheelEvent->delta() > 0 ) + f = 1 / f; + + rescale( f ); + } +} + +/*! + Handle a key press event for the observed widget. + + \param keyEvent Key event + \sa eventFilter(), widgetKeyReleaseEvent() +*/ +void QwtMagnifier::widgetKeyPressEvent( QKeyEvent *keyEvent ) +{ + const int key = keyEvent->key(); + const int state = keyEvent->modifiers(); + + if ( key == d_data->zoomInKey && + state == d_data->zoomInKeyModifiers ) + { + rescale( d_data->keyFactor ); + } + else if ( key == d_data->zoomOutKey && + state == d_data->zoomOutKeyModifiers ) + { + rescale( 1.0 / d_data->keyFactor ); + } +} + +/*! + Handle a key release event for the observed widget. + + \param keyEvent Key event + \sa eventFilter(), widgetKeyReleaseEvent() +*/ +void QwtMagnifier::widgetKeyReleaseEvent( QKeyEvent *keyEvent ) +{ + Q_UNUSED( keyEvent ); +} + +//! \return Parent widget, where the rescaling happens +QWidget *QwtMagnifier::parentWidget() +{ + if ( parent()->inherits( "QWidget" ) ) + return ( QWidget * )parent(); + + return NULL; +} + +//! \return Parent widget, where the rescaling happens +const QWidget *QwtMagnifier::parentWidget() const +{ + if ( parent()->inherits( "QWidget" ) ) + return ( const QWidget * )parent(); + + return NULL; +} + diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_magnifier.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_magnifier.h index e41ae8bf1..f2f4bbd98 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_magnifier.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_magnifier.h @@ -1,86 +1,86 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_MAGNIFIER_H -#define QWT_MAGNIFIER_H 1 - -#include "qwt_global.h" -#include - -class QWidget; -class QMouseEvent; -class QWheelEvent; -class QKeyEvent; - -/*! - \brief QwtMagnifier provides zooming, by magnifying in steps. - - Using QwtMagnifier a plot can be zoomed in/out in steps using - keys, the mouse wheel or moving a mouse button in vertical direction. -*/ -class QWT_EXPORT QwtMagnifier: public QObject -{ - Q_OBJECT - -public: - explicit QwtMagnifier( QWidget * ); - virtual ~QwtMagnifier(); - - QWidget *parentWidget(); - const QWidget *parentWidget() const; - - void setEnabled( bool ); - bool isEnabled() const; - - // mouse - void setMouseFactor( double ); - double mouseFactor() const; - - void setMouseButton( int button, int buttonState = Qt::NoButton ); - void getMouseButton( int &button, int &buttonState ) const; - - // mouse wheel - void setWheelFactor( double ); - double wheelFactor() const; - - void setWheelButtonState( int buttonState ); - int wheelButtonState() const; - - // keyboard - void setKeyFactor( double ); - double keyFactor() const; - - void setZoomInKey( int key, int modifiers ); - void getZoomInKey( int &key, int &modifiers ) const; - - void setZoomOutKey( int key, int modifiers ); - void getZoomOutKey( int &key, int &modifiers ) const; - - virtual bool eventFilter( QObject *, QEvent * ); - -protected: - /*! - Rescale the parent widget - \param factor Scale factor - */ - virtual void rescale( double factor ) = 0; - - virtual void widgetMousePressEvent( QMouseEvent * ); - virtual void widgetMouseReleaseEvent( QMouseEvent * ); - virtual void widgetMouseMoveEvent( QMouseEvent * ); - virtual void widgetWheelEvent( QWheelEvent * ); - virtual void widgetKeyPressEvent( QKeyEvent * ); - virtual void widgetKeyReleaseEvent( QKeyEvent * ); - -private: - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_MAGNIFIER_H +#define QWT_MAGNIFIER_H 1 + +#include "qwt_global.h" +#include + +class QWidget; +class QMouseEvent; +class QWheelEvent; +class QKeyEvent; + +/*! + \brief QwtMagnifier provides zooming, by magnifying in steps. + + Using QwtMagnifier a plot can be zoomed in/out in steps using + keys, the mouse wheel or moving a mouse button in vertical direction. +*/ +class QWT_EXPORT QwtMagnifier: public QObject +{ + Q_OBJECT + +public: + explicit QwtMagnifier( QWidget * ); + virtual ~QwtMagnifier(); + + QWidget *parentWidget(); + const QWidget *parentWidget() const; + + void setEnabled( bool ); + bool isEnabled() const; + + // mouse + void setMouseFactor( double ); + double mouseFactor() const; + + void setMouseButton( int button, int buttonState = Qt::NoButton ); + void getMouseButton( int &button, int &buttonState ) const; + + // mouse wheel + void setWheelFactor( double ); + double wheelFactor() const; + + void setWheelButtonState( int buttonState ); + int wheelButtonState() const; + + // keyboard + void setKeyFactor( double ); + double keyFactor() const; + + void setZoomInKey( int key, int modifiers ); + void getZoomInKey( int &key, int &modifiers ) const; + + void setZoomOutKey( int key, int modifiers ); + void getZoomOutKey( int &key, int &modifiers ) const; + + virtual bool eventFilter( QObject *, QEvent * ); + +protected: + /*! + Rescale the parent widget + \param factor Scale factor + */ + virtual void rescale( double factor ) = 0; + + virtual void widgetMousePressEvent( QMouseEvent * ); + virtual void widgetMouseReleaseEvent( QMouseEvent * ); + virtual void widgetMouseMoveEvent( QMouseEvent * ); + virtual void widgetWheelEvent( QWheelEvent * ); + virtual void widgetKeyPressEvent( QKeyEvent * ); + virtual void widgetKeyReleaseEvent( QKeyEvent * ); + +private: + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_math.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_math.cpp index ee5dfff37..06a039aec 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_math.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_math.cpp @@ -1,45 +1,45 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_math.h" - -/*! - \brief Find the smallest value in an array - \param array Pointer to an array - \param size Array size -*/ -double qwtGetMin( const double *array, int size ) -{ - if ( size <= 0 ) - return 0.0; - - double rv = array[0]; - for ( int i = 1; i < size; i++ ) - rv = qMin( rv, array[i] ); - - return rv; -} - - -/*! - \brief Find the largest value in an array - \param array Pointer to an array - \param size Array size -*/ -double qwtGetMax( const double *array, int size ) -{ - if ( size <= 0 ) - return 0.0; - - double rv = array[0]; - for ( int i = 1; i < size; i++ ) - rv = qMax( rv, array[i] ); - - return rv; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_math.h" + +/*! + \brief Find the smallest value in an array + \param array Pointer to an array + \param size Array size +*/ +double qwtGetMin( const double *array, int size ) +{ + if ( size <= 0 ) + return 0.0; + + double rv = array[0]; + for ( int i = 1; i < size; i++ ) + rv = qMin( rv, array[i] ); + + return rv; +} + + +/*! + \brief Find the largest value in an array + \param array Pointer to an array + \param size Array size +*/ +double qwtGetMax( const double *array, int size ) +{ + if ( size <= 0 ) + return 0.0; + + double rv = array[0]; + for ( int i = 1; i < size; i++ ) + rv = qMax( rv, array[i] ); + + return rv; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_math.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_math.h index a45603fb2..fa8a47696 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_math.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_math.h @@ -1,182 +1,182 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_MATH_H -#define QWT_MATH_H - -#include "qwt_global.h" - -#if defined(_MSC_VER) -/* - Microsoft says: - - Define _USE_MATH_DEFINES before including math.h to expose these macro - definitions for common math constants. These are placed under an #ifdef - since these commonly-defined names are not part of the C/C++ standards. -*/ -#define _USE_MATH_DEFINES 1 -#endif - -#include -#include -#include "qwt_global.h" - -#ifndef LOG10_2 -#define LOG10_2 0.30102999566398119802 /* log10(2) */ -#endif - -#ifndef LOG10_3 -#define LOG10_3 0.47712125471966243540 /* log10(3) */ -#endif - -#ifndef LOG10_5 -#define LOG10_5 0.69897000433601885749 /* log10(5) */ -#endif - -#ifndef M_2PI -#define M_2PI 6.28318530717958623200 /* 2 pi */ -#endif - -#ifndef LOG_MIN -//! Mininum value for logarithmic scales -#define LOG_MIN 1.0e-100 -#endif - -#ifndef LOG_MAX -//! Maximum value for logarithmic scales -#define LOG_MAX 1.0e100 -#endif - -#ifndef M_E -#define M_E 2.7182818284590452354 /* e */ -#endif - -#ifndef M_LOG2E -#define M_LOG2E 1.4426950408889634074 /* log_2 e */ -#endif - -#ifndef M_LOG10E -#define M_LOG10E 0.43429448190325182765 /* log_10 e */ -#endif - -#ifndef M_LN2 -#define M_LN2 0.69314718055994530942 /* log_e 2 */ -#endif - -#ifndef M_LN10 -#define M_LN10 2.30258509299404568402 /* log_e 10 */ -#endif - -#ifndef M_PI -#define M_PI 3.14159265358979323846 /* pi */ -#endif - -#ifndef M_PI_2 -#define M_PI_2 1.57079632679489661923 /* pi/2 */ -#endif - -#ifndef M_PI_4 -#define M_PI_4 0.78539816339744830962 /* pi/4 */ -#endif - -#ifndef M_1_PI -#define M_1_PI 0.31830988618379067154 /* 1/pi */ -#endif - -#ifndef M_2_PI -#define M_2_PI 0.63661977236758134308 /* 2/pi */ -#endif - -#ifndef M_2_SQRTPI -#define M_2_SQRTPI 1.12837916709551257390 /* 2/sqrt(pi) */ -#endif - -#ifndef M_SQRT2 -#define M_SQRT2 1.41421356237309504880 /* sqrt(2) */ -#endif - -#ifndef M_SQRT1_2 -#define M_SQRT1_2 0.70710678118654752440 /* 1/sqrt(2) */ -#endif - -QWT_EXPORT double qwtGetMin( const double *array, int size ); -QWT_EXPORT double qwtGetMax( const double *array, int size ); - -/*! - \brief Compare 2 values, relative to an interval - - Values are "equal", when : - \f$\cdot value2 - value1 <= abs(intervalSize * 10e^{-6})\f$ - - \param value1 First value to compare - \param value2 Second value to compare - \param intervalSize interval size - - \return 0: if equal, -1: if value2 > value1, 1: if value1 > value2 -*/ -inline int qwtFuzzyCompare( double value1, double value2, double intervalSize ) -{ - const double eps = qAbs( 1.0e-6 * intervalSize ); - - if ( value2 - value1 > eps ) - return -1; - - if ( value1 - value2 > eps ) - return 1; - - return 0; -} - - -inline bool qwtFuzzyGreaterOrEqual( double d1, double d2 ) -{ - return ( d1 >= d2 ) || qFuzzyCompare( d1, d2 ); -} - -inline bool qwtFuzzyLessOrEqual( double d1, double d2 ) -{ - return ( d1 <= d2 ) || qFuzzyCompare( d1, d2 ); -} - -//! Return the sign -inline int qwtSign( double x ) -{ - if ( x > 0.0 ) - return 1; - else if ( x < 0.0 ) - return ( -1 ); - else - return 0; -} - -//! Return the square of a number -inline double qwtSqr( double x ) -{ - return x * x; -} - -//! Like qRound, but without converting the result to an int -inline double qwtRoundF(double d) -{ - return ::floor( d + 0.5 ); -} - -//! Like qFloor, but without converting the result to an int -inline double qwtFloorF(double d) -{ - return ::floor( d ); -} - -//! Like qCeil, but without converting the result to an int -inline double qwtCeilF(double d) -{ - return ::ceil( d ); -} - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_MATH_H +#define QWT_MATH_H + +#include "qwt_global.h" + +#if defined(_MSC_VER) +/* + Microsoft says: + + Define _USE_MATH_DEFINES before including math.h to expose these macro + definitions for common math constants. These are placed under an #ifdef + since these commonly-defined names are not part of the C/C++ standards. +*/ +#define _USE_MATH_DEFINES 1 +#endif + +#include +#include +#include "qwt_global.h" + +#ifndef LOG10_2 +#define LOG10_2 0.30102999566398119802 /* log10(2) */ +#endif + +#ifndef LOG10_3 +#define LOG10_3 0.47712125471966243540 /* log10(3) */ +#endif + +#ifndef LOG10_5 +#define LOG10_5 0.69897000433601885749 /* log10(5) */ +#endif + +#ifndef M_2PI +#define M_2PI 6.28318530717958623200 /* 2 pi */ +#endif + +#ifndef LOG_MIN +//! Mininum value for logarithmic scales +#define LOG_MIN 1.0e-100 +#endif + +#ifndef LOG_MAX +//! Maximum value for logarithmic scales +#define LOG_MAX 1.0e100 +#endif + +#ifndef M_E +#define M_E 2.7182818284590452354 /* e */ +#endif + +#ifndef M_LOG2E +#define M_LOG2E 1.4426950408889634074 /* log_2 e */ +#endif + +#ifndef M_LOG10E +#define M_LOG10E 0.43429448190325182765 /* log_10 e */ +#endif + +#ifndef M_LN2 +#define M_LN2 0.69314718055994530942 /* log_e 2 */ +#endif + +#ifndef M_LN10 +#define M_LN10 2.30258509299404568402 /* log_e 10 */ +#endif + +#ifndef M_PI +#define M_PI 3.14159265358979323846 /* pi */ +#endif + +#ifndef M_PI_2 +#define M_PI_2 1.57079632679489661923 /* pi/2 */ +#endif + +#ifndef M_PI_4 +#define M_PI_4 0.78539816339744830962 /* pi/4 */ +#endif + +#ifndef M_1_PI +#define M_1_PI 0.31830988618379067154 /* 1/pi */ +#endif + +#ifndef M_2_PI +#define M_2_PI 0.63661977236758134308 /* 2/pi */ +#endif + +#ifndef M_2_SQRTPI +#define M_2_SQRTPI 1.12837916709551257390 /* 2/sqrt(pi) */ +#endif + +#ifndef M_SQRT2 +#define M_SQRT2 1.41421356237309504880 /* sqrt(2) */ +#endif + +#ifndef M_SQRT1_2 +#define M_SQRT1_2 0.70710678118654752440 /* 1/sqrt(2) */ +#endif + +QWT_EXPORT double qwtGetMin( const double *array, int size ); +QWT_EXPORT double qwtGetMax( const double *array, int size ); + +/*! + \brief Compare 2 values, relative to an interval + + Values are "equal", when : + \f$\cdot value2 - value1 <= abs(intervalSize * 10e^{-6})\f$ + + \param value1 First value to compare + \param value2 Second value to compare + \param intervalSize interval size + + \return 0: if equal, -1: if value2 > value1, 1: if value1 > value2 +*/ +inline int qwtFuzzyCompare( double value1, double value2, double intervalSize ) +{ + const double eps = qAbs( 1.0e-6 * intervalSize ); + + if ( value2 - value1 > eps ) + return -1; + + if ( value1 - value2 > eps ) + return 1; + + return 0; +} + + +inline bool qwtFuzzyGreaterOrEqual( double d1, double d2 ) +{ + return ( d1 >= d2 ) || qFuzzyCompare( d1, d2 ); +} + +inline bool qwtFuzzyLessOrEqual( double d1, double d2 ) +{ + return ( d1 <= d2 ) || qFuzzyCompare( d1, d2 ); +} + +//! Return the sign +inline int qwtSign( double x ) +{ + if ( x > 0.0 ) + return 1; + else if ( x < 0.0 ) + return ( -1 ); + else + return 0; +} + +//! Return the square of a number +inline double qwtSqr( double x ) +{ + return x * x; +} + +//! Like qRound, but without converting the result to an int +inline double qwtRoundF(double d) +{ + return ::floor( d + 0.5 ); +} + +//! Like qFloor, but without converting the result to an int +inline double qwtFloorF(double d) +{ + return ::floor( d ); +} + +//! Like qCeil, but without converting the result to an int +inline double qwtCeilF(double d) +{ + return ::ceil( d ); +} + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_matrix_raster_data.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_matrix_raster_data.cpp index 7f537e7a0..2176ec9fc 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_matrix_raster_data.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_matrix_raster_data.cpp @@ -1,270 +1,270 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_matrix_raster_data.h" -#include -#include - -class QwtMatrixRasterData::PrivateData -{ -public: - PrivateData(): - resampleMode(QwtMatrixRasterData::NearestNeighbour), - numColumns(0) - { - } - - inline double value(size_t row, size_t col) const - { - return values.data()[ row * numColumns + col ]; - } - - QwtMatrixRasterData::ResampleMode resampleMode; - - QVector values; - size_t numColumns; - size_t numRows; - - double dx; - double dy; -}; - -//! Constructor -QwtMatrixRasterData::QwtMatrixRasterData() -{ - d_data = new PrivateData(); - update(); -} - -//! Destructor -QwtMatrixRasterData::~QwtMatrixRasterData() -{ - delete d_data; -} - -/*! - \brief Set the resampling algorithm - - \param mode Resampling mode - \sa resampleMode(), value() -*/ -void QwtMatrixRasterData::setResampleMode(ResampleMode mode) -{ - d_data->resampleMode = mode; -} - -/*! - \return resampling algorithm - \sa setResampleMode(), value() -*/ -QwtMatrixRasterData::ResampleMode QwtMatrixRasterData::resampleMode() const -{ - return d_data->resampleMode; -} - -/*! - \brief Assign the bounding interval for an axis - - Setting the bounding intervals for the X/Y axis is mandatory - to define the positions for the values of the value matrix. - The interval in Z direction defines the possible range for - the values in the matrix, what is f.e used by QwtPlotSpectrogram - to map values to colors. The Z-interval might be the bounding - interval of the values in the matrix, but usually it isn't. - ( f.e a interval of 0.0-100.0 for values in percentage ) - - \param axis X, Y or Z axis - \param interval Interval - - \sa QwtRasterData::interval(), setValueMatrix() -*/ -void QwtMatrixRasterData::setInterval( - Qt::Axis axis, const QwtInterval &interval ) -{ - QwtRasterData::setInterval( axis, interval ); - update(); -} - -/*! - \brief Assign a value matrix - - The positions of the values are calculated by dividing - the bounding rectangle of the X/Y intervals into equidistant - rectangles ( pixels ). Each value corresponds to the center of - a pixel. - - \param values Vector of values - \param numColumns Number of columns - - \sa valueMatrix(), numColumns(), numRows(), setInterval()() -*/ -void QwtMatrixRasterData::setValueMatrix( - const QVector &values, size_t numColumns ) -{ - d_data->values = values; - d_data->numColumns = numColumns; - update(); -} - -/*! - \return Value matrix - \sa setValueMatrix(), numColumns(), numRows(), setInterval() -*/ -const QVector QwtMatrixRasterData::valueMatrix() const -{ - return d_data->values; -} - -/*! - \return Number of columns of the value matrix - \sa valueMatrix(), numRows(), setValueMatrix() -*/ -size_t QwtMatrixRasterData::numColumns() const -{ - return d_data->numColumns; -} - -/*! - \return Number of rows of the value matrix - \sa valueMatrix(), numColumns(), setValueMatrix() -*/ -size_t QwtMatrixRasterData::numRows() const -{ - return d_data->numRows; -} - -/*! - \brief Pixel hint - - - NearestNeighbour\n - pixelHint() returns the surrounding pixel of the top left value - in the matrix. - - - BilinearInterpolation\n - Returns an empty rectangle recommending - to render in target device ( f.e. screen ) resolution. - - \sa ResampleMode, setMatrix(), setInterval() -*/ -QRectF QwtMatrixRasterData::pixelHint( const QRectF & ) const -{ - QRectF rect; - if ( d_data->resampleMode == NearestNeighbour ) - { - const QwtInterval intervalX = interval( Qt::XAxis ); - const QwtInterval intervalY = interval( Qt::YAxis ); - if ( intervalX.isValid() && intervalY.isValid() ) - { - rect = QRectF( intervalX.minValue(), intervalY.minValue(), - d_data->dx, d_data->dy ); - } - } - - return rect; -} - -/*! - \return the value at a raster position - - \param x X value in plot coordinates - \param y Y value in plot coordinates - - \sa ResampleMode -*/ -double QwtMatrixRasterData::value( double x, double y ) const -{ - const QwtInterval xInterval = interval( Qt::XAxis ); - const QwtInterval yInterval = interval( Qt::YAxis ); - - if ( !( xInterval.contains(x) && yInterval.contains(y) ) ) - return qQNaN(); - - double value; - - switch( d_data->resampleMode ) - { - case BilinearInterpolation: - { - int col1 = qRound( (x - xInterval.minValue() ) / d_data->dx ) - 1; - int row1 = qRound( (y - yInterval.minValue() ) / d_data->dy ) - 1; - int col2 = col1 + 1; - int row2 = row1 + 1; - - if ( col1 < 0 ) - col1 = col2; - else if ( col2 >= (int)d_data->numColumns ) - col2 = col1; - - if ( row1 < 0 ) - row1 = row2; - else if ( row2 >= (int)d_data->numRows ) - row2 = row1; - - const double v11 = d_data->value( row1, col1 ); - const double v21 = d_data->value( row1, col2 ); - const double v12 = d_data->value( row2, col1 ); - const double v22 = d_data->value( row2, col2 ); - - const double x2 = xInterval.minValue() + - ( col2 + 0.5 ) * d_data->dx; - const double y2 = yInterval.minValue() + - ( row2 + 0.5 ) * d_data->dy; - - const double rx = ( x2 - x ) / d_data->dx; - const double ry = ( y2 - y ) / d_data->dy; - - const double vr1 = rx * v11 + ( 1.0 - rx ) * v21; - const double vr2 = rx * v12 + ( 1.0 - rx ) * v22; - - value = ry * vr1 + ( 1.0 - ry ) * vr2; - - break; - } - case NearestNeighbour: - default: - { - uint row = uint( (y - yInterval.minValue() ) / d_data->dy ); - uint col = uint( (x - xInterval.minValue() ) / d_data->dx ); - - // In case of intervals, where the maximum is included - // we get out of bound for row/col, when the value for the - // maximum is requested. Instead we return the value - // from the last row/col - - if ( row >= d_data->numRows ) - row = d_data->numRows - 1; - - if ( col >= d_data->numColumns ) - col = d_data->numColumns - 1; - - value = d_data->value( row, col ); - } - } - - return value; -} - -void QwtMatrixRasterData::update() -{ - d_data->numRows = 0; - d_data->dx = 0.0; - d_data->dy = 0.0; - - if ( d_data->numColumns > 0 ) - { - d_data->numRows = d_data->values.size() / d_data->numColumns; - - const QwtInterval xInterval = interval( Qt::XAxis ); - const QwtInterval yInterval = interval( Qt::YAxis ); - if ( xInterval.isValid() ) - d_data->dx = xInterval.width() / d_data->numColumns; - if ( yInterval.isValid() ) - d_data->dy = yInterval.width() / d_data->numRows; - } -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_matrix_raster_data.h" +#include +#include + +class QwtMatrixRasterData::PrivateData +{ +public: + PrivateData(): + resampleMode(QwtMatrixRasterData::NearestNeighbour), + numColumns(0) + { + } + + inline double value(size_t row, size_t col) const + { + return values.data()[ row * numColumns + col ]; + } + + QwtMatrixRasterData::ResampleMode resampleMode; + + QVector values; + size_t numColumns; + size_t numRows; + + double dx; + double dy; +}; + +//! Constructor +QwtMatrixRasterData::QwtMatrixRasterData() +{ + d_data = new PrivateData(); + update(); +} + +//! Destructor +QwtMatrixRasterData::~QwtMatrixRasterData() +{ + delete d_data; +} + +/*! + \brief Set the resampling algorithm + + \param mode Resampling mode + \sa resampleMode(), value() +*/ +void QwtMatrixRasterData::setResampleMode(ResampleMode mode) +{ + d_data->resampleMode = mode; +} + +/*! + \return resampling algorithm + \sa setResampleMode(), value() +*/ +QwtMatrixRasterData::ResampleMode QwtMatrixRasterData::resampleMode() const +{ + return d_data->resampleMode; +} + +/*! + \brief Assign the bounding interval for an axis + + Setting the bounding intervals for the X/Y axis is mandatory + to define the positions for the values of the value matrix. + The interval in Z direction defines the possible range for + the values in the matrix, what is f.e used by QwtPlotSpectrogram + to map values to colors. The Z-interval might be the bounding + interval of the values in the matrix, but usually it isn't. + ( f.e a interval of 0.0-100.0 for values in percentage ) + + \param axis X, Y or Z axis + \param interval Interval + + \sa QwtRasterData::interval(), setValueMatrix() +*/ +void QwtMatrixRasterData::setInterval( + Qt::Axis axis, const QwtInterval &interval ) +{ + QwtRasterData::setInterval( axis, interval ); + update(); +} + +/*! + \brief Assign a value matrix + + The positions of the values are calculated by dividing + the bounding rectangle of the X/Y intervals into equidistant + rectangles ( pixels ). Each value corresponds to the center of + a pixel. + + \param values Vector of values + \param numColumns Number of columns + + \sa valueMatrix(), numColumns(), numRows(), setInterval()() +*/ +void QwtMatrixRasterData::setValueMatrix( + const QVector &values, size_t numColumns ) +{ + d_data->values = values; + d_data->numColumns = numColumns; + update(); +} + +/*! + \return Value matrix + \sa setValueMatrix(), numColumns(), numRows(), setInterval() +*/ +const QVector QwtMatrixRasterData::valueMatrix() const +{ + return d_data->values; +} + +/*! + \return Number of columns of the value matrix + \sa valueMatrix(), numRows(), setValueMatrix() +*/ +size_t QwtMatrixRasterData::numColumns() const +{ + return d_data->numColumns; +} + +/*! + \return Number of rows of the value matrix + \sa valueMatrix(), numColumns(), setValueMatrix() +*/ +size_t QwtMatrixRasterData::numRows() const +{ + return d_data->numRows; +} + +/*! + \brief Pixel hint + + - NearestNeighbour\n + pixelHint() returns the surrounding pixel of the top left value + in the matrix. + + - BilinearInterpolation\n + Returns an empty rectangle recommending + to render in target device ( f.e. screen ) resolution. + + \sa ResampleMode, setMatrix(), setInterval() +*/ +QRectF QwtMatrixRasterData::pixelHint( const QRectF & ) const +{ + QRectF rect; + if ( d_data->resampleMode == NearestNeighbour ) + { + const QwtInterval intervalX = interval( Qt::XAxis ); + const QwtInterval intervalY = interval( Qt::YAxis ); + if ( intervalX.isValid() && intervalY.isValid() ) + { + rect = QRectF( intervalX.minValue(), intervalY.minValue(), + d_data->dx, d_data->dy ); + } + } + + return rect; +} + +/*! + \return the value at a raster position + + \param x X value in plot coordinates + \param y Y value in plot coordinates + + \sa ResampleMode +*/ +double QwtMatrixRasterData::value( double x, double y ) const +{ + const QwtInterval xInterval = interval( Qt::XAxis ); + const QwtInterval yInterval = interval( Qt::YAxis ); + + if ( !( xInterval.contains(x) && yInterval.contains(y) ) ) + return qQNaN(); + + double value; + + switch( d_data->resampleMode ) + { + case BilinearInterpolation: + { + int col1 = qRound( (x - xInterval.minValue() ) / d_data->dx ) - 1; + int row1 = qRound( (y - yInterval.minValue() ) / d_data->dy ) - 1; + int col2 = col1 + 1; + int row2 = row1 + 1; + + if ( col1 < 0 ) + col1 = col2; + else if ( col2 >= (int)d_data->numColumns ) + col2 = col1; + + if ( row1 < 0 ) + row1 = row2; + else if ( row2 >= (int)d_data->numRows ) + row2 = row1; + + const double v11 = d_data->value( row1, col1 ); + const double v21 = d_data->value( row1, col2 ); + const double v12 = d_data->value( row2, col1 ); + const double v22 = d_data->value( row2, col2 ); + + const double x2 = xInterval.minValue() + + ( col2 + 0.5 ) * d_data->dx; + const double y2 = yInterval.minValue() + + ( row2 + 0.5 ) * d_data->dy; + + const double rx = ( x2 - x ) / d_data->dx; + const double ry = ( y2 - y ) / d_data->dy; + + const double vr1 = rx * v11 + ( 1.0 - rx ) * v21; + const double vr2 = rx * v12 + ( 1.0 - rx ) * v22; + + value = ry * vr1 + ( 1.0 - ry ) * vr2; + + break; + } + case NearestNeighbour: + default: + { + uint row = uint( (y - yInterval.minValue() ) / d_data->dy ); + uint col = uint( (x - xInterval.minValue() ) / d_data->dx ); + + // In case of intervals, where the maximum is included + // we get out of bound for row/col, when the value for the + // maximum is requested. Instead we return the value + // from the last row/col + + if ( row >= d_data->numRows ) + row = d_data->numRows - 1; + + if ( col >= d_data->numColumns ) + col = d_data->numColumns - 1; + + value = d_data->value( row, col ); + } + } + + return value; +} + +void QwtMatrixRasterData::update() +{ + d_data->numRows = 0; + d_data->dx = 0.0; + d_data->dy = 0.0; + + if ( d_data->numColumns > 0 ) + { + d_data->numRows = d_data->values.size() / d_data->numColumns; + + const QwtInterval xInterval = interval( Qt::XAxis ); + const QwtInterval yInterval = interval( Qt::YAxis ); + if ( xInterval.isValid() ) + d_data->dx = xInterval.width() / d_data->numColumns; + if ( yInterval.isValid() ) + d_data->dy = yInterval.width() / d_data->numRows; + } +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_matrix_raster_data.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_matrix_raster_data.h index b5b181bb4..a8940f8ac 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_matrix_raster_data.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_matrix_raster_data.h @@ -1,71 +1,71 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_MATRIX_RASTER_DATA_H -#define QWT_MATRIX_RASTER_DATA_H 1 - -#include "qwt_global.h" -#include "qwt_raster_data.h" -#include - -/*! - \brief A class representing a matrix of values as raster data - - QwtMatrixRasterData implements an interface for a matrix of - equidistant values, that can be used by a QwtPlotRasterItem. - It implements a couple of resampling algorithms, to provide - values for positions, that or not on the value matrix. -*/ -class QWT_EXPORT QwtMatrixRasterData: public QwtRasterData -{ -public: - /*! - \brief Resampling algorithm - The default setting is NearestNeighbour; - */ - enum ResampleMode - { - /*! - Return the value from the matrix, that is nearest to the - the requested position. - */ - NearestNeighbour, - - /*! - Interpolate the value from the distances and values of the - 4 surrounding values in the matrix, - */ - BilinearInterpolation - }; - - QwtMatrixRasterData(); - virtual ~QwtMatrixRasterData(); - - void setResampleMode(ResampleMode mode); - ResampleMode resampleMode() const; - - virtual void setInterval( Qt::Axis, const QwtInterval & ); - void setValueMatrix( const QVector &values, size_t numColumns ); - - const QVector valueMatrix() const; - size_t numColumns() const; - size_t numRows() const; - - virtual QRectF pixelHint( const QRectF & ) const; - - virtual double value( double x, double y ) const; - -private: - void update(); - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_MATRIX_RASTER_DATA_H +#define QWT_MATRIX_RASTER_DATA_H 1 + +#include "qwt_global.h" +#include "qwt_raster_data.h" +#include + +/*! + \brief A class representing a matrix of values as raster data + + QwtMatrixRasterData implements an interface for a matrix of + equidistant values, that can be used by a QwtPlotRasterItem. + It implements a couple of resampling algorithms, to provide + values for positions, that or not on the value matrix. +*/ +class QWT_EXPORT QwtMatrixRasterData: public QwtRasterData +{ +public: + /*! + \brief Resampling algorithm + The default setting is NearestNeighbour; + */ + enum ResampleMode + { + /*! + Return the value from the matrix, that is nearest to the + the requested position. + */ + NearestNeighbour, + + /*! + Interpolate the value from the distances and values of the + 4 surrounding values in the matrix, + */ + BilinearInterpolation + }; + + QwtMatrixRasterData(); + virtual ~QwtMatrixRasterData(); + + void setResampleMode(ResampleMode mode); + ResampleMode resampleMode() const; + + virtual void setInterval( Qt::Axis, const QwtInterval & ); + void setValueMatrix( const QVector &values, size_t numColumns ); + + const QVector valueMatrix() const; + size_t numColumns() const; + size_t numRows() const; + + virtual QRectF pixelHint( const QRectF & ) const; + + virtual double value( double x, double y ) const; + +private: + void update(); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_null_paintdevice.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_null_paintdevice.cpp index 1edf2e571..cdab2a6a8 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_null_paintdevice.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_null_paintdevice.cpp @@ -1,428 +1,428 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_null_paintdevice.h" -#include -#include - -class QwtNullPaintDevice::PrivateData -{ -public: - PrivateData(): - size( 0, 0 ) - { - } - - QSize size; -}; - -class QwtNullPaintDevice::PaintEngine: public QPaintEngine -{ -public: - PaintEngine( QPaintEngine::PaintEngineFeatures ); - - virtual bool begin( QPaintDevice * ); - virtual bool end(); - - virtual Type type () const; - virtual void updateState(const QPaintEngineState &); - - virtual void drawRects(const QRect *, int ); - virtual void drawRects(const QRectF *, int ); - - virtual void drawLines(const QLine *, int ); - virtual void drawLines(const QLineF *, int ); - - virtual void drawEllipse(const QRectF &); - virtual void drawEllipse(const QRect &); - - virtual void drawPath(const QPainterPath &); - - virtual void drawPoints(const QPointF *, int ); - virtual void drawPoints(const QPoint *, int ); - - virtual void drawPolygon(const QPointF *, int , PolygonDrawMode ); - virtual void drawPolygon(const QPoint *, int , PolygonDrawMode ); - - virtual void drawPixmap(const QRectF &, - const QPixmap &, const QRectF &); - - virtual void drawTextItem(const QPointF &, const QTextItem &); - virtual void drawTiledPixmap(const QRectF &, - const QPixmap &, const QPointF &s); - virtual void drawImage(const QRectF &, - const QImage &, const QRectF &, Qt::ImageConversionFlags ); - -private: - QwtNullPaintDevice *d_device; -}; - -QwtNullPaintDevice::PaintEngine::PaintEngine( - QPaintEngine::PaintEngineFeatures features ): - QPaintEngine( features ), - d_device(NULL) -{ -} - -bool QwtNullPaintDevice::PaintEngine::begin( - QPaintDevice *device ) -{ - d_device = static_cast( device ); - return true; -} - -bool QwtNullPaintDevice::PaintEngine::end() -{ - d_device = NULL; - return true; -} - -QPaintEngine::Type -QwtNullPaintDevice::PaintEngine::type () const -{ - return QPaintEngine::User; -} - -void QwtNullPaintDevice::PaintEngine::drawRects( - const QRect *rects, int rectCount) -{ - if ( d_device ) - d_device->drawRects( rects, rectCount ); -} - -void QwtNullPaintDevice::PaintEngine::drawRects( - const QRectF *rects, int rectCount) -{ - if ( d_device ) - d_device->drawRects( rects, rectCount ); -} - -void QwtNullPaintDevice::PaintEngine::drawLines( - const QLine *lines, int lineCount) -{ - if ( d_device ) - d_device->drawLines( lines, lineCount ); -} - -void QwtNullPaintDevice::PaintEngine::drawLines( - const QLineF *lines, int lineCount) -{ - if ( d_device ) - d_device->drawLines( lines, lineCount ); -} - -void QwtNullPaintDevice::PaintEngine::drawEllipse( - const QRectF &rect) -{ - if ( d_device ) - d_device->drawEllipse( rect ); -} - -void QwtNullPaintDevice::PaintEngine::drawEllipse( - const QRect &rect) -{ - if ( d_device ) - d_device->drawEllipse( rect ); -} - - -void QwtNullPaintDevice::PaintEngine::drawPath( - const QPainterPath &path) -{ - if ( d_device ) - d_device->drawPath( path ); -} - -void QwtNullPaintDevice::PaintEngine::drawPoints( - const QPointF *points, int pointCount) -{ - if ( d_device ) - d_device->drawPoints( points, pointCount ); -} - -void QwtNullPaintDevice::PaintEngine::drawPoints( - const QPoint *points, int pointCount) -{ - if ( d_device ) - d_device->drawPoints( points, pointCount ); -} - -void QwtNullPaintDevice::PaintEngine::drawPolygon( - const QPointF *points, int pointCount, PolygonDrawMode mode) -{ - if ( d_device ) - d_device->drawPolygon( points, pointCount, mode ); -} - -void QwtNullPaintDevice::PaintEngine::drawPolygon( - const QPoint *points, int pointCount, PolygonDrawMode mode) -{ - if ( d_device ) - d_device->drawPolygon( points, pointCount, mode ); -} - -void QwtNullPaintDevice::PaintEngine::drawPixmap( - const QRectF &rect, const QPixmap &pm, const QRectF &subRect ) -{ - if ( d_device ) - d_device->drawPixmap( rect, pm, subRect ); -} - -void QwtNullPaintDevice::PaintEngine::drawTextItem( - const QPointF &pos, const QTextItem &textItem) -{ - if ( d_device ) - d_device->drawTextItem( pos, textItem ); -} - -void QwtNullPaintDevice::PaintEngine::drawTiledPixmap( - const QRectF &rect, const QPixmap &pixmap, - const QPointF &subRect) -{ - if ( d_device ) - d_device->drawTiledPixmap( rect, pixmap, subRect ); -} - -void QwtNullPaintDevice::PaintEngine::drawImage( - const QRectF &rect, const QImage &image, - const QRectF &subRect, Qt::ImageConversionFlags flags) -{ - if ( d_device ) - d_device->drawImage( rect, image, subRect, flags ); -} - -void QwtNullPaintDevice::PaintEngine::updateState( - const QPaintEngineState &state) -{ - if ( d_device ) - d_device->updateState( state ); -} - -//! Constructor -QwtNullPaintDevice::QwtNullPaintDevice( - QPaintEngine::PaintEngineFeatures features ) -{ - init( features ); -} - -//! Constructor -QwtNullPaintDevice::QwtNullPaintDevice( const QSize &size, - QPaintEngine::PaintEngineFeatures features ) -{ - init( features ); - d_data->size = size; -} - -void QwtNullPaintDevice::init( - QPaintEngine::PaintEngineFeatures features ) -{ - d_engine = new PaintEngine( features ); - d_data = new PrivateData; -} - -//! Destructor -QwtNullPaintDevice::~QwtNullPaintDevice() -{ - delete d_engine; - delete d_data; -} - -/*! - Set the size of the paint device - - \param size Size - \sa size() -*/ -void QwtNullPaintDevice::setSize( const QSize & size ) -{ - d_data->size = size; -} - -/*! - \return Size of the paint device - \sa setSize() -*/ -QSize QwtNullPaintDevice::size() const -{ - return d_data->size; -} - -//! See QPaintDevice::paintEngine() -QPaintEngine *QwtNullPaintDevice::paintEngine() const -{ - return d_engine; -} - -/*! - See QPaintDevice::metric() - \sa setSize() -*/ -int QwtNullPaintDevice::metric( PaintDeviceMetric metric ) const -{ - static QPixmap pm; - - int value; - - switch ( metric ) - { - case PdmWidth: - value = qMax( d_data->size.width(), 0 ); - break; - case PdmHeight: - value = qMax( d_data->size.height(), 0 ); - break; - case PdmNumColors: - value = 16777216; - break; - case PdmDepth: - value = 24; - break; - case PdmPhysicalDpiX: - case PdmDpiY: - case PdmPhysicalDpiY: - case PdmWidthMM: - case PdmHeightMM: - case PdmDpiX: - default: - value = 0; - } - return value; - -} - -//! See QPaintEngine::drawRects() -void QwtNullPaintDevice::drawRects( - const QRect *rects, int rectCount) -{ - Q_UNUSED(rects); - Q_UNUSED(rectCount); -} - -//! See QPaintEngine::drawRects() -void QwtNullPaintDevice::drawRects( - const QRectF *rects, int rectCount) -{ - Q_UNUSED(rects); - Q_UNUSED(rectCount); -} - -//! See QPaintEngine::drawLines() -void QwtNullPaintDevice::drawLines( - const QLine *lines, int lineCount) -{ - Q_UNUSED(lines); - Q_UNUSED(lineCount); -} - -//! See QPaintEngine::drawLines() -void QwtNullPaintDevice::drawLines( - const QLineF *lines, int lineCount) -{ - Q_UNUSED(lines); - Q_UNUSED(lineCount); -} - -//! See QPaintEngine::drawEllipse() -void QwtNullPaintDevice::drawEllipse( const QRectF &rect ) -{ - Q_UNUSED(rect); -} - -//! See QPaintEngine::drawEllipse() -void QwtNullPaintDevice::drawEllipse( const QRect &rect ) -{ - Q_UNUSED(rect); -} - -//! See QPaintEngine::drawPath() -void QwtNullPaintDevice::drawPath( const QPainterPath &path ) -{ - Q_UNUSED(path); -} - -//! See QPaintEngine::drawPoints() -void QwtNullPaintDevice::drawPoints( - const QPointF *points, int pointCount) -{ - Q_UNUSED(points); - Q_UNUSED(pointCount); -} - -//! See QPaintEngine::drawPoints() -void QwtNullPaintDevice::drawPoints( - const QPoint *points, int pointCount) -{ - Q_UNUSED(points); - Q_UNUSED(pointCount); -} - -//! See QPaintEngine::drawPolygon() -void QwtNullPaintDevice::drawPolygon( - const QPointF *points, int pointCount, - QPaintEngine::PolygonDrawMode mode) -{ - Q_UNUSED(points); - Q_UNUSED(pointCount); - Q_UNUSED(mode); -} - -//! See QPaintEngine::drawPolygon() -void QwtNullPaintDevice::drawPolygon( - const QPoint *points, int pointCount, - QPaintEngine::PolygonDrawMode mode) -{ - Q_UNUSED(points); - Q_UNUSED(pointCount); - Q_UNUSED(mode); -} - -//! See QPaintEngine::drawPixmap() -void QwtNullPaintDevice::drawPixmap( const QRectF &rect, - const QPixmap &pm, const QRectF &subRect ) -{ - Q_UNUSED(rect); - Q_UNUSED(pm); - Q_UNUSED(subRect); -} - -//! See QPaintEngine::drawTextItem() -void QwtNullPaintDevice::drawTextItem( - const QPointF &pos, const QTextItem &textItem) -{ - Q_UNUSED(pos); - Q_UNUSED(textItem); -} - -//! See QPaintEngine::drawTiledPixmap() -void QwtNullPaintDevice::drawTiledPixmap( - const QRectF &rect, const QPixmap &pixmap, - const QPointF &subRect) -{ - Q_UNUSED(rect); - Q_UNUSED(pixmap); - Q_UNUSED(subRect); -} - -//! See QPaintEngine::drawImage() -void QwtNullPaintDevice::drawImage( - const QRectF &rect, const QImage &image, - const QRectF &subRect, Qt::ImageConversionFlags flags) -{ - Q_UNUSED(rect); - Q_UNUSED(image); - Q_UNUSED(subRect); - Q_UNUSED(flags); -} - -//! See QPaintEngine::updateState() -void QwtNullPaintDevice::updateState( - const QPaintEngineState &state ) -{ - Q_UNUSED(state); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_null_paintdevice.h" +#include +#include + +class QwtNullPaintDevice::PrivateData +{ +public: + PrivateData(): + size( 0, 0 ) + { + } + + QSize size; +}; + +class QwtNullPaintDevice::PaintEngine: public QPaintEngine +{ +public: + PaintEngine( QPaintEngine::PaintEngineFeatures ); + + virtual bool begin( QPaintDevice * ); + virtual bool end(); + + virtual Type type () const; + virtual void updateState(const QPaintEngineState &); + + virtual void drawRects(const QRect *, int ); + virtual void drawRects(const QRectF *, int ); + + virtual void drawLines(const QLine *, int ); + virtual void drawLines(const QLineF *, int ); + + virtual void drawEllipse(const QRectF &); + virtual void drawEllipse(const QRect &); + + virtual void drawPath(const QPainterPath &); + + virtual void drawPoints(const QPointF *, int ); + virtual void drawPoints(const QPoint *, int ); + + virtual void drawPolygon(const QPointF *, int , PolygonDrawMode ); + virtual void drawPolygon(const QPoint *, int , PolygonDrawMode ); + + virtual void drawPixmap(const QRectF &, + const QPixmap &, const QRectF &); + + virtual void drawTextItem(const QPointF &, const QTextItem &); + virtual void drawTiledPixmap(const QRectF &, + const QPixmap &, const QPointF &s); + virtual void drawImage(const QRectF &, + const QImage &, const QRectF &, Qt::ImageConversionFlags ); + +private: + QwtNullPaintDevice *d_device; +}; + +QwtNullPaintDevice::PaintEngine::PaintEngine( + QPaintEngine::PaintEngineFeatures features ): + QPaintEngine( features ), + d_device(NULL) +{ +} + +bool QwtNullPaintDevice::PaintEngine::begin( + QPaintDevice *device ) +{ + d_device = static_cast( device ); + return true; +} + +bool QwtNullPaintDevice::PaintEngine::end() +{ + d_device = NULL; + return true; +} + +QPaintEngine::Type +QwtNullPaintDevice::PaintEngine::type () const +{ + return QPaintEngine::User; +} + +void QwtNullPaintDevice::PaintEngine::drawRects( + const QRect *rects, int rectCount) +{ + if ( d_device ) + d_device->drawRects( rects, rectCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawRects( + const QRectF *rects, int rectCount) +{ + if ( d_device ) + d_device->drawRects( rects, rectCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawLines( + const QLine *lines, int lineCount) +{ + if ( d_device ) + d_device->drawLines( lines, lineCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawLines( + const QLineF *lines, int lineCount) +{ + if ( d_device ) + d_device->drawLines( lines, lineCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawEllipse( + const QRectF &rect) +{ + if ( d_device ) + d_device->drawEllipse( rect ); +} + +void QwtNullPaintDevice::PaintEngine::drawEllipse( + const QRect &rect) +{ + if ( d_device ) + d_device->drawEllipse( rect ); +} + + +void QwtNullPaintDevice::PaintEngine::drawPath( + const QPainterPath &path) +{ + if ( d_device ) + d_device->drawPath( path ); +} + +void QwtNullPaintDevice::PaintEngine::drawPoints( + const QPointF *points, int pointCount) +{ + if ( d_device ) + d_device->drawPoints( points, pointCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawPoints( + const QPoint *points, int pointCount) +{ + if ( d_device ) + d_device->drawPoints( points, pointCount ); +} + +void QwtNullPaintDevice::PaintEngine::drawPolygon( + const QPointF *points, int pointCount, PolygonDrawMode mode) +{ + if ( d_device ) + d_device->drawPolygon( points, pointCount, mode ); +} + +void QwtNullPaintDevice::PaintEngine::drawPolygon( + const QPoint *points, int pointCount, PolygonDrawMode mode) +{ + if ( d_device ) + d_device->drawPolygon( points, pointCount, mode ); +} + +void QwtNullPaintDevice::PaintEngine::drawPixmap( + const QRectF &rect, const QPixmap &pm, const QRectF &subRect ) +{ + if ( d_device ) + d_device->drawPixmap( rect, pm, subRect ); +} + +void QwtNullPaintDevice::PaintEngine::drawTextItem( + const QPointF &pos, const QTextItem &textItem) +{ + if ( d_device ) + d_device->drawTextItem( pos, textItem ); +} + +void QwtNullPaintDevice::PaintEngine::drawTiledPixmap( + const QRectF &rect, const QPixmap &pixmap, + const QPointF &subRect) +{ + if ( d_device ) + d_device->drawTiledPixmap( rect, pixmap, subRect ); +} + +void QwtNullPaintDevice::PaintEngine::drawImage( + const QRectF &rect, const QImage &image, + const QRectF &subRect, Qt::ImageConversionFlags flags) +{ + if ( d_device ) + d_device->drawImage( rect, image, subRect, flags ); +} + +void QwtNullPaintDevice::PaintEngine::updateState( + const QPaintEngineState &state) +{ + if ( d_device ) + d_device->updateState( state ); +} + +//! Constructor +QwtNullPaintDevice::QwtNullPaintDevice( + QPaintEngine::PaintEngineFeatures features ) +{ + init( features ); +} + +//! Constructor +QwtNullPaintDevice::QwtNullPaintDevice( const QSize &size, + QPaintEngine::PaintEngineFeatures features ) +{ + init( features ); + d_data->size = size; +} + +void QwtNullPaintDevice::init( + QPaintEngine::PaintEngineFeatures features ) +{ + d_engine = new PaintEngine( features ); + d_data = new PrivateData; +} + +//! Destructor +QwtNullPaintDevice::~QwtNullPaintDevice() +{ + delete d_engine; + delete d_data; +} + +/*! + Set the size of the paint device + + \param size Size + \sa size() +*/ +void QwtNullPaintDevice::setSize( const QSize & size ) +{ + d_data->size = size; +} + +/*! + \return Size of the paint device + \sa setSize() +*/ +QSize QwtNullPaintDevice::size() const +{ + return d_data->size; +} + +//! See QPaintDevice::paintEngine() +QPaintEngine *QwtNullPaintDevice::paintEngine() const +{ + return d_engine; +} + +/*! + See QPaintDevice::metric() + \sa setSize() +*/ +int QwtNullPaintDevice::metric( PaintDeviceMetric metric ) const +{ + static QPixmap pm; + + int value; + + switch ( metric ) + { + case PdmWidth: + value = qMax( d_data->size.width(), 0 ); + break; + case PdmHeight: + value = qMax( d_data->size.height(), 0 ); + break; + case PdmNumColors: + value = 16777216; + break; + case PdmDepth: + value = 24; + break; + case PdmPhysicalDpiX: + case PdmDpiY: + case PdmPhysicalDpiY: + case PdmWidthMM: + case PdmHeightMM: + case PdmDpiX: + default: + value = 0; + } + return value; + +} + +//! See QPaintEngine::drawRects() +void QwtNullPaintDevice::drawRects( + const QRect *rects, int rectCount) +{ + Q_UNUSED(rects); + Q_UNUSED(rectCount); +} + +//! See QPaintEngine::drawRects() +void QwtNullPaintDevice::drawRects( + const QRectF *rects, int rectCount) +{ + Q_UNUSED(rects); + Q_UNUSED(rectCount); +} + +//! See QPaintEngine::drawLines() +void QwtNullPaintDevice::drawLines( + const QLine *lines, int lineCount) +{ + Q_UNUSED(lines); + Q_UNUSED(lineCount); +} + +//! See QPaintEngine::drawLines() +void QwtNullPaintDevice::drawLines( + const QLineF *lines, int lineCount) +{ + Q_UNUSED(lines); + Q_UNUSED(lineCount); +} + +//! See QPaintEngine::drawEllipse() +void QwtNullPaintDevice::drawEllipse( const QRectF &rect ) +{ + Q_UNUSED(rect); +} + +//! See QPaintEngine::drawEllipse() +void QwtNullPaintDevice::drawEllipse( const QRect &rect ) +{ + Q_UNUSED(rect); +} + +//! See QPaintEngine::drawPath() +void QwtNullPaintDevice::drawPath( const QPainterPath &path ) +{ + Q_UNUSED(path); +} + +//! See QPaintEngine::drawPoints() +void QwtNullPaintDevice::drawPoints( + const QPointF *points, int pointCount) +{ + Q_UNUSED(points); + Q_UNUSED(pointCount); +} + +//! See QPaintEngine::drawPoints() +void QwtNullPaintDevice::drawPoints( + const QPoint *points, int pointCount) +{ + Q_UNUSED(points); + Q_UNUSED(pointCount); +} + +//! See QPaintEngine::drawPolygon() +void QwtNullPaintDevice::drawPolygon( + const QPointF *points, int pointCount, + QPaintEngine::PolygonDrawMode mode) +{ + Q_UNUSED(points); + Q_UNUSED(pointCount); + Q_UNUSED(mode); +} + +//! See QPaintEngine::drawPolygon() +void QwtNullPaintDevice::drawPolygon( + const QPoint *points, int pointCount, + QPaintEngine::PolygonDrawMode mode) +{ + Q_UNUSED(points); + Q_UNUSED(pointCount); + Q_UNUSED(mode); +} + +//! See QPaintEngine::drawPixmap() +void QwtNullPaintDevice::drawPixmap( const QRectF &rect, + const QPixmap &pm, const QRectF &subRect ) +{ + Q_UNUSED(rect); + Q_UNUSED(pm); + Q_UNUSED(subRect); +} + +//! See QPaintEngine::drawTextItem() +void QwtNullPaintDevice::drawTextItem( + const QPointF &pos, const QTextItem &textItem) +{ + Q_UNUSED(pos); + Q_UNUSED(textItem); +} + +//! See QPaintEngine::drawTiledPixmap() +void QwtNullPaintDevice::drawTiledPixmap( + const QRectF &rect, const QPixmap &pixmap, + const QPointF &subRect) +{ + Q_UNUSED(rect); + Q_UNUSED(pixmap); + Q_UNUSED(subRect); +} + +//! See QPaintEngine::drawImage() +void QwtNullPaintDevice::drawImage( + const QRectF &rect, const QImage &image, + const QRectF &subRect, Qt::ImageConversionFlags flags) +{ + Q_UNUSED(rect); + Q_UNUSED(image); + Q_UNUSED(subRect); + Q_UNUSED(flags); +} + +//! See QPaintEngine::updateState() +void QwtNullPaintDevice::updateState( + const QPaintEngineState &state ) +{ + Q_UNUSED(state); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_null_paintdevice.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_null_paintdevice.h index a67da16a7..aae9c2d6b 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_null_paintdevice.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_null_paintdevice.h @@ -1,89 +1,89 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_NULL_PAINT_DEVICE_H -#define QWT_NULL_PAINT_DEVICE_H 1 - -#include "qwt_global.h" -#include -#include - -/*! - \brief A null paint device doing nothing - - Sometimes important layout/rendering geometries are not - available or changable from the public Qt class interface. - ( f.e hidden in the style implementation ). - - QwtNullPaintDevice can be used to manipulate or filter out - these informations by analyzing the stream of paint primitives. - - F.e. QwtNullPaintDevice is used by QwtPlotCanvas to identify - styled backgrounds with rounded corners. -*/ - -class QWT_EXPORT QwtNullPaintDevice: public QPaintDevice -{ -public: - QwtNullPaintDevice( QPaintEngine::PaintEngineFeatures ); - QwtNullPaintDevice( const QSize &size, - QPaintEngine::PaintEngineFeatures ); - - virtual ~QwtNullPaintDevice(); - - void setSize( const QSize &); - QSize size() const; - - virtual QPaintEngine *paintEngine() const; - virtual int metric( PaintDeviceMetric metric ) const; - - virtual void drawRects(const QRect *, int ); - virtual void drawRects(const QRectF *, int ); - - virtual void drawLines(const QLine *, int ); - virtual void drawLines(const QLineF *, int ); - - virtual void drawEllipse(const QRectF &); - virtual void drawEllipse(const QRect &); - - virtual void drawPath(const QPainterPath &); - - virtual void drawPoints(const QPointF *, int ); - virtual void drawPoints(const QPoint *, int ); - - virtual void drawPolygon( - const QPointF *, int , QPaintEngine::PolygonDrawMode ); - - virtual void drawPolygon( - const QPoint *, int , QPaintEngine::PolygonDrawMode ); - - virtual void drawPixmap(const QRectF &, - const QPixmap &, const QRectF &); - - virtual void drawTextItem(const QPointF &, const QTextItem &); - - virtual void drawTiledPixmap(const QRectF &, - const QPixmap &, const QPointF &s); - - virtual void drawImage(const QRectF &, - const QImage &, const QRectF &, Qt::ImageConversionFlags ); - - virtual void updateState( const QPaintEngineState &state ); - -private: - void init( QPaintEngine::PaintEngineFeatures ); - - class PaintEngine; - PaintEngine *d_engine; - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_NULL_PAINT_DEVICE_H +#define QWT_NULL_PAINT_DEVICE_H 1 + +#include "qwt_global.h" +#include +#include + +/*! + \brief A null paint device doing nothing + + Sometimes important layout/rendering geometries are not + available or changable from the public Qt class interface. + ( f.e hidden in the style implementation ). + + QwtNullPaintDevice can be used to manipulate or filter out + these informations by analyzing the stream of paint primitives. + + F.e. QwtNullPaintDevice is used by QwtPlotCanvas to identify + styled backgrounds with rounded corners. +*/ + +class QWT_EXPORT QwtNullPaintDevice: public QPaintDevice +{ +public: + QwtNullPaintDevice( QPaintEngine::PaintEngineFeatures ); + QwtNullPaintDevice( const QSize &size, + QPaintEngine::PaintEngineFeatures ); + + virtual ~QwtNullPaintDevice(); + + void setSize( const QSize &); + QSize size() const; + + virtual QPaintEngine *paintEngine() const; + virtual int metric( PaintDeviceMetric metric ) const; + + virtual void drawRects(const QRect *, int ); + virtual void drawRects(const QRectF *, int ); + + virtual void drawLines(const QLine *, int ); + virtual void drawLines(const QLineF *, int ); + + virtual void drawEllipse(const QRectF &); + virtual void drawEllipse(const QRect &); + + virtual void drawPath(const QPainterPath &); + + virtual void drawPoints(const QPointF *, int ); + virtual void drawPoints(const QPoint *, int ); + + virtual void drawPolygon( + const QPointF *, int , QPaintEngine::PolygonDrawMode ); + + virtual void drawPolygon( + const QPoint *, int , QPaintEngine::PolygonDrawMode ); + + virtual void drawPixmap(const QRectF &, + const QPixmap &, const QRectF &); + + virtual void drawTextItem(const QPointF &, const QTextItem &); + + virtual void drawTiledPixmap(const QRectF &, + const QPixmap &, const QPointF &s); + + virtual void drawImage(const QRectF &, + const QImage &, const QRectF &, Qt::ImageConversionFlags ); + + virtual void updateState( const QPaintEngineState &state ); + +private: + void init( QPaintEngine::PaintEngineFeatures ); + + class PaintEngine; + PaintEngine *d_engine; + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_painter.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_painter.cpp index dc28cfe6a..58a1d7bc6 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_painter.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_painter.cpp @@ -1,704 +1,704 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_painter.h" -#include "qwt_math.h" -#include "qwt_clipper.h" -#include "qwt_color_map.h" -#include "qwt_scale_map.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -bool QwtPainter::d_polylineSplitting = true; -bool QwtPainter::d_roundingAlignment = true; - -static inline bool isClippingNeeded( const QPainter *painter, QRectF &clipRect ) -{ - bool doClipping = false; - const QPaintEngine *pe = painter->paintEngine(); - if ( pe && pe->type() == QPaintEngine::SVG ) - { - // The SVG paint engine ignores any clipping, - - if ( painter->hasClipping() ) - { - doClipping = true; - clipRect = painter->clipRegion().boundingRect(); - } - } - - return doClipping; -} - -static inline void drawPolyline( QPainter *painter, - const QPointF *points, int pointCount, bool polylineSplitting ) -{ - bool doSplit = false; - if ( polylineSplitting ) - { - const QPaintEngine *pe = painter->paintEngine(); - if ( pe && pe->type() == QPaintEngine::Raster ) - { - /* - The raster paint engine seems to use some algo with O(n*n). - ( Qt 4.3 is better than Qt 4.2, but remains unacceptable) - To work around this problem, we have to split the polygon into - smaller pieces. - */ - doSplit = true; - } - } - - if ( doSplit ) - { - const int splitSize = 20; - for ( int i = 0; i < pointCount; i += splitSize ) - { - const int n = qMin( splitSize + 1, pointCount - i ); - painter->drawPolyline( points + i, n ); - } - } - else - painter->drawPolyline( points, pointCount ); -} - -static inline void unscaleFont( QPainter *painter ) -{ - if ( painter->font().pixelSize() >= 0 ) - return; - - static QSize screenResolution; - if ( !screenResolution.isValid() ) - { - QDesktopWidget *desktop = QApplication::desktop(); - if ( desktop ) - { - screenResolution.setWidth( desktop->logicalDpiX() ); - screenResolution.setHeight( desktop->logicalDpiY() ); - } - } - - const QPaintDevice *pd = painter->device(); - if ( pd->logicalDpiX() != screenResolution.width() || - pd->logicalDpiY() != screenResolution.height() ) - { - QFont pixelFont( painter->font(), QApplication::desktop() ); - pixelFont.setPixelSize( QFontInfo( pixelFont ).pixelSize() ); - - painter->setFont( pixelFont ); - } -} - -/*! - Check if the painter is using a paint engine, that aligns - coordinates to integers. Today these are all paint engines - beside QPaintEngine::Pdf and QPaintEngine::SVG. - - \param painter Painter - \return true, when the paint engine is aligning - - \sa setRoundingAlignment() -*/ -bool QwtPainter::isAligning( QPainter *painter ) -{ - if ( painter && painter->isActive() ) - { - switch ( painter->paintEngine()->type() ) - { - case QPaintEngine::Pdf: - case QPaintEngine::SVG: - return false; - - default:; - } - } - - return true; -} - -/*! - Enable whether coordinates should be rounded, before they are painted - to a paint engine that floors to integer values. For other paint engines - this ( Pdf, SVG ), this flag has no effect. - QwtPainter stores this flag only, the rounding itsself is done in - the painting code ( f.e the plot items ). - - The default setting is true. - - \sa roundingAlignment(), isAligning() -*/ -void QwtPainter::setRoundingAlignment( bool enable ) -{ - d_roundingAlignment = enable; -} - -/*! - \brief En/Disable line splitting for the raster paint engine - - The raster paint engine paints polylines of many points - much faster when they are splitted in smaller chunks. - - \sa polylineSplitting() -*/ -void QwtPainter::setPolylineSplitting( bool enable ) -{ - d_polylineSplitting = enable; -} - -//! Wrapper for QPainter::drawPath() -void QwtPainter::drawPath( QPainter *painter, const QPainterPath &path ) -{ - painter->drawPath( path ); -} - -//! Wrapper for QPainter::drawRect() -void QwtPainter::drawRect( QPainter *painter, double x, double y, double w, double h ) -{ - drawRect( painter, QRectF( x, y, w, h ) ); -} - -//! Wrapper for QPainter::drawRect() -void QwtPainter::drawRect( QPainter *painter, const QRectF &rect ) -{ - const QRectF r = rect; - - QRectF clipRect; - const bool deviceClipping = isClippingNeeded( painter, clipRect ); - - if ( deviceClipping ) - { - if ( !clipRect.intersects( r ) ) - return; - - if ( !clipRect.contains( r ) ) - { - fillRect( painter, r & clipRect, painter->brush() ); - - painter->save(); - painter->setBrush( Qt::NoBrush ); - drawPolyline( painter, QPolygonF( r ) ); - painter->restore(); - - return; - } - } - - painter->drawRect( r ); -} - -//! Wrapper for QPainter::fillRect() -void QwtPainter::fillRect( QPainter *painter, - const QRectF &rect, const QBrush &brush ) -{ - if ( !rect.isValid() ) - return; - - QRectF clipRect; - const bool deviceClipping = isClippingNeeded( painter, clipRect ); - - /* - Performance of Qt4 is horrible for non trivial brushs. Without - clipping expect minutes or hours for repainting large rects - (might result from zooming) - */ - - if ( deviceClipping ) - clipRect &= painter->window(); - else - clipRect = painter->window(); - - if ( painter->hasClipping() ) - clipRect &= painter->clipRegion().boundingRect(); - - QRectF r = rect; - if ( deviceClipping ) - r = r.intersect( clipRect ); - - if ( r.isValid() ) - painter->fillRect( r, brush ); -} - -//! Wrapper for QPainter::drawPie() -void QwtPainter::drawPie( QPainter *painter, const QRectF &rect, - int a, int alen ) -{ - QRectF clipRect; - const bool deviceClipping = isClippingNeeded( painter, clipRect ); - if ( deviceClipping && !clipRect.contains( rect ) ) - return; - - painter->drawPie( rect, a, alen ); -} - -//! Wrapper for QPainter::drawEllipse() -void QwtPainter::drawEllipse( QPainter *painter, const QRectF &rect ) -{ - QRectF clipRect; - const bool deviceClipping = isClippingNeeded( painter, clipRect ); - - if ( deviceClipping && !clipRect.contains( rect ) ) - return; - - painter->drawEllipse( rect ); -} - -//! Wrapper for QPainter::drawText() -void QwtPainter::drawText( QPainter *painter, double x, double y, - const QString &text ) -{ - drawText( painter, QPointF( x, y ), text ); -} - -//! Wrapper for QPainter::drawText() -void QwtPainter::drawText( QPainter *painter, const QPointF &pos, - const QString &text ) -{ - QRectF clipRect; - const bool deviceClipping = isClippingNeeded( painter, clipRect ); - - if ( deviceClipping && !clipRect.contains( pos ) ) - return; - - - painter->save(); - unscaleFont( painter ); - painter->drawText( pos, text ); - painter->restore(); -} - -//! Wrapper for QPainter::drawText() -void QwtPainter::drawText( QPainter *painter, - double x, double y, double w, double h, - int flags, const QString &text ) -{ - drawText( painter, QRectF( x, y, w, h ), flags, text ); -} - -//! Wrapper for QPainter::drawText() -void QwtPainter::drawText( QPainter *painter, const QRectF &rect, - int flags, const QString &text ) -{ - painter->save(); - unscaleFont( painter ); - painter->drawText( rect, flags, text ); - painter->restore(); -} - -#ifndef QT_NO_RICHTEXT - -/*! - Draw a text document into a rectangle - - \param painter Painter - \param rect Traget rectangle - \param flags Alignments/Text flags, see QPainter::drawText() - \param text Text document -*/ -void QwtPainter::drawSimpleRichText( QPainter *painter, const QRectF &rect, - int flags, const QTextDocument &text ) -{ - QTextDocument *txt = text.clone(); - - painter->save(); - - painter->setFont( txt->defaultFont() ); - unscaleFont( painter ); - - txt->setDefaultFont( painter->font() ); - txt->setPageSize( QSizeF( rect.width(), QWIDGETSIZE_MAX ) ); - - QAbstractTextDocumentLayout* layout = txt->documentLayout(); - - const double height = layout->documentSize().height(); - double y = rect.y(); - if ( flags & Qt::AlignBottom ) - y += ( rect.height() - height ); - else if ( flags & Qt::AlignVCenter ) - y += ( rect.height() - height ) / 2; - - QAbstractTextDocumentLayout::PaintContext context; - context.palette.setColor( QPalette::Text, painter->pen().color() ); - - painter->translate( rect.x(), y ); - layout->draw( painter, context ); - - painter->restore(); - delete txt; -} - -#endif // !QT_NO_RICHTEXT - - -//! Wrapper for QPainter::drawLine() -void QwtPainter::drawLine( QPainter *painter, - const QPointF &p1, const QPointF &p2 ) -{ - QRectF clipRect; - const bool deviceClipping = isClippingNeeded( painter, clipRect ); - - if ( deviceClipping && - !( clipRect.contains( p1 ) && clipRect.contains( p2 ) ) ) - { - QPolygonF polygon; - polygon += p1; - polygon += p2; - drawPolyline( painter, polygon ); - return; - } - - painter->drawLine( p1, p2 ); -} - -//! Wrapper for QPainter::drawPolygon() -void QwtPainter::drawPolygon( QPainter *painter, const QPolygonF &polygon ) -{ - QRectF clipRect; - const bool deviceClipping = isClippingNeeded( painter, clipRect ); - - QPolygonF cpa = polygon; - if ( deviceClipping ) - cpa = QwtClipper::clipPolygonF( clipRect, polygon ); - - painter->drawPolygon( cpa ); -} - -//! Wrapper for QPainter::drawPolyline() -void QwtPainter::drawPolyline( QPainter *painter, const QPolygonF &polygon ) -{ - QRectF clipRect; - const bool deviceClipping = isClippingNeeded( painter, clipRect ); - - QPolygonF cpa = polygon; - if ( deviceClipping ) - cpa = QwtClipper::clipPolygonF( clipRect, cpa ); - - ::drawPolyline( painter, - cpa.constData(), cpa.size(), d_polylineSplitting ); -} - -//! Wrapper for QPainter::drawPolyline() -void QwtPainter::drawPolyline( QPainter *painter, - const QPointF *points, int pointCount ) -{ - QRectF clipRect; - const bool deviceClipping = isClippingNeeded( painter, clipRect ); - - if ( deviceClipping ) - { - QPolygonF polygon( pointCount ); - qMemCopy( polygon.data(), points, pointCount * sizeof( QPointF ) ); - - polygon = QwtClipper::clipPolygonF( clipRect, polygon ); - ::drawPolyline( painter, - polygon.constData(), polygon.size(), d_polylineSplitting ); - } - else - ::drawPolyline( painter, points, pointCount, d_polylineSplitting ); -} - -//! Wrapper for QPainter::drawPoint() -void QwtPainter::drawPoint( QPainter *painter, const QPointF &pos ) -{ - QRectF clipRect; - const bool deviceClipping = isClippingNeeded( painter, clipRect ); - - if ( deviceClipping && !clipRect.contains( pos ) ) - return; - - painter->drawPoint( pos ); -} - -//! Wrapper for QPainter::drawImage() -void QwtPainter::drawImage( QPainter *painter, - const QRectF &rect, const QImage &image ) -{ - const QRect alignedRect = rect.toAlignedRect(); - - if ( alignedRect != rect ) - { - const QRectF clipRect = rect.adjusted( 0.0, 0.0, -1.0, -1.0 ); - - painter->save(); - painter->setClipRect( clipRect, Qt::IntersectClip ); - painter->drawImage( alignedRect, image ); - painter->restore(); - } - else - { - painter->drawImage( alignedRect, image ); - } -} - -//! Wrapper for QPainter::drawPixmap() -void QwtPainter::drawPixmap( QPainter *painter, - const QRectF &rect, const QPixmap &pixmap ) -{ - const QRect alignedRect = rect.toAlignedRect(); - - if ( alignedRect != rect ) - { - const QRectF clipRect = rect.adjusted( 0.0, 0.0, -1.0, -1.0 ); - - painter->save(); - painter->setClipRect( clipRect, Qt::IntersectClip ); - painter->drawPixmap( alignedRect, pixmap ); - painter->restore(); - } - else - { - painter->drawPixmap( alignedRect, pixmap ); - } -} - -//! Draw a focus rectangle on a widget using its style. -void QwtPainter::drawFocusRect( QPainter *painter, QWidget *widget ) -{ - drawFocusRect( painter, widget, widget->rect() ); -} - -//! Draw a focus rectangle on a widget using its style. -void QwtPainter::drawFocusRect( QPainter *painter, QWidget *widget, - const QRect &rect ) -{ - QStyleOptionFocusRect opt; - opt.init( widget ); - opt.rect = rect; - opt.state |= QStyle::State_HasFocus; - - widget->style()->drawPrimitive( QStyle::PE_FrameFocusRect, - &opt, painter, widget ); -} - -/*! - Draw a frame with rounded borders - - \param painter Painter - \param rect Frame rectangle - \param xRadius x-radius of the ellipses defining the corners - \param yRadius y-radius of the ellipses defining the corners - \param palette QPalette::WindowText is used for plain borders - QPalette::Dark and QPalette::Light for raised - or sunken borders - \param lineWidth Line width - \param frameStyle bitwise OR´ed value of QFrame::Shape and QFrame::Shadow -*/ - -void QwtPainter::drawRoundedFrame( QPainter *painter, - const QRectF &rect, double xRadius, double yRadius, - const QPalette &palette, int lineWidth, int frameStyle ) -{ - painter->save(); - painter->setRenderHint( QPainter::Antialiasing, true ); - painter->setBrush( Qt::NoBrush ); - - double lw2 = lineWidth * 0.5; - QRectF r = rect.adjusted( lw2, lw2, -lw2, -lw2 ); - - QPainterPath path; - path.addRoundedRect( r, xRadius, yRadius ); - - enum Style - { - Plain, - Sunken, - Raised - }; - - Style style = Plain; - if ( (frameStyle & QFrame::Sunken) == QFrame::Sunken ) - style = Sunken; - else if ( (frameStyle & QFrame::Raised) == QFrame::Raised ) - style = Raised; - - if ( style != Plain && path.elementCount() == 17 ) - { - // move + 4 * ( cubicTo + lineTo ) - QPainterPath pathList[8]; - - for ( int i = 0; i < 4; i++ ) - { - const int j = i * 4 + 1; - - pathList[ 2 * i ].moveTo( - path.elementAt(j - 1).x, path.elementAt( j - 1 ).y - ); - - pathList[ 2 * i ].cubicTo( - path.elementAt(j + 0).x, path.elementAt(j + 0).y, - path.elementAt(j + 1).x, path.elementAt(j + 1).y, - path.elementAt(j + 2).x, path.elementAt(j + 2).y ); - - pathList[ 2 * i + 1 ].moveTo( - path.elementAt(j + 2).x, path.elementAt(j + 2).y - ); - pathList[ 2 * i + 1 ].lineTo( - path.elementAt(j + 3).x, path.elementAt(j + 3).y - ); - } - - QColor c1( palette.color( QPalette::Dark ) ); - QColor c2( palette.color( QPalette::Light ) ); - - if ( style == Raised ) - qSwap( c1, c2 ); - - for ( int i = 0; i < 4; i++ ) - { - QRectF r = pathList[2 * i].controlPointRect(); - - QPen arcPen; - arcPen.setWidth( lineWidth ); - - QPen linePen; - linePen.setWidth( lineWidth ); - - switch( i ) - { - case 0: - { - arcPen.setColor( c1 ); - linePen.setColor( c1 ); - break; - } - case 1: - { - QLinearGradient gradient; - gradient.setStart( r.topLeft() ); - gradient.setFinalStop( r.bottomRight() ); - gradient.setColorAt( 0.0, c1 ); - gradient.setColorAt( 1.0, c2 ); - - arcPen.setBrush( gradient ); - linePen.setColor( c2 ); - break; - } - case 2: - { - arcPen.setColor( c2 ); - linePen.setColor( c2 ); - break; - } - case 3: - { - QLinearGradient gradient; - - gradient.setStart( r.bottomRight() ); - gradient.setFinalStop( r.topLeft() ); - gradient.setColorAt( 0.0, c2 ); - gradient.setColorAt( 1.0, c1 ); - - arcPen.setBrush( gradient ); - linePen.setColor( c1 ); - break; - } - } - - - painter->setPen( arcPen ); - painter->drawPath( pathList[ 2 * i] ); - - painter->setPen( linePen ); - painter->drawPath( pathList[ 2 * i + 1] ); - } - } - else - { - QPen pen( palette.color( QPalette::WindowText ), lineWidth ); - painter->setPen( pen ); - painter->drawPath( path ); - } - - painter->restore(); -} - -/*! - Draw a color bar into a rectangle - - \param painter Painter - \param colorMap Color map - \param interval Value range - \param scaleMap Scale map - \param orientation Orientation - \param rect Traget rectangle -*/ -void QwtPainter::drawColorBar( QPainter *painter, - const QwtColorMap &colorMap, const QwtInterval &interval, - const QwtScaleMap &scaleMap, Qt::Orientation orientation, - const QRectF &rect ) -{ - QVector colorTable; - if ( colorMap.format() == QwtColorMap::Indexed ) - colorTable = colorMap.colorTable( interval ); - - QColor c; - - const QRect devRect = rect.toAlignedRect(); - - /* - We paint to a pixmap first to have something scalable for printing - ( f.e. in a Pdf document ) - */ - - QPixmap pixmap( devRect.size() ); - QPainter pmPainter( &pixmap ); - pmPainter.translate( -devRect.x(), -devRect.y() ); - - if ( orientation == Qt::Horizontal ) - { - QwtScaleMap sMap = scaleMap; - sMap.setPaintInterval( rect.left(), rect.right() ); - - for ( int x = devRect.left(); x <= devRect.right(); x++ ) - { - const double value = sMap.invTransform( x ); - - if ( colorMap.format() == QwtColorMap::RGB ) - c.setRgb( colorMap.rgb( interval, value ) ); - else - c = colorTable[colorMap.colorIndex( interval, value )]; - - pmPainter.setPen( c ); - pmPainter.drawLine( x, devRect.top(), x, devRect.bottom() ); - } - } - else // Vertical - { - QwtScaleMap sMap = scaleMap; - sMap.setPaintInterval( rect.bottom(), rect.top() ); - - for ( int y = devRect.top(); y <= devRect.bottom(); y++ ) - { - const double value = sMap.invTransform( y ); - - if ( colorMap.format() == QwtColorMap::RGB ) - c.setRgb( colorMap.rgb( interval, value ) ); - else - c = colorTable[colorMap.colorIndex( interval, value )]; - - pmPainter.setPen( c ); - pmPainter.drawLine( devRect.left(), y, devRect.right(), y ); - } - } - pmPainter.end(); - - drawPixmap( painter, rect, pixmap ); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_painter.h" +#include "qwt_math.h" +#include "qwt_clipper.h" +#include "qwt_color_map.h" +#include "qwt_scale_map.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +bool QwtPainter::d_polylineSplitting = true; +bool QwtPainter::d_roundingAlignment = true; + +static inline bool isClippingNeeded( const QPainter *painter, QRectF &clipRect ) +{ + bool doClipping = false; + const QPaintEngine *pe = painter->paintEngine(); + if ( pe && pe->type() == QPaintEngine::SVG ) + { + // The SVG paint engine ignores any clipping, + + if ( painter->hasClipping() ) + { + doClipping = true; + clipRect = painter->clipRegion().boundingRect(); + } + } + + return doClipping; +} + +static inline void drawPolyline( QPainter *painter, + const QPointF *points, int pointCount, bool polylineSplitting ) +{ + bool doSplit = false; + if ( polylineSplitting ) + { + const QPaintEngine *pe = painter->paintEngine(); + if ( pe && pe->type() == QPaintEngine::Raster ) + { + /* + The raster paint engine seems to use some algo with O(n*n). + ( Qt 4.3 is better than Qt 4.2, but remains unacceptable) + To work around this problem, we have to split the polygon into + smaller pieces. + */ + doSplit = true; + } + } + + if ( doSplit ) + { + const int splitSize = 20; + for ( int i = 0; i < pointCount; i += splitSize ) + { + const int n = qMin( splitSize + 1, pointCount - i ); + painter->drawPolyline( points + i, n ); + } + } + else + painter->drawPolyline( points, pointCount ); +} + +static inline void unscaleFont( QPainter *painter ) +{ + if ( painter->font().pixelSize() >= 0 ) + return; + + static QSize screenResolution; + if ( !screenResolution.isValid() ) + { + QDesktopWidget *desktop = QApplication::desktop(); + if ( desktop ) + { + screenResolution.setWidth( desktop->logicalDpiX() ); + screenResolution.setHeight( desktop->logicalDpiY() ); + } + } + + const QPaintDevice *pd = painter->device(); + if ( pd->logicalDpiX() != screenResolution.width() || + pd->logicalDpiY() != screenResolution.height() ) + { + QFont pixelFont( painter->font(), QApplication::desktop() ); + pixelFont.setPixelSize( QFontInfo( pixelFont ).pixelSize() ); + + painter->setFont( pixelFont ); + } +} + +/*! + Check if the painter is using a paint engine, that aligns + coordinates to integers. Today these are all paint engines + beside QPaintEngine::Pdf and QPaintEngine::SVG. + + \param painter Painter + \return true, when the paint engine is aligning + + \sa setRoundingAlignment() +*/ +bool QwtPainter::isAligning( QPainter *painter ) +{ + if ( painter && painter->isActive() ) + { + switch ( painter->paintEngine()->type() ) + { + case QPaintEngine::Pdf: + case QPaintEngine::SVG: + return false; + + default:; + } + } + + return true; +} + +/*! + Enable whether coordinates should be rounded, before they are painted + to a paint engine that floors to integer values. For other paint engines + this ( Pdf, SVG ), this flag has no effect. + QwtPainter stores this flag only, the rounding itsself is done in + the painting code ( f.e the plot items ). + + The default setting is true. + + \sa roundingAlignment(), isAligning() +*/ +void QwtPainter::setRoundingAlignment( bool enable ) +{ + d_roundingAlignment = enable; +} + +/*! + \brief En/Disable line splitting for the raster paint engine + + The raster paint engine paints polylines of many points + much faster when they are splitted in smaller chunks. + + \sa polylineSplitting() +*/ +void QwtPainter::setPolylineSplitting( bool enable ) +{ + d_polylineSplitting = enable; +} + +//! Wrapper for QPainter::drawPath() +void QwtPainter::drawPath( QPainter *painter, const QPainterPath &path ) +{ + painter->drawPath( path ); +} + +//! Wrapper for QPainter::drawRect() +void QwtPainter::drawRect( QPainter *painter, double x, double y, double w, double h ) +{ + drawRect( painter, QRectF( x, y, w, h ) ); +} + +//! Wrapper for QPainter::drawRect() +void QwtPainter::drawRect( QPainter *painter, const QRectF &rect ) +{ + const QRectF r = rect; + + QRectF clipRect; + const bool deviceClipping = isClippingNeeded( painter, clipRect ); + + if ( deviceClipping ) + { + if ( !clipRect.intersects( r ) ) + return; + + if ( !clipRect.contains( r ) ) + { + fillRect( painter, r & clipRect, painter->brush() ); + + painter->save(); + painter->setBrush( Qt::NoBrush ); + drawPolyline( painter, QPolygonF( r ) ); + painter->restore(); + + return; + } + } + + painter->drawRect( r ); +} + +//! Wrapper for QPainter::fillRect() +void QwtPainter::fillRect( QPainter *painter, + const QRectF &rect, const QBrush &brush ) +{ + if ( !rect.isValid() ) + return; + + QRectF clipRect; + const bool deviceClipping = isClippingNeeded( painter, clipRect ); + + /* + Performance of Qt4 is horrible for non trivial brushs. Without + clipping expect minutes or hours for repainting large rects + (might result from zooming) + */ + + if ( deviceClipping ) + clipRect &= painter->window(); + else + clipRect = painter->window(); + + if ( painter->hasClipping() ) + clipRect &= painter->clipRegion().boundingRect(); + + QRectF r = rect; + if ( deviceClipping ) + r = r.intersect( clipRect ); + + if ( r.isValid() ) + painter->fillRect( r, brush ); +} + +//! Wrapper for QPainter::drawPie() +void QwtPainter::drawPie( QPainter *painter, const QRectF &rect, + int a, int alen ) +{ + QRectF clipRect; + const bool deviceClipping = isClippingNeeded( painter, clipRect ); + if ( deviceClipping && !clipRect.contains( rect ) ) + return; + + painter->drawPie( rect, a, alen ); +} + +//! Wrapper for QPainter::drawEllipse() +void QwtPainter::drawEllipse( QPainter *painter, const QRectF &rect ) +{ + QRectF clipRect; + const bool deviceClipping = isClippingNeeded( painter, clipRect ); + + if ( deviceClipping && !clipRect.contains( rect ) ) + return; + + painter->drawEllipse( rect ); +} + +//! Wrapper for QPainter::drawText() +void QwtPainter::drawText( QPainter *painter, double x, double y, + const QString &text ) +{ + drawText( painter, QPointF( x, y ), text ); +} + +//! Wrapper for QPainter::drawText() +void QwtPainter::drawText( QPainter *painter, const QPointF &pos, + const QString &text ) +{ + QRectF clipRect; + const bool deviceClipping = isClippingNeeded( painter, clipRect ); + + if ( deviceClipping && !clipRect.contains( pos ) ) + return; + + + painter->save(); + unscaleFont( painter ); + painter->drawText( pos, text ); + painter->restore(); +} + +//! Wrapper for QPainter::drawText() +void QwtPainter::drawText( QPainter *painter, + double x, double y, double w, double h, + int flags, const QString &text ) +{ + drawText( painter, QRectF( x, y, w, h ), flags, text ); +} + +//! Wrapper for QPainter::drawText() +void QwtPainter::drawText( QPainter *painter, const QRectF &rect, + int flags, const QString &text ) +{ + painter->save(); + unscaleFont( painter ); + painter->drawText( rect, flags, text ); + painter->restore(); +} + +#ifndef QT_NO_RICHTEXT + +/*! + Draw a text document into a rectangle + + \param painter Painter + \param rect Traget rectangle + \param flags Alignments/Text flags, see QPainter::drawText() + \param text Text document +*/ +void QwtPainter::drawSimpleRichText( QPainter *painter, const QRectF &rect, + int flags, const QTextDocument &text ) +{ + QTextDocument *txt = text.clone(); + + painter->save(); + + painter->setFont( txt->defaultFont() ); + unscaleFont( painter ); + + txt->setDefaultFont( painter->font() ); + txt->setPageSize( QSizeF( rect.width(), QWIDGETSIZE_MAX ) ); + + QAbstractTextDocumentLayout* layout = txt->documentLayout(); + + const double height = layout->documentSize().height(); + double y = rect.y(); + if ( flags & Qt::AlignBottom ) + y += ( rect.height() - height ); + else if ( flags & Qt::AlignVCenter ) + y += ( rect.height() - height ) / 2; + + QAbstractTextDocumentLayout::PaintContext context; + context.palette.setColor( QPalette::Text, painter->pen().color() ); + + painter->translate( rect.x(), y ); + layout->draw( painter, context ); + + painter->restore(); + delete txt; +} + +#endif // !QT_NO_RICHTEXT + + +//! Wrapper for QPainter::drawLine() +void QwtPainter::drawLine( QPainter *painter, + const QPointF &p1, const QPointF &p2 ) +{ + QRectF clipRect; + const bool deviceClipping = isClippingNeeded( painter, clipRect ); + + if ( deviceClipping && + !( clipRect.contains( p1 ) && clipRect.contains( p2 ) ) ) + { + QPolygonF polygon; + polygon += p1; + polygon += p2; + drawPolyline( painter, polygon ); + return; + } + + painter->drawLine( p1, p2 ); +} + +//! Wrapper for QPainter::drawPolygon() +void QwtPainter::drawPolygon( QPainter *painter, const QPolygonF &polygon ) +{ + QRectF clipRect; + const bool deviceClipping = isClippingNeeded( painter, clipRect ); + + QPolygonF cpa = polygon; + if ( deviceClipping ) + cpa = QwtClipper::clipPolygonF( clipRect, polygon ); + + painter->drawPolygon( cpa ); +} + +//! Wrapper for QPainter::drawPolyline() +void QwtPainter::drawPolyline( QPainter *painter, const QPolygonF &polygon ) +{ + QRectF clipRect; + const bool deviceClipping = isClippingNeeded( painter, clipRect ); + + QPolygonF cpa = polygon; + if ( deviceClipping ) + cpa = QwtClipper::clipPolygonF( clipRect, cpa ); + + ::drawPolyline( painter, + cpa.constData(), cpa.size(), d_polylineSplitting ); +} + +//! Wrapper for QPainter::drawPolyline() +void QwtPainter::drawPolyline( QPainter *painter, + const QPointF *points, int pointCount ) +{ + QRectF clipRect; + const bool deviceClipping = isClippingNeeded( painter, clipRect ); + + if ( deviceClipping ) + { + QPolygonF polygon( pointCount ); + qMemCopy( polygon.data(), points, pointCount * sizeof( QPointF ) ); + + polygon = QwtClipper::clipPolygonF( clipRect, polygon ); + ::drawPolyline( painter, + polygon.constData(), polygon.size(), d_polylineSplitting ); + } + else + ::drawPolyline( painter, points, pointCount, d_polylineSplitting ); +} + +//! Wrapper for QPainter::drawPoint() +void QwtPainter::drawPoint( QPainter *painter, const QPointF &pos ) +{ + QRectF clipRect; + const bool deviceClipping = isClippingNeeded( painter, clipRect ); + + if ( deviceClipping && !clipRect.contains( pos ) ) + return; + + painter->drawPoint( pos ); +} + +//! Wrapper for QPainter::drawImage() +void QwtPainter::drawImage( QPainter *painter, + const QRectF &rect, const QImage &image ) +{ + const QRect alignedRect = rect.toAlignedRect(); + + if ( alignedRect != rect ) + { + const QRectF clipRect = rect.adjusted( 0.0, 0.0, -1.0, -1.0 ); + + painter->save(); + painter->setClipRect( clipRect, Qt::IntersectClip ); + painter->drawImage( alignedRect, image ); + painter->restore(); + } + else + { + painter->drawImage( alignedRect, image ); + } +} + +//! Wrapper for QPainter::drawPixmap() +void QwtPainter::drawPixmap( QPainter *painter, + const QRectF &rect, const QPixmap &pixmap ) +{ + const QRect alignedRect = rect.toAlignedRect(); + + if ( alignedRect != rect ) + { + const QRectF clipRect = rect.adjusted( 0.0, 0.0, -1.0, -1.0 ); + + painter->save(); + painter->setClipRect( clipRect, Qt::IntersectClip ); + painter->drawPixmap( alignedRect, pixmap ); + painter->restore(); + } + else + { + painter->drawPixmap( alignedRect, pixmap ); + } +} + +//! Draw a focus rectangle on a widget using its style. +void QwtPainter::drawFocusRect( QPainter *painter, QWidget *widget ) +{ + drawFocusRect( painter, widget, widget->rect() ); +} + +//! Draw a focus rectangle on a widget using its style. +void QwtPainter::drawFocusRect( QPainter *painter, QWidget *widget, + const QRect &rect ) +{ + QStyleOptionFocusRect opt; + opt.init( widget ); + opt.rect = rect; + opt.state |= QStyle::State_HasFocus; + + widget->style()->drawPrimitive( QStyle::PE_FrameFocusRect, + &opt, painter, widget ); +} + +/*! + Draw a frame with rounded borders + + \param painter Painter + \param rect Frame rectangle + \param xRadius x-radius of the ellipses defining the corners + \param yRadius y-radius of the ellipses defining the corners + \param palette QPalette::WindowText is used for plain borders + QPalette::Dark and QPalette::Light for raised + or sunken borders + \param lineWidth Line width + \param frameStyle bitwise OR´ed value of QFrame::Shape and QFrame::Shadow +*/ + +void QwtPainter::drawRoundedFrame( QPainter *painter, + const QRectF &rect, double xRadius, double yRadius, + const QPalette &palette, int lineWidth, int frameStyle ) +{ + painter->save(); + painter->setRenderHint( QPainter::Antialiasing, true ); + painter->setBrush( Qt::NoBrush ); + + double lw2 = lineWidth * 0.5; + QRectF r = rect.adjusted( lw2, lw2, -lw2, -lw2 ); + + QPainterPath path; + path.addRoundedRect( r, xRadius, yRadius ); + + enum Style + { + Plain, + Sunken, + Raised + }; + + Style style = Plain; + if ( (frameStyle & QFrame::Sunken) == QFrame::Sunken ) + style = Sunken; + else if ( (frameStyle & QFrame::Raised) == QFrame::Raised ) + style = Raised; + + if ( style != Plain && path.elementCount() == 17 ) + { + // move + 4 * ( cubicTo + lineTo ) + QPainterPath pathList[8]; + + for ( int i = 0; i < 4; i++ ) + { + const int j = i * 4 + 1; + + pathList[ 2 * i ].moveTo( + path.elementAt(j - 1).x, path.elementAt( j - 1 ).y + ); + + pathList[ 2 * i ].cubicTo( + path.elementAt(j + 0).x, path.elementAt(j + 0).y, + path.elementAt(j + 1).x, path.elementAt(j + 1).y, + path.elementAt(j + 2).x, path.elementAt(j + 2).y ); + + pathList[ 2 * i + 1 ].moveTo( + path.elementAt(j + 2).x, path.elementAt(j + 2).y + ); + pathList[ 2 * i + 1 ].lineTo( + path.elementAt(j + 3).x, path.elementAt(j + 3).y + ); + } + + QColor c1( palette.color( QPalette::Dark ) ); + QColor c2( palette.color( QPalette::Light ) ); + + if ( style == Raised ) + qSwap( c1, c2 ); + + for ( int i = 0; i < 4; i++ ) + { + QRectF r = pathList[2 * i].controlPointRect(); + + QPen arcPen; + arcPen.setWidth( lineWidth ); + + QPen linePen; + linePen.setWidth( lineWidth ); + + switch( i ) + { + case 0: + { + arcPen.setColor( c1 ); + linePen.setColor( c1 ); + break; + } + case 1: + { + QLinearGradient gradient; + gradient.setStart( r.topLeft() ); + gradient.setFinalStop( r.bottomRight() ); + gradient.setColorAt( 0.0, c1 ); + gradient.setColorAt( 1.0, c2 ); + + arcPen.setBrush( gradient ); + linePen.setColor( c2 ); + break; + } + case 2: + { + arcPen.setColor( c2 ); + linePen.setColor( c2 ); + break; + } + case 3: + { + QLinearGradient gradient; + + gradient.setStart( r.bottomRight() ); + gradient.setFinalStop( r.topLeft() ); + gradient.setColorAt( 0.0, c2 ); + gradient.setColorAt( 1.0, c1 ); + + arcPen.setBrush( gradient ); + linePen.setColor( c1 ); + break; + } + } + + + painter->setPen( arcPen ); + painter->drawPath( pathList[ 2 * i] ); + + painter->setPen( linePen ); + painter->drawPath( pathList[ 2 * i + 1] ); + } + } + else + { + QPen pen( palette.color( QPalette::WindowText ), lineWidth ); + painter->setPen( pen ); + painter->drawPath( path ); + } + + painter->restore(); +} + +/*! + Draw a color bar into a rectangle + + \param painter Painter + \param colorMap Color map + \param interval Value range + \param scaleMap Scale map + \param orientation Orientation + \param rect Traget rectangle +*/ +void QwtPainter::drawColorBar( QPainter *painter, + const QwtColorMap &colorMap, const QwtInterval &interval, + const QwtScaleMap &scaleMap, Qt::Orientation orientation, + const QRectF &rect ) +{ + QVector colorTable; + if ( colorMap.format() == QwtColorMap::Indexed ) + colorTable = colorMap.colorTable( interval ); + + QColor c; + + const QRect devRect = rect.toAlignedRect(); + + /* + We paint to a pixmap first to have something scalable for printing + ( f.e. in a Pdf document ) + */ + + QPixmap pixmap( devRect.size() ); + QPainter pmPainter( &pixmap ); + pmPainter.translate( -devRect.x(), -devRect.y() ); + + if ( orientation == Qt::Horizontal ) + { + QwtScaleMap sMap = scaleMap; + sMap.setPaintInterval( rect.left(), rect.right() ); + + for ( int x = devRect.left(); x <= devRect.right(); x++ ) + { + const double value = sMap.invTransform( x ); + + if ( colorMap.format() == QwtColorMap::RGB ) + c.setRgb( colorMap.rgb( interval, value ) ); + else + c = colorTable[colorMap.colorIndex( interval, value )]; + + pmPainter.setPen( c ); + pmPainter.drawLine( x, devRect.top(), x, devRect.bottom() ); + } + } + else // Vertical + { + QwtScaleMap sMap = scaleMap; + sMap.setPaintInterval( rect.bottom(), rect.top() ); + + for ( int y = devRect.top(); y <= devRect.bottom(); y++ ) + { + const double value = sMap.invTransform( y ); + + if ( colorMap.format() == QwtColorMap::RGB ) + c.setRgb( colorMap.rgb( interval, value ) ); + else + c = colorTable[colorMap.colorIndex( interval, value )]; + + pmPainter.setPen( c ); + pmPainter.drawLine( devRect.left(), y, devRect.right(), y ); + } + } + pmPainter.end(); + + drawPixmap( painter, rect, pixmap ); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_painter.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_painter.h index 4393fd410..22d3df92f 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_painter.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_painter.h @@ -1,149 +1,149 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PAINTER_H -#define QWT_PAINTER_H - -#include "qwt_global.h" - -#include -#include -#include -#include - -class QPainter; -class QBrush; -class QColor; -class QWidget; -class QPolygonF; -class QRectF; -class QImage; -class QPixmap; -class QwtScaleMap; -class QwtColorMap; -class QwtInterval; - -class QPalette; -class QTextDocument; -class QPainterPath; - -/*! - \brief A collection of QPainter workarounds -*/ -class QWT_EXPORT QwtPainter -{ -public: - static void setPolylineSplitting( bool ); - static bool polylineSplitting(); - - static void setRoundingAlignment( bool ); - static bool roundingAlignment(); - static bool roundingAlignment(QPainter *); - - static void drawText( QPainter *, double x, double y, const QString & ); - static void drawText( QPainter *, const QPointF &, const QString & ); - static void drawText( QPainter *, double x, double y, double w, double h, - int flags, const QString & ); - static void drawText( QPainter *, const QRectF &, - int flags, const QString & ); - -#ifndef QT_NO_RICHTEXT - static void drawSimpleRichText( QPainter *, const QRectF &, - int flags, const QTextDocument & ); -#endif - - static void drawRect( QPainter *, double x, double y, double w, double h ); - static void drawRect( QPainter *, const QRectF &rect ); - static void fillRect( QPainter *, const QRectF &, const QBrush & ); - - static void drawEllipse( QPainter *, const QRectF & ); - static void drawPie( QPainter *, const QRectF & r, int a, int alen ); - - static void drawLine( QPainter *, double x1, double y1, double x2, double y2 ); - static void drawLine( QPainter *, const QPointF &p1, const QPointF &p2 ); - static void drawLine( QPainter *, const QLineF & ); - - static void drawPolygon( QPainter *, const QPolygonF &pa ); - static void drawPolyline( QPainter *, const QPolygonF &pa ); - static void drawPolyline( QPainter *, const QPointF *, int pointCount ); - - static void drawPoint( QPainter *, double x, double y ); - static void drawPoint( QPainter *, const QPointF & ); - - static void drawPath( QPainter *, const QPainterPath & ); - static void drawImage( QPainter *, const QRectF &, const QImage & ); - static void drawPixmap( QPainter *, const QRectF &, const QPixmap & ); - - static void drawRoundedFrame( QPainter *, - const QRectF &, double xRadius, double yRadius, - const QPalette &, int lineWidth, int frameStyle ); - - static void drawFocusRect( QPainter *, QWidget * ); - static void drawFocusRect( QPainter *, QWidget *, const QRect & ); - - static void drawColorBar( QPainter *painter, - const QwtColorMap &, const QwtInterval &, - const QwtScaleMap &, Qt::Orientation, const QRectF & ); - - static bool isAligning( QPainter *painter ); - -private: - static bool d_polylineSplitting; - static bool d_roundingAlignment; -}; - -//! Wrapper for QPainter::drawPoint() -inline void QwtPainter::drawPoint( QPainter *painter, double x, double y ) -{ - QwtPainter::drawPoint( painter, QPointF( x, y ) ); -} - -//! Wrapper for QPainter::drawLine() -inline void QwtPainter::drawLine( QPainter *painter, - double x1, double y1, double x2, double y2 ) -{ - QwtPainter::drawLine( painter, QPointF( x1, y1 ), QPointF( x2, y2 ) ); -} - -//! Wrapper for QPainter::drawLine() -inline void QwtPainter::drawLine( QPainter *painter, const QLineF &line ) -{ - QwtPainter::drawLine( painter, line.p1(), line.p2() ); -} - -/*! - Returns whether line splitting for the raster paint engine is enabled. - \sa setPolylineSplitting() -*/ -inline bool QwtPainter::polylineSplitting() -{ - return d_polylineSplitting; -} - -/*! - Returns whether coordinates should be rounded, before they are painted - to a paint engine that floors to integer values. For other paint engines - this ( Pdf, SVG ), this flag has no effect. - - \sa setRoundingAlignment(), isAligning() -*/ -inline bool QwtPainter::roundingAlignment() -{ - return d_roundingAlignment; -} - -/*! - \return roundingAlignment() && isAligning(painter); - \param painter Painter -*/ -inline bool QwtPainter::roundingAlignment(QPainter *painter) -{ - return d_roundingAlignment && isAligning(painter); -} -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PAINTER_H +#define QWT_PAINTER_H + +#include "qwt_global.h" + +#include +#include +#include +#include + +class QPainter; +class QBrush; +class QColor; +class QWidget; +class QPolygonF; +class QRectF; +class QImage; +class QPixmap; +class QwtScaleMap; +class QwtColorMap; +class QwtInterval; + +class QPalette; +class QTextDocument; +class QPainterPath; + +/*! + \brief A collection of QPainter workarounds +*/ +class QWT_EXPORT QwtPainter +{ +public: + static void setPolylineSplitting( bool ); + static bool polylineSplitting(); + + static void setRoundingAlignment( bool ); + static bool roundingAlignment(); + static bool roundingAlignment(QPainter *); + + static void drawText( QPainter *, double x, double y, const QString & ); + static void drawText( QPainter *, const QPointF &, const QString & ); + static void drawText( QPainter *, double x, double y, double w, double h, + int flags, const QString & ); + static void drawText( QPainter *, const QRectF &, + int flags, const QString & ); + +#ifndef QT_NO_RICHTEXT + static void drawSimpleRichText( QPainter *, const QRectF &, + int flags, const QTextDocument & ); +#endif + + static void drawRect( QPainter *, double x, double y, double w, double h ); + static void drawRect( QPainter *, const QRectF &rect ); + static void fillRect( QPainter *, const QRectF &, const QBrush & ); + + static void drawEllipse( QPainter *, const QRectF & ); + static void drawPie( QPainter *, const QRectF & r, int a, int alen ); + + static void drawLine( QPainter *, double x1, double y1, double x2, double y2 ); + static void drawLine( QPainter *, const QPointF &p1, const QPointF &p2 ); + static void drawLine( QPainter *, const QLineF & ); + + static void drawPolygon( QPainter *, const QPolygonF &pa ); + static void drawPolyline( QPainter *, const QPolygonF &pa ); + static void drawPolyline( QPainter *, const QPointF *, int pointCount ); + + static void drawPoint( QPainter *, double x, double y ); + static void drawPoint( QPainter *, const QPointF & ); + + static void drawPath( QPainter *, const QPainterPath & ); + static void drawImage( QPainter *, const QRectF &, const QImage & ); + static void drawPixmap( QPainter *, const QRectF &, const QPixmap & ); + + static void drawRoundedFrame( QPainter *, + const QRectF &, double xRadius, double yRadius, + const QPalette &, int lineWidth, int frameStyle ); + + static void drawFocusRect( QPainter *, QWidget * ); + static void drawFocusRect( QPainter *, QWidget *, const QRect & ); + + static void drawColorBar( QPainter *painter, + const QwtColorMap &, const QwtInterval &, + const QwtScaleMap &, Qt::Orientation, const QRectF & ); + + static bool isAligning( QPainter *painter ); + +private: + static bool d_polylineSplitting; + static bool d_roundingAlignment; +}; + +//! Wrapper for QPainter::drawPoint() +inline void QwtPainter::drawPoint( QPainter *painter, double x, double y ) +{ + QwtPainter::drawPoint( painter, QPointF( x, y ) ); +} + +//! Wrapper for QPainter::drawLine() +inline void QwtPainter::drawLine( QPainter *painter, + double x1, double y1, double x2, double y2 ) +{ + QwtPainter::drawLine( painter, QPointF( x1, y1 ), QPointF( x2, y2 ) ); +} + +//! Wrapper for QPainter::drawLine() +inline void QwtPainter::drawLine( QPainter *painter, const QLineF &line ) +{ + QwtPainter::drawLine( painter, line.p1(), line.p2() ); +} + +/*! + Returns whether line splitting for the raster paint engine is enabled. + \sa setPolylineSplitting() +*/ +inline bool QwtPainter::polylineSplitting() +{ + return d_polylineSplitting; +} + +/*! + Returns whether coordinates should be rounded, before they are painted + to a paint engine that floors to integer values. For other paint engines + this ( Pdf, SVG ), this flag has no effect. + + \sa setRoundingAlignment(), isAligning() +*/ +inline bool QwtPainter::roundingAlignment() +{ + return d_roundingAlignment; +} + +/*! + \return roundingAlignment() && isAligning(painter); + \param painter Painter +*/ +inline bool QwtPainter::roundingAlignment(QPainter *painter) +{ + return d_roundingAlignment && isAligning(painter); +} +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_panner.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_panner.cpp index ff0b6a735..32768060d 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_panner.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_panner.cpp @@ -1,534 +1,534 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_panner.h" -#include "qwt_picker.h" -#include -#include -#include -#include -#include - -static QVector qwtActivePickers( QWidget *w ) -{ - QVector pickers; - - QObjectList children = w->children(); - for ( int i = 0; i < children.size(); i++ ) - { - QObject *obj = children[i]; - if ( obj->inherits( "QwtPicker" ) ) - { - QwtPicker *picker = ( QwtPicker * )obj; - if ( picker->isEnabled() ) - pickers += picker; - } - } - - return pickers; -} - -class QwtPanner::PrivateData -{ -public: - PrivateData(): - button( Qt::LeftButton ), - buttonState( Qt::NoButton ), - abortKey( Qt::Key_Escape ), - abortKeyState( Qt::NoButton ), -#ifndef QT_NO_CURSOR - cursor( NULL ), - restoreCursor( NULL ), - hasCursor( false ), -#endif - isEnabled( false ) - { - orientations = Qt::Vertical | Qt::Horizontal; - } - - ~PrivateData() - { -#ifndef QT_NO_CURSOR - delete cursor; - delete restoreCursor; -#endif - } - - int button; - int buttonState; - int abortKey; - int abortKeyState; - - QPoint initialPos; - QPoint pos; - - QPixmap pixmap; - QBitmap contentsMask; - -#ifndef QT_NO_CURSOR - QCursor *cursor; - QCursor *restoreCursor; - bool hasCursor; -#endif - bool isEnabled; - Qt::Orientations orientations; -}; - -/*! - Creates an panner that is enabled for the left mouse button. - - \param parent Parent widget to be panned -*/ -QwtPanner::QwtPanner( QWidget *parent ): - QWidget( parent ) -{ - d_data = new PrivateData(); - - setAttribute( Qt::WA_TransparentForMouseEvents ); - setAttribute( Qt::WA_NoSystemBackground ); - setFocusPolicy( Qt::NoFocus ); - hide(); - - setEnabled( true ); -} - -//! Destructor -QwtPanner::~QwtPanner() -{ - delete d_data; -} - -/*! - Change the mouse button - The defaults are Qt::LeftButton and Qt::NoButton -*/ -void QwtPanner::setMouseButton( int button, int buttonState ) -{ - d_data->button = button; - d_data->buttonState = buttonState; -} - -//! Get the mouse button -void QwtPanner::getMouseButton( int &button, int &buttonState ) const -{ - button = d_data->button; - buttonState = d_data->buttonState; -} - -/*! - Change the abort key - The defaults are Qt::Key_Escape and Qt::NoButton - - \param key Key ( See Qt::Keycode ) - \param state State -*/ -void QwtPanner::setAbortKey( int key, int state ) -{ - d_data->abortKey = key; - d_data->abortKeyState = state; -} - -//! Get the abort key -void QwtPanner::getAbortKey( int &key, int &state ) const -{ - key = d_data->abortKey; - state = d_data->abortKeyState; -} - -/*! - Change the cursor, that is active while panning - The default is the cursor of the parent widget. - - \param cursor New cursor - - \sa setCursor() -*/ -#ifndef QT_NO_CURSOR -void QwtPanner::setCursor( const QCursor &cursor ) -{ - d_data->cursor = new QCursor( cursor ); -} -#endif - -/*! - \return Cursor that is active while panning - \sa setCursor() -*/ -#ifndef QT_NO_CURSOR -const QCursor QwtPanner::cursor() const -{ - if ( d_data->cursor ) - return *d_data->cursor; - - if ( parentWidget() ) - return parentWidget()->cursor(); - - return QCursor(); -} -#endif - -/*! - \brief En/disable the panner - - When enabled is true an event filter is installed for - the observed widget, otherwise the event filter is removed. - - \param on true or false - \sa isEnabled(), eventFilter() -*/ -void QwtPanner::setEnabled( bool on ) -{ - if ( d_data->isEnabled != on ) - { - d_data->isEnabled = on; - - QWidget *w = parentWidget(); - if ( w ) - { - if ( d_data->isEnabled ) - { - w->installEventFilter( this ); - } - else - { - w->removeEventFilter( this ); - hide(); - } - } - } -} - -/*! - Set the orientations, where panning is enabled - The default value is in both directions: Qt::Horizontal | Qt::Vertical - - /param o Orientation -*/ -void QwtPanner::setOrientations( Qt::Orientations o ) -{ - d_data->orientations = o; -} - -//! Return the orientation, where paning is enabled -Qt::Orientations QwtPanner::orientations() const -{ - return d_data->orientations; -} - -/*! - Return true if a orientatio is enabled - \sa orientations(), setOrientations() -*/ -bool QwtPanner::isOrientationEnabled( Qt::Orientation o ) const -{ - return d_data->orientations & o; -} - -/*! - \return true when enabled, false otherwise - \sa setEnabled, eventFilter() -*/ -bool QwtPanner::isEnabled() const -{ - return d_data->isEnabled; -} - -/*! - \brief Paint event - - Repaint the grabbed pixmap on its current position and - fill the empty spaces by the background of the parent widget. - - \param pe Paint event -*/ -void QwtPanner::paintEvent( QPaintEvent *pe ) -{ - int dx = d_data->pos.x() - d_data->initialPos.x(); - int dy = d_data->pos.y() - d_data->initialPos.y(); - - QRect r( 0, 0, d_data->pixmap.width(), d_data->pixmap.height() ); - r.moveCenter( QPoint( r.center().x() + dx, r.center().y() + dy ) ); - - QPixmap pm( size() ); - pm.fill( parentWidget(), 0, 0 ); - - QPainter painter( &pm ); - - if ( !d_data->contentsMask.isNull() ) - { - QPixmap masked = d_data->pixmap; - masked.setMask( d_data->contentsMask ); - painter.drawPixmap( r, masked ); - } - else - { - painter.drawPixmap( r, d_data->pixmap ); - } - - painter.end(); - - if ( !d_data->contentsMask.isNull() ) - pm.setMask( d_data->contentsMask ); - - painter.begin( this ); - painter.setClipRegion( pe->region() ); - painter.drawPixmap( 0, 0, pm ); -} - -/*! - \brief Calculate a mask for the contents of the panned widget - - Sometimes only parts of the contents of a widget should be - panned. F.e. for a widget with a styled background with rounded borders - only the area inside of the border should be panned. - - \return An empty bitmap, indicating no mask -*/ -QBitmap QwtPanner::contentsMask() const -{ - return QBitmap(); -} - -/*! - Grab the widget into a pixmap. -*/ -QPixmap QwtPanner::grab() const -{ - return QPixmap::grabWidget( parentWidget() ); -} - -/*! - \brief Event filter - - When isEnabled() the mouse events of the observed widget are filtered. - - \param object Object to be filtered - \param event Event - - \sa widgetMousePressEvent(), widgetMouseReleaseEvent(), - widgetMouseMoveEvent() -*/ -bool QwtPanner::eventFilter( QObject *object, QEvent *event ) -{ - if ( object == NULL || object != parentWidget() ) - return false; - - switch ( event->type() ) - { - case QEvent::MouseButtonPress: - { - widgetMousePressEvent( ( QMouseEvent * )event ); - break; - } - case QEvent::MouseMove: - { - widgetMouseMoveEvent( ( QMouseEvent * )event ); - break; - } - case QEvent::MouseButtonRelease: - { - widgetMouseReleaseEvent( ( QMouseEvent * )event ); - break; - } - case QEvent::KeyPress: - { - widgetKeyPressEvent( ( QKeyEvent * )event ); - break; - } - case QEvent::KeyRelease: - { - widgetKeyReleaseEvent( ( QKeyEvent * )event ); - break; - } - case QEvent::Paint: - { - if ( isVisible() ) - return true; - break; - } - default:; - } - - return false; -} - -/*! - Handle a mouse press event for the observed widget. - - \param mouseEvent Mouse event - \sa eventFilter(), widgetMouseReleaseEvent(), - widgetMouseMoveEvent(), -*/ -void QwtPanner::widgetMousePressEvent( QMouseEvent *mouseEvent ) -{ - if ( mouseEvent->button() != d_data->button ) - return; - - QWidget *w = parentWidget(); - if ( w == NULL ) - return; - - if ( ( mouseEvent->modifiers() & Qt::KeyboardModifierMask ) != - ( int )( d_data->buttonState & Qt::KeyboardModifierMask ) ) - { - return; - } - -#ifndef QT_NO_CURSOR - showCursor( true ); -#endif - - d_data->initialPos = d_data->pos = mouseEvent->pos(); - - setGeometry( parentWidget()->rect() ); - - // We don't want to grab the picker ! - QVector pickers = qwtActivePickers( parentWidget() ); - for ( int i = 0; i < ( int )pickers.size(); i++ ) - pickers[i]->setEnabled( false ); - - d_data->pixmap = grab(); - d_data->contentsMask = contentsMask(); - - for ( int i = 0; i < ( int )pickers.size(); i++ ) - pickers[i]->setEnabled( true ); - - show(); -} - -/*! - Handle a mouse move event for the observed widget. - - \param mouseEvent Mouse event - \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent() -*/ -void QwtPanner::widgetMouseMoveEvent( QMouseEvent *mouseEvent ) -{ - if ( !isVisible() ) - return; - - QPoint pos = mouseEvent->pos(); - if ( !isOrientationEnabled( Qt::Horizontal ) ) - pos.setX( d_data->initialPos.x() ); - if ( !isOrientationEnabled( Qt::Vertical ) ) - pos.setY( d_data->initialPos.y() ); - - if ( pos != d_data->pos && rect().contains( pos ) ) - { - d_data->pos = pos; - update(); - - Q_EMIT moved( d_data->pos.x() - d_data->initialPos.x(), - d_data->pos.y() - d_data->initialPos.y() ); - } -} - -/*! - Handle a mouse release event for the observed widget. - - \param mouseEvent Mouse event - \sa eventFilter(), widgetMousePressEvent(), - widgetMouseMoveEvent(), -*/ -void QwtPanner::widgetMouseReleaseEvent( QMouseEvent *mouseEvent ) -{ - if ( isVisible() ) - { - hide(); -#ifndef QT_NO_CURSOR - showCursor( false ); -#endif - - QPoint pos = mouseEvent->pos(); - if ( !isOrientationEnabled( Qt::Horizontal ) ) - pos.setX( d_data->initialPos.x() ); - if ( !isOrientationEnabled( Qt::Vertical ) ) - pos.setY( d_data->initialPos.y() ); - - d_data->pixmap = QPixmap(); - d_data->contentsMask = QBitmap(); - d_data->pos = pos; - - if ( d_data->pos != d_data->initialPos ) - { - Q_EMIT panned( d_data->pos.x() - d_data->initialPos.x(), - d_data->pos.y() - d_data->initialPos.y() ); - } - } -} - -/*! - Handle a key press event for the observed widget. - - \param keyEvent Key event - \sa eventFilter(), widgetKeyReleaseEvent() -*/ -void QwtPanner::widgetKeyPressEvent( QKeyEvent *keyEvent ) -{ - if ( keyEvent->key() == d_data->abortKey ) - { - const bool matched = - ( keyEvent->modifiers() & Qt::KeyboardModifierMask ) == - ( int )( d_data->abortKeyState & Qt::KeyboardModifierMask ); - if ( matched ) - { - hide(); -#ifndef QT_NO_CURSOR - showCursor( false ); -#endif - d_data->pixmap = QPixmap(); - } - } -} - -/*! - Handle a key release event for the observed widget. - - \param keyEvent Key event - \sa eventFilter(), widgetKeyReleaseEvent() -*/ -void QwtPanner::widgetKeyReleaseEvent( QKeyEvent *keyEvent ) -{ - Q_UNUSED( keyEvent ); -} - -#ifndef QT_NO_CURSOR -void QwtPanner::showCursor( bool on ) -{ - if ( on == d_data->hasCursor ) - return; - - QWidget *w = parentWidget(); - if ( w == NULL || d_data->cursor == NULL ) - return; - - d_data->hasCursor = on; - - if ( on ) - { - if ( w->testAttribute( Qt::WA_SetCursor ) ) - { - delete d_data->restoreCursor; - d_data->restoreCursor = new QCursor( w->cursor() ); - } - w->setCursor( *d_data->cursor ); - } - else - { - if ( d_data->restoreCursor ) - { - w->setCursor( *d_data->restoreCursor ); - delete d_data->restoreCursor; - d_data->restoreCursor = NULL; - } - else - w->unsetCursor(); - } -} -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_panner.h" +#include "qwt_picker.h" +#include +#include +#include +#include +#include + +static QVector qwtActivePickers( QWidget *w ) +{ + QVector pickers; + + QObjectList children = w->children(); + for ( int i = 0; i < children.size(); i++ ) + { + QObject *obj = children[i]; + if ( obj->inherits( "QwtPicker" ) ) + { + QwtPicker *picker = ( QwtPicker * )obj; + if ( picker->isEnabled() ) + pickers += picker; + } + } + + return pickers; +} + +class QwtPanner::PrivateData +{ +public: + PrivateData(): + button( Qt::LeftButton ), + buttonState( Qt::NoButton ), + abortKey( Qt::Key_Escape ), + abortKeyState( Qt::NoButton ), +#ifndef QT_NO_CURSOR + cursor( NULL ), + restoreCursor( NULL ), + hasCursor( false ), +#endif + isEnabled( false ) + { + orientations = Qt::Vertical | Qt::Horizontal; + } + + ~PrivateData() + { +#ifndef QT_NO_CURSOR + delete cursor; + delete restoreCursor; +#endif + } + + int button; + int buttonState; + int abortKey; + int abortKeyState; + + QPoint initialPos; + QPoint pos; + + QPixmap pixmap; + QBitmap contentsMask; + +#ifndef QT_NO_CURSOR + QCursor *cursor; + QCursor *restoreCursor; + bool hasCursor; +#endif + bool isEnabled; + Qt::Orientations orientations; +}; + +/*! + Creates an panner that is enabled for the left mouse button. + + \param parent Parent widget to be panned +*/ +QwtPanner::QwtPanner( QWidget *parent ): + QWidget( parent ) +{ + d_data = new PrivateData(); + + setAttribute( Qt::WA_TransparentForMouseEvents ); + setAttribute( Qt::WA_NoSystemBackground ); + setFocusPolicy( Qt::NoFocus ); + hide(); + + setEnabled( true ); +} + +//! Destructor +QwtPanner::~QwtPanner() +{ + delete d_data; +} + +/*! + Change the mouse button + The defaults are Qt::LeftButton and Qt::NoButton +*/ +void QwtPanner::setMouseButton( int button, int buttonState ) +{ + d_data->button = button; + d_data->buttonState = buttonState; +} + +//! Get the mouse button +void QwtPanner::getMouseButton( int &button, int &buttonState ) const +{ + button = d_data->button; + buttonState = d_data->buttonState; +} + +/*! + Change the abort key + The defaults are Qt::Key_Escape and Qt::NoButton + + \param key Key ( See Qt::Keycode ) + \param state State +*/ +void QwtPanner::setAbortKey( int key, int state ) +{ + d_data->abortKey = key; + d_data->abortKeyState = state; +} + +//! Get the abort key +void QwtPanner::getAbortKey( int &key, int &state ) const +{ + key = d_data->abortKey; + state = d_data->abortKeyState; +} + +/*! + Change the cursor, that is active while panning + The default is the cursor of the parent widget. + + \param cursor New cursor + + \sa setCursor() +*/ +#ifndef QT_NO_CURSOR +void QwtPanner::setCursor( const QCursor &cursor ) +{ + d_data->cursor = new QCursor( cursor ); +} +#endif + +/*! + \return Cursor that is active while panning + \sa setCursor() +*/ +#ifndef QT_NO_CURSOR +const QCursor QwtPanner::cursor() const +{ + if ( d_data->cursor ) + return *d_data->cursor; + + if ( parentWidget() ) + return parentWidget()->cursor(); + + return QCursor(); +} +#endif + +/*! + \brief En/disable the panner + + When enabled is true an event filter is installed for + the observed widget, otherwise the event filter is removed. + + \param on true or false + \sa isEnabled(), eventFilter() +*/ +void QwtPanner::setEnabled( bool on ) +{ + if ( d_data->isEnabled != on ) + { + d_data->isEnabled = on; + + QWidget *w = parentWidget(); + if ( w ) + { + if ( d_data->isEnabled ) + { + w->installEventFilter( this ); + } + else + { + w->removeEventFilter( this ); + hide(); + } + } + } +} + +/*! + Set the orientations, where panning is enabled + The default value is in both directions: Qt::Horizontal | Qt::Vertical + + /param o Orientation +*/ +void QwtPanner::setOrientations( Qt::Orientations o ) +{ + d_data->orientations = o; +} + +//! Return the orientation, where paning is enabled +Qt::Orientations QwtPanner::orientations() const +{ + return d_data->orientations; +} + +/*! + Return true if a orientatio is enabled + \sa orientations(), setOrientations() +*/ +bool QwtPanner::isOrientationEnabled( Qt::Orientation o ) const +{ + return d_data->orientations & o; +} + +/*! + \return true when enabled, false otherwise + \sa setEnabled, eventFilter() +*/ +bool QwtPanner::isEnabled() const +{ + return d_data->isEnabled; +} + +/*! + \brief Paint event + + Repaint the grabbed pixmap on its current position and + fill the empty spaces by the background of the parent widget. + + \param pe Paint event +*/ +void QwtPanner::paintEvent( QPaintEvent *pe ) +{ + int dx = d_data->pos.x() - d_data->initialPos.x(); + int dy = d_data->pos.y() - d_data->initialPos.y(); + + QRect r( 0, 0, d_data->pixmap.width(), d_data->pixmap.height() ); + r.moveCenter( QPoint( r.center().x() + dx, r.center().y() + dy ) ); + + QPixmap pm( size() ); + pm.fill( parentWidget(), 0, 0 ); + + QPainter painter( &pm ); + + if ( !d_data->contentsMask.isNull() ) + { + QPixmap masked = d_data->pixmap; + masked.setMask( d_data->contentsMask ); + painter.drawPixmap( r, masked ); + } + else + { + painter.drawPixmap( r, d_data->pixmap ); + } + + painter.end(); + + if ( !d_data->contentsMask.isNull() ) + pm.setMask( d_data->contentsMask ); + + painter.begin( this ); + painter.setClipRegion( pe->region() ); + painter.drawPixmap( 0, 0, pm ); +} + +/*! + \brief Calculate a mask for the contents of the panned widget + + Sometimes only parts of the contents of a widget should be + panned. F.e. for a widget with a styled background with rounded borders + only the area inside of the border should be panned. + + \return An empty bitmap, indicating no mask +*/ +QBitmap QwtPanner::contentsMask() const +{ + return QBitmap(); +} + +/*! + Grab the widget into a pixmap. +*/ +QPixmap QwtPanner::grab() const +{ + return QPixmap::grabWidget( parentWidget() ); +} + +/*! + \brief Event filter + + When isEnabled() the mouse events of the observed widget are filtered. + + \param object Object to be filtered + \param event Event + + \sa widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseMoveEvent() +*/ +bool QwtPanner::eventFilter( QObject *object, QEvent *event ) +{ + if ( object == NULL || object != parentWidget() ) + return false; + + switch ( event->type() ) + { + case QEvent::MouseButtonPress: + { + widgetMousePressEvent( ( QMouseEvent * )event ); + break; + } + case QEvent::MouseMove: + { + widgetMouseMoveEvent( ( QMouseEvent * )event ); + break; + } + case QEvent::MouseButtonRelease: + { + widgetMouseReleaseEvent( ( QMouseEvent * )event ); + break; + } + case QEvent::KeyPress: + { + widgetKeyPressEvent( ( QKeyEvent * )event ); + break; + } + case QEvent::KeyRelease: + { + widgetKeyReleaseEvent( ( QKeyEvent * )event ); + break; + } + case QEvent::Paint: + { + if ( isVisible() ) + return true; + break; + } + default:; + } + + return false; +} + +/*! + Handle a mouse press event for the observed widget. + + \param mouseEvent Mouse event + \sa eventFilter(), widgetMouseReleaseEvent(), + widgetMouseMoveEvent(), +*/ +void QwtPanner::widgetMousePressEvent( QMouseEvent *mouseEvent ) +{ + if ( mouseEvent->button() != d_data->button ) + return; + + QWidget *w = parentWidget(); + if ( w == NULL ) + return; + + if ( ( mouseEvent->modifiers() & Qt::KeyboardModifierMask ) != + ( int )( d_data->buttonState & Qt::KeyboardModifierMask ) ) + { + return; + } + +#ifndef QT_NO_CURSOR + showCursor( true ); +#endif + + d_data->initialPos = d_data->pos = mouseEvent->pos(); + + setGeometry( parentWidget()->rect() ); + + // We don't want to grab the picker ! + QVector pickers = qwtActivePickers( parentWidget() ); + for ( int i = 0; i < ( int )pickers.size(); i++ ) + pickers[i]->setEnabled( false ); + + d_data->pixmap = grab(); + d_data->contentsMask = contentsMask(); + + for ( int i = 0; i < ( int )pickers.size(); i++ ) + pickers[i]->setEnabled( true ); + + show(); +} + +/*! + Handle a mouse move event for the observed widget. + + \param mouseEvent Mouse event + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent() +*/ +void QwtPanner::widgetMouseMoveEvent( QMouseEvent *mouseEvent ) +{ + if ( !isVisible() ) + return; + + QPoint pos = mouseEvent->pos(); + if ( !isOrientationEnabled( Qt::Horizontal ) ) + pos.setX( d_data->initialPos.x() ); + if ( !isOrientationEnabled( Qt::Vertical ) ) + pos.setY( d_data->initialPos.y() ); + + if ( pos != d_data->pos && rect().contains( pos ) ) + { + d_data->pos = pos; + update(); + + Q_EMIT moved( d_data->pos.x() - d_data->initialPos.x(), + d_data->pos.y() - d_data->initialPos.y() ); + } +} + +/*! + Handle a mouse release event for the observed widget. + + \param mouseEvent Mouse event + \sa eventFilter(), widgetMousePressEvent(), + widgetMouseMoveEvent(), +*/ +void QwtPanner::widgetMouseReleaseEvent( QMouseEvent *mouseEvent ) +{ + if ( isVisible() ) + { + hide(); +#ifndef QT_NO_CURSOR + showCursor( false ); +#endif + + QPoint pos = mouseEvent->pos(); + if ( !isOrientationEnabled( Qt::Horizontal ) ) + pos.setX( d_data->initialPos.x() ); + if ( !isOrientationEnabled( Qt::Vertical ) ) + pos.setY( d_data->initialPos.y() ); + + d_data->pixmap = QPixmap(); + d_data->contentsMask = QBitmap(); + d_data->pos = pos; + + if ( d_data->pos != d_data->initialPos ) + { + Q_EMIT panned( d_data->pos.x() - d_data->initialPos.x(), + d_data->pos.y() - d_data->initialPos.y() ); + } + } +} + +/*! + Handle a key press event for the observed widget. + + \param keyEvent Key event + \sa eventFilter(), widgetKeyReleaseEvent() +*/ +void QwtPanner::widgetKeyPressEvent( QKeyEvent *keyEvent ) +{ + if ( keyEvent->key() == d_data->abortKey ) + { + const bool matched = + ( keyEvent->modifiers() & Qt::KeyboardModifierMask ) == + ( int )( d_data->abortKeyState & Qt::KeyboardModifierMask ); + if ( matched ) + { + hide(); +#ifndef QT_NO_CURSOR + showCursor( false ); +#endif + d_data->pixmap = QPixmap(); + } + } +} + +/*! + Handle a key release event for the observed widget. + + \param keyEvent Key event + \sa eventFilter(), widgetKeyReleaseEvent() +*/ +void QwtPanner::widgetKeyReleaseEvent( QKeyEvent *keyEvent ) +{ + Q_UNUSED( keyEvent ); +} + +#ifndef QT_NO_CURSOR +void QwtPanner::showCursor( bool on ) +{ + if ( on == d_data->hasCursor ) + return; + + QWidget *w = parentWidget(); + if ( w == NULL || d_data->cursor == NULL ) + return; + + d_data->hasCursor = on; + + if ( on ) + { + if ( w->testAttribute( Qt::WA_SetCursor ) ) + { + delete d_data->restoreCursor; + d_data->restoreCursor = new QCursor( w->cursor() ); + } + w->setCursor( *d_data->cursor ); + } + else + { + if ( d_data->restoreCursor ) + { + w->setCursor( *d_data->restoreCursor ); + delete d_data->restoreCursor; + d_data->restoreCursor = NULL; + } + else + w->unsetCursor(); + } +} +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_panner.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_panner.h index 166873614..247d4a393 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_panner.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_panner.h @@ -1,100 +1,100 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PANNER_H -#define QWT_PANNER_H 1 - -#include "qwt_global.h" -#include -#include - -class QCursor; - -/*! - \brief QwtPanner provides panning of a widget - - QwtPanner grabs the contents of a widget, that can be dragged - in all directions. The offset between the start and the end position - is emitted by the panned signal. - - QwtPanner grabs the content of the widget into a pixmap and moves - the pixmap around, without initiating any repaint events for the widget. - Areas, that are not part of content are not painted while panning. - This makes panning fast enough for widgets, where - repaints are too slow for mouse movements. - - For widgets, where repaints are very fast it might be better to - implement panning manually by mapping mouse events into paint events. -*/ -class QWT_EXPORT QwtPanner: public QWidget -{ - Q_OBJECT - -public: - QwtPanner( QWidget* parent ); - virtual ~QwtPanner(); - - void setEnabled( bool ); - bool isEnabled() const; - - void setMouseButton( int button, int buttonState = Qt::NoButton ); - void getMouseButton( int &button, int &buttonState ) const; - void setAbortKey( int key, int state = Qt::NoButton ); - void getAbortKey( int &key, int &state ) const; - - void setCursor( const QCursor & ); - const QCursor cursor() const; - - void setOrientations( Qt::Orientations ); - Qt::Orientations orientations() const; - - bool isOrientationEnabled( Qt::Orientation ) const; - - virtual bool eventFilter( QObject *, QEvent * ); - -Q_SIGNALS: - /*! - Signal emitted, when panning is done - - \param dx Offset in horizontal direction - \param dy Offset in vertical direction - */ - void panned( int dx, int dy ); - - /*! - Signal emitted, while the widget moved, but panning - is not finished. - - \param dx Offset in horizontal direction - \param dy Offset in vertical direction - */ - void moved( int dx, int dy ); - -protected: - virtual void widgetMousePressEvent( QMouseEvent * ); - virtual void widgetMouseReleaseEvent( QMouseEvent * ); - virtual void widgetMouseMoveEvent( QMouseEvent * ); - virtual void widgetKeyPressEvent( QKeyEvent * ); - virtual void widgetKeyReleaseEvent( QKeyEvent * ); - - virtual void paintEvent( QPaintEvent * ); - - virtual QBitmap contentsMask() const; - virtual QPixmap grab() const; - -private: -#ifndef QT_NO_CURSOR - void showCursor( bool ); -#endif - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PANNER_H +#define QWT_PANNER_H 1 + +#include "qwt_global.h" +#include +#include + +class QCursor; + +/*! + \brief QwtPanner provides panning of a widget + + QwtPanner grabs the contents of a widget, that can be dragged + in all directions. The offset between the start and the end position + is emitted by the panned signal. + + QwtPanner grabs the content of the widget into a pixmap and moves + the pixmap around, without initiating any repaint events for the widget. + Areas, that are not part of content are not painted while panning. + This makes panning fast enough for widgets, where + repaints are too slow for mouse movements. + + For widgets, where repaints are very fast it might be better to + implement panning manually by mapping mouse events into paint events. +*/ +class QWT_EXPORT QwtPanner: public QWidget +{ + Q_OBJECT + +public: + QwtPanner( QWidget* parent ); + virtual ~QwtPanner(); + + void setEnabled( bool ); + bool isEnabled() const; + + void setMouseButton( int button, int buttonState = Qt::NoButton ); + void getMouseButton( int &button, int &buttonState ) const; + void setAbortKey( int key, int state = Qt::NoButton ); + void getAbortKey( int &key, int &state ) const; + + void setCursor( const QCursor & ); + const QCursor cursor() const; + + void setOrientations( Qt::Orientations ); + Qt::Orientations orientations() const; + + bool isOrientationEnabled( Qt::Orientation ) const; + + virtual bool eventFilter( QObject *, QEvent * ); + +Q_SIGNALS: + /*! + Signal emitted, when panning is done + + \param dx Offset in horizontal direction + \param dy Offset in vertical direction + */ + void panned( int dx, int dy ); + + /*! + Signal emitted, while the widget moved, but panning + is not finished. + + \param dx Offset in horizontal direction + \param dy Offset in vertical direction + */ + void moved( int dx, int dy ); + +protected: + virtual void widgetMousePressEvent( QMouseEvent * ); + virtual void widgetMouseReleaseEvent( QMouseEvent * ); + virtual void widgetMouseMoveEvent( QMouseEvent * ); + virtual void widgetKeyPressEvent( QKeyEvent * ); + virtual void widgetKeyReleaseEvent( QKeyEvent * ); + + virtual void paintEvent( QPaintEvent * ); + + virtual QBitmap contentsMask() const; + virtual QPixmap grab() const; + +private: +#ifndef QT_NO_CURSOR + void showCursor( bool ); +#endif + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_picker.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_picker.cpp index ddca36b43..2871dd439 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_picker.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_picker.cpp @@ -1,1434 +1,1434 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_picker.h" -#include "qwt_picker_machine.h" -#include "qwt_painter.h" -#include "qwt_math.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include - -class QwtPicker::PickerWidget: public QWidget -{ -public: - enum Type - { - RubberBand, - Text - }; - - PickerWidget( QwtPicker *, QWidget *, Type ); - void updateMask(); - - /* - For a tracker text with a background we can use the background - rect as mask. Also for "regular" Qt widgets >= 4.3.0 we - don't need to mask the text anymore. - */ - bool d_hasTextMask; - -protected: - virtual void paintEvent( QPaintEvent * ); - - QwtPicker *d_picker; - Type d_type; -}; - -class QwtPicker::PrivateData -{ -public: - bool enabled; - - QwtPickerMachine *stateMachine; - - QwtPicker::ResizeMode resizeMode; - - QwtPicker::RubberBand rubberBand; - QPen rubberBandPen; - - QwtPicker::DisplayMode trackerMode; - QPen trackerPen; - QFont trackerFont; - - QPolygon pickedPoints; - bool isActive; - QPoint trackerPosition; - - bool mouseTracking; // used to save previous value - - /* - On X11 the widget below the picker widgets gets paint events - with a region that is the bounding rect of the mask, if it is complex. - In case of (f.e) a CrossRubberBand and a text this creates complete - repaints of the widget. So we better use two different widgets. - */ - - QPointer rubberBandWidget; - QPointer trackerWidget; -}; - -QwtPicker::PickerWidget::PickerWidget( - QwtPicker *picker, QWidget *parent, Type type ): - QWidget( parent ), - d_hasTextMask( false ), - d_picker( picker ), - d_type( type ) -{ - setAttribute( Qt::WA_TransparentForMouseEvents ); - setAttribute( Qt::WA_NoSystemBackground ); - setFocusPolicy( Qt::NoFocus ); -} - -void QwtPicker::PickerWidget::updateMask() -{ - QRegion mask; - - if ( d_type == RubberBand ) - { - QBitmap bm( width(), height() ); - bm.fill( Qt::color0 ); - - QPainter painter( &bm ); - QPen pen = d_picker->rubberBandPen(); - pen.setColor( Qt::color1 ); - painter.setPen( pen ); - - d_picker->drawRubberBand( &painter ); - - mask = QRegion( bm ); - } - if ( d_type == Text ) - { - d_hasTextMask = parentWidget()->testAttribute( Qt::WA_PaintOnScreen ); - - if ( d_hasTextMask ) - { - const QwtText label = d_picker->trackerText( - d_picker->trackerPosition() ); - - if ( label.testPaintAttribute( QwtText::PaintBackground ) - && label.backgroundBrush().style() != Qt::NoBrush ) - { - if ( label.backgroundBrush().color().alpha() > 0 ) - { - // We don't need a text mask, when we have a background - d_hasTextMask = false; - } - } - } - - if ( d_hasTextMask ) - { - QBitmap bm( width(), height() ); - bm.fill( Qt::color0 ); - - QPainter painter( &bm ); - painter.setFont( font() ); - - QPen pen = d_picker->trackerPen(); - pen.setColor( Qt::color1 ); - painter.setPen( pen ); - - d_picker->drawTracker( &painter ); - - mask = QRegion( bm ); - } - else - { - mask = d_picker->trackerRect( font() ); - } - } - - QWidget *w = parentWidget(); - if ( w && !w->testAttribute( Qt::WA_PaintOnScreen ) ) - { - // The parent widget gets an update for its complete rectangle - // when the mask is changed in visible state. - // With this hide/show we only get an update for the - // previous mask. - - hide(); - } - setMask( mask ); - setVisible( !mask.isEmpty() ); -} - -void QwtPicker::PickerWidget::paintEvent( QPaintEvent *e ) -{ - QPainter painter( this ); - painter.setClipRegion( e->region() ); - - if ( d_type == RubberBand ) - { - painter.setPen( d_picker->rubberBandPen() ); - d_picker->drawRubberBand( &painter ); - } - - if ( d_type == Text ) - { - /* - If we have a text mask we simply fill the region of - the mask. This gives better results for antialiased fonts. - */ - if ( d_hasTextMask ) - { - painter.fillRect( e->rect(), - QBrush( d_picker->trackerPen().color() ) ); - } - else - { - painter.setPen( d_picker->trackerPen() ); - d_picker->drawTracker( &painter ); - } - } -} - -/*! - Constructor - - Creates an picker that is enabled, but without a state machine. - rubberband and tracker are disabled. - - \param parent Parent widget, that will be observed - */ - -QwtPicker::QwtPicker( QWidget *parent ): - QObject( parent ) -{ - init( parent, NoRubberBand, AlwaysOff ); -} - -/*! - Constructor - - \param rubberBand Rubberband style - \param trackerMode Tracker mode - \param parent Parent widget, that will be observed - */ -QwtPicker::QwtPicker( RubberBand rubberBand, - DisplayMode trackerMode, QWidget *parent ): - QObject( parent ) -{ - init( parent, rubberBand, trackerMode ); -} - -//! Destructor -QwtPicker::~QwtPicker() -{ - setMouseTracking( false ); - delete d_data->stateMachine; - delete d_data->rubberBandWidget; - delete d_data->trackerWidget; - delete d_data; -} - -//! Init the picker, used by the constructors -void QwtPicker::init( QWidget *parent, - RubberBand rubberBand, DisplayMode trackerMode ) -{ - d_data = new PrivateData; - - d_data->rubberBandWidget = NULL; - d_data->trackerWidget = NULL; - - d_data->rubberBand = rubberBand; - d_data->enabled = false; - d_data->resizeMode = Stretch; - d_data->trackerMode = AlwaysOff; - d_data->isActive = false; - d_data->trackerPosition = QPoint( -1, -1 ); - d_data->mouseTracking = false; - - d_data->stateMachine = NULL; - - if ( parent ) - { - if ( parent->focusPolicy() == Qt::NoFocus ) - parent->setFocusPolicy( Qt::WheelFocus ); - - d_data->trackerFont = parent->font(); - d_data->mouseTracking = parent->hasMouseTracking(); - setEnabled( true ); - } - setTrackerMode( trackerMode ); -} - -/*! - Set a state machine and delete the previous one - - \param stateMachine State machine - \sa stateMachine() -*/ -void QwtPicker::setStateMachine( QwtPickerMachine *stateMachine ) -{ - if ( d_data->stateMachine != stateMachine ) - { - reset(); - - delete d_data->stateMachine; - d_data->stateMachine = stateMachine; - - if ( d_data->stateMachine ) - d_data->stateMachine->reset(); - } -} - -/*! - \return Assigned state machine - \sa setStateMachine() -*/ -QwtPickerMachine *QwtPicker::stateMachine() -{ - return d_data->stateMachine; -} - -/*! - \return Assigned state machine - \sa setStateMachine() -*/ -const QwtPickerMachine *QwtPicker::stateMachine() const -{ - return d_data->stateMachine; -} - -//! Return the parent widget, where the selection happens -QWidget *QwtPicker::parentWidget() -{ - QObject *obj = parent(); - if ( obj && obj->isWidgetType() ) - return static_cast( obj ); - - return NULL; -} - -//! Return the parent widget, where the selection happens -const QWidget *QwtPicker::parentWidget() const -{ - QObject *obj = parent(); - if ( obj && obj->isWidgetType() ) - return static_cast< const QWidget *>( obj ); - - return NULL; -} - -/*! - Set the rubberband style - - \param rubberBand Rubberband style - The default value is NoRubberBand. - - \sa rubberBand(), RubberBand, setRubberBandPen() -*/ -void QwtPicker::setRubberBand( RubberBand rubberBand ) -{ - d_data->rubberBand = rubberBand; -} - -/*! - \return Rubberband style - \sa setRubberBand(), RubberBand, rubberBandPen() -*/ -QwtPicker::RubberBand QwtPicker::rubberBand() const -{ - return d_data->rubberBand; -} - -/*! - \brief Set the display mode of the tracker. - - A tracker displays information about current position of - the cursor as a string. The display mode controls - if the tracker has to be displayed whenever the observed - widget has focus and cursor (AlwaysOn), never (AlwaysOff), or - only when the selection is active (ActiveOnly). - - \param mode Tracker display mode - - \warning In case of AlwaysOn, mouseTracking will be enabled - for the observed widget. - \sa trackerMode(), DisplayMode -*/ - -void QwtPicker::setTrackerMode( DisplayMode mode ) -{ - if ( d_data->trackerMode != mode ) - { - d_data->trackerMode = mode; - setMouseTracking( d_data->trackerMode == AlwaysOn ); - } -} - -/*! - \return Tracker display mode - \sa setTrackerMode(), DisplayMode -*/ -QwtPicker::DisplayMode QwtPicker::trackerMode() const -{ - return d_data->trackerMode; -} - -/*! - \brief Set the resize mode. - - The resize mode controls what to do with the selected points of an active - selection when the observed widget is resized. - - Stretch means the points are scaled according to the new - size, KeepSize means the points remain unchanged. - - The default mode is Stretch. - - \param mode Resize mode - \sa resizeMode(), ResizeMode -*/ -void QwtPicker::setResizeMode( ResizeMode mode ) -{ - d_data->resizeMode = mode; -} - -/*! - \return Resize mode - \sa setResizeMode(), ResizeMode -*/ - -QwtPicker::ResizeMode QwtPicker::resizeMode() const -{ - return d_data->resizeMode; -} - -/*! - \brief En/disable the picker - - When enabled is true an event filter is installed for - the observed widget, otherwise the event filter is removed. - - \param enabled true or false - \sa isEnabled(), eventFilter() -*/ -void QwtPicker::setEnabled( bool enabled ) -{ - if ( d_data->enabled != enabled ) - { - d_data->enabled = enabled; - - QWidget *w = parentWidget(); - if ( w ) - { - if ( enabled ) - w->installEventFilter( this ); - else - w->removeEventFilter( this ); - } - - updateDisplay(); - } -} - -/*! - \return true when enabled, false otherwise - \sa setEnabled(), eventFilter() -*/ - -bool QwtPicker::isEnabled() const -{ - return d_data->enabled; -} - -/*! - Set the font for the tracker - - \param font Tracker font - \sa trackerFont(), setTrackerMode(), setTrackerPen() -*/ -void QwtPicker::setTrackerFont( const QFont &font ) -{ - if ( font != d_data->trackerFont ) - { - d_data->trackerFont = font; - updateDisplay(); - } -} - -/*! - \return Tracker font - \sa setTrackerFont(), trackerMode(), trackerPen() -*/ - -QFont QwtPicker::trackerFont() const -{ - return d_data->trackerFont; -} - -/*! - Set the pen for the tracker - - \param pen Tracker pen - \sa trackerPen(), setTrackerMode(), setTrackerFont() -*/ -void QwtPicker::setTrackerPen( const QPen &pen ) -{ - if ( pen != d_data->trackerPen ) - { - d_data->trackerPen = pen; - updateDisplay(); - } -} - -/*! - \return Tracker pen - \sa setTrackerPen(), trackerMode(), trackerFont() -*/ -QPen QwtPicker::trackerPen() const -{ - return d_data->trackerPen; -} - -/*! - Set the pen for the rubberband - - \param pen Rubberband pen - \sa rubberBandPen(), setRubberBand() -*/ -void QwtPicker::setRubberBandPen( const QPen &pen ) -{ - if ( pen != d_data->rubberBandPen ) - { - d_data->rubberBandPen = pen; - updateDisplay(); - } -} - -/*! - \return Rubberband pen - \sa setRubberBandPen(), rubberBand() -*/ -QPen QwtPicker::rubberBandPen() const -{ - return d_data->rubberBandPen; -} - -/*! - \brief Return the label for a position - - In case of HLineRubberBand the label is the value of the - y position, in case of VLineRubberBand the value of the x position. - Otherwise the label contains x and y position separated by a ',' . - - The format for the string conversion is "%d". - - \param pos Position - \return Converted position as string -*/ - -QwtText QwtPicker::trackerText( const QPoint &pos ) const -{ - QString label; - - switch ( rubberBand() ) - { - case HLineRubberBand: - label.sprintf( "%d", pos.y() ); - break; - case VLineRubberBand: - label.sprintf( "%d", pos.x() ); - break; - default: - label.sprintf( "%d, %d", pos.x(), pos.y() ); - } - return label; -} - -/*! - Draw a rubberband, depending on rubberBand() - - \param painter Painter, initialized with clip rect - - \sa rubberBand(), RubberBand -*/ - -void QwtPicker::drawRubberBand( QPainter *painter ) const -{ - if ( !isActive() || rubberBand() == NoRubberBand || - rubberBandPen().style() == Qt::NoPen ) - { - return; - } - - const QRect &pRect = pickRect(); - const QPolygon pa = adjustedPoints( d_data->pickedPoints ); - - QwtPickerMachine::SelectionType selectionType = - QwtPickerMachine::NoSelection; - - if ( d_data->stateMachine ) - selectionType = d_data->stateMachine->selectionType(); - - switch ( selectionType ) - { - case QwtPickerMachine::NoSelection: - case QwtPickerMachine::PointSelection: - { - if ( pa.count() < 1 ) - return; - - const QPoint pos = pa[0]; - - switch ( rubberBand() ) - { - case VLineRubberBand: - QwtPainter::drawLine( painter, pos.x(), - pRect.top(), pos.x(), pRect.bottom() ); - break; - - case HLineRubberBand: - QwtPainter::drawLine( painter, pRect.left(), - pos.y(), pRect.right(), pos.y() ); - break; - - case CrossRubberBand: - QwtPainter::drawLine( painter, pos.x(), - pRect.top(), pos.x(), pRect.bottom() ); - QwtPainter::drawLine( painter, pRect.left(), - pos.y(), pRect.right(), pos.y() ); - break; - default: - break; - } - break; - } - case QwtPickerMachine::RectSelection: - { - if ( pa.count() < 2 ) - return; - - const QPoint p1 = pa[0]; - const QPoint p2 = pa[int( pa.count() - 1 )]; - - const QRect rect = QRect( p1, p2 ).normalized(); - switch ( rubberBand() ) - { - case EllipseRubberBand: - QwtPainter::drawEllipse( painter, rect ); - break; - case RectRubberBand: - QwtPainter::drawRect( painter, rect ); - break; - default: - break; - } - break; - } - case QwtPickerMachine::PolygonSelection: - { - if ( rubberBand() == PolygonRubberBand ) - painter->drawPolyline( pa ); - break; - } - default: - break; - } -} - -/*! - Draw the tracker - - \param painter Painter - \sa trackerRect(), trackerText() -*/ - -void QwtPicker::drawTracker( QPainter *painter ) const -{ - const QRect textRect = trackerRect( painter->font() ); - if ( !textRect.isEmpty() ) - { - const QwtText label = trackerText( d_data->trackerPosition ); - if ( !label.isEmpty() ) - label.draw( painter, textRect ); - } -} - -/*! - \brief Map the pickedPoints() into a selection() - - adjustedPoints() maps the points, that have been collected on - the parentWidget() into a selection(). The default implementation - simply returns the points unmodified. - - The reason, why a selection() differs from the picked points - depends on the application requirements. F.e. : - - - A rectangular selection might need to have a specific aspect ratio only.\n - - A selection could accept non intersecting polygons only.\n - - ...\n - - The example below is for a rectangular selection, where the first - point is the center of the selected rectangle. - \par Example - \verbatim QPolygon MyPicker::adjustedPoints(const QPolygon &points) const -{ - QPolygon adjusted; - if ( points.size() == 2 ) - { - const int width = qAbs(points[1].x() - points[0].x()); - const int height = qAbs(points[1].y() - points[0].y()); - - QRect rect(0, 0, 2 * width, 2 * height); - rect.moveCenter(points[0]); - - adjusted += rect.topLeft(); - adjusted += rect.bottomRight(); - } - return adjusted; -}\endverbatim\n -*/ -QPolygon QwtPicker::adjustedPoints( const QPolygon &points ) const -{ - return points; -} - -/*! - \return Selected points - \sa pickedPoints(), adjustedPoints() -*/ -QPolygon QwtPicker::selection() const -{ - return adjustedPoints( d_data->pickedPoints ); -} - -//! \return Current position of the tracker -QPoint QwtPicker::trackerPosition() const -{ - return d_data->trackerPosition; -} - -/*! - Calculate the bounding rectangle for the tracker text - from the current position of the tracker - - \param font Font of the tracker text - \return Bounding rectangle of the tracker text - - \sa trackerPosition() -*/ -QRect QwtPicker::trackerRect( const QFont &font ) const -{ - if ( trackerMode() == AlwaysOff || - ( trackerMode() == ActiveOnly && !isActive() ) ) - { - return QRect(); - } - - if ( d_data->trackerPosition.x() < 0 || d_data->trackerPosition.y() < 0 ) - return QRect(); - - QwtText text = trackerText( d_data->trackerPosition ); - if ( text.isEmpty() ) - return QRect(); - - const QSizeF textSize = text.textSize( font ); - QRect textRect( 0, 0, qCeil( textSize.width() ), qCeil( textSize.height() ) ); - - const QPoint &pos = d_data->trackerPosition; - - int alignment = 0; - if ( isActive() && d_data->pickedPoints.count() > 1 - && rubberBand() != NoRubberBand ) - { - const QPoint last = - d_data->pickedPoints[int( d_data->pickedPoints.count() ) - 2]; - - alignment |= ( pos.x() >= last.x() ) ? Qt::AlignRight : Qt::AlignLeft; - alignment |= ( pos.y() > last.y() ) ? Qt::AlignBottom : Qt::AlignTop; - } - else - alignment = Qt::AlignTop | Qt::AlignRight; - - const int margin = 5; - - int x = pos.x(); - if ( alignment & Qt::AlignLeft ) - x -= textRect.width() + margin; - else if ( alignment & Qt::AlignRight ) - x += margin; - - int y = pos.y(); - if ( alignment & Qt::AlignBottom ) - y += margin; - else if ( alignment & Qt::AlignTop ) - y -= textRect.height() + margin; - - textRect.moveTopLeft( QPoint( x, y ) ); - - int right = qMin( textRect.right(), pickRect().right() - margin ); - int bottom = qMin( textRect.bottom(), pickRect().bottom() - margin ); - textRect.moveBottomRight( QPoint( right, bottom ) ); - - int left = qMax( textRect.left(), pickRect().left() + margin ); - int top = qMax( textRect.top(), pickRect().top() + margin ); - textRect.moveTopLeft( QPoint( left, top ) ); - - return textRect; -} - -/*! - \brief Event filter - - When isEnabled() == true all events of the observed widget are filtered. - Mouse and keyboard events are translated into widgetMouse- and widgetKey- - and widgetWheel-events. Paint and Resize events are handled to keep - rubberband and tracker up to date. - - \param object Object to be filtered - \param event Event - - \sa widgetEnterEvent(), widgetLeaveEvent(), - widgetMousePressEvent(), widgetMouseReleaseEvent(), - widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), - widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent(), - QObject::installEventFilter(), QObject::event() -*/ -bool QwtPicker::eventFilter( QObject *object, QEvent *event ) -{ - if ( object && object == parentWidget() ) - { - switch ( event->type() ) - { - case QEvent::Resize: - { - const QResizeEvent *re = ( QResizeEvent * )event; - if ( d_data->resizeMode == Stretch ) - stretchSelection( re->oldSize(), re->size() ); - - if ( d_data->rubberBandWidget ) - d_data->rubberBandWidget->resize( re->size() ); - - if ( d_data->trackerWidget ) - d_data->trackerWidget->resize( re->size() ); - break; - } - case QEvent::Enter: - widgetEnterEvent( event ); - break; - case QEvent::Leave: - widgetLeaveEvent( event ); - break; - case QEvent::MouseButtonPress: - widgetMousePressEvent( ( QMouseEvent * )event ); - break; - case QEvent::MouseButtonRelease: - widgetMouseReleaseEvent( ( QMouseEvent * )event ); - break; - case QEvent::MouseButtonDblClick: - widgetMouseDoubleClickEvent( ( QMouseEvent * )event ); - break; - case QEvent::MouseMove: - widgetMouseMoveEvent( ( QMouseEvent * )event ); - break; - case QEvent::KeyPress: - widgetKeyPressEvent( ( QKeyEvent * )event ); - break; - case QEvent::KeyRelease: - widgetKeyReleaseEvent( ( QKeyEvent * )event ); - break; - case QEvent::Wheel: - widgetWheelEvent( ( QWheelEvent * )event ); - break; - default: - break; - } - } - return false; -} - -/*! - Handle a mouse press event for the observed widget. - - \param mouseEvent Mouse event - - \sa eventFilter(), widgetMouseReleaseEvent(), - widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), - widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() -*/ -void QwtPicker::widgetMousePressEvent( QMouseEvent *mouseEvent ) -{ - transition( mouseEvent ); -} - -/*! - Handle a mouse move event for the observed widget. - - \param mouseEvent Mouse event - - \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), - widgetMouseDoubleClickEvent(), - widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() -*/ -void QwtPicker::widgetMouseMoveEvent( QMouseEvent *mouseEvent ) -{ - if ( pickRect().contains( mouseEvent->pos() ) ) - d_data->trackerPosition = mouseEvent->pos(); - else - d_data->trackerPosition = QPoint( -1, -1 ); - - if ( !isActive() ) - updateDisplay(); - - transition( mouseEvent ); -} - -/*! - Handle a enter event for the observed widget. - - \param event Qt event - - \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), - widgetMouseDoubleClickEvent(), - widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() -*/ -void QwtPicker::widgetEnterEvent( QEvent *event ) -{ - transition( event ); -} - -/*! - Handle a leave event for the observed widget. - - \param event Qt event - - \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), - widgetMouseDoubleClickEvent(), - widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() -*/ -void QwtPicker::widgetLeaveEvent( QEvent *event ) -{ - transition( event ); - - d_data->trackerPosition = QPoint( -1, -1 ); - if ( !isActive() ) - updateDisplay(); -} - -/*! - Handle a mouse relase event for the observed widget. - - \param mouseEvent Mouse event - - \sa eventFilter(), widgetMousePressEvent(), - widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), - widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() -*/ -void QwtPicker::widgetMouseReleaseEvent( QMouseEvent *mouseEvent ) -{ - transition( mouseEvent ); -} - -/*! - Handle mouse double click event for the observed widget. - - \param mouseEvent Mouse event - - \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), - widgetMouseMoveEvent(), - widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() -*/ -void QwtPicker::widgetMouseDoubleClickEvent( QMouseEvent *mouseEvent ) -{ - transition( mouseEvent ); -} - - -/*! - Handle a wheel event for the observed widget. - - Move the last point of the selection in case of isActive() == true - - \param wheelEvent Wheel event - - \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), - widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), - widgetKeyPressEvent(), widgetKeyReleaseEvent() -*/ -void QwtPicker::widgetWheelEvent( QWheelEvent *wheelEvent ) -{ - if ( pickRect().contains( wheelEvent->pos() ) ) - d_data->trackerPosition = wheelEvent->pos(); - else - d_data->trackerPosition = QPoint( -1, -1 ); - - updateDisplay(); - - transition( wheelEvent ); -} - -/*! - Handle a key press event for the observed widget. - - Selections can be completely done by the keyboard. The arrow keys - move the cursor, the abort key aborts a selection. All other keys - are handled by the current state machine. - - \param keyEvent Key event - - \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), - widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), - widgetWheelEvent(), widgetKeyReleaseEvent(), stateMachine(), - QwtEventPattern::KeyPatternCode -*/ -void QwtPicker::widgetKeyPressEvent( QKeyEvent *keyEvent ) -{ - int dx = 0; - int dy = 0; - - int offset = 1; - if ( keyEvent->isAutoRepeat() ) - offset = 5; - - if ( keyMatch( KeyLeft, keyEvent ) ) - dx = -offset; - else if ( keyMatch( KeyRight, keyEvent ) ) - dx = offset; - else if ( keyMatch( KeyUp, keyEvent ) ) - dy = -offset; - else if ( keyMatch( KeyDown, keyEvent ) ) - dy = offset; - else if ( keyMatch( KeyAbort, keyEvent ) ) - { - reset(); - } - else - transition( keyEvent ); - - if ( dx != 0 || dy != 0 ) - { - const QRect rect = pickRect(); - const QPoint pos = parentWidget()->mapFromGlobal( QCursor::pos() ); - - int x = pos.x() + dx; - x = qMax( rect.left(), x ); - x = qMin( rect.right(), x ); - - int y = pos.y() + dy; - y = qMax( rect.top(), y ); - y = qMin( rect.bottom(), y ); - - QCursor::setPos( parentWidget()->mapToGlobal( QPoint( x, y ) ) ); - } -} - -/*! - Handle a key release event for the observed widget. - - Passes the event to the state machine. - - \param keyEvent Key event - - \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), - widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), - widgetWheelEvent(), widgetKeyPressEvent(), stateMachine() -*/ -void QwtPicker::widgetKeyReleaseEvent( QKeyEvent *keyEvent ) -{ - transition( keyEvent ); -} - -/*! - Passes an event to the state machine and executes the resulting - commands. Append and Move commands use the current position - of the cursor (QCursor::pos()). - - \param event Event -*/ -void QwtPicker::transition( const QEvent *event ) -{ - if ( !d_data->stateMachine ) - return; - - const QList commandList = - d_data->stateMachine->transition( *this, event ); - - QPoint pos; - switch ( event->type() ) - { - case QEvent::MouseButtonDblClick: - case QEvent::MouseButtonPress: - case QEvent::MouseButtonRelease: - case QEvent::MouseMove: - { - const QMouseEvent *me = - static_cast< const QMouseEvent * >( event ); - pos = me->pos(); - break; - } - default: - pos = parentWidget()->mapFromGlobal( QCursor::pos() ); - } - - for ( int i = 0; i < commandList.count(); i++ ) - { - switch ( commandList[i] ) - { - case QwtPickerMachine::Begin: - { - begin(); - break; - } - case QwtPickerMachine::Append: - { - append( pos ); - break; - } - case QwtPickerMachine::Move: - { - move( pos ); - break; - } - case QwtPickerMachine::Remove: - { - remove(); - break; - } - case QwtPickerMachine::End: - { - end(); - break; - } - } - } -} - -/*! - Open a selection setting the state to active - - \sa isActive(), end(), append(), move() -*/ -void QwtPicker::begin() -{ - if ( d_data->isActive ) - return; - - d_data->pickedPoints.resize( 0 ); - d_data->isActive = true; - Q_EMIT activated( true ); - - if ( trackerMode() != AlwaysOff ) - { - if ( d_data->trackerPosition.x() < 0 || d_data->trackerPosition.y() < 0 ) - { - QWidget *w = parentWidget(); - if ( w ) - d_data->trackerPosition = w->mapFromGlobal( QCursor::pos() ); - } - } - - updateDisplay(); - setMouseTracking( true ); -} - -/*! - \brief Close a selection setting the state to inactive. - - The selection is validated and maybe fixed by accept(). - - \param ok If true, complete the selection and emit a selected signal - otherwise discard the selection. - \return true if the selection is accepted, false otherwise - \sa isActive(), begin(), append(), move(), selected(), accept() -*/ -bool QwtPicker::end( bool ok ) -{ - if ( d_data->isActive ) - { - setMouseTracking( false ); - - d_data->isActive = false; - Q_EMIT activated( false ); - - if ( trackerMode() == ActiveOnly ) - d_data->trackerPosition = QPoint( -1, -1 ); - - if ( ok ) - ok = accept( d_data->pickedPoints ); - - if ( ok ) - Q_EMIT selected( d_data->pickedPoints ); - else - d_data->pickedPoints.resize( 0 ); - - updateDisplay(); - } - else - ok = false; - - return ok; -} - -/*! - Reset the state machine and terminate (end(false)) the selection -*/ -void QwtPicker::reset() -{ - if ( d_data->stateMachine ) - d_data->stateMachine->reset(); - - if ( isActive() ) - end( false ); -} - -/*! - Append a point to the selection and update rubberband and tracker. - The appended() signal is emitted. - - \param pos Additional point - - \sa isActive(), begin(), end(), move(), appended() -*/ -void QwtPicker::append( const QPoint &pos ) -{ - if ( d_data->isActive ) - { - const int idx = d_data->pickedPoints.count(); - d_data->pickedPoints.resize( idx + 1 ); - d_data->pickedPoints[idx] = pos; - - updateDisplay(); - Q_EMIT appended( pos ); - } -} - -/*! - Move the last point of the selection - The moved() signal is emitted. - - \param pos New position - \sa isActive(), begin(), end(), append() -*/ -void QwtPicker::move( const QPoint &pos ) -{ - if ( d_data->isActive ) - { - const int idx = d_data->pickedPoints.count() - 1; - if ( idx >= 0 ) - { - if ( d_data->pickedPoints[idx] != pos ) - { - d_data->pickedPoints[idx] = pos; - - updateDisplay(); - Q_EMIT moved( pos ); - } - } - } -} - -/*! - Remove the last point of the selection - The removed() signal is emitted. - - \sa isActive(), begin(), end(), append(), move() -*/ -void QwtPicker::remove() -{ - if ( d_data->isActive ) - { - const int idx = d_data->pickedPoints.count() - 1; - if ( idx > 0 ) - { - const int idx = d_data->pickedPoints.count(); - - const QPoint pos = d_data->pickedPoints[idx - 1]; - d_data->pickedPoints.resize( idx - 1 ); - - updateDisplay(); - Q_EMIT removed( pos ); - } - } -} - -/*! - \brief Validate and fixup the selection - - Accepts all selections unmodified - - \param selection Selection to validate and fixup - \return true, when accepted, false otherwise -*/ -bool QwtPicker::accept( QPolygon &selection ) const -{ - Q_UNUSED( selection ); - return true; -} - -/*! - A picker is active between begin() and end(). - \return true if the selection is active. -*/ -bool QwtPicker::isActive() const -{ - return d_data->isActive; -} - -/*! - Return the points, that have been collected so far. The selection() - is calculated from the pickedPoints() in adjustedPoints(). - \return Picked points -*/ -const QPolygon &QwtPicker::pickedPoints() const -{ - return d_data->pickedPoints; -} - -/*! - Scale the selection by the ratios of oldSize and newSize - The changed() signal is emitted. - - \param oldSize Previous size - \param newSize Current size - - \sa ResizeMode, setResizeMode(), resizeMode() -*/ -void QwtPicker::stretchSelection( const QSize &oldSize, const QSize &newSize ) -{ - if ( oldSize.isEmpty() ) - { - // avoid division by zero. But scaling for small sizes also - // doesn't make much sense, because of rounding losses. TODO ... - return; - } - - const double xRatio = - double( newSize.width() ) / double( oldSize.width() ); - const double yRatio = - double( newSize.height() ) / double( oldSize.height() ); - - for ( int i = 0; i < int( d_data->pickedPoints.count() ); i++ ) - { - QPoint &p = d_data->pickedPoints[i]; - p.setX( qRound( p.x() * xRatio ) ); - p.setY( qRound( p.y() * yRatio ) ); - - Q_EMIT changed( d_data->pickedPoints ); - } -} - -/*! - Set mouse tracking for the observed widget. - - In case of enable is true, the previous value - is saved, that is restored when enable is false. - - \warning Even when enable is false, mouse tracking might be restored - to true. When mouseTracking for the observed widget - has been changed directly by QWidget::setMouseTracking - while mouse tracking has been set to true, this value can't - be restored. -*/ - -void QwtPicker::setMouseTracking( bool enable ) -{ - QWidget *widget = parentWidget(); - if ( !widget ) - return; - - if ( enable ) - { - d_data->mouseTracking = widget->hasMouseTracking(); - widget->setMouseTracking( true ); - } - else - { - widget->setMouseTracking( d_data->mouseTracking ); - } -} - -/*! - Find the area of the observed widget, where selection might happen. - - \return parentWidget()->contentsRect() -*/ -QRect QwtPicker::pickRect() const -{ - const QWidget *widget = parentWidget(); - if ( widget ) - return widget->contentsRect(); - - return QRect(); -} - -//! Update the state of rubberband and tracker label -void QwtPicker::updateDisplay() -{ - QWidget *w = parentWidget(); - - bool showRubberband = false; - bool showTracker = false; - if ( w && w->isVisible() && d_data->enabled ) - { - if ( rubberBand() != NoRubberBand && isActive() && - rubberBandPen().style() != Qt::NoPen ) - { - showRubberband = true; - } - - if ( trackerMode() == AlwaysOn || - ( trackerMode() == ActiveOnly && isActive() ) ) - { - if ( trackerPen() != Qt::NoPen ) - showTracker = true; - } - } - - QPointer &rw = d_data->rubberBandWidget; - if ( showRubberband ) - { - if ( rw.isNull() ) - { - rw = new PickerWidget( this, w, PickerWidget::RubberBand ); - rw->resize( w->size() ); - } - rw->updateMask(); - rw->update(); // Needed, when the mask doesn't change - } - else - delete rw; - - QPointer &tw = d_data->trackerWidget; - if ( showTracker ) - { - if ( tw.isNull() ) - { - tw = new PickerWidget( this, w, PickerWidget::Text ); - tw->resize( w->size() ); - } - tw->setFont( d_data->trackerFont ); - tw->updateMask(); - tw->update(); // Needed, when the mask doesn't change - } - else - delete tw; -} - -//! \return Widget displaying the rubberband -const QWidget *QwtPicker::rubberBandWidget() const -{ - return d_data->rubberBandWidget; -} - -//! \return Widget displaying the tracker text -const QWidget *QwtPicker::trackerWidget() const -{ - return d_data->trackerWidget; -} - +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_picker.h" +#include "qwt_picker_machine.h" +#include "qwt_painter.h" +#include "qwt_math.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +class QwtPicker::PickerWidget: public QWidget +{ +public: + enum Type + { + RubberBand, + Text + }; + + PickerWidget( QwtPicker *, QWidget *, Type ); + void updateMask(); + + /* + For a tracker text with a background we can use the background + rect as mask. Also for "regular" Qt widgets >= 4.3.0 we + don't need to mask the text anymore. + */ + bool d_hasTextMask; + +protected: + virtual void paintEvent( QPaintEvent * ); + + QwtPicker *d_picker; + Type d_type; +}; + +class QwtPicker::PrivateData +{ +public: + bool enabled; + + QwtPickerMachine *stateMachine; + + QwtPicker::ResizeMode resizeMode; + + QwtPicker::RubberBand rubberBand; + QPen rubberBandPen; + + QwtPicker::DisplayMode trackerMode; + QPen trackerPen; + QFont trackerFont; + + QPolygon pickedPoints; + bool isActive; + QPoint trackerPosition; + + bool mouseTracking; // used to save previous value + + /* + On X11 the widget below the picker widgets gets paint events + with a region that is the bounding rect of the mask, if it is complex. + In case of (f.e) a CrossRubberBand and a text this creates complete + repaints of the widget. So we better use two different widgets. + */ + + QPointer rubberBandWidget; + QPointer trackerWidget; +}; + +QwtPicker::PickerWidget::PickerWidget( + QwtPicker *picker, QWidget *parent, Type type ): + QWidget( parent ), + d_hasTextMask( false ), + d_picker( picker ), + d_type( type ) +{ + setAttribute( Qt::WA_TransparentForMouseEvents ); + setAttribute( Qt::WA_NoSystemBackground ); + setFocusPolicy( Qt::NoFocus ); +} + +void QwtPicker::PickerWidget::updateMask() +{ + QRegion mask; + + if ( d_type == RubberBand ) + { + QBitmap bm( width(), height() ); + bm.fill( Qt::color0 ); + + QPainter painter( &bm ); + QPen pen = d_picker->rubberBandPen(); + pen.setColor( Qt::color1 ); + painter.setPen( pen ); + + d_picker->drawRubberBand( &painter ); + + mask = QRegion( bm ); + } + if ( d_type == Text ) + { + d_hasTextMask = parentWidget()->testAttribute( Qt::WA_PaintOnScreen ); + + if ( d_hasTextMask ) + { + const QwtText label = d_picker->trackerText( + d_picker->trackerPosition() ); + + if ( label.testPaintAttribute( QwtText::PaintBackground ) + && label.backgroundBrush().style() != Qt::NoBrush ) + { + if ( label.backgroundBrush().color().alpha() > 0 ) + { + // We don't need a text mask, when we have a background + d_hasTextMask = false; + } + } + } + + if ( d_hasTextMask ) + { + QBitmap bm( width(), height() ); + bm.fill( Qt::color0 ); + + QPainter painter( &bm ); + painter.setFont( font() ); + + QPen pen = d_picker->trackerPen(); + pen.setColor( Qt::color1 ); + painter.setPen( pen ); + + d_picker->drawTracker( &painter ); + + mask = QRegion( bm ); + } + else + { + mask = d_picker->trackerRect( font() ); + } + } + + QWidget *w = parentWidget(); + if ( w && !w->testAttribute( Qt::WA_PaintOnScreen ) ) + { + // The parent widget gets an update for its complete rectangle + // when the mask is changed in visible state. + // With this hide/show we only get an update for the + // previous mask. + + hide(); + } + setMask( mask ); + setVisible( !mask.isEmpty() ); +} + +void QwtPicker::PickerWidget::paintEvent( QPaintEvent *e ) +{ + QPainter painter( this ); + painter.setClipRegion( e->region() ); + + if ( d_type == RubberBand ) + { + painter.setPen( d_picker->rubberBandPen() ); + d_picker->drawRubberBand( &painter ); + } + + if ( d_type == Text ) + { + /* + If we have a text mask we simply fill the region of + the mask. This gives better results for antialiased fonts. + */ + if ( d_hasTextMask ) + { + painter.fillRect( e->rect(), + QBrush( d_picker->trackerPen().color() ) ); + } + else + { + painter.setPen( d_picker->trackerPen() ); + d_picker->drawTracker( &painter ); + } + } +} + +/*! + Constructor + + Creates an picker that is enabled, but without a state machine. + rubberband and tracker are disabled. + + \param parent Parent widget, that will be observed + */ + +QwtPicker::QwtPicker( QWidget *parent ): + QObject( parent ) +{ + init( parent, NoRubberBand, AlwaysOff ); +} + +/*! + Constructor + + \param rubberBand Rubberband style + \param trackerMode Tracker mode + \param parent Parent widget, that will be observed + */ +QwtPicker::QwtPicker( RubberBand rubberBand, + DisplayMode trackerMode, QWidget *parent ): + QObject( parent ) +{ + init( parent, rubberBand, trackerMode ); +} + +//! Destructor +QwtPicker::~QwtPicker() +{ + setMouseTracking( false ); + delete d_data->stateMachine; + delete d_data->rubberBandWidget; + delete d_data->trackerWidget; + delete d_data; +} + +//! Init the picker, used by the constructors +void QwtPicker::init( QWidget *parent, + RubberBand rubberBand, DisplayMode trackerMode ) +{ + d_data = new PrivateData; + + d_data->rubberBandWidget = NULL; + d_data->trackerWidget = NULL; + + d_data->rubberBand = rubberBand; + d_data->enabled = false; + d_data->resizeMode = Stretch; + d_data->trackerMode = AlwaysOff; + d_data->isActive = false; + d_data->trackerPosition = QPoint( -1, -1 ); + d_data->mouseTracking = false; + + d_data->stateMachine = NULL; + + if ( parent ) + { + if ( parent->focusPolicy() == Qt::NoFocus ) + parent->setFocusPolicy( Qt::WheelFocus ); + + d_data->trackerFont = parent->font(); + d_data->mouseTracking = parent->hasMouseTracking(); + setEnabled( true ); + } + setTrackerMode( trackerMode ); +} + +/*! + Set a state machine and delete the previous one + + \param stateMachine State machine + \sa stateMachine() +*/ +void QwtPicker::setStateMachine( QwtPickerMachine *stateMachine ) +{ + if ( d_data->stateMachine != stateMachine ) + { + reset(); + + delete d_data->stateMachine; + d_data->stateMachine = stateMachine; + + if ( d_data->stateMachine ) + d_data->stateMachine->reset(); + } +} + +/*! + \return Assigned state machine + \sa setStateMachine() +*/ +QwtPickerMachine *QwtPicker::stateMachine() +{ + return d_data->stateMachine; +} + +/*! + \return Assigned state machine + \sa setStateMachine() +*/ +const QwtPickerMachine *QwtPicker::stateMachine() const +{ + return d_data->stateMachine; +} + +//! Return the parent widget, where the selection happens +QWidget *QwtPicker::parentWidget() +{ + QObject *obj = parent(); + if ( obj && obj->isWidgetType() ) + return static_cast( obj ); + + return NULL; +} + +//! Return the parent widget, where the selection happens +const QWidget *QwtPicker::parentWidget() const +{ + QObject *obj = parent(); + if ( obj && obj->isWidgetType() ) + return static_cast< const QWidget *>( obj ); + + return NULL; +} + +/*! + Set the rubberband style + + \param rubberBand Rubberband style + The default value is NoRubberBand. + + \sa rubberBand(), RubberBand, setRubberBandPen() +*/ +void QwtPicker::setRubberBand( RubberBand rubberBand ) +{ + d_data->rubberBand = rubberBand; +} + +/*! + \return Rubberband style + \sa setRubberBand(), RubberBand, rubberBandPen() +*/ +QwtPicker::RubberBand QwtPicker::rubberBand() const +{ + return d_data->rubberBand; +} + +/*! + \brief Set the display mode of the tracker. + + A tracker displays information about current position of + the cursor as a string. The display mode controls + if the tracker has to be displayed whenever the observed + widget has focus and cursor (AlwaysOn), never (AlwaysOff), or + only when the selection is active (ActiveOnly). + + \param mode Tracker display mode + + \warning In case of AlwaysOn, mouseTracking will be enabled + for the observed widget. + \sa trackerMode(), DisplayMode +*/ + +void QwtPicker::setTrackerMode( DisplayMode mode ) +{ + if ( d_data->trackerMode != mode ) + { + d_data->trackerMode = mode; + setMouseTracking( d_data->trackerMode == AlwaysOn ); + } +} + +/*! + \return Tracker display mode + \sa setTrackerMode(), DisplayMode +*/ +QwtPicker::DisplayMode QwtPicker::trackerMode() const +{ + return d_data->trackerMode; +} + +/*! + \brief Set the resize mode. + + The resize mode controls what to do with the selected points of an active + selection when the observed widget is resized. + + Stretch means the points are scaled according to the new + size, KeepSize means the points remain unchanged. + + The default mode is Stretch. + + \param mode Resize mode + \sa resizeMode(), ResizeMode +*/ +void QwtPicker::setResizeMode( ResizeMode mode ) +{ + d_data->resizeMode = mode; +} + +/*! + \return Resize mode + \sa setResizeMode(), ResizeMode +*/ + +QwtPicker::ResizeMode QwtPicker::resizeMode() const +{ + return d_data->resizeMode; +} + +/*! + \brief En/disable the picker + + When enabled is true an event filter is installed for + the observed widget, otherwise the event filter is removed. + + \param enabled true or false + \sa isEnabled(), eventFilter() +*/ +void QwtPicker::setEnabled( bool enabled ) +{ + if ( d_data->enabled != enabled ) + { + d_data->enabled = enabled; + + QWidget *w = parentWidget(); + if ( w ) + { + if ( enabled ) + w->installEventFilter( this ); + else + w->removeEventFilter( this ); + } + + updateDisplay(); + } +} + +/*! + \return true when enabled, false otherwise + \sa setEnabled(), eventFilter() +*/ + +bool QwtPicker::isEnabled() const +{ + return d_data->enabled; +} + +/*! + Set the font for the tracker + + \param font Tracker font + \sa trackerFont(), setTrackerMode(), setTrackerPen() +*/ +void QwtPicker::setTrackerFont( const QFont &font ) +{ + if ( font != d_data->trackerFont ) + { + d_data->trackerFont = font; + updateDisplay(); + } +} + +/*! + \return Tracker font + \sa setTrackerFont(), trackerMode(), trackerPen() +*/ + +QFont QwtPicker::trackerFont() const +{ + return d_data->trackerFont; +} + +/*! + Set the pen for the tracker + + \param pen Tracker pen + \sa trackerPen(), setTrackerMode(), setTrackerFont() +*/ +void QwtPicker::setTrackerPen( const QPen &pen ) +{ + if ( pen != d_data->trackerPen ) + { + d_data->trackerPen = pen; + updateDisplay(); + } +} + +/*! + \return Tracker pen + \sa setTrackerPen(), trackerMode(), trackerFont() +*/ +QPen QwtPicker::trackerPen() const +{ + return d_data->trackerPen; +} + +/*! + Set the pen for the rubberband + + \param pen Rubberband pen + \sa rubberBandPen(), setRubberBand() +*/ +void QwtPicker::setRubberBandPen( const QPen &pen ) +{ + if ( pen != d_data->rubberBandPen ) + { + d_data->rubberBandPen = pen; + updateDisplay(); + } +} + +/*! + \return Rubberband pen + \sa setRubberBandPen(), rubberBand() +*/ +QPen QwtPicker::rubberBandPen() const +{ + return d_data->rubberBandPen; +} + +/*! + \brief Return the label for a position + + In case of HLineRubberBand the label is the value of the + y position, in case of VLineRubberBand the value of the x position. + Otherwise the label contains x and y position separated by a ',' . + + The format for the string conversion is "%d". + + \param pos Position + \return Converted position as string +*/ + +QwtText QwtPicker::trackerText( const QPoint &pos ) const +{ + QString label; + + switch ( rubberBand() ) + { + case HLineRubberBand: + label.sprintf( "%d", pos.y() ); + break; + case VLineRubberBand: + label.sprintf( "%d", pos.x() ); + break; + default: + label.sprintf( "%d, %d", pos.x(), pos.y() ); + } + return label; +} + +/*! + Draw a rubberband, depending on rubberBand() + + \param painter Painter, initialized with clip rect + + \sa rubberBand(), RubberBand +*/ + +void QwtPicker::drawRubberBand( QPainter *painter ) const +{ + if ( !isActive() || rubberBand() == NoRubberBand || + rubberBandPen().style() == Qt::NoPen ) + { + return; + } + + const QRect &pRect = pickRect(); + const QPolygon pa = adjustedPoints( d_data->pickedPoints ); + + QwtPickerMachine::SelectionType selectionType = + QwtPickerMachine::NoSelection; + + if ( d_data->stateMachine ) + selectionType = d_data->stateMachine->selectionType(); + + switch ( selectionType ) + { + case QwtPickerMachine::NoSelection: + case QwtPickerMachine::PointSelection: + { + if ( pa.count() < 1 ) + return; + + const QPoint pos = pa[0]; + + switch ( rubberBand() ) + { + case VLineRubberBand: + QwtPainter::drawLine( painter, pos.x(), + pRect.top(), pos.x(), pRect.bottom() ); + break; + + case HLineRubberBand: + QwtPainter::drawLine( painter, pRect.left(), + pos.y(), pRect.right(), pos.y() ); + break; + + case CrossRubberBand: + QwtPainter::drawLine( painter, pos.x(), + pRect.top(), pos.x(), pRect.bottom() ); + QwtPainter::drawLine( painter, pRect.left(), + pos.y(), pRect.right(), pos.y() ); + break; + default: + break; + } + break; + } + case QwtPickerMachine::RectSelection: + { + if ( pa.count() < 2 ) + return; + + const QPoint p1 = pa[0]; + const QPoint p2 = pa[int( pa.count() - 1 )]; + + const QRect rect = QRect( p1, p2 ).normalized(); + switch ( rubberBand() ) + { + case EllipseRubberBand: + QwtPainter::drawEllipse( painter, rect ); + break; + case RectRubberBand: + QwtPainter::drawRect( painter, rect ); + break; + default: + break; + } + break; + } + case QwtPickerMachine::PolygonSelection: + { + if ( rubberBand() == PolygonRubberBand ) + painter->drawPolyline( pa ); + break; + } + default: + break; + } +} + +/*! + Draw the tracker + + \param painter Painter + \sa trackerRect(), trackerText() +*/ + +void QwtPicker::drawTracker( QPainter *painter ) const +{ + const QRect textRect = trackerRect( painter->font() ); + if ( !textRect.isEmpty() ) + { + const QwtText label = trackerText( d_data->trackerPosition ); + if ( !label.isEmpty() ) + label.draw( painter, textRect ); + } +} + +/*! + \brief Map the pickedPoints() into a selection() + + adjustedPoints() maps the points, that have been collected on + the parentWidget() into a selection(). The default implementation + simply returns the points unmodified. + + The reason, why a selection() differs from the picked points + depends on the application requirements. F.e. : + + - A rectangular selection might need to have a specific aspect ratio only.\n + - A selection could accept non intersecting polygons only.\n + - ...\n + + The example below is for a rectangular selection, where the first + point is the center of the selected rectangle. + \par Example + \verbatim QPolygon MyPicker::adjustedPoints(const QPolygon &points) const +{ + QPolygon adjusted; + if ( points.size() == 2 ) + { + const int width = qAbs(points[1].x() - points[0].x()); + const int height = qAbs(points[1].y() - points[0].y()); + + QRect rect(0, 0, 2 * width, 2 * height); + rect.moveCenter(points[0]); + + adjusted += rect.topLeft(); + adjusted += rect.bottomRight(); + } + return adjusted; +}\endverbatim\n +*/ +QPolygon QwtPicker::adjustedPoints( const QPolygon &points ) const +{ + return points; +} + +/*! + \return Selected points + \sa pickedPoints(), adjustedPoints() +*/ +QPolygon QwtPicker::selection() const +{ + return adjustedPoints( d_data->pickedPoints ); +} + +//! \return Current position of the tracker +QPoint QwtPicker::trackerPosition() const +{ + return d_data->trackerPosition; +} + +/*! + Calculate the bounding rectangle for the tracker text + from the current position of the tracker + + \param font Font of the tracker text + \return Bounding rectangle of the tracker text + + \sa trackerPosition() +*/ +QRect QwtPicker::trackerRect( const QFont &font ) const +{ + if ( trackerMode() == AlwaysOff || + ( trackerMode() == ActiveOnly && !isActive() ) ) + { + return QRect(); + } + + if ( d_data->trackerPosition.x() < 0 || d_data->trackerPosition.y() < 0 ) + return QRect(); + + QwtText text = trackerText( d_data->trackerPosition ); + if ( text.isEmpty() ) + return QRect(); + + const QSizeF textSize = text.textSize( font ); + QRect textRect( 0, 0, qCeil( textSize.width() ), qCeil( textSize.height() ) ); + + const QPoint &pos = d_data->trackerPosition; + + int alignment = 0; + if ( isActive() && d_data->pickedPoints.count() > 1 + && rubberBand() != NoRubberBand ) + { + const QPoint last = + d_data->pickedPoints[int( d_data->pickedPoints.count() ) - 2]; + + alignment |= ( pos.x() >= last.x() ) ? Qt::AlignRight : Qt::AlignLeft; + alignment |= ( pos.y() > last.y() ) ? Qt::AlignBottom : Qt::AlignTop; + } + else + alignment = Qt::AlignTop | Qt::AlignRight; + + const int margin = 5; + + int x = pos.x(); + if ( alignment & Qt::AlignLeft ) + x -= textRect.width() + margin; + else if ( alignment & Qt::AlignRight ) + x += margin; + + int y = pos.y(); + if ( alignment & Qt::AlignBottom ) + y += margin; + else if ( alignment & Qt::AlignTop ) + y -= textRect.height() + margin; + + textRect.moveTopLeft( QPoint( x, y ) ); + + int right = qMin( textRect.right(), pickRect().right() - margin ); + int bottom = qMin( textRect.bottom(), pickRect().bottom() - margin ); + textRect.moveBottomRight( QPoint( right, bottom ) ); + + int left = qMax( textRect.left(), pickRect().left() + margin ); + int top = qMax( textRect.top(), pickRect().top() + margin ); + textRect.moveTopLeft( QPoint( left, top ) ); + + return textRect; +} + +/*! + \brief Event filter + + When isEnabled() == true all events of the observed widget are filtered. + Mouse and keyboard events are translated into widgetMouse- and widgetKey- + and widgetWheel-events. Paint and Resize events are handled to keep + rubberband and tracker up to date. + + \param object Object to be filtered + \param event Event + + \sa widgetEnterEvent(), widgetLeaveEvent(), + widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), + widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent(), + QObject::installEventFilter(), QObject::event() +*/ +bool QwtPicker::eventFilter( QObject *object, QEvent *event ) +{ + if ( object && object == parentWidget() ) + { + switch ( event->type() ) + { + case QEvent::Resize: + { + const QResizeEvent *re = ( QResizeEvent * )event; + if ( d_data->resizeMode == Stretch ) + stretchSelection( re->oldSize(), re->size() ); + + if ( d_data->rubberBandWidget ) + d_data->rubberBandWidget->resize( re->size() ); + + if ( d_data->trackerWidget ) + d_data->trackerWidget->resize( re->size() ); + break; + } + case QEvent::Enter: + widgetEnterEvent( event ); + break; + case QEvent::Leave: + widgetLeaveEvent( event ); + break; + case QEvent::MouseButtonPress: + widgetMousePressEvent( ( QMouseEvent * )event ); + break; + case QEvent::MouseButtonRelease: + widgetMouseReleaseEvent( ( QMouseEvent * )event ); + break; + case QEvent::MouseButtonDblClick: + widgetMouseDoubleClickEvent( ( QMouseEvent * )event ); + break; + case QEvent::MouseMove: + widgetMouseMoveEvent( ( QMouseEvent * )event ); + break; + case QEvent::KeyPress: + widgetKeyPressEvent( ( QKeyEvent * )event ); + break; + case QEvent::KeyRelease: + widgetKeyReleaseEvent( ( QKeyEvent * )event ); + break; + case QEvent::Wheel: + widgetWheelEvent( ( QWheelEvent * )event ); + break; + default: + break; + } + } + return false; +} + +/*! + Handle a mouse press event for the observed widget. + + \param mouseEvent Mouse event + + \sa eventFilter(), widgetMouseReleaseEvent(), + widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), + widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() +*/ +void QwtPicker::widgetMousePressEvent( QMouseEvent *mouseEvent ) +{ + transition( mouseEvent ); +} + +/*! + Handle a mouse move event for the observed widget. + + \param mouseEvent Mouse event + + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseDoubleClickEvent(), + widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() +*/ +void QwtPicker::widgetMouseMoveEvent( QMouseEvent *mouseEvent ) +{ + if ( pickRect().contains( mouseEvent->pos() ) ) + d_data->trackerPosition = mouseEvent->pos(); + else + d_data->trackerPosition = QPoint( -1, -1 ); + + if ( !isActive() ) + updateDisplay(); + + transition( mouseEvent ); +} + +/*! + Handle a enter event for the observed widget. + + \param event Qt event + + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseDoubleClickEvent(), + widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() +*/ +void QwtPicker::widgetEnterEvent( QEvent *event ) +{ + transition( event ); +} + +/*! + Handle a leave event for the observed widget. + + \param event Qt event + + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseDoubleClickEvent(), + widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() +*/ +void QwtPicker::widgetLeaveEvent( QEvent *event ) +{ + transition( event ); + + d_data->trackerPosition = QPoint( -1, -1 ); + if ( !isActive() ) + updateDisplay(); +} + +/*! + Handle a mouse relase event for the observed widget. + + \param mouseEvent Mouse event + + \sa eventFilter(), widgetMousePressEvent(), + widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), + widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() +*/ +void QwtPicker::widgetMouseReleaseEvent( QMouseEvent *mouseEvent ) +{ + transition( mouseEvent ); +} + +/*! + Handle mouse double click event for the observed widget. + + \param mouseEvent Mouse event + + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseMoveEvent(), + widgetWheelEvent(), widgetKeyPressEvent(), widgetKeyReleaseEvent() +*/ +void QwtPicker::widgetMouseDoubleClickEvent( QMouseEvent *mouseEvent ) +{ + transition( mouseEvent ); +} + + +/*! + Handle a wheel event for the observed widget. + + Move the last point of the selection in case of isActive() == true + + \param wheelEvent Wheel event + + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), + widgetKeyPressEvent(), widgetKeyReleaseEvent() +*/ +void QwtPicker::widgetWheelEvent( QWheelEvent *wheelEvent ) +{ + if ( pickRect().contains( wheelEvent->pos() ) ) + d_data->trackerPosition = wheelEvent->pos(); + else + d_data->trackerPosition = QPoint( -1, -1 ); + + updateDisplay(); + + transition( wheelEvent ); +} + +/*! + Handle a key press event for the observed widget. + + Selections can be completely done by the keyboard. The arrow keys + move the cursor, the abort key aborts a selection. All other keys + are handled by the current state machine. + + \param keyEvent Key event + + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), + widgetWheelEvent(), widgetKeyReleaseEvent(), stateMachine(), + QwtEventPattern::KeyPatternCode +*/ +void QwtPicker::widgetKeyPressEvent( QKeyEvent *keyEvent ) +{ + int dx = 0; + int dy = 0; + + int offset = 1; + if ( keyEvent->isAutoRepeat() ) + offset = 5; + + if ( keyMatch( KeyLeft, keyEvent ) ) + dx = -offset; + else if ( keyMatch( KeyRight, keyEvent ) ) + dx = offset; + else if ( keyMatch( KeyUp, keyEvent ) ) + dy = -offset; + else if ( keyMatch( KeyDown, keyEvent ) ) + dy = offset; + else if ( keyMatch( KeyAbort, keyEvent ) ) + { + reset(); + } + else + transition( keyEvent ); + + if ( dx != 0 || dy != 0 ) + { + const QRect rect = pickRect(); + const QPoint pos = parentWidget()->mapFromGlobal( QCursor::pos() ); + + int x = pos.x() + dx; + x = qMax( rect.left(), x ); + x = qMin( rect.right(), x ); + + int y = pos.y() + dy; + y = qMax( rect.top(), y ); + y = qMin( rect.bottom(), y ); + + QCursor::setPos( parentWidget()->mapToGlobal( QPoint( x, y ) ) ); + } +} + +/*! + Handle a key release event for the observed widget. + + Passes the event to the state machine. + + \param keyEvent Key event + + \sa eventFilter(), widgetMousePressEvent(), widgetMouseReleaseEvent(), + widgetMouseDoubleClickEvent(), widgetMouseMoveEvent(), + widgetWheelEvent(), widgetKeyPressEvent(), stateMachine() +*/ +void QwtPicker::widgetKeyReleaseEvent( QKeyEvent *keyEvent ) +{ + transition( keyEvent ); +} + +/*! + Passes an event to the state machine and executes the resulting + commands. Append and Move commands use the current position + of the cursor (QCursor::pos()). + + \param event Event +*/ +void QwtPicker::transition( const QEvent *event ) +{ + if ( !d_data->stateMachine ) + return; + + const QList commandList = + d_data->stateMachine->transition( *this, event ); + + QPoint pos; + switch ( event->type() ) + { + case QEvent::MouseButtonDblClick: + case QEvent::MouseButtonPress: + case QEvent::MouseButtonRelease: + case QEvent::MouseMove: + { + const QMouseEvent *me = + static_cast< const QMouseEvent * >( event ); + pos = me->pos(); + break; + } + default: + pos = parentWidget()->mapFromGlobal( QCursor::pos() ); + } + + for ( int i = 0; i < commandList.count(); i++ ) + { + switch ( commandList[i] ) + { + case QwtPickerMachine::Begin: + { + begin(); + break; + } + case QwtPickerMachine::Append: + { + append( pos ); + break; + } + case QwtPickerMachine::Move: + { + move( pos ); + break; + } + case QwtPickerMachine::Remove: + { + remove(); + break; + } + case QwtPickerMachine::End: + { + end(); + break; + } + } + } +} + +/*! + Open a selection setting the state to active + + \sa isActive(), end(), append(), move() +*/ +void QwtPicker::begin() +{ + if ( d_data->isActive ) + return; + + d_data->pickedPoints.resize( 0 ); + d_data->isActive = true; + Q_EMIT activated( true ); + + if ( trackerMode() != AlwaysOff ) + { + if ( d_data->trackerPosition.x() < 0 || d_data->trackerPosition.y() < 0 ) + { + QWidget *w = parentWidget(); + if ( w ) + d_data->trackerPosition = w->mapFromGlobal( QCursor::pos() ); + } + } + + updateDisplay(); + setMouseTracking( true ); +} + +/*! + \brief Close a selection setting the state to inactive. + + The selection is validated and maybe fixed by accept(). + + \param ok If true, complete the selection and emit a selected signal + otherwise discard the selection. + \return true if the selection is accepted, false otherwise + \sa isActive(), begin(), append(), move(), selected(), accept() +*/ +bool QwtPicker::end( bool ok ) +{ + if ( d_data->isActive ) + { + setMouseTracking( false ); + + d_data->isActive = false; + Q_EMIT activated( false ); + + if ( trackerMode() == ActiveOnly ) + d_data->trackerPosition = QPoint( -1, -1 ); + + if ( ok ) + ok = accept( d_data->pickedPoints ); + + if ( ok ) + Q_EMIT selected( d_data->pickedPoints ); + else + d_data->pickedPoints.resize( 0 ); + + updateDisplay(); + } + else + ok = false; + + return ok; +} + +/*! + Reset the state machine and terminate (end(false)) the selection +*/ +void QwtPicker::reset() +{ + if ( d_data->stateMachine ) + d_data->stateMachine->reset(); + + if ( isActive() ) + end( false ); +} + +/*! + Append a point to the selection and update rubberband and tracker. + The appended() signal is emitted. + + \param pos Additional point + + \sa isActive(), begin(), end(), move(), appended() +*/ +void QwtPicker::append( const QPoint &pos ) +{ + if ( d_data->isActive ) + { + const int idx = d_data->pickedPoints.count(); + d_data->pickedPoints.resize( idx + 1 ); + d_data->pickedPoints[idx] = pos; + + updateDisplay(); + Q_EMIT appended( pos ); + } +} + +/*! + Move the last point of the selection + The moved() signal is emitted. + + \param pos New position + \sa isActive(), begin(), end(), append() +*/ +void QwtPicker::move( const QPoint &pos ) +{ + if ( d_data->isActive ) + { + const int idx = d_data->pickedPoints.count() - 1; + if ( idx >= 0 ) + { + if ( d_data->pickedPoints[idx] != pos ) + { + d_data->pickedPoints[idx] = pos; + + updateDisplay(); + Q_EMIT moved( pos ); + } + } + } +} + +/*! + Remove the last point of the selection + The removed() signal is emitted. + + \sa isActive(), begin(), end(), append(), move() +*/ +void QwtPicker::remove() +{ + if ( d_data->isActive ) + { + const int idx = d_data->pickedPoints.count() - 1; + if ( idx > 0 ) + { + const int idx = d_data->pickedPoints.count(); + + const QPoint pos = d_data->pickedPoints[idx - 1]; + d_data->pickedPoints.resize( idx - 1 ); + + updateDisplay(); + Q_EMIT removed( pos ); + } + } +} + +/*! + \brief Validate and fixup the selection + + Accepts all selections unmodified + + \param selection Selection to validate and fixup + \return true, when accepted, false otherwise +*/ +bool QwtPicker::accept( QPolygon &selection ) const +{ + Q_UNUSED( selection ); + return true; +} + +/*! + A picker is active between begin() and end(). + \return true if the selection is active. +*/ +bool QwtPicker::isActive() const +{ + return d_data->isActive; +} + +/*! + Return the points, that have been collected so far. The selection() + is calculated from the pickedPoints() in adjustedPoints(). + \return Picked points +*/ +const QPolygon &QwtPicker::pickedPoints() const +{ + return d_data->pickedPoints; +} + +/*! + Scale the selection by the ratios of oldSize and newSize + The changed() signal is emitted. + + \param oldSize Previous size + \param newSize Current size + + \sa ResizeMode, setResizeMode(), resizeMode() +*/ +void QwtPicker::stretchSelection( const QSize &oldSize, const QSize &newSize ) +{ + if ( oldSize.isEmpty() ) + { + // avoid division by zero. But scaling for small sizes also + // doesn't make much sense, because of rounding losses. TODO ... + return; + } + + const double xRatio = + double( newSize.width() ) / double( oldSize.width() ); + const double yRatio = + double( newSize.height() ) / double( oldSize.height() ); + + for ( int i = 0; i < int( d_data->pickedPoints.count() ); i++ ) + { + QPoint &p = d_data->pickedPoints[i]; + p.setX( qRound( p.x() * xRatio ) ); + p.setY( qRound( p.y() * yRatio ) ); + + Q_EMIT changed( d_data->pickedPoints ); + } +} + +/*! + Set mouse tracking for the observed widget. + + In case of enable is true, the previous value + is saved, that is restored when enable is false. + + \warning Even when enable is false, mouse tracking might be restored + to true. When mouseTracking for the observed widget + has been changed directly by QWidget::setMouseTracking + while mouse tracking has been set to true, this value can't + be restored. +*/ + +void QwtPicker::setMouseTracking( bool enable ) +{ + QWidget *widget = parentWidget(); + if ( !widget ) + return; + + if ( enable ) + { + d_data->mouseTracking = widget->hasMouseTracking(); + widget->setMouseTracking( true ); + } + else + { + widget->setMouseTracking( d_data->mouseTracking ); + } +} + +/*! + Find the area of the observed widget, where selection might happen. + + \return parentWidget()->contentsRect() +*/ +QRect QwtPicker::pickRect() const +{ + const QWidget *widget = parentWidget(); + if ( widget ) + return widget->contentsRect(); + + return QRect(); +} + +//! Update the state of rubberband and tracker label +void QwtPicker::updateDisplay() +{ + QWidget *w = parentWidget(); + + bool showRubberband = false; + bool showTracker = false; + if ( w && w->isVisible() && d_data->enabled ) + { + if ( rubberBand() != NoRubberBand && isActive() && + rubberBandPen().style() != Qt::NoPen ) + { + showRubberband = true; + } + + if ( trackerMode() == AlwaysOn || + ( trackerMode() == ActiveOnly && isActive() ) ) + { + if ( trackerPen() != Qt::NoPen ) + showTracker = true; + } + } + + QPointer &rw = d_data->rubberBandWidget; + if ( showRubberband ) + { + if ( rw.isNull() ) + { + rw = new PickerWidget( this, w, PickerWidget::RubberBand ); + rw->resize( w->size() ); + } + rw->updateMask(); + rw->update(); // Needed, when the mask doesn't change + } + else + delete rw; + + QPointer &tw = d_data->trackerWidget; + if ( showTracker ) + { + if ( tw.isNull() ) + { + tw = new PickerWidget( this, w, PickerWidget::Text ); + tw->resize( w->size() ); + } + tw->setFont( d_data->trackerFont ); + tw->updateMask(); + tw->update(); // Needed, when the mask doesn't change + } + else + delete tw; +} + +//! \return Widget displaying the rubberband +const QWidget *QwtPicker::rubberBandWidget() const +{ + return d_data->rubberBandWidget; +} + +//! \return Widget displaying the tracker text +const QWidget *QwtPicker::trackerWidget() const +{ + return d_data->trackerWidget; +} + diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_picker.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_picker.h index 5049f71e3..c0b22dcdf 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_picker.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_picker.h @@ -1,327 +1,327 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PICKER -#define QWT_PICKER 1 - -#include "qwt_global.h" -#include "qwt_text.h" -#include "qwt_event_pattern.h" -#include -#include -#include -#include - -class QWidget; -class QMouseEvent; -class QWheelEvent; -class QKeyEvent; -class QwtPickerMachine; - -/*! - \brief QwtPicker provides selections on a widget - - QwtPicker filters all enter, leave, mouse and keyboard events of a widget - and translates them into an array of selected points. - - The way how the points are collected depends on type of state machine - that is connected to the picker. Qwt offers a couple of predefined - state machines for selecting: - - - Nothing\n - QwtPickerTrackerMachine - - Single points\n - QwtPickerClickPointMachine, QwtPickerDragPointMachine - - Rectangles\n - QwtPickerClickRectMachine, QwtPickerDragRectMachine - - Polygons\n - QwtPickerPolygonMachine - - While these state machines cover the most common ways to collect points - it is also possible to implement individual machines as well. - - QwtPicker translates the picked points into a selection using the - adjustedPoints method. adjustedPoints is intended to be reimplemented - to fixup the selection according to application specific requirements. - (F.e. when an application accepts rectangles of a fixed aspect ratio only.) - - Optionally QwtPicker support the process of collecting points by a - rubberband and tracker displaying a text for the current mouse - position. - - \par Example - \verbatim #include -#include - -QwtPicker *picker = new QwtPicker(widget); -picker->setStateMachine(new QwtPickerDragRectMachine); -picker->setTrackerMode(QwtPicker::ActiveOnly); -picker->setRubberBand(QwtPicker::RectRubberBand); \endverbatim\n - - The state machine triggers the following commands: - - - begin()\n - Activate/Initialize the selection. - - append()\n - Add a new point - - move() \n - Change the position of the last point. - - remove()\n - Remove the last point. - - end()\n - Terminate the selection and call accept to validate the picked points. - - The picker is active (isActive()), between begin() and end(). - In active state the rubberband is displayed, and the tracker is visible - in case of trackerMode is ActiveOnly or AlwaysOn. - - The cursor can be moved using the arrow keys. All selections can be aborted - using the abort key. (QwtEventPattern::KeyPatternCode) - - \warning In case of QWidget::NoFocus the focus policy of the observed - widget is set to QWidget::WheelFocus and mouse tracking - will be manipulated while the picker is active, - or if trackerMode() is AlwayOn. -*/ - -class QWT_EXPORT QwtPicker: public QObject, public QwtEventPattern -{ - Q_OBJECT - - Q_ENUMS( RubberBand ) - Q_ENUMS( DisplayMode ) - Q_ENUMS( ResizeMode ) - - Q_PROPERTY( bool isEnabled READ isEnabled WRITE setEnabled ) - Q_PROPERTY( ResizeMode resizeMode READ resizeMode WRITE setResizeMode ) - - Q_PROPERTY( DisplayMode trackerMode READ trackerMode WRITE setTrackerMode ) - Q_PROPERTY( QPen trackerPen READ trackerPen WRITE setTrackerPen ) - Q_PROPERTY( QFont trackerFont READ trackerFont WRITE setTrackerFont ) - - Q_PROPERTY( RubberBand rubberBand READ rubberBand WRITE setRubberBand ) - Q_PROPERTY( QPen rubberBandPen READ rubberBandPen WRITE setRubberBandPen ) - -public: - /*! - Rubberband style - - The default value is QwtPicker::NoRubberBand. - \sa setRubberBand(), rubberBand() - */ - - enum RubberBand - { - //! No rubberband. - NoRubberBand = 0, - - //! A horizontal line ( only for QwtPicker::PointSelection ) - HLineRubberBand, - - //! A vertical line ( only for QwtPicker::PointSelection ) - VLineRubberBand, - - //! A crosshair ( only for QwtPicker::PointSelection ) - CrossRubberBand, - - //! A rectangle ( only for QwtPicker::RectSelection ) - RectRubberBand, - - //! An ellipse ( only for QwtPicker::RectSelection ) - EllipseRubberBand, - - //! A polygon ( only for QwtPicker::&PolygonSelection ) - PolygonRubberBand, - - /*! - Values >= UserRubberBand can be used to define additional - rubber bands. - */ - UserRubberBand = 100 - }; - - /*! - \brief Display mode - \sa setTrackerMode(), trackerMode(), isActive() - */ - enum DisplayMode - { - //! Display never - AlwaysOff, - - //! Display always - AlwaysOn, - - //! Display only when the selection is active - ActiveOnly - }; - - /*! - Controls what to do with the selected points of an active - selection when the observed widget is resized. - - The default value is QwtPicker::Stretch. - \sa setResizeMode() - */ - - enum ResizeMode - { - //! All points are scaled according to the new size, - Stretch, - - //! All points remain unchanged. - KeepSize - }; - - explicit QwtPicker( QWidget *parent ); - explicit QwtPicker( RubberBand rubberBand, - DisplayMode trackerMode, QWidget * ); - - virtual ~QwtPicker(); - - void setStateMachine( QwtPickerMachine * ); - const QwtPickerMachine *stateMachine() const; - QwtPickerMachine *stateMachine(); - - void setRubberBand( RubberBand ); - RubberBand rubberBand() const; - - void setTrackerMode( DisplayMode ); - DisplayMode trackerMode() const; - - void setResizeMode( ResizeMode ); - ResizeMode resizeMode() const; - - void setRubberBandPen( const QPen & ); - QPen rubberBandPen() const; - - void setTrackerPen( const QPen & ); - QPen trackerPen() const; - - void setTrackerFont( const QFont & ); - QFont trackerFont() const; - - bool isEnabled() const; - bool isActive() const; - - virtual bool eventFilter( QObject *, QEvent * ); - - QWidget *parentWidget(); - const QWidget *parentWidget() const; - - virtual QRect pickRect() const; - - virtual void drawRubberBand( QPainter * ) const; - virtual void drawTracker( QPainter * ) const; - - virtual QwtText trackerText( const QPoint &pos ) const; - QPoint trackerPosition() const; - virtual QRect trackerRect( const QFont & ) const; - - QPolygon selection() const; - -public Q_SLOTS: - void setEnabled( bool ); - -Q_SIGNALS: - /*! - A signal indicating, when the picker has been activated. - Together with setEnabled() it can be used to implement - selections with more than one picker. - - \param on True, when the picker has been activated - */ - void activated( bool on ); - - /*! - A signal emitting the selected points, - at the end of a selection. - - \param polygon Selected points - */ - void selected( const QPolygon &polygon ); - - /*! - A signal emitted when a point has been appended to the selection - - \param pos Position of the appended point. - \sa append(). moved() - */ - void appended( const QPoint &pos ); - - /*! - A signal emitted whenever the last appended point of the - selection has been moved. - - \param pos Position of the moved last point of the selection. - \sa move(), appended() - */ - void moved( const QPoint &pos ); - - /*! - A signal emitted whenever the last appended point of the - selection has been removed. - - \sa remove(), appended() - */ - void removed( const QPoint &pos ); - /*! - A signal emitted when the active selection has been changed. - This might happen when the observed widget is resized. - - \param selection Changed selection - \sa stretchSelection() - */ - void changed( const QPolygon &selection ); - -protected: - virtual QPolygon adjustedPoints( const QPolygon & ) const; - - virtual void transition( const QEvent * ); - - virtual void begin(); - virtual void append( const QPoint & ); - virtual void move( const QPoint & ); - virtual void remove(); - virtual bool end( bool ok = true ); - - virtual bool accept( QPolygon & ) const; - virtual void reset(); - - virtual void widgetMousePressEvent( QMouseEvent * ); - virtual void widgetMouseReleaseEvent( QMouseEvent * ); - virtual void widgetMouseDoubleClickEvent( QMouseEvent * ); - virtual void widgetMouseMoveEvent( QMouseEvent * ); - virtual void widgetWheelEvent( QWheelEvent * ); - virtual void widgetKeyPressEvent( QKeyEvent * ); - virtual void widgetKeyReleaseEvent( QKeyEvent * ); - virtual void widgetEnterEvent( QEvent * ); - virtual void widgetLeaveEvent( QEvent * ); - - virtual void stretchSelection( const QSize &oldSize, - const QSize &newSize ); - - virtual void updateDisplay(); - - const QWidget *rubberBandWidget() const; - const QWidget *trackerWidget() const; - - const QPolygon &pickedPoints() const; - -private: - void init( QWidget *, RubberBand rubberBand, DisplayMode trackerMode ); - - void setMouseTracking( bool ); - - class PickerWidget; - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PICKER +#define QWT_PICKER 1 + +#include "qwt_global.h" +#include "qwt_text.h" +#include "qwt_event_pattern.h" +#include +#include +#include +#include + +class QWidget; +class QMouseEvent; +class QWheelEvent; +class QKeyEvent; +class QwtPickerMachine; + +/*! + \brief QwtPicker provides selections on a widget + + QwtPicker filters all enter, leave, mouse and keyboard events of a widget + and translates them into an array of selected points. + + The way how the points are collected depends on type of state machine + that is connected to the picker. Qwt offers a couple of predefined + state machines for selecting: + + - Nothing\n + QwtPickerTrackerMachine + - Single points\n + QwtPickerClickPointMachine, QwtPickerDragPointMachine + - Rectangles\n + QwtPickerClickRectMachine, QwtPickerDragRectMachine + - Polygons\n + QwtPickerPolygonMachine + + While these state machines cover the most common ways to collect points + it is also possible to implement individual machines as well. + + QwtPicker translates the picked points into a selection using the + adjustedPoints method. adjustedPoints is intended to be reimplemented + to fixup the selection according to application specific requirements. + (F.e. when an application accepts rectangles of a fixed aspect ratio only.) + + Optionally QwtPicker support the process of collecting points by a + rubberband and tracker displaying a text for the current mouse + position. + + \par Example + \verbatim #include +#include + +QwtPicker *picker = new QwtPicker(widget); +picker->setStateMachine(new QwtPickerDragRectMachine); +picker->setTrackerMode(QwtPicker::ActiveOnly); +picker->setRubberBand(QwtPicker::RectRubberBand); \endverbatim\n + + The state machine triggers the following commands: + + - begin()\n + Activate/Initialize the selection. + - append()\n + Add a new point + - move() \n + Change the position of the last point. + - remove()\n + Remove the last point. + - end()\n + Terminate the selection and call accept to validate the picked points. + + The picker is active (isActive()), between begin() and end(). + In active state the rubberband is displayed, and the tracker is visible + in case of trackerMode is ActiveOnly or AlwaysOn. + + The cursor can be moved using the arrow keys. All selections can be aborted + using the abort key. (QwtEventPattern::KeyPatternCode) + + \warning In case of QWidget::NoFocus the focus policy of the observed + widget is set to QWidget::WheelFocus and mouse tracking + will be manipulated while the picker is active, + or if trackerMode() is AlwayOn. +*/ + +class QWT_EXPORT QwtPicker: public QObject, public QwtEventPattern +{ + Q_OBJECT + + Q_ENUMS( RubberBand ) + Q_ENUMS( DisplayMode ) + Q_ENUMS( ResizeMode ) + + Q_PROPERTY( bool isEnabled READ isEnabled WRITE setEnabled ) + Q_PROPERTY( ResizeMode resizeMode READ resizeMode WRITE setResizeMode ) + + Q_PROPERTY( DisplayMode trackerMode READ trackerMode WRITE setTrackerMode ) + Q_PROPERTY( QPen trackerPen READ trackerPen WRITE setTrackerPen ) + Q_PROPERTY( QFont trackerFont READ trackerFont WRITE setTrackerFont ) + + Q_PROPERTY( RubberBand rubberBand READ rubberBand WRITE setRubberBand ) + Q_PROPERTY( QPen rubberBandPen READ rubberBandPen WRITE setRubberBandPen ) + +public: + /*! + Rubberband style + + The default value is QwtPicker::NoRubberBand. + \sa setRubberBand(), rubberBand() + */ + + enum RubberBand + { + //! No rubberband. + NoRubberBand = 0, + + //! A horizontal line ( only for QwtPicker::PointSelection ) + HLineRubberBand, + + //! A vertical line ( only for QwtPicker::PointSelection ) + VLineRubberBand, + + //! A crosshair ( only for QwtPicker::PointSelection ) + CrossRubberBand, + + //! A rectangle ( only for QwtPicker::RectSelection ) + RectRubberBand, + + //! An ellipse ( only for QwtPicker::RectSelection ) + EllipseRubberBand, + + //! A polygon ( only for QwtPicker::&PolygonSelection ) + PolygonRubberBand, + + /*! + Values >= UserRubberBand can be used to define additional + rubber bands. + */ + UserRubberBand = 100 + }; + + /*! + \brief Display mode + \sa setTrackerMode(), trackerMode(), isActive() + */ + enum DisplayMode + { + //! Display never + AlwaysOff, + + //! Display always + AlwaysOn, + + //! Display only when the selection is active + ActiveOnly + }; + + /*! + Controls what to do with the selected points of an active + selection when the observed widget is resized. + + The default value is QwtPicker::Stretch. + \sa setResizeMode() + */ + + enum ResizeMode + { + //! All points are scaled according to the new size, + Stretch, + + //! All points remain unchanged. + KeepSize + }; + + explicit QwtPicker( QWidget *parent ); + explicit QwtPicker( RubberBand rubberBand, + DisplayMode trackerMode, QWidget * ); + + virtual ~QwtPicker(); + + void setStateMachine( QwtPickerMachine * ); + const QwtPickerMachine *stateMachine() const; + QwtPickerMachine *stateMachine(); + + void setRubberBand( RubberBand ); + RubberBand rubberBand() const; + + void setTrackerMode( DisplayMode ); + DisplayMode trackerMode() const; + + void setResizeMode( ResizeMode ); + ResizeMode resizeMode() const; + + void setRubberBandPen( const QPen & ); + QPen rubberBandPen() const; + + void setTrackerPen( const QPen & ); + QPen trackerPen() const; + + void setTrackerFont( const QFont & ); + QFont trackerFont() const; + + bool isEnabled() const; + bool isActive() const; + + virtual bool eventFilter( QObject *, QEvent * ); + + QWidget *parentWidget(); + const QWidget *parentWidget() const; + + virtual QRect pickRect() const; + + virtual void drawRubberBand( QPainter * ) const; + virtual void drawTracker( QPainter * ) const; + + virtual QwtText trackerText( const QPoint &pos ) const; + QPoint trackerPosition() const; + virtual QRect trackerRect( const QFont & ) const; + + QPolygon selection() const; + +public Q_SLOTS: + void setEnabled( bool ); + +Q_SIGNALS: + /*! + A signal indicating, when the picker has been activated. + Together with setEnabled() it can be used to implement + selections with more than one picker. + + \param on True, when the picker has been activated + */ + void activated( bool on ); + + /*! + A signal emitting the selected points, + at the end of a selection. + + \param polygon Selected points + */ + void selected( const QPolygon &polygon ); + + /*! + A signal emitted when a point has been appended to the selection + + \param pos Position of the appended point. + \sa append(). moved() + */ + void appended( const QPoint &pos ); + + /*! + A signal emitted whenever the last appended point of the + selection has been moved. + + \param pos Position of the moved last point of the selection. + \sa move(), appended() + */ + void moved( const QPoint &pos ); + + /*! + A signal emitted whenever the last appended point of the + selection has been removed. + + \sa remove(), appended() + */ + void removed( const QPoint &pos ); + /*! + A signal emitted when the active selection has been changed. + This might happen when the observed widget is resized. + + \param selection Changed selection + \sa stretchSelection() + */ + void changed( const QPolygon &selection ); + +protected: + virtual QPolygon adjustedPoints( const QPolygon & ) const; + + virtual void transition( const QEvent * ); + + virtual void begin(); + virtual void append( const QPoint & ); + virtual void move( const QPoint & ); + virtual void remove(); + virtual bool end( bool ok = true ); + + virtual bool accept( QPolygon & ) const; + virtual void reset(); + + virtual void widgetMousePressEvent( QMouseEvent * ); + virtual void widgetMouseReleaseEvent( QMouseEvent * ); + virtual void widgetMouseDoubleClickEvent( QMouseEvent * ); + virtual void widgetMouseMoveEvent( QMouseEvent * ); + virtual void widgetWheelEvent( QWheelEvent * ); + virtual void widgetKeyPressEvent( QKeyEvent * ); + virtual void widgetKeyReleaseEvent( QKeyEvent * ); + virtual void widgetEnterEvent( QEvent * ); + virtual void widgetLeaveEvent( QEvent * ); + + virtual void stretchSelection( const QSize &oldSize, + const QSize &newSize ); + + virtual void updateDisplay(); + + const QWidget *rubberBandWidget() const; + const QWidget *trackerWidget() const; + + const QPolygon &pickedPoints() const; + +private: + void init( QWidget *, RubberBand rubberBand, DisplayMode trackerMode ); + + void setMouseTracking( bool ); + + class PickerWidget; + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_picker_machine.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_picker_machine.cpp index 0ae245cdf..97d890ec1 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_picker_machine.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_picker_machine.cpp @@ -1,450 +1,450 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_picker_machine.h" -#include "qwt_event_pattern.h" -#include - -//! Constructor -QwtPickerMachine::QwtPickerMachine( SelectionType type ): - d_selectionType( type ), - d_state( 0 ) -{ -} - -//! Destructor -QwtPickerMachine::~QwtPickerMachine() -{ -} - -//! Return the selection type -QwtPickerMachine::SelectionType QwtPickerMachine::selectionType() const -{ - return d_selectionType; -} - -//! Return the current state -int QwtPickerMachine::state() const -{ - return d_state; -} - -//! Change the current state -void QwtPickerMachine::setState( int state ) -{ - d_state = state; -} - -//! Set the current state to 0. -void QwtPickerMachine::reset() -{ - setState( 0 ); -} - -//! Constructor -QwtPickerTrackerMachine::QwtPickerTrackerMachine(): - QwtPickerMachine( NoSelection ) -{ -} - -//! Transition -QList QwtPickerTrackerMachine::transition( - const QwtEventPattern &, const QEvent *e ) -{ - QList cmdList; - - switch ( e->type() ) - { - case QEvent::Enter: - case QEvent::MouseMove: - { - if ( state() == 0 ) - { - cmdList += Begin; - cmdList += Append; - setState( 1 ); - } - else - { - cmdList += Move; - } - break; - } - case QEvent::Leave: - { - cmdList += Remove; - cmdList += End; - setState( 0 ); - } - default: - break; - } - - return cmdList; -} - -//! Constructor -QwtPickerClickPointMachine::QwtPickerClickPointMachine(): - QwtPickerMachine( PointSelection ) -{ -} - -//! Transition -QList QwtPickerClickPointMachine::transition( - const QwtEventPattern &eventPattern, const QEvent *e ) -{ - QList cmdList; - - switch ( e->type() ) - { - case QEvent::MouseButtonPress: - { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) - { - cmdList += Begin; - cmdList += Append; - cmdList += End; - } - break; - } - case QEvent::KeyPress: - { - if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect1, ( const QKeyEvent * )e ) ) - { - cmdList += Begin; - cmdList += Append; - cmdList += End; - } - break; - } - default: - break; - } - - return cmdList; -} - -//! Constructor -QwtPickerDragPointMachine::QwtPickerDragPointMachine(): - QwtPickerMachine( PointSelection ) -{ -} - -//! Transition -QList QwtPickerDragPointMachine::transition( - const QwtEventPattern &eventPattern, const QEvent *e ) -{ - QList cmdList; - - switch ( e->type() ) - { - case QEvent::MouseButtonPress: - { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) - { - if ( state() == 0 ) - { - cmdList += Begin; - cmdList += Append; - setState( 1 ); - } - } - break; - } - case QEvent::MouseMove: - case QEvent::Wheel: - { - if ( state() != 0 ) - cmdList += Move; - break; - } - case QEvent::MouseButtonRelease: - { - if ( state() != 0 ) - { - cmdList += End; - setState( 0 ); - } - break; - } - case QEvent::KeyPress: - { - if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect1, ( const QKeyEvent * )e ) ) - { - if ( state() == 0 ) - { - cmdList += Begin; - cmdList += Append; - setState( 1 ); - } - else - { - cmdList += End; - setState( 0 ); - } - } - break; - } - default: - break; - } - - return cmdList; -} - -//! Constructor -QwtPickerClickRectMachine::QwtPickerClickRectMachine(): - QwtPickerMachine( RectSelection ) -{ -} - -//! Transition -QList QwtPickerClickRectMachine::transition( - const QwtEventPattern &eventPattern, const QEvent *e ) -{ - QList cmdList; - - switch ( e->type() ) - { - case QEvent::MouseButtonPress: - { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) - { - switch ( state() ) - { - case 0: - { - cmdList += Begin; - cmdList += Append; - setState( 1 ); - break; - } - case 1: - { - // Uh, strange we missed the MouseButtonRelease - break; - } - default: - { - cmdList += End; - setState( 0 ); - } - } - } - } - case QEvent::MouseMove: - case QEvent::Wheel: - { - if ( state() != 0 ) - cmdList += Move; - break; - } - case QEvent::MouseButtonRelease: - { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) - { - if ( state() == 1 ) - { - cmdList += Append; - setState( 2 ); - } - } - break; - } - case QEvent::KeyPress: - { - if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect1, ( const QKeyEvent * )e ) ) - { - if ( state() == 0 ) - { - cmdList += Begin; - cmdList += Append; - setState( 1 ); - } - else - { - if ( state() == 1 ) - { - cmdList += Append; - setState( 2 ); - } - else if ( state() == 2 ) - { - cmdList += End; - setState( 0 ); - } - } - } - break; - } - default: - break; - } - - return cmdList; -} - -//! Constructor -QwtPickerDragRectMachine::QwtPickerDragRectMachine(): - QwtPickerMachine( RectSelection ) -{ -} - -//! Transition -QList QwtPickerDragRectMachine::transition( - const QwtEventPattern &eventPattern, const QEvent *e ) -{ - QList cmdList; - - switch ( e->type() ) - { - case QEvent::MouseButtonPress: - { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) - { - if ( state() == 0 ) - { - cmdList += Begin; - cmdList += Append; - cmdList += Append; - setState( 2 ); - } - } - break; - } - case QEvent::MouseMove: - case QEvent::Wheel: - { - if ( state() != 0 ) - cmdList += Move; - break; - } - case QEvent::MouseButtonRelease: - { - if ( state() == 2 ) - { - cmdList += End; - setState( 0 ); - } - break; - } - case QEvent::KeyPress: - { - if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect1, ( const QKeyEvent * )e ) ) - { - if ( state() == 0 ) - { - cmdList += Begin; - cmdList += Append; - cmdList += Append; - setState( 2 ); - } - else - { - cmdList += End; - setState( 0 ); - } - } - break; - } - default: - break; - } - - return cmdList; -} - -//! Constructor -QwtPickerPolygonMachine::QwtPickerPolygonMachine(): - QwtPickerMachine( PolygonSelection ) -{ -} - -//! Transition -QList QwtPickerPolygonMachine::transition( - const QwtEventPattern &eventPattern, const QEvent *e ) -{ - QList cmdList; - - switch ( e->type() ) - { - case QEvent::MouseButtonPress: - { - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) - { - if ( state() == 0 ) - { - cmdList += Begin; - cmdList += Append; - cmdList += Append; - setState( 1 ); - } - else - { - cmdList += End; - setState( 0 ); - } - } - if ( eventPattern.mouseMatch( - QwtEventPattern::MouseSelect2, ( const QMouseEvent * )e ) ) - { - if ( state() == 1 ) - cmdList += Append; - } - break; - } - case QEvent::MouseMove: - case QEvent::Wheel: - { - if ( state() != 0 ) - cmdList += Move; - break; - } - case QEvent::KeyPress: - { - if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect1, ( const QKeyEvent * )e ) ) - { - if ( state() == 0 ) - { - cmdList += Begin; - cmdList += Append; - cmdList += Append; - setState( 1 ); - } - else - { - cmdList += End; - setState( 0 ); - } - } - else if ( eventPattern.keyMatch( - QwtEventPattern::KeySelect2, ( const QKeyEvent * )e ) ) - { - if ( state() == 1 ) - cmdList += Append; - } - break; - } - default: - break; - } - - return cmdList; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_picker_machine.h" +#include "qwt_event_pattern.h" +#include + +//! Constructor +QwtPickerMachine::QwtPickerMachine( SelectionType type ): + d_selectionType( type ), + d_state( 0 ) +{ +} + +//! Destructor +QwtPickerMachine::~QwtPickerMachine() +{ +} + +//! Return the selection type +QwtPickerMachine::SelectionType QwtPickerMachine::selectionType() const +{ + return d_selectionType; +} + +//! Return the current state +int QwtPickerMachine::state() const +{ + return d_state; +} + +//! Change the current state +void QwtPickerMachine::setState( int state ) +{ + d_state = state; +} + +//! Set the current state to 0. +void QwtPickerMachine::reset() +{ + setState( 0 ); +} + +//! Constructor +QwtPickerTrackerMachine::QwtPickerTrackerMachine(): + QwtPickerMachine( NoSelection ) +{ +} + +//! Transition +QList QwtPickerTrackerMachine::transition( + const QwtEventPattern &, const QEvent *e ) +{ + QList cmdList; + + switch ( e->type() ) + { + case QEvent::Enter: + case QEvent::MouseMove: + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + setState( 1 ); + } + else + { + cmdList += Move; + } + break; + } + case QEvent::Leave: + { + cmdList += Remove; + cmdList += End; + setState( 0 ); + } + default: + break; + } + + return cmdList; +} + +//! Constructor +QwtPickerClickPointMachine::QwtPickerClickPointMachine(): + QwtPickerMachine( PointSelection ) +{ +} + +//! Transition +QList QwtPickerClickPointMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *e ) +{ + QList cmdList; + + switch ( e->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( + QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) + { + cmdList += Begin; + cmdList += Append; + cmdList += End; + } + break; + } + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( + QwtEventPattern::KeySelect1, ( const QKeyEvent * )e ) ) + { + cmdList += Begin; + cmdList += Append; + cmdList += End; + } + break; + } + default: + break; + } + + return cmdList; +} + +//! Constructor +QwtPickerDragPointMachine::QwtPickerDragPointMachine(): + QwtPickerMachine( PointSelection ) +{ +} + +//! Transition +QList QwtPickerDragPointMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *e ) +{ + QList cmdList; + + switch ( e->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( + QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + setState( 1 ); + } + } + break; + } + case QEvent::MouseMove: + case QEvent::Wheel: + { + if ( state() != 0 ) + cmdList += Move; + break; + } + case QEvent::MouseButtonRelease: + { + if ( state() != 0 ) + { + cmdList += End; + setState( 0 ); + } + break; + } + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( + QwtEventPattern::KeySelect1, ( const QKeyEvent * )e ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + setState( 1 ); + } + else + { + cmdList += End; + setState( 0 ); + } + } + break; + } + default: + break; + } + + return cmdList; +} + +//! Constructor +QwtPickerClickRectMachine::QwtPickerClickRectMachine(): + QwtPickerMachine( RectSelection ) +{ +} + +//! Transition +QList QwtPickerClickRectMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *e ) +{ + QList cmdList; + + switch ( e->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( + QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) + { + switch ( state() ) + { + case 0: + { + cmdList += Begin; + cmdList += Append; + setState( 1 ); + break; + } + case 1: + { + // Uh, strange we missed the MouseButtonRelease + break; + } + default: + { + cmdList += End; + setState( 0 ); + } + } + } + } + case QEvent::MouseMove: + case QEvent::Wheel: + { + if ( state() != 0 ) + cmdList += Move; + break; + } + case QEvent::MouseButtonRelease: + { + if ( eventPattern.mouseMatch( + QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) + { + if ( state() == 1 ) + { + cmdList += Append; + setState( 2 ); + } + } + break; + } + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( + QwtEventPattern::KeySelect1, ( const QKeyEvent * )e ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + setState( 1 ); + } + else + { + if ( state() == 1 ) + { + cmdList += Append; + setState( 2 ); + } + else if ( state() == 2 ) + { + cmdList += End; + setState( 0 ); + } + } + } + break; + } + default: + break; + } + + return cmdList; +} + +//! Constructor +QwtPickerDragRectMachine::QwtPickerDragRectMachine(): + QwtPickerMachine( RectSelection ) +{ +} + +//! Transition +QList QwtPickerDragRectMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *e ) +{ + QList cmdList; + + switch ( e->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( + QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + cmdList += Append; + setState( 2 ); + } + } + break; + } + case QEvent::MouseMove: + case QEvent::Wheel: + { + if ( state() != 0 ) + cmdList += Move; + break; + } + case QEvent::MouseButtonRelease: + { + if ( state() == 2 ) + { + cmdList += End; + setState( 0 ); + } + break; + } + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( + QwtEventPattern::KeySelect1, ( const QKeyEvent * )e ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + cmdList += Append; + setState( 2 ); + } + else + { + cmdList += End; + setState( 0 ); + } + } + break; + } + default: + break; + } + + return cmdList; +} + +//! Constructor +QwtPickerPolygonMachine::QwtPickerPolygonMachine(): + QwtPickerMachine( PolygonSelection ) +{ +} + +//! Transition +QList QwtPickerPolygonMachine::transition( + const QwtEventPattern &eventPattern, const QEvent *e ) +{ + QList cmdList; + + switch ( e->type() ) + { + case QEvent::MouseButtonPress: + { + if ( eventPattern.mouseMatch( + QwtEventPattern::MouseSelect1, ( const QMouseEvent * )e ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + cmdList += Append; + setState( 1 ); + } + else + { + cmdList += End; + setState( 0 ); + } + } + if ( eventPattern.mouseMatch( + QwtEventPattern::MouseSelect2, ( const QMouseEvent * )e ) ) + { + if ( state() == 1 ) + cmdList += Append; + } + break; + } + case QEvent::MouseMove: + case QEvent::Wheel: + { + if ( state() != 0 ) + cmdList += Move; + break; + } + case QEvent::KeyPress: + { + if ( eventPattern.keyMatch( + QwtEventPattern::KeySelect1, ( const QKeyEvent * )e ) ) + { + if ( state() == 0 ) + { + cmdList += Begin; + cmdList += Append; + cmdList += Append; + setState( 1 ); + } + else + { + cmdList += End; + setState( 0 ); + } + } + else if ( eventPattern.keyMatch( + QwtEventPattern::KeySelect2, ( const QKeyEvent * )e ) ) + { + if ( state() == 1 ) + cmdList += Append; + } + break; + } + default: + break; + } + + return cmdList; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_picker_machine.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_picker_machine.h index 99a1e744c..8527115de 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_picker_machine.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_picker_machine.h @@ -1,190 +1,190 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PICKER_MACHINE -#define QWT_PICKER_MACHINE 1 - -#include "qwt_global.h" -#include - -class QEvent; -class QwtEventPattern; - -/*! - \brief A state machine for QwtPicker selections - - QwtPickerMachine accepts key and mouse events and translates them - into selection commands. - - \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode -*/ - -class QWT_EXPORT QwtPickerMachine -{ -public: - /*! - Type of a selection. - \sa selectionType() - */ - enum SelectionType - { - //! The state machine not usable for any type of selection. - NoSelection = -1, - - //! The state machine is for selecting a single point. - PointSelection, - - //! The state machine is for selecting a rectangle (2 points). - RectSelection, - - //! The state machine is for selecting a polygon (many points). - PolygonSelection - }; - - //! Commands - the output of a state machine - enum Command - { - Begin, - Append, - Move, - Remove, - End - }; - - QwtPickerMachine( SelectionType ); - virtual ~QwtPickerMachine(); - - //! Transition - virtual QList transition( - const QwtEventPattern &, const QEvent * ) = 0; - void reset(); - - int state() const; - void setState( int ); - - SelectionType selectionType() const; - -private: - const SelectionType d_selectionType; - int d_state; -}; - -/*! - \brief A state machine for indicating mouse movements - - QwtPickerTrackerMachine supports displaying information - corresponding to mouse movements, but is not intended for - selecting anything. Begin/End are related to Enter/Leave events. -*/ -class QWT_EXPORT QwtPickerTrackerMachine: public QwtPickerMachine -{ -public: - QwtPickerTrackerMachine(); - - virtual QList transition( - const QwtEventPattern &, const QEvent * ); -}; - -/*! - \brief A state machine for point selections - - Pressing QwtEventPattern::MouseSelect1 or - QwtEventPattern::KeySelect1 selects a point. - - \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode -*/ -class QWT_EXPORT QwtPickerClickPointMachine: public QwtPickerMachine -{ -public: - QwtPickerClickPointMachine(); - - virtual QList transition( - const QwtEventPattern &, const QEvent * ); -}; - -/*! - \brief A state machine for point selections - - Pressing QwtEventPattern::MouseSelect1 or QwtEventPattern::KeySelect1 - starts the selection, releasing QwtEventPattern::MouseSelect1 or - a second press of QwtEventPattern::KeySelect1 terminates it. -*/ -class QWT_EXPORT QwtPickerDragPointMachine: public QwtPickerMachine -{ -public: - QwtPickerDragPointMachine(); - - virtual QList transition( - const QwtEventPattern &, const QEvent * ); -}; - -/*! - \brief A state machine for rectangle selections - - Pressing QwtEventPattern::MouseSelect1 starts - the selection, releasing it selects the first point. Pressing it - again selects the second point and terminates the selection. - Pressing QwtEventPattern::KeySelect1 also starts the - selection, a second press selects the first point. A third one selects - the second point and terminates the selection. - - \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode -*/ - -class QWT_EXPORT QwtPickerClickRectMachine: public QwtPickerMachine -{ -public: - QwtPickerClickRectMachine(); - - virtual QList transition( - const QwtEventPattern &, const QEvent * ); -}; - -/*! - \brief A state machine for rectangle selections - - Pressing QwtEventPattern::MouseSelect1 selects - the first point, releasing it the second point. - Pressing QwtEventPattern::KeySelect1 also selects the - first point, a second press selects the second point and terminates - the selection. - - \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode -*/ - -class QWT_EXPORT QwtPickerDragRectMachine: public QwtPickerMachine -{ -public: - QwtPickerDragRectMachine(); - - virtual QList transition( - const QwtEventPattern &, const QEvent * ); -}; - -/*! - \brief A state machine for polygon selections - - Pressing QwtEventPattern::MouseSelect1 or QwtEventPattern::KeySelect1 - starts the selection and selects the first point, or appends a point. - Pressing QwtEventPattern::MouseSelect2 or QwtEventPattern::KeySelect2 - appends the last point and terminates the selection. - - \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode -*/ - -class QWT_EXPORT QwtPickerPolygonMachine: public QwtPickerMachine -{ -public: - QwtPickerPolygonMachine(); - - virtual QList transition( - const QwtEventPattern &, const QEvent * ); -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PICKER_MACHINE +#define QWT_PICKER_MACHINE 1 + +#include "qwt_global.h" +#include + +class QEvent; +class QwtEventPattern; + +/*! + \brief A state machine for QwtPicker selections + + QwtPickerMachine accepts key and mouse events and translates them + into selection commands. + + \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode +*/ + +class QWT_EXPORT QwtPickerMachine +{ +public: + /*! + Type of a selection. + \sa selectionType() + */ + enum SelectionType + { + //! The state machine not usable for any type of selection. + NoSelection = -1, + + //! The state machine is for selecting a single point. + PointSelection, + + //! The state machine is for selecting a rectangle (2 points). + RectSelection, + + //! The state machine is for selecting a polygon (many points). + PolygonSelection + }; + + //! Commands - the output of a state machine + enum Command + { + Begin, + Append, + Move, + Remove, + End + }; + + QwtPickerMachine( SelectionType ); + virtual ~QwtPickerMachine(); + + //! Transition + virtual QList transition( + const QwtEventPattern &, const QEvent * ) = 0; + void reset(); + + int state() const; + void setState( int ); + + SelectionType selectionType() const; + +private: + const SelectionType d_selectionType; + int d_state; +}; + +/*! + \brief A state machine for indicating mouse movements + + QwtPickerTrackerMachine supports displaying information + corresponding to mouse movements, but is not intended for + selecting anything. Begin/End are related to Enter/Leave events. +*/ +class QWT_EXPORT QwtPickerTrackerMachine: public QwtPickerMachine +{ +public: + QwtPickerTrackerMachine(); + + virtual QList transition( + const QwtEventPattern &, const QEvent * ); +}; + +/*! + \brief A state machine for point selections + + Pressing QwtEventPattern::MouseSelect1 or + QwtEventPattern::KeySelect1 selects a point. + + \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode +*/ +class QWT_EXPORT QwtPickerClickPointMachine: public QwtPickerMachine +{ +public: + QwtPickerClickPointMachine(); + + virtual QList transition( + const QwtEventPattern &, const QEvent * ); +}; + +/*! + \brief A state machine for point selections + + Pressing QwtEventPattern::MouseSelect1 or QwtEventPattern::KeySelect1 + starts the selection, releasing QwtEventPattern::MouseSelect1 or + a second press of QwtEventPattern::KeySelect1 terminates it. +*/ +class QWT_EXPORT QwtPickerDragPointMachine: public QwtPickerMachine +{ +public: + QwtPickerDragPointMachine(); + + virtual QList transition( + const QwtEventPattern &, const QEvent * ); +}; + +/*! + \brief A state machine for rectangle selections + + Pressing QwtEventPattern::MouseSelect1 starts + the selection, releasing it selects the first point. Pressing it + again selects the second point and terminates the selection. + Pressing QwtEventPattern::KeySelect1 also starts the + selection, a second press selects the first point. A third one selects + the second point and terminates the selection. + + \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode +*/ + +class QWT_EXPORT QwtPickerClickRectMachine: public QwtPickerMachine +{ +public: + QwtPickerClickRectMachine(); + + virtual QList transition( + const QwtEventPattern &, const QEvent * ); +}; + +/*! + \brief A state machine for rectangle selections + + Pressing QwtEventPattern::MouseSelect1 selects + the first point, releasing it the second point. + Pressing QwtEventPattern::KeySelect1 also selects the + first point, a second press selects the second point and terminates + the selection. + + \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode +*/ + +class QWT_EXPORT QwtPickerDragRectMachine: public QwtPickerMachine +{ +public: + QwtPickerDragRectMachine(); + + virtual QList transition( + const QwtEventPattern &, const QEvent * ); +}; + +/*! + \brief A state machine for polygon selections + + Pressing QwtEventPattern::MouseSelect1 or QwtEventPattern::KeySelect1 + starts the selection and selects the first point, or appends a point. + Pressing QwtEventPattern::MouseSelect2 or QwtEventPattern::KeySelect2 + appends the last point and terminates the selection. + + \sa QwtEventPattern::MousePatternCode, QwtEventPattern::KeyPatternCode +*/ + +class QWT_EXPORT QwtPickerPolygonMachine: public QwtPickerMachine +{ +public: + QwtPickerPolygonMachine(); + + virtual QList transition( + const QwtEventPattern &, const QEvent * ); +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot.cpp index 60f10f3a4..69c868537 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot.cpp @@ -1,748 +1,748 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot.h" -#include "qwt_plot_dict.h" -#include "qwt_plot_layout.h" -#include "qwt_scale_widget.h" -#include "qwt_scale_engine.h" -#include "qwt_text_label.h" -#include "qwt_legend.h" -#include "qwt_dyngrid_layout.h" -#include "qwt_plot_canvas.h" -#include -#include -#include -#include -#include - -class QwtPlot::PrivateData -{ -public: - QPointer lblTitle; - QPointer canvas; - QPointer legend; - QwtPlotLayout *layout; - - bool autoReplot; -}; - -/*! - \brief Constructor - \param parent Parent widget - */ -QwtPlot::QwtPlot( QWidget *parent ): - QFrame( parent ) -{ - initPlot( QwtText() ); -} - -/*! - \brief Constructor - \param title Title text - \param parent Parent widget - */ -QwtPlot::QwtPlot( const QwtText &title, QWidget *parent ): - QFrame( parent ) -{ - initPlot( title ); -} - -//! Destructor -QwtPlot::~QwtPlot() -{ - detachItems( QwtPlotItem::Rtti_PlotItem, autoDelete() ); - - delete d_data->layout; - deleteAxesData(); - delete d_data; -} - -/*! - \brief Initializes a QwtPlot instance - \param title Title text - */ -void QwtPlot::initPlot( const QwtText &title ) -{ - d_data = new PrivateData; - - d_data->layout = new QwtPlotLayout; - d_data->autoReplot = false; - - d_data->lblTitle = new QwtTextLabel( title, this ); - d_data->lblTitle->setObjectName( "QwtPlotTitle" ); - - d_data->lblTitle->setFont( QFont( fontInfo().family(), 14, QFont::Bold ) ); - - QwtText text( title ); - text.setRenderFlags( Qt::AlignCenter | Qt::TextWordWrap ); - d_data->lblTitle->setText( text ); - - d_data->legend = NULL; - - initAxesData(); - - d_data->canvas = new QwtPlotCanvas( this ); - d_data->canvas->setObjectName( "QwtPlotCanvas" ); - d_data->canvas->setFrameStyle( QFrame::Panel | QFrame::Sunken ); - d_data->canvas->setLineWidth( 2 ); - - updateTabOrder(); - - setSizePolicy( QSizePolicy::MinimumExpanding, - QSizePolicy::MinimumExpanding ); - - resize( 200, 200 ); -} - -/*! - \brief Adds handling of layout requests - \param event Event -*/ -bool QwtPlot::event( QEvent *event ) -{ - bool ok = QFrame::event( event ); - switch ( event->type() ) - { - case QEvent::LayoutRequest: - updateLayout(); - break; - case QEvent::PolishRequest: - replot(); - break; - default:; - } - return ok; -} - -//! Replots the plot if autoReplot() is \c true. -void QwtPlot::autoRefresh() -{ - if ( d_data->autoReplot ) - replot(); -} - -/*! - \brief Set or reset the autoReplot option - - If the autoReplot option is set, the plot will be - updated implicitly by manipulating member functions. - Since this may be time-consuming, it is recommended - to leave this option switched off and call replot() - explicitly if necessary. - - The autoReplot option is set to false by default, which - means that the user has to call replot() in order to make - changes visible. - \param tf \c true or \c false. Defaults to \c true. - \sa replot() -*/ -void QwtPlot::setAutoReplot( bool tf ) -{ - d_data->autoReplot = tf; -} - -/*! - \return true if the autoReplot option is set. - \sa setAutoReplot() -*/ -bool QwtPlot::autoReplot() const -{ - return d_data->autoReplot; -} - -/*! - Change the plot's title - \param title New title -*/ -void QwtPlot::setTitle( const QString &title ) -{ - if ( title != d_data->lblTitle->text().text() ) - { - d_data->lblTitle->setText( title ); - updateLayout(); - } -} - -/*! - Change the plot's title - \param title New title -*/ -void QwtPlot::setTitle( const QwtText &title ) -{ - if ( title != d_data->lblTitle->text() ) - { - d_data->lblTitle->setText( title ); - updateLayout(); - } -} - -//! \return the plot's title -QwtText QwtPlot::title() const -{ - return d_data->lblTitle->text(); -} - -//! \return the plot's title -QwtPlotLayout *QwtPlot::plotLayout() -{ - return d_data->layout; -} - -//! \return the plot's titel label. -const QwtPlotLayout *QwtPlot::plotLayout() const -{ - return d_data->layout; -} - -//! \return the plot's titel label. -QwtTextLabel *QwtPlot::titleLabel() -{ - return d_data->lblTitle; -} - -/*! - \return the plot's titel label. -*/ -const QwtTextLabel *QwtPlot::titleLabel() const -{ - return d_data->lblTitle; -} - -/*! - \return the plot's legend - \sa insertLegend() -*/ -QwtLegend *QwtPlot::legend() -{ - return d_data->legend; -} - -/*! - \return the plot's legend - \sa insertLegend() -*/ -const QwtLegend *QwtPlot::legend() const -{ - return d_data->legend; -} - - -/*! - \return the plot's canvas -*/ -QwtPlotCanvas *QwtPlot::canvas() -{ - return d_data->canvas; -} - -/*! - \return the plot's canvas -*/ -const QwtPlotCanvas *QwtPlot::canvas() const -{ - return d_data->canvas; -} - -/*! - Return sizeHint - \sa minimumSizeHint() -*/ - -QSize QwtPlot::sizeHint() const -{ - int dw = 0; - int dh = 0; - for ( int axisId = 0; axisId < axisCnt; axisId++ ) - { - if ( axisEnabled( axisId ) ) - { - const int niceDist = 40; - const QwtScaleWidget *scaleWidget = axisWidget( axisId ); - const QwtScaleDiv &scaleDiv = scaleWidget->scaleDraw()->scaleDiv(); - const int majCnt = scaleDiv.ticks( QwtScaleDiv::MajorTick ).count(); - - if ( axisId == yLeft || axisId == yRight ) - { - int hDiff = ( majCnt - 1 ) * niceDist - - scaleWidget->minimumSizeHint().height(); - if ( hDiff > dh ) - dh = hDiff; - } - else - { - int wDiff = ( majCnt - 1 ) * niceDist - - scaleWidget->minimumSizeHint().width(); - if ( wDiff > dw ) - dw = wDiff; - } - } - } - return minimumSizeHint() + QSize( dw, dh ); -} - -/*! - \brief Return a minimum size hint -*/ -QSize QwtPlot::minimumSizeHint() const -{ - QSize hint = d_data->layout->minimumSizeHint( this ); - hint += QSize( 2 * frameWidth(), 2 * frameWidth() ); - - return hint; -} - -/*! - Resize and update internal layout - \param e Resize event -*/ -void QwtPlot::resizeEvent( QResizeEvent *e ) -{ - QFrame::resizeEvent( e ); - updateLayout(); -} - -/*! - \brief Redraw the plot - - If the autoReplot option is not set (which is the default) - or if any curves are attached to raw data, the plot has to - be refreshed explicitly in order to make changes visible. - - \sa setAutoReplot() - \warning Calls canvas()->repaint, take care of infinite recursions -*/ -void QwtPlot::replot() -{ - bool doAutoReplot = autoReplot(); - setAutoReplot( false ); - - updateAxes(); - - /* - Maybe the layout needs to be updated, because of changed - axes labels. We need to process them here before painting - to avoid that scales and canvas get out of sync. - */ - QApplication::sendPostedEvents( this, QEvent::LayoutRequest ); - - d_data->canvas->replot(); - - setAutoReplot( doAutoReplot ); -} - -/*! - \brief Adjust plot content to its current size. - \sa resizeEvent() -*/ -void QwtPlot::updateLayout() -{ - d_data->layout->activate( this, contentsRect() ); - - QRect titleRect = d_data->layout->titleRect().toRect(); - QRect scaleRect[QwtPlot::axisCnt]; - for ( int axisId = 0; axisId < axisCnt; axisId++ ) - scaleRect[axisId] = d_data->layout->scaleRect( axisId ).toRect(); - QRect legendRect = d_data->layout->legendRect().toRect(); - QRect canvasRect = d_data->layout->canvasRect().toRect(); - - // - // resize and show the visible widgets - // - if ( !d_data->lblTitle->text().isEmpty() ) - { - d_data->lblTitle->setGeometry( titleRect ); - if ( !d_data->lblTitle->isVisibleTo( this ) ) - d_data->lblTitle->show(); - } - else - d_data->lblTitle->hide(); - - for ( int axisId = 0; axisId < axisCnt; axisId++ ) - { - if ( axisEnabled( axisId ) ) - { - axisWidget( axisId )->setGeometry( scaleRect[axisId] ); - - if ( axisId == xBottom || axisId == xTop ) - { - QRegion r( scaleRect[axisId] ); - if ( axisEnabled( yLeft ) ) - r = r.subtract( QRegion( scaleRect[yLeft] ) ); - if ( axisEnabled( yRight ) ) - r = r.subtract( QRegion( scaleRect[yRight] ) ); - r.translate( -d_data->layout->scaleRect( axisId ).x(), - -scaleRect[axisId].y() ); - - axisWidget( axisId )->setMask( r ); - } - if ( !axisWidget( axisId )->isVisibleTo( this ) ) - axisWidget( axisId )->show(); - } - else - axisWidget( axisId )->hide(); - } - - if ( d_data->legend && - d_data->layout->legendPosition() != ExternalLegend ) - { - if ( d_data->legend->itemCount() > 0 ) - { - d_data->legend->setGeometry( legendRect ); - d_data->legend->show(); - } - else - d_data->legend->hide(); - } - - d_data->canvas->setGeometry( canvasRect ); -} - -/*! - Update the focus tab order - - The order is changed so that the canvas will be in front of the - first legend item, or behind the last legend item - depending - on the position of the legend. -*/ - -void QwtPlot::updateTabOrder() -{ - if ( d_data->canvas->focusPolicy() == Qt::NoFocus ) - return; - if ( d_data->legend.isNull() - || d_data->layout->legendPosition() == ExternalLegend - || d_data->legend->legendItems().count() == 0 ) - { - return; - } - - // Depending on the position of the legend the - // tab order will be changed that the canvas is - // next to the last legend item, or before - // the first one. - - const bool canvasFirst = - d_data->layout->legendPosition() == QwtPlot::BottomLegend || - d_data->layout->legendPosition() == QwtPlot::RightLegend; - - QWidget *previous = NULL; - - QWidget *w = d_data->canvas; - while ( ( w = w->nextInFocusChain() ) != d_data->canvas ) - { - bool isLegendItem = false; - if ( w->focusPolicy() != Qt::NoFocus - && w->parent() && w->parent() == d_data->legend->contentsWidget() ) - { - isLegendItem = true; - } - - if ( canvasFirst ) - { - if ( isLegendItem ) - break; - - previous = w; - } - else - { - if ( isLegendItem ) - previous = w; - else - { - if ( previous ) - break; - } - } - } - - if ( previous && previous != d_data->canvas ) - setTabOrder( previous, d_data->canvas ); -} - -/*! - Redraw the canvas. - \param painter Painter used for drawing - - \warning drawCanvas calls drawItems what is also used - for printing. Applications that like to add individual - plot items better overload drawItems() - \sa drawItems() -*/ -void QwtPlot::drawCanvas( QPainter *painter ) -{ - QwtScaleMap maps[axisCnt]; - for ( int axisId = 0; axisId < axisCnt; axisId++ ) - maps[axisId] = canvasMap( axisId ); - - drawItems( painter, d_data->canvas->contentsRect(), maps ); -} - -/*! - Redraw the canvas items. - \param painter Painter used for drawing - \param canvasRect Bounding rectangle where to paint - \param map QwtPlot::axisCnt maps, mapping between plot and paint device coordinates -*/ - -void QwtPlot::drawItems( QPainter *painter, const QRectF &canvasRect, - const QwtScaleMap map[axisCnt] ) const -{ - const QwtPlotItemList& itmList = itemList(); - for ( QwtPlotItemIterator it = itmList.begin(); - it != itmList.end(); ++it ) - { - QwtPlotItem *item = *it; - if ( item && item->isVisible() ) - { - painter->save(); - - painter->setRenderHint( QPainter::Antialiasing, - item->testRenderHint( QwtPlotItem::RenderAntialiased ) ); - - item->draw( painter, - map[item->xAxis()], map[item->yAxis()], - canvasRect ); - - painter->restore(); - } - } -} - -/*! - \param axisId Axis - \return Map for the axis on the canvas. With this map pixel coordinates can - translated to plot coordinates and vice versa. - \sa QwtScaleMap, transform(), invTransform() - -*/ -QwtScaleMap QwtPlot::canvasMap( int axisId ) const -{ - QwtScaleMap map; - if ( !d_data->canvas ) - return map; - - map.setTransformation( axisScaleEngine( axisId )->transformation() ); - - const QwtScaleDiv *sd = axisScaleDiv( axisId ); - map.setScaleInterval( sd->lowerBound(), sd->upperBound() ); - - if ( axisEnabled( axisId ) ) - { - const QwtScaleWidget *s = axisWidget( axisId ); - if ( axisId == yLeft || axisId == yRight ) - { - double y = s->y() + s->startBorderDist() - d_data->canvas->y(); - double h = s->height() - s->startBorderDist() - s->endBorderDist(); - map.setPaintInterval( y + h, y ); - } - else - { - double x = s->x() + s->startBorderDist() - d_data->canvas->x(); - double w = s->width() - s->startBorderDist() - s->endBorderDist(); - map.setPaintInterval( x, x + w ); - } - } - else - { - int margin = 0; - if ( !plotLayout()->alignCanvasToScales() ) - margin = plotLayout()->canvasMargin( axisId ); - - const QRect &canvasRect = d_data->canvas->contentsRect(); - if ( axisId == yLeft || axisId == yRight ) - { - map.setPaintInterval( canvasRect.bottom() - margin, - canvasRect.top() + margin ); - } - else - { - map.setPaintInterval( canvasRect.left() + margin, - canvasRect.right() - margin ); - } - } - return map; -} - -/*! - \brief Change the background of the plotting area - - Sets brush to QPalette::Window of all colorgroups of - the palette of the canvas. Using canvas()->setPalette() - is a more powerful way to set these colors. - - \param brush New background brush - \sa canvasBackground() -*/ -void QwtPlot::setCanvasBackground( const QBrush &brush ) -{ - QPalette pal = d_data->canvas->palette(); - - for ( int i = 0; i < QPalette::NColorGroups; i++ ) - pal.setBrush( ( QPalette::ColorGroup )i, QPalette::Window, brush ); - - canvas()->setPalette( pal ); -} - -/*! - Nothing else than: canvas()->palette().brush( - QPalette::Normal, QPalette::Window); - - \return Background brush of the plotting area. - \sa setCanvasBackground() -*/ -QBrush QwtPlot::canvasBackground() const -{ - return canvas()->palette().brush( - QPalette::Normal, QPalette::Window ); -} - -/*! - \brief Change the border width of the plotting area - - Nothing else than canvas()->setLineWidth(w), - left for compatibility only. - - \param width New border width -*/ -void QwtPlot::setCanvasLineWidth( int width ) -{ - canvas()->setLineWidth( width ); - updateLayout(); -} - -/*! - Nothing else than: canvas()->lineWidth(), - left for compatibility only. - - \return the border width of the plotting area -*/ -int QwtPlot::canvasLineWidth() const -{ - return canvas()->lineWidth(); -} - -/*! - \return \c true if the specified axis exists, otherwise \c false - \param axisId axis index - */ -bool QwtPlot::axisValid( int axisId ) -{ - return ( ( axisId >= QwtPlot::yLeft ) && ( axisId < QwtPlot::axisCnt ) ); -} - -/*! - Called internally when the legend has been clicked on. - Emits a legendClicked() signal. -*/ -void QwtPlot::legendItemClicked() -{ - if ( d_data->legend && sender()->isWidgetType() ) - { - QwtPlotItem *plotItem = - ( QwtPlotItem* )d_data->legend->find( ( QWidget * )sender() ); - if ( plotItem ) - Q_EMIT legendClicked( plotItem ); - } -} - -/*! - Called internally when the legend has been checked - Emits a legendClicked() signal. -*/ -void QwtPlot::legendItemChecked( bool on ) -{ - if ( d_data->legend && sender()->isWidgetType() ) - { - QwtPlotItem *plotItem = - ( QwtPlotItem* )d_data->legend->find( ( QWidget * )sender() ); - if ( plotItem ) - Q_EMIT legendChecked( plotItem, on ); - } -} - -/*! - \brief Insert a legend - - If the position legend is \c QwtPlot::LeftLegend or \c QwtPlot::RightLegend - the legend will be organized in one column from top to down. - Otherwise the legend items will be placed in a table - with a best fit number of columns from left to right. - - If pos != QwtPlot::ExternalLegend the plot widget will become - parent of the legend. It will be deleted when the plot is deleted, - or another legend is set with insertLegend(). - - \param legend Legend - \param pos The legend's position. For top/left position the number - of colums will be limited to 1, otherwise it will be set to - unlimited. - - \param ratio Ratio between legend and the bounding rect - of title, canvas and axes. The legend will be shrinked - if it would need more space than the given ratio. - The ratio is limited to ]0.0 .. 1.0]. In case of <= 0.0 - it will be reset to the default ratio. - The default vertical/horizontal ratio is 0.33/0.5. - - \sa legend(), QwtPlotLayout::legendPosition(), - QwtPlotLayout::setLegendPosition() -*/ -void QwtPlot::insertLegend( QwtLegend *legend, - QwtPlot::LegendPosition pos, double ratio ) -{ - d_data->layout->setLegendPosition( pos, ratio ); - - if ( legend != d_data->legend ) - { - if ( d_data->legend && d_data->legend->parent() == this ) - delete d_data->legend; - - d_data->legend = legend; - - if ( d_data->legend ) - { - if ( pos != ExternalLegend ) - { - if ( d_data->legend->parent() != this ) - d_data->legend->setParent( this ); - } - - const QwtPlotItemList& itmList = itemList(); - for ( QwtPlotItemIterator it = itmList.begin(); - it != itmList.end(); ++it ) - { - ( *it )->updateLegend( d_data->legend ); - } - - QwtDynGridLayout *tl = qobject_cast( - d_data->legend->contentsWidget()->layout() ); - if ( tl ) - { - switch ( d_data->layout->legendPosition() ) - { - case LeftLegend: - case RightLegend: - tl->setMaxCols( 1 ); // 1 column: align vertical - break; - case TopLegend: - case BottomLegend: - tl->setMaxCols( 0 ); // unlimited - break; - case ExternalLegend: - break; - } - } - } - updateTabOrder(); - } - - updateLayout(); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot.h" +#include "qwt_plot_dict.h" +#include "qwt_plot_layout.h" +#include "qwt_scale_widget.h" +#include "qwt_scale_engine.h" +#include "qwt_text_label.h" +#include "qwt_legend.h" +#include "qwt_dyngrid_layout.h" +#include "qwt_plot_canvas.h" +#include +#include +#include +#include +#include + +class QwtPlot::PrivateData +{ +public: + QPointer lblTitle; + QPointer canvas; + QPointer legend; + QwtPlotLayout *layout; + + bool autoReplot; +}; + +/*! + \brief Constructor + \param parent Parent widget + */ +QwtPlot::QwtPlot( QWidget *parent ): + QFrame( parent ) +{ + initPlot( QwtText() ); +} + +/*! + \brief Constructor + \param title Title text + \param parent Parent widget + */ +QwtPlot::QwtPlot( const QwtText &title, QWidget *parent ): + QFrame( parent ) +{ + initPlot( title ); +} + +//! Destructor +QwtPlot::~QwtPlot() +{ + detachItems( QwtPlotItem::Rtti_PlotItem, autoDelete() ); + + delete d_data->layout; + deleteAxesData(); + delete d_data; +} + +/*! + \brief Initializes a QwtPlot instance + \param title Title text + */ +void QwtPlot::initPlot( const QwtText &title ) +{ + d_data = new PrivateData; + + d_data->layout = new QwtPlotLayout; + d_data->autoReplot = false; + + d_data->lblTitle = new QwtTextLabel( title, this ); + d_data->lblTitle->setObjectName( "QwtPlotTitle" ); + + d_data->lblTitle->setFont( QFont( fontInfo().family(), 14, QFont::Bold ) ); + + QwtText text( title ); + text.setRenderFlags( Qt::AlignCenter | Qt::TextWordWrap ); + d_data->lblTitle->setText( text ); + + d_data->legend = NULL; + + initAxesData(); + + d_data->canvas = new QwtPlotCanvas( this ); + d_data->canvas->setObjectName( "QwtPlotCanvas" ); + d_data->canvas->setFrameStyle( QFrame::Panel | QFrame::Sunken ); + d_data->canvas->setLineWidth( 2 ); + + updateTabOrder(); + + setSizePolicy( QSizePolicy::MinimumExpanding, + QSizePolicy::MinimumExpanding ); + + resize( 200, 200 ); +} + +/*! + \brief Adds handling of layout requests + \param event Event +*/ +bool QwtPlot::event( QEvent *event ) +{ + bool ok = QFrame::event( event ); + switch ( event->type() ) + { + case QEvent::LayoutRequest: + updateLayout(); + break; + case QEvent::PolishRequest: + replot(); + break; + default:; + } + return ok; +} + +//! Replots the plot if autoReplot() is \c true. +void QwtPlot::autoRefresh() +{ + if ( d_data->autoReplot ) + replot(); +} + +/*! + \brief Set or reset the autoReplot option + + If the autoReplot option is set, the plot will be + updated implicitly by manipulating member functions. + Since this may be time-consuming, it is recommended + to leave this option switched off and call replot() + explicitly if necessary. + + The autoReplot option is set to false by default, which + means that the user has to call replot() in order to make + changes visible. + \param tf \c true or \c false. Defaults to \c true. + \sa replot() +*/ +void QwtPlot::setAutoReplot( bool tf ) +{ + d_data->autoReplot = tf; +} + +/*! + \return true if the autoReplot option is set. + \sa setAutoReplot() +*/ +bool QwtPlot::autoReplot() const +{ + return d_data->autoReplot; +} + +/*! + Change the plot's title + \param title New title +*/ +void QwtPlot::setTitle( const QString &title ) +{ + if ( title != d_data->lblTitle->text().text() ) + { + d_data->lblTitle->setText( title ); + updateLayout(); + } +} + +/*! + Change the plot's title + \param title New title +*/ +void QwtPlot::setTitle( const QwtText &title ) +{ + if ( title != d_data->lblTitle->text() ) + { + d_data->lblTitle->setText( title ); + updateLayout(); + } +} + +//! \return the plot's title +QwtText QwtPlot::title() const +{ + return d_data->lblTitle->text(); +} + +//! \return the plot's title +QwtPlotLayout *QwtPlot::plotLayout() +{ + return d_data->layout; +} + +//! \return the plot's titel label. +const QwtPlotLayout *QwtPlot::plotLayout() const +{ + return d_data->layout; +} + +//! \return the plot's titel label. +QwtTextLabel *QwtPlot::titleLabel() +{ + return d_data->lblTitle; +} + +/*! + \return the plot's titel label. +*/ +const QwtTextLabel *QwtPlot::titleLabel() const +{ + return d_data->lblTitle; +} + +/*! + \return the plot's legend + \sa insertLegend() +*/ +QwtLegend *QwtPlot::legend() +{ + return d_data->legend; +} + +/*! + \return the plot's legend + \sa insertLegend() +*/ +const QwtLegend *QwtPlot::legend() const +{ + return d_data->legend; +} + + +/*! + \return the plot's canvas +*/ +QwtPlotCanvas *QwtPlot::canvas() +{ + return d_data->canvas; +} + +/*! + \return the plot's canvas +*/ +const QwtPlotCanvas *QwtPlot::canvas() const +{ + return d_data->canvas; +} + +/*! + Return sizeHint + \sa minimumSizeHint() +*/ + +QSize QwtPlot::sizeHint() const +{ + int dw = 0; + int dh = 0; + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + { + if ( axisEnabled( axisId ) ) + { + const int niceDist = 40; + const QwtScaleWidget *scaleWidget = axisWidget( axisId ); + const QwtScaleDiv &scaleDiv = scaleWidget->scaleDraw()->scaleDiv(); + const int majCnt = scaleDiv.ticks( QwtScaleDiv::MajorTick ).count(); + + if ( axisId == yLeft || axisId == yRight ) + { + int hDiff = ( majCnt - 1 ) * niceDist + - scaleWidget->minimumSizeHint().height(); + if ( hDiff > dh ) + dh = hDiff; + } + else + { + int wDiff = ( majCnt - 1 ) * niceDist + - scaleWidget->minimumSizeHint().width(); + if ( wDiff > dw ) + dw = wDiff; + } + } + } + return minimumSizeHint() + QSize( dw, dh ); +} + +/*! + \brief Return a minimum size hint +*/ +QSize QwtPlot::minimumSizeHint() const +{ + QSize hint = d_data->layout->minimumSizeHint( this ); + hint += QSize( 2 * frameWidth(), 2 * frameWidth() ); + + return hint; +} + +/*! + Resize and update internal layout + \param e Resize event +*/ +void QwtPlot::resizeEvent( QResizeEvent *e ) +{ + QFrame::resizeEvent( e ); + updateLayout(); +} + +/*! + \brief Redraw the plot + + If the autoReplot option is not set (which is the default) + or if any curves are attached to raw data, the plot has to + be refreshed explicitly in order to make changes visible. + + \sa setAutoReplot() + \warning Calls canvas()->repaint, take care of infinite recursions +*/ +void QwtPlot::replot() +{ + bool doAutoReplot = autoReplot(); + setAutoReplot( false ); + + updateAxes(); + + /* + Maybe the layout needs to be updated, because of changed + axes labels. We need to process them here before painting + to avoid that scales and canvas get out of sync. + */ + QApplication::sendPostedEvents( this, QEvent::LayoutRequest ); + + d_data->canvas->replot(); + + setAutoReplot( doAutoReplot ); +} + +/*! + \brief Adjust plot content to its current size. + \sa resizeEvent() +*/ +void QwtPlot::updateLayout() +{ + d_data->layout->activate( this, contentsRect() ); + + QRect titleRect = d_data->layout->titleRect().toRect(); + QRect scaleRect[QwtPlot::axisCnt]; + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + scaleRect[axisId] = d_data->layout->scaleRect( axisId ).toRect(); + QRect legendRect = d_data->layout->legendRect().toRect(); + QRect canvasRect = d_data->layout->canvasRect().toRect(); + + // + // resize and show the visible widgets + // + if ( !d_data->lblTitle->text().isEmpty() ) + { + d_data->lblTitle->setGeometry( titleRect ); + if ( !d_data->lblTitle->isVisibleTo( this ) ) + d_data->lblTitle->show(); + } + else + d_data->lblTitle->hide(); + + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + { + if ( axisEnabled( axisId ) ) + { + axisWidget( axisId )->setGeometry( scaleRect[axisId] ); + + if ( axisId == xBottom || axisId == xTop ) + { + QRegion r( scaleRect[axisId] ); + if ( axisEnabled( yLeft ) ) + r = r.subtract( QRegion( scaleRect[yLeft] ) ); + if ( axisEnabled( yRight ) ) + r = r.subtract( QRegion( scaleRect[yRight] ) ); + r.translate( -d_data->layout->scaleRect( axisId ).x(), + -scaleRect[axisId].y() ); + + axisWidget( axisId )->setMask( r ); + } + if ( !axisWidget( axisId )->isVisibleTo( this ) ) + axisWidget( axisId )->show(); + } + else + axisWidget( axisId )->hide(); + } + + if ( d_data->legend && + d_data->layout->legendPosition() != ExternalLegend ) + { + if ( d_data->legend->itemCount() > 0 ) + { + d_data->legend->setGeometry( legendRect ); + d_data->legend->show(); + } + else + d_data->legend->hide(); + } + + d_data->canvas->setGeometry( canvasRect ); +} + +/*! + Update the focus tab order + + The order is changed so that the canvas will be in front of the + first legend item, or behind the last legend item - depending + on the position of the legend. +*/ + +void QwtPlot::updateTabOrder() +{ + if ( d_data->canvas->focusPolicy() == Qt::NoFocus ) + return; + if ( d_data->legend.isNull() + || d_data->layout->legendPosition() == ExternalLegend + || d_data->legend->legendItems().count() == 0 ) + { + return; + } + + // Depending on the position of the legend the + // tab order will be changed that the canvas is + // next to the last legend item, or before + // the first one. + + const bool canvasFirst = + d_data->layout->legendPosition() == QwtPlot::BottomLegend || + d_data->layout->legendPosition() == QwtPlot::RightLegend; + + QWidget *previous = NULL; + + QWidget *w = d_data->canvas; + while ( ( w = w->nextInFocusChain() ) != d_data->canvas ) + { + bool isLegendItem = false; + if ( w->focusPolicy() != Qt::NoFocus + && w->parent() && w->parent() == d_data->legend->contentsWidget() ) + { + isLegendItem = true; + } + + if ( canvasFirst ) + { + if ( isLegendItem ) + break; + + previous = w; + } + else + { + if ( isLegendItem ) + previous = w; + else + { + if ( previous ) + break; + } + } + } + + if ( previous && previous != d_data->canvas ) + setTabOrder( previous, d_data->canvas ); +} + +/*! + Redraw the canvas. + \param painter Painter used for drawing + + \warning drawCanvas calls drawItems what is also used + for printing. Applications that like to add individual + plot items better overload drawItems() + \sa drawItems() +*/ +void QwtPlot::drawCanvas( QPainter *painter ) +{ + QwtScaleMap maps[axisCnt]; + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + maps[axisId] = canvasMap( axisId ); + + drawItems( painter, d_data->canvas->contentsRect(), maps ); +} + +/*! + Redraw the canvas items. + \param painter Painter used for drawing + \param canvasRect Bounding rectangle where to paint + \param map QwtPlot::axisCnt maps, mapping between plot and paint device coordinates +*/ + +void QwtPlot::drawItems( QPainter *painter, const QRectF &canvasRect, + const QwtScaleMap map[axisCnt] ) const +{ + const QwtPlotItemList& itmList = itemList(); + for ( QwtPlotItemIterator it = itmList.begin(); + it != itmList.end(); ++it ) + { + QwtPlotItem *item = *it; + if ( item && item->isVisible() ) + { + painter->save(); + + painter->setRenderHint( QPainter::Antialiasing, + item->testRenderHint( QwtPlotItem::RenderAntialiased ) ); + + item->draw( painter, + map[item->xAxis()], map[item->yAxis()], + canvasRect ); + + painter->restore(); + } + } +} + +/*! + \param axisId Axis + \return Map for the axis on the canvas. With this map pixel coordinates can + translated to plot coordinates and vice versa. + \sa QwtScaleMap, transform(), invTransform() + +*/ +QwtScaleMap QwtPlot::canvasMap( int axisId ) const +{ + QwtScaleMap map; + if ( !d_data->canvas ) + return map; + + map.setTransformation( axisScaleEngine( axisId )->transformation() ); + + const QwtScaleDiv *sd = axisScaleDiv( axisId ); + map.setScaleInterval( sd->lowerBound(), sd->upperBound() ); + + if ( axisEnabled( axisId ) ) + { + const QwtScaleWidget *s = axisWidget( axisId ); + if ( axisId == yLeft || axisId == yRight ) + { + double y = s->y() + s->startBorderDist() - d_data->canvas->y(); + double h = s->height() - s->startBorderDist() - s->endBorderDist(); + map.setPaintInterval( y + h, y ); + } + else + { + double x = s->x() + s->startBorderDist() - d_data->canvas->x(); + double w = s->width() - s->startBorderDist() - s->endBorderDist(); + map.setPaintInterval( x, x + w ); + } + } + else + { + int margin = 0; + if ( !plotLayout()->alignCanvasToScales() ) + margin = plotLayout()->canvasMargin( axisId ); + + const QRect &canvasRect = d_data->canvas->contentsRect(); + if ( axisId == yLeft || axisId == yRight ) + { + map.setPaintInterval( canvasRect.bottom() - margin, + canvasRect.top() + margin ); + } + else + { + map.setPaintInterval( canvasRect.left() + margin, + canvasRect.right() - margin ); + } + } + return map; +} + +/*! + \brief Change the background of the plotting area + + Sets brush to QPalette::Window of all colorgroups of + the palette of the canvas. Using canvas()->setPalette() + is a more powerful way to set these colors. + + \param brush New background brush + \sa canvasBackground() +*/ +void QwtPlot::setCanvasBackground( const QBrush &brush ) +{ + QPalette pal = d_data->canvas->palette(); + + for ( int i = 0; i < QPalette::NColorGroups; i++ ) + pal.setBrush( ( QPalette::ColorGroup )i, QPalette::Window, brush ); + + canvas()->setPalette( pal ); +} + +/*! + Nothing else than: canvas()->palette().brush( + QPalette::Normal, QPalette::Window); + + \return Background brush of the plotting area. + \sa setCanvasBackground() +*/ +QBrush QwtPlot::canvasBackground() const +{ + return canvas()->palette().brush( + QPalette::Normal, QPalette::Window ); +} + +/*! + \brief Change the border width of the plotting area + + Nothing else than canvas()->setLineWidth(w), + left for compatibility only. + + \param width New border width +*/ +void QwtPlot::setCanvasLineWidth( int width ) +{ + canvas()->setLineWidth( width ); + updateLayout(); +} + +/*! + Nothing else than: canvas()->lineWidth(), + left for compatibility only. + + \return the border width of the plotting area +*/ +int QwtPlot::canvasLineWidth() const +{ + return canvas()->lineWidth(); +} + +/*! + \return \c true if the specified axis exists, otherwise \c false + \param axisId axis index + */ +bool QwtPlot::axisValid( int axisId ) +{ + return ( ( axisId >= QwtPlot::yLeft ) && ( axisId < QwtPlot::axisCnt ) ); +} + +/*! + Called internally when the legend has been clicked on. + Emits a legendClicked() signal. +*/ +void QwtPlot::legendItemClicked() +{ + if ( d_data->legend && sender()->isWidgetType() ) + { + QwtPlotItem *plotItem = + ( QwtPlotItem* )d_data->legend->find( ( QWidget * )sender() ); + if ( plotItem ) + Q_EMIT legendClicked( plotItem ); + } +} + +/*! + Called internally when the legend has been checked + Emits a legendClicked() signal. +*/ +void QwtPlot::legendItemChecked( bool on ) +{ + if ( d_data->legend && sender()->isWidgetType() ) + { + QwtPlotItem *plotItem = + ( QwtPlotItem* )d_data->legend->find( ( QWidget * )sender() ); + if ( plotItem ) + Q_EMIT legendChecked( plotItem, on ); + } +} + +/*! + \brief Insert a legend + + If the position legend is \c QwtPlot::LeftLegend or \c QwtPlot::RightLegend + the legend will be organized in one column from top to down. + Otherwise the legend items will be placed in a table + with a best fit number of columns from left to right. + + If pos != QwtPlot::ExternalLegend the plot widget will become + parent of the legend. It will be deleted when the plot is deleted, + or another legend is set with insertLegend(). + + \param legend Legend + \param pos The legend's position. For top/left position the number + of colums will be limited to 1, otherwise it will be set to + unlimited. + + \param ratio Ratio between legend and the bounding rect + of title, canvas and axes. The legend will be shrinked + if it would need more space than the given ratio. + The ratio is limited to ]0.0 .. 1.0]. In case of <= 0.0 + it will be reset to the default ratio. + The default vertical/horizontal ratio is 0.33/0.5. + + \sa legend(), QwtPlotLayout::legendPosition(), + QwtPlotLayout::setLegendPosition() +*/ +void QwtPlot::insertLegend( QwtLegend *legend, + QwtPlot::LegendPosition pos, double ratio ) +{ + d_data->layout->setLegendPosition( pos, ratio ); + + if ( legend != d_data->legend ) + { + if ( d_data->legend && d_data->legend->parent() == this ) + delete d_data->legend; + + d_data->legend = legend; + + if ( d_data->legend ) + { + if ( pos != ExternalLegend ) + { + if ( d_data->legend->parent() != this ) + d_data->legend->setParent( this ); + } + + const QwtPlotItemList& itmList = itemList(); + for ( QwtPlotItemIterator it = itmList.begin(); + it != itmList.end(); ++it ) + { + ( *it )->updateLegend( d_data->legend ); + } + + QwtDynGridLayout *tl = qobject_cast( + d_data->legend->contentsWidget()->layout() ); + if ( tl ) + { + switch ( d_data->layout->legendPosition() ) + { + case LeftLegend: + case RightLegend: + tl->setMaxCols( 1 ); // 1 column: align vertical + break; + case TopLegend: + case BottomLegend: + tl->setMaxCols( 0 ); // unlimited + break; + case ExternalLegend: + break; + } + } + } + updateTabOrder(); + } + + updateLayout(); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot.h index 0528849d8..88a8530bf 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot.h @@ -1,290 +1,290 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PLOT_H -#define QWT_PLOT_H - -#include "qwt_global.h" -#include "qwt_text.h" -#include "qwt_plot_dict.h" -#include "qwt_scale_map.h" -#include "qwt_interval.h" -#include - -class QwtPlotLayout; -class QwtLegend; -class QwtScaleWidget; -class QwtScaleEngine; -class QwtScaleDiv; -class QwtScaleDraw; -class QwtTextLabel; -class QwtPlotCanvas; - -/*! - \brief A 2-D plotting widget - - QwtPlot is a widget for plotting two-dimensional graphs. - An unlimited number of plot items can be displayed on - its canvas. Plot items might be curves (QwtPlotCurve), markers - (QwtPlotMarker), the grid (QwtPlotGrid), or anything else derived - from QwtPlotItem. - A plot can have up to four axes, with each plot item attached to an x- and - a y axis. The scales at the axes can be explicitely set (QwtScaleDiv), or - are calculated from the plot items, using algorithms (QwtScaleEngine) which - can be configured separately for each axis. - - \image html plot.png - - \par Example - The following example shows (schematically) the most simple - way to use QwtPlot. By default, only the left and bottom axes are - visible and their scales are computed automatically. - \verbatim -#include -#include - -QwtPlot *myPlot = new QwtPlot("Two Curves", parent); - -// add curves -QwtPlotCurve *curve1 = new QwtPlotCurve("Curve 1"); -QwtPlotCurve *curve2 = new QwtPlotCurve("Curve 2"); - -// copy the data into the curves -curve1->setData(...); -curve2->setData(...); - -curve1->attach(myPlot); -curve2->attach(myPlot); - -// finally, refresh the plot -myPlot->replot(); -\endverbatim -*/ - -class QWT_EXPORT QwtPlot: public QFrame, public QwtPlotDict -{ - Q_OBJECT - Q_PROPERTY( QString propertiesDocument - READ grabProperties WRITE applyProperties ) - -public: - //! \brief Axis index - enum Axis - { - //! Y axis left of the canvas - yLeft, - - //! Y axis right of the canvas - yRight, - - //! X axis below the canvas - xBottom, - - //! X axis above the canvas - xTop, - - //! Number of axes - axisCnt - }; - - /*! - Position of the legend, relative to the canvas. - - \sa insertLegend() - \note In case of ExternalLegend, the legend is not - handled by QwtPlotRenderer - */ - enum LegendPosition - { - //! The legend will be left from the QwtPlot::yLeft axis. - LeftLegend, - - //! The legend will be right from the QwtPlot::yRight axis. - RightLegend, - - //! The legend will be below QwtPlot::xBottom axis. - BottomLegend, - - //! The legend will be between QwtPlot::xTop axis and the title. - TopLegend, - - /*! - External means that only the content of the legend - will be handled by QwtPlot, but not its geometry. - This type can be used to have a legend in an - external window ( or on the canvas ). - */ - ExternalLegend - }; - - explicit QwtPlot( QWidget * = NULL ); - explicit QwtPlot( const QwtText &title, QWidget *p = NULL ); - - virtual ~QwtPlot(); - - void applyProperties( const QString & ); - QString grabProperties() const; - - void setAutoReplot( bool tf = true ); - bool autoReplot() const; - - // Layout - - QwtPlotLayout *plotLayout(); - const QwtPlotLayout *plotLayout() const; - - // Title - - void setTitle( const QString & ); - void setTitle( const QwtText &t ); - QwtText title() const; - - QwtTextLabel *titleLabel(); - const QwtTextLabel *titleLabel() const; - - // Canvas - - QwtPlotCanvas *canvas(); - const QwtPlotCanvas *canvas() const; - - void setCanvasBackground( const QBrush & ); - QBrush canvasBackground() const; - - void setCanvasLineWidth( int w ); - int canvasLineWidth() const; - - virtual QwtScaleMap canvasMap( int axisId ) const; - - double invTransform( int axisId, int pos ) const; - double transform( int axisId, double value ) const; - - // Axes - - QwtScaleEngine *axisScaleEngine( int axisId ); - const QwtScaleEngine *axisScaleEngine( int axisId ) const; - void setAxisScaleEngine( int axisId, QwtScaleEngine * ); - - void setAxisAutoScale( int axisId, bool on = true ); - bool axisAutoScale( int axisId ) const; - - void enableAxis( int axisId, bool tf = true ); - bool axisEnabled( int axisId ) const; - - void setAxisFont( int axisId, const QFont &f ); - QFont axisFont( int axisId ) const; - - void setAxisScale( int axisId, double min, double max, double step = 0 ); - void setAxisScaleDiv( int axisId, const QwtScaleDiv & ); - void setAxisScaleDraw( int axisId, QwtScaleDraw * ); - - double axisStepSize( int axisId ) const; - QwtInterval axisInterval( int axisId ) const; - - const QwtScaleDiv *axisScaleDiv( int axisId ) const; - QwtScaleDiv *axisScaleDiv( int axisId ); - - const QwtScaleDraw *axisScaleDraw( int axisId ) const; - QwtScaleDraw *axisScaleDraw( int axisId ); - - const QwtScaleWidget *axisWidget( int axisId ) const; - QwtScaleWidget *axisWidget( int axisId ); - - void setAxisLabelAlignment( int axisId, Qt::Alignment ); - void setAxisLabelRotation( int axisId, double rotation ); - - void setAxisTitle( int axisId, const QString & ); - void setAxisTitle( int axisId, const QwtText & ); - QwtText axisTitle( int axisId ) const; - - void setAxisMaxMinor( int axisId, int maxMinor ); - int axisMaxMinor( int axisId ) const; - - void setAxisMaxMajor( int axisId, int maxMajor ); - int axisMaxMajor( int axisId ) const; - - // Legend - - void insertLegend( QwtLegend *, LegendPosition = QwtPlot::RightLegend, - double ratio = -1.0 ); - - QwtLegend *legend(); - const QwtLegend *legend() const; - - // Misc - - virtual QSize sizeHint() const; - virtual QSize minimumSizeHint() const; - - virtual void updateLayout(); - virtual void drawCanvas( QPainter * ); - - void updateAxes(); - - virtual bool event( QEvent * ); - - virtual void drawItems( QPainter *, const QRectF &, - const QwtScaleMap maps[axisCnt] ) const; - -Q_SIGNALS: - /*! - A signal which is emitted when the user has clicked on - a legend item, which is in QwtLegend::ClickableItem mode. - - \param plotItem Corresponding plot item of the - selected legend item - - \note clicks are disabled as default - \sa QwtLegend::setItemMode(), QwtLegend::itemMode() - */ - void legendClicked( QwtPlotItem *plotItem ); - - /*! - A signal which is emitted when the user has clicked on - a legend item, which is in QwtLegend::CheckableItem mode - - \param plotItem Corresponding plot item of the - selected legend item - \param on True when the legen item is checked - - \note clicks are disabled as default - \sa QwtLegend::setItemMode(), QwtLegend::itemMode() - */ - - void legendChecked( QwtPlotItem *plotItem, bool on ); - -public Q_SLOTS: - virtual void replot(); - void autoRefresh(); - -protected Q_SLOTS: - virtual void legendItemClicked(); - virtual void legendItemChecked( bool ); - -protected: - static bool axisValid( int axisId ); - - virtual void updateTabOrder(); - - virtual void resizeEvent( QResizeEvent *e ); - -private: - void initAxesData(); - void deleteAxesData(); - void updateScaleDiv(); - - void initPlot( const QwtText &title ); - - class AxisData; - AxisData *d_axisData[axisCnt]; - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_H +#define QWT_PLOT_H + +#include "qwt_global.h" +#include "qwt_text.h" +#include "qwt_plot_dict.h" +#include "qwt_scale_map.h" +#include "qwt_interval.h" +#include + +class QwtPlotLayout; +class QwtLegend; +class QwtScaleWidget; +class QwtScaleEngine; +class QwtScaleDiv; +class QwtScaleDraw; +class QwtTextLabel; +class QwtPlotCanvas; + +/*! + \brief A 2-D plotting widget + + QwtPlot is a widget for plotting two-dimensional graphs. + An unlimited number of plot items can be displayed on + its canvas. Plot items might be curves (QwtPlotCurve), markers + (QwtPlotMarker), the grid (QwtPlotGrid), or anything else derived + from QwtPlotItem. + A plot can have up to four axes, with each plot item attached to an x- and + a y axis. The scales at the axes can be explicitely set (QwtScaleDiv), or + are calculated from the plot items, using algorithms (QwtScaleEngine) which + can be configured separately for each axis. + + \image html plot.png + + \par Example + The following example shows (schematically) the most simple + way to use QwtPlot. By default, only the left and bottom axes are + visible and their scales are computed automatically. + \verbatim +#include +#include + +QwtPlot *myPlot = new QwtPlot("Two Curves", parent); + +// add curves +QwtPlotCurve *curve1 = new QwtPlotCurve("Curve 1"); +QwtPlotCurve *curve2 = new QwtPlotCurve("Curve 2"); + +// copy the data into the curves +curve1->setData(...); +curve2->setData(...); + +curve1->attach(myPlot); +curve2->attach(myPlot); + +// finally, refresh the plot +myPlot->replot(); +\endverbatim +*/ + +class QWT_EXPORT QwtPlot: public QFrame, public QwtPlotDict +{ + Q_OBJECT + Q_PROPERTY( QString propertiesDocument + READ grabProperties WRITE applyProperties ) + +public: + //! \brief Axis index + enum Axis + { + //! Y axis left of the canvas + yLeft, + + //! Y axis right of the canvas + yRight, + + //! X axis below the canvas + xBottom, + + //! X axis above the canvas + xTop, + + //! Number of axes + axisCnt + }; + + /*! + Position of the legend, relative to the canvas. + + \sa insertLegend() + \note In case of ExternalLegend, the legend is not + handled by QwtPlotRenderer + */ + enum LegendPosition + { + //! The legend will be left from the QwtPlot::yLeft axis. + LeftLegend, + + //! The legend will be right from the QwtPlot::yRight axis. + RightLegend, + + //! The legend will be below QwtPlot::xBottom axis. + BottomLegend, + + //! The legend will be between QwtPlot::xTop axis and the title. + TopLegend, + + /*! + External means that only the content of the legend + will be handled by QwtPlot, but not its geometry. + This type can be used to have a legend in an + external window ( or on the canvas ). + */ + ExternalLegend + }; + + explicit QwtPlot( QWidget * = NULL ); + explicit QwtPlot( const QwtText &title, QWidget *p = NULL ); + + virtual ~QwtPlot(); + + void applyProperties( const QString & ); + QString grabProperties() const; + + void setAutoReplot( bool tf = true ); + bool autoReplot() const; + + // Layout + + QwtPlotLayout *plotLayout(); + const QwtPlotLayout *plotLayout() const; + + // Title + + void setTitle( const QString & ); + void setTitle( const QwtText &t ); + QwtText title() const; + + QwtTextLabel *titleLabel(); + const QwtTextLabel *titleLabel() const; + + // Canvas + + QwtPlotCanvas *canvas(); + const QwtPlotCanvas *canvas() const; + + void setCanvasBackground( const QBrush & ); + QBrush canvasBackground() const; + + void setCanvasLineWidth( int w ); + int canvasLineWidth() const; + + virtual QwtScaleMap canvasMap( int axisId ) const; + + double invTransform( int axisId, int pos ) const; + double transform( int axisId, double value ) const; + + // Axes + + QwtScaleEngine *axisScaleEngine( int axisId ); + const QwtScaleEngine *axisScaleEngine( int axisId ) const; + void setAxisScaleEngine( int axisId, QwtScaleEngine * ); + + void setAxisAutoScale( int axisId, bool on = true ); + bool axisAutoScale( int axisId ) const; + + void enableAxis( int axisId, bool tf = true ); + bool axisEnabled( int axisId ) const; + + void setAxisFont( int axisId, const QFont &f ); + QFont axisFont( int axisId ) const; + + void setAxisScale( int axisId, double min, double max, double step = 0 ); + void setAxisScaleDiv( int axisId, const QwtScaleDiv & ); + void setAxisScaleDraw( int axisId, QwtScaleDraw * ); + + double axisStepSize( int axisId ) const; + QwtInterval axisInterval( int axisId ) const; + + const QwtScaleDiv *axisScaleDiv( int axisId ) const; + QwtScaleDiv *axisScaleDiv( int axisId ); + + const QwtScaleDraw *axisScaleDraw( int axisId ) const; + QwtScaleDraw *axisScaleDraw( int axisId ); + + const QwtScaleWidget *axisWidget( int axisId ) const; + QwtScaleWidget *axisWidget( int axisId ); + + void setAxisLabelAlignment( int axisId, Qt::Alignment ); + void setAxisLabelRotation( int axisId, double rotation ); + + void setAxisTitle( int axisId, const QString & ); + void setAxisTitle( int axisId, const QwtText & ); + QwtText axisTitle( int axisId ) const; + + void setAxisMaxMinor( int axisId, int maxMinor ); + int axisMaxMinor( int axisId ) const; + + void setAxisMaxMajor( int axisId, int maxMajor ); + int axisMaxMajor( int axisId ) const; + + // Legend + + void insertLegend( QwtLegend *, LegendPosition = QwtPlot::RightLegend, + double ratio = -1.0 ); + + QwtLegend *legend(); + const QwtLegend *legend() const; + + // Misc + + virtual QSize sizeHint() const; + virtual QSize minimumSizeHint() const; + + virtual void updateLayout(); + virtual void drawCanvas( QPainter * ); + + void updateAxes(); + + virtual bool event( QEvent * ); + + virtual void drawItems( QPainter *, const QRectF &, + const QwtScaleMap maps[axisCnt] ) const; + +Q_SIGNALS: + /*! + A signal which is emitted when the user has clicked on + a legend item, which is in QwtLegend::ClickableItem mode. + + \param plotItem Corresponding plot item of the + selected legend item + + \note clicks are disabled as default + \sa QwtLegend::setItemMode(), QwtLegend::itemMode() + */ + void legendClicked( QwtPlotItem *plotItem ); + + /*! + A signal which is emitted when the user has clicked on + a legend item, which is in QwtLegend::CheckableItem mode + + \param plotItem Corresponding plot item of the + selected legend item + \param on True when the legen item is checked + + \note clicks are disabled as default + \sa QwtLegend::setItemMode(), QwtLegend::itemMode() + */ + + void legendChecked( QwtPlotItem *plotItem, bool on ); + +public Q_SLOTS: + virtual void replot(); + void autoRefresh(); + +protected Q_SLOTS: + virtual void legendItemClicked(); + virtual void legendItemChecked( bool ); + +protected: + static bool axisValid( int axisId ); + + virtual void updateTabOrder(); + + virtual void resizeEvent( QResizeEvent *e ); + +private: + void initAxesData(); + void deleteAxesData(); + void updateScaleDiv(); + + void initPlot( const QwtText &title ); + + class AxisData; + AxisData *d_axisData[axisCnt]; + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_axis.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_axis.cpp index cef5bd101..66f2fa123 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_axis.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_axis.cpp @@ -1,670 +1,670 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot.h" -#include "qwt_math.h" -#include "qwt_scale_widget.h" -#include "qwt_scale_div.h" -#include "qwt_scale_engine.h" - -class QwtPlot::AxisData -{ -public: - bool isEnabled; - bool doAutoScale; - - double minValue; - double maxValue; - double stepSize; - - int maxMajor; - int maxMinor; - - QwtScaleDiv scaleDiv; - QwtScaleEngine *scaleEngine; - QwtScaleWidget *scaleWidget; -}; - -//! Initialize axes -void QwtPlot::initAxesData() -{ - int axisId; - - for ( axisId = 0; axisId < axisCnt; axisId++ ) - d_axisData[axisId] = new AxisData; - - d_axisData[yLeft]->scaleWidget = - new QwtScaleWidget( QwtScaleDraw::LeftScale, this ); - d_axisData[yRight]->scaleWidget = - new QwtScaleWidget( QwtScaleDraw::RightScale, this ); - d_axisData[xTop]->scaleWidget = - new QwtScaleWidget( QwtScaleDraw::TopScale, this ); - d_axisData[xBottom]->scaleWidget = - new QwtScaleWidget( QwtScaleDraw::BottomScale, this ); - - d_axisData[yLeft]->scaleWidget->setObjectName( "QwtPlotAxisYLeft" ); - d_axisData[yRight]->scaleWidget->setObjectName( "QwtPlotAxisYRight" ); - d_axisData[xTop]->scaleWidget->setObjectName( "QwtPlotAxisXTop" ); - d_axisData[xBottom]->scaleWidget->setObjectName( "QwtPlotAxisXBottom" ); - - QFont fscl( fontInfo().family(), 10 ); - QFont fttl( fontInfo().family(), 12, QFont::Bold ); - - for ( axisId = 0; axisId < axisCnt; axisId++ ) - { - AxisData &d = *d_axisData[axisId]; - - d.scaleWidget->setFont( fscl ); - d.scaleWidget->setMargin( 2 ); - - QwtText text = d.scaleWidget->title(); - text.setFont( fttl ); - d.scaleWidget->setTitle( text ); - - d.doAutoScale = true; - - d.minValue = 0.0; - d.maxValue = 1000.0; - d.stepSize = 0.0; - - d.maxMinor = 5; - d.maxMajor = 8; - - d.scaleEngine = new QwtLinearScaleEngine; - - d.scaleDiv.invalidate(); - } - - d_axisData[yLeft]->isEnabled = true; - d_axisData[yRight]->isEnabled = false; - d_axisData[xBottom]->isEnabled = true; - d_axisData[xTop]->isEnabled = false; -} - -void QwtPlot::deleteAxesData() -{ - for ( int axisId = 0; axisId < axisCnt; axisId++ ) - { - delete d_axisData[axisId]->scaleEngine; - delete d_axisData[axisId]; - d_axisData[axisId] = NULL; - } -} - -/*! - \return specified axis, or NULL if axisId is invalid. - \param axisId axis index -*/ -const QwtScaleWidget *QwtPlot::axisWidget( int axisId ) const -{ - if ( axisValid( axisId ) ) - return d_axisData[axisId]->scaleWidget; - - return NULL; -} - -/*! - \return specified axis, or NULL if axisId is invalid. - \param axisId axis index -*/ -QwtScaleWidget *QwtPlot::axisWidget( int axisId ) -{ - if ( axisValid( axisId ) ) - return d_axisData[axisId]->scaleWidget; - - return NULL; -} - -/*! - Change the scale engine for an axis - - \param axisId axis index - \param scaleEngine Scale engine - - \sa axisScaleEngine() -*/ -void QwtPlot::setAxisScaleEngine( int axisId, QwtScaleEngine *scaleEngine ) -{ - if ( axisValid( axisId ) && scaleEngine != NULL ) - { - AxisData &d = *d_axisData[axisId]; - - delete d.scaleEngine; - d.scaleEngine = scaleEngine; - - d.scaleDiv.invalidate(); - - autoRefresh(); - } -} - -/*! - \param axisId axis index - \return Scale engine for a specific axis -*/ -QwtScaleEngine *QwtPlot::axisScaleEngine( int axisId ) -{ - if ( axisValid( axisId ) ) - return d_axisData[axisId]->scaleEngine; - else - return NULL; -} - -/*! - \param axisId axis index - \return Scale engine for a specific axis -*/ -const QwtScaleEngine *QwtPlot::axisScaleEngine( int axisId ) const -{ - if ( axisValid( axisId ) ) - return d_axisData[axisId]->scaleEngine; - else - return NULL; -} -/*! - \return \c true if autoscaling is enabled - \param axisId axis index -*/ -bool QwtPlot::axisAutoScale( int axisId ) const -{ - if ( axisValid( axisId ) ) - return d_axisData[axisId]->doAutoScale; - else - return false; - -} - -/*! - \return \c true if a specified axis is enabled - \param axisId axis index -*/ -bool QwtPlot::axisEnabled( int axisId ) const -{ - if ( axisValid( axisId ) ) - return d_axisData[axisId]->isEnabled; - else - return false; -} - -/*! - \return the font of the scale labels for a specified axis - \param axisId axis index -*/ -QFont QwtPlot::axisFont( int axisId ) const -{ - if ( axisValid( axisId ) ) - return axisWidget( axisId )->font(); - else - return QFont(); - -} - -/*! - \return the maximum number of major ticks for a specified axis - \param axisId axis index - \sa setAxisMaxMajor() -*/ -int QwtPlot::axisMaxMajor( int axisId ) const -{ - if ( axisValid( axisId ) ) - return d_axisData[axisId]->maxMajor; - else - return 0; -} - -/*! - \return the maximum number of minor ticks for a specified axis - \param axisId axis index - \sa setAxisMaxMinor() -*/ -int QwtPlot::axisMaxMinor( int axisId ) const -{ - if ( axisValid( axisId ) ) - return d_axisData[axisId]->maxMinor; - else - return 0; -} - -/*! - \brief Return the scale division of a specified axis - - axisScaleDiv(axisId)->lowerBound(), axisScaleDiv(axisId)->upperBound() - are the current limits of the axis scale. - - \param axisId axis index - \return Scale division - - \sa QwtScaleDiv, setAxisScaleDiv() -*/ -const QwtScaleDiv *QwtPlot::axisScaleDiv( int axisId ) const -{ - if ( !axisValid( axisId ) ) - return NULL; - - return &d_axisData[axisId]->scaleDiv; -} - -/*! - \brief Return the scale division of a specified axis - - axisScaleDiv(axisId)->lowerBound(), axisScaleDiv(axisId)->upperBound() - are the current limits of the axis scale. - - \param axisId axis index - \return Scale division - - \sa QwtScaleDiv, setAxisScaleDiv() -*/ -QwtScaleDiv *QwtPlot::axisScaleDiv( int axisId ) -{ - if ( !axisValid( axisId ) ) - return NULL; - - return &d_axisData[axisId]->scaleDiv; -} - -/*! - \returns the scale draw of a specified axis - \param axisId axis index - \return specified scaleDraw for axis, or NULL if axis is invalid. - \sa QwtScaleDraw -*/ -const QwtScaleDraw *QwtPlot::axisScaleDraw( int axisId ) const -{ - if ( !axisValid( axisId ) ) - return NULL; - - return axisWidget( axisId )->scaleDraw(); -} - -/*! - \returns the scale draw of a specified axis - \param axisId axis index - \return specified scaleDraw for axis, or NULL if axis is invalid. - \sa QwtScaleDraw -*/ -QwtScaleDraw *QwtPlot::axisScaleDraw( int axisId ) -{ - if ( !axisValid( axisId ) ) - return NULL; - - return axisWidget( axisId )->scaleDraw(); -} - -/*! - Return the step size parameter, that has been set - in setAxisScale. This doesn't need to be the step size - of the current scale. - - \param axisId axis index - \return step size parameter value - - \sa setAxisScale() -*/ -double QwtPlot::axisStepSize( int axisId ) const -{ - if ( !axisValid( axisId ) ) - return 0; - - return d_axisData[axisId]->stepSize; -} - -/*! - \brief Return the current interval of the specified axis - - This is only a convenience function for axisScaleDiv( axisId )->interval(); - - \param axisId axis index - \return Scale interval - - \sa QwtScaleDiv, axisScaleDiv() -*/ -QwtInterval QwtPlot::axisInterval( int axisId ) const -{ - if ( !axisValid( axisId ) ) - return QwtInterval(); - - return d_axisData[axisId]->scaleDiv.interval(); -} - -/*! - \return the title of a specified axis - \param axisId axis index -*/ -QwtText QwtPlot::axisTitle( int axisId ) const -{ - if ( axisValid( axisId ) ) - return axisWidget( axisId )->title(); - else - return QwtText(); -} - -/*! - \brief Enable or disable a specified axis - - When an axis is disabled, this only means that it is not - visible on the screen. Curves, markers and can be attached - to disabled axes, and transformation of screen coordinates - into values works as normal. - - Only xBottom and yLeft are enabled by default. - \param axisId axis index - \param tf \c true (enabled) or \c false (disabled) -*/ -void QwtPlot::enableAxis( int axisId, bool tf ) -{ - if ( axisValid( axisId ) && tf != d_axisData[axisId]->isEnabled ) - { - d_axisData[axisId]->isEnabled = tf; - updateLayout(); - } -} - -/*! - Transform the x or y coordinate of a position in the - drawing region into a value. - \param axisId axis index - \param pos position - \warning The position can be an x or a y coordinate, - depending on the specified axis. -*/ -double QwtPlot::invTransform( int axisId, int pos ) const -{ - if ( axisValid( axisId ) ) - return( canvasMap( axisId ).invTransform( pos ) ); - else - return 0.0; -} - - -/*! - \brief Transform a value into a coordinate in the plotting region - \param axisId axis index - \param value value - \return X or y coordinate in the plotting region corresponding - to the value. -*/ -double QwtPlot::transform( int axisId, double value ) const -{ - if ( axisValid( axisId ) ) - return( canvasMap( axisId ).transform( value ) ); - else - return 0.0; -} - -/*! - \brief Change the font of an axis - \param axisId axis index - \param f font - \warning This function changes the font of the tick labels, - not of the axis title. -*/ -void QwtPlot::setAxisFont( int axisId, const QFont &f ) -{ - if ( axisValid( axisId ) ) - axisWidget( axisId )->setFont( f ); -} - -/*! - \brief Enable autoscaling for a specified axis - - This member function is used to switch back to autoscaling mode - after a fixed scale has been set. Autoscaling is enabled by default. - - \param axisId axis index - \param on On/Off - \sa setAxisScale(), setAxisScaleDiv(), updateAxes() - - \note The autoscaling flag has no effect until updateAxes() is executed - ( called by replot() ). -*/ -void QwtPlot::setAxisAutoScale( int axisId, bool on ) -{ - if ( axisValid( axisId ) && ( d_axisData[axisId]->doAutoScale != on ) ) - { - d_axisData[axisId]->doAutoScale = on; - autoRefresh(); - } -} - -/*! - \brief Disable autoscaling and specify a fixed scale for a selected axis. - \param axisId axis index - \param min - \param max minimum and maximum of the scale - \param stepSize Major step size. If step == 0, the step size is - calculated automatically using the maxMajor setting. - \sa setAxisMaxMajor(), setAxisAutoScale(), axisStepSize() -*/ -void QwtPlot::setAxisScale( int axisId, double min, double max, double stepSize ) -{ - if ( axisValid( axisId ) ) - { - AxisData &d = *d_axisData[axisId]; - - d.doAutoScale = false; - d.scaleDiv.invalidate(); - - d.minValue = min; - d.maxValue = max; - d.stepSize = stepSize; - - autoRefresh(); - } -} - -/*! - \brief Disable autoscaling and specify a fixed scale for a selected axis. - \param axisId axis index - \param scaleDiv Scale division - \sa setAxisScale(), setAxisAutoScale() -*/ -void QwtPlot::setAxisScaleDiv( int axisId, const QwtScaleDiv &scaleDiv ) -{ - if ( axisValid( axisId ) ) - { - AxisData &d = *d_axisData[axisId]; - - d.doAutoScale = false; - d.scaleDiv = scaleDiv; - - autoRefresh(); - } -} - -/*! - \brief Set a scale draw - \param axisId axis index - \param scaleDraw object responsible for drawing scales. - - By passing scaleDraw it is possible to extend QwtScaleDraw - functionality and let it take place in QwtPlot. Please note - that scaleDraw has to be created with new and will be deleted - by the corresponding QwtScale member ( like a child object ). - - \sa QwtScaleDraw, QwtScaleWidget - \warning The attributes of scaleDraw will be overwritten by those of the - previous QwtScaleDraw. -*/ - -void QwtPlot::setAxisScaleDraw( int axisId, QwtScaleDraw *scaleDraw ) -{ - if ( axisValid( axisId ) ) - { - axisWidget( axisId )->setScaleDraw( scaleDraw ); - autoRefresh(); - } -} - -/*! - Change the alignment of the tick labels - \param axisId axis index - \param alignment Or'd Qt::AlignmentFlags see - \sa QwtScaleDraw::setLabelAlignment() -*/ -void QwtPlot::setAxisLabelAlignment( int axisId, Qt::Alignment alignment ) -{ - if ( axisValid( axisId ) ) - axisWidget( axisId )->setLabelAlignment( alignment ); -} - -/*! - Rotate all tick labels - \param axisId axis index - \param rotation Angle in degrees. When changing the label rotation, - the label alignment might be adjusted too. - \sa QwtScaleDraw::setLabelRotation(), setAxisLabelAlignment() -*/ -void QwtPlot::setAxisLabelRotation( int axisId, double rotation ) -{ - if ( axisValid( axisId ) ) - axisWidget( axisId )->setLabelRotation( rotation ); -} - -/*! - Set the maximum number of minor scale intervals for a specified axis - - \param axisId axis index - \param maxMinor maximum number of minor steps - \sa axisMaxMinor() -*/ -void QwtPlot::setAxisMaxMinor( int axisId, int maxMinor ) -{ - if ( axisValid( axisId ) ) - { - maxMinor = qBound( 0, maxMinor, 100 ); - - AxisData &d = *d_axisData[axisId]; - if ( maxMinor != d.maxMinor ) - { - d.maxMinor = maxMinor; - d.scaleDiv.invalidate(); - autoRefresh(); - } - } -} - -/*! - Set the maximum number of major scale intervals for a specified axis - - \param axisId axis index - \param maxMajor maximum number of major steps - \sa axisMaxMajor() -*/ -void QwtPlot::setAxisMaxMajor( int axisId, int maxMajor ) -{ - if ( axisValid( axisId ) ) - { - maxMajor = qBound( 1, maxMajor, 10000 ); - - AxisData &d = *d_axisData[axisId]; - if ( maxMajor != d.maxMajor ) - { - d.maxMajor = maxMajor; - d.scaleDiv.invalidate(); - autoRefresh(); - } - } -} - -/*! - \brief Change the title of a specified axis - \param axisId axis index - \param title axis title -*/ -void QwtPlot::setAxisTitle( int axisId, const QString &title ) -{ - if ( axisValid( axisId ) ) - axisWidget( axisId )->setTitle( title ); -} - -/*! - \brief Change the title of a specified axis - \param axisId axis index - \param title axis title -*/ -void QwtPlot::setAxisTitle( int axisId, const QwtText &title ) -{ - if ( axisValid( axisId ) ) - axisWidget( axisId )->setTitle( title ); -} - -//! Rebuild the scales -void QwtPlot::updateAxes() -{ - // Find bounding interval of the item data - // for all axes, where autoscaling is enabled - - QwtInterval intv[axisCnt]; - - const QwtPlotItemList& itmList = itemList(); - - QwtPlotItemIterator it; - for ( it = itmList.begin(); it != itmList.end(); ++it ) - { - const QwtPlotItem *item = *it; - - if ( !item->testItemAttribute( QwtPlotItem::AutoScale ) ) - continue; - - if ( !item->isVisible() ) - continue; - - if ( axisAutoScale( item->xAxis() ) || axisAutoScale( item->yAxis() ) ) - { - const QRectF rect = item->boundingRect(); - intv[item->xAxis()] |= QwtInterval( rect.left(), rect.right() ); - intv[item->yAxis()] |= QwtInterval( rect.top(), rect.bottom() ); - } - } - - // Adjust scales - - for ( int axisId = 0; axisId < axisCnt; axisId++ ) - { - AxisData &d = *d_axisData[axisId]; - - double minValue = d.minValue; - double maxValue = d.maxValue; - double stepSize = d.stepSize; - - if ( d.doAutoScale && intv[axisId].isValid() ) - { - d.scaleDiv.invalidate(); - - minValue = intv[axisId].minValue(); - maxValue = intv[axisId].maxValue(); - - d.scaleEngine->autoScale( d.maxMajor, - minValue, maxValue, stepSize ); - } - if ( !d.scaleDiv.isValid() ) - { - d.scaleDiv = d.scaleEngine->divideScale( - minValue, maxValue, - d.maxMajor, d.maxMinor, stepSize ); - } - - QwtScaleWidget *scaleWidget = axisWidget( axisId ); - scaleWidget->setScaleDiv( - d.scaleEngine->transformation(), d.scaleDiv ); - - int startDist, endDist; - scaleWidget->getBorderDistHint( startDist, endDist ); - scaleWidget->setBorderDist( startDist, endDist ); - } - - for ( it = itmList.begin(); it != itmList.end(); ++it ) - { - QwtPlotItem *item = *it; - item->updateScaleDiv( *axisScaleDiv( item->xAxis() ), - *axisScaleDiv( item->yAxis() ) ); - } -} - +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot.h" +#include "qwt_math.h" +#include "qwt_scale_widget.h" +#include "qwt_scale_div.h" +#include "qwt_scale_engine.h" + +class QwtPlot::AxisData +{ +public: + bool isEnabled; + bool doAutoScale; + + double minValue; + double maxValue; + double stepSize; + + int maxMajor; + int maxMinor; + + QwtScaleDiv scaleDiv; + QwtScaleEngine *scaleEngine; + QwtScaleWidget *scaleWidget; +}; + +//! Initialize axes +void QwtPlot::initAxesData() +{ + int axisId; + + for ( axisId = 0; axisId < axisCnt; axisId++ ) + d_axisData[axisId] = new AxisData; + + d_axisData[yLeft]->scaleWidget = + new QwtScaleWidget( QwtScaleDraw::LeftScale, this ); + d_axisData[yRight]->scaleWidget = + new QwtScaleWidget( QwtScaleDraw::RightScale, this ); + d_axisData[xTop]->scaleWidget = + new QwtScaleWidget( QwtScaleDraw::TopScale, this ); + d_axisData[xBottom]->scaleWidget = + new QwtScaleWidget( QwtScaleDraw::BottomScale, this ); + + d_axisData[yLeft]->scaleWidget->setObjectName( "QwtPlotAxisYLeft" ); + d_axisData[yRight]->scaleWidget->setObjectName( "QwtPlotAxisYRight" ); + d_axisData[xTop]->scaleWidget->setObjectName( "QwtPlotAxisXTop" ); + d_axisData[xBottom]->scaleWidget->setObjectName( "QwtPlotAxisXBottom" ); + + QFont fscl( fontInfo().family(), 10 ); + QFont fttl( fontInfo().family(), 12, QFont::Bold ); + + for ( axisId = 0; axisId < axisCnt; axisId++ ) + { + AxisData &d = *d_axisData[axisId]; + + d.scaleWidget->setFont( fscl ); + d.scaleWidget->setMargin( 2 ); + + QwtText text = d.scaleWidget->title(); + text.setFont( fttl ); + d.scaleWidget->setTitle( text ); + + d.doAutoScale = true; + + d.minValue = 0.0; + d.maxValue = 1000.0; + d.stepSize = 0.0; + + d.maxMinor = 5; + d.maxMajor = 8; + + d.scaleEngine = new QwtLinearScaleEngine; + + d.scaleDiv.invalidate(); + } + + d_axisData[yLeft]->isEnabled = true; + d_axisData[yRight]->isEnabled = false; + d_axisData[xBottom]->isEnabled = true; + d_axisData[xTop]->isEnabled = false; +} + +void QwtPlot::deleteAxesData() +{ + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + { + delete d_axisData[axisId]->scaleEngine; + delete d_axisData[axisId]; + d_axisData[axisId] = NULL; + } +} + +/*! + \return specified axis, or NULL if axisId is invalid. + \param axisId axis index +*/ +const QwtScaleWidget *QwtPlot::axisWidget( int axisId ) const +{ + if ( axisValid( axisId ) ) + return d_axisData[axisId]->scaleWidget; + + return NULL; +} + +/*! + \return specified axis, or NULL if axisId is invalid. + \param axisId axis index +*/ +QwtScaleWidget *QwtPlot::axisWidget( int axisId ) +{ + if ( axisValid( axisId ) ) + return d_axisData[axisId]->scaleWidget; + + return NULL; +} + +/*! + Change the scale engine for an axis + + \param axisId axis index + \param scaleEngine Scale engine + + \sa axisScaleEngine() +*/ +void QwtPlot::setAxisScaleEngine( int axisId, QwtScaleEngine *scaleEngine ) +{ + if ( axisValid( axisId ) && scaleEngine != NULL ) + { + AxisData &d = *d_axisData[axisId]; + + delete d.scaleEngine; + d.scaleEngine = scaleEngine; + + d.scaleDiv.invalidate(); + + autoRefresh(); + } +} + +/*! + \param axisId axis index + \return Scale engine for a specific axis +*/ +QwtScaleEngine *QwtPlot::axisScaleEngine( int axisId ) +{ + if ( axisValid( axisId ) ) + return d_axisData[axisId]->scaleEngine; + else + return NULL; +} + +/*! + \param axisId axis index + \return Scale engine for a specific axis +*/ +const QwtScaleEngine *QwtPlot::axisScaleEngine( int axisId ) const +{ + if ( axisValid( axisId ) ) + return d_axisData[axisId]->scaleEngine; + else + return NULL; +} +/*! + \return \c true if autoscaling is enabled + \param axisId axis index +*/ +bool QwtPlot::axisAutoScale( int axisId ) const +{ + if ( axisValid( axisId ) ) + return d_axisData[axisId]->doAutoScale; + else + return false; + +} + +/*! + \return \c true if a specified axis is enabled + \param axisId axis index +*/ +bool QwtPlot::axisEnabled( int axisId ) const +{ + if ( axisValid( axisId ) ) + return d_axisData[axisId]->isEnabled; + else + return false; +} + +/*! + \return the font of the scale labels for a specified axis + \param axisId axis index +*/ +QFont QwtPlot::axisFont( int axisId ) const +{ + if ( axisValid( axisId ) ) + return axisWidget( axisId )->font(); + else + return QFont(); + +} + +/*! + \return the maximum number of major ticks for a specified axis + \param axisId axis index + \sa setAxisMaxMajor() +*/ +int QwtPlot::axisMaxMajor( int axisId ) const +{ + if ( axisValid( axisId ) ) + return d_axisData[axisId]->maxMajor; + else + return 0; +} + +/*! + \return the maximum number of minor ticks for a specified axis + \param axisId axis index + \sa setAxisMaxMinor() +*/ +int QwtPlot::axisMaxMinor( int axisId ) const +{ + if ( axisValid( axisId ) ) + return d_axisData[axisId]->maxMinor; + else + return 0; +} + +/*! + \brief Return the scale division of a specified axis + + axisScaleDiv(axisId)->lowerBound(), axisScaleDiv(axisId)->upperBound() + are the current limits of the axis scale. + + \param axisId axis index + \return Scale division + + \sa QwtScaleDiv, setAxisScaleDiv() +*/ +const QwtScaleDiv *QwtPlot::axisScaleDiv( int axisId ) const +{ + if ( !axisValid( axisId ) ) + return NULL; + + return &d_axisData[axisId]->scaleDiv; +} + +/*! + \brief Return the scale division of a specified axis + + axisScaleDiv(axisId)->lowerBound(), axisScaleDiv(axisId)->upperBound() + are the current limits of the axis scale. + + \param axisId axis index + \return Scale division + + \sa QwtScaleDiv, setAxisScaleDiv() +*/ +QwtScaleDiv *QwtPlot::axisScaleDiv( int axisId ) +{ + if ( !axisValid( axisId ) ) + return NULL; + + return &d_axisData[axisId]->scaleDiv; +} + +/*! + \returns the scale draw of a specified axis + \param axisId axis index + \return specified scaleDraw for axis, or NULL if axis is invalid. + \sa QwtScaleDraw +*/ +const QwtScaleDraw *QwtPlot::axisScaleDraw( int axisId ) const +{ + if ( !axisValid( axisId ) ) + return NULL; + + return axisWidget( axisId )->scaleDraw(); +} + +/*! + \returns the scale draw of a specified axis + \param axisId axis index + \return specified scaleDraw for axis, or NULL if axis is invalid. + \sa QwtScaleDraw +*/ +QwtScaleDraw *QwtPlot::axisScaleDraw( int axisId ) +{ + if ( !axisValid( axisId ) ) + return NULL; + + return axisWidget( axisId )->scaleDraw(); +} + +/*! + Return the step size parameter, that has been set + in setAxisScale. This doesn't need to be the step size + of the current scale. + + \param axisId axis index + \return step size parameter value + + \sa setAxisScale() +*/ +double QwtPlot::axisStepSize( int axisId ) const +{ + if ( !axisValid( axisId ) ) + return 0; + + return d_axisData[axisId]->stepSize; +} + +/*! + \brief Return the current interval of the specified axis + + This is only a convenience function for axisScaleDiv( axisId )->interval(); + + \param axisId axis index + \return Scale interval + + \sa QwtScaleDiv, axisScaleDiv() +*/ +QwtInterval QwtPlot::axisInterval( int axisId ) const +{ + if ( !axisValid( axisId ) ) + return QwtInterval(); + + return d_axisData[axisId]->scaleDiv.interval(); +} + +/*! + \return the title of a specified axis + \param axisId axis index +*/ +QwtText QwtPlot::axisTitle( int axisId ) const +{ + if ( axisValid( axisId ) ) + return axisWidget( axisId )->title(); + else + return QwtText(); +} + +/*! + \brief Enable or disable a specified axis + + When an axis is disabled, this only means that it is not + visible on the screen. Curves, markers and can be attached + to disabled axes, and transformation of screen coordinates + into values works as normal. + + Only xBottom and yLeft are enabled by default. + \param axisId axis index + \param tf \c true (enabled) or \c false (disabled) +*/ +void QwtPlot::enableAxis( int axisId, bool tf ) +{ + if ( axisValid( axisId ) && tf != d_axisData[axisId]->isEnabled ) + { + d_axisData[axisId]->isEnabled = tf; + updateLayout(); + } +} + +/*! + Transform the x or y coordinate of a position in the + drawing region into a value. + \param axisId axis index + \param pos position + \warning The position can be an x or a y coordinate, + depending on the specified axis. +*/ +double QwtPlot::invTransform( int axisId, int pos ) const +{ + if ( axisValid( axisId ) ) + return( canvasMap( axisId ).invTransform( pos ) ); + else + return 0.0; +} + + +/*! + \brief Transform a value into a coordinate in the plotting region + \param axisId axis index + \param value value + \return X or y coordinate in the plotting region corresponding + to the value. +*/ +double QwtPlot::transform( int axisId, double value ) const +{ + if ( axisValid( axisId ) ) + return( canvasMap( axisId ).transform( value ) ); + else + return 0.0; +} + +/*! + \brief Change the font of an axis + \param axisId axis index + \param f font + \warning This function changes the font of the tick labels, + not of the axis title. +*/ +void QwtPlot::setAxisFont( int axisId, const QFont &f ) +{ + if ( axisValid( axisId ) ) + axisWidget( axisId )->setFont( f ); +} + +/*! + \brief Enable autoscaling for a specified axis + + This member function is used to switch back to autoscaling mode + after a fixed scale has been set. Autoscaling is enabled by default. + + \param axisId axis index + \param on On/Off + \sa setAxisScale(), setAxisScaleDiv(), updateAxes() + + \note The autoscaling flag has no effect until updateAxes() is executed + ( called by replot() ). +*/ +void QwtPlot::setAxisAutoScale( int axisId, bool on ) +{ + if ( axisValid( axisId ) && ( d_axisData[axisId]->doAutoScale != on ) ) + { + d_axisData[axisId]->doAutoScale = on; + autoRefresh(); + } +} + +/*! + \brief Disable autoscaling and specify a fixed scale for a selected axis. + \param axisId axis index + \param min + \param max minimum and maximum of the scale + \param stepSize Major step size. If step == 0, the step size is + calculated automatically using the maxMajor setting. + \sa setAxisMaxMajor(), setAxisAutoScale(), axisStepSize() +*/ +void QwtPlot::setAxisScale( int axisId, double min, double max, double stepSize ) +{ + if ( axisValid( axisId ) ) + { + AxisData &d = *d_axisData[axisId]; + + d.doAutoScale = false; + d.scaleDiv.invalidate(); + + d.minValue = min; + d.maxValue = max; + d.stepSize = stepSize; + + autoRefresh(); + } +} + +/*! + \brief Disable autoscaling and specify a fixed scale for a selected axis. + \param axisId axis index + \param scaleDiv Scale division + \sa setAxisScale(), setAxisAutoScale() +*/ +void QwtPlot::setAxisScaleDiv( int axisId, const QwtScaleDiv &scaleDiv ) +{ + if ( axisValid( axisId ) ) + { + AxisData &d = *d_axisData[axisId]; + + d.doAutoScale = false; + d.scaleDiv = scaleDiv; + + autoRefresh(); + } +} + +/*! + \brief Set a scale draw + \param axisId axis index + \param scaleDraw object responsible for drawing scales. + + By passing scaleDraw it is possible to extend QwtScaleDraw + functionality and let it take place in QwtPlot. Please note + that scaleDraw has to be created with new and will be deleted + by the corresponding QwtScale member ( like a child object ). + + \sa QwtScaleDraw, QwtScaleWidget + \warning The attributes of scaleDraw will be overwritten by those of the + previous QwtScaleDraw. +*/ + +void QwtPlot::setAxisScaleDraw( int axisId, QwtScaleDraw *scaleDraw ) +{ + if ( axisValid( axisId ) ) + { + axisWidget( axisId )->setScaleDraw( scaleDraw ); + autoRefresh(); + } +} + +/*! + Change the alignment of the tick labels + \param axisId axis index + \param alignment Or'd Qt::AlignmentFlags see + \sa QwtScaleDraw::setLabelAlignment() +*/ +void QwtPlot::setAxisLabelAlignment( int axisId, Qt::Alignment alignment ) +{ + if ( axisValid( axisId ) ) + axisWidget( axisId )->setLabelAlignment( alignment ); +} + +/*! + Rotate all tick labels + \param axisId axis index + \param rotation Angle in degrees. When changing the label rotation, + the label alignment might be adjusted too. + \sa QwtScaleDraw::setLabelRotation(), setAxisLabelAlignment() +*/ +void QwtPlot::setAxisLabelRotation( int axisId, double rotation ) +{ + if ( axisValid( axisId ) ) + axisWidget( axisId )->setLabelRotation( rotation ); +} + +/*! + Set the maximum number of minor scale intervals for a specified axis + + \param axisId axis index + \param maxMinor maximum number of minor steps + \sa axisMaxMinor() +*/ +void QwtPlot::setAxisMaxMinor( int axisId, int maxMinor ) +{ + if ( axisValid( axisId ) ) + { + maxMinor = qBound( 0, maxMinor, 100 ); + + AxisData &d = *d_axisData[axisId]; + if ( maxMinor != d.maxMinor ) + { + d.maxMinor = maxMinor; + d.scaleDiv.invalidate(); + autoRefresh(); + } + } +} + +/*! + Set the maximum number of major scale intervals for a specified axis + + \param axisId axis index + \param maxMajor maximum number of major steps + \sa axisMaxMajor() +*/ +void QwtPlot::setAxisMaxMajor( int axisId, int maxMajor ) +{ + if ( axisValid( axisId ) ) + { + maxMajor = qBound( 1, maxMajor, 10000 ); + + AxisData &d = *d_axisData[axisId]; + if ( maxMajor != d.maxMajor ) + { + d.maxMajor = maxMajor; + d.scaleDiv.invalidate(); + autoRefresh(); + } + } +} + +/*! + \brief Change the title of a specified axis + \param axisId axis index + \param title axis title +*/ +void QwtPlot::setAxisTitle( int axisId, const QString &title ) +{ + if ( axisValid( axisId ) ) + axisWidget( axisId )->setTitle( title ); +} + +/*! + \brief Change the title of a specified axis + \param axisId axis index + \param title axis title +*/ +void QwtPlot::setAxisTitle( int axisId, const QwtText &title ) +{ + if ( axisValid( axisId ) ) + axisWidget( axisId )->setTitle( title ); +} + +//! Rebuild the scales +void QwtPlot::updateAxes() +{ + // Find bounding interval of the item data + // for all axes, where autoscaling is enabled + + QwtInterval intv[axisCnt]; + + const QwtPlotItemList& itmList = itemList(); + + QwtPlotItemIterator it; + for ( it = itmList.begin(); it != itmList.end(); ++it ) + { + const QwtPlotItem *item = *it; + + if ( !item->testItemAttribute( QwtPlotItem::AutoScale ) ) + continue; + + if ( !item->isVisible() ) + continue; + + if ( axisAutoScale( item->xAxis() ) || axisAutoScale( item->yAxis() ) ) + { + const QRectF rect = item->boundingRect(); + intv[item->xAxis()] |= QwtInterval( rect.left(), rect.right() ); + intv[item->yAxis()] |= QwtInterval( rect.top(), rect.bottom() ); + } + } + + // Adjust scales + + for ( int axisId = 0; axisId < axisCnt; axisId++ ) + { + AxisData &d = *d_axisData[axisId]; + + double minValue = d.minValue; + double maxValue = d.maxValue; + double stepSize = d.stepSize; + + if ( d.doAutoScale && intv[axisId].isValid() ) + { + d.scaleDiv.invalidate(); + + minValue = intv[axisId].minValue(); + maxValue = intv[axisId].maxValue(); + + d.scaleEngine->autoScale( d.maxMajor, + minValue, maxValue, stepSize ); + } + if ( !d.scaleDiv.isValid() ) + { + d.scaleDiv = d.scaleEngine->divideScale( + minValue, maxValue, + d.maxMajor, d.maxMinor, stepSize ); + } + + QwtScaleWidget *scaleWidget = axisWidget( axisId ); + scaleWidget->setScaleDiv( + d.scaleEngine->transformation(), d.scaleDiv ); + + int startDist, endDist; + scaleWidget->getBorderDistHint( startDist, endDist ); + scaleWidget->setBorderDist( startDist, endDist ); + } + + for ( it = itmList.begin(); it != itmList.end(); ++it ) + { + QwtPlotItem *item = *it; + item->updateScaleDiv( *axisScaleDiv( item->xAxis() ), + *axisScaleDiv( item->yAxis() ) ); + } +} + diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_canvas.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_canvas.cpp index 19903823e..b5048f0e4 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_canvas.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_canvas.cpp @@ -1,1079 +1,1079 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot_canvas.h" -#include "qwt_painter.h" -#include "qwt_null_paintdevice.h" -#include "qwt_math.h" -#include "qwt_plot.h" -#include -#include -#include -#include -#include -#include -#ifdef Q_WS_X11 -#include -#endif - -class QwtStyleSheetRecorder: public QwtNullPaintDevice -{ -public: - QwtStyleSheetRecorder( const QSize &size ): - QwtNullPaintDevice( QPaintEngine::AllFeatures ) - { - setSize( size ); - } - - virtual void updateState( const QPaintEngineState &state ) - { - if ( state.state() & QPaintEngine::DirtyPen ) - { - d_pen = state.pen(); - } - if ( state.state() & QPaintEngine::DirtyBrush ) - { - d_brush = state.brush(); - } - if ( state.state() & QPaintEngine::DirtyBrushOrigin ) - { - d_origin = state.brushOrigin(); - } - } - - virtual void drawRects(const QRectF *rects, int count ) - { - for ( int i = 0; i < count; i++ ) - border.rectList += rects[i]; - } - - virtual void drawPath( const QPainterPath &path ) - { - const QRectF rect( QPointF( 0.0, 0.0 ) , size() ); - if ( path.controlPointRect().contains( rect.center() ) ) - { - setCornerRects( path ); - alignCornerRects( rect ); - - background.path = path; - background.brush = d_brush; - background.origin = d_origin; - } - else - { - border.pathList += path; - } - } - - void setCornerRects( const QPainterPath &path ) - { - QPointF pos( 0.0, 0.0 ); - - for ( int i = 0; i < path.elementCount(); i++ ) - { - QPainterPath::Element el = path.elementAt(i); - switch( el.type ) - { - case QPainterPath::MoveToElement: - case QPainterPath::LineToElement: - { - pos.setX( el.x ); - pos.setY( el.y ); - break; - } - case QPainterPath::CurveToElement: - { - QRectF r( pos, QPointF( el.x, el.y ) ); - clipRects += r.normalized(); - - pos.setX( el.x ); - pos.setY( el.y ); - - break; - } - case QPainterPath::CurveToDataElement: - { - if ( clipRects.size() > 0 ) - { - QRectF r = clipRects.last(); - r.setCoords( - qMin( r.left(), el.x ), - qMin( r.top(), el.y ), - qMax( r.right(), el.x ), - qMax( r.bottom(), el.y ) - ); - clipRects.last() = r.normalized(); - } - break; - } - } - } - } - -private: - void alignCornerRects( const QRectF &rect ) - { - for ( int i = 0; i < clipRects.size(); i++ ) - { - QRectF &r = clipRects[i]; - if ( r.center().x() < rect.center().x() ) - r.setLeft( rect.left() ); - else - r.setRight( rect.right() ); - - if ( r.center().y() < rect.center().y() ) - r.setTop( rect.top() ); - else - r.setBottom( rect.bottom() ); - } - } - - -public: - QVector clipRects; - - struct Border - { - QList pathList; - QList rectList; - QRegion clipRegion; - } border; - - struct Background - { - QPainterPath path; - QBrush brush; - QPointF origin; - } background; - -private: - QPen d_pen; - QBrush d_brush; - QPointF d_origin; -}; - -static void qwtDrawBackground( QPainter *painter, QWidget *widget ) -{ - const QBrush &brush = - widget->palette().brush( widget->backgroundRole() ); - - if ( brush.style() == Qt::TexturePattern ) - { - QPixmap pm( widget->size() ); - pm.fill( widget, 0, 0 ); - painter->drawPixmap( 0, 0, pm ); - } - else if ( brush.gradient() ) - { - QVector rects; - - if ( brush.gradient()->coordinateMode() == QGradient::ObjectBoundingMode ) - { - rects += widget->rect(); - } - else - { - rects = painter->clipRegion().rects(); - } - -#if 1 - bool useRaster = false; - - if ( painter->paintEngine()->type() == QPaintEngine::X11 ) - { - // Qt 4.7.1: gradients on X11 are broken ( subrects + - // QGradient::StretchToDeviceMode ) and horrible slow. - // As workaround we have to use the raster paintengine. - // Even if the QImage -> QPixmap translation is slow - // it is three times faster, than using X11 directly - - useRaster = true; - } -#endif - if ( useRaster ) - { - QImage::Format format = QImage::Format_RGB32; - - const QGradientStops stops = brush.gradient()->stops(); - for ( int i = 0; i < stops.size(); i++ ) - { - if ( stops[i].second.alpha() != 255 ) - { - // don't use Format_ARGB32_Premultiplied. It's - // recommended by the Qt docs, but QPainter::drawImage() - // is horrible slow on X11. - - format = QImage::Format_ARGB32; - break; - } - } - - QImage image( widget->size(), format ); - - QPainter p( &image ); - p.setPen( Qt::NoPen ); - p.setBrush( brush ); - - p.drawRects( rects ); - - p.end(); - - painter->drawImage( 0, 0, image ); - } - else - { - painter->save(); - - painter->setPen( Qt::NoPen ); - painter->setBrush( brush ); - - painter->drawRects( rects ); - - painter->restore(); - } - } - else - { - painter->save(); - - painter->setPen( Qt::NoPen ); - painter->setBrush( brush ); - - painter->drawRects( painter->clipRegion().rects() ); - - painter->restore(); - } -} - -static inline void qwtRevertPath( QPainterPath &path ) -{ - if ( path.elementCount() == 4 ) - { - QPainterPath::Element &el0 = - const_cast( path.elementAt(0) ); - QPainterPath::Element &el2 = - const_cast( path.elementAt(3) ); - - qSwap( el0.x, el2.x ); - qSwap( el0.y, el2.y ); - } -} - -static QPainterPath qwtCombinePathList( const QRectF &rect, - const QList &pathList ) -{ - if ( pathList.isEmpty() ) - return QPainterPath(); - - QPainterPath ordered[8]; // starting top left - - for ( int i = 0; i < pathList.size(); i++ ) - { - int index = -1; - QPainterPath subPath = pathList[i]; - - const QRectF br = pathList[i].controlPointRect(); - if ( br.center().x() < rect.center().x() ) - { - if ( br.center().y() < rect.center().y() ) - { - if ( qAbs( br.top() - rect.top() ) < - qAbs( br.left() - rect.left() ) ) - { - index = 1; - } - else - { - index = 0; - } - } - else - { - if ( qAbs( br.bottom() - rect.bottom() ) < - qAbs( br.left() - rect.left() ) ) - { - index = 6; - } - else - { - index = 7; - } - } - - if ( subPath.currentPosition().y() > br.center().y() ) - qwtRevertPath( subPath ); - } - else - { - if ( br.center().y() < rect.center().y() ) - { - if ( qAbs( br.top() - rect.top() ) < - qAbs( br.right() - rect.right() ) ) - { - index = 2; - } - else - { - index = 3; - } - } - else - { - if ( qAbs( br.bottom() - rect.bottom() ) < - qAbs( br.right() - rect.right() ) ) - { - index = 5; - } - else - { - index = 4; - } - } - if ( subPath.currentPosition().y() < br.center().y() ) - qwtRevertPath( subPath ); - } - ordered[index] = subPath; - } - - for ( int i = 0; i < 4; i++ ) - { - if ( ordered[ 2 * i].isEmpty() != ordered[2 * i + 1].isEmpty() ) - { - // we don't accept incomplete rounded borders - return QPainterPath(); - } - } - - - const QPolygonF corners( rect ); - - QPainterPath path; - //path.moveTo( rect.topLeft() ); - - for ( int i = 0; i < 4; i++ ) - { - if ( ordered[2 * i].isEmpty() ) - { - path.lineTo( corners[i] ); - } - else - { - path.connectPath( ordered[2 * i] ); - path.connectPath( ordered[2 * i + 1] ); - } - } - - path.closeSubpath(); - -#if 0 - return path.simplified(); -#else - return path; -#endif -} - -static inline void qwtDrawStyledBackground( - QWidget *w, QPainter *painter ) -{ - QStyleOption opt; - opt.initFrom(w); - w->style()->drawPrimitive( QStyle::PE_Widget, &opt, painter, w); -} - -static QWidget *qwtBackgroundWidget( QWidget *w ) -{ - if ( w->parentWidget() == NULL ) - return w; - - if ( w->autoFillBackground() ) - { - const QBrush brush = w->palette().brush( w->backgroundRole() ); - if ( brush.color().alpha() > 0 ) - return w; - } - - if ( w->testAttribute( Qt::WA_StyledBackground ) ) - { - QImage image( 1, 1, QImage::Format_ARGB32 ); - image.fill( Qt::transparent ); - - QPainter painter( &image ); - painter.translate( -w->rect().center() ); - qwtDrawStyledBackground( w, &painter ); - painter.end(); - - if ( qAlpha( image.pixel( 0, 0 ) ) != 0 ) - return w; - } - - return qwtBackgroundWidget( w->parentWidget() ); -} - -static void qwtFillBackground( QPainter *painter, - QWidget *widget, const QVector &fillRects ) -{ - if ( fillRects.isEmpty() ) - return; - - QRegion clipRegion; - if ( painter->hasClipping() ) - clipRegion = painter->transform().map( painter->clipRegion() ); - else - clipRegion = widget->contentsRect(); - - // Try to find out which widget fills - // the unfilled areas of the styled background - - QWidget *bgWidget = qwtBackgroundWidget( widget->parentWidget() ); - - for ( int i = 0; i < fillRects.size(); i++ ) - { - const QRect rect = fillRects[i].toAlignedRect(); - if ( clipRegion.intersects( rect ) ) - { - QPixmap pm( rect.size() ); - pm.fill( bgWidget, widget->mapTo( bgWidget, rect.topLeft() ) ); - painter->drawPixmap( rect, pm ); - } - } -} - -static void qwtFillBackground( QPainter *painter, QwtPlotCanvas *canvas ) -{ - QVector rects; - - if ( canvas->testAttribute( Qt::WA_StyledBackground ) ) - { - QwtStyleSheetRecorder recorder( canvas->size() ); - - QPainter p( &recorder ); - qwtDrawStyledBackground( canvas, &p ); - p.end(); - - if ( recorder.background.brush.isOpaque() ) - rects = recorder.clipRects; - else - rects += canvas->rect(); - } - else - { - const QRectF r = canvas->rect(); - const double radius = canvas->borderRadius(); - if ( radius > 0.0 ) - { - QSize sz( radius, radius ); - - rects += QRectF( r.topLeft(), sz ); - rects += QRectF( r.topRight() - QPointF( radius, 0 ), sz ); - rects += QRectF( r.bottomRight() - QPointF( radius, radius ), sz ); - rects += QRectF( r.bottomLeft() - QPointF( 0, radius ), sz ); - } - } - - qwtFillBackground( painter, canvas, rects); -} - - -class QwtPlotCanvas::PrivateData -{ -public: - PrivateData(): - focusIndicator( NoFocusIndicator ), - borderRadius( 0 ), - paintAttributes( 0 ), - backingStore( NULL ) - { - styleSheet.hasBorder = false; - } - - ~PrivateData() - { - delete backingStore; - } - - FocusIndicator focusIndicator; - double borderRadius; - QwtPlotCanvas::PaintAttributes paintAttributes; - QPixmap *backingStore; - - struct StyleSheet - { - bool hasBorder; - QPainterPath borderPath; - QVector cornerRects; - - struct StyleSheetBackground - { - QBrush brush; - QPointF origin; - } background; - - } styleSheet; - -}; - -//! Sets a cross cursor, enables QwtPlotCanvas::BackingStore - -QwtPlotCanvas::QwtPlotCanvas( QwtPlot *plot ): - QFrame( plot ) -{ - d_data = new PrivateData; - -#ifndef QT_NO_CURSOR - setCursor( Qt::CrossCursor ); -#endif - - setAutoFillBackground( true ); - setPaintAttribute( QwtPlotCanvas::BackingStore, true ); - setPaintAttribute( QwtPlotCanvas::Opaque, true ); - setPaintAttribute( QwtPlotCanvas::HackStyledBackground, true ); -} - -//! Destructor -QwtPlotCanvas::~QwtPlotCanvas() -{ - delete d_data; -} - -//! Return parent plot widget -QwtPlot *QwtPlotCanvas::plot() -{ - return qobject_cast( parentWidget() ); -} - -//! Return parent plot widget -const QwtPlot *QwtPlotCanvas::plot() const -{ - return qobject_cast( parentWidget() ); -} - -/*! - \brief Changing the paint attributes - - \param attribute Paint attribute - \param on On/Off - - \sa testPaintAttribute(), backingStore() -*/ -void QwtPlotCanvas::setPaintAttribute( PaintAttribute attribute, bool on ) -{ - if ( bool( d_data->paintAttributes & attribute ) == on ) - return; - - if ( on ) - d_data->paintAttributes |= attribute; - else - d_data->paintAttributes &= ~attribute; - - switch ( attribute ) - { - case BackingStore: - { - if ( on ) - { - if ( d_data->backingStore == NULL ) - d_data->backingStore = new QPixmap(); - - if ( isVisible() ) - { - *d_data->backingStore = - QPixmap::grabWidget( this, rect() ); - } - } - else - { - delete d_data->backingStore; - d_data->backingStore = NULL; - } - break; - } - case Opaque: - { - if ( on ) - setAttribute( Qt::WA_OpaquePaintEvent, true ); - - break; - } - case HackStyledBackground: - case ImmediatePaint: - { - break; - } - } -} - -/*! - Test wether a paint attribute is enabled - - \param attribute Paint attribute - \return true if the attribute is enabled - \sa setPaintAttribute() -*/ -bool QwtPlotCanvas::testPaintAttribute( PaintAttribute attribute ) const -{ - return d_data->paintAttributes & attribute; -} - -//! \return Backing store, might be null -const QPixmap *QwtPlotCanvas::backingStore() const -{ - return d_data->backingStore; -} - -//! Invalidate the internal backing store -void QwtPlotCanvas::invalidateBackingStore() -{ - if ( d_data->backingStore ) - *d_data->backingStore = QPixmap(); -} - -/*! - Set the focus indicator - - \sa FocusIndicator, focusIndicator() -*/ -void QwtPlotCanvas::setFocusIndicator( FocusIndicator focusIndicator ) -{ - d_data->focusIndicator = focusIndicator; -} - -/*! - \return Focus indicator - - \sa FocusIndicator, setFocusIndicator() -*/ -QwtPlotCanvas::FocusIndicator QwtPlotCanvas::focusIndicator() const -{ - return d_data->focusIndicator; -} - -/*! - Set the radius for the corners of the border frame - - \param radius Radius of a rounded corner - \sa borderRadius() -*/ -void QwtPlotCanvas::setBorderRadius( double radius ) -{ - d_data->borderRadius = qMax( 0.0, radius ); -} - -/*! - \return Radius for the corners of the border frame - \sa setBorderRadius() -*/ -double QwtPlotCanvas::borderRadius() const -{ - return d_data->borderRadius; -} - -/*! - Qt event handler for QEvent::PolishRequest and QEvent::StyleChange - \param event Qt Event -*/ -bool QwtPlotCanvas::event( QEvent *event ) -{ - if ( event->type() == QEvent::PolishRequest ) - { - if ( testPaintAttribute( QwtPlotCanvas::Opaque ) ) - { - // Setting a style sheet changes the - // Qt::WA_OpaquePaintEvent attribute, but we insist - // on painting the background. - - setAttribute( Qt::WA_OpaquePaintEvent, true ); - } - } - - if ( event->type() == QEvent::PolishRequest || - event->type() == QEvent::StyleChange ) - { - updateStyleSheetInfo(); - } - - return QFrame::event( event ); -} - -/*! - Paint event - \param event Paint event -*/ -void QwtPlotCanvas::paintEvent( QPaintEvent *event ) -{ - QPainter painter( this ); - painter.setClipRegion( event->region() ); - - if ( testPaintAttribute( QwtPlotCanvas::BackingStore ) && - d_data->backingStore != NULL ) - { - QPixmap &bs = *d_data->backingStore; - if ( bs.size() != size() ) - { - bs = QPixmap( size() ); - -#ifdef Q_WS_X11 - if ( bs.x11Info().screen() != x11Info().screen() ) - bs.x11SetScreen( x11Info().screen() ); -#endif - - if ( testAttribute(Qt::WA_StyledBackground) ) - { - QPainter p( &bs ); - qwtFillBackground( &p, this ); - drawCanvas( &p, true ); - } - else - { - QPainter p; - if ( d_data->borderRadius <= 0.0 ) - { - bs.fill( this, 0, 0 ); - p.begin( &bs ); - drawCanvas( &p, false ); - } - else - { - p.begin( &bs ); - qwtFillBackground( &p, this ); - drawCanvas( &p, true ); - } - - if ( frameWidth() > 0 ) - drawBorder( &p ); - } - } - - painter.drawPixmap( 0, 0, *d_data->backingStore ); - } - else - { - if ( testAttribute(Qt::WA_StyledBackground ) ) - { - if ( testAttribute( Qt::WA_OpaquePaintEvent ) ) - { - qwtFillBackground( &painter, this ); - drawCanvas( &painter, true ); - } - else - { - drawCanvas( &painter, false ); - } - } - else - { - if ( testAttribute( Qt::WA_OpaquePaintEvent ) ) - { - if ( autoFillBackground() ) - qwtDrawBackground( &painter, this ); - } - - drawCanvas( &painter, false ); - - if ( frameWidth() > 0 ) - drawBorder( &painter ); - } - } - - if ( hasFocus() && focusIndicator() == CanvasFocusIndicator ) - drawFocusIndicator( &painter ); -} - -void QwtPlotCanvas::drawCanvas( QPainter *painter, bool withBackground ) -{ - bool hackStyledBackground = false; - - if ( withBackground && testAttribute( Qt::WA_StyledBackground ) - && testPaintAttribute( HackStyledBackground ) ) - { - // Antialiasing rounded borders is done by - // inserting pixels with colors between the - // border color and the color on the canvas, - // When the border is painted before the plot items - // these colors are interpolated for the canvas - // and the plot items need to be clipped excluding - // the anialiased pixels. In situations, where - // the plot items fill the area at the rounded - // borders this is noticeable. - // The only way to avoid these annoying "artefacts" - // is to paint the border on top of the plot items. - - if ( d_data->styleSheet.hasBorder && - !d_data->styleSheet.borderPath.isEmpty() ) - { - // We have a border with at least one rounded corner - hackStyledBackground = true; - } - } - - if ( withBackground ) - { - painter->save(); - - if ( testAttribute( Qt::WA_StyledBackground ) ) - { - if ( hackStyledBackground ) - { - // paint background without border - - painter->setPen( Qt::NoPen ); - painter->setBrush( d_data->styleSheet.background.brush ); - painter->setBrushOrigin( d_data->styleSheet.background.origin ); - painter->setClipPath( d_data->styleSheet.borderPath ); - painter->drawRect( contentsRect() ); - } - else - { - qwtDrawStyledBackground( this, painter ); - } - } - else if ( autoFillBackground() ) - { - painter->setPen( Qt::NoPen ); - painter->setBrush( palette().brush( backgroundRole() ) ); - - if ( d_data->borderRadius > 0.0 ) - { - if ( frameWidth() > 0 ) - { - painter->setClipPath( borderPath( rect() ) ); - painter->drawRect( rect() ); - } - else - { - painter->setRenderHint( QPainter::Antialiasing, true ); - painter->drawPath( borderPath( rect() ) ); - } - } - else - { - painter->drawRect( contentsRect() ); - } - } - - painter->restore(); - } - - painter->save(); - - if ( !d_data->styleSheet.borderPath.isEmpty() ) - { - painter->setClipPath( - d_data->styleSheet.borderPath, Qt::IntersectClip ); - } - else - { - if ( d_data->borderRadius > 0.0 ) - painter->setClipPath( borderPath( rect() ), Qt::IntersectClip ); - else - painter->setClipRect( contentsRect(), Qt::IntersectClip ); - } - - plot()->drawCanvas( painter ); - - painter->restore(); - - if ( withBackground && hackStyledBackground ) - { - // Now paint the border on top - QStyleOptionFrame opt; - opt.initFrom(this); - style()->drawPrimitive( QStyle::PE_Frame, &opt, painter, this); - } -} - -/*! - Draw the border of the plot canvas - - \param painter Painter - \sa setBorderRadius(), QFrame::drawFrame() -*/ -void QwtPlotCanvas::drawBorder( QPainter *painter ) -{ - if ( d_data->borderRadius > 0 ) - { - if ( frameWidth() > 0 ) - { - QwtPainter::drawRoundedFrame( painter, QRectF( rect() ), - d_data->borderRadius, d_data->borderRadius, - palette(), frameWidth(), frameStyle() ); - } - } - else - { - drawFrame( painter ); - } -} - -/*! - Resize event - \param event Resize event -*/ -void QwtPlotCanvas::resizeEvent( QResizeEvent *event ) -{ - QFrame::resizeEvent( event ); - updateStyleSheetInfo(); -} - -/*! - Draw the focus indication - \param painter Painter -*/ -void QwtPlotCanvas::drawFocusIndicator( QPainter *painter ) -{ - const int margin = 1; - - QRect focusRect = contentsRect(); - focusRect.setRect( focusRect.x() + margin, focusRect.y() + margin, - focusRect.width() - 2 * margin, focusRect.height() - 2 * margin ); - - QwtPainter::drawFocusRect( painter, this, focusRect ); -} - -/*! - Invalidate the paint cache and repaint the canvas - \sa invalidatePaintCache() -*/ -void QwtPlotCanvas::replot() -{ - invalidateBackingStore(); - - if ( testPaintAttribute( QwtPlotCanvas::ImmediatePaint ) ) - repaint( contentsRect() ); - else - update( contentsRect() ); -} - -//! Update the cached informations about the current style sheet -void QwtPlotCanvas::updateStyleSheetInfo() -{ - if ( !testAttribute(Qt::WA_StyledBackground ) ) - return; - - QwtStyleSheetRecorder recorder( size() ); - - QPainter painter( &recorder ); - - QStyleOption opt; - opt.initFrom(this); - style()->drawPrimitive( QStyle::PE_Widget, &opt, &painter, this); - - painter.end(); - - d_data->styleSheet.hasBorder = !recorder.border.rectList.isEmpty(); - d_data->styleSheet.cornerRects = recorder.clipRects; - - if ( recorder.background.path.isEmpty() ) - { - if ( !recorder.border.rectList.isEmpty() ) - { - d_data->styleSheet.borderPath = - qwtCombinePathList( rect(), recorder.border.pathList ); - } - } - else - { - d_data->styleSheet.borderPath = recorder.background.path; - d_data->styleSheet.background.brush = recorder.background.brush; - d_data->styleSheet.background.origin = recorder.background.origin; - } -} - -/*! - Calculate the painter path for a styled or rounded border - - When the canvas has no styled background or rounded borders - the painter path is empty. - - \param rect Bounding rectangle of the canvas - \return Painter path, that can be used for clipping -*/ -QPainterPath QwtPlotCanvas::borderPath( const QRect &rect ) const -{ - if ( testAttribute(Qt::WA_StyledBackground ) ) - { - QwtStyleSheetRecorder recorder( rect.size() ); - - QPainter painter( &recorder ); - - QStyleOption opt; - opt.initFrom(this); - opt.rect = rect; - style()->drawPrimitive( QStyle::PE_Widget, &opt, &painter, this); - - painter.end(); - - if ( !recorder.background.path.isEmpty() ) - return recorder.background.path; - - if ( !recorder.border.rectList.isEmpty() ) - return qwtCombinePathList( rect, recorder.border.pathList ); - } - else if ( d_data->borderRadius > 0.0 ) - { - double fw2 = frameWidth() * 0.5; - QRectF r = QRectF(rect).adjusted( fw2, fw2, -fw2, -fw2 ); - - QPainterPath path; - path.addRoundedRect( r, d_data->borderRadius, d_data->borderRadius ); - return path; - } - - return QPainterPath(); -} - -/*! - Calculate a mask, that can be used to clip away the border frame - - \param size Size including the frame -*/ -QBitmap QwtPlotCanvas::borderMask( const QSize &size ) const -{ - const QRect r( 0, 0, size.width(), size.height() ); - - const QPainterPath path = borderPath( r ); - if ( path.isEmpty() ) - return QBitmap(); - - QImage image( size, QImage::Format_ARGB32_Premultiplied ); - image.fill( Qt::color0 ); - - QPainter painter( &image ); - painter.setClipPath( path ); - painter.fillRect( r, Qt::color1 ); - - // now erase the frame - - painter.setCompositionMode( QPainter::CompositionMode_DestinationOut ); - - if ( testAttribute(Qt::WA_StyledBackground ) ) - { - QStyleOptionFrame opt; - opt.initFrom(this); - opt.rect = r; - style()->drawPrimitive( QStyle::PE_Frame, &opt, &painter, this ); - } - else - { - if ( d_data->borderRadius > 0 && frameWidth() > 0 ) - { - painter.setPen( QPen( Qt::color1, frameWidth() ) ); - painter.setBrush( Qt::NoBrush ); - painter.setRenderHint( QPainter::Antialiasing, true ); - - painter.drawPath( path ); - } - } - - painter.end(); - - const QImage mask = image.createMaskFromColor( - QColor( Qt::color1 ).rgb(), Qt::MaskOutColor ); - - return QBitmap::fromImage( mask ); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_canvas.h" +#include "qwt_painter.h" +#include "qwt_null_paintdevice.h" +#include "qwt_math.h" +#include "qwt_plot.h" +#include +#include +#include +#include +#include +#include +#ifdef Q_WS_X11 +#include +#endif + +class QwtStyleSheetRecorder: public QwtNullPaintDevice +{ +public: + QwtStyleSheetRecorder( const QSize &size ): + QwtNullPaintDevice( QPaintEngine::AllFeatures ) + { + setSize( size ); + } + + virtual void updateState( const QPaintEngineState &state ) + { + if ( state.state() & QPaintEngine::DirtyPen ) + { + d_pen = state.pen(); + } + if ( state.state() & QPaintEngine::DirtyBrush ) + { + d_brush = state.brush(); + } + if ( state.state() & QPaintEngine::DirtyBrushOrigin ) + { + d_origin = state.brushOrigin(); + } + } + + virtual void drawRects(const QRectF *rects, int count ) + { + for ( int i = 0; i < count; i++ ) + border.rectList += rects[i]; + } + + virtual void drawPath( const QPainterPath &path ) + { + const QRectF rect( QPointF( 0.0, 0.0 ) , size() ); + if ( path.controlPointRect().contains( rect.center() ) ) + { + setCornerRects( path ); + alignCornerRects( rect ); + + background.path = path; + background.brush = d_brush; + background.origin = d_origin; + } + else + { + border.pathList += path; + } + } + + void setCornerRects( const QPainterPath &path ) + { + QPointF pos( 0.0, 0.0 ); + + for ( int i = 0; i < path.elementCount(); i++ ) + { + QPainterPath::Element el = path.elementAt(i); + switch( el.type ) + { + case QPainterPath::MoveToElement: + case QPainterPath::LineToElement: + { + pos.setX( el.x ); + pos.setY( el.y ); + break; + } + case QPainterPath::CurveToElement: + { + QRectF r( pos, QPointF( el.x, el.y ) ); + clipRects += r.normalized(); + + pos.setX( el.x ); + pos.setY( el.y ); + + break; + } + case QPainterPath::CurveToDataElement: + { + if ( clipRects.size() > 0 ) + { + QRectF r = clipRects.last(); + r.setCoords( + qMin( r.left(), el.x ), + qMin( r.top(), el.y ), + qMax( r.right(), el.x ), + qMax( r.bottom(), el.y ) + ); + clipRects.last() = r.normalized(); + } + break; + } + } + } + } + +private: + void alignCornerRects( const QRectF &rect ) + { + for ( int i = 0; i < clipRects.size(); i++ ) + { + QRectF &r = clipRects[i]; + if ( r.center().x() < rect.center().x() ) + r.setLeft( rect.left() ); + else + r.setRight( rect.right() ); + + if ( r.center().y() < rect.center().y() ) + r.setTop( rect.top() ); + else + r.setBottom( rect.bottom() ); + } + } + + +public: + QVector clipRects; + + struct Border + { + QList pathList; + QList rectList; + QRegion clipRegion; + } border; + + struct Background + { + QPainterPath path; + QBrush brush; + QPointF origin; + } background; + +private: + QPen d_pen; + QBrush d_brush; + QPointF d_origin; +}; + +static void qwtDrawBackground( QPainter *painter, QWidget *widget ) +{ + const QBrush &brush = + widget->palette().brush( widget->backgroundRole() ); + + if ( brush.style() == Qt::TexturePattern ) + { + QPixmap pm( widget->size() ); + pm.fill( widget, 0, 0 ); + painter->drawPixmap( 0, 0, pm ); + } + else if ( brush.gradient() ) + { + QVector rects; + + if ( brush.gradient()->coordinateMode() == QGradient::ObjectBoundingMode ) + { + rects += widget->rect(); + } + else + { + rects = painter->clipRegion().rects(); + } + +#if 1 + bool useRaster = false; + + if ( painter->paintEngine()->type() == QPaintEngine::X11 ) + { + // Qt 4.7.1: gradients on X11 are broken ( subrects + + // QGradient::StretchToDeviceMode ) and horrible slow. + // As workaround we have to use the raster paintengine. + // Even if the QImage -> QPixmap translation is slow + // it is three times faster, than using X11 directly + + useRaster = true; + } +#endif + if ( useRaster ) + { + QImage::Format format = QImage::Format_RGB32; + + const QGradientStops stops = brush.gradient()->stops(); + for ( int i = 0; i < stops.size(); i++ ) + { + if ( stops[i].second.alpha() != 255 ) + { + // don't use Format_ARGB32_Premultiplied. It's + // recommended by the Qt docs, but QPainter::drawImage() + // is horrible slow on X11. + + format = QImage::Format_ARGB32; + break; + } + } + + QImage image( widget->size(), format ); + + QPainter p( &image ); + p.setPen( Qt::NoPen ); + p.setBrush( brush ); + + p.drawRects( rects ); + + p.end(); + + painter->drawImage( 0, 0, image ); + } + else + { + painter->save(); + + painter->setPen( Qt::NoPen ); + painter->setBrush( brush ); + + painter->drawRects( rects ); + + painter->restore(); + } + } + else + { + painter->save(); + + painter->setPen( Qt::NoPen ); + painter->setBrush( brush ); + + painter->drawRects( painter->clipRegion().rects() ); + + painter->restore(); + } +} + +static inline void qwtRevertPath( QPainterPath &path ) +{ + if ( path.elementCount() == 4 ) + { + QPainterPath::Element &el0 = + const_cast( path.elementAt(0) ); + QPainterPath::Element &el2 = + const_cast( path.elementAt(3) ); + + qSwap( el0.x, el2.x ); + qSwap( el0.y, el2.y ); + } +} + +static QPainterPath qwtCombinePathList( const QRectF &rect, + const QList &pathList ) +{ + if ( pathList.isEmpty() ) + return QPainterPath(); + + QPainterPath ordered[8]; // starting top left + + for ( int i = 0; i < pathList.size(); i++ ) + { + int index = -1; + QPainterPath subPath = pathList[i]; + + const QRectF br = pathList[i].controlPointRect(); + if ( br.center().x() < rect.center().x() ) + { + if ( br.center().y() < rect.center().y() ) + { + if ( qAbs( br.top() - rect.top() ) < + qAbs( br.left() - rect.left() ) ) + { + index = 1; + } + else + { + index = 0; + } + } + else + { + if ( qAbs( br.bottom() - rect.bottom() ) < + qAbs( br.left() - rect.left() ) ) + { + index = 6; + } + else + { + index = 7; + } + } + + if ( subPath.currentPosition().y() > br.center().y() ) + qwtRevertPath( subPath ); + } + else + { + if ( br.center().y() < rect.center().y() ) + { + if ( qAbs( br.top() - rect.top() ) < + qAbs( br.right() - rect.right() ) ) + { + index = 2; + } + else + { + index = 3; + } + } + else + { + if ( qAbs( br.bottom() - rect.bottom() ) < + qAbs( br.right() - rect.right() ) ) + { + index = 5; + } + else + { + index = 4; + } + } + if ( subPath.currentPosition().y() < br.center().y() ) + qwtRevertPath( subPath ); + } + ordered[index] = subPath; + } + + for ( int i = 0; i < 4; i++ ) + { + if ( ordered[ 2 * i].isEmpty() != ordered[2 * i + 1].isEmpty() ) + { + // we don't accept incomplete rounded borders + return QPainterPath(); + } + } + + + const QPolygonF corners( rect ); + + QPainterPath path; + //path.moveTo( rect.topLeft() ); + + for ( int i = 0; i < 4; i++ ) + { + if ( ordered[2 * i].isEmpty() ) + { + path.lineTo( corners[i] ); + } + else + { + path.connectPath( ordered[2 * i] ); + path.connectPath( ordered[2 * i + 1] ); + } + } + + path.closeSubpath(); + +#if 0 + return path.simplified(); +#else + return path; +#endif +} + +static inline void qwtDrawStyledBackground( + QWidget *w, QPainter *painter ) +{ + QStyleOption opt; + opt.initFrom(w); + w->style()->drawPrimitive( QStyle::PE_Widget, &opt, painter, w); +} + +static QWidget *qwtBackgroundWidget( QWidget *w ) +{ + if ( w->parentWidget() == NULL ) + return w; + + if ( w->autoFillBackground() ) + { + const QBrush brush = w->palette().brush( w->backgroundRole() ); + if ( brush.color().alpha() > 0 ) + return w; + } + + if ( w->testAttribute( Qt::WA_StyledBackground ) ) + { + QImage image( 1, 1, QImage::Format_ARGB32 ); + image.fill( Qt::transparent ); + + QPainter painter( &image ); + painter.translate( -w->rect().center() ); + qwtDrawStyledBackground( w, &painter ); + painter.end(); + + if ( qAlpha( image.pixel( 0, 0 ) ) != 0 ) + return w; + } + + return qwtBackgroundWidget( w->parentWidget() ); +} + +static void qwtFillBackground( QPainter *painter, + QWidget *widget, const QVector &fillRects ) +{ + if ( fillRects.isEmpty() ) + return; + + QRegion clipRegion; + if ( painter->hasClipping() ) + clipRegion = painter->transform().map( painter->clipRegion() ); + else + clipRegion = widget->contentsRect(); + + // Try to find out which widget fills + // the unfilled areas of the styled background + + QWidget *bgWidget = qwtBackgroundWidget( widget->parentWidget() ); + + for ( int i = 0; i < fillRects.size(); i++ ) + { + const QRect rect = fillRects[i].toAlignedRect(); + if ( clipRegion.intersects( rect ) ) + { + QPixmap pm( rect.size() ); + pm.fill( bgWidget, widget->mapTo( bgWidget, rect.topLeft() ) ); + painter->drawPixmap( rect, pm ); + } + } +} + +static void qwtFillBackground( QPainter *painter, QwtPlotCanvas *canvas ) +{ + QVector rects; + + if ( canvas->testAttribute( Qt::WA_StyledBackground ) ) + { + QwtStyleSheetRecorder recorder( canvas->size() ); + + QPainter p( &recorder ); + qwtDrawStyledBackground( canvas, &p ); + p.end(); + + if ( recorder.background.brush.isOpaque() ) + rects = recorder.clipRects; + else + rects += canvas->rect(); + } + else + { + const QRectF r = canvas->rect(); + const double radius = canvas->borderRadius(); + if ( radius > 0.0 ) + { + QSize sz( radius, radius ); + + rects += QRectF( r.topLeft(), sz ); + rects += QRectF( r.topRight() - QPointF( radius, 0 ), sz ); + rects += QRectF( r.bottomRight() - QPointF( radius, radius ), sz ); + rects += QRectF( r.bottomLeft() - QPointF( 0, radius ), sz ); + } + } + + qwtFillBackground( painter, canvas, rects); +} + + +class QwtPlotCanvas::PrivateData +{ +public: + PrivateData(): + focusIndicator( NoFocusIndicator ), + borderRadius( 0 ), + paintAttributes( 0 ), + backingStore( NULL ) + { + styleSheet.hasBorder = false; + } + + ~PrivateData() + { + delete backingStore; + } + + FocusIndicator focusIndicator; + double borderRadius; + QwtPlotCanvas::PaintAttributes paintAttributes; + QPixmap *backingStore; + + struct StyleSheet + { + bool hasBorder; + QPainterPath borderPath; + QVector cornerRects; + + struct StyleSheetBackground + { + QBrush brush; + QPointF origin; + } background; + + } styleSheet; + +}; + +//! Sets a cross cursor, enables QwtPlotCanvas::BackingStore + +QwtPlotCanvas::QwtPlotCanvas( QwtPlot *plot ): + QFrame( plot ) +{ + d_data = new PrivateData; + +#ifndef QT_NO_CURSOR + setCursor( Qt::CrossCursor ); +#endif + + setAutoFillBackground( true ); + setPaintAttribute( QwtPlotCanvas::BackingStore, true ); + setPaintAttribute( QwtPlotCanvas::Opaque, true ); + setPaintAttribute( QwtPlotCanvas::HackStyledBackground, true ); +} + +//! Destructor +QwtPlotCanvas::~QwtPlotCanvas() +{ + delete d_data; +} + +//! Return parent plot widget +QwtPlot *QwtPlotCanvas::plot() +{ + return qobject_cast( parentWidget() ); +} + +//! Return parent plot widget +const QwtPlot *QwtPlotCanvas::plot() const +{ + return qobject_cast( parentWidget() ); +} + +/*! + \brief Changing the paint attributes + + \param attribute Paint attribute + \param on On/Off + + \sa testPaintAttribute(), backingStore() +*/ +void QwtPlotCanvas::setPaintAttribute( PaintAttribute attribute, bool on ) +{ + if ( bool( d_data->paintAttributes & attribute ) == on ) + return; + + if ( on ) + d_data->paintAttributes |= attribute; + else + d_data->paintAttributes &= ~attribute; + + switch ( attribute ) + { + case BackingStore: + { + if ( on ) + { + if ( d_data->backingStore == NULL ) + d_data->backingStore = new QPixmap(); + + if ( isVisible() ) + { + *d_data->backingStore = + QPixmap::grabWidget( this, rect() ); + } + } + else + { + delete d_data->backingStore; + d_data->backingStore = NULL; + } + break; + } + case Opaque: + { + if ( on ) + setAttribute( Qt::WA_OpaquePaintEvent, true ); + + break; + } + case HackStyledBackground: + case ImmediatePaint: + { + break; + } + } +} + +/*! + Test wether a paint attribute is enabled + + \param attribute Paint attribute + \return true if the attribute is enabled + \sa setPaintAttribute() +*/ +bool QwtPlotCanvas::testPaintAttribute( PaintAttribute attribute ) const +{ + return d_data->paintAttributes & attribute; +} + +//! \return Backing store, might be null +const QPixmap *QwtPlotCanvas::backingStore() const +{ + return d_data->backingStore; +} + +//! Invalidate the internal backing store +void QwtPlotCanvas::invalidateBackingStore() +{ + if ( d_data->backingStore ) + *d_data->backingStore = QPixmap(); +} + +/*! + Set the focus indicator + + \sa FocusIndicator, focusIndicator() +*/ +void QwtPlotCanvas::setFocusIndicator( FocusIndicator focusIndicator ) +{ + d_data->focusIndicator = focusIndicator; +} + +/*! + \return Focus indicator + + \sa FocusIndicator, setFocusIndicator() +*/ +QwtPlotCanvas::FocusIndicator QwtPlotCanvas::focusIndicator() const +{ + return d_data->focusIndicator; +} + +/*! + Set the radius for the corners of the border frame + + \param radius Radius of a rounded corner + \sa borderRadius() +*/ +void QwtPlotCanvas::setBorderRadius( double radius ) +{ + d_data->borderRadius = qMax( 0.0, radius ); +} + +/*! + \return Radius for the corners of the border frame + \sa setBorderRadius() +*/ +double QwtPlotCanvas::borderRadius() const +{ + return d_data->borderRadius; +} + +/*! + Qt event handler for QEvent::PolishRequest and QEvent::StyleChange + \param event Qt Event +*/ +bool QwtPlotCanvas::event( QEvent *event ) +{ + if ( event->type() == QEvent::PolishRequest ) + { + if ( testPaintAttribute( QwtPlotCanvas::Opaque ) ) + { + // Setting a style sheet changes the + // Qt::WA_OpaquePaintEvent attribute, but we insist + // on painting the background. + + setAttribute( Qt::WA_OpaquePaintEvent, true ); + } + } + + if ( event->type() == QEvent::PolishRequest || + event->type() == QEvent::StyleChange ) + { + updateStyleSheetInfo(); + } + + return QFrame::event( event ); +} + +/*! + Paint event + \param event Paint event +*/ +void QwtPlotCanvas::paintEvent( QPaintEvent *event ) +{ + QPainter painter( this ); + painter.setClipRegion( event->region() ); + + if ( testPaintAttribute( QwtPlotCanvas::BackingStore ) && + d_data->backingStore != NULL ) + { + QPixmap &bs = *d_data->backingStore; + if ( bs.size() != size() ) + { + bs = QPixmap( size() ); + +#ifdef Q_WS_X11 + if ( bs.x11Info().screen() != x11Info().screen() ) + bs.x11SetScreen( x11Info().screen() ); +#endif + + if ( testAttribute(Qt::WA_StyledBackground) ) + { + QPainter p( &bs ); + qwtFillBackground( &p, this ); + drawCanvas( &p, true ); + } + else + { + QPainter p; + if ( d_data->borderRadius <= 0.0 ) + { + bs.fill( this, 0, 0 ); + p.begin( &bs ); + drawCanvas( &p, false ); + } + else + { + p.begin( &bs ); + qwtFillBackground( &p, this ); + drawCanvas( &p, true ); + } + + if ( frameWidth() > 0 ) + drawBorder( &p ); + } + } + + painter.drawPixmap( 0, 0, *d_data->backingStore ); + } + else + { + if ( testAttribute(Qt::WA_StyledBackground ) ) + { + if ( testAttribute( Qt::WA_OpaquePaintEvent ) ) + { + qwtFillBackground( &painter, this ); + drawCanvas( &painter, true ); + } + else + { + drawCanvas( &painter, false ); + } + } + else + { + if ( testAttribute( Qt::WA_OpaquePaintEvent ) ) + { + if ( autoFillBackground() ) + qwtDrawBackground( &painter, this ); + } + + drawCanvas( &painter, false ); + + if ( frameWidth() > 0 ) + drawBorder( &painter ); + } + } + + if ( hasFocus() && focusIndicator() == CanvasFocusIndicator ) + drawFocusIndicator( &painter ); +} + +void QwtPlotCanvas::drawCanvas( QPainter *painter, bool withBackground ) +{ + bool hackStyledBackground = false; + + if ( withBackground && testAttribute( Qt::WA_StyledBackground ) + && testPaintAttribute( HackStyledBackground ) ) + { + // Antialiasing rounded borders is done by + // inserting pixels with colors between the + // border color and the color on the canvas, + // When the border is painted before the plot items + // these colors are interpolated for the canvas + // and the plot items need to be clipped excluding + // the anialiased pixels. In situations, where + // the plot items fill the area at the rounded + // borders this is noticeable. + // The only way to avoid these annoying "artefacts" + // is to paint the border on top of the plot items. + + if ( d_data->styleSheet.hasBorder && + !d_data->styleSheet.borderPath.isEmpty() ) + { + // We have a border with at least one rounded corner + hackStyledBackground = true; + } + } + + if ( withBackground ) + { + painter->save(); + + if ( testAttribute( Qt::WA_StyledBackground ) ) + { + if ( hackStyledBackground ) + { + // paint background without border + + painter->setPen( Qt::NoPen ); + painter->setBrush( d_data->styleSheet.background.brush ); + painter->setBrushOrigin( d_data->styleSheet.background.origin ); + painter->setClipPath( d_data->styleSheet.borderPath ); + painter->drawRect( contentsRect() ); + } + else + { + qwtDrawStyledBackground( this, painter ); + } + } + else if ( autoFillBackground() ) + { + painter->setPen( Qt::NoPen ); + painter->setBrush( palette().brush( backgroundRole() ) ); + + if ( d_data->borderRadius > 0.0 ) + { + if ( frameWidth() > 0 ) + { + painter->setClipPath( borderPath( rect() ) ); + painter->drawRect( rect() ); + } + else + { + painter->setRenderHint( QPainter::Antialiasing, true ); + painter->drawPath( borderPath( rect() ) ); + } + } + else + { + painter->drawRect( contentsRect() ); + } + } + + painter->restore(); + } + + painter->save(); + + if ( !d_data->styleSheet.borderPath.isEmpty() ) + { + painter->setClipPath( + d_data->styleSheet.borderPath, Qt::IntersectClip ); + } + else + { + if ( d_data->borderRadius > 0.0 ) + painter->setClipPath( borderPath( rect() ), Qt::IntersectClip ); + else + painter->setClipRect( contentsRect(), Qt::IntersectClip ); + } + + plot()->drawCanvas( painter ); + + painter->restore(); + + if ( withBackground && hackStyledBackground ) + { + // Now paint the border on top + QStyleOptionFrame opt; + opt.initFrom(this); + style()->drawPrimitive( QStyle::PE_Frame, &opt, painter, this); + } +} + +/*! + Draw the border of the plot canvas + + \param painter Painter + \sa setBorderRadius(), QFrame::drawFrame() +*/ +void QwtPlotCanvas::drawBorder( QPainter *painter ) +{ + if ( d_data->borderRadius > 0 ) + { + if ( frameWidth() > 0 ) + { + QwtPainter::drawRoundedFrame( painter, QRectF( rect() ), + d_data->borderRadius, d_data->borderRadius, + palette(), frameWidth(), frameStyle() ); + } + } + else + { + drawFrame( painter ); + } +} + +/*! + Resize event + \param event Resize event +*/ +void QwtPlotCanvas::resizeEvent( QResizeEvent *event ) +{ + QFrame::resizeEvent( event ); + updateStyleSheetInfo(); +} + +/*! + Draw the focus indication + \param painter Painter +*/ +void QwtPlotCanvas::drawFocusIndicator( QPainter *painter ) +{ + const int margin = 1; + + QRect focusRect = contentsRect(); + focusRect.setRect( focusRect.x() + margin, focusRect.y() + margin, + focusRect.width() - 2 * margin, focusRect.height() - 2 * margin ); + + QwtPainter::drawFocusRect( painter, this, focusRect ); +} + +/*! + Invalidate the paint cache and repaint the canvas + \sa invalidatePaintCache() +*/ +void QwtPlotCanvas::replot() +{ + invalidateBackingStore(); + + if ( testPaintAttribute( QwtPlotCanvas::ImmediatePaint ) ) + repaint( contentsRect() ); + else + update( contentsRect() ); +} + +//! Update the cached informations about the current style sheet +void QwtPlotCanvas::updateStyleSheetInfo() +{ + if ( !testAttribute(Qt::WA_StyledBackground ) ) + return; + + QwtStyleSheetRecorder recorder( size() ); + + QPainter painter( &recorder ); + + QStyleOption opt; + opt.initFrom(this); + style()->drawPrimitive( QStyle::PE_Widget, &opt, &painter, this); + + painter.end(); + + d_data->styleSheet.hasBorder = !recorder.border.rectList.isEmpty(); + d_data->styleSheet.cornerRects = recorder.clipRects; + + if ( recorder.background.path.isEmpty() ) + { + if ( !recorder.border.rectList.isEmpty() ) + { + d_data->styleSheet.borderPath = + qwtCombinePathList( rect(), recorder.border.pathList ); + } + } + else + { + d_data->styleSheet.borderPath = recorder.background.path; + d_data->styleSheet.background.brush = recorder.background.brush; + d_data->styleSheet.background.origin = recorder.background.origin; + } +} + +/*! + Calculate the painter path for a styled or rounded border + + When the canvas has no styled background or rounded borders + the painter path is empty. + + \param rect Bounding rectangle of the canvas + \return Painter path, that can be used for clipping +*/ +QPainterPath QwtPlotCanvas::borderPath( const QRect &rect ) const +{ + if ( testAttribute(Qt::WA_StyledBackground ) ) + { + QwtStyleSheetRecorder recorder( rect.size() ); + + QPainter painter( &recorder ); + + QStyleOption opt; + opt.initFrom(this); + opt.rect = rect; + style()->drawPrimitive( QStyle::PE_Widget, &opt, &painter, this); + + painter.end(); + + if ( !recorder.background.path.isEmpty() ) + return recorder.background.path; + + if ( !recorder.border.rectList.isEmpty() ) + return qwtCombinePathList( rect, recorder.border.pathList ); + } + else if ( d_data->borderRadius > 0.0 ) + { + double fw2 = frameWidth() * 0.5; + QRectF r = QRectF(rect).adjusted( fw2, fw2, -fw2, -fw2 ); + + QPainterPath path; + path.addRoundedRect( r, d_data->borderRadius, d_data->borderRadius ); + return path; + } + + return QPainterPath(); +} + +/*! + Calculate a mask, that can be used to clip away the border frame + + \param size Size including the frame +*/ +QBitmap QwtPlotCanvas::borderMask( const QSize &size ) const +{ + const QRect r( 0, 0, size.width(), size.height() ); + + const QPainterPath path = borderPath( r ); + if ( path.isEmpty() ) + return QBitmap(); + + QImage image( size, QImage::Format_ARGB32_Premultiplied ); + image.fill( Qt::color0 ); + + QPainter painter( &image ); + painter.setClipPath( path ); + painter.fillRect( r, Qt::color1 ); + + // now erase the frame + + painter.setCompositionMode( QPainter::CompositionMode_DestinationOut ); + + if ( testAttribute(Qt::WA_StyledBackground ) ) + { + QStyleOptionFrame opt; + opt.initFrom(this); + opt.rect = r; + style()->drawPrimitive( QStyle::PE_Frame, &opt, &painter, this ); + } + else + { + if ( d_data->borderRadius > 0 && frameWidth() > 0 ) + { + painter.setPen( QPen( Qt::color1, frameWidth() ) ); + painter.setBrush( Qt::NoBrush ); + painter.setRenderHint( QPainter::Antialiasing, true ); + + painter.drawPath( path ); + } + } + + painter.end(); + + const QImage mask = image.createMaskFromColor( + QColor( Qt::color1 ).rgb(), Qt::MaskOutColor ); + + return QBitmap::fromImage( mask ); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_canvas.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_canvas.h index 740dfeaca..9f1bd9381 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_canvas.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_canvas.h @@ -1,168 +1,168 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PLOT_CANVAS_H -#define QWT_PLOT_CANVAS_H - -#include "qwt_global.h" -#include -#include -#include -#include - -class QwtPlot; -class QPixmap; - -/*! - \brief Canvas of a QwtPlot. - \sa QwtPlot -*/ -class QWT_EXPORT QwtPlotCanvas : public QFrame -{ - Q_OBJECT - -public: - - /*! - \brief Paint attributes - - The default setting enables BackingStore and Opaque. - - \sa setPaintAttribute(), testPaintAttribute() - */ - enum PaintAttribute - { - /*! - \brief Paint double buffered reusing the content - of the pixmap buffer when possible. - - Using a backing store might improve the performance - significantly, when workin with widget overlays ( like rubberbands ). - Disabling the cache might improve the performance for - incremental paints (using QwtPlotDirectPainter ). - - \sa backingStore(), invalidateBackingStore() - */ - BackingStore = 1, - - /*! - \brief Try to fill the complete contents rectangle - of the plot canvas - - When using styled backgrounds Qt assumes, that the - canvas doesn't fill its area completely - ( f.e because of rounded borders ) and fills the area - below the canvas. When this is done with gradients it might - result in a serious performance bottleneck - depending on the size. - - When the Opaque attribute is enabled the canvas tries to - identify the gaps with some heuristics and to fill those only. - - \warning Will not work for semitransparent backgrounds - */ - Opaque = 2, - - /*! - \brief Try to improve painting of styled backgrounds - - QwtPlotCanvas supports the box model attributes for - customizing the layout with style sheets. Unfortunately - the design of Qt style sheets has no concept how to - handle backgrounds with rounded corners - beside of padding. - - When HackStyledBackground is enabled the plot canvas tries - to seperate the background from the background border - by reverse engeneering to paint the background before and - the border after the plot items. In this order the border - gets prefectly antialiased and you can avoid some pixel - artifacts in the corners. - */ - HackStyledBackground = 4, - - /*! - When ImmediatePaint is set replot() calls repaint() - instead of update(). - - \sa replot(), QWidget::repaint(), QWidget::update() - */ - ImmediatePaint = 8 - }; - - //! Paint attributes - typedef QFlags PaintAttributes; - - /*! - \brief Focus indicator - - - NoFocusIndicator\n - Don't paint a focus indicator - - - CanvasFocusIndicator\n - The focus is related to the complete canvas. - Paint the focus indicator using paintFocus() - - - ItemFocusIndicator\n - The focus is related to an item (curve, point, ...) on - the canvas. It is up to the application to display a - focus indication using f.e. highlighting. - - \sa setFocusIndicator(), focusIndicator(), paintFocus() - */ - - enum FocusIndicator - { - NoFocusIndicator, - CanvasFocusIndicator, - ItemFocusIndicator - }; - - explicit QwtPlotCanvas( QwtPlot * ); - virtual ~QwtPlotCanvas(); - - QwtPlot *plot(); - const QwtPlot *plot() const; - - void setFocusIndicator( FocusIndicator ); - FocusIndicator focusIndicator() const; - - void setBorderRadius( double ); - double borderRadius() const; - - QPainterPath borderPath( const QRect &rect ) const; - QBitmap borderMask( const QSize & ) const; - - void setPaintAttribute( PaintAttribute, bool on = true ); - bool testPaintAttribute( PaintAttribute ) const; - - const QPixmap *backingStore() const; - void invalidateBackingStore(); - - void replot(); - - virtual bool event( QEvent * ); - -protected: - virtual void paintEvent( QPaintEvent * ); - virtual void resizeEvent( QResizeEvent * ); - - virtual void drawFocusIndicator( QPainter * ); - virtual void drawBorder( QPainter * ); - - void updateStyleSheetInfo(); - -private: - void drawCanvas( QPainter *, bool withBackground ); - - class PrivateData; - PrivateData *d_data; -}; - -Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCanvas::PaintAttributes ) - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_CANVAS_H +#define QWT_PLOT_CANVAS_H + +#include "qwt_global.h" +#include +#include +#include +#include + +class QwtPlot; +class QPixmap; + +/*! + \brief Canvas of a QwtPlot. + \sa QwtPlot +*/ +class QWT_EXPORT QwtPlotCanvas : public QFrame +{ + Q_OBJECT + +public: + + /*! + \brief Paint attributes + + The default setting enables BackingStore and Opaque. + + \sa setPaintAttribute(), testPaintAttribute() + */ + enum PaintAttribute + { + /*! + \brief Paint double buffered reusing the content + of the pixmap buffer when possible. + + Using a backing store might improve the performance + significantly, when workin with widget overlays ( like rubberbands ). + Disabling the cache might improve the performance for + incremental paints (using QwtPlotDirectPainter ). + + \sa backingStore(), invalidateBackingStore() + */ + BackingStore = 1, + + /*! + \brief Try to fill the complete contents rectangle + of the plot canvas + + When using styled backgrounds Qt assumes, that the + canvas doesn't fill its area completely + ( f.e because of rounded borders ) and fills the area + below the canvas. When this is done with gradients it might + result in a serious performance bottleneck - depending on the size. + + When the Opaque attribute is enabled the canvas tries to + identify the gaps with some heuristics and to fill those only. + + \warning Will not work for semitransparent backgrounds + */ + Opaque = 2, + + /*! + \brief Try to improve painting of styled backgrounds + + QwtPlotCanvas supports the box model attributes for + customizing the layout with style sheets. Unfortunately + the design of Qt style sheets has no concept how to + handle backgrounds with rounded corners - beside of padding. + + When HackStyledBackground is enabled the plot canvas tries + to seperate the background from the background border + by reverse engeneering to paint the background before and + the border after the plot items. In this order the border + gets prefectly antialiased and you can avoid some pixel + artifacts in the corners. + */ + HackStyledBackground = 4, + + /*! + When ImmediatePaint is set replot() calls repaint() + instead of update(). + + \sa replot(), QWidget::repaint(), QWidget::update() + */ + ImmediatePaint = 8 + }; + + //! Paint attributes + typedef QFlags PaintAttributes; + + /*! + \brief Focus indicator + + - NoFocusIndicator\n + Don't paint a focus indicator + + - CanvasFocusIndicator\n + The focus is related to the complete canvas. + Paint the focus indicator using paintFocus() + + - ItemFocusIndicator\n + The focus is related to an item (curve, point, ...) on + the canvas. It is up to the application to display a + focus indication using f.e. highlighting. + + \sa setFocusIndicator(), focusIndicator(), paintFocus() + */ + + enum FocusIndicator + { + NoFocusIndicator, + CanvasFocusIndicator, + ItemFocusIndicator + }; + + explicit QwtPlotCanvas( QwtPlot * ); + virtual ~QwtPlotCanvas(); + + QwtPlot *plot(); + const QwtPlot *plot() const; + + void setFocusIndicator( FocusIndicator ); + FocusIndicator focusIndicator() const; + + void setBorderRadius( double ); + double borderRadius() const; + + QPainterPath borderPath( const QRect &rect ) const; + QBitmap borderMask( const QSize & ) const; + + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; + + const QPixmap *backingStore() const; + void invalidateBackingStore(); + + void replot(); + + virtual bool event( QEvent * ); + +protected: + virtual void paintEvent( QPaintEvent * ); + virtual void resizeEvent( QResizeEvent * ); + + virtual void drawFocusIndicator( QPainter * ); + virtual void drawBorder( QPainter * ); + + void updateStyleSheetInfo(); + +private: + void drawCanvas( QPainter *, bool withBackground ); + + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCanvas::PaintAttributes ) + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_curve.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_curve.cpp index 4111d744a..a38119ab8 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_curve.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_curve.cpp @@ -1,1124 +1,1124 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot_curve.h" -#include "qwt_math.h" -#include "qwt_clipper.h" -#include "qwt_painter.h" -#include "qwt_legend.h" -#include "qwt_legend_item.h" -#include "qwt_scale_map.h" -#include "qwt_plot.h" -#include "qwt_plot_canvas.h" -#include "qwt_curve_fitter.h" -#include "qwt_symbol.h" -#include -#include -#include -#include - -static int verifyRange( int size, int &i1, int &i2 ) -{ - if ( size < 1 ) - return 0; - - i1 = qBound( 0, i1, size - 1 ); - i2 = qBound( 0, i2, size - 1 ); - - if ( i1 > i2 ) - qSwap( i1, i2 ); - - return ( i2 - i1 + 1 ); -} - -class QwtPlotCurve::PrivateData -{ -public: - PrivateData(): - style( QwtPlotCurve::Lines ), - baseline( 0.0 ), - symbol( NULL ), - attributes( 0 ), - paintAttributes( QwtPlotCurve::ClipPolygons ), - legendAttributes( 0 ) - { - pen = QPen( Qt::black ); - curveFitter = new QwtSplineCurveFitter; - } - - ~PrivateData() - { - delete symbol; - delete curveFitter; - } - - QwtPlotCurve::CurveStyle style; - double baseline; - - const QwtSymbol *symbol; - QwtCurveFitter *curveFitter; - - QPen pen; - QBrush brush; - - QwtPlotCurve::CurveAttributes attributes; - QwtPlotCurve::PaintAttributes paintAttributes; - - QwtPlotCurve::LegendAttributes legendAttributes; -}; - -/*! - Constructor - \param title Title of the curve -*/ -QwtPlotCurve::QwtPlotCurve( const QwtText &title ): - QwtPlotSeriesItem( title ) -{ - init(); -} - -/*! - Constructor - \param title Title of the curve -*/ -QwtPlotCurve::QwtPlotCurve( const QString &title ): - QwtPlotSeriesItem( QwtText( title ) ) -{ - init(); -} - -//! Destructor -QwtPlotCurve::~QwtPlotCurve() -{ - delete d_data; -} - -//! Initialize internal members -void QwtPlotCurve::init() -{ - setItemAttribute( QwtPlotItem::Legend ); - setItemAttribute( QwtPlotItem::AutoScale ); - - d_data = new PrivateData; - d_series = new QwtPointSeriesData(); - - setZ( 20.0 ); -} - -//! \return QwtPlotItem::Rtti_PlotCurve -int QwtPlotCurve::rtti() const -{ - return QwtPlotItem::Rtti_PlotCurve; -} - -/*! - Specify an attribute how to draw the curve - - \param attribute Paint attribute - \param on On/Off - \sa testPaintAttribute() -*/ -void QwtPlotCurve::setPaintAttribute( PaintAttribute attribute, bool on ) -{ - if ( on ) - d_data->paintAttributes |= attribute; - else - d_data->paintAttributes &= ~attribute; -} - -/*! - \brief Return the current paint attributes - \sa setPaintAttribute() -*/ -bool QwtPlotCurve::testPaintAttribute( PaintAttribute attribute ) const -{ - return ( d_data->paintAttributes & attribute ); -} - -/*! - Specify an attribute how to draw the legend identifier - - \param attribute Attribute - \param on On/Off - /sa testLegendAttribute() -*/ -void QwtPlotCurve::setLegendAttribute( LegendAttribute attribute, bool on ) -{ - if ( on ) - d_data->legendAttributes |= attribute; - else - d_data->legendAttributes &= ~attribute; -} - -/*! - \brief Return the current paint attributes - \sa setLegendAttribute() -*/ -bool QwtPlotCurve::testLegendAttribute( LegendAttribute attribute ) const -{ - return ( d_data->legendAttributes & attribute ); -} - -/*! - Set the curve's drawing style - - \param style Curve style - \sa style() -*/ -void QwtPlotCurve::setStyle( CurveStyle style ) -{ - if ( style != d_data->style ) - { - d_data->style = style; - itemChanged(); - } -} - -/*! - Return the current style - \sa setStyle() -*/ -QwtPlotCurve::CurveStyle QwtPlotCurve::style() const -{ - return d_data->style; -} - -/*! - Assign a symbol - - \param symbol Symbol - \sa symbol() -*/ -void QwtPlotCurve::setSymbol( const QwtSymbol *symbol ) -{ - if ( symbol != d_data->symbol ) - { - delete d_data->symbol; - d_data->symbol = symbol; - itemChanged(); - } -} - -/*! - \return Current symbol or NULL, when no symbol has been assigned - \sa setSymbol() -*/ -const QwtSymbol *QwtPlotCurve::symbol() const -{ - return d_data->symbol; -} - -/*! - Assign a pen - - \param pen New pen - \sa pen(), brush() -*/ -void QwtPlotCurve::setPen( const QPen &pen ) -{ - if ( pen != d_data->pen ) - { - d_data->pen = pen; - itemChanged(); - } -} - -/*! - \return Pen used to draw the lines - \sa setPen(), brush() -*/ -const QPen& QwtPlotCurve::pen() const -{ - return d_data->pen; -} - -/*! - \brief Assign a brush. - - In case of brush.style() != QBrush::NoBrush - and style() != QwtPlotCurve::Sticks - the area between the curve and the baseline will be filled. - - In case !brush.color().isValid() the area will be filled by - pen.color(). The fill algorithm simply connects the first and the - last curve point to the baseline. So the curve data has to be sorted - (ascending or descending). - - \param brush New brush - \sa brush(), setBaseline(), baseline() -*/ -void QwtPlotCurve::setBrush( const QBrush &brush ) -{ - if ( brush != d_data->brush ) - { - d_data->brush = brush; - itemChanged(); - } -} - -/*! - \return Brush used to fill the area between lines and the baseline - \sa setBrush(), setBaseline(), baseline() -*/ -const QBrush& QwtPlotCurve::brush() const -{ - return d_data->brush; -} - -/*! - Draw an interval of the curve - - \param painter Painter - \param xMap Maps x-values into pixel coordinates. - \param yMap Maps y-values into pixel coordinates. - \param canvasRect Contents rect of the canvas - \param from Index of the first point to be painted - \param to Index of the last point to be painted. If to < 0 the - curve will be painted to its last point. - - \sa drawCurve(), drawSymbols(), -*/ -void QwtPlotCurve::drawSeries( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const -{ - if ( !painter || dataSize() <= 0 ) - return; - - if ( to < 0 ) - to = dataSize() - 1; - - if ( verifyRange( dataSize(), from, to ) > 0 ) - { - painter->save(); - painter->setPen( d_data->pen ); - - /* - Qt 4.0.0 is slow when drawing lines, but it's even - slower when the painter has a brush. So we don't - set the brush before we really need it. - */ - - drawCurve( painter, d_data->style, xMap, yMap, canvasRect, from, to ); - painter->restore(); - - if ( d_data->symbol && - ( d_data->symbol->style() != QwtSymbol::NoSymbol ) ) - { - painter->save(); - drawSymbols( painter, *d_data->symbol, - xMap, yMap, canvasRect, from, to ); - painter->restore(); - } - } -} - -/*! - \brief Draw the line part (without symbols) of a curve interval. - \param painter Painter - \param style curve style, see QwtPlotCurve::CurveStyle - \param xMap x map - \param yMap y map - \param canvasRect Contents rect of the canvas - \param from index of the first point to be painted - \param to index of the last point to be painted - \sa draw(), drawDots(), drawLines(), drawSteps(), drawSticks() -*/ -void QwtPlotCurve::drawCurve( QPainter *painter, int style, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const -{ - switch ( style ) - { - case Lines: - if ( testCurveAttribute( Fitted ) ) - { - // we always need the complete - // curve for fitting - from = 0; - to = dataSize() - 1; - } - drawLines( painter, xMap, yMap, canvasRect, from, to ); - break; - case Sticks: - drawSticks( painter, xMap, yMap, canvasRect, from, to ); - break; - case Steps: - drawSteps( painter, xMap, yMap, canvasRect, from, to ); - break; - case Dots: - drawDots( painter, xMap, yMap, canvasRect, from, to ); - break; - case NoCurve: - default: - break; - } -} - -/*! - \brief Draw lines - - If the CurveAttribute Fitted is enabled a QwtCurveFitter tries - to interpolate/smooth the curve, before it is painted. - - \param painter Painter - \param xMap x map - \param yMap y map - \param canvasRect Contents rect of the canvas - \param from index of the first point to be painted - \param to index of the last point to be painted - - \sa setCurveAttribute(), setCurveFitter(), draw(), - drawLines(), drawDots(), drawSteps(), drawSticks() -*/ -void QwtPlotCurve::drawLines( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const -{ - int size = to - from + 1; - if ( size <= 0 ) - return; - - const bool doAlign = QwtPainter::roundingAlignment( painter ); - - QPolygonF polyline( size ); - - QPointF *points = polyline.data(); - for ( int i = from; i <= to; i++ ) - { - const QPointF sample = d_series->sample( i ); - - double x = xMap.transform( sample.x() ); - double y = yMap.transform( sample.y() ); - if ( doAlign ) - { - x = qRound( x ); - y = qRound( y ); - } - - points[i - from].rx() = x; - points[i - from].ry() = y; - } - - if ( ( d_data->attributes & Fitted ) && d_data->curveFitter ) - polyline = d_data->curveFitter->fitCurve( polyline ); - - if ( d_data->paintAttributes & ClipPolygons ) - { - qreal pw = qMax( qreal( 1.0 ), painter->pen().widthF()); - const QPolygonF clipped = QwtClipper::clipPolygonF( - canvasRect.adjusted(-pw, -pw, pw, pw), polyline, false ); - - QwtPainter::drawPolyline( painter, clipped ); - } - else - { - QwtPainter::drawPolyline( painter, polyline ); - } - - if ( d_data->brush.style() != Qt::NoBrush ) - fillCurve( painter, xMap, yMap, canvasRect, polyline ); -} - -/*! - Draw sticks - - \param painter Painter - \param xMap x map - \param yMap y map - \param canvasRect Contents rect of the canvas - \param from index of the first point to be painted - \param to index of the last point to be painted - - \sa draw(), drawCurve(), drawDots(), drawLines(), drawSteps() -*/ -void QwtPlotCurve::drawSticks( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &, int from, int to ) const -{ - painter->save(); - painter->setRenderHint( QPainter::Antialiasing, false ); - - const bool doAlign = QwtPainter::roundingAlignment( painter ); - - double x0 = xMap.transform( d_data->baseline ); - double y0 = yMap.transform( d_data->baseline ); - if ( doAlign ) - { - x0 = qRound( x0 ); - y0 = qRound( y0 ); - } - - const Qt::Orientation o = orientation(); - - for ( int i = from; i <= to; i++ ) - { - const QPointF sample = d_series->sample( i ); - double xi = xMap.transform( sample.x() ); - double yi = yMap.transform( sample.y() ); - if ( doAlign ) - { - xi = qRound( xi ); - yi = qRound( yi ); - } - - if ( o == Qt::Horizontal ) - QwtPainter::drawLine( painter, x0, yi, xi, yi ); - else - QwtPainter::drawLine( painter, xi, y0, xi, yi ); - } - - painter->restore(); -} - -/*! - Draw dots - - \param painter Painter - \param xMap x map - \param yMap y map - \param canvasRect Contents rect of the canvas - \param from index of the first point to be painted - \param to index of the last point to be painted - - \sa draw(), drawCurve(), drawSticks(), drawLines(), drawSteps() -*/ -void QwtPlotCurve::drawDots( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const -{ - const bool doFill = d_data->brush.style() != Qt::NoBrush; - const bool doAlign = QwtPainter::roundingAlignment( painter ); - - QPolygonF polyline; - if ( doFill ) - polyline.resize( to - from + 1 ); - - QPointF *points = polyline.data(); - - for ( int i = from; i <= to; i++ ) - { - const QPointF sample = d_series->sample( i ); - double xi = xMap.transform( sample.x() ); - double yi = yMap.transform( sample.y() ); - if ( doAlign ) - { - xi = qRound( xi ); - yi = qRound( yi ); - } - - QwtPainter::drawPoint( painter, QPointF( xi, yi ) ); - - if ( doFill ) - { - points[i - from].rx() = xi; - points[i - from].ry() = yi; - } - } - - if ( doFill ) - fillCurve( painter, xMap, yMap, canvasRect, polyline ); -} - -/*! - Draw step function - - The direction of the steps depends on Inverted attribute. - - \param painter Painter - \param xMap x map - \param yMap y map - \param canvasRect Contents rect of the canvas - \param from index of the first point to be painted - \param to index of the last point to be painted - - \sa CurveAttribute, setCurveAttribute(), - draw(), drawCurve(), drawDots(), drawLines(), drawSticks() -*/ -void QwtPlotCurve::drawSteps( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const -{ - const bool doAlign = QwtPainter::roundingAlignment( painter ); - - QPolygonF polygon( 2 * ( to - from ) + 1 ); - QPointF *points = polygon.data(); - - bool inverted = orientation() == Qt::Vertical; - if ( d_data->attributes & Inverted ) - inverted = !inverted; - - int i, ip; - for ( i = from, ip = 0; i <= to; i++, ip += 2 ) - { - const QPointF sample = d_series->sample( i ); - double xi = xMap.transform( sample.x() ); - double yi = yMap.transform( sample.y() ); - if ( doAlign ) - { - xi = qRound( xi ); - yi = qRound( yi ); - } - - if ( ip > 0 ) - { - const QPointF &p0 = points[ip - 2]; - QPointF &p = points[ip - 1]; - - if ( inverted ) - { - p.rx() = p0.x(); - p.ry() = yi; - } - else - { - p.rx() = xi; - p.ry() = p0.y(); - } - } - - points[ip].rx() = xi; - points[ip].ry() = yi; - } - - if ( d_data->paintAttributes & ClipPolygons ) - { - const QPolygonF clipped = QwtClipper::clipPolygonF( - canvasRect, polygon, false ); - - QwtPainter::drawPolyline( painter, clipped ); - } - else - { - QwtPainter::drawPolyline( painter, polygon ); - } - - if ( d_data->brush.style() != Qt::NoBrush ) - fillCurve( painter, xMap, yMap, canvasRect, polygon ); -} - - -/*! - Specify an attribute for drawing the curve - - \param attribute Curve attribute - \param on On/Off - - /sa testCurveAttribute(), setCurveFitter() -*/ -void QwtPlotCurve::setCurveAttribute( CurveAttribute attribute, bool on ) -{ - if ( bool( d_data->attributes & attribute ) == on ) - return; - - if ( on ) - d_data->attributes |= attribute; - else - d_data->attributes &= ~attribute; - - itemChanged(); -} - -/*! - \return true, if attribute is enabled - \sa setCurveAttribute() -*/ -bool QwtPlotCurve::testCurveAttribute( CurveAttribute attribute ) const -{ - return d_data->attributes & attribute; -} - -/*! - Assign a curve fitter - - The curve fitter "smooths" the curve points, when the Fitted - CurveAttribute is set. setCurveFitter(NULL) also disables curve fitting. - - The curve fitter operates on the translated points ( = widget coordinates) - to be functional for logarithmic scales. Obviously this is less performant - for fitting algorithms, that reduce the number of points. - - For situations, where curve fitting is used to improve the performance - of painting huge series of points it might be better to execute the fitter - on the curve points once and to cache the result in the QwtSeriesData object. - - \param curveFitter() Curve fitter - \sa Fitted -*/ -void QwtPlotCurve::setCurveFitter( QwtCurveFitter *curveFitter ) -{ - delete d_data->curveFitter; - d_data->curveFitter = curveFitter; - - itemChanged(); -} - -/*! - Get the curve fitter. If curve fitting is disabled NULL is returned. - - \return Curve fitter - \sa setCurveFitter(), Fitted -*/ -QwtCurveFitter *QwtPlotCurve::curveFitter() const -{ - return d_data->curveFitter; -} - -/*! - Fill the area between the curve and the baseline with - the curve brush - - \param painter Painter - \param xMap x map - \param yMap y map - \param canvasRect Contents rect of the canvas - \param polygon Polygon - will be modified ! - - \sa setBrush(), setBaseline(), setStyle() -*/ -void QwtPlotCurve::fillCurve( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, QPolygonF &polygon ) const -{ - if ( d_data->brush.style() == Qt::NoBrush ) - return; - - closePolyline( painter, xMap, yMap, polygon ); - if ( polygon.count() <= 2 ) // a line can't be filled - return; - - QBrush brush = d_data->brush; - if ( !brush.color().isValid() ) - brush.setColor( d_data->pen.color() ); - - if ( d_data->paintAttributes & ClipPolygons ) - polygon = QwtClipper::clipPolygonF( canvasRect, polygon, true ); - - painter->save(); - - painter->setPen( Qt::NoPen ); - painter->setBrush( brush ); - - QwtPainter::drawPolygon( painter, polygon ); - - painter->restore(); -} - -/*! - \brief Complete a polygon to be a closed polygon including the - area between the original polygon and the baseline. - - \param painter Painter - \param xMap X map - \param yMap Y map - \param polygon Polygon to be completed -*/ -void QwtPlotCurve::closePolyline( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - QPolygonF &polygon ) const -{ - if ( polygon.size() < 2 ) - return; - - const bool doAlign = QwtPainter::roundingAlignment( painter ); - - double baseline = d_data->baseline; - - if ( orientation() == Qt::Vertical ) - { - if ( yMap.transformation()->type() == QwtScaleTransformation::Log10 ) - { - if ( baseline < QwtScaleMap::LogMin ) - baseline = QwtScaleMap::LogMin; - } - - double refY = yMap.transform( baseline ); - if ( doAlign ) - refY = qRound( refY ); - - polygon += QPointF( polygon.last().x(), refY ); - polygon += QPointF( polygon.first().x(), refY ); - } - else - { - if ( xMap.transformation()->type() == QwtScaleTransformation::Log10 ) - { - if ( baseline < QwtScaleMap::LogMin ) - baseline = QwtScaleMap::LogMin; - } - - double refX = xMap.transform( baseline ); - if ( doAlign ) - refX = qRound( refX ); - - polygon += QPointF( refX, polygon.last().y() ); - polygon += QPointF( refX, polygon.first().y() ); - } -} - -/*! - Draw symbols - - \param painter Painter - \param symbol Curve symbol - \param xMap x map - \param yMap y map - \param canvasRect Contents rect of the canvas - \param from Index of the first point to be painted - \param to Index of the last point to be painted - - \sa setSymbol(), drawSeries(), drawCurve() -*/ -void QwtPlotCurve::drawSymbols( QPainter *painter, const QwtSymbol &symbol, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const -{ - const bool doAlign = QwtPainter::roundingAlignment( painter ); - - bool usePixmap = testPaintAttribute( CacheSymbols ); - if ( usePixmap && !doAlign ) - { - // Don't use the pixmap, when the paint device - // could generate scalable vectors - - usePixmap = false; - } - - if ( usePixmap ) - { - QPixmap pm( symbol.boundingSize() ); - pm.fill( Qt::transparent ); - - const double pw2 = 0.5 * pm.width(); - const double ph2 = 0.5 * pm.height(); - - QPainter p( &pm ); - p.setRenderHints( painter->renderHints() ); - symbol.drawSymbol( &p, QPointF( pw2, ph2 ) ); - p.end(); - - for ( int i = from; i <= to; i++ ) - { - const QPointF sample = d_series->sample( i ); - - double xi = xMap.transform( sample.x() ); - double yi = yMap.transform( sample.y() ); - if ( doAlign ) - { - xi = qRound( xi ); - yi = qRound( yi ); - } - - if ( canvasRect.contains( xi, yi ) ) - { - const int left = qCeil( xi ) - pw2; - const int top = qCeil( yi ) - ph2; - - painter->drawPixmap( left, top, pm ); - } - } - } - else - { - const int chunkSize = 500; - - for ( int i = from; i <= to; i += chunkSize ) - { - const int n = qMin( chunkSize, to - i + 1 ); - - QPolygonF points; - for ( int j = 0; j < n; j++ ) - { - const QPointF sample = d_series->sample( i + j ); - - const double xi = xMap.transform( sample.x() ); - const double yi = yMap.transform( sample.y() ); - - if ( canvasRect.contains( xi, yi ) ) - points += QPointF( xi, yi ); - } - - if ( points.size() > 0 ) - symbol.drawSymbols( painter, points ); - } - } -} - -/*! - \brief Set the value of the baseline - - The baseline is needed for filling the curve with a brush or - the Sticks drawing style. - The interpretation of the baseline depends on the CurveType. - With QwtPlotCurve::Yfx, the baseline is interpreted as a horizontal line - at y = baseline(), with QwtPlotCurve::Yfy, it is interpreted as a vertical - line at x = baseline(). - - The default value is 0.0. - - \param value Value of the baseline - \sa baseline(), setBrush(), setStyle(), setStyle() -*/ -void QwtPlotCurve::setBaseline( double value ) -{ - if ( d_data->baseline != value ) - { - d_data->baseline = value; - itemChanged(); - } -} - -/*! - \return Value of the baseline - \sa setBaseline() -*/ -double QwtPlotCurve::baseline() const -{ - return d_data->baseline; -} - -/*! - Find the closest curve point for a specific position - - \param pos Position, where to look for the closest curve point - \param dist If dist != NULL, closestPoint() returns the distance between - the position and the clostest curve point - \return Index of the closest curve point, or -1 if none can be found - ( f.e when the curve has no points ) - \note closestPoint() implements a dumb algorithm, that iterates - over all points -*/ -int QwtPlotCurve::closestPoint( const QPoint &pos, double *dist ) const -{ - if ( plot() == NULL || dataSize() <= 0 ) - return -1; - - const QwtScaleMap xMap = plot()->canvasMap( xAxis() ); - const QwtScaleMap yMap = plot()->canvasMap( yAxis() ); - - int index = -1; - double dmin = 1.0e10; - - for ( uint i = 0; i < dataSize(); i++ ) - { - const QPointF sample = d_series->sample( i ); - - const double cx = xMap.transform( sample.x() ) - pos.x(); - const double cy = yMap.transform( sample.y() ) - pos.y(); - - const double f = qwtSqr( cx ) + qwtSqr( cy ); - if ( f < dmin ) - { - index = i; - dmin = f; - } - } - if ( dist ) - *dist = qSqrt( dmin ); - - return index; -} - -/*! - \brief Update the widget that represents the item on the legend - - \param legend Legend - \sa drawLegendIdentifier(), legendItem(), QwtPlotItem::Legend -*/ -void QwtPlotCurve::updateLegend( QwtLegend *legend ) const -{ - if ( legend && testItemAttribute( QwtPlotItem::Legend ) - && ( d_data->legendAttributes & QwtPlotCurve::LegendShowSymbol ) - && d_data->symbol - && d_data->symbol->style() != QwtSymbol::NoSymbol ) - { - QWidget *lgdItem = legend->find( this ); - if ( lgdItem == NULL ) - { - lgdItem = legendItem(); - if ( lgdItem ) - legend->insert( this, lgdItem ); - } - - QwtLegendItem *l = qobject_cast( lgdItem ); - if ( l ) - { - QSize sz = d_data->symbol->boundingSize(); - sz += QSize( 2, 2 ); // margin - - if ( d_data->legendAttributes & QwtPlotCurve::LegendShowLine ) - { - // Avoid, that the line is completely covered by the symbol - - int w = qCeil( 1.5 * sz.width() ); - if ( w % 2 ) - w++; - - sz.setWidth( qMax( 8, w ) ); - } - - l->setIdentifierSize( sz ); - } - } - - QwtPlotItem::updateLegend( legend ); -} - -/*! - \brief Draw the identifier representing the curve on the legend - - \param painter Painter - \param rect Bounding rectangle for the identifier - - \sa setLegendAttribute(), QwtPlotItem::Legend -*/ -void QwtPlotCurve::drawLegendIdentifier( - QPainter *painter, const QRectF &rect ) const -{ - if ( rect.isEmpty() ) - return; - - const int dim = qMin( rect.width(), rect.height() ); - - QSize size( dim, dim ); - - QRectF r( 0, 0, size.width(), size.height() ); - r.moveCenter( rect.center() ); - - if ( d_data->legendAttributes == 0 ) - { - QBrush brush = d_data->brush; - if ( brush.style() == Qt::NoBrush ) - { - if ( style() != QwtPlotCurve::NoCurve ) - brush = QBrush( pen().color() ); - else if ( d_data->symbol && - ( d_data->symbol->style() != QwtSymbol::NoSymbol ) ) - { - brush = QBrush( d_data->symbol->pen().color() ); - } - } - if ( brush.style() != Qt::NoBrush ) - painter->fillRect( r, brush ); - } - if ( d_data->legendAttributes & QwtPlotCurve::LegendShowBrush ) - { - if ( d_data->brush.style() != Qt::NoBrush ) - painter->fillRect( r, d_data->brush ); - } - if ( d_data->legendAttributes & QwtPlotCurve::LegendShowLine ) - { - if ( pen() != Qt::NoPen ) - { - painter->setPen( pen() ); - QwtPainter::drawLine( painter, rect.left(), rect.center().y(), - rect.right() - 1.0, rect.center().y() ); - } - } - if ( d_data->legendAttributes & QwtPlotCurve::LegendShowSymbol ) - { - if ( d_data->symbol && - ( d_data->symbol->style() != QwtSymbol::NoSymbol ) ) - { - QSize symbolSize = d_data->symbol->boundingSize(); - symbolSize -= QSize( 2, 2 ); - - // scale the symbol size down if it doesn't fit into rect. - - double xRatio = 1.0; - if ( rect.width() < symbolSize.width() ) - xRatio = rect.width() / symbolSize.width(); - double yRatio = 1.0; - if ( rect.height() < symbolSize.height() ) - yRatio = rect.height() / symbolSize.height(); - - const double ratio = qMin( xRatio, yRatio ); - - painter->save(); - painter->scale( ratio, ratio ); - - d_data->symbol->drawSymbol( painter, rect.center() / ratio ); - - painter->restore(); - } - } -} - -/*! - Initialize data with an array of points (explicitly shared). - - \param samples Vector of points -*/ -void QwtPlotCurve::setSamples( const QVector &samples ) -{ - delete d_series; - d_series = new QwtPointSeriesData( samples ); - itemChanged(); -} - -#ifndef QWT_NO_COMPAT - -/*! - \brief Initialize the data by pointing to memory blocks which - are not managed by QwtPlotCurve. - - setRawSamples is provided for efficiency. - It is important to keep the pointers - during the lifetime of the underlying QwtCPointerData class. - - \param xData pointer to x data - \param yData pointer to y data - \param size size of x and y - - \sa QwtCPointerData -*/ -void QwtPlotCurve::setRawSamples( - const double *xData, const double *yData, int size ) -{ - delete d_series; - d_series = new QwtCPointerData( xData, yData, size ); - itemChanged(); -} - -/*! - Set data by copying x- and y-values from specified memory blocks. - Contrary to setRawSamples(), this function makes a 'deep copy' of - the data. - - \param xData pointer to x values - \param yData pointer to y values - \param size size of xData and yData - - \sa QwtPointArrayData -*/ -void QwtPlotCurve::setSamples( - const double *xData, const double *yData, int size ) -{ - delete d_series; - d_series = new QwtPointArrayData( xData, yData, size ); - itemChanged(); -} - -/*! - \brief Initialize data with x- and y-arrays (explicitly shared) - - \param xData x data - \param yData y data - - \sa QwtPointArrayData -*/ -void QwtPlotCurve::setSamples( const QVector &xData, - const QVector &yData ) -{ - delete d_series; - d_series = new QwtPointArrayData( xData, yData ); - itemChanged(); -} -#endif // !QWT_NO_COMPAT - +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_curve.h" +#include "qwt_math.h" +#include "qwt_clipper.h" +#include "qwt_painter.h" +#include "qwt_legend.h" +#include "qwt_legend_item.h" +#include "qwt_scale_map.h" +#include "qwt_plot.h" +#include "qwt_plot_canvas.h" +#include "qwt_curve_fitter.h" +#include "qwt_symbol.h" +#include +#include +#include +#include + +static int verifyRange( int size, int &i1, int &i2 ) +{ + if ( size < 1 ) + return 0; + + i1 = qBound( 0, i1, size - 1 ); + i2 = qBound( 0, i2, size - 1 ); + + if ( i1 > i2 ) + qSwap( i1, i2 ); + + return ( i2 - i1 + 1 ); +} + +class QwtPlotCurve::PrivateData +{ +public: + PrivateData(): + style( QwtPlotCurve::Lines ), + baseline( 0.0 ), + symbol( NULL ), + attributes( 0 ), + paintAttributes( QwtPlotCurve::ClipPolygons ), + legendAttributes( 0 ) + { + pen = QPen( Qt::black ); + curveFitter = new QwtSplineCurveFitter; + } + + ~PrivateData() + { + delete symbol; + delete curveFitter; + } + + QwtPlotCurve::CurveStyle style; + double baseline; + + const QwtSymbol *symbol; + QwtCurveFitter *curveFitter; + + QPen pen; + QBrush brush; + + QwtPlotCurve::CurveAttributes attributes; + QwtPlotCurve::PaintAttributes paintAttributes; + + QwtPlotCurve::LegendAttributes legendAttributes; +}; + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotCurve::QwtPlotCurve( const QwtText &title ): + QwtPlotSeriesItem( title ) +{ + init(); +} + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotCurve::QwtPlotCurve( const QString &title ): + QwtPlotSeriesItem( QwtText( title ) ) +{ + init(); +} + +//! Destructor +QwtPlotCurve::~QwtPlotCurve() +{ + delete d_data; +} + +//! Initialize internal members +void QwtPlotCurve::init() +{ + setItemAttribute( QwtPlotItem::Legend ); + setItemAttribute( QwtPlotItem::AutoScale ); + + d_data = new PrivateData; + d_series = new QwtPointSeriesData(); + + setZ( 20.0 ); +} + +//! \return QwtPlotItem::Rtti_PlotCurve +int QwtPlotCurve::rtti() const +{ + return QwtPlotItem::Rtti_PlotCurve; +} + +/*! + Specify an attribute how to draw the curve + + \param attribute Paint attribute + \param on On/Off + \sa testPaintAttribute() +*/ +void QwtPlotCurve::setPaintAttribute( PaintAttribute attribute, bool on ) +{ + if ( on ) + d_data->paintAttributes |= attribute; + else + d_data->paintAttributes &= ~attribute; +} + +/*! + \brief Return the current paint attributes + \sa setPaintAttribute() +*/ +bool QwtPlotCurve::testPaintAttribute( PaintAttribute attribute ) const +{ + return ( d_data->paintAttributes & attribute ); +} + +/*! + Specify an attribute how to draw the legend identifier + + \param attribute Attribute + \param on On/Off + /sa testLegendAttribute() +*/ +void QwtPlotCurve::setLegendAttribute( LegendAttribute attribute, bool on ) +{ + if ( on ) + d_data->legendAttributes |= attribute; + else + d_data->legendAttributes &= ~attribute; +} + +/*! + \brief Return the current paint attributes + \sa setLegendAttribute() +*/ +bool QwtPlotCurve::testLegendAttribute( LegendAttribute attribute ) const +{ + return ( d_data->legendAttributes & attribute ); +} + +/*! + Set the curve's drawing style + + \param style Curve style + \sa style() +*/ +void QwtPlotCurve::setStyle( CurveStyle style ) +{ + if ( style != d_data->style ) + { + d_data->style = style; + itemChanged(); + } +} + +/*! + Return the current style + \sa setStyle() +*/ +QwtPlotCurve::CurveStyle QwtPlotCurve::style() const +{ + return d_data->style; +} + +/*! + Assign a symbol + + \param symbol Symbol + \sa symbol() +*/ +void QwtPlotCurve::setSymbol( const QwtSymbol *symbol ) +{ + if ( symbol != d_data->symbol ) + { + delete d_data->symbol; + d_data->symbol = symbol; + itemChanged(); + } +} + +/*! + \return Current symbol or NULL, when no symbol has been assigned + \sa setSymbol() +*/ +const QwtSymbol *QwtPlotCurve::symbol() const +{ + return d_data->symbol; +} + +/*! + Assign a pen + + \param pen New pen + \sa pen(), brush() +*/ +void QwtPlotCurve::setPen( const QPen &pen ) +{ + if ( pen != d_data->pen ) + { + d_data->pen = pen; + itemChanged(); + } +} + +/*! + \return Pen used to draw the lines + \sa setPen(), brush() +*/ +const QPen& QwtPlotCurve::pen() const +{ + return d_data->pen; +} + +/*! + \brief Assign a brush. + + In case of brush.style() != QBrush::NoBrush + and style() != QwtPlotCurve::Sticks + the area between the curve and the baseline will be filled. + + In case !brush.color().isValid() the area will be filled by + pen.color(). The fill algorithm simply connects the first and the + last curve point to the baseline. So the curve data has to be sorted + (ascending or descending). + + \param brush New brush + \sa brush(), setBaseline(), baseline() +*/ +void QwtPlotCurve::setBrush( const QBrush &brush ) +{ + if ( brush != d_data->brush ) + { + d_data->brush = brush; + itemChanged(); + } +} + +/*! + \return Brush used to fill the area between lines and the baseline + \sa setBrush(), setBaseline(), baseline() +*/ +const QBrush& QwtPlotCurve::brush() const +{ + return d_data->brush; +} + +/*! + Draw an interval of the curve + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rect of the canvas + \param from Index of the first point to be painted + \param to Index of the last point to be painted. If to < 0 the + curve will be painted to its last point. + + \sa drawCurve(), drawSymbols(), +*/ +void QwtPlotCurve::drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + if ( !painter || dataSize() <= 0 ) + return; + + if ( to < 0 ) + to = dataSize() - 1; + + if ( verifyRange( dataSize(), from, to ) > 0 ) + { + painter->save(); + painter->setPen( d_data->pen ); + + /* + Qt 4.0.0 is slow when drawing lines, but it's even + slower when the painter has a brush. So we don't + set the brush before we really need it. + */ + + drawCurve( painter, d_data->style, xMap, yMap, canvasRect, from, to ); + painter->restore(); + + if ( d_data->symbol && + ( d_data->symbol->style() != QwtSymbol::NoSymbol ) ) + { + painter->save(); + drawSymbols( painter, *d_data->symbol, + xMap, yMap, canvasRect, from, to ); + painter->restore(); + } + } +} + +/*! + \brief Draw the line part (without symbols) of a curve interval. + \param painter Painter + \param style curve style, see QwtPlotCurve::CurveStyle + \param xMap x map + \param yMap y map + \param canvasRect Contents rect of the canvas + \param from index of the first point to be painted + \param to index of the last point to be painted + \sa draw(), drawDots(), drawLines(), drawSteps(), drawSticks() +*/ +void QwtPlotCurve::drawCurve( QPainter *painter, int style, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + switch ( style ) + { + case Lines: + if ( testCurveAttribute( Fitted ) ) + { + // we always need the complete + // curve for fitting + from = 0; + to = dataSize() - 1; + } + drawLines( painter, xMap, yMap, canvasRect, from, to ); + break; + case Sticks: + drawSticks( painter, xMap, yMap, canvasRect, from, to ); + break; + case Steps: + drawSteps( painter, xMap, yMap, canvasRect, from, to ); + break; + case Dots: + drawDots( painter, xMap, yMap, canvasRect, from, to ); + break; + case NoCurve: + default: + break; + } +} + +/*! + \brief Draw lines + + If the CurveAttribute Fitted is enabled a QwtCurveFitter tries + to interpolate/smooth the curve, before it is painted. + + \param painter Painter + \param xMap x map + \param yMap y map + \param canvasRect Contents rect of the canvas + \param from index of the first point to be painted + \param to index of the last point to be painted + + \sa setCurveAttribute(), setCurveFitter(), draw(), + drawLines(), drawDots(), drawSteps(), drawSticks() +*/ +void QwtPlotCurve::drawLines( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + int size = to - from + 1; + if ( size <= 0 ) + return; + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + QPolygonF polyline( size ); + + QPointF *points = polyline.data(); + for ( int i = from; i <= to; i++ ) + { + const QPointF sample = d_series->sample( i ); + + double x = xMap.transform( sample.x() ); + double y = yMap.transform( sample.y() ); + if ( doAlign ) + { + x = qRound( x ); + y = qRound( y ); + } + + points[i - from].rx() = x; + points[i - from].ry() = y; + } + + if ( ( d_data->attributes & Fitted ) && d_data->curveFitter ) + polyline = d_data->curveFitter->fitCurve( polyline ); + + if ( d_data->paintAttributes & ClipPolygons ) + { + qreal pw = qMax( qreal( 1.0 ), painter->pen().widthF()); + const QPolygonF clipped = QwtClipper::clipPolygonF( + canvasRect.adjusted(-pw, -pw, pw, pw), polyline, false ); + + QwtPainter::drawPolyline( painter, clipped ); + } + else + { + QwtPainter::drawPolyline( painter, polyline ); + } + + if ( d_data->brush.style() != Qt::NoBrush ) + fillCurve( painter, xMap, yMap, canvasRect, polyline ); +} + +/*! + Draw sticks + + \param painter Painter + \param xMap x map + \param yMap y map + \param canvasRect Contents rect of the canvas + \param from index of the first point to be painted + \param to index of the last point to be painted + + \sa draw(), drawCurve(), drawDots(), drawLines(), drawSteps() +*/ +void QwtPlotCurve::drawSticks( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &, int from, int to ) const +{ + painter->save(); + painter->setRenderHint( QPainter::Antialiasing, false ); + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + double x0 = xMap.transform( d_data->baseline ); + double y0 = yMap.transform( d_data->baseline ); + if ( doAlign ) + { + x0 = qRound( x0 ); + y0 = qRound( y0 ); + } + + const Qt::Orientation o = orientation(); + + for ( int i = from; i <= to; i++ ) + { + const QPointF sample = d_series->sample( i ); + double xi = xMap.transform( sample.x() ); + double yi = yMap.transform( sample.y() ); + if ( doAlign ) + { + xi = qRound( xi ); + yi = qRound( yi ); + } + + if ( o == Qt::Horizontal ) + QwtPainter::drawLine( painter, x0, yi, xi, yi ); + else + QwtPainter::drawLine( painter, xi, y0, xi, yi ); + } + + painter->restore(); +} + +/*! + Draw dots + + \param painter Painter + \param xMap x map + \param yMap y map + \param canvasRect Contents rect of the canvas + \param from index of the first point to be painted + \param to index of the last point to be painted + + \sa draw(), drawCurve(), drawSticks(), drawLines(), drawSteps() +*/ +void QwtPlotCurve::drawDots( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + const bool doFill = d_data->brush.style() != Qt::NoBrush; + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + QPolygonF polyline; + if ( doFill ) + polyline.resize( to - from + 1 ); + + QPointF *points = polyline.data(); + + for ( int i = from; i <= to; i++ ) + { + const QPointF sample = d_series->sample( i ); + double xi = xMap.transform( sample.x() ); + double yi = yMap.transform( sample.y() ); + if ( doAlign ) + { + xi = qRound( xi ); + yi = qRound( yi ); + } + + QwtPainter::drawPoint( painter, QPointF( xi, yi ) ); + + if ( doFill ) + { + points[i - from].rx() = xi; + points[i - from].ry() = yi; + } + } + + if ( doFill ) + fillCurve( painter, xMap, yMap, canvasRect, polyline ); +} + +/*! + Draw step function + + The direction of the steps depends on Inverted attribute. + + \param painter Painter + \param xMap x map + \param yMap y map + \param canvasRect Contents rect of the canvas + \param from index of the first point to be painted + \param to index of the last point to be painted + + \sa CurveAttribute, setCurveAttribute(), + draw(), drawCurve(), drawDots(), drawLines(), drawSticks() +*/ +void QwtPlotCurve::drawSteps( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + QPolygonF polygon( 2 * ( to - from ) + 1 ); + QPointF *points = polygon.data(); + + bool inverted = orientation() == Qt::Vertical; + if ( d_data->attributes & Inverted ) + inverted = !inverted; + + int i, ip; + for ( i = from, ip = 0; i <= to; i++, ip += 2 ) + { + const QPointF sample = d_series->sample( i ); + double xi = xMap.transform( sample.x() ); + double yi = yMap.transform( sample.y() ); + if ( doAlign ) + { + xi = qRound( xi ); + yi = qRound( yi ); + } + + if ( ip > 0 ) + { + const QPointF &p0 = points[ip - 2]; + QPointF &p = points[ip - 1]; + + if ( inverted ) + { + p.rx() = p0.x(); + p.ry() = yi; + } + else + { + p.rx() = xi; + p.ry() = p0.y(); + } + } + + points[ip].rx() = xi; + points[ip].ry() = yi; + } + + if ( d_data->paintAttributes & ClipPolygons ) + { + const QPolygonF clipped = QwtClipper::clipPolygonF( + canvasRect, polygon, false ); + + QwtPainter::drawPolyline( painter, clipped ); + } + else + { + QwtPainter::drawPolyline( painter, polygon ); + } + + if ( d_data->brush.style() != Qt::NoBrush ) + fillCurve( painter, xMap, yMap, canvasRect, polygon ); +} + + +/*! + Specify an attribute for drawing the curve + + \param attribute Curve attribute + \param on On/Off + + /sa testCurveAttribute(), setCurveFitter() +*/ +void QwtPlotCurve::setCurveAttribute( CurveAttribute attribute, bool on ) +{ + if ( bool( d_data->attributes & attribute ) == on ) + return; + + if ( on ) + d_data->attributes |= attribute; + else + d_data->attributes &= ~attribute; + + itemChanged(); +} + +/*! + \return true, if attribute is enabled + \sa setCurveAttribute() +*/ +bool QwtPlotCurve::testCurveAttribute( CurveAttribute attribute ) const +{ + return d_data->attributes & attribute; +} + +/*! + Assign a curve fitter + + The curve fitter "smooths" the curve points, when the Fitted + CurveAttribute is set. setCurveFitter(NULL) also disables curve fitting. + + The curve fitter operates on the translated points ( = widget coordinates) + to be functional for logarithmic scales. Obviously this is less performant + for fitting algorithms, that reduce the number of points. + + For situations, where curve fitting is used to improve the performance + of painting huge series of points it might be better to execute the fitter + on the curve points once and to cache the result in the QwtSeriesData object. + + \param curveFitter() Curve fitter + \sa Fitted +*/ +void QwtPlotCurve::setCurveFitter( QwtCurveFitter *curveFitter ) +{ + delete d_data->curveFitter; + d_data->curveFitter = curveFitter; + + itemChanged(); +} + +/*! + Get the curve fitter. If curve fitting is disabled NULL is returned. + + \return Curve fitter + \sa setCurveFitter(), Fitted +*/ +QwtCurveFitter *QwtPlotCurve::curveFitter() const +{ + return d_data->curveFitter; +} + +/*! + Fill the area between the curve and the baseline with + the curve brush + + \param painter Painter + \param xMap x map + \param yMap y map + \param canvasRect Contents rect of the canvas + \param polygon Polygon - will be modified ! + + \sa setBrush(), setBaseline(), setStyle() +*/ +void QwtPlotCurve::fillCurve( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, QPolygonF &polygon ) const +{ + if ( d_data->brush.style() == Qt::NoBrush ) + return; + + closePolyline( painter, xMap, yMap, polygon ); + if ( polygon.count() <= 2 ) // a line can't be filled + return; + + QBrush brush = d_data->brush; + if ( !brush.color().isValid() ) + brush.setColor( d_data->pen.color() ); + + if ( d_data->paintAttributes & ClipPolygons ) + polygon = QwtClipper::clipPolygonF( canvasRect, polygon, true ); + + painter->save(); + + painter->setPen( Qt::NoPen ); + painter->setBrush( brush ); + + QwtPainter::drawPolygon( painter, polygon ); + + painter->restore(); +} + +/*! + \brief Complete a polygon to be a closed polygon including the + area between the original polygon and the baseline. + + \param painter Painter + \param xMap X map + \param yMap Y map + \param polygon Polygon to be completed +*/ +void QwtPlotCurve::closePolyline( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + QPolygonF &polygon ) const +{ + if ( polygon.size() < 2 ) + return; + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + double baseline = d_data->baseline; + + if ( orientation() == Qt::Vertical ) + { + if ( yMap.transformation()->type() == QwtScaleTransformation::Log10 ) + { + if ( baseline < QwtScaleMap::LogMin ) + baseline = QwtScaleMap::LogMin; + } + + double refY = yMap.transform( baseline ); + if ( doAlign ) + refY = qRound( refY ); + + polygon += QPointF( polygon.last().x(), refY ); + polygon += QPointF( polygon.first().x(), refY ); + } + else + { + if ( xMap.transformation()->type() == QwtScaleTransformation::Log10 ) + { + if ( baseline < QwtScaleMap::LogMin ) + baseline = QwtScaleMap::LogMin; + } + + double refX = xMap.transform( baseline ); + if ( doAlign ) + refX = qRound( refX ); + + polygon += QPointF( refX, polygon.last().y() ); + polygon += QPointF( refX, polygon.first().y() ); + } +} + +/*! + Draw symbols + + \param painter Painter + \param symbol Curve symbol + \param xMap x map + \param yMap y map + \param canvasRect Contents rect of the canvas + \param from Index of the first point to be painted + \param to Index of the last point to be painted + + \sa setSymbol(), drawSeries(), drawCurve() +*/ +void QwtPlotCurve::drawSymbols( QPainter *painter, const QwtSymbol &symbol, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + bool usePixmap = testPaintAttribute( CacheSymbols ); + if ( usePixmap && !doAlign ) + { + // Don't use the pixmap, when the paint device + // could generate scalable vectors + + usePixmap = false; + } + + if ( usePixmap ) + { + QPixmap pm( symbol.boundingSize() ); + pm.fill( Qt::transparent ); + + const double pw2 = 0.5 * pm.width(); + const double ph2 = 0.5 * pm.height(); + + QPainter p( &pm ); + p.setRenderHints( painter->renderHints() ); + symbol.drawSymbol( &p, QPointF( pw2, ph2 ) ); + p.end(); + + for ( int i = from; i <= to; i++ ) + { + const QPointF sample = d_series->sample( i ); + + double xi = xMap.transform( sample.x() ); + double yi = yMap.transform( sample.y() ); + if ( doAlign ) + { + xi = qRound( xi ); + yi = qRound( yi ); + } + + if ( canvasRect.contains( xi, yi ) ) + { + const int left = qCeil( xi ) - pw2; + const int top = qCeil( yi ) - ph2; + + painter->drawPixmap( left, top, pm ); + } + } + } + else + { + const int chunkSize = 500; + + for ( int i = from; i <= to; i += chunkSize ) + { + const int n = qMin( chunkSize, to - i + 1 ); + + QPolygonF points; + for ( int j = 0; j < n; j++ ) + { + const QPointF sample = d_series->sample( i + j ); + + const double xi = xMap.transform( sample.x() ); + const double yi = yMap.transform( sample.y() ); + + if ( canvasRect.contains( xi, yi ) ) + points += QPointF( xi, yi ); + } + + if ( points.size() > 0 ) + symbol.drawSymbols( painter, points ); + } + } +} + +/*! + \brief Set the value of the baseline + + The baseline is needed for filling the curve with a brush or + the Sticks drawing style. + The interpretation of the baseline depends on the CurveType. + With QwtPlotCurve::Yfx, the baseline is interpreted as a horizontal line + at y = baseline(), with QwtPlotCurve::Yfy, it is interpreted as a vertical + line at x = baseline(). + + The default value is 0.0. + + \param value Value of the baseline + \sa baseline(), setBrush(), setStyle(), setStyle() +*/ +void QwtPlotCurve::setBaseline( double value ) +{ + if ( d_data->baseline != value ) + { + d_data->baseline = value; + itemChanged(); + } +} + +/*! + \return Value of the baseline + \sa setBaseline() +*/ +double QwtPlotCurve::baseline() const +{ + return d_data->baseline; +} + +/*! + Find the closest curve point for a specific position + + \param pos Position, where to look for the closest curve point + \param dist If dist != NULL, closestPoint() returns the distance between + the position and the clostest curve point + \return Index of the closest curve point, or -1 if none can be found + ( f.e when the curve has no points ) + \note closestPoint() implements a dumb algorithm, that iterates + over all points +*/ +int QwtPlotCurve::closestPoint( const QPoint &pos, double *dist ) const +{ + if ( plot() == NULL || dataSize() <= 0 ) + return -1; + + const QwtScaleMap xMap = plot()->canvasMap( xAxis() ); + const QwtScaleMap yMap = plot()->canvasMap( yAxis() ); + + int index = -1; + double dmin = 1.0e10; + + for ( uint i = 0; i < dataSize(); i++ ) + { + const QPointF sample = d_series->sample( i ); + + const double cx = xMap.transform( sample.x() ) - pos.x(); + const double cy = yMap.transform( sample.y() ) - pos.y(); + + const double f = qwtSqr( cx ) + qwtSqr( cy ); + if ( f < dmin ) + { + index = i; + dmin = f; + } + } + if ( dist ) + *dist = qSqrt( dmin ); + + return index; +} + +/*! + \brief Update the widget that represents the item on the legend + + \param legend Legend + \sa drawLegendIdentifier(), legendItem(), QwtPlotItem::Legend +*/ +void QwtPlotCurve::updateLegend( QwtLegend *legend ) const +{ + if ( legend && testItemAttribute( QwtPlotItem::Legend ) + && ( d_data->legendAttributes & QwtPlotCurve::LegendShowSymbol ) + && d_data->symbol + && d_data->symbol->style() != QwtSymbol::NoSymbol ) + { + QWidget *lgdItem = legend->find( this ); + if ( lgdItem == NULL ) + { + lgdItem = legendItem(); + if ( lgdItem ) + legend->insert( this, lgdItem ); + } + + QwtLegendItem *l = qobject_cast( lgdItem ); + if ( l ) + { + QSize sz = d_data->symbol->boundingSize(); + sz += QSize( 2, 2 ); // margin + + if ( d_data->legendAttributes & QwtPlotCurve::LegendShowLine ) + { + // Avoid, that the line is completely covered by the symbol + + int w = qCeil( 1.5 * sz.width() ); + if ( w % 2 ) + w++; + + sz.setWidth( qMax( 8, w ) ); + } + + l->setIdentifierSize( sz ); + } + } + + QwtPlotItem::updateLegend( legend ); +} + +/*! + \brief Draw the identifier representing the curve on the legend + + \param painter Painter + \param rect Bounding rectangle for the identifier + + \sa setLegendAttribute(), QwtPlotItem::Legend +*/ +void QwtPlotCurve::drawLegendIdentifier( + QPainter *painter, const QRectF &rect ) const +{ + if ( rect.isEmpty() ) + return; + + const int dim = qMin( rect.width(), rect.height() ); + + QSize size( dim, dim ); + + QRectF r( 0, 0, size.width(), size.height() ); + r.moveCenter( rect.center() ); + + if ( d_data->legendAttributes == 0 ) + { + QBrush brush = d_data->brush; + if ( brush.style() == Qt::NoBrush ) + { + if ( style() != QwtPlotCurve::NoCurve ) + brush = QBrush( pen().color() ); + else if ( d_data->symbol && + ( d_data->symbol->style() != QwtSymbol::NoSymbol ) ) + { + brush = QBrush( d_data->symbol->pen().color() ); + } + } + if ( brush.style() != Qt::NoBrush ) + painter->fillRect( r, brush ); + } + if ( d_data->legendAttributes & QwtPlotCurve::LegendShowBrush ) + { + if ( d_data->brush.style() != Qt::NoBrush ) + painter->fillRect( r, d_data->brush ); + } + if ( d_data->legendAttributes & QwtPlotCurve::LegendShowLine ) + { + if ( pen() != Qt::NoPen ) + { + painter->setPen( pen() ); + QwtPainter::drawLine( painter, rect.left(), rect.center().y(), + rect.right() - 1.0, rect.center().y() ); + } + } + if ( d_data->legendAttributes & QwtPlotCurve::LegendShowSymbol ) + { + if ( d_data->symbol && + ( d_data->symbol->style() != QwtSymbol::NoSymbol ) ) + { + QSize symbolSize = d_data->symbol->boundingSize(); + symbolSize -= QSize( 2, 2 ); + + // scale the symbol size down if it doesn't fit into rect. + + double xRatio = 1.0; + if ( rect.width() < symbolSize.width() ) + xRatio = rect.width() / symbolSize.width(); + double yRatio = 1.0; + if ( rect.height() < symbolSize.height() ) + yRatio = rect.height() / symbolSize.height(); + + const double ratio = qMin( xRatio, yRatio ); + + painter->save(); + painter->scale( ratio, ratio ); + + d_data->symbol->drawSymbol( painter, rect.center() / ratio ); + + painter->restore(); + } + } +} + +/*! + Initialize data with an array of points (explicitly shared). + + \param samples Vector of points +*/ +void QwtPlotCurve::setSamples( const QVector &samples ) +{ + delete d_series; + d_series = new QwtPointSeriesData( samples ); + itemChanged(); +} + +#ifndef QWT_NO_COMPAT + +/*! + \brief Initialize the data by pointing to memory blocks which + are not managed by QwtPlotCurve. + + setRawSamples is provided for efficiency. + It is important to keep the pointers + during the lifetime of the underlying QwtCPointerData class. + + \param xData pointer to x data + \param yData pointer to y data + \param size size of x and y + + \sa QwtCPointerData +*/ +void QwtPlotCurve::setRawSamples( + const double *xData, const double *yData, int size ) +{ + delete d_series; + d_series = new QwtCPointerData( xData, yData, size ); + itemChanged(); +} + +/*! + Set data by copying x- and y-values from specified memory blocks. + Contrary to setRawSamples(), this function makes a 'deep copy' of + the data. + + \param xData pointer to x values + \param yData pointer to y values + \param size size of xData and yData + + \sa QwtPointArrayData +*/ +void QwtPlotCurve::setSamples( + const double *xData, const double *yData, int size ) +{ + delete d_series; + d_series = new QwtPointArrayData( xData, yData, size ); + itemChanged(); +} + +/*! + \brief Initialize data with x- and y-arrays (explicitly shared) + + \param xData x data + \param yData y data + + \sa QwtPointArrayData +*/ +void QwtPlotCurve::setSamples( const QVector &xData, + const QVector &yData ) +{ + delete d_series; + d_series = new QwtPointArrayData( xData, yData ); + itemChanged(); +} +#endif // !QWT_NO_COMPAT + diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_curve.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_curve.h index fa11dab25..3ea402682 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_curve.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_curve.h @@ -1,319 +1,319 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PLOT_CURVE_H -#define QWT_PLOT_CURVE_H - -#include "qwt_global.h" -#include "qwt_plot_seriesitem.h" -#include "qwt_series_data.h" -#include "qwt_text.h" -#include -#include - -class QPainter; -class QPolygonF; -class QwtScaleMap; -class QwtSymbol; -class QwtCurveFitter; - -/*! - \brief A plot item, that represents a series of points - - A curve is the representation of a series of points in the x-y plane. - It supports different display styles, interpolation ( f.e. spline ) - and symbols. - - \par Usage -
a) Assign curve properties
-
When a curve is created, it is configured to draw black solid lines - with in QwtPlotCurve::Lines style and no symbols. - You can change this by calling - setPen(), setStyle() and setSymbol().
-
b) Connect/Assign data.
-
QwtPlotCurve gets its points using a QwtSeriesData object offering - a bridge to the real storage of the points ( like QAbstractItemModel ). - There are several convenience classes derived from QwtSeriesData, that also store - the points inside ( like QStandardItemModel ). QwtPlotCurve also offers - a couple of variations of setSamples(), that build QwtSeriesData objects from - arrays internally.
-
c) Attach the curve to a plot
-
See QwtPlotItem::attach() -
- - \par Example: - see examples/bode - - \sa QwtPointSeriesData, QwtSymbol, QwtScaleMap -*/ -class QWT_EXPORT QwtPlotCurve: public QwtPlotSeriesItem -{ -public: - /*! - Curve styles. - \sa setStyle(), style() - */ - enum CurveStyle - { - /*! - Don't draw a curve. Note: This doesn't affect the symbols. - */ - NoCurve = -1, - - /*! - Connect the points with straight lines. The lines might - be interpolated depending on the 'Fitted' attribute. Curve - fitting can be configured using setCurveFitter(). - */ - Lines, - - /*! - Draw vertical or horizontal sticks ( depending on the - orientation() ) from a baseline which is defined by setBaseline(). - */ - Sticks, - - /*! - Connect the points with a step function. The step function - is drawn from the left to the right or vice versa, - depending on the QwtPlotCurve::Inverted attribute. - */ - Steps, - - /*! - Draw dots at the locations of the data points. Note: - This is different from a dotted line (see setPen()), and faster - as a curve in QwtPlotCurve::NoStyle style and a symbol - painting a point. - */ - Dots, - - /*! - Styles >= QwtPlotCurve::UserCurve are reserved for derived - classes of QwtPlotCurve that overload drawCurve() with - additional application specific curve types. - */ - UserCurve = 100 - }; - - /*! - Attribute for drawing the curve - \sa setCurveAttribute(), testCurveAttribute(), curveFitter() - */ - enum CurveAttribute - { - /*! - For QwtPlotCurve::Steps only. - Draws a step function from the right to the left. - */ - Inverted = 0x01, - - /*! - Only in combination with QwtPlotCurve::Lines - A QwtCurveFitter tries to - interpolate/smooth the curve, before it is painted. - - \note Curve fitting requires temorary memory - for calculating coefficients and additional points. - If painting in QwtPlotCurve::Fitted mode is slow it might be better - to fit the points, before they are passed to QwtPlotCurve. - */ - Fitted = 0x02 - }; - - //! Curve attributes - typedef QFlags CurveAttributes; - - /*! - Attributes how to represent the curve on the legend - - \sa setLegendAttribute(), testLegendAttribute(), - drawLegendIdentifier() - */ - - enum LegendAttribute - { - /*! - QwtPlotCurve tries to find a color representing the curve - and paints a rectangle with it. - */ - LegendNoAttribute = 0x00, - - /*! - If the style() is not QwtPlotCurve::NoCurve a line - is painted with the curve pen(). - */ - LegendShowLine = 0x01, - - /*! - If the curve has a valid symbol it is painted. - */ - LegendShowSymbol = 0x02, - - /*! - If the curve has a brush a rectangle filled with the - curve brush() is painted. - */ - LegendShowBrush = 0x04 - }; - - //! Legend attributes - typedef QFlags LegendAttributes; - - /*! - Attributes to modify the drawing algorithm. - The default setting enables ClipPolygons - - \sa setPaintAttribute(), testPaintAttribute() - */ - enum PaintAttribute - { - /*! - Clip polygons before painting them. In situations, where points - are far outside the visible area (f.e when zooming deep) this - might be a substantial improvement for the painting performance - */ - ClipPolygons = 0x01, - - /*! - Paint the symbol to a QPixmap and paint the pixmap - instead rendering the symbol for each point. The flag has - no effect, when the curve is not painted to the canvas - ( f.e when exporting the plot to a PDF document ). - */ - CacheSymbols = 0x02 - }; - - //! Paint attributes - typedef QFlags PaintAttributes; - - explicit QwtPlotCurve( const QString &title = QString::null ); - explicit QwtPlotCurve( const QwtText &title ); - - virtual ~QwtPlotCurve(); - - virtual int rtti() const; - - void setPaintAttribute( PaintAttribute, bool on = true ); - bool testPaintAttribute( PaintAttribute ) const; - - void setLegendAttribute( LegendAttribute, bool on = true ); - bool testLegendAttribute( LegendAttribute ) const; - -#ifndef QWT_NO_COMPAT - void setRawSamples( const double *xData, const double *yData, int size ); - void setSamples( const double *xData, const double *yData, int size ); - void setSamples( const QVector &xData, const QVector &yData ); -#endif - void setSamples( const QVector & ); - - int closestPoint( const QPoint &pos, double *dist = NULL ) const; - - double minXValue() const; - double maxXValue() const; - double minYValue() const; - double maxYValue() const; - - void setCurveAttribute( CurveAttribute, bool on = true ); - bool testCurveAttribute( CurveAttribute ) const; - - void setPen( const QPen & ); - const QPen &pen() const; - - void setBrush( const QBrush & ); - const QBrush &brush() const; - - void setBaseline( double ref ); - double baseline() const; - - void setStyle( CurveStyle style ); - CurveStyle style() const; - - void setSymbol( const QwtSymbol *s ); - const QwtSymbol *symbol() const; - - void setCurveFitter( QwtCurveFitter * ); - QwtCurveFitter *curveFitter() const; - - virtual void drawSeries( QPainter *, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - - virtual void updateLegend( QwtLegend * ) const; - virtual void drawLegendIdentifier( QPainter *, const QRectF & ) const; - -protected: - - void init(); - - virtual void drawCurve( QPainter *p, int style, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - - virtual void drawSymbols( QPainter *p, const QwtSymbol &, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - - void drawLines( QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - - void drawSticks( QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - - void drawDots( QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - - void drawSteps( QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - - virtual void fillCurve( QPainter *, - const QwtScaleMap &, const QwtScaleMap &, - const QRectF &canvasRect, QPolygonF & ) const; - - void closePolyline( QPainter *, - const QwtScaleMap &, const QwtScaleMap &, QPolygonF & ) const; - -private: - class PrivateData; - PrivateData *d_data; -}; - -//! boundingRect().left() -inline double QwtPlotCurve::minXValue() const -{ - return boundingRect().left(); -} - -//! boundingRect().right() -inline double QwtPlotCurve::maxXValue() const -{ - return boundingRect().right(); -} - -//! boundingRect().top() -inline double QwtPlotCurve::minYValue() const -{ - return boundingRect().top(); -} - -//! boundingRect().bottom() -inline double QwtPlotCurve::maxYValue() const -{ - return boundingRect().bottom(); -} - -Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCurve::PaintAttributes ) -Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCurve::LegendAttributes ) -Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCurve::CurveAttributes ) - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_CURVE_H +#define QWT_PLOT_CURVE_H + +#include "qwt_global.h" +#include "qwt_plot_seriesitem.h" +#include "qwt_series_data.h" +#include "qwt_text.h" +#include +#include + +class QPainter; +class QPolygonF; +class QwtScaleMap; +class QwtSymbol; +class QwtCurveFitter; + +/*! + \brief A plot item, that represents a series of points + + A curve is the representation of a series of points in the x-y plane. + It supports different display styles, interpolation ( f.e. spline ) + and symbols. + + \par Usage +
a) Assign curve properties
+
When a curve is created, it is configured to draw black solid lines + with in QwtPlotCurve::Lines style and no symbols. + You can change this by calling + setPen(), setStyle() and setSymbol().
+
b) Connect/Assign data.
+
QwtPlotCurve gets its points using a QwtSeriesData object offering + a bridge to the real storage of the points ( like QAbstractItemModel ). + There are several convenience classes derived from QwtSeriesData, that also store + the points inside ( like QStandardItemModel ). QwtPlotCurve also offers + a couple of variations of setSamples(), that build QwtSeriesData objects from + arrays internally.
+
c) Attach the curve to a plot
+
See QwtPlotItem::attach() +
+ + \par Example: + see examples/bode + + \sa QwtPointSeriesData, QwtSymbol, QwtScaleMap +*/ +class QWT_EXPORT QwtPlotCurve: public QwtPlotSeriesItem +{ +public: + /*! + Curve styles. + \sa setStyle(), style() + */ + enum CurveStyle + { + /*! + Don't draw a curve. Note: This doesn't affect the symbols. + */ + NoCurve = -1, + + /*! + Connect the points with straight lines. The lines might + be interpolated depending on the 'Fitted' attribute. Curve + fitting can be configured using setCurveFitter(). + */ + Lines, + + /*! + Draw vertical or horizontal sticks ( depending on the + orientation() ) from a baseline which is defined by setBaseline(). + */ + Sticks, + + /*! + Connect the points with a step function. The step function + is drawn from the left to the right or vice versa, + depending on the QwtPlotCurve::Inverted attribute. + */ + Steps, + + /*! + Draw dots at the locations of the data points. Note: + This is different from a dotted line (see setPen()), and faster + as a curve in QwtPlotCurve::NoStyle style and a symbol + painting a point. + */ + Dots, + + /*! + Styles >= QwtPlotCurve::UserCurve are reserved for derived + classes of QwtPlotCurve that overload drawCurve() with + additional application specific curve types. + */ + UserCurve = 100 + }; + + /*! + Attribute for drawing the curve + \sa setCurveAttribute(), testCurveAttribute(), curveFitter() + */ + enum CurveAttribute + { + /*! + For QwtPlotCurve::Steps only. + Draws a step function from the right to the left. + */ + Inverted = 0x01, + + /*! + Only in combination with QwtPlotCurve::Lines + A QwtCurveFitter tries to + interpolate/smooth the curve, before it is painted. + + \note Curve fitting requires temorary memory + for calculating coefficients and additional points. + If painting in QwtPlotCurve::Fitted mode is slow it might be better + to fit the points, before they are passed to QwtPlotCurve. + */ + Fitted = 0x02 + }; + + //! Curve attributes + typedef QFlags CurveAttributes; + + /*! + Attributes how to represent the curve on the legend + + \sa setLegendAttribute(), testLegendAttribute(), + drawLegendIdentifier() + */ + + enum LegendAttribute + { + /*! + QwtPlotCurve tries to find a color representing the curve + and paints a rectangle with it. + */ + LegendNoAttribute = 0x00, + + /*! + If the style() is not QwtPlotCurve::NoCurve a line + is painted with the curve pen(). + */ + LegendShowLine = 0x01, + + /*! + If the curve has a valid symbol it is painted. + */ + LegendShowSymbol = 0x02, + + /*! + If the curve has a brush a rectangle filled with the + curve brush() is painted. + */ + LegendShowBrush = 0x04 + }; + + //! Legend attributes + typedef QFlags LegendAttributes; + + /*! + Attributes to modify the drawing algorithm. + The default setting enables ClipPolygons + + \sa setPaintAttribute(), testPaintAttribute() + */ + enum PaintAttribute + { + /*! + Clip polygons before painting them. In situations, where points + are far outside the visible area (f.e when zooming deep) this + might be a substantial improvement for the painting performance + */ + ClipPolygons = 0x01, + + /*! + Paint the symbol to a QPixmap and paint the pixmap + instead rendering the symbol for each point. The flag has + no effect, when the curve is not painted to the canvas + ( f.e when exporting the plot to a PDF document ). + */ + CacheSymbols = 0x02 + }; + + //! Paint attributes + typedef QFlags PaintAttributes; + + explicit QwtPlotCurve( const QString &title = QString::null ); + explicit QwtPlotCurve( const QwtText &title ); + + virtual ~QwtPlotCurve(); + + virtual int rtti() const; + + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; + + void setLegendAttribute( LegendAttribute, bool on = true ); + bool testLegendAttribute( LegendAttribute ) const; + +#ifndef QWT_NO_COMPAT + void setRawSamples( const double *xData, const double *yData, int size ); + void setSamples( const double *xData, const double *yData, int size ); + void setSamples( const QVector &xData, const QVector &yData ); +#endif + void setSamples( const QVector & ); + + int closestPoint( const QPoint &pos, double *dist = NULL ) const; + + double minXValue() const; + double maxXValue() const; + double minYValue() const; + double maxYValue() const; + + void setCurveAttribute( CurveAttribute, bool on = true ); + bool testCurveAttribute( CurveAttribute ) const; + + void setPen( const QPen & ); + const QPen &pen() const; + + void setBrush( const QBrush & ); + const QBrush &brush() const; + + void setBaseline( double ref ); + double baseline() const; + + void setStyle( CurveStyle style ); + CurveStyle style() const; + + void setSymbol( const QwtSymbol *s ); + const QwtSymbol *symbol() const; + + void setCurveFitter( QwtCurveFitter * ); + QwtCurveFitter *curveFitter() const; + + virtual void drawSeries( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual void updateLegend( QwtLegend * ) const; + virtual void drawLegendIdentifier( QPainter *, const QRectF & ) const; + +protected: + + void init(); + + virtual void drawCurve( QPainter *p, int style, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual void drawSymbols( QPainter *p, const QwtSymbol &, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + void drawLines( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + void drawSticks( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + void drawDots( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + void drawSteps( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual void fillCurve( QPainter *, + const QwtScaleMap &, const QwtScaleMap &, + const QRectF &canvasRect, QPolygonF & ) const; + + void closePolyline( QPainter *, + const QwtScaleMap &, const QwtScaleMap &, QPolygonF & ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +//! boundingRect().left() +inline double QwtPlotCurve::minXValue() const +{ + return boundingRect().left(); +} + +//! boundingRect().right() +inline double QwtPlotCurve::maxXValue() const +{ + return boundingRect().right(); +} + +//! boundingRect().top() +inline double QwtPlotCurve::minYValue() const +{ + return boundingRect().top(); +} + +//! boundingRect().bottom() +inline double QwtPlotCurve::maxYValue() const +{ + return boundingRect().bottom(); +} + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCurve::PaintAttributes ) +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCurve::LegendAttributes ) +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotCurve::CurveAttributes ) + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_dict.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_dict.cpp index f7000bc93..4125137e8 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_dict.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_dict.cpp @@ -1,188 +1,188 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot_dict.h" - -class QwtPlotDict::PrivateData -{ -public: - - class ItemList: public QList - { - public: - void insertItem( QwtPlotItem *item ) - { - if ( item == NULL ) - return; - - QList::iterator it = - qUpperBound( begin(), end(), item, LessZThan() ); - insert( it, item ); - } - - void removeItem( QwtPlotItem *item ) - { - if ( item == NULL ) - return; - - QList::iterator it = - qLowerBound( begin(), end(), item, LessZThan() ); - - for ( ; it != end(); ++it ) - { - if ( item == *it ) - { - erase( it ); - break; - } - } - } - private: - class LessZThan - { - public: - inline bool operator()( const QwtPlotItem *item1, - const QwtPlotItem *item2 ) const - { - return item1->z() < item2->z(); - } - }; - }; - - ItemList itemList; - bool autoDelete; -}; - -/*! - Constructor - - Auto deletion is enabled. - \sa setAutoDelete(), attachItem() -*/ -QwtPlotDict::QwtPlotDict() -{ - d_data = new QwtPlotDict::PrivateData; - d_data->autoDelete = true; -} - -/*! - Destructor - - If autoDelete is on, all attached items will be deleted - \sa setAutoDelete(), autoDelete(), attachItem() -*/ -QwtPlotDict::~QwtPlotDict() -{ - detachItems( QwtPlotItem::Rtti_PlotItem, d_data->autoDelete ); - delete d_data; -} - -/*! - En/Disable Auto deletion - - If Auto deletion is on all attached plot items will be deleted - in the destructor of QwtPlotDict. The default value is on. - - \sa autoDelete(), attachItem() -*/ -void QwtPlotDict::setAutoDelete( bool autoDelete ) -{ - d_data->autoDelete = autoDelete; -} - -/*! - \return true if auto deletion is enabled - \sa setAutoDelete(), attachItem() -*/ -bool QwtPlotDict::autoDelete() const -{ - return d_data->autoDelete; -} - -/*! - Attach/Detach a plot item - - Attached items will be deleted in the destructor, - if auto deletion is enabled (default). Manually detached - items are not deleted. - - \param item Plot item to attach/detach - \ on If true attach, else detach the item - - \sa setAutoDelete(), ~QwtPlotDict() -*/ -void QwtPlotDict::attachItem( QwtPlotItem *item, bool on ) -{ - if ( on ) - d_data->itemList.insertItem( item ); - else - d_data->itemList.removeItem( item ); -} - -/*! - Detach items from the dictionary - - \param rtti In case of QwtPlotItem::Rtti_PlotItem detach all items - otherwise only those items of the type rtti. - \param autoDelete If true, delete all detached items -*/ -void QwtPlotDict::detachItems( int rtti, bool autoDelete ) -{ - PrivateData::ItemList list = d_data->itemList; - QwtPlotItemIterator it = list.begin(); - while ( it != list.end() ) - { - QwtPlotItem *item = *it; - - ++it; // increment before removing item from the list - - if ( rtti == QwtPlotItem::Rtti_PlotItem || item->rtti() == rtti ) - { - item->attach( NULL ); - if ( autoDelete ) - delete item; - } - } -} - -/*! - \brief A QwtPlotItemList of all attached plot items. - - Use caution when iterating these lists, as removing/detaching an item will - invalidate the iterator. Instead you can place pointers to objects to be - removed in a removal list, and traverse that list later. - - \return List of all attached plot items. -*/ -const QwtPlotItemList &QwtPlotDict::itemList() const -{ - return d_data->itemList; -} - -/*! - \return List of all attached plot items of a specific type. - \sa QwtPlotItem::rtti() -*/ -QwtPlotItemList QwtPlotDict::itemList( int rtti ) const -{ - if ( rtti == QwtPlotItem::Rtti_PlotItem ) - return d_data->itemList; - - QwtPlotItemList items; - - PrivateData::ItemList list = d_data->itemList; - for ( QwtPlotItemIterator it = list.begin(); it != list.end(); ++it ) - { - QwtPlotItem *item = *it; - if ( item->rtti() == rtti ) - items += item; - } - - return items; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_dict.h" + +class QwtPlotDict::PrivateData +{ +public: + + class ItemList: public QList + { + public: + void insertItem( QwtPlotItem *item ) + { + if ( item == NULL ) + return; + + QList::iterator it = + qUpperBound( begin(), end(), item, LessZThan() ); + insert( it, item ); + } + + void removeItem( QwtPlotItem *item ) + { + if ( item == NULL ) + return; + + QList::iterator it = + qLowerBound( begin(), end(), item, LessZThan() ); + + for ( ; it != end(); ++it ) + { + if ( item == *it ) + { + erase( it ); + break; + } + } + } + private: + class LessZThan + { + public: + inline bool operator()( const QwtPlotItem *item1, + const QwtPlotItem *item2 ) const + { + return item1->z() < item2->z(); + } + }; + }; + + ItemList itemList; + bool autoDelete; +}; + +/*! + Constructor + + Auto deletion is enabled. + \sa setAutoDelete(), attachItem() +*/ +QwtPlotDict::QwtPlotDict() +{ + d_data = new QwtPlotDict::PrivateData; + d_data->autoDelete = true; +} + +/*! + Destructor + + If autoDelete is on, all attached items will be deleted + \sa setAutoDelete(), autoDelete(), attachItem() +*/ +QwtPlotDict::~QwtPlotDict() +{ + detachItems( QwtPlotItem::Rtti_PlotItem, d_data->autoDelete ); + delete d_data; +} + +/*! + En/Disable Auto deletion + + If Auto deletion is on all attached plot items will be deleted + in the destructor of QwtPlotDict. The default value is on. + + \sa autoDelete(), attachItem() +*/ +void QwtPlotDict::setAutoDelete( bool autoDelete ) +{ + d_data->autoDelete = autoDelete; +} + +/*! + \return true if auto deletion is enabled + \sa setAutoDelete(), attachItem() +*/ +bool QwtPlotDict::autoDelete() const +{ + return d_data->autoDelete; +} + +/*! + Attach/Detach a plot item + + Attached items will be deleted in the destructor, + if auto deletion is enabled (default). Manually detached + items are not deleted. + + \param item Plot item to attach/detach + \ on If true attach, else detach the item + + \sa setAutoDelete(), ~QwtPlotDict() +*/ +void QwtPlotDict::attachItem( QwtPlotItem *item, bool on ) +{ + if ( on ) + d_data->itemList.insertItem( item ); + else + d_data->itemList.removeItem( item ); +} + +/*! + Detach items from the dictionary + + \param rtti In case of QwtPlotItem::Rtti_PlotItem detach all items + otherwise only those items of the type rtti. + \param autoDelete If true, delete all detached items +*/ +void QwtPlotDict::detachItems( int rtti, bool autoDelete ) +{ + PrivateData::ItemList list = d_data->itemList; + QwtPlotItemIterator it = list.begin(); + while ( it != list.end() ) + { + QwtPlotItem *item = *it; + + ++it; // increment before removing item from the list + + if ( rtti == QwtPlotItem::Rtti_PlotItem || item->rtti() == rtti ) + { + item->attach( NULL ); + if ( autoDelete ) + delete item; + } + } +} + +/*! + \brief A QwtPlotItemList of all attached plot items. + + Use caution when iterating these lists, as removing/detaching an item will + invalidate the iterator. Instead you can place pointers to objects to be + removed in a removal list, and traverse that list later. + + \return List of all attached plot items. +*/ +const QwtPlotItemList &QwtPlotDict::itemList() const +{ + return d_data->itemList; +} + +/*! + \return List of all attached plot items of a specific type. + \sa QwtPlotItem::rtti() +*/ +QwtPlotItemList QwtPlotDict::itemList( int rtti ) const +{ + if ( rtti == QwtPlotItem::Rtti_PlotItem ) + return d_data->itemList; + + QwtPlotItemList items; + + PrivateData::ItemList list = d_data->itemList; + for ( QwtPlotItemIterator it = list.begin(); it != list.end(); ++it ) + { + QwtPlotItem *item = *it; + if ( item->rtti() == rtti ) + items += item; + } + + return items; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_dict.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_dict.h index 2a8ad69a1..f68c80b10 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_dict.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_dict.h @@ -1,56 +1,56 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -/*! \file !*/ -#ifndef QWT_PLOT_DICT -#define QWT_PLOT_DICT - -#include "qwt_global.h" -#include "qwt_plot_item.h" -#include - -/// \var typedef QList< QwtPlotItem *> QwtPlotItemList -/// \brief See QT 4.x assistant documentation for QList -typedef QList QwtPlotItemList; -typedef QList::ConstIterator QwtPlotItemIterator; - -/*! - \brief A dictionary for plot items - - QwtPlotDict organizes plot items in increasing z-order. - If autoDelete() is enabled, all attached items will be deleted - in the destructor of the dictionary. - - \sa QwtPlotItem::attach(), QwtPlotItem::detach(), QwtPlotItem::z() -*/ -class QWT_EXPORT QwtPlotDict -{ -public: - explicit QwtPlotDict(); - virtual ~QwtPlotDict(); - - void setAutoDelete( bool ); - bool autoDelete() const; - - const QwtPlotItemList& itemList() const; - QwtPlotItemList itemList( int rtti ) const; - - void detachItems( int rtti = QwtPlotItem::Rtti_PlotItem, - bool autoDelete = true ); - -private: - friend class QwtPlotItem; - - void attachItem( QwtPlotItem *, bool ); - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +/*! \file !*/ +#ifndef QWT_PLOT_DICT +#define QWT_PLOT_DICT + +#include "qwt_global.h" +#include "qwt_plot_item.h" +#include + +/// \var typedef QList< QwtPlotItem *> QwtPlotItemList +/// \brief See QT 4.x assistant documentation for QList +typedef QList QwtPlotItemList; +typedef QList::ConstIterator QwtPlotItemIterator; + +/*! + \brief A dictionary for plot items + + QwtPlotDict organizes plot items in increasing z-order. + If autoDelete() is enabled, all attached items will be deleted + in the destructor of the dictionary. + + \sa QwtPlotItem::attach(), QwtPlotItem::detach(), QwtPlotItem::z() +*/ +class QWT_EXPORT QwtPlotDict +{ +public: + explicit QwtPlotDict(); + virtual ~QwtPlotDict(); + + void setAutoDelete( bool ); + bool autoDelete() const; + + const QwtPlotItemList& itemList() const; + QwtPlotItemList itemList( int rtti ) const; + + void detachItems( int rtti = QwtPlotItem::Rtti_PlotItem, + bool autoDelete = true ); + +private: + friend class QwtPlotItem; + + void attachItem( QwtPlotItem *, bool ); + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_directpainter.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_directpainter.cpp index 3cc69408c..f6b1d588f 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_directpainter.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_directpainter.cpp @@ -1,313 +1,313 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot_directpainter.h" -#include "qwt_scale_map.h" -#include "qwt_plot.h" -#include "qwt_plot_canvas.h" -#include "qwt_plot_seriesitem.h" -#include -#include -#include -#include - -static inline void renderItem( - QPainter *painter, const QRect &canvasRect, - QwtPlotAbstractSeriesItem *seriesItem, int from, int to ) -{ - // A minor performance improvement is possible - // with caching the maps. TODO ... - - QwtPlot *plot = seriesItem->plot(); - const QwtScaleMap xMap = plot->canvasMap( seriesItem->xAxis() ); - const QwtScaleMap yMap = plot->canvasMap( seriesItem->yAxis() ); - - painter->setRenderHint( QPainter::Antialiasing, - seriesItem->testRenderHint( QwtPlotItem::RenderAntialiased ) ); - seriesItem->drawSeries( painter, xMap, yMap, canvasRect, from, to ); -} - -class QwtPlotDirectPainter::PrivateData -{ -public: - PrivateData(): - attributes( 0 ), - hasClipping(false), - seriesItem( NULL ) - { - } - - QwtPlotDirectPainter::Attributes attributes; - - bool hasClipping; - QRegion clipRegion; - - QPainter painter; - - QwtPlotAbstractSeriesItem *seriesItem; - int from; - int to; -}; - -//! Constructor -QwtPlotDirectPainter::QwtPlotDirectPainter( QObject *parent ): - QObject( parent ) -{ - d_data = new PrivateData; -} - -//! Destructor -QwtPlotDirectPainter::~QwtPlotDirectPainter() -{ - delete d_data; -} - -/*! - Change an attribute - - \param attribute Attribute to change - \param on On/Off - - \sa Attribute, testAttribute() -*/ -void QwtPlotDirectPainter::setAttribute( Attribute attribute, bool on ) -{ - if ( bool( d_data->attributes & attribute ) != on ) - { - if ( on ) - d_data->attributes |= attribute; - else - d_data->attributes &= ~attribute; - - if ( ( attribute == AtomicPainter ) && on ) - reset(); - } -} - -/*! - Check if a attribute is set. - - \param attribute Attribute to be tested - \sa Attribute, setAttribute() -*/ -bool QwtPlotDirectPainter::testAttribute( Attribute attribute ) const -{ - return d_data->attributes & attribute; -} - -/*! - En/Disables clipping - - \param enable Enables clipping is true, disable it otherwise - \sa hasClipping(), clipRegion(), setClipRegion() -*/ -void QwtPlotDirectPainter::setClipping( bool enable ) -{ - d_data->hasClipping = enable; -} - -/*! - \return true, when clipping is enabled - \sa setClipping(), clipRegion(), setClipRegion() -*/ -bool QwtPlotDirectPainter::hasClipping() const -{ - return d_data->hasClipping; -} - -/*! - \brief Assign a clip region and enable clipping - - Depending on the environment setting a proper clip region might improve - the performance heavily. F.e. on Qt embedded only the clipped part of - the backing store will be copied to a ( maybe unaccelerated ) frame buffer - device. - - \param region Clip region - \sa clipRegion(), hasClipping(), setClipping() -*/ -void QwtPlotDirectPainter::setClipRegion( const QRegion ®ion ) -{ - d_data->clipRegion = region; - d_data->hasClipping = true; -} - -/*! - \return Currently set clip region. - \sa setClipRegion(), setClipping(), hasClipping() -*/ -QRegion QwtPlotDirectPainter::clipRegion() const -{ - return d_data->clipRegion; -} - -/*! - \brief Draw a set of points of a seriesItem. - - When observing an measurement while it is running, new points have to be - added to an existing seriesItem. drawSeries can be used to display them avoiding - a complete redraw of the canvas. - - Setting plot()->canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, true); - will result in faster painting, if the paint engine of the canvas widget - supports this feature. - - \param seriesItem Item to be painted - \param from Index of the first point to be painted - \param to Index of the last point to be painted. If to < 0 the - series will be painted to its last point. -*/ -void QwtPlotDirectPainter::drawSeries( - QwtPlotAbstractSeriesItem *seriesItem, int from, int to ) -{ - if ( seriesItem == NULL || seriesItem->plot() == NULL ) - return; - - QwtPlotCanvas *canvas = seriesItem->plot()->canvas(); - const QRect canvasRect = canvas->contentsRect(); - - const bool hasBackingStore = - canvas->testPaintAttribute( QwtPlotCanvas::BackingStore ) - && canvas->backingStore() && !canvas->backingStore()->isNull(); - - if ( hasBackingStore ) - { - QPainter painter( const_cast( canvas->backingStore() ) ); - painter.translate( -canvasRect.x(), -canvasRect.y() ); - - if ( d_data->hasClipping ) - painter.setClipRegion( d_data->clipRegion ); - - renderItem( &painter, canvasRect, seriesItem, from, to ); - - if ( testAttribute( QwtPlotDirectPainter::FullRepaint ) ) - { - canvas->repaint(); - return; - } - } - - bool immediatePaint = true; - if ( !canvas->testAttribute( Qt::WA_WState_InPaintEvent ) && - !canvas->testAttribute( Qt::WA_PaintOutsidePaintEvent ) ) - { - immediatePaint = false; - } - - if ( immediatePaint ) - { - QwtPlotCanvas *canvas = seriesItem->plot()->canvas(); - if ( !d_data->painter.isActive() ) - { - reset(); - - d_data->painter.begin( canvas ); - canvas->installEventFilter( this ); - } - - if ( d_data->hasClipping ) - { - d_data->painter.setClipRegion( - QRegion( canvasRect ) & d_data->clipRegion ); - } - else - { - if ( !d_data->painter.hasClipping() ) - d_data->painter.setClipRect( canvasRect ); - } - - renderItem( &d_data->painter, canvasRect, seriesItem, from, to ); - - if ( d_data->attributes & QwtPlotDirectPainter::AtomicPainter ) - { - reset(); - } - else - { - if ( d_data->hasClipping ) - d_data->painter.setClipping( false ); - } - } - else - { - reset(); - - d_data->seriesItem = seriesItem; - d_data->from = from; - d_data->to = to; - - QRegion clipRegion = canvasRect; - if ( d_data->hasClipping ) - clipRegion &= d_data->clipRegion; - - canvas->installEventFilter( this ); - canvas->repaint(clipRegion); - canvas->removeEventFilter( this ); - - d_data->seriesItem = NULL; - } -} - -//! Close the internal QPainter -void QwtPlotDirectPainter::reset() -{ - if ( d_data->painter.isActive() ) - { - QWidget *w = ( QWidget * )d_data->painter.device(); - if ( w ) - w->removeEventFilter( this ); - - d_data->painter.end(); - } -} - -//! Event filter -bool QwtPlotDirectPainter::eventFilter( QObject *, QEvent *event ) -{ - if ( event->type() == QEvent::Paint ) - { - reset(); - - if ( d_data->seriesItem ) - { - const QPaintEvent *pe = static_cast< QPaintEvent *>( event ); - - QwtPlotCanvas *canvas = d_data->seriesItem->plot()->canvas(); - - QPainter painter( canvas ); - painter.setClipRegion( pe->region() ); - - bool copyCache = testAttribute( CopyBackingStore ) - && canvas->testPaintAttribute( QwtPlotCanvas::BackingStore ); - - if ( copyCache ) - { - // is something valid in the cache ? - copyCache = ( canvas->backingStore() != NULL ) - && !canvas->backingStore()->isNull(); - } - - if ( copyCache ) - { - painter.drawPixmap( - canvas->contentsRect().topLeft(), - *canvas->backingStore() ); - } - else - { - renderItem( &painter, canvas->contentsRect(), - d_data->seriesItem, d_data->from, d_data->to ); - } - - return true; // don't call QwtPlotCanvas::paintEvent() - } - } - - return false; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_directpainter.h" +#include "qwt_scale_map.h" +#include "qwt_plot.h" +#include "qwt_plot_canvas.h" +#include "qwt_plot_seriesitem.h" +#include +#include +#include +#include + +static inline void renderItem( + QPainter *painter, const QRect &canvasRect, + QwtPlotAbstractSeriesItem *seriesItem, int from, int to ) +{ + // A minor performance improvement is possible + // with caching the maps. TODO ... + + QwtPlot *plot = seriesItem->plot(); + const QwtScaleMap xMap = plot->canvasMap( seriesItem->xAxis() ); + const QwtScaleMap yMap = plot->canvasMap( seriesItem->yAxis() ); + + painter->setRenderHint( QPainter::Antialiasing, + seriesItem->testRenderHint( QwtPlotItem::RenderAntialiased ) ); + seriesItem->drawSeries( painter, xMap, yMap, canvasRect, from, to ); +} + +class QwtPlotDirectPainter::PrivateData +{ +public: + PrivateData(): + attributes( 0 ), + hasClipping(false), + seriesItem( NULL ) + { + } + + QwtPlotDirectPainter::Attributes attributes; + + bool hasClipping; + QRegion clipRegion; + + QPainter painter; + + QwtPlotAbstractSeriesItem *seriesItem; + int from; + int to; +}; + +//! Constructor +QwtPlotDirectPainter::QwtPlotDirectPainter( QObject *parent ): + QObject( parent ) +{ + d_data = new PrivateData; +} + +//! Destructor +QwtPlotDirectPainter::~QwtPlotDirectPainter() +{ + delete d_data; +} + +/*! + Change an attribute + + \param attribute Attribute to change + \param on On/Off + + \sa Attribute, testAttribute() +*/ +void QwtPlotDirectPainter::setAttribute( Attribute attribute, bool on ) +{ + if ( bool( d_data->attributes & attribute ) != on ) + { + if ( on ) + d_data->attributes |= attribute; + else + d_data->attributes &= ~attribute; + + if ( ( attribute == AtomicPainter ) && on ) + reset(); + } +} + +/*! + Check if a attribute is set. + + \param attribute Attribute to be tested + \sa Attribute, setAttribute() +*/ +bool QwtPlotDirectPainter::testAttribute( Attribute attribute ) const +{ + return d_data->attributes & attribute; +} + +/*! + En/Disables clipping + + \param enable Enables clipping is true, disable it otherwise + \sa hasClipping(), clipRegion(), setClipRegion() +*/ +void QwtPlotDirectPainter::setClipping( bool enable ) +{ + d_data->hasClipping = enable; +} + +/*! + \return true, when clipping is enabled + \sa setClipping(), clipRegion(), setClipRegion() +*/ +bool QwtPlotDirectPainter::hasClipping() const +{ + return d_data->hasClipping; +} + +/*! + \brief Assign a clip region and enable clipping + + Depending on the environment setting a proper clip region might improve + the performance heavily. F.e. on Qt embedded only the clipped part of + the backing store will be copied to a ( maybe unaccelerated ) frame buffer + device. + + \param region Clip region + \sa clipRegion(), hasClipping(), setClipping() +*/ +void QwtPlotDirectPainter::setClipRegion( const QRegion ®ion ) +{ + d_data->clipRegion = region; + d_data->hasClipping = true; +} + +/*! + \return Currently set clip region. + \sa setClipRegion(), setClipping(), hasClipping() +*/ +QRegion QwtPlotDirectPainter::clipRegion() const +{ + return d_data->clipRegion; +} + +/*! + \brief Draw a set of points of a seriesItem. + + When observing an measurement while it is running, new points have to be + added to an existing seriesItem. drawSeries can be used to display them avoiding + a complete redraw of the canvas. + + Setting plot()->canvas()->setAttribute(Qt::WA_PaintOutsidePaintEvent, true); + will result in faster painting, if the paint engine of the canvas widget + supports this feature. + + \param seriesItem Item to be painted + \param from Index of the first point to be painted + \param to Index of the last point to be painted. If to < 0 the + series will be painted to its last point. +*/ +void QwtPlotDirectPainter::drawSeries( + QwtPlotAbstractSeriesItem *seriesItem, int from, int to ) +{ + if ( seriesItem == NULL || seriesItem->plot() == NULL ) + return; + + QwtPlotCanvas *canvas = seriesItem->plot()->canvas(); + const QRect canvasRect = canvas->contentsRect(); + + const bool hasBackingStore = + canvas->testPaintAttribute( QwtPlotCanvas::BackingStore ) + && canvas->backingStore() && !canvas->backingStore()->isNull(); + + if ( hasBackingStore ) + { + QPainter painter( const_cast( canvas->backingStore() ) ); + painter.translate( -canvasRect.x(), -canvasRect.y() ); + + if ( d_data->hasClipping ) + painter.setClipRegion( d_data->clipRegion ); + + renderItem( &painter, canvasRect, seriesItem, from, to ); + + if ( testAttribute( QwtPlotDirectPainter::FullRepaint ) ) + { + canvas->repaint(); + return; + } + } + + bool immediatePaint = true; + if ( !canvas->testAttribute( Qt::WA_WState_InPaintEvent ) && + !canvas->testAttribute( Qt::WA_PaintOutsidePaintEvent ) ) + { + immediatePaint = false; + } + + if ( immediatePaint ) + { + QwtPlotCanvas *canvas = seriesItem->plot()->canvas(); + if ( !d_data->painter.isActive() ) + { + reset(); + + d_data->painter.begin( canvas ); + canvas->installEventFilter( this ); + } + + if ( d_data->hasClipping ) + { + d_data->painter.setClipRegion( + QRegion( canvasRect ) & d_data->clipRegion ); + } + else + { + if ( !d_data->painter.hasClipping() ) + d_data->painter.setClipRect( canvasRect ); + } + + renderItem( &d_data->painter, canvasRect, seriesItem, from, to ); + + if ( d_data->attributes & QwtPlotDirectPainter::AtomicPainter ) + { + reset(); + } + else + { + if ( d_data->hasClipping ) + d_data->painter.setClipping( false ); + } + } + else + { + reset(); + + d_data->seriesItem = seriesItem; + d_data->from = from; + d_data->to = to; + + QRegion clipRegion = canvasRect; + if ( d_data->hasClipping ) + clipRegion &= d_data->clipRegion; + + canvas->installEventFilter( this ); + canvas->repaint(clipRegion); + canvas->removeEventFilter( this ); + + d_data->seriesItem = NULL; + } +} + +//! Close the internal QPainter +void QwtPlotDirectPainter::reset() +{ + if ( d_data->painter.isActive() ) + { + QWidget *w = ( QWidget * )d_data->painter.device(); + if ( w ) + w->removeEventFilter( this ); + + d_data->painter.end(); + } +} + +//! Event filter +bool QwtPlotDirectPainter::eventFilter( QObject *, QEvent *event ) +{ + if ( event->type() == QEvent::Paint ) + { + reset(); + + if ( d_data->seriesItem ) + { + const QPaintEvent *pe = static_cast< QPaintEvent *>( event ); + + QwtPlotCanvas *canvas = d_data->seriesItem->plot()->canvas(); + + QPainter painter( canvas ); + painter.setClipRegion( pe->region() ); + + bool copyCache = testAttribute( CopyBackingStore ) + && canvas->testPaintAttribute( QwtPlotCanvas::BackingStore ); + + if ( copyCache ) + { + // is something valid in the cache ? + copyCache = ( canvas->backingStore() != NULL ) + && !canvas->backingStore()->isNull(); + } + + if ( copyCache ) + { + painter.drawPixmap( + canvas->contentsRect().topLeft(), + *canvas->backingStore() ); + } + else + { + renderItem( &painter, canvas->contentsRect(), + d_data->seriesItem, d_data->from, d_data->to ); + } + + return true; // don't call QwtPlotCanvas::paintEvent() + } + } + + return false; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_directpainter.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_directpainter.h index 318c115e0..ca7dbf941 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_directpainter.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_directpainter.h @@ -1,100 +1,100 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PLOT_DIRECT_PAINTER_H -#define QWT_PLOT_DIRECT_PAINTER_H - -#include "qwt_global.h" -#include - -class QRegion; -class QwtPlotAbstractSeriesItem; - -/*! - \brief Painter object trying to paint incrementally - - Often applications want to display samples while they are - collected. When there are too many samples complete replots - will be expensive to be processed in a collection cycle. - - QwtPlotDirectPainter offers an API to paint - subsets ( f.e all additions points ) without erasing/repainting - the plot canvas. - - On certain environments it might be important to calculate a proper - clip region before painting. F.e. for Qt Embedded only the clipped part - of the backing store will be copied to a ( maybe unaccelerated ) - frame buffer. - - \warning Incremental painting will only help when no replot is triggered - by another operation ( like changing scales ) and nothing needs - to be erased. -*/ -class QWT_EXPORT QwtPlotDirectPainter: public QObject -{ -public: - /*! - \brief Paint attributes - \sa setAttribute(), testAttribute(), drawSeries() - */ - enum Attribute - { - /*! - Initializing a QPainter is an expensive operation. - When AtomicPainter is set each call of drawSeries() opens/closes - a temporary QPainter. Otherwise QwtPlotDirectPainter tries to - use the same QPainter as long as possible. - */ - AtomicPainter = 0x01, - - /*! - When FullRepaint is set the plot canvas is explicitely repainted - after the samples have been rendered. - */ - FullRepaint = 0x02, - - /*! - When QwtPlotCanvas::BackingStore is enabled the painter - has to paint to the backing store and the widget. In certain - situations/environments it might be faster to paint to - the backing store only and then copy the backingstore to the canvas. - This flag can also be useful for settings, where Qt fills the - the clip region with the widget background. - */ - CopyBackingStore = 0x04 - }; - - //! Paint attributes - typedef QFlags Attributes; - - QwtPlotDirectPainter( QObject *parent = NULL ); - virtual ~QwtPlotDirectPainter(); - - void setAttribute( Attribute, bool on ); - bool testAttribute( Attribute ) const; - - void setClipping( bool ); - bool hasClipping() const; - - void setClipRegion( const QRegion & ); - QRegion clipRegion() const; - - void drawSeries( QwtPlotAbstractSeriesItem *, int from, int to ); - void reset(); - - virtual bool eventFilter( QObject *, QEvent * ); - -private: - class PrivateData; - PrivateData *d_data; -}; - -Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotDirectPainter::Attributes ) - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_DIRECT_PAINTER_H +#define QWT_PLOT_DIRECT_PAINTER_H + +#include "qwt_global.h" +#include + +class QRegion; +class QwtPlotAbstractSeriesItem; + +/*! + \brief Painter object trying to paint incrementally + + Often applications want to display samples while they are + collected. When there are too many samples complete replots + will be expensive to be processed in a collection cycle. + + QwtPlotDirectPainter offers an API to paint + subsets ( f.e all additions points ) without erasing/repainting + the plot canvas. + + On certain environments it might be important to calculate a proper + clip region before painting. F.e. for Qt Embedded only the clipped part + of the backing store will be copied to a ( maybe unaccelerated ) + frame buffer. + + \warning Incremental painting will only help when no replot is triggered + by another operation ( like changing scales ) and nothing needs + to be erased. +*/ +class QWT_EXPORT QwtPlotDirectPainter: public QObject +{ +public: + /*! + \brief Paint attributes + \sa setAttribute(), testAttribute(), drawSeries() + */ + enum Attribute + { + /*! + Initializing a QPainter is an expensive operation. + When AtomicPainter is set each call of drawSeries() opens/closes + a temporary QPainter. Otherwise QwtPlotDirectPainter tries to + use the same QPainter as long as possible. + */ + AtomicPainter = 0x01, + + /*! + When FullRepaint is set the plot canvas is explicitely repainted + after the samples have been rendered. + */ + FullRepaint = 0x02, + + /*! + When QwtPlotCanvas::BackingStore is enabled the painter + has to paint to the backing store and the widget. In certain + situations/environments it might be faster to paint to + the backing store only and then copy the backingstore to the canvas. + This flag can also be useful for settings, where Qt fills the + the clip region with the widget background. + */ + CopyBackingStore = 0x04 + }; + + //! Paint attributes + typedef QFlags Attributes; + + QwtPlotDirectPainter( QObject *parent = NULL ); + virtual ~QwtPlotDirectPainter(); + + void setAttribute( Attribute, bool on ); + bool testAttribute( Attribute ) const; + + void setClipping( bool ); + bool hasClipping() const; + + void setClipRegion( const QRegion & ); + QRegion clipRegion() const; + + void drawSeries( QwtPlotAbstractSeriesItem *, int from, int to ); + void reset(); + + virtual bool eventFilter( QObject *, QEvent * ); + +private: + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotDirectPainter::Attributes ) + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_grid.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_grid.cpp index 283ed01d5..8e25aebaa 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_grid.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_grid.cpp @@ -1,367 +1,367 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot_grid.h" -#include "qwt_painter.h" -#include "qwt_text.h" -#include "qwt_scale_map.h" -#include "qwt_scale_div.h" -#include "qwt_math.h" -#include -#include - -class QwtPlotGrid::PrivateData -{ -public: - PrivateData(): - xEnabled( true ), - yEnabled( true ), - xMinEnabled( false ), - yMinEnabled( false ) - { - } - - bool xEnabled; - bool yEnabled; - bool xMinEnabled; - bool yMinEnabled; - - QwtScaleDiv xScaleDiv; - QwtScaleDiv yScaleDiv; - - QPen majPen; - QPen minPen; -}; - -//! Enables major grid, disables minor grid -QwtPlotGrid::QwtPlotGrid(): - QwtPlotItem( QwtText( "Grid" ) ) -{ - d_data = new PrivateData; - setZ( 10.0 ); -} - -//! Destructor -QwtPlotGrid::~QwtPlotGrid() -{ - delete d_data; -} - -//! \return QwtPlotItem::Rtti_PlotGrid -int QwtPlotGrid::rtti() const -{ - return QwtPlotItem::Rtti_PlotGrid; -} - -/*! - \brief Enable or disable vertical gridlines - \param tf Enable (true) or disable - - \sa Minor gridlines can be enabled or disabled with - enableXMin() -*/ -void QwtPlotGrid::enableX( bool tf ) -{ - if ( d_data->xEnabled != tf ) - { - d_data->xEnabled = tf; - itemChanged(); - } -} - -/*! - \brief Enable or disable horizontal gridlines - \param tf Enable (true) or disable - \sa Minor gridlines can be enabled or disabled with enableYMin() -*/ -void QwtPlotGrid::enableY( bool tf ) -{ - if ( d_data->yEnabled != tf ) - { - d_data->yEnabled = tf; - itemChanged(); - } -} - -/*! - \brief Enable or disable minor vertical gridlines. - \param tf Enable (true) or disable - \sa enableX() -*/ -void QwtPlotGrid::enableXMin( bool tf ) -{ - if ( d_data->xMinEnabled != tf ) - { - d_data->xMinEnabled = tf; - itemChanged(); - } -} - -/*! - \brief Enable or disable minor horizontal gridlines - \param tf Enable (true) or disable - \sa enableY() -*/ -void QwtPlotGrid::enableYMin( bool tf ) -{ - if ( d_data->yMinEnabled != tf ) - { - d_data->yMinEnabled = tf; - itemChanged(); - } -} - -/*! - Assign an x axis scale division - - \param scaleDiv Scale division -*/ -void QwtPlotGrid::setXDiv( const QwtScaleDiv &scaleDiv ) -{ - if ( d_data->xScaleDiv != scaleDiv ) - { - d_data->xScaleDiv = scaleDiv; - itemChanged(); - } -} - -/*! - Assign a y axis division - - \param scaleDiv Scale division -*/ -void QwtPlotGrid::setYDiv( const QwtScaleDiv &scaleDiv ) -{ - if ( d_data->yScaleDiv != scaleDiv ) - { - d_data->yScaleDiv = scaleDiv; - itemChanged(); - } -} - -/*! - Assign a pen for both major and minor gridlines - - \param pen Pen - \sa setMajPen(), setMinPen() -*/ -void QwtPlotGrid::setPen( const QPen &pen ) -{ - if ( d_data->majPen != pen || d_data->minPen != pen ) - { - d_data->majPen = pen; - d_data->minPen = pen; - itemChanged(); - } -} - -/*! - Assign a pen for the major gridlines - - \param pen Pen - \sa majPen(), setMinPen(), setPen() -*/ -void QwtPlotGrid::setMajPen( const QPen &pen ) -{ - if ( d_data->majPen != pen ) - { - d_data->majPen = pen; - itemChanged(); - } -} - -/*! - Assign a pen for the minor gridlines - - \param pen Pen - \sa minPen(), setMajPen(), setPen() -*/ -void QwtPlotGrid::setMinPen( const QPen &pen ) -{ - if ( d_data->minPen != pen ) - { - d_data->minPen = pen; - itemChanged(); - } -} - -/*! - \brief Draw the grid - - The grid is drawn into the bounding rectangle such that - gridlines begin and end at the rectangle's borders. The X and Y - maps are used to map the scale divisions into the drawing region - screen. - \param painter Painter - \param xMap X axis map - \param yMap Y axis - \param canvasRect Contents rect of the plot canvas -*/ -void QwtPlotGrid::draw( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect ) const -{ - // draw minor gridlines - QPen minPen = d_data->minPen; - minPen.setCapStyle( Qt::FlatCap ); - - painter->setPen( minPen ); - - if ( d_data->xEnabled && d_data->xMinEnabled ) - { - drawLines( painter, canvasRect, Qt::Vertical, xMap, - d_data->xScaleDiv.ticks( QwtScaleDiv::MinorTick ) ); - drawLines( painter, canvasRect, Qt::Vertical, xMap, - d_data->xScaleDiv.ticks( QwtScaleDiv::MediumTick ) ); - } - - if ( d_data->yEnabled && d_data->yMinEnabled ) - { - drawLines( painter, canvasRect, Qt::Horizontal, yMap, - d_data->yScaleDiv.ticks( QwtScaleDiv::MinorTick ) ); - drawLines( painter, canvasRect, Qt::Horizontal, yMap, - d_data->yScaleDiv.ticks( QwtScaleDiv::MediumTick ) ); - } - - // draw major gridlines - QPen majPen = d_data->majPen; - majPen.setCapStyle( Qt::FlatCap ); - - painter->setPen( majPen ); - - if ( d_data->xEnabled ) - { - drawLines( painter, canvasRect, Qt::Vertical, xMap, - d_data->xScaleDiv.ticks( QwtScaleDiv::MajorTick ) ); - } - - if ( d_data->yEnabled ) - { - drawLines( painter, canvasRect, Qt::Horizontal, yMap, - d_data->yScaleDiv.ticks( QwtScaleDiv::MajorTick ) ); - } -} - -void QwtPlotGrid::drawLines( QPainter *painter, const QRectF &canvasRect, - Qt::Orientation orientation, const QwtScaleMap &scaleMap, - const QList &values ) const -{ - const double x1 = canvasRect.left(); - const double x2 = canvasRect.right() - 1.0; - const double y1 = canvasRect.top(); - const double y2 = canvasRect.bottom() - 1.0; - - const bool doAlign = QwtPainter::roundingAlignment( painter ); - - for ( int i = 0; i < values.count(); i++ ) - { - double value = scaleMap.transform( values[i] ); - if ( doAlign ) - value = qRound( value ); - - if ( orientation == Qt::Horizontal ) - { - if ( qwtFuzzyGreaterOrEqual( value, y1 ) && - qwtFuzzyLessOrEqual( value, y2 ) ) - { - QwtPainter::drawLine( painter, x1, value, x2, value ); - } - } - else - { - if ( qwtFuzzyGreaterOrEqual( value, x1 ) && - qwtFuzzyLessOrEqual( value, x2 ) ) - { - QwtPainter::drawLine( painter, value, y1, value, y2 ); - } - } - } -} - -/*! - \return the pen for the major gridlines - \sa setMajPen(), setMinPen(), setPen() -*/ -const QPen &QwtPlotGrid::majPen() const -{ - return d_data->majPen; -} - -/*! - \return the pen for the minor gridlines - \sa setMinPen(), setMajPen(), setPen() -*/ -const QPen &QwtPlotGrid::minPen() const -{ - return d_data->minPen; -} - -/*! - \return true if vertical gridlines are enabled - \sa enableX() -*/ -bool QwtPlotGrid::xEnabled() const -{ - return d_data->xEnabled; -} - -/*! - \return true if minor vertical gridlines are enabled - \sa enableXMin() -*/ -bool QwtPlotGrid::xMinEnabled() const -{ - return d_data->xMinEnabled; -} - -/*! - \return true if horizontal gridlines are enabled - \sa enableY() -*/ -bool QwtPlotGrid::yEnabled() const -{ - return d_data->yEnabled; -} - -/*! - \return true if minor horizontal gridlines are enabled - \sa enableYMin() -*/ -bool QwtPlotGrid::yMinEnabled() const -{ - return d_data->yMinEnabled; -} - - -/*! \return the scale division of the x axis */ -const QwtScaleDiv &QwtPlotGrid::xScaleDiv() const -{ - return d_data->xScaleDiv; -} - -/*! \return the scale division of the y axis */ -const QwtScaleDiv &QwtPlotGrid::yScaleDiv() const -{ - return d_data->yScaleDiv; -} - -/*! - Update the grid to changes of the axes scale division - - \param xScaleDiv Scale division of the x-axis - \param yScaleDiv Scale division of the y-axis - - \sa QwtPlot::updateAxes() -*/ -void QwtPlotGrid::updateScaleDiv( const QwtScaleDiv& xScaleDiv, - const QwtScaleDiv& yScaleDiv ) -{ - setXDiv( xScaleDiv ); - setYDiv( yScaleDiv ); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_grid.h" +#include "qwt_painter.h" +#include "qwt_text.h" +#include "qwt_scale_map.h" +#include "qwt_scale_div.h" +#include "qwt_math.h" +#include +#include + +class QwtPlotGrid::PrivateData +{ +public: + PrivateData(): + xEnabled( true ), + yEnabled( true ), + xMinEnabled( false ), + yMinEnabled( false ) + { + } + + bool xEnabled; + bool yEnabled; + bool xMinEnabled; + bool yMinEnabled; + + QwtScaleDiv xScaleDiv; + QwtScaleDiv yScaleDiv; + + QPen majPen; + QPen minPen; +}; + +//! Enables major grid, disables minor grid +QwtPlotGrid::QwtPlotGrid(): + QwtPlotItem( QwtText( "Grid" ) ) +{ + d_data = new PrivateData; + setZ( 10.0 ); +} + +//! Destructor +QwtPlotGrid::~QwtPlotGrid() +{ + delete d_data; +} + +//! \return QwtPlotItem::Rtti_PlotGrid +int QwtPlotGrid::rtti() const +{ + return QwtPlotItem::Rtti_PlotGrid; +} + +/*! + \brief Enable or disable vertical gridlines + \param tf Enable (true) or disable + + \sa Minor gridlines can be enabled or disabled with + enableXMin() +*/ +void QwtPlotGrid::enableX( bool tf ) +{ + if ( d_data->xEnabled != tf ) + { + d_data->xEnabled = tf; + itemChanged(); + } +} + +/*! + \brief Enable or disable horizontal gridlines + \param tf Enable (true) or disable + \sa Minor gridlines can be enabled or disabled with enableYMin() +*/ +void QwtPlotGrid::enableY( bool tf ) +{ + if ( d_data->yEnabled != tf ) + { + d_data->yEnabled = tf; + itemChanged(); + } +} + +/*! + \brief Enable or disable minor vertical gridlines. + \param tf Enable (true) or disable + \sa enableX() +*/ +void QwtPlotGrid::enableXMin( bool tf ) +{ + if ( d_data->xMinEnabled != tf ) + { + d_data->xMinEnabled = tf; + itemChanged(); + } +} + +/*! + \brief Enable or disable minor horizontal gridlines + \param tf Enable (true) or disable + \sa enableY() +*/ +void QwtPlotGrid::enableYMin( bool tf ) +{ + if ( d_data->yMinEnabled != tf ) + { + d_data->yMinEnabled = tf; + itemChanged(); + } +} + +/*! + Assign an x axis scale division + + \param scaleDiv Scale division +*/ +void QwtPlotGrid::setXDiv( const QwtScaleDiv &scaleDiv ) +{ + if ( d_data->xScaleDiv != scaleDiv ) + { + d_data->xScaleDiv = scaleDiv; + itemChanged(); + } +} + +/*! + Assign a y axis division + + \param scaleDiv Scale division +*/ +void QwtPlotGrid::setYDiv( const QwtScaleDiv &scaleDiv ) +{ + if ( d_data->yScaleDiv != scaleDiv ) + { + d_data->yScaleDiv = scaleDiv; + itemChanged(); + } +} + +/*! + Assign a pen for both major and minor gridlines + + \param pen Pen + \sa setMajPen(), setMinPen() +*/ +void QwtPlotGrid::setPen( const QPen &pen ) +{ + if ( d_data->majPen != pen || d_data->minPen != pen ) + { + d_data->majPen = pen; + d_data->minPen = pen; + itemChanged(); + } +} + +/*! + Assign a pen for the major gridlines + + \param pen Pen + \sa majPen(), setMinPen(), setPen() +*/ +void QwtPlotGrid::setMajPen( const QPen &pen ) +{ + if ( d_data->majPen != pen ) + { + d_data->majPen = pen; + itemChanged(); + } +} + +/*! + Assign a pen for the minor gridlines + + \param pen Pen + \sa minPen(), setMajPen(), setPen() +*/ +void QwtPlotGrid::setMinPen( const QPen &pen ) +{ + if ( d_data->minPen != pen ) + { + d_data->minPen = pen; + itemChanged(); + } +} + +/*! + \brief Draw the grid + + The grid is drawn into the bounding rectangle such that + gridlines begin and end at the rectangle's borders. The X and Y + maps are used to map the scale divisions into the drawing region + screen. + \param painter Painter + \param xMap X axis map + \param yMap Y axis + \param canvasRect Contents rect of the plot canvas +*/ +void QwtPlotGrid::draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const +{ + // draw minor gridlines + QPen minPen = d_data->minPen; + minPen.setCapStyle( Qt::FlatCap ); + + painter->setPen( minPen ); + + if ( d_data->xEnabled && d_data->xMinEnabled ) + { + drawLines( painter, canvasRect, Qt::Vertical, xMap, + d_data->xScaleDiv.ticks( QwtScaleDiv::MinorTick ) ); + drawLines( painter, canvasRect, Qt::Vertical, xMap, + d_data->xScaleDiv.ticks( QwtScaleDiv::MediumTick ) ); + } + + if ( d_data->yEnabled && d_data->yMinEnabled ) + { + drawLines( painter, canvasRect, Qt::Horizontal, yMap, + d_data->yScaleDiv.ticks( QwtScaleDiv::MinorTick ) ); + drawLines( painter, canvasRect, Qt::Horizontal, yMap, + d_data->yScaleDiv.ticks( QwtScaleDiv::MediumTick ) ); + } + + // draw major gridlines + QPen majPen = d_data->majPen; + majPen.setCapStyle( Qt::FlatCap ); + + painter->setPen( majPen ); + + if ( d_data->xEnabled ) + { + drawLines( painter, canvasRect, Qt::Vertical, xMap, + d_data->xScaleDiv.ticks( QwtScaleDiv::MajorTick ) ); + } + + if ( d_data->yEnabled ) + { + drawLines( painter, canvasRect, Qt::Horizontal, yMap, + d_data->yScaleDiv.ticks( QwtScaleDiv::MajorTick ) ); + } +} + +void QwtPlotGrid::drawLines( QPainter *painter, const QRectF &canvasRect, + Qt::Orientation orientation, const QwtScaleMap &scaleMap, + const QList &values ) const +{ + const double x1 = canvasRect.left(); + const double x2 = canvasRect.right() - 1.0; + const double y1 = canvasRect.top(); + const double y2 = canvasRect.bottom() - 1.0; + + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + for ( int i = 0; i < values.count(); i++ ) + { + double value = scaleMap.transform( values[i] ); + if ( doAlign ) + value = qRound( value ); + + if ( orientation == Qt::Horizontal ) + { + if ( qwtFuzzyGreaterOrEqual( value, y1 ) && + qwtFuzzyLessOrEqual( value, y2 ) ) + { + QwtPainter::drawLine( painter, x1, value, x2, value ); + } + } + else + { + if ( qwtFuzzyGreaterOrEqual( value, x1 ) && + qwtFuzzyLessOrEqual( value, x2 ) ) + { + QwtPainter::drawLine( painter, value, y1, value, y2 ); + } + } + } +} + +/*! + \return the pen for the major gridlines + \sa setMajPen(), setMinPen(), setPen() +*/ +const QPen &QwtPlotGrid::majPen() const +{ + return d_data->majPen; +} + +/*! + \return the pen for the minor gridlines + \sa setMinPen(), setMajPen(), setPen() +*/ +const QPen &QwtPlotGrid::minPen() const +{ + return d_data->minPen; +} + +/*! + \return true if vertical gridlines are enabled + \sa enableX() +*/ +bool QwtPlotGrid::xEnabled() const +{ + return d_data->xEnabled; +} + +/*! + \return true if minor vertical gridlines are enabled + \sa enableXMin() +*/ +bool QwtPlotGrid::xMinEnabled() const +{ + return d_data->xMinEnabled; +} + +/*! + \return true if horizontal gridlines are enabled + \sa enableY() +*/ +bool QwtPlotGrid::yEnabled() const +{ + return d_data->yEnabled; +} + +/*! + \return true if minor horizontal gridlines are enabled + \sa enableYMin() +*/ +bool QwtPlotGrid::yMinEnabled() const +{ + return d_data->yMinEnabled; +} + + +/*! \return the scale division of the x axis */ +const QwtScaleDiv &QwtPlotGrid::xScaleDiv() const +{ + return d_data->xScaleDiv; +} + +/*! \return the scale division of the y axis */ +const QwtScaleDiv &QwtPlotGrid::yScaleDiv() const +{ + return d_data->yScaleDiv; +} + +/*! + Update the grid to changes of the axes scale division + + \param xScaleDiv Scale division of the x-axis + \param yScaleDiv Scale division of the y-axis + + \sa QwtPlot::updateAxes() +*/ +void QwtPlotGrid::updateScaleDiv( const QwtScaleDiv& xScaleDiv, + const QwtScaleDiv& yScaleDiv ) +{ + setXDiv( xScaleDiv ); + setYDiv( yScaleDiv ); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_grid.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_grid.h index 969239809..361ec81ca 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_grid.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_grid.h @@ -1,84 +1,84 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PLOT_GRID_H -#define QWT_PLOT_GRID_H - -#include "qwt_global.h" -#include "qwt_plot_item.h" -#include "qwt_scale_div.h" - -class QPainter; -class QPen; -class QwtScaleMap; -class QwtScaleDiv; - -/*! - \brief A class which draws a coordinate grid - - The QwtPlotGrid class can be used to draw a coordinate grid. - A coordinate grid consists of major and minor vertical - and horizontal gridlines. The locations of the gridlines - are determined by the X and Y scale divisions which can - be assigned with setXDiv() and setYDiv(). - The draw() member draws the grid within a bounding - rectangle. -*/ - -class QWT_EXPORT QwtPlotGrid: public QwtPlotItem -{ -public: - explicit QwtPlotGrid(); - virtual ~QwtPlotGrid(); - - virtual int rtti() const; - - void enableX( bool tf ); - bool xEnabled() const; - - void enableY( bool tf ); - bool yEnabled() const; - - void enableXMin( bool tf ); - bool xMinEnabled() const; - - void enableYMin( bool tf ); - bool yMinEnabled() const; - - void setXDiv( const QwtScaleDiv &sx ); - const QwtScaleDiv &xScaleDiv() const; - - void setYDiv( const QwtScaleDiv &sy ); - const QwtScaleDiv &yScaleDiv() const; - - void setPen( const QPen &p ); - - void setMajPen( const QPen &p ); - const QPen& majPen() const; - - void setMinPen( const QPen &p ); - const QPen& minPen() const; - - virtual void draw( QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &rect ) const; - - virtual void updateScaleDiv( - const QwtScaleDiv &xMap, const QwtScaleDiv &yMap ); - -private: - void drawLines( QPainter *painter, const QRectF &, - Qt::Orientation orientation, const QwtScaleMap &, - const QList & ) const; - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_GRID_H +#define QWT_PLOT_GRID_H + +#include "qwt_global.h" +#include "qwt_plot_item.h" +#include "qwt_scale_div.h" + +class QPainter; +class QPen; +class QwtScaleMap; +class QwtScaleDiv; + +/*! + \brief A class which draws a coordinate grid + + The QwtPlotGrid class can be used to draw a coordinate grid. + A coordinate grid consists of major and minor vertical + and horizontal gridlines. The locations of the gridlines + are determined by the X and Y scale divisions which can + be assigned with setXDiv() and setYDiv(). + The draw() member draws the grid within a bounding + rectangle. +*/ + +class QWT_EXPORT QwtPlotGrid: public QwtPlotItem +{ +public: + explicit QwtPlotGrid(); + virtual ~QwtPlotGrid(); + + virtual int rtti() const; + + void enableX( bool tf ); + bool xEnabled() const; + + void enableY( bool tf ); + bool yEnabled() const; + + void enableXMin( bool tf ); + bool xMinEnabled() const; + + void enableYMin( bool tf ); + bool yMinEnabled() const; + + void setXDiv( const QwtScaleDiv &sx ); + const QwtScaleDiv &xScaleDiv() const; + + void setYDiv( const QwtScaleDiv &sy ); + const QwtScaleDiv &yScaleDiv() const; + + void setPen( const QPen &p ); + + void setMajPen( const QPen &p ); + const QPen& majPen() const; + + void setMinPen( const QPen &p ); + const QPen& minPen() const; + + virtual void draw( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &rect ) const; + + virtual void updateScaleDiv( + const QwtScaleDiv &xMap, const QwtScaleDiv &yMap ); + +private: + void drawLines( QPainter *painter, const QRectF &, + Qt::Orientation orientation, const QwtScaleMap &, + const QList & ) const; + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_histogram.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_histogram.cpp index 1bd972c8e..1fcf87109 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_histogram.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_histogram.cpp @@ -1,648 +1,648 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot_histogram.h" -#include "qwt_plot.h" -#include "qwt_legend.h" -#include "qwt_legend_item.h" -#include "qwt_painter.h" -#include "qwt_column_symbol.h" -#include "qwt_scale_map.h" -#include -#include - -static inline bool isCombinable( const QwtInterval &d1, - const QwtInterval &d2 ) -{ - if ( d1.isValid() && d2.isValid() ) - { - if ( d1.maxValue() == d2.minValue() ) - { - if ( !( d1.borderFlags() & QwtInterval::ExcludeMaximum - && d2.borderFlags() & QwtInterval::ExcludeMinimum ) ) - { - return true; - } - } - } - - return false; -} - -class QwtPlotHistogram::PrivateData -{ -public: - PrivateData(): - baseline( 0.0 ), - style( Columns ), - symbol( NULL ) - { - } - - ~PrivateData() - { - delete symbol; - } - - double baseline; - - QPen pen; - QBrush brush; - QwtPlotHistogram::HistogramStyle style; - const QwtColumnSymbol *symbol; -}; - -/*! - Constructor - \param title Title of the histogram. -*/ - -QwtPlotHistogram::QwtPlotHistogram( const QwtText &title ): - QwtPlotSeriesItem( title ) -{ - init(); -} - -/*! - Constructor - \param title Title of the histogram. -*/ -QwtPlotHistogram::QwtPlotHistogram( const QString &title ): - QwtPlotSeriesItem( title ) -{ - init(); -} - -//! Destructor -QwtPlotHistogram::~QwtPlotHistogram() -{ - delete d_data; -} - -//! Initialize data members -void QwtPlotHistogram::init() -{ - d_data = new PrivateData(); - d_series = new QwtIntervalSeriesData(); - - setItemAttribute( QwtPlotItem::AutoScale, true ); - setItemAttribute( QwtPlotItem::Legend, true ); - - setZ( 20.0 ); -} - -/*! - Set the histogram's drawing style - - \param style Histogram style - \sa HistogramStyle, style() -*/ -void QwtPlotHistogram::setStyle( HistogramStyle style ) -{ - if ( style != d_data->style ) - { - d_data->style = style; - itemChanged(); - } -} - -/*! - Return the current style - \sa HistogramStyle, setStyle() -*/ -QwtPlotHistogram::HistogramStyle QwtPlotHistogram::style() const -{ - return d_data->style; -} - -/*! - Assign a pen, that is used in a style() depending way. - - \param pen New pen - \sa pen(), brush() -*/ -void QwtPlotHistogram::setPen( const QPen &pen ) -{ - if ( pen != d_data->pen ) - { - d_data->pen = pen; - itemChanged(); - } -} - -/*! - \return Pen used in a style() depending way. - \sa setPen(), brush() -*/ -const QPen &QwtPlotHistogram::pen() const -{ - return d_data->pen; -} - -/*! - Assign a brush, that is used in a style() depending way. - - \param brush New brush - \sa pen(), brush() -*/ -void QwtPlotHistogram::setBrush( const QBrush &brush ) -{ - if ( brush != d_data->brush ) - { - d_data->brush = brush; - itemChanged(); - } -} - -/*! - \return Brush used in a style() depending way. - \sa setPen(), brush() -*/ -const QBrush &QwtPlotHistogram::brush() const -{ - return d_data->brush; -} - -/*! - \brief Assign a symbol - - In Column style an optional symbol can be assigned, that is responsible - for displaying the rectangle that is defined by the interval and - the distance between baseline() and value. When no symbol has been - defined the area is displayed as plain rectangle using pen() and brush(). - - \sa style(), symbol(), drawColumn(), pen(), brush() - - \note In applications, where different intervals need to be displayed - in a different way ( f.e different colors or even using differnt symbols) - it is recommended to overload drawColumn(). -*/ -void QwtPlotHistogram::setSymbol( const QwtColumnSymbol *symbol ) -{ - if ( symbol != d_data->symbol ) - { - delete d_data->symbol; - d_data->symbol = symbol; - itemChanged(); - } -} - -/*! - \return Current symbol or NULL, when no symbol has been assigned - \sa setSymbol() -*/ -const QwtColumnSymbol *QwtPlotHistogram::symbol() const -{ - return d_data->symbol; -} - -/*! - \brief Set the value of the baseline - - Each column representing an QwtIntervalSample is defined by its - interval and the interval between baseline and the value of the sample. - - The default value of the baseline is 0.0. - - \param value Value of the baseline - \sa baseline() -*/ -void QwtPlotHistogram::setBaseline( double value ) -{ - if ( d_data->baseline != value ) - { - d_data->baseline = value; - itemChanged(); - } -} - -/*! - \return Value of the baseline - \sa setBaseline() -*/ -double QwtPlotHistogram::baseline() const -{ - return d_data->baseline; -} - -/*! - \return Bounding rectangle of all samples. - For an empty series the rectangle is invalid. -*/ -QRectF QwtPlotHistogram::boundingRect() const -{ - QRectF rect = d_series->boundingRect(); - if ( !rect.isValid() ) - return rect; - - if ( orientation() == Qt::Horizontal ) - { - rect = QRectF( rect.y(), rect.x(), - rect.height(), rect.width() ); - - if ( rect.left() > d_data->baseline ) - rect.setLeft( d_data->baseline ); - else if ( rect.right() < d_data->baseline ) - rect.setRight( d_data->baseline ); - } - else - { - if ( rect.bottom() < d_data->baseline ) - rect.setBottom( d_data->baseline ); - else if ( rect.top() > d_data->baseline ) - rect.setTop( d_data->baseline ); - } - - return rect; -} - -//! \return QwtPlotItem::Rtti_PlotHistogram -int QwtPlotHistogram::rtti() const -{ - return QwtPlotItem::Rtti_PlotHistogram; -} - -/*! - Initialize data with an array of samples. - \param samples Vector of points -*/ -void QwtPlotHistogram::setSamples( - const QVector &samples ) -{ - delete d_series; - d_series = new QwtIntervalSeriesData( samples ); - itemChanged(); -} - -/*! - Draw a subset of the histogram samples - - \param painter Painter - \param xMap Maps x-values into pixel coordinates. - \param yMap Maps y-values into pixel coordinates. - \param canvasRect Contents rect of the canvas - \param from Index of the first sample to be painted - \param to Index of the last sample to be painted. If to < 0 the - series will be painted to its last sample. - - \sa drawOutline(), drawLines(), drawColumns -*/ -void QwtPlotHistogram::drawSeries( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &, int from, int to ) const -{ - if ( !painter || dataSize() <= 0 ) - return; - - if ( to < 0 ) - to = dataSize() - 1; - - switch ( d_data->style ) - { - case Outline: - drawOutline( painter, xMap, yMap, from, to ); - break; - case Lines: - drawLines( painter, xMap, yMap, from, to ); - break; - case Columns: - drawColumns( painter, xMap, yMap, from, to ); - break; - default: - break; - } -} - -/*! - Draw a histogram in Outline style() - - \param painter Painter - \param xMap Maps x-values into pixel coordinates. - \param yMap Maps y-values into pixel coordinates. - \param from Index of the first sample to be painted - \param to Index of the last sample to be painted. If to < 0 the - histogram will be painted to its last point. - - \sa setStyle(), style() - \warning The outline style requires, that the intervals are in increasing - order and not overlapping. -*/ -void QwtPlotHistogram::drawOutline( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to ) const -{ - const bool doAlign = QwtPainter::roundingAlignment( painter ); - - double v0 = ( orientation() == Qt::Horizontal ) ? - xMap.transform( baseline() ) : yMap.transform( baseline() ); - if ( doAlign ) - v0 = qRound( v0 ); - - QwtIntervalSample previous; - - QPolygonF polygon; - for ( int i = from; i <= to; i++ ) - { - const QwtIntervalSample sample = d_series->sample( i ); - - if ( !sample.interval.isValid() ) - { - flushPolygon( painter, v0, polygon ); - previous = sample; - continue; - } - - if ( previous.interval.isValid() ) - { - if ( !isCombinable( previous.interval, sample.interval ) ) - flushPolygon( painter, v0, polygon ); - } - - if ( orientation() == Qt::Vertical ) - { - double x1 = xMap.transform( sample.interval.minValue() ); - double x2 = xMap.transform( sample.interval.maxValue() ); - double y = yMap.transform( sample.value ); - if ( doAlign ) - { - x1 = qRound( x1 ); - x2 = qRound( x2 ); - y = qRound( y ); - } - - if ( polygon.size() == 0 ) - polygon += QPointF( x1, v0 ); - - polygon += QPointF( x1, y ); - polygon += QPointF( x2, y ); - } - else - { - double y1 = yMap.transform( sample.interval.minValue() ); - double y2 = yMap.transform( sample.interval.maxValue() ); - double x = xMap.transform( sample.value ); - if ( doAlign ) - { - y1 = qRound( y1 ); - y2 = qRound( y2 ); - x = qRound( x ); - } - - if ( polygon.size() == 0 ) - polygon += QPointF( v0, y1 ); - - polygon += QPointF( x, y1 ); - polygon += QPointF( x, y2 ); - } - previous = sample; - } - - flushPolygon( painter, v0, polygon ); -} - -/*! - Draw a histogram in Columns style() - - \param painter Painter - \param xMap Maps x-values into pixel coordinates. - \param yMap Maps y-values into pixel coordinates. - \param from Index of the first sample to be painted - \param to Index of the last sample to be painted. If to < 0 the - histogram will be painted to its last point. - - \sa setStyle(), style(), setSymbol(), drawColumn() -*/ -void QwtPlotHistogram::drawColumns( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to ) const -{ - painter->setPen( d_data->pen ); - painter->setBrush( d_data->brush ); - - for ( int i = from; i <= to; i++ ) - { - const QwtIntervalSample sample = d_series->sample( i ); - if ( !sample.interval.isNull() ) - { - const QwtColumnRect rect = columnRect( sample, xMap, yMap ); - drawColumn( painter, rect, sample ); - } - } -} - -/*! - Draw a histogram in Lines style() - - \param painter Painter - \param xMap Maps x-values into pixel coordinates. - \param yMap Maps y-values into pixel coordinates. - \param from Index of the first sample to be painted - \param to Index of the last sample to be painted. If to < 0 the - histogram will be painted to its last point. - - \sa setStyle(), style(), setPen() -*/ -void QwtPlotHistogram::drawLines( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to ) const -{ - const bool doAlign = QwtPainter::roundingAlignment( painter ); - - painter->setPen( d_data->pen ); - painter->setBrush( Qt::NoBrush ); - - for ( int i = from; i <= to; i++ ) - { - const QwtIntervalSample sample = d_series->sample( i ); - if ( !sample.interval.isNull() ) - { - const QwtColumnRect rect = columnRect( sample, xMap, yMap ); - - QRectF r = rect.toRect(); - if ( doAlign ) - { - r.setLeft( qRound( r.left() ) ); - r.setRight( qRound( r.right() ) ); - r.setTop( qRound( r.top() ) ); - r.setBottom( qRound( r.bottom() ) ); - } - - switch ( rect.direction ) - { - case QwtColumnRect::LeftToRight: - { - QwtPainter::drawLine( painter, - r.topRight(), r.bottomRight() ); - break; - } - case QwtColumnRect::RightToLeft: - { - QwtPainter::drawLine( painter, - r.topLeft(), r.bottomLeft() ); - break; - } - case QwtColumnRect::TopToBottom: - { - QwtPainter::drawLine( painter, - r.bottomRight(), r.bottomLeft() ); - break; - } - case QwtColumnRect::BottomToTop: - { - QwtPainter::drawLine( painter, - r.topRight(), r.topLeft() ); - break; - } - } - } - } -} - -//! Internal, used by the Outline style. -void QwtPlotHistogram::flushPolygon( QPainter *painter, - double baseLine, QPolygonF &polygon ) const -{ - if ( polygon.size() == 0 ) - return; - - if ( orientation() == Qt::Horizontal ) - polygon += QPointF( baseLine, polygon.last().y() ); - else - polygon += QPointF( polygon.last().x(), baseLine ); - - if ( d_data->brush.style() != Qt::NoBrush ) - { - painter->setPen( Qt::NoPen ); - painter->setBrush( d_data->brush ); - - if ( orientation() == Qt::Horizontal ) - { - polygon += QPointF( polygon.last().x(), baseLine ); - polygon += QPointF( polygon.first().x(), baseLine ); - } - else - { - polygon += QPointF( baseLine, polygon.last().y() ); - polygon += QPointF( baseLine, polygon.first().y() ); - } - QwtPainter::drawPolygon( painter, polygon ); - polygon.resize( polygon.size() - 2 ); - } - if ( d_data->pen.style() != Qt::NoPen ) - { - painter->setBrush( Qt::NoBrush ); - painter->setPen( d_data->pen ); - QwtPainter::drawPolyline( painter, polygon ); - } - polygon.clear(); -} - -/*! - Calculate the area that is covered by a sample - - \param sample Sample - \param xMap Maps x-values into pixel coordinates. - \param yMap Maps y-values into pixel coordinates. - - \return Rectangle, that is covered by a sample -*/ -QwtColumnRect QwtPlotHistogram::columnRect( const QwtIntervalSample &sample, - const QwtScaleMap &xMap, const QwtScaleMap &yMap ) const -{ - QwtColumnRect rect; - - const QwtInterval &iv = sample.interval; - if ( !iv.isValid() ) - return rect; - - if ( orientation() == Qt::Horizontal ) - { - const double x0 = xMap.transform( baseline() ); - const double x = xMap.transform( sample.value ); - const double y1 = yMap.transform( iv.minValue() ); - const double y2 = yMap.transform( iv.maxValue() ); - - rect.hInterval.setInterval( x0, x ); - rect.vInterval.setInterval( y1, y2, iv.borderFlags() ); - rect.direction = ( x < x0 ) ? QwtColumnRect::RightToLeft : - QwtColumnRect::LeftToRight; - } - else - { - const double x1 = xMap.transform( iv.minValue() ); - const double x2 = xMap.transform( iv.maxValue() ); - const double y0 = yMap.transform( baseline() ); - const double y = yMap.transform( sample.value ); - - rect.hInterval.setInterval( x1, x2, iv.borderFlags() ); - rect.vInterval.setInterval( y0, y ); - rect.direction = ( y < y0 ) ? QwtColumnRect::BottomToTop : - QwtColumnRect::TopToBottom; - } - - return rect; -} - -/*! - Draw a column for a sample in Columns style(). - - When a symbol() has been set the symbol is used otherwise the - column is displayed as plain rectangle using pen() and brush(). - - \param painter Painter - \param rect Rectangle where to paint the column in paint device coordinates - \param sample Sample to be displayed - - \note In applications, where different intervals need to be displayed - in a different way ( f.e different colors or even using differnt symbols) - it is recommended to overload drawColumn(). -*/ -void QwtPlotHistogram::drawColumn( QPainter *painter, - const QwtColumnRect &rect, const QwtIntervalSample &sample ) const -{ - Q_UNUSED( sample ); - - if ( d_data->symbol && - ( d_data->symbol->style() != QwtColumnSymbol::NoStyle ) ) - { - d_data->symbol->draw( painter, rect ); - } - else - { - QRectF r = rect.toRect(); - if ( QwtPainter::roundingAlignment( painter ) ) - { - r.setLeft( qRound( r.left() ) ); - r.setRight( qRound( r.right() ) ); - r.setTop( qRound( r.top() ) ); - r.setBottom( qRound( r.bottom() ) ); - } - - QwtPainter::drawRect( painter, r ); - } -} - -/*! - Draw a plain rectangle without pen using the brush() as identifier - - \param painter Painter - \param rect Bounding rectangle for the identifier -*/ -void QwtPlotHistogram::drawLegendIdentifier( - QPainter *painter, const QRectF &rect ) const -{ - const double dim = qMin( rect.width(), rect.height() ); - - QSizeF size( dim, dim ); - - QRectF r( 0, 0, size.width(), size.height() ); - r.moveCenter( rect.center() ); - - painter->fillRect( r, d_data->brush ); -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_histogram.h" +#include "qwt_plot.h" +#include "qwt_legend.h" +#include "qwt_legend_item.h" +#include "qwt_painter.h" +#include "qwt_column_symbol.h" +#include "qwt_scale_map.h" +#include +#include + +static inline bool isCombinable( const QwtInterval &d1, + const QwtInterval &d2 ) +{ + if ( d1.isValid() && d2.isValid() ) + { + if ( d1.maxValue() == d2.minValue() ) + { + if ( !( d1.borderFlags() & QwtInterval::ExcludeMaximum + && d2.borderFlags() & QwtInterval::ExcludeMinimum ) ) + { + return true; + } + } + } + + return false; +} + +class QwtPlotHistogram::PrivateData +{ +public: + PrivateData(): + baseline( 0.0 ), + style( Columns ), + symbol( NULL ) + { + } + + ~PrivateData() + { + delete symbol; + } + + double baseline; + + QPen pen; + QBrush brush; + QwtPlotHistogram::HistogramStyle style; + const QwtColumnSymbol *symbol; +}; + +/*! + Constructor + \param title Title of the histogram. +*/ + +QwtPlotHistogram::QwtPlotHistogram( const QwtText &title ): + QwtPlotSeriesItem( title ) +{ + init(); +} + +/*! + Constructor + \param title Title of the histogram. +*/ +QwtPlotHistogram::QwtPlotHistogram( const QString &title ): + QwtPlotSeriesItem( title ) +{ + init(); +} + +//! Destructor +QwtPlotHistogram::~QwtPlotHistogram() +{ + delete d_data; +} + +//! Initialize data members +void QwtPlotHistogram::init() +{ + d_data = new PrivateData(); + d_series = new QwtIntervalSeriesData(); + + setItemAttribute( QwtPlotItem::AutoScale, true ); + setItemAttribute( QwtPlotItem::Legend, true ); + + setZ( 20.0 ); +} + +/*! + Set the histogram's drawing style + + \param style Histogram style + \sa HistogramStyle, style() +*/ +void QwtPlotHistogram::setStyle( HistogramStyle style ) +{ + if ( style != d_data->style ) + { + d_data->style = style; + itemChanged(); + } +} + +/*! + Return the current style + \sa HistogramStyle, setStyle() +*/ +QwtPlotHistogram::HistogramStyle QwtPlotHistogram::style() const +{ + return d_data->style; +} + +/*! + Assign a pen, that is used in a style() depending way. + + \param pen New pen + \sa pen(), brush() +*/ +void QwtPlotHistogram::setPen( const QPen &pen ) +{ + if ( pen != d_data->pen ) + { + d_data->pen = pen; + itemChanged(); + } +} + +/*! + \return Pen used in a style() depending way. + \sa setPen(), brush() +*/ +const QPen &QwtPlotHistogram::pen() const +{ + return d_data->pen; +} + +/*! + Assign a brush, that is used in a style() depending way. + + \param brush New brush + \sa pen(), brush() +*/ +void QwtPlotHistogram::setBrush( const QBrush &brush ) +{ + if ( brush != d_data->brush ) + { + d_data->brush = brush; + itemChanged(); + } +} + +/*! + \return Brush used in a style() depending way. + \sa setPen(), brush() +*/ +const QBrush &QwtPlotHistogram::brush() const +{ + return d_data->brush; +} + +/*! + \brief Assign a symbol + + In Column style an optional symbol can be assigned, that is responsible + for displaying the rectangle that is defined by the interval and + the distance between baseline() and value. When no symbol has been + defined the area is displayed as plain rectangle using pen() and brush(). + + \sa style(), symbol(), drawColumn(), pen(), brush() + + \note In applications, where different intervals need to be displayed + in a different way ( f.e different colors or even using differnt symbols) + it is recommended to overload drawColumn(). +*/ +void QwtPlotHistogram::setSymbol( const QwtColumnSymbol *symbol ) +{ + if ( symbol != d_data->symbol ) + { + delete d_data->symbol; + d_data->symbol = symbol; + itemChanged(); + } +} + +/*! + \return Current symbol or NULL, when no symbol has been assigned + \sa setSymbol() +*/ +const QwtColumnSymbol *QwtPlotHistogram::symbol() const +{ + return d_data->symbol; +} + +/*! + \brief Set the value of the baseline + + Each column representing an QwtIntervalSample is defined by its + interval and the interval between baseline and the value of the sample. + + The default value of the baseline is 0.0. + + \param value Value of the baseline + \sa baseline() +*/ +void QwtPlotHistogram::setBaseline( double value ) +{ + if ( d_data->baseline != value ) + { + d_data->baseline = value; + itemChanged(); + } +} + +/*! + \return Value of the baseline + \sa setBaseline() +*/ +double QwtPlotHistogram::baseline() const +{ + return d_data->baseline; +} + +/*! + \return Bounding rectangle of all samples. + For an empty series the rectangle is invalid. +*/ +QRectF QwtPlotHistogram::boundingRect() const +{ + QRectF rect = d_series->boundingRect(); + if ( !rect.isValid() ) + return rect; + + if ( orientation() == Qt::Horizontal ) + { + rect = QRectF( rect.y(), rect.x(), + rect.height(), rect.width() ); + + if ( rect.left() > d_data->baseline ) + rect.setLeft( d_data->baseline ); + else if ( rect.right() < d_data->baseline ) + rect.setRight( d_data->baseline ); + } + else + { + if ( rect.bottom() < d_data->baseline ) + rect.setBottom( d_data->baseline ); + else if ( rect.top() > d_data->baseline ) + rect.setTop( d_data->baseline ); + } + + return rect; +} + +//! \return QwtPlotItem::Rtti_PlotHistogram +int QwtPlotHistogram::rtti() const +{ + return QwtPlotItem::Rtti_PlotHistogram; +} + +/*! + Initialize data with an array of samples. + \param samples Vector of points +*/ +void QwtPlotHistogram::setSamples( + const QVector &samples ) +{ + delete d_series; + d_series = new QwtIntervalSeriesData( samples ); + itemChanged(); +} + +/*! + Draw a subset of the histogram samples + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rect of the canvas + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + series will be painted to its last sample. + + \sa drawOutline(), drawLines(), drawColumns +*/ +void QwtPlotHistogram::drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &, int from, int to ) const +{ + if ( !painter || dataSize() <= 0 ) + return; + + if ( to < 0 ) + to = dataSize() - 1; + + switch ( d_data->style ) + { + case Outline: + drawOutline( painter, xMap, yMap, from, to ); + break; + case Lines: + drawLines( painter, xMap, yMap, from, to ); + break; + case Columns: + drawColumns( painter, xMap, yMap, from, to ); + break; + default: + break; + } +} + +/*! + Draw a histogram in Outline style() + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + histogram will be painted to its last point. + + \sa setStyle(), style() + \warning The outline style requires, that the intervals are in increasing + order and not overlapping. +*/ +void QwtPlotHistogram::drawOutline( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const +{ + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + double v0 = ( orientation() == Qt::Horizontal ) ? + xMap.transform( baseline() ) : yMap.transform( baseline() ); + if ( doAlign ) + v0 = qRound( v0 ); + + QwtIntervalSample previous; + + QPolygonF polygon; + for ( int i = from; i <= to; i++ ) + { + const QwtIntervalSample sample = d_series->sample( i ); + + if ( !sample.interval.isValid() ) + { + flushPolygon( painter, v0, polygon ); + previous = sample; + continue; + } + + if ( previous.interval.isValid() ) + { + if ( !isCombinable( previous.interval, sample.interval ) ) + flushPolygon( painter, v0, polygon ); + } + + if ( orientation() == Qt::Vertical ) + { + double x1 = xMap.transform( sample.interval.minValue() ); + double x2 = xMap.transform( sample.interval.maxValue() ); + double y = yMap.transform( sample.value ); + if ( doAlign ) + { + x1 = qRound( x1 ); + x2 = qRound( x2 ); + y = qRound( y ); + } + + if ( polygon.size() == 0 ) + polygon += QPointF( x1, v0 ); + + polygon += QPointF( x1, y ); + polygon += QPointF( x2, y ); + } + else + { + double y1 = yMap.transform( sample.interval.minValue() ); + double y2 = yMap.transform( sample.interval.maxValue() ); + double x = xMap.transform( sample.value ); + if ( doAlign ) + { + y1 = qRound( y1 ); + y2 = qRound( y2 ); + x = qRound( x ); + } + + if ( polygon.size() == 0 ) + polygon += QPointF( v0, y1 ); + + polygon += QPointF( x, y1 ); + polygon += QPointF( x, y2 ); + } + previous = sample; + } + + flushPolygon( painter, v0, polygon ); +} + +/*! + Draw a histogram in Columns style() + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + histogram will be painted to its last point. + + \sa setStyle(), style(), setSymbol(), drawColumn() +*/ +void QwtPlotHistogram::drawColumns( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const +{ + painter->setPen( d_data->pen ); + painter->setBrush( d_data->brush ); + + for ( int i = from; i <= to; i++ ) + { + const QwtIntervalSample sample = d_series->sample( i ); + if ( !sample.interval.isNull() ) + { + const QwtColumnRect rect = columnRect( sample, xMap, yMap ); + drawColumn( painter, rect, sample ); + } + } +} + +/*! + Draw a histogram in Lines style() + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + histogram will be painted to its last point. + + \sa setStyle(), style(), setPen() +*/ +void QwtPlotHistogram::drawLines( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const +{ + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + painter->setPen( d_data->pen ); + painter->setBrush( Qt::NoBrush ); + + for ( int i = from; i <= to; i++ ) + { + const QwtIntervalSample sample = d_series->sample( i ); + if ( !sample.interval.isNull() ) + { + const QwtColumnRect rect = columnRect( sample, xMap, yMap ); + + QRectF r = rect.toRect(); + if ( doAlign ) + { + r.setLeft( qRound( r.left() ) ); + r.setRight( qRound( r.right() ) ); + r.setTop( qRound( r.top() ) ); + r.setBottom( qRound( r.bottom() ) ); + } + + switch ( rect.direction ) + { + case QwtColumnRect::LeftToRight: + { + QwtPainter::drawLine( painter, + r.topRight(), r.bottomRight() ); + break; + } + case QwtColumnRect::RightToLeft: + { + QwtPainter::drawLine( painter, + r.topLeft(), r.bottomLeft() ); + break; + } + case QwtColumnRect::TopToBottom: + { + QwtPainter::drawLine( painter, + r.bottomRight(), r.bottomLeft() ); + break; + } + case QwtColumnRect::BottomToTop: + { + QwtPainter::drawLine( painter, + r.topRight(), r.topLeft() ); + break; + } + } + } + } +} + +//! Internal, used by the Outline style. +void QwtPlotHistogram::flushPolygon( QPainter *painter, + double baseLine, QPolygonF &polygon ) const +{ + if ( polygon.size() == 0 ) + return; + + if ( orientation() == Qt::Horizontal ) + polygon += QPointF( baseLine, polygon.last().y() ); + else + polygon += QPointF( polygon.last().x(), baseLine ); + + if ( d_data->brush.style() != Qt::NoBrush ) + { + painter->setPen( Qt::NoPen ); + painter->setBrush( d_data->brush ); + + if ( orientation() == Qt::Horizontal ) + { + polygon += QPointF( polygon.last().x(), baseLine ); + polygon += QPointF( polygon.first().x(), baseLine ); + } + else + { + polygon += QPointF( baseLine, polygon.last().y() ); + polygon += QPointF( baseLine, polygon.first().y() ); + } + QwtPainter::drawPolygon( painter, polygon ); + polygon.resize( polygon.size() - 2 ); + } + if ( d_data->pen.style() != Qt::NoPen ) + { + painter->setBrush( Qt::NoBrush ); + painter->setPen( d_data->pen ); + QwtPainter::drawPolyline( painter, polygon ); + } + polygon.clear(); +} + +/*! + Calculate the area that is covered by a sample + + \param sample Sample + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + + \return Rectangle, that is covered by a sample +*/ +QwtColumnRect QwtPlotHistogram::columnRect( const QwtIntervalSample &sample, + const QwtScaleMap &xMap, const QwtScaleMap &yMap ) const +{ + QwtColumnRect rect; + + const QwtInterval &iv = sample.interval; + if ( !iv.isValid() ) + return rect; + + if ( orientation() == Qt::Horizontal ) + { + const double x0 = xMap.transform( baseline() ); + const double x = xMap.transform( sample.value ); + const double y1 = yMap.transform( iv.minValue() ); + const double y2 = yMap.transform( iv.maxValue() ); + + rect.hInterval.setInterval( x0, x ); + rect.vInterval.setInterval( y1, y2, iv.borderFlags() ); + rect.direction = ( x < x0 ) ? QwtColumnRect::RightToLeft : + QwtColumnRect::LeftToRight; + } + else + { + const double x1 = xMap.transform( iv.minValue() ); + const double x2 = xMap.transform( iv.maxValue() ); + const double y0 = yMap.transform( baseline() ); + const double y = yMap.transform( sample.value ); + + rect.hInterval.setInterval( x1, x2, iv.borderFlags() ); + rect.vInterval.setInterval( y0, y ); + rect.direction = ( y < y0 ) ? QwtColumnRect::BottomToTop : + QwtColumnRect::TopToBottom; + } + + return rect; +} + +/*! + Draw a column for a sample in Columns style(). + + When a symbol() has been set the symbol is used otherwise the + column is displayed as plain rectangle using pen() and brush(). + + \param painter Painter + \param rect Rectangle where to paint the column in paint device coordinates + \param sample Sample to be displayed + + \note In applications, where different intervals need to be displayed + in a different way ( f.e different colors or even using differnt symbols) + it is recommended to overload drawColumn(). +*/ +void QwtPlotHistogram::drawColumn( QPainter *painter, + const QwtColumnRect &rect, const QwtIntervalSample &sample ) const +{ + Q_UNUSED( sample ); + + if ( d_data->symbol && + ( d_data->symbol->style() != QwtColumnSymbol::NoStyle ) ) + { + d_data->symbol->draw( painter, rect ); + } + else + { + QRectF r = rect.toRect(); + if ( QwtPainter::roundingAlignment( painter ) ) + { + r.setLeft( qRound( r.left() ) ); + r.setRight( qRound( r.right() ) ); + r.setTop( qRound( r.top() ) ); + r.setBottom( qRound( r.bottom() ) ); + } + + QwtPainter::drawRect( painter, r ); + } +} + +/*! + Draw a plain rectangle without pen using the brush() as identifier + + \param painter Painter + \param rect Bounding rectangle for the identifier +*/ +void QwtPlotHistogram::drawLegendIdentifier( + QPainter *painter, const QRectF &rect ) const +{ + const double dim = qMin( rect.width(), rect.height() ); + + QSizeF size( dim, dim ); + + QRectF r( 0, 0, size.width(), size.height() ); + r.moveCenter( rect.center() ); + + painter->fillRect( r, d_data->brush ); +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_histogram.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_histogram.h index 3f88042c0..3e40c451b 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_histogram.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_histogram.h @@ -1,134 +1,134 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PLOT_HISTOGRAM_H -#define QWT_PLOT_HISTOGRAM_H - -#include "qwt_global.h" -#include "qwt_plot_seriesitem.h" -#include "qwt_column_symbol.h" -#include -#include - -class QwtIntervalData; -class QString; -class QPolygonF; - -/*! - \brief QwtPlotHistogram represents a series of samples, where an interval - is associated with a value ( \f$y = f([x1,x2])\f$ ). - - The representation depends on the style() and an optional symbol() - that is displayed for each interval. - - \note The term "histogram" is used in a different way in the areas of - digital image processing and statistics. Wikipedia introduces the - terms "image histogram" and "color histogram" to avoid confusions. - While "image histograms" can be displayed by a QwtPlotCurve there - is no applicable plot item for a "color histogram" yet. -*/ - -class QWT_EXPORT QwtPlotHistogram: public QwtPlotSeriesItem -{ -public: - /*! - Histogram styles. - The default style is QwtPlotHistogram::Columns. - - \sa setStyle(), style(), setSymbol(), symbol(), setBaseline() - */ - enum HistogramStyle - { - /*! - Draw an outline around the area, that is build by all intervals - using the pen() and fill it with the brush(). The outline style - requires, that the intervals are in increasing order and - not overlapping. - */ - Outline, - - /*! - Draw a column for each interval. When a symbol() has been set - the symbol is used otherwise the column is displayed as - plain rectangle using pen() and brush(). - */ - Columns, - - /*! - Draw a simple line using the pen() for each interval. - */ - Lines, - - /*! - Styles >= UserStyle are reserved for derived - classes that overload drawSeries() with - additional application specific ways to display a histogram. - */ - UserStyle = 100 - }; - - explicit QwtPlotHistogram( const QString &title = QString::null ); - explicit QwtPlotHistogram( const QwtText &title ); - virtual ~QwtPlotHistogram(); - - virtual int rtti() const; - - void setPen( const QPen & ); - const QPen &pen() const; - - void setBrush( const QBrush & ); - const QBrush &brush() const; - - void setSamples( const QVector & ); - - void setBaseline( double reference ); - double baseline() const; - - void setStyle( HistogramStyle style ); - HistogramStyle style() const; - - void setSymbol( const QwtColumnSymbol * ); - const QwtColumnSymbol *symbol() const; - - virtual void drawSeries( QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - - virtual QRectF boundingRect() const; - - virtual void drawLegendIdentifier( QPainter *, const QRectF & ) const; - -protected: - virtual QwtColumnRect columnRect( const QwtIntervalSample &, - const QwtScaleMap &, const QwtScaleMap & ) const; - - virtual void drawColumn( QPainter *, const QwtColumnRect &, - const QwtIntervalSample & ) const; - - void drawColumns( QPainter *, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to ) const; - - void drawOutline( QPainter *, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to ) const; - - void drawLines( QPainter *, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - int from, int to ) const; - -private: - void init(); - void flushPolygon( QPainter *, double baseLine, QPolygonF & ) const; - - class PrivateData; - PrivateData *d_data; -}; - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_HISTOGRAM_H +#define QWT_PLOT_HISTOGRAM_H + +#include "qwt_global.h" +#include "qwt_plot_seriesitem.h" +#include "qwt_column_symbol.h" +#include +#include + +class QwtIntervalData; +class QString; +class QPolygonF; + +/*! + \brief QwtPlotHistogram represents a series of samples, where an interval + is associated with a value ( \f$y = f([x1,x2])\f$ ). + + The representation depends on the style() and an optional symbol() + that is displayed for each interval. + + \note The term "histogram" is used in a different way in the areas of + digital image processing and statistics. Wikipedia introduces the + terms "image histogram" and "color histogram" to avoid confusions. + While "image histograms" can be displayed by a QwtPlotCurve there + is no applicable plot item for a "color histogram" yet. +*/ + +class QWT_EXPORT QwtPlotHistogram: public QwtPlotSeriesItem +{ +public: + /*! + Histogram styles. + The default style is QwtPlotHistogram::Columns. + + \sa setStyle(), style(), setSymbol(), symbol(), setBaseline() + */ + enum HistogramStyle + { + /*! + Draw an outline around the area, that is build by all intervals + using the pen() and fill it with the brush(). The outline style + requires, that the intervals are in increasing order and + not overlapping. + */ + Outline, + + /*! + Draw a column for each interval. When a symbol() has been set + the symbol is used otherwise the column is displayed as + plain rectangle using pen() and brush(). + */ + Columns, + + /*! + Draw a simple line using the pen() for each interval. + */ + Lines, + + /*! + Styles >= UserStyle are reserved for derived + classes that overload drawSeries() with + additional application specific ways to display a histogram. + */ + UserStyle = 100 + }; + + explicit QwtPlotHistogram( const QString &title = QString::null ); + explicit QwtPlotHistogram( const QwtText &title ); + virtual ~QwtPlotHistogram(); + + virtual int rtti() const; + + void setPen( const QPen & ); + const QPen &pen() const; + + void setBrush( const QBrush & ); + const QBrush &brush() const; + + void setSamples( const QVector & ); + + void setBaseline( double reference ); + double baseline() const; + + void setStyle( HistogramStyle style ); + HistogramStyle style() const; + + void setSymbol( const QwtColumnSymbol * ); + const QwtColumnSymbol *symbol() const; + + virtual void drawSeries( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual QRectF boundingRect() const; + + virtual void drawLegendIdentifier( QPainter *, const QRectF & ) const; + +protected: + virtual QwtColumnRect columnRect( const QwtIntervalSample &, + const QwtScaleMap &, const QwtScaleMap & ) const; + + virtual void drawColumn( QPainter *, const QwtColumnRect &, + const QwtIntervalSample & ) const; + + void drawColumns( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const; + + void drawOutline( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const; + + void drawLines( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + int from, int to ) const; + +private: + void init(); + void flushPolygon( QPainter *, double baseLine, QPolygonF & ) const; + + class PrivateData; + PrivateData *d_data; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_intervalcurve.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_intervalcurve.cpp index 5fe3b5437..9a99e64c1 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_intervalcurve.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_intervalcurve.cpp @@ -1,547 +1,547 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot_intervalcurve.h" -#include "qwt_interval_symbol.h" -#include "qwt_scale_map.h" -#include "qwt_clipper.h" -#include "qwt_painter.h" - -#include - -static inline bool qwtIsHSampleInside( const QwtIntervalSample &sample, - double xMin, double xMax, double yMin, double yMax ) -{ - const double y = sample.value; - const double x1 = sample.interval.minValue(); - const double x2 = sample.interval.maxValue(); - - const bool isOffScreen = ( y < yMin ) || ( y > yMax ) - || ( x1 < xMin && x2 < xMin ) || ( x1 > yMax && x2 > xMax ); - - return !isOffScreen; -} - -static inline bool qwtIsVSampleInside( const QwtIntervalSample &sample, - double xMin, double xMax, double yMin, double yMax ) -{ - const double x = sample.value; - const double y1 = sample.interval.minValue(); - const double y2 = sample.interval.maxValue(); - - const bool isOffScreen = ( x < xMin ) || ( x > xMax ) - || ( y1 < yMin && y2 < yMin ) || ( y1 > yMax && y2 > yMax ); - - return !isOffScreen; -} - -class QwtPlotIntervalCurve::PrivateData -{ -public: - PrivateData(): - style( Tube ), - symbol( NULL ), - pen( Qt::black ), - brush( Qt::white ) - { - paintAttributes = QwtPlotIntervalCurve::ClipPolygons; - paintAttributes |= QwtPlotIntervalCurve::ClipSymbol; - - pen.setCapStyle( Qt::FlatCap ); - } - - ~PrivateData() - { - delete symbol; - } - - CurveStyle style; - const QwtIntervalSymbol *symbol; - - QPen pen; - QBrush brush; - - QwtPlotIntervalCurve::PaintAttributes paintAttributes; -}; - -/*! - Constructor - \param title Title of the curve -*/ -QwtPlotIntervalCurve::QwtPlotIntervalCurve( const QwtText &title ): - QwtPlotSeriesItem( title ) -{ - init(); -} - -/*! - Constructor - \param title Title of the curve -*/ -QwtPlotIntervalCurve::QwtPlotIntervalCurve( const QString &title ): - QwtPlotSeriesItem( QwtText( title ) ) -{ - init(); -} - -//! Destructor -QwtPlotIntervalCurve::~QwtPlotIntervalCurve() -{ - delete d_data; -} - -//! Initialize internal members -void QwtPlotIntervalCurve::init() -{ - setItemAttribute( QwtPlotItem::Legend, true ); - setItemAttribute( QwtPlotItem::AutoScale, true ); - - d_data = new PrivateData; - d_series = new QwtIntervalSeriesData(); - - setZ( 19.0 ); -} - -//! \return QwtPlotItem::Rtti_PlotIntervalCurve -int QwtPlotIntervalCurve::rtti() const -{ - return QwtPlotIntervalCurve::Rtti_PlotIntervalCurve; -} - -/*! - Specify an attribute how to draw the curve - - \param attribute Paint attribute - \param on On/Off - \sa testPaintAttribute() -*/ -void QwtPlotIntervalCurve::setPaintAttribute( - PaintAttribute attribute, bool on ) -{ - if ( on ) - d_data->paintAttributes |= attribute; - else - d_data->paintAttributes &= ~attribute; -} - -/*! - \brief Return the current paint attributes - \sa PaintAttribute, setPaintAttribute() -*/ -bool QwtPlotIntervalCurve::testPaintAttribute( - PaintAttribute attribute ) const -{ - return ( d_data->paintAttributes & attribute ); -} - -/*! - Initialize data with an array of samples. - \param samples Vector of samples -*/ -void QwtPlotIntervalCurve::setSamples( - const QVector &samples ) -{ - delete d_series; - d_series = new QwtIntervalSeriesData( samples ); - itemChanged(); -} - -/*! - Set the curve's drawing style - - \param style Curve style - \sa CurveStyle, style() -*/ -void QwtPlotIntervalCurve::setStyle( CurveStyle style ) -{ - if ( style != d_data->style ) - { - d_data->style = style; - itemChanged(); - } -} - -/*! - \brief Return the current style - \sa setStyle() -*/ -QwtPlotIntervalCurve::CurveStyle QwtPlotIntervalCurve::style() const -{ - return d_data->style; -} - -/*! - Assign a symbol. - - \param symbol Symbol - \sa symbol() -*/ -void QwtPlotIntervalCurve::setSymbol( const QwtIntervalSymbol *symbol ) -{ - if ( symbol != d_data->symbol ) - { - delete d_data->symbol; - d_data->symbol = symbol; - itemChanged(); - } -} - -/*! - \return Current symbol or NULL, when no symbol has been assigned - \sa setSymbol() -*/ -const QwtIntervalSymbol *QwtPlotIntervalCurve::symbol() const -{ - return d_data->symbol; -} - -/*! - \brief Assign a pen - \param pen New pen - \sa pen(), brush() -*/ -void QwtPlotIntervalCurve::setPen( const QPen &pen ) -{ - if ( pen != d_data->pen ) - { - d_data->pen = pen; - itemChanged(); - } -} - -/*! - \brief Return the pen used to draw the lines - \sa setPen(), brush() -*/ -const QPen& QwtPlotIntervalCurve::pen() const -{ - return d_data->pen; -} - -/*! - Assign a brush. - - The brush is used to fill the area in Tube style(). - - \param brush Brush - \sa brush(), pen(), setStyle(), CurveStyle -*/ -void QwtPlotIntervalCurve::setBrush( const QBrush &brush ) -{ - if ( brush != d_data->brush ) - { - d_data->brush = brush; - itemChanged(); - } -} - -/*! - \return Brush used to fill the area in Tube style() - \sa setBrush(), setStyle(), CurveStyle -*/ -const QBrush& QwtPlotIntervalCurve::brush() const -{ - return d_data->brush; -} - -/*! - \return Bounding rectangle of all samples. - For an empty series the rectangle is invalid. -*/ -QRectF QwtPlotIntervalCurve::boundingRect() const -{ - QRectF rect = QwtPlotSeriesItem::boundingRect(); - if ( rect.isValid() && orientation() == Qt::Vertical ) - rect.setRect( rect.y(), rect.x(), rect.height(), rect.width() ); - - return rect; -} - -/*! - Draw a subset of the samples - - \param painter Painter - \param xMap Maps x-values into pixel coordinates. - \param yMap Maps y-values into pixel coordinates. - \param canvasRect Contents rect of the canvas - \param from Index of the first sample to be painted - \param to Index of the last sample to be painted. If to < 0 the - series will be painted to its last sample. - - \sa drawTube(), drawSymbols() -*/ -void QwtPlotIntervalCurve::drawSeries( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const -{ - if ( to < 0 ) - to = dataSize() - 1; - - if ( from < 0 ) - from = 0; - - if ( from > to ) - return; - - switch ( d_data->style ) - { - case Tube: - drawTube( painter, xMap, yMap, canvasRect, from, to ); - break; - - case NoCurve: - default: - break; - } - - if ( d_data->symbol && - ( d_data->symbol->style() != QwtIntervalSymbol::NoSymbol ) ) - { - drawSymbols( painter, *d_data->symbol, - xMap, yMap, canvasRect, from, to ); - } -} - -/*! - Draw a tube - - Builds 2 curves from the upper and lower limits of the intervals - and draws them with the pen(). The area between the curves is - filled with the brush(). - - \param painter Painter - \param xMap Maps x-values into pixel coordinates. - \param yMap Maps y-values into pixel coordinates. - \param canvasRect Contents rect of the canvas - \param from Index of the first sample to be painted - \param to Index of the last sample to be painted. If to < 0 the - series will be painted to its last sample. - - \sa drawSeries(), drawSymbols() -*/ -void QwtPlotIntervalCurve::drawTube( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const -{ - const bool doAlign = QwtPainter::roundingAlignment( painter ); - - painter->save(); - - const size_t size = to - from + 1; - QPolygonF polygon( 2 * size ); - QPointF *points = polygon.data(); - - for ( uint i = 0; i < size; i++ ) - { - QPointF &minValue = points[i]; - QPointF &maxValue = points[2 * size - 1 - i]; - - const QwtIntervalSample intervalSample = sample( from + i ); - if ( orientation() == Qt::Vertical ) - { - double x = xMap.transform( intervalSample.value ); - double y1 = yMap.transform( intervalSample.interval.minValue() ); - double y2 = yMap.transform( intervalSample.interval.maxValue() ); - if ( doAlign ) - { - x = qRound( x ); - y1 = qRound( y1 ); - y2 = qRound( y2 ); - } - - minValue.rx() = x; - minValue.ry() = y1; - maxValue.rx() = x; - maxValue.ry() = y2; - } - else - { - double y = yMap.transform( intervalSample.value ); - double x1 = xMap.transform( intervalSample.interval.minValue() ); - double x2 = xMap.transform( intervalSample.interval.maxValue() ); - if ( doAlign ) - { - y = qRound( y ); - x1 = qRound( x1 ); - x2 = qRound( x2 ); - } - - minValue.rx() = x1; - minValue.ry() = y; - maxValue.rx() = x2; - maxValue.ry() = y; - } - } - - if ( d_data->brush.style() != Qt::NoBrush ) - { - painter->setPen( QPen( Qt::NoPen ) ); - painter->setBrush( d_data->brush ); - - if ( d_data->paintAttributes & ClipPolygons ) - { - const qreal m = 1.0; - const QPolygonF p = QwtClipper::clipPolygonF( - canvasRect.adjusted(-m, -m, m, m), polygon, true ); - - QwtPainter::drawPolygon( painter, p ); - } - else - { - QwtPainter::drawPolygon( painter, polygon ); - } - } - - if ( d_data->pen.style() != Qt::NoPen ) - { - painter->setPen( d_data->pen ); - painter->setBrush( Qt::NoBrush ); - - if ( d_data->paintAttributes & ClipPolygons ) - { - qreal pw = qMax( qreal( 1.0 ), painter->pen().widthF()); - const QRectF clipRect = canvasRect.adjusted(-pw, -pw, pw, pw); - - QPolygonF p; - - p.resize( size ); - qMemCopy( p.data(), points, size * sizeof( QPointF ) ); - p = QwtClipper::clipPolygonF( canvasRect, p ); - QwtPainter::drawPolyline( painter, p ); - - p.resize( size ); - qMemCopy( p.data(), points + size, size * sizeof( QPointF ) ); - p = QwtClipper::clipPolygonF( canvasRect, p ); - QwtPainter::drawPolyline( painter, p ); - } - else - { - QwtPainter::drawPolyline( painter, points, size ); - QwtPainter::drawPolyline( painter, points + size, size ); - } - } - - painter->restore(); -} - -/*! - Draw symbols for a subset of the samples - - \param painter Painter - \param symbol Interval symbol - \param xMap x map - \param yMap y map - \param canvasRect Contents rect of the canvas - \param from Index of the first sample to be painted - \param to Index of the last sample to be painted - - \sa setSymbol(), drawSeries(), drawTube() -*/ -void QwtPlotIntervalCurve::drawSymbols( - QPainter *painter, const QwtIntervalSymbol &symbol, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const -{ - painter->save(); - - QPen pen = symbol.pen(); - pen.setCapStyle( Qt::FlatCap ); - - painter->setPen( pen ); - painter->setBrush( symbol.brush() ); - - const QRectF &tr = QwtScaleMap::invTransform( xMap, yMap, canvasRect); - - const double xMin = tr.left(); - const double xMax = tr.right(); - const double yMin = tr.top(); - const double yMax = tr.bottom(); - - const bool doClip = d_data->paintAttributes & ClipPolygons; - - for ( int i = from; i <= to; i++ ) - { - const QwtIntervalSample s = sample( i ); - - if ( orientation() == Qt::Vertical ) - { - if ( !doClip || qwtIsVSampleInside( s, xMin, xMax, yMin, yMax ) ) - { - const double x = xMap.transform( s.value ); - const double y1 = yMap.transform( s.interval.minValue() ); - const double y2 = yMap.transform( s.interval.maxValue() ); - - symbol.draw( painter, orientation(), - QPointF( x, y1 ), QPointF( x, y2 ) ); - } - } - else - { - if ( !doClip || qwtIsHSampleInside( s, xMin, xMax, yMin, yMax ) ) - { - const double y = yMap.transform( s.value ); - const double x1 = xMap.transform( s.interval.minValue() ); - const double x2 = xMap.transform( s.interval.maxValue() ); - - symbol.draw( painter, orientation(), - QPointF( x1, y ), QPointF( x2, y ) ); - } - } - } - - painter->restore(); -} - -/*! - In case of Tibe stale() a plain rectangle is painted without a pen filled - the brush(). If a symbol is assigned it is painted cebtered into rect. - - \param painter Painter - \param rect Bounding rectangle for the identifier -*/ - -void QwtPlotIntervalCurve::drawLegendIdentifier( - QPainter *painter, const QRectF &rect ) const -{ - const double dim = qMin( rect.width(), rect.height() ); - - QSizeF size( dim, dim ); - - QRectF r( 0, 0, size.width(), size.height() ); - r.moveCenter( rect.center() ); - - if ( d_data->style == Tube ) - { - painter->fillRect( r, d_data->brush ); - } - - if ( d_data->symbol && - ( d_data->symbol->style() != QwtIntervalSymbol::NoSymbol ) ) - { - QPen pen = d_data->symbol->pen(); - pen.setWidthF( pen.widthF() ); - pen.setCapStyle( Qt::FlatCap ); - - painter->setPen( pen ); - painter->setBrush( d_data->symbol->brush() ); - - if ( orientation() == Qt::Vertical ) - { - d_data->symbol->draw( painter, orientation(), - QPointF( r.center().x(), r.top() ), - QPointF( r.center().x(), r.bottom() - 1 ) ); - } - else - { - d_data->symbol->draw( painter, orientation(), - QPointF( r.left(), r.center().y() ), - QPointF( r.right() - 1, r.center().y() ) ); - } - } -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_intervalcurve.h" +#include "qwt_interval_symbol.h" +#include "qwt_scale_map.h" +#include "qwt_clipper.h" +#include "qwt_painter.h" + +#include + +static inline bool qwtIsHSampleInside( const QwtIntervalSample &sample, + double xMin, double xMax, double yMin, double yMax ) +{ + const double y = sample.value; + const double x1 = sample.interval.minValue(); + const double x2 = sample.interval.maxValue(); + + const bool isOffScreen = ( y < yMin ) || ( y > yMax ) + || ( x1 < xMin && x2 < xMin ) || ( x1 > yMax && x2 > xMax ); + + return !isOffScreen; +} + +static inline bool qwtIsVSampleInside( const QwtIntervalSample &sample, + double xMin, double xMax, double yMin, double yMax ) +{ + const double x = sample.value; + const double y1 = sample.interval.minValue(); + const double y2 = sample.interval.maxValue(); + + const bool isOffScreen = ( x < xMin ) || ( x > xMax ) + || ( y1 < yMin && y2 < yMin ) || ( y1 > yMax && y2 > yMax ); + + return !isOffScreen; +} + +class QwtPlotIntervalCurve::PrivateData +{ +public: + PrivateData(): + style( Tube ), + symbol( NULL ), + pen( Qt::black ), + brush( Qt::white ) + { + paintAttributes = QwtPlotIntervalCurve::ClipPolygons; + paintAttributes |= QwtPlotIntervalCurve::ClipSymbol; + + pen.setCapStyle( Qt::FlatCap ); + } + + ~PrivateData() + { + delete symbol; + } + + CurveStyle style; + const QwtIntervalSymbol *symbol; + + QPen pen; + QBrush brush; + + QwtPlotIntervalCurve::PaintAttributes paintAttributes; +}; + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotIntervalCurve::QwtPlotIntervalCurve( const QwtText &title ): + QwtPlotSeriesItem( title ) +{ + init(); +} + +/*! + Constructor + \param title Title of the curve +*/ +QwtPlotIntervalCurve::QwtPlotIntervalCurve( const QString &title ): + QwtPlotSeriesItem( QwtText( title ) ) +{ + init(); +} + +//! Destructor +QwtPlotIntervalCurve::~QwtPlotIntervalCurve() +{ + delete d_data; +} + +//! Initialize internal members +void QwtPlotIntervalCurve::init() +{ + setItemAttribute( QwtPlotItem::Legend, true ); + setItemAttribute( QwtPlotItem::AutoScale, true ); + + d_data = new PrivateData; + d_series = new QwtIntervalSeriesData(); + + setZ( 19.0 ); +} + +//! \return QwtPlotItem::Rtti_PlotIntervalCurve +int QwtPlotIntervalCurve::rtti() const +{ + return QwtPlotIntervalCurve::Rtti_PlotIntervalCurve; +} + +/*! + Specify an attribute how to draw the curve + + \param attribute Paint attribute + \param on On/Off + \sa testPaintAttribute() +*/ +void QwtPlotIntervalCurve::setPaintAttribute( + PaintAttribute attribute, bool on ) +{ + if ( on ) + d_data->paintAttributes |= attribute; + else + d_data->paintAttributes &= ~attribute; +} + +/*! + \brief Return the current paint attributes + \sa PaintAttribute, setPaintAttribute() +*/ +bool QwtPlotIntervalCurve::testPaintAttribute( + PaintAttribute attribute ) const +{ + return ( d_data->paintAttributes & attribute ); +} + +/*! + Initialize data with an array of samples. + \param samples Vector of samples +*/ +void QwtPlotIntervalCurve::setSamples( + const QVector &samples ) +{ + delete d_series; + d_series = new QwtIntervalSeriesData( samples ); + itemChanged(); +} + +/*! + Set the curve's drawing style + + \param style Curve style + \sa CurveStyle, style() +*/ +void QwtPlotIntervalCurve::setStyle( CurveStyle style ) +{ + if ( style != d_data->style ) + { + d_data->style = style; + itemChanged(); + } +} + +/*! + \brief Return the current style + \sa setStyle() +*/ +QwtPlotIntervalCurve::CurveStyle QwtPlotIntervalCurve::style() const +{ + return d_data->style; +} + +/*! + Assign a symbol. + + \param symbol Symbol + \sa symbol() +*/ +void QwtPlotIntervalCurve::setSymbol( const QwtIntervalSymbol *symbol ) +{ + if ( symbol != d_data->symbol ) + { + delete d_data->symbol; + d_data->symbol = symbol; + itemChanged(); + } +} + +/*! + \return Current symbol or NULL, when no symbol has been assigned + \sa setSymbol() +*/ +const QwtIntervalSymbol *QwtPlotIntervalCurve::symbol() const +{ + return d_data->symbol; +} + +/*! + \brief Assign a pen + \param pen New pen + \sa pen(), brush() +*/ +void QwtPlotIntervalCurve::setPen( const QPen &pen ) +{ + if ( pen != d_data->pen ) + { + d_data->pen = pen; + itemChanged(); + } +} + +/*! + \brief Return the pen used to draw the lines + \sa setPen(), brush() +*/ +const QPen& QwtPlotIntervalCurve::pen() const +{ + return d_data->pen; +} + +/*! + Assign a brush. + + The brush is used to fill the area in Tube style(). + + \param brush Brush + \sa brush(), pen(), setStyle(), CurveStyle +*/ +void QwtPlotIntervalCurve::setBrush( const QBrush &brush ) +{ + if ( brush != d_data->brush ) + { + d_data->brush = brush; + itemChanged(); + } +} + +/*! + \return Brush used to fill the area in Tube style() + \sa setBrush(), setStyle(), CurveStyle +*/ +const QBrush& QwtPlotIntervalCurve::brush() const +{ + return d_data->brush; +} + +/*! + \return Bounding rectangle of all samples. + For an empty series the rectangle is invalid. +*/ +QRectF QwtPlotIntervalCurve::boundingRect() const +{ + QRectF rect = QwtPlotSeriesItem::boundingRect(); + if ( rect.isValid() && orientation() == Qt::Vertical ) + rect.setRect( rect.y(), rect.x(), rect.height(), rect.width() ); + + return rect; +} + +/*! + Draw a subset of the samples + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rect of the canvas + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + series will be painted to its last sample. + + \sa drawTube(), drawSymbols() +*/ +void QwtPlotIntervalCurve::drawSeries( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + if ( to < 0 ) + to = dataSize() - 1; + + if ( from < 0 ) + from = 0; + + if ( from > to ) + return; + + switch ( d_data->style ) + { + case Tube: + drawTube( painter, xMap, yMap, canvasRect, from, to ); + break; + + case NoCurve: + default: + break; + } + + if ( d_data->symbol && + ( d_data->symbol->style() != QwtIntervalSymbol::NoSymbol ) ) + { + drawSymbols( painter, *d_data->symbol, + xMap, yMap, canvasRect, from, to ); + } +} + +/*! + Draw a tube + + Builds 2 curves from the upper and lower limits of the intervals + and draws them with the pen(). The area between the curves is + filled with the brush(). + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rect of the canvas + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted. If to < 0 the + series will be painted to its last sample. + + \sa drawSeries(), drawSymbols() +*/ +void QwtPlotIntervalCurve::drawTube( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + const bool doAlign = QwtPainter::roundingAlignment( painter ); + + painter->save(); + + const size_t size = to - from + 1; + QPolygonF polygon( 2 * size ); + QPointF *points = polygon.data(); + + for ( uint i = 0; i < size; i++ ) + { + QPointF &minValue = points[i]; + QPointF &maxValue = points[2 * size - 1 - i]; + + const QwtIntervalSample intervalSample = sample( from + i ); + if ( orientation() == Qt::Vertical ) + { + double x = xMap.transform( intervalSample.value ); + double y1 = yMap.transform( intervalSample.interval.minValue() ); + double y2 = yMap.transform( intervalSample.interval.maxValue() ); + if ( doAlign ) + { + x = qRound( x ); + y1 = qRound( y1 ); + y2 = qRound( y2 ); + } + + minValue.rx() = x; + minValue.ry() = y1; + maxValue.rx() = x; + maxValue.ry() = y2; + } + else + { + double y = yMap.transform( intervalSample.value ); + double x1 = xMap.transform( intervalSample.interval.minValue() ); + double x2 = xMap.transform( intervalSample.interval.maxValue() ); + if ( doAlign ) + { + y = qRound( y ); + x1 = qRound( x1 ); + x2 = qRound( x2 ); + } + + minValue.rx() = x1; + minValue.ry() = y; + maxValue.rx() = x2; + maxValue.ry() = y; + } + } + + if ( d_data->brush.style() != Qt::NoBrush ) + { + painter->setPen( QPen( Qt::NoPen ) ); + painter->setBrush( d_data->brush ); + + if ( d_data->paintAttributes & ClipPolygons ) + { + const qreal m = 1.0; + const QPolygonF p = QwtClipper::clipPolygonF( + canvasRect.adjusted(-m, -m, m, m), polygon, true ); + + QwtPainter::drawPolygon( painter, p ); + } + else + { + QwtPainter::drawPolygon( painter, polygon ); + } + } + + if ( d_data->pen.style() != Qt::NoPen ) + { + painter->setPen( d_data->pen ); + painter->setBrush( Qt::NoBrush ); + + if ( d_data->paintAttributes & ClipPolygons ) + { + qreal pw = qMax( qreal( 1.0 ), painter->pen().widthF()); + const QRectF clipRect = canvasRect.adjusted(-pw, -pw, pw, pw); + + QPolygonF p; + + p.resize( size ); + qMemCopy( p.data(), points, size * sizeof( QPointF ) ); + p = QwtClipper::clipPolygonF( canvasRect, p ); + QwtPainter::drawPolyline( painter, p ); + + p.resize( size ); + qMemCopy( p.data(), points + size, size * sizeof( QPointF ) ); + p = QwtClipper::clipPolygonF( canvasRect, p ); + QwtPainter::drawPolyline( painter, p ); + } + else + { + QwtPainter::drawPolyline( painter, points, size ); + QwtPainter::drawPolyline( painter, points + size, size ); + } + } + + painter->restore(); +} + +/*! + Draw symbols for a subset of the samples + + \param painter Painter + \param symbol Interval symbol + \param xMap x map + \param yMap y map + \param canvasRect Contents rect of the canvas + \param from Index of the first sample to be painted + \param to Index of the last sample to be painted + + \sa setSymbol(), drawSeries(), drawTube() +*/ +void QwtPlotIntervalCurve::drawSymbols( + QPainter *painter, const QwtIntervalSymbol &symbol, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const +{ + painter->save(); + + QPen pen = symbol.pen(); + pen.setCapStyle( Qt::FlatCap ); + + painter->setPen( pen ); + painter->setBrush( symbol.brush() ); + + const QRectF &tr = QwtScaleMap::invTransform( xMap, yMap, canvasRect); + + const double xMin = tr.left(); + const double xMax = tr.right(); + const double yMin = tr.top(); + const double yMax = tr.bottom(); + + const bool doClip = d_data->paintAttributes & ClipPolygons; + + for ( int i = from; i <= to; i++ ) + { + const QwtIntervalSample s = sample( i ); + + if ( orientation() == Qt::Vertical ) + { + if ( !doClip || qwtIsVSampleInside( s, xMin, xMax, yMin, yMax ) ) + { + const double x = xMap.transform( s.value ); + const double y1 = yMap.transform( s.interval.minValue() ); + const double y2 = yMap.transform( s.interval.maxValue() ); + + symbol.draw( painter, orientation(), + QPointF( x, y1 ), QPointF( x, y2 ) ); + } + } + else + { + if ( !doClip || qwtIsHSampleInside( s, xMin, xMax, yMin, yMax ) ) + { + const double y = yMap.transform( s.value ); + const double x1 = xMap.transform( s.interval.minValue() ); + const double x2 = xMap.transform( s.interval.maxValue() ); + + symbol.draw( painter, orientation(), + QPointF( x1, y ), QPointF( x2, y ) ); + } + } + } + + painter->restore(); +} + +/*! + In case of Tibe stale() a plain rectangle is painted without a pen filled + the brush(). If a symbol is assigned it is painted cebtered into rect. + + \param painter Painter + \param rect Bounding rectangle for the identifier +*/ + +void QwtPlotIntervalCurve::drawLegendIdentifier( + QPainter *painter, const QRectF &rect ) const +{ + const double dim = qMin( rect.width(), rect.height() ); + + QSizeF size( dim, dim ); + + QRectF r( 0, 0, size.width(), size.height() ); + r.moveCenter( rect.center() ); + + if ( d_data->style == Tube ) + { + painter->fillRect( r, d_data->brush ); + } + + if ( d_data->symbol && + ( d_data->symbol->style() != QwtIntervalSymbol::NoSymbol ) ) + { + QPen pen = d_data->symbol->pen(); + pen.setWidthF( pen.widthF() ); + pen.setCapStyle( Qt::FlatCap ); + + painter->setPen( pen ); + painter->setBrush( d_data->symbol->brush() ); + + if ( orientation() == Qt::Vertical ) + { + d_data->symbol->draw( painter, orientation(), + QPointF( r.center().x(), r.top() ), + QPointF( r.center().x(), r.bottom() - 1 ) ); + } + else + { + d_data->symbol->draw( painter, orientation(), + QPointF( r.left(), r.center().y() ), + QPointF( r.right() - 1, r.center().y() ) ); + } + } +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_intervalcurve.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_intervalcurve.h index b63f44ea4..b26586e64 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_intervalcurve.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_intervalcurve.h @@ -1,130 +1,130 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PLOT_INTERVAL_CURVE_H -#define QWT_PLOT_INTERVAL_CURVE_H - -#include "qwt_global.h" -#include "qwt_plot_seriesitem.h" -#include "qwt_series_data.h" - -class QwtIntervalSymbol; - -/*! - \brief QwtPlotIntervalCurve represents a series of samples, where each value - is associated with an interval ( \f$[y1,y2] = f(x)\f$ ). - - The representation depends on the style() and an optional symbol() - that is displayed for each interval. QwtPlotIntervalCurve might be used - to disply error bars or the area between 2 curves. -*/ - -class QWT_EXPORT QwtPlotIntervalCurve: public QwtPlotSeriesItem -{ -public: - /*! - \brief Curve styles. - The default setting is QwtPlotIntervalCurve::Tube. - - \sa setStyle(), style() - */ - - enum CurveStyle - { - /*! - Don't draw a curve. Note: This doesn't affect the symbols. - */ - NoCurve, - - /*! - Build 2 curves from the upper and lower limits of the intervals - and draw them with the pen(). The area between the curves is - filled with the brush(). - */ - Tube, - - /*! - Styles >= QwtPlotIntervalCurve::UserCurve are reserved for derived - classes that overload drawSeries() with - additional application specific curve types. - */ - UserCurve = 100 - }; - - /*! - Attributes to modify the drawing algorithm. - \sa setPaintAttribute(), testPaintAttribute() - */ - enum PaintAttribute - { - /*! - Clip polygons before painting them. In situations, where points - are far outside the visible area (f.e when zooming deep) this - might be a substantial improvement for the painting performance. - */ - ClipPolygons = 0x01, - - //! Check if a symbol is on the plot canvas before painting it. - ClipSymbol = 0x02 - }; - - //! Paint attributes - typedef QFlags PaintAttributes; - - explicit QwtPlotIntervalCurve( const QString &title = QString::null ); - explicit QwtPlotIntervalCurve( const QwtText &title ); - - virtual ~QwtPlotIntervalCurve(); - - virtual int rtti() const; - - void setPaintAttribute( PaintAttribute, bool on = true ); - bool testPaintAttribute( PaintAttribute ) const; - - void setSamples( const QVector & ); - - void setPen( const QPen & ); - const QPen &pen() const; - - void setBrush( const QBrush & ); - const QBrush &brush() const; - - void setStyle( CurveStyle style ); - CurveStyle style() const; - - void setSymbol( const QwtIntervalSymbol * ); - const QwtIntervalSymbol *symbol() const; - - virtual void drawSeries( QPainter *p, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - - virtual QRectF boundingRect() const; - virtual void drawLegendIdentifier( QPainter *, const QRectF & ) const; - -protected: - - void init(); - - virtual void drawTube( QPainter *, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - - virtual void drawSymbols( QPainter *, const QwtIntervalSymbol &, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect, int from, int to ) const; - -private: - class PrivateData; - PrivateData *d_data; -}; - -Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotIntervalCurve::PaintAttributes ) - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_INTERVAL_CURVE_H +#define QWT_PLOT_INTERVAL_CURVE_H + +#include "qwt_global.h" +#include "qwt_plot_seriesitem.h" +#include "qwt_series_data.h" + +class QwtIntervalSymbol; + +/*! + \brief QwtPlotIntervalCurve represents a series of samples, where each value + is associated with an interval ( \f$[y1,y2] = f(x)\f$ ). + + The representation depends on the style() and an optional symbol() + that is displayed for each interval. QwtPlotIntervalCurve might be used + to disply error bars or the area between 2 curves. +*/ + +class QWT_EXPORT QwtPlotIntervalCurve: public QwtPlotSeriesItem +{ +public: + /*! + \brief Curve styles. + The default setting is QwtPlotIntervalCurve::Tube. + + \sa setStyle(), style() + */ + + enum CurveStyle + { + /*! + Don't draw a curve. Note: This doesn't affect the symbols. + */ + NoCurve, + + /*! + Build 2 curves from the upper and lower limits of the intervals + and draw them with the pen(). The area between the curves is + filled with the brush(). + */ + Tube, + + /*! + Styles >= QwtPlotIntervalCurve::UserCurve are reserved for derived + classes that overload drawSeries() with + additional application specific curve types. + */ + UserCurve = 100 + }; + + /*! + Attributes to modify the drawing algorithm. + \sa setPaintAttribute(), testPaintAttribute() + */ + enum PaintAttribute + { + /*! + Clip polygons before painting them. In situations, where points + are far outside the visible area (f.e when zooming deep) this + might be a substantial improvement for the painting performance. + */ + ClipPolygons = 0x01, + + //! Check if a symbol is on the plot canvas before painting it. + ClipSymbol = 0x02 + }; + + //! Paint attributes + typedef QFlags PaintAttributes; + + explicit QwtPlotIntervalCurve( const QString &title = QString::null ); + explicit QwtPlotIntervalCurve( const QwtText &title ); + + virtual ~QwtPlotIntervalCurve(); + + virtual int rtti() const; + + void setPaintAttribute( PaintAttribute, bool on = true ); + bool testPaintAttribute( PaintAttribute ) const; + + void setSamples( const QVector & ); + + void setPen( const QPen & ); + const QPen &pen() const; + + void setBrush( const QBrush & ); + const QBrush &brush() const; + + void setStyle( CurveStyle style ); + CurveStyle style() const; + + void setSymbol( const QwtIntervalSymbol * ); + const QwtIntervalSymbol *symbol() const; + + virtual void drawSeries( QPainter *p, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual QRectF boundingRect() const; + virtual void drawLegendIdentifier( QPainter *, const QRectF & ) const; + +protected: + + void init(); + + virtual void drawTube( QPainter *, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + + virtual void drawSymbols( QPainter *, const QwtIntervalSymbol &, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect, int from, int to ) const; + +private: + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotIntervalCurve::PaintAttributes ) + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_item.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_item.cpp index cbbfb99af..e814e7e2e 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_item.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_item.cpp @@ -1,542 +1,542 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot_item.h" -#include "qwt_text.h" -#include "qwt_plot.h" -#include "qwt_legend.h" -#include "qwt_legend_item.h" -#include "qwt_scale_div.h" -#include - -class QwtPlotItem::PrivateData -{ -public: - PrivateData(): - plot( NULL ), - isVisible( true ), - attributes( 0 ), - renderHints( 0 ), - z( 0.0 ), - xAxis( QwtPlot::xBottom ), - yAxis( QwtPlot::yLeft ) - { - } - - mutable QwtPlot *plot; - - bool isVisible; - QwtPlotItem::ItemAttributes attributes; - QwtPlotItem::RenderHints renderHints; - double z; - - int xAxis; - int yAxis; - - QwtText title; -}; - -/*! - Constructor - \param title Title of the item -*/ -QwtPlotItem::QwtPlotItem( const QwtText &title ) -{ - d_data = new PrivateData; - d_data->title = title; -} - -//! Destroy the QwtPlotItem -QwtPlotItem::~QwtPlotItem() -{ - attach( NULL ); - delete d_data; -} - -/*! - \brief Attach the item to a plot. - - This method will attach a QwtPlotItem to the QwtPlot argument. It will first - detach the QwtPlotItem from any plot from a previous call to attach (if - necessary). If a NULL argument is passed, it will detach from any QwtPlot it - was attached to. - - \param plot Plot widget - \sa detach() -*/ -void QwtPlotItem::attach( QwtPlot *plot ) -{ - if ( plot == d_data->plot ) - return; - - // remove the item from the previous plot - - if ( d_data->plot ) - { - if ( d_data->plot->legend() ) - d_data->plot->legend()->remove( this ); - - d_data->plot->attachItem( this, false ); - - if ( d_data->plot->autoReplot() ) - d_data->plot->update(); - } - - d_data->plot = plot; - - if ( d_data->plot ) - { - // insert the item into the current plot - - d_data->plot->attachItem( this, true ); - itemChanged(); - } -} - -/*! - \brief This method detaches a QwtPlotItem from any - QwtPlot it has been associated with. - - detach() is equivalent to calling attach( NULL ) - \sa attach() -*/ -void QwtPlotItem::detach() -{ - attach( NULL ); -} - -/*! - Return rtti for the specific class represented. QwtPlotItem is simply - a virtual interface class, and base classes will implement this method - with specific rtti values so a user can differentiate them. - - The rtti value is useful for environments, where the - runtime type information is disabled and it is not possible - to do a dynamic_cast<...>. - - \return rtti value - \sa RttiValues -*/ -int QwtPlotItem::rtti() const -{ - return Rtti_PlotItem; -} - -//! Return attached plot -QwtPlot *QwtPlotItem::plot() const -{ - return d_data->plot; -} - -/*! - Plot items are painted in increasing z-order. - - \return setZ(), QwtPlotDict::itemList() -*/ -double QwtPlotItem::z() const -{ - return d_data->z; -} - -/*! - \brief Set the z value - - Plot items are painted in increasing z-order. - - \param z Z-value - \sa z(), QwtPlotDict::itemList() -*/ -void QwtPlotItem::setZ( double z ) -{ - if ( d_data->z != z ) - { - if ( d_data->plot ) // update the z order - d_data->plot->attachItem( this, false ); - - d_data->z = z; - - if ( d_data->plot ) - d_data->plot->attachItem( this, true ); - - itemChanged(); - } -} - -/*! - Set a new title - - \param title Title - \sa title() -*/ -void QwtPlotItem::setTitle( const QString &title ) -{ - setTitle( QwtText( title ) ); -} - -/*! - Set a new title - - \param title Title - \sa title() -*/ -void QwtPlotItem::setTitle( const QwtText &title ) -{ - if ( d_data->title != title ) - { - d_data->title = title; - itemChanged(); - } -} - -/*! - \return Title of the item - \sa setTitle() -*/ -const QwtText &QwtPlotItem::title() const -{ - return d_data->title; -} - -/*! - Toggle an item attribute - - \param attribute Attribute type - \param on true/false - - \sa testItemAttribute(), ItemAttribute -*/ -void QwtPlotItem::setItemAttribute( ItemAttribute attribute, bool on ) -{ - if ( bool( d_data->attributes & attribute ) != on ) - { - if ( on ) - d_data->attributes |= attribute; - else - d_data->attributes &= ~attribute; - - itemChanged(); - } -} - -/*! - Test an item attribute - - \param attribute Attribute type - \return true/false - \sa setItemAttribute(), ItemAttribute -*/ -bool QwtPlotItem::testItemAttribute( ItemAttribute attribute ) const -{ - return ( d_data->attributes & attribute ); -} - -/*! - Toggle an render hint - - \param hint Render hint - \param on true/false - - \sa testRenderHint(), RenderHint -*/ -void QwtPlotItem::setRenderHint( RenderHint hint, bool on ) -{ - if ( ( ( d_data->renderHints & hint ) != 0 ) != on ) - { - if ( on ) - d_data->renderHints |= hint; - else - d_data->renderHints &= ~hint; - - itemChanged(); - } -} - -/*! - Test a render hint - - \param hint Render hint - \return true/false - \sa setRenderHint(), RenderHint -*/ -bool QwtPlotItem::testRenderHint( RenderHint hint ) const -{ - return ( d_data->renderHints & hint ); -} - -//! Show the item -void QwtPlotItem::show() -{ - setVisible( true ); -} - -//! Hide the item -void QwtPlotItem::hide() -{ - setVisible( false ); -} - -/*! - Show/Hide the item - - \param on Show if true, otherwise hide - \sa isVisible(), show(), hide() -*/ -void QwtPlotItem::setVisible( bool on ) -{ - if ( on != d_data->isVisible ) - { - d_data->isVisible = on; - itemChanged(); - } -} - -/*! - \return true if visible - \sa setVisible(), show(), hide() -*/ -bool QwtPlotItem::isVisible() const -{ - return d_data->isVisible; -} - -/*! - Update the legend and call QwtPlot::autoRefresh for the - parent plot. - - \sa updateLegend() -*/ -void QwtPlotItem::itemChanged() -{ - if ( d_data->plot ) - { - if ( d_data->plot->legend() ) - updateLegend( d_data->plot->legend() ); - - d_data->plot->autoRefresh(); - } -} - -/*! - Set X and Y axis - - The item will painted according to the coordinates its Axes. - - \param xAxis X Axis - \param yAxis Y Axis - - \sa setXAxis(), setYAxis(), xAxis(), yAxis() -*/ -void QwtPlotItem::setAxes( int xAxis, int yAxis ) -{ - if ( xAxis == QwtPlot::xBottom || xAxis == QwtPlot::xTop ) - d_data->xAxis = xAxis; - - if ( yAxis == QwtPlot::yLeft || yAxis == QwtPlot::yRight ) - d_data->yAxis = yAxis; - - itemChanged(); -} - -/*! - Set the X axis - - The item will painted according to the coordinates its Axes. - - \param axis X Axis - \sa setAxes(), setYAxis(), xAxis() -*/ -void QwtPlotItem::setXAxis( int axis ) -{ - if ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) - { - d_data->xAxis = axis; - itemChanged(); - } -} - -/*! - Set the Y axis - - The item will painted according to the coordinates its Axes. - - \param axis Y Axis - \sa setAxes(), setXAxis(), yAxis() -*/ -void QwtPlotItem::setYAxis( int axis ) -{ - if ( axis == QwtPlot::yLeft || axis == QwtPlot::yRight ) - { - d_data->yAxis = axis; - itemChanged(); - } -} - -//! Return xAxis -int QwtPlotItem::xAxis() const -{ - return d_data->xAxis; -} - -//! Return yAxis -int QwtPlotItem::yAxis() const -{ - return d_data->yAxis; -} - -/*! - \return An invalid bounding rect: QRectF(1.0, 1.0, -2.0, -2.0) -*/ -QRectF QwtPlotItem::boundingRect() const -{ - return QRectF( 1.0, 1.0, -2.0, -2.0 ); // invalid -} - -/*! - \brief Allocate the widget that represents the item on the legend - - The default implementation returns a QwtLegendItem(), but an item - could be represented by any type of widget, - by overloading legendItem() and updateLegend(). - - \return QwtLegendItem() - \sa updateLegend() QwtLegend() -*/ -QWidget *QwtPlotItem::legendItem() const -{ - QwtLegendItem *item = new QwtLegendItem; - if ( d_data->plot ) - { - QObject::connect( item, SIGNAL( clicked() ), - d_data->plot, SLOT( legendItemClicked() ) ); - QObject::connect( item, SIGNAL( checked( bool ) ), - d_data->plot, SLOT( legendItemChecked( bool ) ) ); - } - return item; -} - -/*! - \brief Update the widget that represents the item on the legend - - updateLegend() is called from itemChanged() to adopt the widget - representing the item on the legend to its new configuration. - - The default implementation updates a QwtLegendItem(), - but an item could be represented by any type of widget, - by overloading legendItem() and updateLegend(). - - \param legend Legend - - \sa legendItem(), itemChanged(), QwtLegend() -*/ -void QwtPlotItem::updateLegend( QwtLegend *legend ) const -{ - if ( legend == NULL ) - return; - - QWidget *lgdItem = legend->find( this ); - if ( testItemAttribute( QwtPlotItem::Legend ) ) - { - if ( lgdItem == NULL ) - { - lgdItem = legendItem(); - if ( lgdItem ) - legend->insert( this, lgdItem ); - } - - QwtLegendItem *label = qobject_cast( lgdItem ); - if ( label ) - { - // paint the identifier - const QSize sz = label->identifierSize(); - - QPixmap identifier( sz.width(), sz.height() ); - identifier.fill( Qt::transparent ); - - QPainter painter( &identifier ); - painter.setRenderHint( QPainter::Antialiasing, - testRenderHint( QwtPlotItem::RenderAntialiased ) ); - drawLegendIdentifier( &painter, - QRect( 0, 0, sz.width(), sz.height() ) ); - painter.end(); - - const bool doUpdate = label->updatesEnabled(); - if ( doUpdate ) - label->setUpdatesEnabled( false ); - - label->setText( title() ); - label->setIdentifier( identifier ); - label->setItemMode( legend->itemMode() ); - - if ( doUpdate ) - label->setUpdatesEnabled( true ); - - label->update(); - } - } - else - { - if ( lgdItem ) - { - lgdItem->hide(); - lgdItem->deleteLater(); - } - } -} - -/*! - \brief Update the item to changes of the axes scale division - - Update the item, when the axes of plot have changed. - The default implementation does nothing, but items that depend - on the scale division (like QwtPlotGrid()) have to reimplement - updateScaleDiv() - - \param xScaleDiv Scale division of the x-axis - \param yScaleDiv Scale division of the y-axis - - \sa QwtPlot::updateAxes() -*/ -void QwtPlotItem::updateScaleDiv( const QwtScaleDiv &xScaleDiv, - const QwtScaleDiv &yScaleDiv ) -{ - Q_UNUSED( xScaleDiv ); - Q_UNUSED( yScaleDiv ); -} - -/*! - \brief Calculate the bounding scale rect of 2 maps - - \param xMap X map - \param yMap X map - - \return Bounding scale rect of the scale maps, normalized -*/ -QRectF QwtPlotItem::scaleRect( const QwtScaleMap &xMap, - const QwtScaleMap &yMap ) const -{ - return QRectF( xMap.s1(), yMap.s1(), - xMap.sDist(), yMap.sDist() ); -} - -/*! - \brief Calculate the bounding paint rect of 2 maps - - \param xMap X map - \param yMap X map - - \return Bounding paint rect of the scale maps, normalized -*/ -QRectF QwtPlotItem::paintRect( const QwtScaleMap &xMap, - const QwtScaleMap &yMap ) const -{ - const QRectF rect( xMap.p1(), yMap.p1(), - xMap.pDist(), yMap.pDist() ); - - return rect; -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_item.h" +#include "qwt_text.h" +#include "qwt_plot.h" +#include "qwt_legend.h" +#include "qwt_legend_item.h" +#include "qwt_scale_div.h" +#include + +class QwtPlotItem::PrivateData +{ +public: + PrivateData(): + plot( NULL ), + isVisible( true ), + attributes( 0 ), + renderHints( 0 ), + z( 0.0 ), + xAxis( QwtPlot::xBottom ), + yAxis( QwtPlot::yLeft ) + { + } + + mutable QwtPlot *plot; + + bool isVisible; + QwtPlotItem::ItemAttributes attributes; + QwtPlotItem::RenderHints renderHints; + double z; + + int xAxis; + int yAxis; + + QwtText title; +}; + +/*! + Constructor + \param title Title of the item +*/ +QwtPlotItem::QwtPlotItem( const QwtText &title ) +{ + d_data = new PrivateData; + d_data->title = title; +} + +//! Destroy the QwtPlotItem +QwtPlotItem::~QwtPlotItem() +{ + attach( NULL ); + delete d_data; +} + +/*! + \brief Attach the item to a plot. + + This method will attach a QwtPlotItem to the QwtPlot argument. It will first + detach the QwtPlotItem from any plot from a previous call to attach (if + necessary). If a NULL argument is passed, it will detach from any QwtPlot it + was attached to. + + \param plot Plot widget + \sa detach() +*/ +void QwtPlotItem::attach( QwtPlot *plot ) +{ + if ( plot == d_data->plot ) + return; + + // remove the item from the previous plot + + if ( d_data->plot ) + { + if ( d_data->plot->legend() ) + d_data->plot->legend()->remove( this ); + + d_data->plot->attachItem( this, false ); + + if ( d_data->plot->autoReplot() ) + d_data->plot->update(); + } + + d_data->plot = plot; + + if ( d_data->plot ) + { + // insert the item into the current plot + + d_data->plot->attachItem( this, true ); + itemChanged(); + } +} + +/*! + \brief This method detaches a QwtPlotItem from any + QwtPlot it has been associated with. + + detach() is equivalent to calling attach( NULL ) + \sa attach() +*/ +void QwtPlotItem::detach() +{ + attach( NULL ); +} + +/*! + Return rtti for the specific class represented. QwtPlotItem is simply + a virtual interface class, and base classes will implement this method + with specific rtti values so a user can differentiate them. + + The rtti value is useful for environments, where the + runtime type information is disabled and it is not possible + to do a dynamic_cast<...>. + + \return rtti value + \sa RttiValues +*/ +int QwtPlotItem::rtti() const +{ + return Rtti_PlotItem; +} + +//! Return attached plot +QwtPlot *QwtPlotItem::plot() const +{ + return d_data->plot; +} + +/*! + Plot items are painted in increasing z-order. + + \return setZ(), QwtPlotDict::itemList() +*/ +double QwtPlotItem::z() const +{ + return d_data->z; +} + +/*! + \brief Set the z value + + Plot items are painted in increasing z-order. + + \param z Z-value + \sa z(), QwtPlotDict::itemList() +*/ +void QwtPlotItem::setZ( double z ) +{ + if ( d_data->z != z ) + { + if ( d_data->plot ) // update the z order + d_data->plot->attachItem( this, false ); + + d_data->z = z; + + if ( d_data->plot ) + d_data->plot->attachItem( this, true ); + + itemChanged(); + } +} + +/*! + Set a new title + + \param title Title + \sa title() +*/ +void QwtPlotItem::setTitle( const QString &title ) +{ + setTitle( QwtText( title ) ); +} + +/*! + Set a new title + + \param title Title + \sa title() +*/ +void QwtPlotItem::setTitle( const QwtText &title ) +{ + if ( d_data->title != title ) + { + d_data->title = title; + itemChanged(); + } +} + +/*! + \return Title of the item + \sa setTitle() +*/ +const QwtText &QwtPlotItem::title() const +{ + return d_data->title; +} + +/*! + Toggle an item attribute + + \param attribute Attribute type + \param on true/false + + \sa testItemAttribute(), ItemAttribute +*/ +void QwtPlotItem::setItemAttribute( ItemAttribute attribute, bool on ) +{ + if ( bool( d_data->attributes & attribute ) != on ) + { + if ( on ) + d_data->attributes |= attribute; + else + d_data->attributes &= ~attribute; + + itemChanged(); + } +} + +/*! + Test an item attribute + + \param attribute Attribute type + \return true/false + \sa setItemAttribute(), ItemAttribute +*/ +bool QwtPlotItem::testItemAttribute( ItemAttribute attribute ) const +{ + return ( d_data->attributes & attribute ); +} + +/*! + Toggle an render hint + + \param hint Render hint + \param on true/false + + \sa testRenderHint(), RenderHint +*/ +void QwtPlotItem::setRenderHint( RenderHint hint, bool on ) +{ + if ( ( ( d_data->renderHints & hint ) != 0 ) != on ) + { + if ( on ) + d_data->renderHints |= hint; + else + d_data->renderHints &= ~hint; + + itemChanged(); + } +} + +/*! + Test a render hint + + \param hint Render hint + \return true/false + \sa setRenderHint(), RenderHint +*/ +bool QwtPlotItem::testRenderHint( RenderHint hint ) const +{ + return ( d_data->renderHints & hint ); +} + +//! Show the item +void QwtPlotItem::show() +{ + setVisible( true ); +} + +//! Hide the item +void QwtPlotItem::hide() +{ + setVisible( false ); +} + +/*! + Show/Hide the item + + \param on Show if true, otherwise hide + \sa isVisible(), show(), hide() +*/ +void QwtPlotItem::setVisible( bool on ) +{ + if ( on != d_data->isVisible ) + { + d_data->isVisible = on; + itemChanged(); + } +} + +/*! + \return true if visible + \sa setVisible(), show(), hide() +*/ +bool QwtPlotItem::isVisible() const +{ + return d_data->isVisible; +} + +/*! + Update the legend and call QwtPlot::autoRefresh for the + parent plot. + + \sa updateLegend() +*/ +void QwtPlotItem::itemChanged() +{ + if ( d_data->plot ) + { + if ( d_data->plot->legend() ) + updateLegend( d_data->plot->legend() ); + + d_data->plot->autoRefresh(); + } +} + +/*! + Set X and Y axis + + The item will painted according to the coordinates its Axes. + + \param xAxis X Axis + \param yAxis Y Axis + + \sa setXAxis(), setYAxis(), xAxis(), yAxis() +*/ +void QwtPlotItem::setAxes( int xAxis, int yAxis ) +{ + if ( xAxis == QwtPlot::xBottom || xAxis == QwtPlot::xTop ) + d_data->xAxis = xAxis; + + if ( yAxis == QwtPlot::yLeft || yAxis == QwtPlot::yRight ) + d_data->yAxis = yAxis; + + itemChanged(); +} + +/*! + Set the X axis + + The item will painted according to the coordinates its Axes. + + \param axis X Axis + \sa setAxes(), setYAxis(), xAxis() +*/ +void QwtPlotItem::setXAxis( int axis ) +{ + if ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) + { + d_data->xAxis = axis; + itemChanged(); + } +} + +/*! + Set the Y axis + + The item will painted according to the coordinates its Axes. + + \param axis Y Axis + \sa setAxes(), setXAxis(), yAxis() +*/ +void QwtPlotItem::setYAxis( int axis ) +{ + if ( axis == QwtPlot::yLeft || axis == QwtPlot::yRight ) + { + d_data->yAxis = axis; + itemChanged(); + } +} + +//! Return xAxis +int QwtPlotItem::xAxis() const +{ + return d_data->xAxis; +} + +//! Return yAxis +int QwtPlotItem::yAxis() const +{ + return d_data->yAxis; +} + +/*! + \return An invalid bounding rect: QRectF(1.0, 1.0, -2.0, -2.0) +*/ +QRectF QwtPlotItem::boundingRect() const +{ + return QRectF( 1.0, 1.0, -2.0, -2.0 ); // invalid +} + +/*! + \brief Allocate the widget that represents the item on the legend + + The default implementation returns a QwtLegendItem(), but an item + could be represented by any type of widget, + by overloading legendItem() and updateLegend(). + + \return QwtLegendItem() + \sa updateLegend() QwtLegend() +*/ +QWidget *QwtPlotItem::legendItem() const +{ + QwtLegendItem *item = new QwtLegendItem; + if ( d_data->plot ) + { + QObject::connect( item, SIGNAL( clicked() ), + d_data->plot, SLOT( legendItemClicked() ) ); + QObject::connect( item, SIGNAL( checked( bool ) ), + d_data->plot, SLOT( legendItemChecked( bool ) ) ); + } + return item; +} + +/*! + \brief Update the widget that represents the item on the legend + + updateLegend() is called from itemChanged() to adopt the widget + representing the item on the legend to its new configuration. + + The default implementation updates a QwtLegendItem(), + but an item could be represented by any type of widget, + by overloading legendItem() and updateLegend(). + + \param legend Legend + + \sa legendItem(), itemChanged(), QwtLegend() +*/ +void QwtPlotItem::updateLegend( QwtLegend *legend ) const +{ + if ( legend == NULL ) + return; + + QWidget *lgdItem = legend->find( this ); + if ( testItemAttribute( QwtPlotItem::Legend ) ) + { + if ( lgdItem == NULL ) + { + lgdItem = legendItem(); + if ( lgdItem ) + legend->insert( this, lgdItem ); + } + + QwtLegendItem *label = qobject_cast( lgdItem ); + if ( label ) + { + // paint the identifier + const QSize sz = label->identifierSize(); + + QPixmap identifier( sz.width(), sz.height() ); + identifier.fill( Qt::transparent ); + + QPainter painter( &identifier ); + painter.setRenderHint( QPainter::Antialiasing, + testRenderHint( QwtPlotItem::RenderAntialiased ) ); + drawLegendIdentifier( &painter, + QRect( 0, 0, sz.width(), sz.height() ) ); + painter.end(); + + const bool doUpdate = label->updatesEnabled(); + if ( doUpdate ) + label->setUpdatesEnabled( false ); + + label->setText( title() ); + label->setIdentifier( identifier ); + label->setItemMode( legend->itemMode() ); + + if ( doUpdate ) + label->setUpdatesEnabled( true ); + + label->update(); + } + } + else + { + if ( lgdItem ) + { + lgdItem->hide(); + lgdItem->deleteLater(); + } + } +} + +/*! + \brief Update the item to changes of the axes scale division + + Update the item, when the axes of plot have changed. + The default implementation does nothing, but items that depend + on the scale division (like QwtPlotGrid()) have to reimplement + updateScaleDiv() + + \param xScaleDiv Scale division of the x-axis + \param yScaleDiv Scale division of the y-axis + + \sa QwtPlot::updateAxes() +*/ +void QwtPlotItem::updateScaleDiv( const QwtScaleDiv &xScaleDiv, + const QwtScaleDiv &yScaleDiv ) +{ + Q_UNUSED( xScaleDiv ); + Q_UNUSED( yScaleDiv ); +} + +/*! + \brief Calculate the bounding scale rect of 2 maps + + \param xMap X map + \param yMap X map + + \return Bounding scale rect of the scale maps, normalized +*/ +QRectF QwtPlotItem::scaleRect( const QwtScaleMap &xMap, + const QwtScaleMap &yMap ) const +{ + return QRectF( xMap.s1(), yMap.s1(), + xMap.sDist(), yMap.sDist() ); +} + +/*! + \brief Calculate the bounding paint rect of 2 maps + + \param xMap X map + \param yMap X map + + \return Bounding paint rect of the scale maps, normalized +*/ +QRectF QwtPlotItem::paintRect( const QwtScaleMap &xMap, + const QwtScaleMap &yMap ) const +{ + const QRectF rect( xMap.p1(), yMap.p1(), + xMap.pDist(), yMap.pDist() ); + + return rect; +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_item.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_item.h index 3f8f82e1c..16c61a766 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_item.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_item.h @@ -1,192 +1,192 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PLOT_ITEM_H -#define QWT_PLOT_ITEM_H - -#include "qwt_global.h" -#include "qwt_legend_itemmanager.h" -#include "qwt_text.h" -#include - -class QString; -class QPainter; -class QWidget; -class QwtPlot; -class QwtLegend; -class QwtScaleMap; -class QwtScaleDiv; - -/*! - \brief Base class for items on the plot canvas - - A plot item is "something", that can be painted on the plot canvas, - or only affects the scales of the plot widget. They can be categorized as: - - - Representator\n - A "Representator" is an item that represents some sort of data - on the plot canvas. The different representator classes are organized - according to the characteristics of the data: - - QwtPlotMarker - Represents a point or a horizontal/vertical coordinate - - QwtPlotCurve - Represents a series of points - - QwtPlotSpectrogram ( QwtPlotRasterItem ) - Represents raster data - - ... - - - Decorators\n - A "Decorator" is an item, that displays additional information, that - is not related to any data: - - QwtPlotGrid - - QwtPlotScaleItem - - QwtPlotSvgItem - - ... - - Depending on the QwtPlotItem::ItemAttribute flags, an item is included - into autoscaling or has an entry on the legnd. - - Before misusing the existing item classes it might be better to - implement a new type of plot item - ( don't implement a watermark as spectrogram ). - Deriving a new type of QwtPlotItem primarily means to implement - the YourPlotItem::draw() method. - - \sa The cpuplot example shows the implementation of additional plot items. -*/ - -class QWT_EXPORT QwtPlotItem: public QwtLegendItemManager -{ -public: - /*! - \brief Runtime type information - - RttiValues is used to cast plot items, without - having to enable runtime type information of the compiler. - */ - enum RttiValues - { - Rtti_PlotItem = 0, - - Rtti_PlotGrid, - Rtti_PlotScale, - Rtti_PlotMarker, - Rtti_PlotCurve, - Rtti_PlotSpectroCurve, - Rtti_PlotIntervalCurve, - Rtti_PlotHistogram, - Rtti_PlotSpectrogram, - Rtti_PlotSVG, - - Rtti_PlotUserItem = 1000 - }; - - /*! - Plot Item Attributes - \sa setItemAttribute(), testItemAttribute() - */ - enum ItemAttribute - { - //! The item is represented on the legend. - Legend = 0x01, - - /*! - The boundingRect() of the item is included in the - autoscaling calculation. - */ - AutoScale = 0x02 - }; - - //! Plot Item Attributes - typedef QFlags ItemAttributes; - - //! Render hints - enum RenderHint - { - //! Enable antialiasing - RenderAntialiased = 1 - }; - - //! Render hints - typedef QFlags RenderHints; - - explicit QwtPlotItem( const QwtText &title = QwtText() ); - virtual ~QwtPlotItem(); - - void attach( QwtPlot *plot ); - void detach(); - - QwtPlot *plot() const; - - void setTitle( const QString &title ); - void setTitle( const QwtText &title ); - const QwtText &title() const; - - virtual int rtti() const; - - void setItemAttribute( ItemAttribute, bool on = true ); - bool testItemAttribute( ItemAttribute ) const; - - void setRenderHint( RenderHint, bool on = true ); - bool testRenderHint( RenderHint ) const; - - double z() const; - void setZ( double z ); - - void show(); - void hide(); - virtual void setVisible( bool ); - bool isVisible () const; - - void setAxes( int xAxis, int yAxis ); - - void setXAxis( int axis ); - int xAxis() const; - - void setYAxis( int axis ); - int yAxis() const; - - virtual void itemChanged(); - - /*! - \brief Draw the item - - \param painter Painter - \param xMap Maps x-values into pixel coordinates. - \param yMap Maps y-values into pixel coordinates. - \param canvasRect Contents rect of the canvas in painter coordinates - */ - virtual void draw( QPainter *painter, - const QwtScaleMap &xMap, const QwtScaleMap &yMap, - const QRectF &canvasRect ) const = 0; - - virtual QRectF boundingRect() const; - - virtual void updateLegend( QwtLegend * ) const; - virtual void updateScaleDiv( - const QwtScaleDiv&, const QwtScaleDiv& ); - - virtual QWidget *legendItem() const; - - QRectF scaleRect( const QwtScaleMap &, const QwtScaleMap & ) const; - QRectF paintRect( const QwtScaleMap &, const QwtScaleMap & ) const; - -private: - // Disabled copy constructor and operator= - QwtPlotItem( const QwtPlotItem & ); - QwtPlotItem &operator=( const QwtPlotItem & ); - - class PrivateData; - PrivateData *d_data; -}; - -Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotItem::ItemAttributes ) -Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotItem::RenderHints ) - -#endif +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#ifndef QWT_PLOT_ITEM_H +#define QWT_PLOT_ITEM_H + +#include "qwt_global.h" +#include "qwt_legend_itemmanager.h" +#include "qwt_text.h" +#include + +class QString; +class QPainter; +class QWidget; +class QwtPlot; +class QwtLegend; +class QwtScaleMap; +class QwtScaleDiv; + +/*! + \brief Base class for items on the plot canvas + + A plot item is "something", that can be painted on the plot canvas, + or only affects the scales of the plot widget. They can be categorized as: + + - Representator\n + A "Representator" is an item that represents some sort of data + on the plot canvas. The different representator classes are organized + according to the characteristics of the data: + - QwtPlotMarker + Represents a point or a horizontal/vertical coordinate + - QwtPlotCurve + Represents a series of points + - QwtPlotSpectrogram ( QwtPlotRasterItem ) + Represents raster data + - ... + + - Decorators\n + A "Decorator" is an item, that displays additional information, that + is not related to any data: + - QwtPlotGrid + - QwtPlotScaleItem + - QwtPlotSvgItem + - ... + + Depending on the QwtPlotItem::ItemAttribute flags, an item is included + into autoscaling or has an entry on the legnd. + + Before misusing the existing item classes it might be better to + implement a new type of plot item + ( don't implement a watermark as spectrogram ). + Deriving a new type of QwtPlotItem primarily means to implement + the YourPlotItem::draw() method. + + \sa The cpuplot example shows the implementation of additional plot items. +*/ + +class QWT_EXPORT QwtPlotItem: public QwtLegendItemManager +{ +public: + /*! + \brief Runtime type information + + RttiValues is used to cast plot items, without + having to enable runtime type information of the compiler. + */ + enum RttiValues + { + Rtti_PlotItem = 0, + + Rtti_PlotGrid, + Rtti_PlotScale, + Rtti_PlotMarker, + Rtti_PlotCurve, + Rtti_PlotSpectroCurve, + Rtti_PlotIntervalCurve, + Rtti_PlotHistogram, + Rtti_PlotSpectrogram, + Rtti_PlotSVG, + + Rtti_PlotUserItem = 1000 + }; + + /*! + Plot Item Attributes + \sa setItemAttribute(), testItemAttribute() + */ + enum ItemAttribute + { + //! The item is represented on the legend. + Legend = 0x01, + + /*! + The boundingRect() of the item is included in the + autoscaling calculation. + */ + AutoScale = 0x02 + }; + + //! Plot Item Attributes + typedef QFlags ItemAttributes; + + //! Render hints + enum RenderHint + { + //! Enable antialiasing + RenderAntialiased = 1 + }; + + //! Render hints + typedef QFlags RenderHints; + + explicit QwtPlotItem( const QwtText &title = QwtText() ); + virtual ~QwtPlotItem(); + + void attach( QwtPlot *plot ); + void detach(); + + QwtPlot *plot() const; + + void setTitle( const QString &title ); + void setTitle( const QwtText &title ); + const QwtText &title() const; + + virtual int rtti() const; + + void setItemAttribute( ItemAttribute, bool on = true ); + bool testItemAttribute( ItemAttribute ) const; + + void setRenderHint( RenderHint, bool on = true ); + bool testRenderHint( RenderHint ) const; + + double z() const; + void setZ( double z ); + + void show(); + void hide(); + virtual void setVisible( bool ); + bool isVisible () const; + + void setAxes( int xAxis, int yAxis ); + + void setXAxis( int axis ); + int xAxis() const; + + void setYAxis( int axis ); + int yAxis() const; + + virtual void itemChanged(); + + /*! + \brief Draw the item + + \param painter Painter + \param xMap Maps x-values into pixel coordinates. + \param yMap Maps y-values into pixel coordinates. + \param canvasRect Contents rect of the canvas in painter coordinates + */ + virtual void draw( QPainter *painter, + const QwtScaleMap &xMap, const QwtScaleMap &yMap, + const QRectF &canvasRect ) const = 0; + + virtual QRectF boundingRect() const; + + virtual void updateLegend( QwtLegend * ) const; + virtual void updateScaleDiv( + const QwtScaleDiv&, const QwtScaleDiv& ); + + virtual QWidget *legendItem() const; + + QRectF scaleRect( const QwtScaleMap &, const QwtScaleMap & ) const; + QRectF paintRect( const QwtScaleMap &, const QwtScaleMap & ) const; + +private: + // Disabled copy constructor and operator= + QwtPlotItem( const QwtPlotItem & ); + QwtPlotItem &operator=( const QwtPlotItem & ); + + class PrivateData; + PrivateData *d_data; +}; + +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotItem::ItemAttributes ) +Q_DECLARE_OPERATORS_FOR_FLAGS( QwtPlotItem::RenderHints ) + +#endif diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_layout.cpp b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_layout.cpp index 9ad2db61c..460e3ae84 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_layout.cpp +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_layout.cpp @@ -1,1227 +1,1227 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#include "qwt_plot_layout.h" -#include "qwt_text.h" -#include "qwt_text_label.h" -#include "qwt_plot_canvas.h" -#include "qwt_scale_widget.h" -#include "qwt_legend.h" -#include -#include - -class QwtPlotLayout::LayoutData -{ -public: - void init( const QwtPlot *, const QRectF &rect ); - - struct t_legendData - { - int frameWidth; - int vScrollBarWidth; - int hScrollBarHeight; - QSize hint; - } legend; - - struct t_titleData - { - QwtText text; - int frameWidth; - } title; - - struct t_scaleData - { - bool isEnabled; - const QwtScaleWidget *scaleWidget; - QFont scaleFont; - int start; - int end; - int baseLineOffset; - int tickOffset; - int dimWithoutTitle; - } scale[QwtPlot::axisCnt]; - - struct t_canvasData - { - int frameWidth; - } canvas; -}; - -/* - Extract all layout relevant data from the plot components -*/ - -void QwtPlotLayout::LayoutData::init( const QwtPlot *plot, const QRectF &rect ) -{ - // legend - - if ( plot->plotLayout()->legendPosition() != QwtPlot::ExternalLegend - && plot->legend() ) - { - legend.frameWidth = plot->legend()->frameWidth(); - legend.vScrollBarWidth = - plot->legend()->verticalScrollBar()->sizeHint().width(); - legend.hScrollBarHeight = - plot->legend()->horizontalScrollBar()->sizeHint().height(); - - const QSize hint = plot->legend()->sizeHint(); - - int w = qMin( hint.width(), qFloor( rect.width() ) ); - int h = plot->legend()->heightForWidth( w ); - if ( h == 0 ) - h = hint.height(); - - if ( h > rect.height() ) - w += legend.vScrollBarWidth; - - legend.hint = QSize( w, h ); - } - - // title - - title.frameWidth = 0; - title.text = QwtText(); - - if ( plot->titleLabel() ) - { - const QwtTextLabel *label = plot->titleLabel(); - title.text = label->text(); - if ( !( title.text.testPaintAttribute( QwtText::PaintUsingTextFont ) ) ) - title.text.setFont( label->font() ); - - title.frameWidth = plot->titleLabel()->frameWidth(); - } - - // scales - - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) - { - if ( plot->axisEnabled( axis ) ) - { - const QwtScaleWidget *scaleWidget = plot->axisWidget( axis ); - - scale[axis].isEnabled = true; - - scale[axis].scaleWidget = scaleWidget; - - scale[axis].scaleFont = scaleWidget->font(); - - scale[axis].start = scaleWidget->startBorderDist(); - scale[axis].end = scaleWidget->endBorderDist(); - - scale[axis].baseLineOffset = scaleWidget->margin(); - scale[axis].tickOffset = scaleWidget->margin(); - if ( scaleWidget->scaleDraw()->hasComponent( - QwtAbstractScaleDraw::Ticks ) ) - { - scale[axis].tickOffset += - scaleWidget->scaleDraw()->maxTickLength(); - } - - scale[axis].dimWithoutTitle = scaleWidget->dimForLength( - QWIDGETSIZE_MAX, scale[axis].scaleFont ); - - if ( !scaleWidget->title().isEmpty() ) - { - scale[axis].dimWithoutTitle -= - scaleWidget->titleHeightForWidth( QWIDGETSIZE_MAX ); - } - } - else - { - scale[axis].isEnabled = false; - scale[axis].start = 0; - scale[axis].end = 0; - scale[axis].baseLineOffset = 0; - scale[axis].tickOffset = 0; - scale[axis].dimWithoutTitle = 0; - } - } - - // canvas - - canvas.frameWidth = plot->canvas()->frameWidth(); -} - -class QwtPlotLayout::PrivateData -{ -public: - PrivateData(): - spacing( 5 ), - alignCanvasToScales( false ) - { - } - - QRectF titleRect; - QRectF legendRect; - QRectF scaleRect[QwtPlot::axisCnt]; - QRectF canvasRect; - - QwtPlotLayout::LayoutData layoutData; - - QwtPlot::LegendPosition legendPos; - double legendRatio; - unsigned int spacing; - unsigned int canvasMargin[QwtPlot::axisCnt]; - bool alignCanvasToScales; -}; - -/*! - \brief Constructor - */ - -QwtPlotLayout::QwtPlotLayout() -{ - d_data = new PrivateData; - - setLegendPosition( QwtPlot::BottomLegend ); - setCanvasMargin( 4 ); - - invalidate(); -} - -//! Destructor -QwtPlotLayout::~QwtPlotLayout() -{ - delete d_data; -} - -/*! - Change a margin of the canvas. The margin is the space - above/below the scale ticks. A negative margin will - be set to -1, excluding the borders of the scales. - - \param margin New margin - \param axis One of QwtPlot::Axis. Specifies where the position of the margin. - -1 means margin at all borders. - \sa canvasMargin() - - \warning The margin will have no effect when alignCanvasToScales is true -*/ - -void QwtPlotLayout::setCanvasMargin( int margin, int axis ) -{ - if ( margin < -1 ) - margin = -1; - - if ( axis == -1 ) - { - for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) - d_data->canvasMargin[axis] = margin; - } - else if ( axis >= 0 && axis < QwtPlot::axisCnt ) - d_data->canvasMargin[axis] = margin; -} - -/*! - \return Margin around the scale tick borders - \sa setCanvasMargin() -*/ -int QwtPlotLayout::canvasMargin( int axis ) const -{ - if ( axis < 0 || axis >= QwtPlot::axisCnt ) - return 0; - - return d_data->canvasMargin[axis]; -} - -/*! - Change the align-canvas-to-axis-scales setting. The canvas may: - - extend beyond the axis scale ends to maximize its size, - - align with the axis scale ends to control its size. - - \param alignCanvasToScales New align-canvas-to-axis-scales setting - - \sa setCanvasMargin() - \note In this context the term 'scale' means the backbone of a scale. - \warning In case of alignCanvasToScales == true canvasMargin will have - no effect -*/ -void QwtPlotLayout::setAlignCanvasToScales( bool alignCanvasToScales ) -{ - d_data->alignCanvasToScales = alignCanvasToScales; -} - -/*! - Return the align-canvas-to-axis-scales setting. The canvas may: - - extend beyond the axis scale ends to maximize its size - - align with the axis scale ends to control its size. - - \return align-canvas-to-axis-scales setting - \sa setAlignCanvasToScales, setCanvasMargin() - \note In this context the term 'scale' means the backbone of a scale. -*/ -bool QwtPlotLayout::alignCanvasToScales() const -{ - return d_data->alignCanvasToScales; -} - -/*! - Change the spacing of the plot. The spacing is the distance - between the plot components. - - \param spacing new spacing - \sa setMargin(), spacing() -*/ -void QwtPlotLayout::setSpacing( int spacing ) -{ - d_data->spacing = qMax( 0, spacing ); -} - -/*! - \return spacing - \sa margin(), setSpacing() -*/ -int QwtPlotLayout::spacing() const -{ - return d_data->spacing; -} - -/*! - \brief Specify the position of the legend - \param pos The legend's position. - \param ratio Ratio between legend and the bounding rect - of title, canvas and axes. The legend will be shrinked - if it would need more space than the given ratio. - The ratio is limited to ]0.0 .. 1.0]. In case of <= 0.0 - it will be reset to the default ratio. - The default vertical/horizontal ratio is 0.33/0.5. - - \sa QwtPlot::setLegendPosition() -*/ - -void QwtPlotLayout::setLegendPosition( QwtPlot::LegendPosition pos, double ratio ) -{ - if ( ratio > 1.0 ) - ratio = 1.0; - - switch ( pos ) - { - case QwtPlot::TopLegend: - case QwtPlot::BottomLegend: - if ( ratio <= 0.0 ) - ratio = 0.33; - d_data->legendRatio = ratio; - d_data->legendPos = pos; - break; - case QwtPlot::LeftLegend: - case QwtPlot::RightLegend: - if ( ratio <= 0.0 ) - ratio = 0.5; - d_data->legendRatio = ratio; - d_data->legendPos = pos; - break; - case QwtPlot::ExternalLegend: - d_data->legendRatio = ratio; // meaningless - d_data->legendPos = pos; - default: - break; - } -} - -/*! - \brief Specify the position of the legend - \param pos The legend's position. Valid values are - \c QwtPlot::LeftLegend, \c QwtPlot::RightLegend, - \c QwtPlot::TopLegend, \c QwtPlot::BottomLegend. - - \sa QwtPlot::setLegendPosition() -*/ -void QwtPlotLayout::setLegendPosition( QwtPlot::LegendPosition pos ) -{ - setLegendPosition( pos, 0.0 ); -} - -/*! - \return Position of the legend - \sa setLegendPosition(), QwtPlot::setLegendPosition(), - QwtPlot::legendPosition() -*/ -QwtPlot::LegendPosition QwtPlotLayout::legendPosition() const -{ - return d_data->legendPos; -} - -/*! - Specify the relative size of the legend in the plot - \param ratio Ratio between legend and the bounding rect - of title, canvas and axes. The legend will be shrinked - if it would need more space than the given ratio. - The ratio is limited to ]0.0 .. 1.0]. In case of <= 0.0 - it will be reset to the default ratio. - The default vertical/horizontal ratio is 0.33/0.5. -*/ -void QwtPlotLayout::setLegendRatio( double ratio ) -{ - setLegendPosition( legendPosition(), ratio ); -} - -/*! - \return The relative size of the legend in the plot. - \sa setLegendPosition() -*/ -double QwtPlotLayout::legendRatio() const -{ - return d_data->legendRatio; -} - -/*! - \return Geometry for the title - \sa activate(), invalidate() -*/ - -const QRectF &QwtPlotLayout::titleRect() const -{ - return d_data->titleRect; -} - -/*! - \return Geometry for the legend - \sa activate(), invalidate() -*/ - -const QRectF &QwtPlotLayout::legendRect() const -{ - return d_data->legendRect; -} - -/*! - \param axis Axis index - \return Geometry for the scale - \sa activate(), invalidate() -*/ - -const QRectF &QwtPlotLayout::scaleRect( int axis ) const -{ - if ( axis < 0 || axis >= QwtPlot::axisCnt ) - { - static QRectF dummyRect; - return dummyRect; - } - return d_data->scaleRect[axis]; -} - -/*! - \return Geometry for the canvas - \sa activate(), invalidate() -*/ - -const QRectF &QwtPlotLayout::canvasRect() const -{ - return d_data->canvasRect; -} - -/*! - Invalidate the geometry of all components. - \sa activate() -*/ -void QwtPlotLayout::invalidate() -{ - d_data->titleRect = d_data->legendRect = d_data->canvasRect = QRect(); - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) - d_data->scaleRect[axis] = QRect(); -} - -/*! - \brief Return a minimum size hint - \sa QwtPlot::minimumSizeHint() -*/ - -QSize QwtPlotLayout::minimumSizeHint( const QwtPlot *plot ) const -{ - class ScaleData - { - public: - ScaleData() - { - w = h = minLeft = minRight = tickOffset = 0; - } - - int w; - int h; - int minLeft; - int minRight; - int tickOffset; - } scaleData[QwtPlot::axisCnt]; - - int canvasBorder[QwtPlot::axisCnt]; - - int axis; - for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) - { - if ( plot->axisEnabled( axis ) ) - { - const QwtScaleWidget *scl = plot->axisWidget( axis ); - ScaleData &sd = scaleData[axis]; - - const QSize hint = scl->minimumSizeHint(); - sd.w = hint.width(); - sd.h = hint.height(); - scl->getBorderDistHint( sd.minLeft, sd.minRight ); - sd.tickOffset = scl->margin(); - if ( scl->scaleDraw()->hasComponent( QwtAbstractScaleDraw::Ticks ) ) - sd.tickOffset += scl->scaleDraw()->maxTickLength(); - } - - canvasBorder[axis] = plot->canvas()->frameWidth() + - d_data->canvasMargin[axis] + 1; - - } - - - for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) - { - ScaleData &sd = scaleData[axis]; - if ( sd.w && ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) ) - { - if ( ( sd.minLeft > canvasBorder[QwtPlot::yLeft] ) - && scaleData[QwtPlot::yLeft].w ) - { - int shiftLeft = sd.minLeft - canvasBorder[QwtPlot::yLeft]; - if ( shiftLeft > scaleData[QwtPlot::yLeft].w ) - shiftLeft = scaleData[QwtPlot::yLeft].w; - - sd.w -= shiftLeft; - } - if ( ( sd.minRight > canvasBorder[QwtPlot::yRight] ) - && scaleData[QwtPlot::yRight].w ) - { - int shiftRight = sd.minRight - canvasBorder[QwtPlot::yRight]; - if ( shiftRight > scaleData[QwtPlot::yRight].w ) - shiftRight = scaleData[QwtPlot::yRight].w; - - sd.w -= shiftRight; - } - } - - if ( sd.h && ( axis == QwtPlot::yLeft || axis == QwtPlot::yRight ) ) - { - if ( ( sd.minLeft > canvasBorder[QwtPlot::xBottom] ) && - scaleData[QwtPlot::xBottom].h ) - { - int shiftBottom = sd.minLeft - canvasBorder[QwtPlot::xBottom]; - if ( shiftBottom > scaleData[QwtPlot::xBottom].tickOffset ) - shiftBottom = scaleData[QwtPlot::xBottom].tickOffset; - - sd.h -= shiftBottom; - } - if ( ( sd.minLeft > canvasBorder[QwtPlot::xTop] ) && - scaleData[QwtPlot::xTop].h ) - { - int shiftTop = sd.minRight - canvasBorder[QwtPlot::xTop]; - if ( shiftTop > scaleData[QwtPlot::xTop].tickOffset ) - shiftTop = scaleData[QwtPlot::xTop].tickOffset; - - sd.h -= shiftTop; - } - } - } - - const QwtPlotCanvas *canvas = plot->canvas(); - const QSize minCanvasSize = canvas->minimumSize(); - - int w = scaleData[QwtPlot::yLeft].w + scaleData[QwtPlot::yRight].w; - int cw = qMax( scaleData[QwtPlot::xBottom].w, scaleData[QwtPlot::xTop].w ) - + 2 * ( canvas->frameWidth() + 1 ); - w += qMax( cw, minCanvasSize.width() ); - - int h = scaleData[QwtPlot::xBottom].h + scaleData[QwtPlot::xTop].h; - int ch = qMax( scaleData[QwtPlot::yLeft].h, scaleData[QwtPlot::yRight].h ) - + 2 * ( canvas->frameWidth() + 1 ); - h += qMax( ch, minCanvasSize.height() ); - - const QwtTextLabel *title = plot->titleLabel(); - if ( title && !title->text().isEmpty() ) - { - // If only QwtPlot::yLeft or QwtPlot::yRight is showing, - // we center on the plot canvas. - const bool centerOnCanvas = !( plot->axisEnabled( QwtPlot::yLeft ) - && plot->axisEnabled( QwtPlot::yRight ) ); - - int titleW = w; - if ( centerOnCanvas ) - { - titleW -= scaleData[QwtPlot::yLeft].w - + scaleData[QwtPlot::yRight].w; - } - - int titleH = title->heightForWidth( titleW ); - if ( titleH > titleW ) // Compensate for a long title - { - w = titleW = titleH; - if ( centerOnCanvas ) - { - w += scaleData[QwtPlot::yLeft].w - + scaleData[QwtPlot::yRight].w; - } - - titleH = title->heightForWidth( titleW ); - } - h += titleH + d_data->spacing; - } - - // Compute the legend contribution - - const QwtLegend *legend = plot->legend(); - if ( d_data->legendPos != QwtPlot::ExternalLegend - && legend && !legend->isEmpty() ) - { - if ( d_data->legendPos == QwtPlot::LeftLegend - || d_data->legendPos == QwtPlot::RightLegend ) - { - int legendW = legend->sizeHint().width(); - int legendH = legend->heightForWidth( legendW ); - - if ( legend->frameWidth() > 0 ) - w += d_data->spacing; - - if ( legendH > h ) - legendW += legend->verticalScrollBar()->sizeHint().height(); - - if ( d_data->legendRatio < 1.0 ) - legendW = qMin( legendW, int( w / ( 1.0 - d_data->legendRatio ) ) ); - - w += legendW + d_data->spacing; - } - else // QwtPlot::Top, QwtPlot::Bottom - { - int legendW = qMin( legend->sizeHint().width(), w ); - int legendH = legend->heightForWidth( legendW ); - - if ( legend->frameWidth() > 0 ) - h += d_data->spacing; - - if ( d_data->legendRatio < 1.0 ) - legendH = qMin( legendH, int( h / ( 1.0 - d_data->legendRatio ) ) ); - - h += legendH + d_data->spacing; - } - } - - return QSize( w, h ); -} - -/*! - Find the geometry for the legend - \param options Options how to layout the legend - \param rect Rectangle where to place the legend - \return Geometry for the legend - \sa Options -*/ - -QRectF QwtPlotLayout::layoutLegend( Options options, - const QRectF &rect ) const -{ - const QSize hint( d_data->layoutData.legend.hint ); - - int dim; - if ( d_data->legendPos == QwtPlot::LeftLegend - || d_data->legendPos == QwtPlot::RightLegend ) - { - // We don't allow vertical legends to take more than - // half of the available space. - - dim = qMin( hint.width(), int( rect.width() * d_data->legendRatio ) ); - - if ( !( options & IgnoreScrollbars ) ) - { - if ( hint.height() > rect.height() ) - { - // The legend will need additional - // space for the vertical scrollbar. - - dim += d_data->layoutData.legend.vScrollBarWidth; - } - } - } - else - { - dim = qMin( hint.height(), int( rect.height() * d_data->legendRatio ) ); - dim = qMax( dim, d_data->layoutData.legend.hScrollBarHeight ); - } - - QRectF legendRect = rect; - switch ( d_data->legendPos ) - { - case QwtPlot::LeftLegend: - legendRect.setWidth( dim ); - break; - case QwtPlot::RightLegend: - legendRect.setX( rect.right() - dim ); - legendRect.setWidth( dim ); - break; - case QwtPlot::TopLegend: - legendRect.setHeight( dim ); - break; - case QwtPlot::BottomLegend: - legendRect.setY( rect.bottom() - dim ); - legendRect.setHeight( dim ); - break; - case QwtPlot::ExternalLegend: - break; - } - - return legendRect; -} - -/*! - Align the legend to the canvas - \param canvasRect Geometry of the canvas - \param legendRect Maximum geometry for the legend - \return Geometry for the aligned legend -*/ -QRectF QwtPlotLayout::alignLegend( const QRectF &canvasRect, - const QRectF &legendRect ) const -{ - QRectF alignedRect = legendRect; - - if ( d_data->legendPos == QwtPlot::BottomLegend - || d_data->legendPos == QwtPlot::TopLegend ) - { - if ( d_data->layoutData.legend.hint.width() < canvasRect.width() ) - { - alignedRect.setX( canvasRect.x() ); - alignedRect.setWidth( canvasRect.width() ); - } - } - else - { - if ( d_data->layoutData.legend.hint.height() < canvasRect.height() ) - { - alignedRect.setY( canvasRect.y() ); - alignedRect.setHeight( canvasRect.height() ); - } - } - - return alignedRect; -} - -/*! - Expand all line breaks in text labels, and calculate the height - of their widgets in orientation of the text. - - \param options Options how to layout the legend - \param rect Bounding rect for title, axes and canvas. - \param dimTitle Expanded height of the title widget - \param dimAxis Expanded heights of the axis in axis orientation. - - \sa Options -*/ -void QwtPlotLayout::expandLineBreaks( int options, const QRectF &rect, - int &dimTitle, int dimAxis[QwtPlot::axisCnt] ) const -{ - dimTitle = 0; - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) - dimAxis[axis] = 0; - - int backboneOffset[QwtPlot::axisCnt]; - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) - { - backboneOffset[axis] = 0; - if ( !d_data->alignCanvasToScales ) - backboneOffset[axis] += d_data->canvasMargin[axis]; - if ( !( options & IgnoreFrames ) ) - backboneOffset[axis] += d_data->layoutData.canvas.frameWidth; - } - - bool done = false; - while ( !done ) - { - done = true; - - // the size for the 4 axis depend on each other. Expanding - // the height of a horizontal axis will shrink the height - // for the vertical axis, shrinking the height of a vertical - // axis will result in a line break what will expand the - // width and results in shrinking the width of a horizontal - // axis what might result in a line break of a horizontal - // axis ... . So we loop as long until no size changes. - - if ( !d_data->layoutData.title.text.isEmpty() ) - { - int w = rect.width(); - - if ( d_data->layoutData.scale[QwtPlot::yLeft].isEnabled - != d_data->layoutData.scale[QwtPlot::yRight].isEnabled ) - { - // center to the canvas - w -= dimAxis[QwtPlot::yLeft] + dimAxis[QwtPlot::yRight]; - } - - int d = qCeil( d_data->layoutData.title.text.heightForWidth( w ) ); - if ( !( options & IgnoreFrames ) ) - d += 2 * d_data->layoutData.title.frameWidth; - - if ( d > dimTitle ) - { - dimTitle = d; - done = false; - } - } - - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) - { - const struct LayoutData::t_scaleData &scaleData = - d_data->layoutData.scale[axis]; - - if ( scaleData.isEnabled ) - { - int length; - if ( axis == QwtPlot::xTop || axis == QwtPlot::xBottom ) - { - length = rect.width() - dimAxis[QwtPlot::yLeft] - - dimAxis[QwtPlot::yRight]; - length -= scaleData.start + scaleData.end; - - if ( dimAxis[QwtPlot::yRight] > 0 ) - length -= 1; - - length += qMin( dimAxis[QwtPlot::yLeft], - scaleData.start - backboneOffset[QwtPlot::yLeft] ); - length += qMin( dimAxis[QwtPlot::yRight], - scaleData.end - backboneOffset[QwtPlot::yRight] ); - } - else // QwtPlot::yLeft, QwtPlot::yRight - { - length = rect.height() - dimAxis[QwtPlot::xTop] - - dimAxis[QwtPlot::xBottom]; - length -= scaleData.start + scaleData.end; - length -= 1; - - if ( dimAxis[QwtPlot::xBottom] <= 0 ) - length -= 1; - if ( dimAxis[QwtPlot::xTop] <= 0 ) - length -= 1; - - if ( dimAxis[QwtPlot::xBottom] > 0 ) - { - length += qMin( - d_data->layoutData.scale[QwtPlot::xBottom].tickOffset, - scaleData.start - backboneOffset[QwtPlot::xBottom] ); - } - if ( dimAxis[QwtPlot::xTop] > 0 ) - { - length += qMin( - d_data->layoutData.scale[QwtPlot::xTop].tickOffset, - scaleData.end - backboneOffset[QwtPlot::xTop] ); - } - - if ( dimTitle > 0 ) - length -= dimTitle + d_data->spacing; - } - - int d = scaleData.dimWithoutTitle; - if ( !scaleData.scaleWidget->title().isEmpty() ) - { - d += scaleData.scaleWidget->titleHeightForWidth( length ); - } - - - if ( d > dimAxis[axis] ) - { - dimAxis[axis] = d; - done = false; - } - } - } - } -} - -/*! - Align the ticks of the axis to the canvas borders using - the empty corners. - - \sa Options -*/ - -void QwtPlotLayout::alignScales( int options, - QRectF &canvasRect, QRectF scaleRect[QwtPlot::axisCnt] ) const -{ - int backboneOffset[QwtPlot::axisCnt]; - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) - { - backboneOffset[axis] = 0; - if ( !d_data->alignCanvasToScales ) - backboneOffset[axis] += d_data->canvasMargin[axis]; - if ( !( options & IgnoreFrames ) ) - backboneOffset[axis] += d_data->layoutData.canvas.frameWidth; - } - - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) - { - if ( !scaleRect[axis].isValid() ) - continue; - - const int startDist = d_data->layoutData.scale[axis].start; - const int endDist = d_data->layoutData.scale[axis].end; - - QRectF &axisRect = scaleRect[axis]; - - if ( axis == QwtPlot::xTop || axis == QwtPlot::xBottom ) - { - const QRectF &leftScaleRect = scaleRect[QwtPlot::yLeft]; - const int leftOffset = - backboneOffset[QwtPlot::yLeft] - startDist; - - if ( leftScaleRect.isValid() ) - { - const int dx = leftOffset + leftScaleRect.width(); - if ( d_data->alignCanvasToScales && dx < 0 ) - { - /* - The axis needs more space than the width - of the left scale. - */ - canvasRect.setLeft( qMax( canvasRect.left(), - axisRect.left() - dx ) ); - } - else - { - const double minLeft = leftScaleRect.left(); - const double left = axisRect.left() + leftOffset; - axisRect.setLeft( qMax( left, minLeft ) ); - } - } - else - { - if ( d_data->alignCanvasToScales && leftOffset < 0 ) - { - canvasRect.setLeft( qMax( canvasRect.left(), - axisRect.left() - leftOffset ) ); - } - else - { - if ( leftOffset > 0 ) - axisRect.setLeft( axisRect.left() + leftOffset ); - } - } - - const QRectF &rightScaleRect = scaleRect[QwtPlot::yRight]; - const int rightOffset = - backboneOffset[QwtPlot::yRight] - endDist + 1; - - if ( rightScaleRect.isValid() ) - { - const int dx = rightOffset + rightScaleRect.width(); - if ( d_data->alignCanvasToScales && dx < 0 ) - { - /* - The axis needs more space than the width - of the right scale. - */ - canvasRect.setRight( qMin( canvasRect.right(), - axisRect.right() + dx ) ); - } - - const double maxRight = rightScaleRect.right(); - const double right = axisRect.right() - rightOffset; - axisRect.setRight( qMin( right, maxRight ) ); - } - else - { - if ( d_data->alignCanvasToScales && rightOffset < 0 ) - { - canvasRect.setRight( qMin( canvasRect.right(), - axisRect.right() + rightOffset ) ); - } - else - { - if ( rightOffset > 0 ) - axisRect.setRight( axisRect.right() - rightOffset ); - } - } - } - else // QwtPlot::yLeft, QwtPlot::yRight - { - const QRectF &bottomScaleRect = scaleRect[QwtPlot::xBottom]; - const int bottomOffset = - backboneOffset[QwtPlot::xBottom] - endDist + 1; - - if ( bottomScaleRect.isValid() ) - { - const int dy = bottomOffset + bottomScaleRect.height(); - if ( d_data->alignCanvasToScales && dy < 0 ) - { - /* - The axis needs more space than the height - of the bottom scale. - */ - canvasRect.setBottom( qMin( canvasRect.bottom(), - axisRect.bottom() + dy ) ); - } - else - { - const double maxBottom = bottomScaleRect.top() + - d_data->layoutData.scale[QwtPlot::xBottom].tickOffset; - const double bottom = axisRect.bottom() - bottomOffset; - axisRect.setBottom( qMin( bottom, maxBottom ) ); - } - } - else - { - if ( d_data->alignCanvasToScales && bottomOffset < 0 ) - { - canvasRect.setBottom( qMin( canvasRect.bottom(), - axisRect.bottom() + bottomOffset ) ); - } - else - { - if ( bottomOffset > 0 ) - axisRect.setBottom( axisRect.bottom() - bottomOffset ); - } - } - - const QRectF &topScaleRect = scaleRect[QwtPlot::xTop]; - const int topOffset = backboneOffset[QwtPlot::xTop] - startDist; - - if ( topScaleRect.isValid() ) - { - const int dy = topOffset + topScaleRect.height(); - if ( d_data->alignCanvasToScales && dy < 0 ) - { - /* - The axis needs more space than the height - of the top scale. - */ - canvasRect.setTop( qMax( canvasRect.top(), - axisRect.top() - dy ) ); - } - else - { - const double minTop = topScaleRect.bottom() - - d_data->layoutData.scale[QwtPlot::xTop].tickOffset; - const double top = axisRect.top() + topOffset; - axisRect.setTop( qMax( top, minTop ) ); - } - } - else - { - if ( d_data->alignCanvasToScales && topOffset < 0 ) - { - canvasRect.setTop( qMax( canvasRect.top(), - axisRect.top() - topOffset ) ); - } - else - { - if ( topOffset > 0 ) - axisRect.setTop( axisRect.top() + topOffset ); - } - } - } - } - - if ( d_data->alignCanvasToScales ) - { - /* - The canvas has been aligned to the scale with largest - border distances. Now we have to realign the other scale. - */ - - int fw = 0; - if ( !( options & IgnoreFrames ) ) - fw = d_data->layoutData.canvas.frameWidth; - - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) - { - if ( !scaleRect[axis].isValid() ) - continue; - - if ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) - { - scaleRect[axis].setLeft( canvasRect.left() + fw - - d_data->layoutData.scale[axis].start ); - scaleRect[axis].setRight( canvasRect.right() - fw - 1 - + d_data->layoutData.scale[axis].end ); - } - else - { - scaleRect[axis].setTop( canvasRect.top() + fw - - d_data->layoutData.scale[axis].start ); - scaleRect[axis].setBottom( canvasRect.bottom() - fw - 1 - + d_data->layoutData.scale[axis].end ); - } - } - - if ( scaleRect[QwtPlot::xTop].isValid() ) - scaleRect[QwtPlot::xTop].setBottom( canvasRect.top() ); - if ( scaleRect[QwtPlot::xBottom].isValid() ) - scaleRect[QwtPlot::xBottom].setTop( canvasRect.bottom() ); - if ( scaleRect[QwtPlot::yLeft].isValid() ) - scaleRect[QwtPlot::yLeft].setRight( canvasRect.left() ); - if ( scaleRect[QwtPlot::yRight].isValid() ) - scaleRect[QwtPlot::yRight].setLeft( canvasRect.right() ); - } -} - -/*! - \brief Recalculate the geometry of all components. - - \param plot Plot to be layout - \param plotRect Rect where to place the components - \param options Layout options - - \sa invalidate(), titleRect(), - legendRect(), scaleRect(), canvasRect() -*/ -void QwtPlotLayout::activate( const QwtPlot *plot, - const QRectF &plotRect, Options options ) -{ - invalidate(); - - QRectF rect( plotRect ); // undistributed rest of the plot rect - - // We extract all layout relevant data from the widgets, - // filter them through pfilter and save them to d_data->layoutData. - - d_data->layoutData.init( plot, rect ); - - if ( !( options & IgnoreLegend ) - && d_data->legendPos != QwtPlot::ExternalLegend - && plot->legend() && !plot->legend()->isEmpty() ) - { - d_data->legendRect = layoutLegend( options, rect ); - - // subtract d_data->legendRect from rect - - const QRegion region( rect.toRect() ); - rect = region.subtract( d_data->legendRect.toRect() ).boundingRect(); - - switch ( d_data->legendPos ) - { - case QwtPlot::LeftLegend: - rect.setLeft( rect.left() + d_data->spacing ); - break; - case QwtPlot::RightLegend: - rect.setRight( rect.right() - d_data->spacing ); - break; - case QwtPlot::TopLegend: - rect.setTop( rect.top() + d_data->spacing ); - break; - case QwtPlot::BottomLegend: - rect.setBottom( rect.bottom() - d_data->spacing ); - break; - case QwtPlot::ExternalLegend: - break; // suppress compiler warning - } - } - - /* - +---+-----------+---+ - | Title | - +---+-----------+---+ - | | Axis | | - +---+-----------+---+ - | A | | A | - | x | Canvas | x | - | i | | i | - | s | | s | - +---+-----------+---+ - | | Axis | | - +---+-----------+---+ - */ - - // axes and title include text labels. The height of each - // label depends on its line breaks, that depend on the width - // for the label. A line break in a horizontal text will reduce - // the available width for vertical texts and vice versa. - // expandLineBreaks finds the height/width for title and axes - // including all line breaks. - - int dimTitle, dimAxes[QwtPlot::axisCnt]; - expandLineBreaks( options, rect, dimTitle, dimAxes ); - - if ( dimTitle > 0 ) - { - d_data->titleRect = QRect( rect.x(), rect.y(), - rect.width(), dimTitle ); - - if ( d_data->layoutData.scale[QwtPlot::yLeft].isEnabled != - d_data->layoutData.scale[QwtPlot::yRight].isEnabled ) - { - // if only one of the y axes is missing we align - // the title centered to the canvas - - d_data->titleRect.setX( rect.x() + dimAxes[QwtPlot::yLeft] ); - d_data->titleRect.setWidth( rect.width() - - dimAxes[QwtPlot::yLeft] - dimAxes[QwtPlot::yRight] ); - } - - // subtract title - rect.setTop( rect.top() + dimTitle + d_data->spacing ); - } - - d_data->canvasRect.setRect( - rect.x() + dimAxes[QwtPlot::yLeft], - rect.y() + dimAxes[QwtPlot::xTop], - rect.width() - dimAxes[QwtPlot::yRight] - dimAxes[QwtPlot::yLeft], - rect.height() - dimAxes[QwtPlot::xBottom] - dimAxes[QwtPlot::xTop] ); - - for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) - { - // set the rects for the axes - - if ( dimAxes[axis] ) - { - int dim = dimAxes[axis]; - QRectF &scaleRect = d_data->scaleRect[axis]; - - scaleRect = d_data->canvasRect; - switch ( axis ) - { - case QwtPlot::yLeft: - scaleRect.setX( d_data->canvasRect.left() - dim ); - scaleRect.setWidth( dim ); - break; - case QwtPlot::yRight: - scaleRect.setX( d_data->canvasRect.right() ); - scaleRect.setWidth( dim ); - break; - case QwtPlot::xBottom: - scaleRect.setY( d_data->canvasRect.bottom() ); - scaleRect.setHeight( dim ); - break; - case QwtPlot::xTop: - scaleRect.setY( d_data->canvasRect.top() - dim ); - scaleRect.setHeight( dim ); - break; - } - scaleRect = scaleRect.normalized(); - } - } - - // +---+-----------+---+ - // | <- Axis -> | - // +-^-+-----------+-^-+ - // | | | | | | - // | | | | - // | A | | A | - // | x | Canvas | x | - // | i | | i | - // | s | | s | - // | | | | - // | | | | | | - // +-V-+-----------+-V-+ - // | <- Axis -> | - // +---+-----------+---+ - - // The ticks of the axes - not the labels above - should - // be aligned to the canvas. So we try to use the empty - // corners to extend the axes, so that the label texts - // left/right of the min/max ticks are moved into them. - - alignScales( options, d_data->canvasRect, d_data->scaleRect ); - - if ( !d_data->legendRect.isEmpty() ) - { - // We prefer to align the legend to the canvas - not to - // the complete plot - if possible. - - d_data->legendRect = alignLegend( d_data->canvasRect, d_data->legendRect ); - } -} +/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** + * Qwt Widget Library + * Copyright (C) 1997 Josef Wilgen + * Copyright (C) 2002 Uwe Rathmann + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the Qwt License, Version 1.0 + *****************************************************************************/ + +#include "qwt_plot_layout.h" +#include "qwt_text.h" +#include "qwt_text_label.h" +#include "qwt_plot_canvas.h" +#include "qwt_scale_widget.h" +#include "qwt_legend.h" +#include +#include + +class QwtPlotLayout::LayoutData +{ +public: + void init( const QwtPlot *, const QRectF &rect ); + + struct t_legendData + { + int frameWidth; + int vScrollBarWidth; + int hScrollBarHeight; + QSize hint; + } legend; + + struct t_titleData + { + QwtText text; + int frameWidth; + } title; + + struct t_scaleData + { + bool isEnabled; + const QwtScaleWidget *scaleWidget; + QFont scaleFont; + int start; + int end; + int baseLineOffset; + int tickOffset; + int dimWithoutTitle; + } scale[QwtPlot::axisCnt]; + + struct t_canvasData + { + int frameWidth; + } canvas; +}; + +/* + Extract all layout relevant data from the plot components +*/ + +void QwtPlotLayout::LayoutData::init( const QwtPlot *plot, const QRectF &rect ) +{ + // legend + + if ( plot->plotLayout()->legendPosition() != QwtPlot::ExternalLegend + && plot->legend() ) + { + legend.frameWidth = plot->legend()->frameWidth(); + legend.vScrollBarWidth = + plot->legend()->verticalScrollBar()->sizeHint().width(); + legend.hScrollBarHeight = + plot->legend()->horizontalScrollBar()->sizeHint().height(); + + const QSize hint = plot->legend()->sizeHint(); + + int w = qMin( hint.width(), qFloor( rect.width() ) ); + int h = plot->legend()->heightForWidth( w ); + if ( h == 0 ) + h = hint.height(); + + if ( h > rect.height() ) + w += legend.vScrollBarWidth; + + legend.hint = QSize( w, h ); + } + + // title + + title.frameWidth = 0; + title.text = QwtText(); + + if ( plot->titleLabel() ) + { + const QwtTextLabel *label = plot->titleLabel(); + title.text = label->text(); + if ( !( title.text.testPaintAttribute( QwtText::PaintUsingTextFont ) ) ) + title.text.setFont( label->font() ); + + title.frameWidth = plot->titleLabel()->frameWidth(); + } + + // scales + + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + if ( plot->axisEnabled( axis ) ) + { + const QwtScaleWidget *scaleWidget = plot->axisWidget( axis ); + + scale[axis].isEnabled = true; + + scale[axis].scaleWidget = scaleWidget; + + scale[axis].scaleFont = scaleWidget->font(); + + scale[axis].start = scaleWidget->startBorderDist(); + scale[axis].end = scaleWidget->endBorderDist(); + + scale[axis].baseLineOffset = scaleWidget->margin(); + scale[axis].tickOffset = scaleWidget->margin(); + if ( scaleWidget->scaleDraw()->hasComponent( + QwtAbstractScaleDraw::Ticks ) ) + { + scale[axis].tickOffset += + scaleWidget->scaleDraw()->maxTickLength(); + } + + scale[axis].dimWithoutTitle = scaleWidget->dimForLength( + QWIDGETSIZE_MAX, scale[axis].scaleFont ); + + if ( !scaleWidget->title().isEmpty() ) + { + scale[axis].dimWithoutTitle -= + scaleWidget->titleHeightForWidth( QWIDGETSIZE_MAX ); + } + } + else + { + scale[axis].isEnabled = false; + scale[axis].start = 0; + scale[axis].end = 0; + scale[axis].baseLineOffset = 0; + scale[axis].tickOffset = 0; + scale[axis].dimWithoutTitle = 0; + } + } + + // canvas + + canvas.frameWidth = plot->canvas()->frameWidth(); +} + +class QwtPlotLayout::PrivateData +{ +public: + PrivateData(): + spacing( 5 ), + alignCanvasToScales( false ) + { + } + + QRectF titleRect; + QRectF legendRect; + QRectF scaleRect[QwtPlot::axisCnt]; + QRectF canvasRect; + + QwtPlotLayout::LayoutData layoutData; + + QwtPlot::LegendPosition legendPos; + double legendRatio; + unsigned int spacing; + unsigned int canvasMargin[QwtPlot::axisCnt]; + bool alignCanvasToScales; +}; + +/*! + \brief Constructor + */ + +QwtPlotLayout::QwtPlotLayout() +{ + d_data = new PrivateData; + + setLegendPosition( QwtPlot::BottomLegend ); + setCanvasMargin( 4 ); + + invalidate(); +} + +//! Destructor +QwtPlotLayout::~QwtPlotLayout() +{ + delete d_data; +} + +/*! + Change a margin of the canvas. The margin is the space + above/below the scale ticks. A negative margin will + be set to -1, excluding the borders of the scales. + + \param margin New margin + \param axis One of QwtPlot::Axis. Specifies where the position of the margin. + -1 means margin at all borders. + \sa canvasMargin() + + \warning The margin will have no effect when alignCanvasToScales is true +*/ + +void QwtPlotLayout::setCanvasMargin( int margin, int axis ) +{ + if ( margin < -1 ) + margin = -1; + + if ( axis == -1 ) + { + for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) + d_data->canvasMargin[axis] = margin; + } + else if ( axis >= 0 && axis < QwtPlot::axisCnt ) + d_data->canvasMargin[axis] = margin; +} + +/*! + \return Margin around the scale tick borders + \sa setCanvasMargin() +*/ +int QwtPlotLayout::canvasMargin( int axis ) const +{ + if ( axis < 0 || axis >= QwtPlot::axisCnt ) + return 0; + + return d_data->canvasMargin[axis]; +} + +/*! + Change the align-canvas-to-axis-scales setting. The canvas may: + - extend beyond the axis scale ends to maximize its size, + - align with the axis scale ends to control its size. + + \param alignCanvasToScales New align-canvas-to-axis-scales setting + + \sa setCanvasMargin() + \note In this context the term 'scale' means the backbone of a scale. + \warning In case of alignCanvasToScales == true canvasMargin will have + no effect +*/ +void QwtPlotLayout::setAlignCanvasToScales( bool alignCanvasToScales ) +{ + d_data->alignCanvasToScales = alignCanvasToScales; +} + +/*! + Return the align-canvas-to-axis-scales setting. The canvas may: + - extend beyond the axis scale ends to maximize its size + - align with the axis scale ends to control its size. + + \return align-canvas-to-axis-scales setting + \sa setAlignCanvasToScales, setCanvasMargin() + \note In this context the term 'scale' means the backbone of a scale. +*/ +bool QwtPlotLayout::alignCanvasToScales() const +{ + return d_data->alignCanvasToScales; +} + +/*! + Change the spacing of the plot. The spacing is the distance + between the plot components. + + \param spacing new spacing + \sa setMargin(), spacing() +*/ +void QwtPlotLayout::setSpacing( int spacing ) +{ + d_data->spacing = qMax( 0, spacing ); +} + +/*! + \return spacing + \sa margin(), setSpacing() +*/ +int QwtPlotLayout::spacing() const +{ + return d_data->spacing; +} + +/*! + \brief Specify the position of the legend + \param pos The legend's position. + \param ratio Ratio between legend and the bounding rect + of title, canvas and axes. The legend will be shrinked + if it would need more space than the given ratio. + The ratio is limited to ]0.0 .. 1.0]. In case of <= 0.0 + it will be reset to the default ratio. + The default vertical/horizontal ratio is 0.33/0.5. + + \sa QwtPlot::setLegendPosition() +*/ + +void QwtPlotLayout::setLegendPosition( QwtPlot::LegendPosition pos, double ratio ) +{ + if ( ratio > 1.0 ) + ratio = 1.0; + + switch ( pos ) + { + case QwtPlot::TopLegend: + case QwtPlot::BottomLegend: + if ( ratio <= 0.0 ) + ratio = 0.33; + d_data->legendRatio = ratio; + d_data->legendPos = pos; + break; + case QwtPlot::LeftLegend: + case QwtPlot::RightLegend: + if ( ratio <= 0.0 ) + ratio = 0.5; + d_data->legendRatio = ratio; + d_data->legendPos = pos; + break; + case QwtPlot::ExternalLegend: + d_data->legendRatio = ratio; // meaningless + d_data->legendPos = pos; + default: + break; + } +} + +/*! + \brief Specify the position of the legend + \param pos The legend's position. Valid values are + \c QwtPlot::LeftLegend, \c QwtPlot::RightLegend, + \c QwtPlot::TopLegend, \c QwtPlot::BottomLegend. + + \sa QwtPlot::setLegendPosition() +*/ +void QwtPlotLayout::setLegendPosition( QwtPlot::LegendPosition pos ) +{ + setLegendPosition( pos, 0.0 ); +} + +/*! + \return Position of the legend + \sa setLegendPosition(), QwtPlot::setLegendPosition(), + QwtPlot::legendPosition() +*/ +QwtPlot::LegendPosition QwtPlotLayout::legendPosition() const +{ + return d_data->legendPos; +} + +/*! + Specify the relative size of the legend in the plot + \param ratio Ratio between legend and the bounding rect + of title, canvas and axes. The legend will be shrinked + if it would need more space than the given ratio. + The ratio is limited to ]0.0 .. 1.0]. In case of <= 0.0 + it will be reset to the default ratio. + The default vertical/horizontal ratio is 0.33/0.5. +*/ +void QwtPlotLayout::setLegendRatio( double ratio ) +{ + setLegendPosition( legendPosition(), ratio ); +} + +/*! + \return The relative size of the legend in the plot. + \sa setLegendPosition() +*/ +double QwtPlotLayout::legendRatio() const +{ + return d_data->legendRatio; +} + +/*! + \return Geometry for the title + \sa activate(), invalidate() +*/ + +const QRectF &QwtPlotLayout::titleRect() const +{ + return d_data->titleRect; +} + +/*! + \return Geometry for the legend + \sa activate(), invalidate() +*/ + +const QRectF &QwtPlotLayout::legendRect() const +{ + return d_data->legendRect; +} + +/*! + \param axis Axis index + \return Geometry for the scale + \sa activate(), invalidate() +*/ + +const QRectF &QwtPlotLayout::scaleRect( int axis ) const +{ + if ( axis < 0 || axis >= QwtPlot::axisCnt ) + { + static QRectF dummyRect; + return dummyRect; + } + return d_data->scaleRect[axis]; +} + +/*! + \return Geometry for the canvas + \sa activate(), invalidate() +*/ + +const QRectF &QwtPlotLayout::canvasRect() const +{ + return d_data->canvasRect; +} + +/*! + Invalidate the geometry of all components. + \sa activate() +*/ +void QwtPlotLayout::invalidate() +{ + d_data->titleRect = d_data->legendRect = d_data->canvasRect = QRect(); + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + d_data->scaleRect[axis] = QRect(); +} + +/*! + \brief Return a minimum size hint + \sa QwtPlot::minimumSizeHint() +*/ + +QSize QwtPlotLayout::minimumSizeHint( const QwtPlot *plot ) const +{ + class ScaleData + { + public: + ScaleData() + { + w = h = minLeft = minRight = tickOffset = 0; + } + + int w; + int h; + int minLeft; + int minRight; + int tickOffset; + } scaleData[QwtPlot::axisCnt]; + + int canvasBorder[QwtPlot::axisCnt]; + + int axis; + for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + if ( plot->axisEnabled( axis ) ) + { + const QwtScaleWidget *scl = plot->axisWidget( axis ); + ScaleData &sd = scaleData[axis]; + + const QSize hint = scl->minimumSizeHint(); + sd.w = hint.width(); + sd.h = hint.height(); + scl->getBorderDistHint( sd.minLeft, sd.minRight ); + sd.tickOffset = scl->margin(); + if ( scl->scaleDraw()->hasComponent( QwtAbstractScaleDraw::Ticks ) ) + sd.tickOffset += scl->scaleDraw()->maxTickLength(); + } + + canvasBorder[axis] = plot->canvas()->frameWidth() + + d_data->canvasMargin[axis] + 1; + + } + + + for ( axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + ScaleData &sd = scaleData[axis]; + if ( sd.w && ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) ) + { + if ( ( sd.minLeft > canvasBorder[QwtPlot::yLeft] ) + && scaleData[QwtPlot::yLeft].w ) + { + int shiftLeft = sd.minLeft - canvasBorder[QwtPlot::yLeft]; + if ( shiftLeft > scaleData[QwtPlot::yLeft].w ) + shiftLeft = scaleData[QwtPlot::yLeft].w; + + sd.w -= shiftLeft; + } + if ( ( sd.minRight > canvasBorder[QwtPlot::yRight] ) + && scaleData[QwtPlot::yRight].w ) + { + int shiftRight = sd.minRight - canvasBorder[QwtPlot::yRight]; + if ( shiftRight > scaleData[QwtPlot::yRight].w ) + shiftRight = scaleData[QwtPlot::yRight].w; + + sd.w -= shiftRight; + } + } + + if ( sd.h && ( axis == QwtPlot::yLeft || axis == QwtPlot::yRight ) ) + { + if ( ( sd.minLeft > canvasBorder[QwtPlot::xBottom] ) && + scaleData[QwtPlot::xBottom].h ) + { + int shiftBottom = sd.minLeft - canvasBorder[QwtPlot::xBottom]; + if ( shiftBottom > scaleData[QwtPlot::xBottom].tickOffset ) + shiftBottom = scaleData[QwtPlot::xBottom].tickOffset; + + sd.h -= shiftBottom; + } + if ( ( sd.minLeft > canvasBorder[QwtPlot::xTop] ) && + scaleData[QwtPlot::xTop].h ) + { + int shiftTop = sd.minRight - canvasBorder[QwtPlot::xTop]; + if ( shiftTop > scaleData[QwtPlot::xTop].tickOffset ) + shiftTop = scaleData[QwtPlot::xTop].tickOffset; + + sd.h -= shiftTop; + } + } + } + + const QwtPlotCanvas *canvas = plot->canvas(); + const QSize minCanvasSize = canvas->minimumSize(); + + int w = scaleData[QwtPlot::yLeft].w + scaleData[QwtPlot::yRight].w; + int cw = qMax( scaleData[QwtPlot::xBottom].w, scaleData[QwtPlot::xTop].w ) + + 2 * ( canvas->frameWidth() + 1 ); + w += qMax( cw, minCanvasSize.width() ); + + int h = scaleData[QwtPlot::xBottom].h + scaleData[QwtPlot::xTop].h; + int ch = qMax( scaleData[QwtPlot::yLeft].h, scaleData[QwtPlot::yRight].h ) + + 2 * ( canvas->frameWidth() + 1 ); + h += qMax( ch, minCanvasSize.height() ); + + const QwtTextLabel *title = plot->titleLabel(); + if ( title && !title->text().isEmpty() ) + { + // If only QwtPlot::yLeft or QwtPlot::yRight is showing, + // we center on the plot canvas. + const bool centerOnCanvas = !( plot->axisEnabled( QwtPlot::yLeft ) + && plot->axisEnabled( QwtPlot::yRight ) ); + + int titleW = w; + if ( centerOnCanvas ) + { + titleW -= scaleData[QwtPlot::yLeft].w + + scaleData[QwtPlot::yRight].w; + } + + int titleH = title->heightForWidth( titleW ); + if ( titleH > titleW ) // Compensate for a long title + { + w = titleW = titleH; + if ( centerOnCanvas ) + { + w += scaleData[QwtPlot::yLeft].w + + scaleData[QwtPlot::yRight].w; + } + + titleH = title->heightForWidth( titleW ); + } + h += titleH + d_data->spacing; + } + + // Compute the legend contribution + + const QwtLegend *legend = plot->legend(); + if ( d_data->legendPos != QwtPlot::ExternalLegend + && legend && !legend->isEmpty() ) + { + if ( d_data->legendPos == QwtPlot::LeftLegend + || d_data->legendPos == QwtPlot::RightLegend ) + { + int legendW = legend->sizeHint().width(); + int legendH = legend->heightForWidth( legendW ); + + if ( legend->frameWidth() > 0 ) + w += d_data->spacing; + + if ( legendH > h ) + legendW += legend->verticalScrollBar()->sizeHint().height(); + + if ( d_data->legendRatio < 1.0 ) + legendW = qMin( legendW, int( w / ( 1.0 - d_data->legendRatio ) ) ); + + w += legendW + d_data->spacing; + } + else // QwtPlot::Top, QwtPlot::Bottom + { + int legendW = qMin( legend->sizeHint().width(), w ); + int legendH = legend->heightForWidth( legendW ); + + if ( legend->frameWidth() > 0 ) + h += d_data->spacing; + + if ( d_data->legendRatio < 1.0 ) + legendH = qMin( legendH, int( h / ( 1.0 - d_data->legendRatio ) ) ); + + h += legendH + d_data->spacing; + } + } + + return QSize( w, h ); +} + +/*! + Find the geometry for the legend + \param options Options how to layout the legend + \param rect Rectangle where to place the legend + \return Geometry for the legend + \sa Options +*/ + +QRectF QwtPlotLayout::layoutLegend( Options options, + const QRectF &rect ) const +{ + const QSize hint( d_data->layoutData.legend.hint ); + + int dim; + if ( d_data->legendPos == QwtPlot::LeftLegend + || d_data->legendPos == QwtPlot::RightLegend ) + { + // We don't allow vertical legends to take more than + // half of the available space. + + dim = qMin( hint.width(), int( rect.width() * d_data->legendRatio ) ); + + if ( !( options & IgnoreScrollbars ) ) + { + if ( hint.height() > rect.height() ) + { + // The legend will need additional + // space for the vertical scrollbar. + + dim += d_data->layoutData.legend.vScrollBarWidth; + } + } + } + else + { + dim = qMin( hint.height(), int( rect.height() * d_data->legendRatio ) ); + dim = qMax( dim, d_data->layoutData.legend.hScrollBarHeight ); + } + + QRectF legendRect = rect; + switch ( d_data->legendPos ) + { + case QwtPlot::LeftLegend: + legendRect.setWidth( dim ); + break; + case QwtPlot::RightLegend: + legendRect.setX( rect.right() - dim ); + legendRect.setWidth( dim ); + break; + case QwtPlot::TopLegend: + legendRect.setHeight( dim ); + break; + case QwtPlot::BottomLegend: + legendRect.setY( rect.bottom() - dim ); + legendRect.setHeight( dim ); + break; + case QwtPlot::ExternalLegend: + break; + } + + return legendRect; +} + +/*! + Align the legend to the canvas + \param canvasRect Geometry of the canvas + \param legendRect Maximum geometry for the legend + \return Geometry for the aligned legend +*/ +QRectF QwtPlotLayout::alignLegend( const QRectF &canvasRect, + const QRectF &legendRect ) const +{ + QRectF alignedRect = legendRect; + + if ( d_data->legendPos == QwtPlot::BottomLegend + || d_data->legendPos == QwtPlot::TopLegend ) + { + if ( d_data->layoutData.legend.hint.width() < canvasRect.width() ) + { + alignedRect.setX( canvasRect.x() ); + alignedRect.setWidth( canvasRect.width() ); + } + } + else + { + if ( d_data->layoutData.legend.hint.height() < canvasRect.height() ) + { + alignedRect.setY( canvasRect.y() ); + alignedRect.setHeight( canvasRect.height() ); + } + } + + return alignedRect; +} + +/*! + Expand all line breaks in text labels, and calculate the height + of their widgets in orientation of the text. + + \param options Options how to layout the legend + \param rect Bounding rect for title, axes and canvas. + \param dimTitle Expanded height of the title widget + \param dimAxis Expanded heights of the axis in axis orientation. + + \sa Options +*/ +void QwtPlotLayout::expandLineBreaks( int options, const QRectF &rect, + int &dimTitle, int dimAxis[QwtPlot::axisCnt] ) const +{ + dimTitle = 0; + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + dimAxis[axis] = 0; + + int backboneOffset[QwtPlot::axisCnt]; + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + backboneOffset[axis] = 0; + if ( !d_data->alignCanvasToScales ) + backboneOffset[axis] += d_data->canvasMargin[axis]; + if ( !( options & IgnoreFrames ) ) + backboneOffset[axis] += d_data->layoutData.canvas.frameWidth; + } + + bool done = false; + while ( !done ) + { + done = true; + + // the size for the 4 axis depend on each other. Expanding + // the height of a horizontal axis will shrink the height + // for the vertical axis, shrinking the height of a vertical + // axis will result in a line break what will expand the + // width and results in shrinking the width of a horizontal + // axis what might result in a line break of a horizontal + // axis ... . So we loop as long until no size changes. + + if ( !d_data->layoutData.title.text.isEmpty() ) + { + int w = rect.width(); + + if ( d_data->layoutData.scale[QwtPlot::yLeft].isEnabled + != d_data->layoutData.scale[QwtPlot::yRight].isEnabled ) + { + // center to the canvas + w -= dimAxis[QwtPlot::yLeft] + dimAxis[QwtPlot::yRight]; + } + + int d = qCeil( d_data->layoutData.title.text.heightForWidth( w ) ); + if ( !( options & IgnoreFrames ) ) + d += 2 * d_data->layoutData.title.frameWidth; + + if ( d > dimTitle ) + { + dimTitle = d; + done = false; + } + } + + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + const struct LayoutData::t_scaleData &scaleData = + d_data->layoutData.scale[axis]; + + if ( scaleData.isEnabled ) + { + int length; + if ( axis == QwtPlot::xTop || axis == QwtPlot::xBottom ) + { + length = rect.width() - dimAxis[QwtPlot::yLeft] + - dimAxis[QwtPlot::yRight]; + length -= scaleData.start + scaleData.end; + + if ( dimAxis[QwtPlot::yRight] > 0 ) + length -= 1; + + length += qMin( dimAxis[QwtPlot::yLeft], + scaleData.start - backboneOffset[QwtPlot::yLeft] ); + length += qMin( dimAxis[QwtPlot::yRight], + scaleData.end - backboneOffset[QwtPlot::yRight] ); + } + else // QwtPlot::yLeft, QwtPlot::yRight + { + length = rect.height() - dimAxis[QwtPlot::xTop] + - dimAxis[QwtPlot::xBottom]; + length -= scaleData.start + scaleData.end; + length -= 1; + + if ( dimAxis[QwtPlot::xBottom] <= 0 ) + length -= 1; + if ( dimAxis[QwtPlot::xTop] <= 0 ) + length -= 1; + + if ( dimAxis[QwtPlot::xBottom] > 0 ) + { + length += qMin( + d_data->layoutData.scale[QwtPlot::xBottom].tickOffset, + scaleData.start - backboneOffset[QwtPlot::xBottom] ); + } + if ( dimAxis[QwtPlot::xTop] > 0 ) + { + length += qMin( + d_data->layoutData.scale[QwtPlot::xTop].tickOffset, + scaleData.end - backboneOffset[QwtPlot::xTop] ); + } + + if ( dimTitle > 0 ) + length -= dimTitle + d_data->spacing; + } + + int d = scaleData.dimWithoutTitle; + if ( !scaleData.scaleWidget->title().isEmpty() ) + { + d += scaleData.scaleWidget->titleHeightForWidth( length ); + } + + + if ( d > dimAxis[axis] ) + { + dimAxis[axis] = d; + done = false; + } + } + } + } +} + +/*! + Align the ticks of the axis to the canvas borders using + the empty corners. + + \sa Options +*/ + +void QwtPlotLayout::alignScales( int options, + QRectF &canvasRect, QRectF scaleRect[QwtPlot::axisCnt] ) const +{ + int backboneOffset[QwtPlot::axisCnt]; + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + backboneOffset[axis] = 0; + if ( !d_data->alignCanvasToScales ) + backboneOffset[axis] += d_data->canvasMargin[axis]; + if ( !( options & IgnoreFrames ) ) + backboneOffset[axis] += d_data->layoutData.canvas.frameWidth; + } + + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + if ( !scaleRect[axis].isValid() ) + continue; + + const int startDist = d_data->layoutData.scale[axis].start; + const int endDist = d_data->layoutData.scale[axis].end; + + QRectF &axisRect = scaleRect[axis]; + + if ( axis == QwtPlot::xTop || axis == QwtPlot::xBottom ) + { + const QRectF &leftScaleRect = scaleRect[QwtPlot::yLeft]; + const int leftOffset = + backboneOffset[QwtPlot::yLeft] - startDist; + + if ( leftScaleRect.isValid() ) + { + const int dx = leftOffset + leftScaleRect.width(); + if ( d_data->alignCanvasToScales && dx < 0 ) + { + /* + The axis needs more space than the width + of the left scale. + */ + canvasRect.setLeft( qMax( canvasRect.left(), + axisRect.left() - dx ) ); + } + else + { + const double minLeft = leftScaleRect.left(); + const double left = axisRect.left() + leftOffset; + axisRect.setLeft( qMax( left, minLeft ) ); + } + } + else + { + if ( d_data->alignCanvasToScales && leftOffset < 0 ) + { + canvasRect.setLeft( qMax( canvasRect.left(), + axisRect.left() - leftOffset ) ); + } + else + { + if ( leftOffset > 0 ) + axisRect.setLeft( axisRect.left() + leftOffset ); + } + } + + const QRectF &rightScaleRect = scaleRect[QwtPlot::yRight]; + const int rightOffset = + backboneOffset[QwtPlot::yRight] - endDist + 1; + + if ( rightScaleRect.isValid() ) + { + const int dx = rightOffset + rightScaleRect.width(); + if ( d_data->alignCanvasToScales && dx < 0 ) + { + /* + The axis needs more space than the width + of the right scale. + */ + canvasRect.setRight( qMin( canvasRect.right(), + axisRect.right() + dx ) ); + } + + const double maxRight = rightScaleRect.right(); + const double right = axisRect.right() - rightOffset; + axisRect.setRight( qMin( right, maxRight ) ); + } + else + { + if ( d_data->alignCanvasToScales && rightOffset < 0 ) + { + canvasRect.setRight( qMin( canvasRect.right(), + axisRect.right() + rightOffset ) ); + } + else + { + if ( rightOffset > 0 ) + axisRect.setRight( axisRect.right() - rightOffset ); + } + } + } + else // QwtPlot::yLeft, QwtPlot::yRight + { + const QRectF &bottomScaleRect = scaleRect[QwtPlot::xBottom]; + const int bottomOffset = + backboneOffset[QwtPlot::xBottom] - endDist + 1; + + if ( bottomScaleRect.isValid() ) + { + const int dy = bottomOffset + bottomScaleRect.height(); + if ( d_data->alignCanvasToScales && dy < 0 ) + { + /* + The axis needs more space than the height + of the bottom scale. + */ + canvasRect.setBottom( qMin( canvasRect.bottom(), + axisRect.bottom() + dy ) ); + } + else + { + const double maxBottom = bottomScaleRect.top() + + d_data->layoutData.scale[QwtPlot::xBottom].tickOffset; + const double bottom = axisRect.bottom() - bottomOffset; + axisRect.setBottom( qMin( bottom, maxBottom ) ); + } + } + else + { + if ( d_data->alignCanvasToScales && bottomOffset < 0 ) + { + canvasRect.setBottom( qMin( canvasRect.bottom(), + axisRect.bottom() + bottomOffset ) ); + } + else + { + if ( bottomOffset > 0 ) + axisRect.setBottom( axisRect.bottom() - bottomOffset ); + } + } + + const QRectF &topScaleRect = scaleRect[QwtPlot::xTop]; + const int topOffset = backboneOffset[QwtPlot::xTop] - startDist; + + if ( topScaleRect.isValid() ) + { + const int dy = topOffset + topScaleRect.height(); + if ( d_data->alignCanvasToScales && dy < 0 ) + { + /* + The axis needs more space than the height + of the top scale. + */ + canvasRect.setTop( qMax( canvasRect.top(), + axisRect.top() - dy ) ); + } + else + { + const double minTop = topScaleRect.bottom() - + d_data->layoutData.scale[QwtPlot::xTop].tickOffset; + const double top = axisRect.top() + topOffset; + axisRect.setTop( qMax( top, minTop ) ); + } + } + else + { + if ( d_data->alignCanvasToScales && topOffset < 0 ) + { + canvasRect.setTop( qMax( canvasRect.top(), + axisRect.top() - topOffset ) ); + } + else + { + if ( topOffset > 0 ) + axisRect.setTop( axisRect.top() + topOffset ); + } + } + } + } + + if ( d_data->alignCanvasToScales ) + { + /* + The canvas has been aligned to the scale with largest + border distances. Now we have to realign the other scale. + */ + + int fw = 0; + if ( !( options & IgnoreFrames ) ) + fw = d_data->layoutData.canvas.frameWidth; + + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + if ( !scaleRect[axis].isValid() ) + continue; + + if ( axis == QwtPlot::xBottom || axis == QwtPlot::xTop ) + { + scaleRect[axis].setLeft( canvasRect.left() + fw + - d_data->layoutData.scale[axis].start ); + scaleRect[axis].setRight( canvasRect.right() - fw - 1 + + d_data->layoutData.scale[axis].end ); + } + else + { + scaleRect[axis].setTop( canvasRect.top() + fw + - d_data->layoutData.scale[axis].start ); + scaleRect[axis].setBottom( canvasRect.bottom() - fw - 1 + + d_data->layoutData.scale[axis].end ); + } + } + + if ( scaleRect[QwtPlot::xTop].isValid() ) + scaleRect[QwtPlot::xTop].setBottom( canvasRect.top() ); + if ( scaleRect[QwtPlot::xBottom].isValid() ) + scaleRect[QwtPlot::xBottom].setTop( canvasRect.bottom() ); + if ( scaleRect[QwtPlot::yLeft].isValid() ) + scaleRect[QwtPlot::yLeft].setRight( canvasRect.left() ); + if ( scaleRect[QwtPlot::yRight].isValid() ) + scaleRect[QwtPlot::yRight].setLeft( canvasRect.right() ); + } +} + +/*! + \brief Recalculate the geometry of all components. + + \param plot Plot to be layout + \param plotRect Rect where to place the components + \param options Layout options + + \sa invalidate(), titleRect(), + legendRect(), scaleRect(), canvasRect() +*/ +void QwtPlotLayout::activate( const QwtPlot *plot, + const QRectF &plotRect, Options options ) +{ + invalidate(); + + QRectF rect( plotRect ); // undistributed rest of the plot rect + + // We extract all layout relevant data from the widgets, + // filter them through pfilter and save them to d_data->layoutData. + + d_data->layoutData.init( plot, rect ); + + if ( !( options & IgnoreLegend ) + && d_data->legendPos != QwtPlot::ExternalLegend + && plot->legend() && !plot->legend()->isEmpty() ) + { + d_data->legendRect = layoutLegend( options, rect ); + + // subtract d_data->legendRect from rect + + const QRegion region( rect.toRect() ); + rect = region.subtract( d_data->legendRect.toRect() ).boundingRect(); + + switch ( d_data->legendPos ) + { + case QwtPlot::LeftLegend: + rect.setLeft( rect.left() + d_data->spacing ); + break; + case QwtPlot::RightLegend: + rect.setRight( rect.right() - d_data->spacing ); + break; + case QwtPlot::TopLegend: + rect.setTop( rect.top() + d_data->spacing ); + break; + case QwtPlot::BottomLegend: + rect.setBottom( rect.bottom() - d_data->spacing ); + break; + case QwtPlot::ExternalLegend: + break; // suppress compiler warning + } + } + + /* + +---+-----------+---+ + | Title | + +---+-----------+---+ + | | Axis | | + +---+-----------+---+ + | A | | A | + | x | Canvas | x | + | i | | i | + | s | | s | + +---+-----------+---+ + | | Axis | | + +---+-----------+---+ + */ + + // axes and title include text labels. The height of each + // label depends on its line breaks, that depend on the width + // for the label. A line break in a horizontal text will reduce + // the available width for vertical texts and vice versa. + // expandLineBreaks finds the height/width for title and axes + // including all line breaks. + + int dimTitle, dimAxes[QwtPlot::axisCnt]; + expandLineBreaks( options, rect, dimTitle, dimAxes ); + + if ( dimTitle > 0 ) + { + d_data->titleRect = QRect( rect.x(), rect.y(), + rect.width(), dimTitle ); + + if ( d_data->layoutData.scale[QwtPlot::yLeft].isEnabled != + d_data->layoutData.scale[QwtPlot::yRight].isEnabled ) + { + // if only one of the y axes is missing we align + // the title centered to the canvas + + d_data->titleRect.setX( rect.x() + dimAxes[QwtPlot::yLeft] ); + d_data->titleRect.setWidth( rect.width() + - dimAxes[QwtPlot::yLeft] - dimAxes[QwtPlot::yRight] ); + } + + // subtract title + rect.setTop( rect.top() + dimTitle + d_data->spacing ); + } + + d_data->canvasRect.setRect( + rect.x() + dimAxes[QwtPlot::yLeft], + rect.y() + dimAxes[QwtPlot::xTop], + rect.width() - dimAxes[QwtPlot::yRight] - dimAxes[QwtPlot::yLeft], + rect.height() - dimAxes[QwtPlot::xBottom] - dimAxes[QwtPlot::xTop] ); + + for ( int axis = 0; axis < QwtPlot::axisCnt; axis++ ) + { + // set the rects for the axes + + if ( dimAxes[axis] ) + { + int dim = dimAxes[axis]; + QRectF &scaleRect = d_data->scaleRect[axis]; + + scaleRect = d_data->canvasRect; + switch ( axis ) + { + case QwtPlot::yLeft: + scaleRect.setX( d_data->canvasRect.left() - dim ); + scaleRect.setWidth( dim ); + break; + case QwtPlot::yRight: + scaleRect.setX( d_data->canvasRect.right() ); + scaleRect.setWidth( dim ); + break; + case QwtPlot::xBottom: + scaleRect.setY( d_data->canvasRect.bottom() ); + scaleRect.setHeight( dim ); + break; + case QwtPlot::xTop: + scaleRect.setY( d_data->canvasRect.top() - dim ); + scaleRect.setHeight( dim ); + break; + } + scaleRect = scaleRect.normalized(); + } + } + + // +---+-----------+---+ + // | <- Axis -> | + // +-^-+-----------+-^-+ + // | | | | | | + // | | | | + // | A | | A | + // | x | Canvas | x | + // | i | | i | + // | s | | s | + // | | | | + // | | | | | | + // +-V-+-----------+-V-+ + // | <- Axis -> | + // +---+-----------+---+ + + // The ticks of the axes - not the labels above - should + // be aligned to the canvas. So we try to use the empty + // corners to extend the axes, so that the label texts + // left/right of the min/max ticks are moved into them. + + alignScales( options, d_data->canvasRect, d_data->scaleRect ); + + if ( !d_data->legendRect.isEmpty() ) + { + // We prefer to align the legend to the canvas - not to + // the complete plot - if possible. + + d_data->legendRect = alignLegend( d_data->canvasRect, d_data->legendRect ); + } +} diff --git a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_layout.h b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_layout.h index 6073768d0..43e420ff4 100644 --- a/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_layout.h +++ b/ground/openpilotgcs/src/libs/qwt/src/qwt_plot_layout.h @@ -1,105 +1,105 @@ -/* -*- mode: C++ ; c-file-style: "stroustrup" -*- ***************************** - * Qwt Widget Library - * Copyright (C) 1997 Josef Wilgen - * Copyright (C) 2002 Uwe Rathmann - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the Qwt License, Version 1.0 - *****************************************************************************/ - -#ifndef QWT_PLOT_LAYOUT_H -#define QWT_PLOT_LAYOUT_H - -#include "qwt_global.h" -#include "qwt_plot.h" - -/*! - \brief Layout engine for QwtPlot. - - It is used by the QwtPlot widget to organize its internal widgets - or by QwtPlot::print() to render its content to a QPaintDevice like - a QPrinter, QPixmap/QImage or QSvgRenderer. -*/ - -class QWT_EXPORT QwtPlotLayout -{ -public: - /*! - Options to configure the plot layout engine - \sa activate(), QwtPlotRenderer - */ - enum Option - { - //! Unused - AlignScales = 0x01, - - /*! - Ignore the dimension of the scrollbars. There are no - scrollbars, when the plot is not rendered to widgets. - */ - IgnoreScrollbars = 0x02, - - //! Ignore all frames. - IgnoreFrames = 0x04, - - //! Ignore the legend. - IgnoreLegend = 0x08 - }; - - //! Layout options - typedef QFlags